diff --git a/.git-blame-ignore-revs b/.git-blame-ignore-revs index 80c607e02ac4a6..e8a7ece5cbb9c4 100644 --- a/.git-blame-ignore-revs +++ b/.git-blame-ignore-revs @@ -4,3 +4,6 @@ # Tools: ros2: Run ament_black on all files 85172b56467668bee9fa0e68081027b13bc18c4a + +# Tools: ros2: Reformat +4d9822131354dc7dc3351f24660969f58720a1de diff --git a/.github/problem-matchers/autotestfail.json b/.github/problem-matchers/autotestfail.json index ccda5c1a940f7e..10e845de574393 100644 --- a/.github/problem-matchers/autotestfail.json +++ b/.github/problem-matchers/autotestfail.json @@ -1,12 +1,12 @@ { - "__comment": "by buzz try to match common autotest warnings and errors that arent caught by gcc.json or python.json", + "__comment": "by buzz try to match autotest test failures", "problemMatcher": [ { "owner": "autotest-fail-matcher", "severity": "error", "pattern": [ { - "regexp": "^(.*)(TIMEOUT|Build failed|FAILED STEP):(.*)$", + "regexp": "^(.*)(TIMEOUT|Build failed|FAILED STEP|FAILED):(.*)$", "column": 1, "code": 2, "message": 3 diff --git a/.github/workflows/colcon.yml b/.github/workflows/colcon.yml index e39af18fc16949..4d59e04062b0d3 100644 --- a/.github/workflows/colcon.yml +++ b/.github/workflows/colcon.yml @@ -26,7 +26,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -157,7 +156,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -199,7 +198,7 @@ jobs: shell: 'bash' run: | source install/setup.bash - colcon test --packages-select ardupilot_dds_tests --event-handlers=console_cohesion+ + colcon test --executor sequential --parallel-workers 0 --base-paths src/ardupilot --event-handlers=console_cohesion+ - name: Report colcon test results run: | colcon test-result --all --verbose diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index f836b9c09a923b..1cf7932a1aa457 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -21,7 +21,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -178,7 +177,7 @@ jobs: source ~/ccache.conf && ccache -s - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: D:/a/ardupilot/ardupilot/ccache key: ${{ steps.ccache_cache_timestamp.outputs.cache-key }}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -189,8 +188,8 @@ jobs: shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}' run: >- ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip && - python -m pip install --progress-bar off empy==3.3.4 pexpect && - python -m pip install --progress-bar off dronecan --upgrade && + python3 -m pip install --progress-bar off empy==3.3.4 pexpect && + python3 -m pip install --progress-bar off dronecan --upgrade && cp /usr/bin/ccache /usr/local/bin/ && cd /usr/local/bin && ln -s ccache /usr/local/bin/gcc && ln -s ccache /usr/local/bin/g++ && @@ -202,6 +201,7 @@ jobs: PATH: /usr/bin:$(cygpath ${SYSTEMROOT})/system32 shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}' run: >- + git config --global --add safe.directory /cygdrive/d/a/${GITHUB_REPOSITORY#$GITHUB_REPOSITORY_OWNER/}/${GITHUB_REPOSITORY#$GITHUB_REPOSITORY_OWNER/} && export PATH=/usr/local/bin:/usr/bin:$(cygpath ${SYSTEMROOT})/system32 && source ~/ccache.conf && Tools/scripts/cygwin_build.sh && @@ -215,7 +215,7 @@ jobs: fail: true - name: Archive build - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: binaries path: artifacts diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index 91926070e12277..e8101d34b1a051 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -29,7 +29,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -179,7 +178,7 @@ jobs: sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0 sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10 update-alternatives --query python - python --version + python3 --version pip3 install gevent # we actualy want 3.11 .. but the above only gave us 3.10, not ok with esp32 builds. @@ -189,7 +188,7 @@ jobs: sudo apt-get install python3 python3-pip python3-venv python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools update-alternatives --query python pip3 install gevent - python --version + python3 --version python3.11 --version which python3.11 sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.11 11 @@ -230,7 +229,7 @@ jobs: ./install.sh source ./export.sh cd ../.. - python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan + python3 -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan which cmake ./waf configure --board ${{matrix.config}} echo './waf configure --board ${{matrix.config}}' >> $GITHUB_STEP_SUMMARY @@ -257,7 +256,7 @@ jobs: ls bootloader* partition* Ardu*.elf Ardu*.bin >> $GITHUB_STEP_SUMMARY - name: Archive artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: esp32-binaries -${{matrix.config}} path: | diff --git a/.github/workflows/macos_build.yml b/.github/workflows/macos_build.yml index 7dba405b0300e6..bfa7010904366b 100644 --- a/.github/workflows/macos_build.yml +++ b/.github/workflows/macos_build.yml @@ -27,7 +27,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -170,7 +169,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{matrix.config}}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -188,5 +187,7 @@ jobs: echo $PATH ./waf configure --board ${{matrix.config}} ./waf + ./waf configure --board ${{matrix.config}} --debug + ./waf ccache -s ccache -z diff --git a/.github/workflows/qurt_build.yml b/.github/workflows/qurt_build.yml new file mode 100644 index 00000000000000..9120c9f683c2fd --- /dev/null +++ b/.github/workflows/qurt_build.yml @@ -0,0 +1,175 @@ +name: QURT Build + +on: + push: + paths-ignore: + # remove other vehicles + - 'AntennaTracker/**' + - 'Blimp/**' + # remove non SITL HAL + - 'libraries/AP_HAL_ChibiOS/**' + - 'libraries/AP_HAL_ESP32/**' + # remove non SITL directories + - 'Tools/AP_Bootloader/**' + - 'Tools/AP_Periph/**' + - 'Tools/CHDK-Script/**' + - 'Tools/CPUInfo/**' + - 'Tools/CodeStyle/**' + - 'Tools/FilterTestTool/**' + - 'Tools/Frame_params/**' + - 'Tools/GIT_Test/**' + - 'Tools/Hello/**' + - 'Tools/IO_Firmware/**' + - 'Tools/Linux_HAL_Essentials/**' + - 'Tools/Pozyx/**' + - 'Tools/PrintVersion.py' + - 'Tools/Replay/**' + - 'Tools/UDP_Proxy/**' + - 'Tools/Vicon/**' + - 'Tools/bootloaders/**' + - 'Tools/completion/**' + - 'Tools/debug/**' + - 'Tools/environment_install/**' + - 'Tools/geotag/**' + - 'Tools/gittools/**' + - 'Tools/mavproxy_modules/**' + - 'Tools/simulink/**' + - 'Tools/vagrant/**' + # Discard python file from Tools/scripts as not used + - 'Tools/scripts/**.py' + - 'Tools/scripts/build_sizes/**' + - 'Tools/scripts/build_tests/**' + - 'Tools/scripts/CAN/**' + - 'Tools/scripts/signing/**' + # Remove autotest + - 'Tools/autotest/**' + # Remove markdown files as irrelevant + - '**.md' + # Remove dotfile at root directory + - './.dir-locals.el' + - './.dockerignore' + - './.editorconfig' + - './.flake8' + - './.gitattributes' + - './.github' + - './.gitignore' + - './.pre-commit-config.yaml' + - './.pydevproject' + - './.valgrind-suppressions' + - './.valgrindrc' + - 'Dockerfile' + - 'Vagrantfile' + - 'Makefile' + # Remove some directories check + - '.vscode/**' + - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' + + pull_request: + paths-ignore: + # remove other vehicles + - 'AntennaTracker/**' + - 'Blimp/**' + # remove non SITL HAL + - 'libraries/AP_HAL_ChibiOS/**' + - 'libraries/AP_HAL_ESP32/**' + # remove non SITL directories + - 'Tools/AP_Bootloader/**' + - 'Tools/AP_Periph/**' + - 'Tools/bootloaders/**' + - 'Tools/CHDK-Script/**' + - 'Tools/CodeStyle/**' + - 'Tools/completion/**' + - 'Tools/CPUInfo/**' + - 'Tools/debug/**' + - 'Tools/environment_install/**' + - 'Tools/FilterTestTool/**' + - 'Tools/Frame_params/**' + - 'Tools/geotag/**' + - 'Tools/GIT_Test/**' + - 'Tools/gittools/**' + - 'Tools/Hello/**' + - 'Tools/IO_Firmware/**' + - 'Tools/Linux_HAL_Essentials/**' + - 'Tools/LogAnalyzer/**' + - 'Tools/mavproxy_modules/**' + - 'Tools/Pozyx/**' + - 'Tools/PrintVersion.py' + - 'Tools/Replay/**' + - 'Tools/simulink/**' + - 'Tools/UDP_Proxy/**' + - 'Tools/vagrant/**' + - 'Tools/Vicon/**' + # Discard python file from Tools/scripts as not used + - 'Tools/scripts/**.py' + - 'Tools/scripts/build_sizes/**' + - 'Tools/scripts/build_tests/**' + - 'Tools/scripts/CAN/**' + - 'Tools/scripts/signing/**' + # Remove autotest + - 'Tools/autotest/**' + # Remove markdown files as irrelevant + - '**.md' + # Remove dotfile at root directory + - './.dir-locals.el' + - './.dockerignore' + - './.editorconfig' + - './.flake8' + - './.gitattributes' + - './.github' + - './.gitignore' + - './.pre-commit-config.yaml' + - './.pydevproject' + - './.valgrind-suppressions' + - './.valgrindrc' + - 'Dockerfile' + - 'Vagrantfile' + - 'Makefile' + # Remove some directories check + - '.vscode/**' + - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' + + workflow_dispatch: + +concurrency: + group: ci-${{github.workflow}}-${{ github.ref }} + cancel-in-progress: true + +jobs: + build: + if: github.repository == 'ArduPilot/ardupilot' + runs-on: 'ardupilot-qurt' + steps: + - uses: actions/checkout@v4 + with: + submodules: 'recursive' + + - name: Build QURT + run: | + ./waf configure --board QURT + ./waf copter + ./waf plane + ./waf rover + cp -a build/QURT/bin/arducopter build/QURT/ArduPilot.so + cp -a build/QURT/bin/arducopter build/QURT/ArduPilot_Copter.so + cp -a build/QURT/bin/arduplane build/QURT/ArduPilot_Plane.so + cp -a build/QURT/bin/ardurover build/QURT/ArduPilot_Rover.so + libraries/AP_HAL_QURT/packaging/make_package.sh ArduCopter arducopter + libraries/AP_HAL_QURT/packaging/make_package.sh ArduPlane arduplane + libraries/AP_HAL_QURT/packaging/make_package.sh Rover ardurover + + - name: Archive build + uses: actions/upload-artifact@v4 + with: + name: qurt-binaries + path: | + build/QURT/ardupilot + build/QURT/ArduPilot_Copter.so + build/QURT/ArduPilot_Plane.so + build/QURT/ArduPilot_Rover.so + build/QURT/ArduPilot.so + libraries/AP_HAL_QURT/packaging/*.deb + retention-days: 7 diff --git a/.github/workflows/test_ccache.yml b/.github/workflows/test_ccache.yml index 94e14d1eed093a..b41c3e830658c6 100644 --- a/.github/workflows/test_ccache.yml +++ b/.github/workflows/test_ccache.yml @@ -25,7 +25,6 @@ on: - 'Tools/GIT_Test/**' - 'Tools/gittools/**' - 'Tools/Hello/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index ed16e57e2cd404..22c97610038df1 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -19,7 +19,6 @@ on: - 'Tools/GIT_Test/**' - 'Tools/gittools/**' - 'Tools/Hello/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -157,8 +156,10 @@ jobs: build-options-defaults-test, signing, CubeOrange-PPP, + CubeRed-EKF2, SOHW, Pixhawk6X-PPPGW, + new-check, ] toolchain: [ chibios, @@ -181,7 +182,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{ matrix.gcc }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index c6dba24a392fc1..150159b4c3ae8e 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -48,7 +48,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} diff --git a/.github/workflows/test_dds.yml b/.github/workflows/test_dds.yml index c8e63c33eda026..9001de83a5ed34 100644 --- a/.github/workflows/test_dds.yml +++ b/.github/workflows/test_dds.yml @@ -26,7 +26,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -162,7 +161,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.config }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -180,7 +179,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} diff --git a/.github/workflows/test_environment.yml b/.github/workflows/test_environment.yml index 4a062f056844a5..c84151418d9859 100644 --- a/.github/workflows/test_environment.yml +++ b/.github/workflows/test_environment.yml @@ -33,9 +33,7 @@ jobs: - os: ubuntu name: jammy - os: ubuntu - name: lunar - - os: ubuntu - name: mantic + name: noble - os: archlinux name: latest - os: debian @@ -79,7 +77,7 @@ jobs: with: submodules: 'recursive' - name: test install environment ${{matrix.os}}.${{matrix.name}} - timeout-minutes: 45 + timeout-minutes: 60 env: DISABLE_MAVNATIVE: True DEBIAN_FRONTEND: noninteractive @@ -103,7 +101,7 @@ jobs: *"archlinux"*) cp /etc/skel/.bashrc /root cp /etc/skel/.bashrc /github/home - git config --global --add safe.directory /__w/ardupilot/ardupilot + git config --global --add safe.directory ${GITHUB_WORKSPACE} Tools/environment_install/install-prereqs-arch.sh -qy ;; esac @@ -123,6 +121,7 @@ jobs: ./waf rover - name: test build Chibios ${{matrix.os}}.${{matrix.name}} + if: matrix.os != 'alpine' env: DISABLE_MAVNATIVE: True DEBIAN_FRONTEND: noninteractive @@ -141,3 +140,38 @@ jobs: git config --global --add safe.directory /__w/ardupilot/ardupilot ./waf configure --board CubeOrange ./waf plane + + build-alpine: # special case for alpine as it doesn't have bash by default + runs-on: ubuntu-22.04 + container: + image: alpine:latest + options: --privileged + steps: + - name: Install Git + timeout-minutes: 30 + env: + DEBIAN_FRONTEND: noninteractive + TZ: Europe/Paris + run: | + apk update && apk add --no-cache git + - uses: actions/checkout@v4 + with: + submodules: 'recursive' + - name: test install environment alpine + timeout-minutes: 60 + env: + DISABLE_MAVNATIVE: True + TZ: Europe/Paris + SKIP_AP_GIT_CHECK: 1 + run: | + PATH="/github/home/.local/bin:$PATH" + Tools/environment_install/install-prereqs-alpine.sh + - name: test build STIL alpine + env: + DISABLE_MAVNATIVE: True + TZ: Europe/Paris + run: | + git config --global --add safe.directory ${GITHUB_WORKSPACE} + git config --global --add safe.directory /__w/ardupilot/ardupilot + ./waf configure + ./waf rover \ No newline at end of file diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index a66bc24de37b85..2bec49b8bad9f0 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -24,7 +24,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -160,6 +159,10 @@ jobs: toolchain: armhf-musl - config: linux toolchain: base # GCC + - config: navigator64 + toolchain: aarch64 + - config: linux + toolchain: base # GCC exclude: - config: navigator toolchain: armhf @@ -178,7 +181,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index 86cd8ba3b307b9..7799d0317aec47 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -31,7 +31,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -171,7 +170,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -193,7 +192,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{ matrix.toolchain }}-${{matrix.config}} diff --git a/.github/workflows/test_scripting.yml b/.github/workflows/test_scripting.yml index fab7a226deba19..53dbf016f5445b 100644 --- a/.github/workflows/test_scripting.yml +++ b/.github/workflows/test_scripting.yml @@ -36,6 +36,17 @@ jobs: sudo apt-get -y install lua-check ./Tools/scripts/run_luacheck.sh + - name: Language server check + shell: bash + run: | + python -m pip install github-release-downloader + python ./Tools/scripts/run_lua_language_check.py + + - name: Generate docs md + shell: bash + run: | + ./Tools/scripts/generate_lua_docs.sh + - name: copy docs run: | PATH="/github/home/.local/bin:$PATH" @@ -53,3 +64,10 @@ jobs: run: | PATH="/github/home/.local/bin:$PATH" python ./libraries/AP_Scripting/tests/docs_check.py "./libraries/AP_Scripting/docs/docs.lua" "./libraries/AP_Scripting/docs/current_docs.lua" + + - name: Upload docs + uses: actions/upload-artifact@v4 + with: + name: Docs + path: ScriptingDocs.md + retention-days: 7 diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index b2e0c7bc6d1392..923365dafcd97a 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -19,6 +19,7 @@ jobs: python-cleanliness, astyle-cleanliness, validate_board_list, + logger_metadata, ] steps: # git checkout the PR @@ -30,4 +31,5 @@ jobs: CI_BUILD_TARGET: ${{matrix.config}} shell: bash run: | + git config --global --add safe.directory ${GITHUB_WORKSPACE} Tools/scripts/build_ci.sh diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml index d4530e6614dc00..ebd105943129db 100644 --- a/.github/workflows/test_sitl_blimp.yml +++ b/.github/workflows/test_sitl_blimp.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -183,7 +182,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -230,7 +229,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -248,7 +247,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -262,7 +261,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index c3e8dd622f1ca0..86fd5ecebada2a 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/simulink/**' @@ -174,6 +173,7 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + # Put ccache into github cache for faster build - name: Prepare ccache timestamp id: ccache_cache_timestamp @@ -181,7 +181,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -227,6 +227,19 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + + - name: Register gcc problem matcher + run: echo "::add-matcher::.github/problem-matchers/gcc.json" + + - name: Register python problem matcher + run: echo "::add-matcher::.github/problem-matchers/python.json" + + - name: Register autotest warn matcher + run: echo "::add-matcher::.github/problem-matchers/autotestwarn.json" + + - name: Register autotest fail matcher + run: echo "::add-matcher::.github/problem-matchers/autotestfail.json" + # Put ccache into github cache for faster build - name: Prepare ccache timestamp id: ccache_cache_timestamp @@ -234,7 +247,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -252,7 +265,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -266,7 +279,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs @@ -289,7 +302,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -330,7 +343,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -348,7 +361,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -362,7 +375,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index 06580252dd8029..de470a8e09ec2f 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -28,7 +28,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -173,7 +172,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -223,7 +222,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 245c738a2bb930..3b1e41bd4c77bf 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -182,7 +181,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -214,7 +213,8 @@ jobs: fail-fast: false # don't cancel if a job from the matrix fails matrix: config: [ - sitltest-plane, + sitltest-plane-tests1a, + sitltest-plane-tests1b, sitltest-quadplane, ] @@ -230,7 +230,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -248,7 +248,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -262,7 +262,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index e778f5953a2a86..6adeb20060c1c8 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -181,7 +180,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -225,6 +224,19 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + + - name: Register gcc problem matcher + run: echo "::add-matcher::.github/problem-matchers/gcc.json" + + - name: Register python problem matcher + run: echo "::add-matcher::.github/problem-matchers/python.json" + + - name: Register autotest warn matcher + run: echo "::add-matcher::.github/problem-matchers/autotestwarn.json" + + - name: Register autotest fail matcher + run: echo "::add-matcher::.github/problem-matchers/autotestfail.json" + # Put ccache into github cache for faster build - name: Prepare ccache timestamp id: ccache_cache_timestamp @@ -232,7 +244,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -250,7 +262,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -264,7 +276,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index d4d84b38cd20ff..427ba6c1f90b7b 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -177,6 +176,7 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + # Put ccache into github cache for faster build - name: Prepare ccache timestamp id: ccache_cache_timestamp @@ -184,7 +184,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -224,6 +224,19 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + + - name: Register gcc problem matcher + run: echo "::add-matcher::.github/problem-matchers/gcc.json" + + - name: Register python problem matcher + run: echo "::add-matcher::.github/problem-matchers/python.json" + + - name: Register autotest warn matcher + run: echo "::add-matcher::.github/problem-matchers/autotestwarn.json" + + - name: Register autotest fail matcher + run: echo "::add-matcher::.github/problem-matchers/autotestfail.json" + # Put ccache into github cache for faster build - name: Prepare ccache timestamp id: ccache_cache_timestamp @@ -231,7 +244,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -249,7 +262,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -263,7 +276,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index 7bb633e0e552a5..278a2d446a86be 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -30,7 +30,6 @@ on: - 'Tools/Hello/**' - 'Tools/IO_Firmware/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' - 'Tools/Replay/**' @@ -184,7 +183,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -231,7 +230,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache/restore@v3 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -249,7 +248,7 @@ jobs: Tools/scripts/build_ci.sh - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{matrix.config}} @@ -263,7 +262,7 @@ jobs: retention-days: 14 - name: Archive .bin artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: BIN-${{matrix.config}} path: /__w/ardupilot/ardupilot/logs diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index f8015bc88a717a..fe83756a3a7599 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -37,7 +37,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -98,7 +97,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -269,7 +268,7 @@ jobs: shell: bash run: | cd pr/ - Tools/scripts/pretty_diff_size.py -m $GITHUB_WORKSPACE/base_branch_bin -s $GITHUB_WORKSPACE/pr_bin + Tools/scripts/build_tests/pretty_diff_size.py -m $GITHUB_WORKSPACE/base_branch_bin -s $GITHUB_WORKSPACE/pr_bin - name: Feature compare with ${{ github.event.pull_request.base.ref }} shell: bash @@ -302,8 +301,26 @@ jobs: Tools/scripts/extract_features.py "$EF_BASE_BRANCH_BINARY" -nm "${BIN_PREFIX}nm" >features-base_branch.txt Tools/scripts/extract_features.py "$EF_PR_BRANCH_BINARY" -nm "${BIN_PREFIX}nm" >features-pr.txt diff -u features-base_branch.txt features-pr.txt || true + diff_output=$(diff -u features-base_branch.txt features-pr.txt || true) + echo "### Features Diff Output" >> $GITHUB_STEP_SUMMARY + if [ -n "$diff_output" ]; then + echo '```diff' >> $GITHUB_STEP_SUMMARY + echo "$diff_output" >> $GITHUB_STEP_SUMMARY + echo '```' >> $GITHUB_STEP_SUMMARY + else + echo "No differences found." >> $GITHUB_STEP_SUMMARY + fi - name: Checksum compare with ${{ github.event.pull_request.base.ref }} shell: bash run: | diff -r $GITHUB_WORKSPACE/base_branch_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true + diff_output=$(diff -r $GITHUB_WORKSPACE/base_branch_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true || true) + echo "### Checksum Diff Output" >> $GITHUB_STEP_SUMMARY + if [ -n "$diff_output" ]; then + echo '```diff' >> $GITHUB_STEP_SUMMARY + echo "$diff_output" >> $GITHUB_STEP_SUMMARY + echo '```' >> $GITHUB_STEP_SUMMARY + else + echo "No differences found." >> $GITHUB_STEP_SUMMARY + fi diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 641177b1493b71..bc325afb7d3190 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -33,7 +33,6 @@ on: - 'Tools/gittools/**' - 'Tools/Hello/**' - 'Tools/Linux_HAL_Essentials/**' - - 'Tools/LogAnalyzer/**' - 'Tools/mavproxy_modules/**' - 'Tools/Pozyx/**' - 'Tools/PrintVersion.py' @@ -127,7 +126,7 @@ jobs: NOW=$(date -u +"%F-%T") echo "timestamp=${NOW}" >> $GITHUB_OUTPUT - name: ccache cache files - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} @@ -165,7 +164,7 @@ jobs: Tools/autotest/unittest/annotate_params_unittest.py - name: Archive buildlog artifacts - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 if: failure() with: name: fail-${{ matrix.toolchain }}-${{matrix.config}} diff --git a/.gitignore b/.gitignore index 2769d317904195..b3d5003c68bde4 100644 --- a/.gitignore +++ b/.gitignore @@ -156,6 +156,11 @@ build.tmp.binaries/ tasklist.json modules/esp_idf +# lua-language-server linter +ScriptingDocs.md +/lua-language-server/ +repo-LuaLS-lua-language-server.cache + # Ignore Python virtual environments # from: https://github.com/github/gitignore/blob/4488915eec0b3a45b5c63ead28f286819c0917de/Python.gitignore#L125 .env @@ -166,3 +171,7 @@ ENV/ env.bak/ venv.bak/ autotest_result_*_junit.xml + +# Ignore ESP-IDF SDK defines +/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 9c15396246364a..94919cc3841183 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -41,11 +41,6 @@ repos: - id: check-xml - id: check-yaml - - repo: https://github.com/lsst-ts/pre-commit-xmllint - rev: 6f36260b537bf9a42b6ea5262c915ae50786296e - hooks: - - id: format-xmllint - files: libraries/AP_DDS/dds_xrce_profile.xml - repo: https://github.com/psf/black rev: 23.7.0 hooks: diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index c99d22bb0d43fe..c9ec2050c746fe 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -264,6 +264,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -273,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif }; @@ -289,7 +298,9 @@ static const ap_message STREAM_RAW_CONTROLLER_msgs[] = { }; static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -310,7 +321,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { @@ -638,3 +650,43 @@ void GCS_MAVLINK_Tracker::send_global_position_int() 0, // Z speed cm/s (+ve Down) tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree } + +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const +{ + const Mode* modes[] { + &tracker.mode_manual, + &tracker.mode_stop, + &tracker.mode_scan, + &tracker.mode_guided, + &tracker.mode_servotest, + &tracker.mode_auto, + &tracker.mode_initialising, + }; + + const uint8_t mode_count = ARRAY_SIZE(modes); + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name = modes[index_zero]->name(); + const uint8_t mode_number = (uint8_t)modes[index_zero]->number(); + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index a431f5217e2306..af98ee5a39fd74 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -30,6 +30,10 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK void send_nav_controller_output() const override; void send_pid_tuning() override; + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override; diff --git a/AntennaTracker/GCS_Tracker.h b/AntennaTracker/GCS_Tracker.h index 4201cadde8cce4..30cfaef564991c 100644 --- a/AntennaTracker/GCS_Tracker.h +++ b/AntennaTracker/GCS_Tracker.h @@ -28,7 +28,7 @@ class GCS_Tracker : public GCS GCS_MAVLINK_Tracker *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Tracker(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Tracker(params, uart); } private: diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 48048dc1a17cdc..b1adb3ba11af27 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -7,9 +7,7 @@ // Write an attitude packet void Tracker::Log_Write_Attitude() { - Vector3f targets; - targets.y = nav_status.pitch * 100.0f; - targets.z = wrap_360_cd(nav_status.bearing * 100.0f); + const Vector3f targets{0.0f, nav_status.pitch, nav_status.bearing}; ahrs.Write_Attitude(targets); AP::ahrs().Log_Write(); } diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 12b00cb5c8f37d..2c0b1f3e86f9d7 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -518,7 +518,6 @@ const AP_Param::Info Tracker::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:Pitch,2:Yaw // @Bitmask: 0:Pitch,1:Yaw GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), @@ -556,7 +555,6 @@ const AP_Param::Info Tracker::var_info[] = { // @DisplayName: Auto mode options // @Description: 1: Scan for unknown target // @User: Standard - // @Values: 0:None, 1: Scan for unknown target in auto mode // @Bitmask: 0:Scan for unknown target GSCALAR(auto_opts, "AUTO_OPTIONS", 0), diff --git a/AntennaTracker/ReleaseNotes.txt b/AntennaTracker/ReleaseNotes.txt index a8c64f03b5979b..c03c34c3ab4d82 100644 --- a/AntennaTracker/ReleaseNotes.txt +++ b/AntennaTracker/ReleaseNotes.txt @@ -1,4 +1,608 @@ Antenna Tracker Release Notes: +------------------------------------------------------------------ +Release 4.6.0-beta 13 Nov 2024 + +Changes from 4.5.7 + +1) Board specific changes + +- AnyLeaf H7 supports compass and onboard logging +- Blitz743Pro supports CAN +- BlueRobotics Navigator supports BMP390 baro +- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed) +- CB Unmanned Stamp H743 support +- ClearSky CSKY405 support +- CUAV-7-Nano default batt monitor fixed +- CubeRed bootloader fixes including disabling 2nd core by default +- CubeRed supports PPP networking between primary and secondary MCU +- CubeRedPrimary supports external compasses +- ESP32 main loop rate improvements +- ESP32 RC input fixes and wifi connection reliability improved +- ESP32 safety switch and GPIO pin support +- FlyingMoon no longer support MAX7456 +- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot +- Flywoo H743 Pro support +- Flywoo/Goku F405 HD 1-2S ELRS AIO v2 +- FlywooF745 supports DPS310 baro +- FPV boards lose SMBus battery support (to save flash) +- GEPRC F745BTHD support +- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash) +- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates +- Holybro Kakute F4 Wing support +- iFlight 2RAW H743 supports onboard logging +- JFB110 supports measuring servo rail voltage +- JFB110 supports safety switch LED +- JHEM-JHEF405 bootloader supports firmware updates via serial +- JHEMCU GF30H743 HD support +- JHEMCU-GF16-F405 autopilot support +- JHEMCU-GSF405A becomes FPV board (to save flash) +- KakuteF7 only supports BMP280 baro (to save flash) +- KakuteH7Mini supports ICM42688 IMU +- Linux auto detection of GPS baud rate fixed +- Linux board scheduler jitter reduced +- Linux board shutdown fixes +- MakeFlyEasy PixPilot-V6Pro support +- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash) +- MatekH7A3 support Bi-directional DShot +- MicoAir405v2 and MicoAir405Mini support optical flow and OSD +- MicoAir743 internal compass orientation fixed +- MicroAir405Mini, MicroAir743, NxtPX4v2 support +- MicroAir405v2 Bi-directional DShot and LED DMA fixes +- MicroAir405v2 defined as FPV board with reduced features (to save flash) +- ModalAI VOXL2 support including Starling 2 and Starling 2 max +- mRo Control Zero Classic supports servo rail analog input +- mRo KitCAN revC fixed +- Mugin MUPilot support +- OmnibusF7v2 loses quadplane support (to save flash) +- Pixhack-v3 board added (same as fmuv3) +- Pixhawk6C bootloader supports flashing firmware from SD card +- RadiolinkPIX6 imu orientation fixed +- RadiolinkPIX6 supports SPA06 baro +- ReaperF745 V4 FC supports MPU6000 IMU +- RPI5 support +- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed +- Solo serial ports default to MAVLink1 +- SpeedyBeeF405Wing gets Bi-directional DShot +- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash) +- Spektreworks boom board support +- TrueNavPro-G4 SPI does not share DMA +- X-MAV AP-H743v2 support + +2) AHRS/EKF enhancements and fixes + +- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back) +- AHRS_OPTION to disable innovation check for airspeed sensor +- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity +- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only) +- EK2 supports disabling external nav (see EK2_OPTIONS) +- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1) +- EK3 uses filtered velocity corrections for IMU position +- EKF2, EKF3, ExternalAHRS all use common origin +- EKF3 accepts set origin even when using GPS +- EKF3 allows earth-frame fields to be estimated with an origin but no GPS +- EKF3 copes better with GPS jamming +- EKF3 logs mag fusion selection to XKFS +- EKF3 wind estimation when using GPS-for-yaw fixed +- External AHRS improvements including handling variances, pre-arm origin check +- Inertial Labs External AHRS fixes +- VectorNav driver fix for handling of error from sensor +- VectorNav External AHRS enhancements including validation of config commands and logging improvements +- VectorNav support for sensors outside VN-100 and VN-300 + +3) Driver enhancements and bug fixes + +- ADSB fix to display last character in status text sent to GCS +- Ainstein LR-D1 radar support +- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor +- AIRSPEED message sent to GCS +- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5) +- ARSPD_OPTIONS to report calibration offset to GCS +- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only) +- Baro provides improved atmospheric model for high altitude flight +- BARO_ALT_OFFSET slew slowed to keep EKF happy +- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries +- BATTx_OPTION to not send battery voltage, current, etc to GCS +- Benewake RDS02U radar support +- Bi-directional DShot on IOMCU supports reversible mask +- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs +- BMM350 compass support +- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus) +- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS) +- CRSF baro and vertical speeed fixed +- CRSF RX bind command support +- DroneCAN battery monitor check to avoid memory corruption when type changed +- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info +- DroneCAN EFI health check fix +- DroneCAN ESC battery monitors calculate consumed mah +- DroneCAN ESCs forced to zero when disarmed +- DroneCAN RPM message support +- DroneCAN timeout fix for auxiliary frames +- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600') +- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass +- FuelLevel battery monitor fix to report capacity +- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx +- Hirth EFI logging includes modified throttle +- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter) +- Hott and LTM telemetry deprecated (still available through custom build server) +- i-BUS telemetry support +- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only) +- ICE_START_CHAN replaced with RC aux function (Plane only) +- ICEngine retry max added (see ICE_STRT_MX_RTRY) +- IE 2400 generator error message severity to GCS improved +- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params) +- MCP9600 temperature sensor I2C address fixed +- MLX90614 temperature sensor support +- MSP GPS ground course scaling fixed +- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect) +- Networking supports reconnection to TCP server or client +- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT) +- Relay inverted output support (see RELAYx_INVERTED parameter) +- ROMFS efficiency improvements +- RS-485 driver enable RTS flow control +- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt) +- Septentrio GPS sat count correctly drops to zero when 255 received +- Septentrio supports selecting constellations (see GPS_GNSS_MODE) +- Single LED for user notification supported +- SPA06 baro supported +- Sum battery monitor optionally reports minimum voltage instead of average +- Sum battery monitor reports average temp +- Torqeedo dual motor support (see TRQ1, TRQ2 params) +- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes) +- UBlox GPS time ignored until at least 2D fix +- VideoTX supports additional freq bands (RushFPV 3.3Ghz) +- Volz logs desired and actual position, voltage, current, motor and PCB temp +- Volz server feedback and logging fixed +- Volz servo output in its own thread resulting in smoother movements +- W25N02KV flash support + +4) Networking enhancements and fixes + +- Allow multiple UDP clients to connect/disconnect/reconnect +- Ethernet supports faster log downloading (raised SDMMC clock limit on H7) + +5) Camera and gimbal enhancements + +- Alexmos precision improved slightly +- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC) +- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at +- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame) +- Dual serial camera gimbal mounts fixed +- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS +- Retract Mount2 aux function added (see RCx_OPTION = 113) +- Servo gimbal reported angles respect roll, pitch and yaw limits +- Siyi driver sends autopilot location and speed (recorded in images via EXIF) +- Siyi picture and video download scripts +- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg) +- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script +- Siyi ZT6 hardware id and set-lens fixed +- Topotek gimbal support +- Trigger distance ignores GPS status and only uses EKF reported location + +6) Harmonic notch enhancements + +- Harmonic notch is active in forward flight on quadplanes +- Harmonic notch filter freq clamping and disabling reworked +- Harmonic notch handles negative ESC RPMs +- Harmonic notch supports per-motor throttle-based harmonic notch + +7) Copter specific enhancements and bug fixes + +- Attitude control fix to dt update order (reduces rate controller noise) +- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time +- Auto mode small target position jump when takeoff completes removed +- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None +- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178) +- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command +- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only) +- AutoTune fix to prevent spool up after landing +- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well) +- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180) +- Config error avoided if auto mode is paused very soon after poweron +- FLIGHT_OPTIONS bit added to require position estimate before arming +- Follow mode slowdown calcs fixed when target is moving +- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT) +- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message +- Guided mode internal error resolved when switching between thrust or climb rate based altitude control +- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle +- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down +- Landing detector logging added to ease support (see LDET message) +- Loiter unlimited command accepts NaNs (QGC sends these) +- Mavlink SYSTEM_STATUS set to BOOT during initialisation +- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values +- Payload place bug fix when aborted because gripper is already released +- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219) +- RTL_ALT minimum reduced to 30cm +- SystemID position controller support (Copter and Heli) +- TriCopter motor test and slew-up fixed +- WPNAV_SPEED min reduced to 10 cm/s (Copter only) +- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe + +8) TradHeli specific enhancements + +- Autorotation yaw behaviour fix +- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate +- Blade pitch angle logging added (see SWSH log message) +- Constrain cyclic roll for intermeshing +- ICE / turbine cool down fix +- Inverted flight extended to non manual throttle modes +- Inverted flight transitions smoothed and restricted to only Stabilize mode +- SWSH logging fix for reversed collectives + +9) Plane specific enhancements and bug fixes + +- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling +- Allow for different orientations of landing rangefinder +- Assistance requirements evaluted on mode change +- FBWB/CRUISE climb/sink rate limited by TECS limits +- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope) +- Glider pullup support (available only through custom build server) +- Loiter breakout improved to better handle destinations inside loiter circle +- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled) +- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes +- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition) +- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic +- Quadplane assistance check enhancements +- Quadplane Deca frame support +- Quadplane gets smoother takeoff by input shaping target accel and velocity +- Servo wiggles in altitude wait staged to be one after another +- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames +- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN) +- Takeoff fixes for fence autoenable +- Takeoff improvements including less overshoot of TKOFF_ALT +- TECS reset along with other controllers (important if plane dropped from balloon) +- Tilt quadplane ramp of motors on back transition fixed +- Tiltrotor tilt angles logged +- TKOFF_THR_MIN applied to SLT transitions +- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration +- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff + +10) Rover specific enhancements and bug fixes + +- Auto mode reversed state maintained if momentarily switched to Hold mode +- Circle mode tracks better and avoids getting stuck at circle edge +- Flight time stats fixed +- MAV_CMD_NAV_SET_YAW_SPEED deprecated +- Omni3Mecanum frame support +- Stopping point uses max deceleration (was incorrectly using acceleration) +- Wheel rate controller slew rate fix + +11) Antenna Tracker specific enhancements and bug fixes + +- Never track lat,lon of 0,0 + +12) Scripting enhancements + +- advance-wp.lua applet supports advancing Auto mode WP via RC switch +- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch +- battery_internal_resistance_check.lua monitors battery resistance +- CAN:get_device returns nil for unconfigured CAN device +- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only) +- Copter:get_target_location, update_target_location support +- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only) +- Display text on OLED display supported +- Docs improved for many bindings +- EFI get_last_update_ms binding +- EFI_SkyPower.lua driver accepts 2nd supply voltage +- ESC_slew_rate.lua example script supports testing ESCs +- Filesystem CRC32 check to allow scripts to check module versions +- forced arming support +- GPIO get/set mode bindings (see gpio:set_mode, get_mode) +- GPS-for-yaw angle binding (see gps:gps_yaw_deg) +- Halo6000 EFI driver can log all CAN packets for easier debugging +- handle_external_position_estimate binding allows sending position estimate from lua to EKF +- I2C:transfer support +- IMU gyros_consistent and accels_consistent bindings added +- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control +- INS bindings for is calibrating, gyro and accel sensor values +- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients +- Logging of booleans supported +- Lua language checks improved (finds more errors) +- MAVLink commands can be called from scripting +- MCU voltage binding (see analog:mcu_voltage) +- NMEA 2000 EFI driver (see EFI_NMEA2k.lua) +- "open directory failed" false warning when scripts in ROMFS fixed +- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch +- Pass by reference values are always initialized +- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras +- plane_aerobatics.lua minor enhancements +- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation +- "require" function failures in rare circumstances fixed +- "require" function works for modules in ROMFS (e.g. not on SD card) +- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_) +- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand) +- SD card formatting supported +- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation) +- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter) +- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch +- Slung payload oscillation suppression applet added (see copter-slung-payload.lua) +- Temperature sensor bindings added +- uint64 support +- Various performance and memory usage optimizations +- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8 +- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame + +13) GCS / mavlink related changes and fixes + +- BATTERY2 message deprecated (replaced by BATTERY_STATUS) +- CMD_MISSION_START/STOP rejected if first-item/last-item args provided +- Deny attempts to upload two missions simultaneously +- Fence and Rally points may be uploaded using FTP +- GPS_INPUT and HIL_GPS handles multiple GPSs +- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC) +- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196 +- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support +- MAV_CMD_SET_HAGL support (Plane only) +- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links +- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message) +- Message interval supports TERRAIN_REPORT msg +- Mission upload may be cancelled using MISSION_CLEAR_ALL +- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated +- RC_CHANNELS_RAW deprecated +- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers +- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only) +- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports + +14) Logging enhancements and fixes + +- AC_PID resets and I-term sets logged +- ANG provides attitude at high rate (equivalent to ATT) +- ATT logs angles as floats (better resolution than ints) +- CAND message gets driver index +- DCM log message includes roll/pitch and yaw error +- EDT2 log msg includes stress and status received via extended DShot Telemetry v2 +- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin) +- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct +- FMT messages written as required instead of all at beginning +- Logging restarted after download completes when LOG_DISARMED = 1 +- MISE msg logs active mission command (CMD logged when commands are uploaded) +- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN +- RPM sensor logging gets instance field, quality and health fields +- Short filename support removed (e.g log1.BIN instead of 00000001.BIN) +- Temperature sensor logging option for only sensors with no source (see TEMP_LOG) +- UART data rates logged at 1hz (see UART message) + +15) ROS2 / DDS support + +- Airspeed published +- Battery topic reports all available batteries +- Compile-time configurable rates for each publisher +- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent +- GPS global origin published at 1 Hz +- High frequency raw imu data transmission +- Joystick support +- Support sending waypoints to Copter and Rover +- Remove the XML refs file in favor of binary entity creation + +16) Safety related enhancements and fixes + +- Accel/Gyro inconsistent message fixed for using with only single IMU +- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action +- Far from EKF origin pre-arm check removed (Copter only) +- Fence breach warning message slightly improved +- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS) +- Fences can be stored to SD Card (see BRD_SD_FENCE param) +- ICEngine stopped when in E-Stop or safety engaged (Plane only) +- LEDs flash green lights based on EKF location not GPS +- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS) +- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added +- Pre-arm check if OpenDroneID is compiled in but disabled +- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions) +- Pre-arm checks alert user more quickly on failure +- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE +- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover) +- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on +- Warning of duplicate SERIALx_PROTOCOL = RCIN + +17) Other bug fixes and minor enhancements + +- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher) +- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools +- Bootloader rejects allocation of broadcast node ID +- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI) +- Dijkstras fix to correct use of uninitialised variable +- DShot rates are not limited by NeoPixel rates +- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode +- Filesystem does not show entries for empty @ files +- Filesystem efficiency improvements when reading files +- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset) +- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm) +- Internal error thrown if we lose parameters due to saving queue being too small +- MAVLink via DroneCAN baud rate fix +- SPI pins may also be used as GPIOs +- Terrain cache size configurable (see TERRAIN_CACHE_SZ) + +18) Developer focused fixes and enhancements + +- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams +- Cygwin build fix for non-SITL builds +- Cygwin build fixed with malloc wrap +- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua) +- EKF3 code generator documentation and cleanup +- GPS jamming simulator added +- MacOS compiler warnings reduced +- SFML joystick support +- SITL support for OpenBSD +- Text warning if older Fence or Rally point protocols are used +------------------------------------------------------------------ +Release 4.5.7 08 Oct 2024 + +Changes from 4.5.7-beta1 + +1) Reverted Septentrio GPS sat count correctly drops to zero when 255 received +------------------------------------------------------------------ +Release 4.5.7-beta1 26 Sep 2024 + +Changes from 4.5.6 + +1) Bug fixes and minor enhancements + +- VUAV-V7pro support +- CUAV-7-Nano correction for LEDs and battery volt and current scaling +- DroneCAN deadlock and saturation of CAN bus fixed +- DroneCAN DNA server init fix (caused logging issues and spam on bus) +- F4 boards with inverter support correctly uninvert RX/TX +- Nanoradar M72 radar driver fix for object avoidance path planning +- RC support for latest version of GHST +- Septentrio GPS sat count correctly drops to zero when 255 received + +2) ROS2/DDS and other developer focused enhancements + +- AP quaternions normalised for ROS2 to avoid warnings +- Dependencies fixed for easier installation +- ROS2 SITL launch file enhancements including displaying console and map +- ROS_DOMAIN_ID param added to support multiple vehicles or instances of ROS2 +- Python 3.12 support +------------------------------------------------------------------ +Release 4.5.6 03 Sep 2024 + +No changes from 4.5.6-beta1 +------------------------------------------------------------------ +Release 4.5.6-beta1 20 Aug 2024 + +Changes from 4.5.5 + +1) Board specific enhancements and bug fixes + +- 3DR Control Zero H7 Rev G support +- CUAV-7-Nano support +- FoxeerF405v2 servo outputs increased from 9 to 11 +- Holybro Pixhawk6C hi-power peripheral overcurrent reporting fixed +- iFlight 2RAW H7 support +- MFT-SEMA100 support +- TMotorH743 support BMI270 baro +- ZeroOneX6 support + +2) Minor enhancements and bug fixes + +- Cameras using MAVLink report vendor and model name correctly +- DroneCAN fix to remove occasional NodeID registration error +- GPS NMEA and GSoF driver ground course corrected (now always 0 ~ 360 deg) +- ICP101XX barometer slowed to avoid I2C communication errors +- IMU temp cal param (INSn_ACCSCAL_Z) stored correctly when bootloader is flashed +- IMU gyro/accel duplicate id registration fixed to avoid possible pre-arm failure +- Logging to flash timestamp fix +- OSD displays ESC temp instead of motor temp +- PID controller error calculation bug fix (was using target from prev iteration) +- Relay on MAIN pins fixed +------------------------------------------------------------------ +Release 4.5.5 1st Aug 2024 + +No changes from 4.5.5-beta2 +------------------------------------------------------------------ +Release 4.5.5-beta2 27 July 2024 + +Changes from 4.5.5-beta1 + +1) Board specific enhancements and bug fixes + +- CubeRed's second core disabled at boot to avoid spurious writes to RAM +- CubeRed bootloader's dual endpoint update method fixed +------------------------------------------------------------------ +Release 4.5.5-beta1 1st July 2024 + +Changes from 4.5.4 + +1) Board specific enhancements and bug fixes + +- fixed IOMCU transmission errors when using bdshot +- update relay parameter names on various boards +- add ASP5033 airspeed in minimal builds +- added RadiolinkPIX6 +- fix Aocoda-RC H743Dual motor issue +- use ICM45686 as an ICM20649 alternative in CubeRedPrimary + +2) System level minor enhancements and bug fixes + +- correct use-after-free in script statistics +- added arming check for eeprom full +- fixed a block logging issue which caused log messages to be dropped +- enable Socket SO_REUSEADDR on LwIP +- removed IST8310 overrun message +- added Siyi ZT6 support +- added BTFL sidebar symbols to the OSD +- added CRSF extended link stats to the OSD +- use the ESC with the highest RPM in the OSD when only one can be displayed +- support all Tramp power levels on high power VTXs +- emit jump count in missions even if no limit +- improve the bitmask indicating persistent parameters on bootloader flash +- fix duplicate error condition in the MicroStrain7 + +5) Other minor enhancements and bug fixes + +- specify pymonocypher version in more places +- added DroneCAN dependencies to custom builds + +------------------------------------------------------------------ +Release 4.5.4 12th June 2024 + +Changes from 4.5.3 + +Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X + +------------------------------------------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) ------------------------------------------------------------------ Release 4.5.1 8th April 2024 diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index 3c6398ec6a5648..a35a6f3251ad58 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -58,7 +58,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40), SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45), SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50), - SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900, 55), #if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 300, 60), SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65), @@ -83,7 +82,7 @@ void Tracker::one_second_loop() mavlink_system.sysid = g.sysid_this_mav; // update assigned functions and enable auxiliary servos - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // updated armed/disarmed status LEDs update_armed_disarmed(); diff --git a/AntennaTracker/config.h b/AntennaTracker/config.h index fd2932550ddbaa..0875e1d8d98eca 100644 --- a/AntennaTracker/config.h +++ b/AntennaTracker/config.h @@ -3,14 +3,6 @@ #include "defines.h" -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - #ifndef MAV_SYSTEM_ID // use 2 for antenna tracker by default # define MAV_SYSTEM_ID 2 diff --git a/AntennaTracker/mode.h b/AntennaTracker/mode.h index d6a10022dc8c55..bfdcad9ac7860e 100644 --- a/AntennaTracker/mode.h +++ b/AntennaTracker/mode.h @@ -22,6 +22,7 @@ class Mode { // returns a unique number specific to this mode virtual Mode::Number number() const = 0; + virtual const char* name() const = 0; virtual bool requires_armed_servos() const = 0; @@ -41,6 +42,7 @@ class Mode { class ModeAuto : public Mode { public: Mode::Number number() const override { return Mode::Number::AUTO; } + const char* name() const override { return "Auto"; } bool requires_armed_servos() const override { return true; } void update() override; }; @@ -48,6 +50,7 @@ class ModeAuto : public Mode { class ModeGuided : public Mode { public: Mode::Number number() const override { return Mode::Number::GUIDED; } + const char* name() const override { return "Guided"; } bool requires_armed_servos() const override { return true; } void update() override; @@ -66,6 +69,7 @@ class ModeGuided : public Mode { class ModeInitialising : public Mode { public: Mode::Number number() const override { return Mode::Number::INITIALISING; } + const char* name() const override { return "Initialising"; } bool requires_armed_servos() const override { return false; } void update() override {}; }; @@ -73,6 +77,7 @@ class ModeInitialising : public Mode { class ModeManual : public Mode { public: Mode::Number number() const override { return Mode::Number::MANUAL; } + const char* name() const override { return "Manual"; } bool requires_armed_servos() const override { return true; } void update() override; }; @@ -80,6 +85,7 @@ class ModeManual : public Mode { class ModeScan : public Mode { public: Mode::Number number() const override { return Mode::Number::SCAN; } + const char* name() const override { return "Scan"; } bool requires_armed_servos() const override { return true; } void update() override; }; @@ -87,6 +93,7 @@ class ModeScan : public Mode { class ModeServoTest : public Mode { public: Mode::Number number() const override { return Mode::Number::SERVOTEST; } + const char* name() const override { return "ServoTest"; } bool requires_armed_servos() const override { return true; } void update() override {}; @@ -96,6 +103,7 @@ class ModeServoTest : public Mode { class ModeStop : public Mode { public: Mode::Number number() const override { return Mode::Number::STOP; } + const char* name() const override { return "Stop"; } bool requires_armed_servos() const override { return false; } void update() override {}; }; diff --git a/AntennaTracker/servos.cpp b/AntennaTracker/servos.cpp index 23e1e0cab5bfd4..5ca8bc0b54656a 100644 --- a/AntennaTracker/servos.cpp +++ b/AntennaTracker/servos.cpp @@ -8,7 +8,7 @@ void Tracker::init_servos() { // update assigned functions and enable auxiliary servos - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw); SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch); diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index facd7141b53ebc..8a1240d2ee3910 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -131,6 +131,11 @@ void Tracker::update_tracking(void) */ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg) { + // reject (0;0) coordinates + if (!msg.lat && !msg.lon) { + return; + } + vehicle.location.lat = msg.lat; vehicle.location.lng = msg.lon; vehicle.location.alt = msg.alt/10; @@ -139,7 +144,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg) vehicle.last_update_us = AP_HAL::micros(); vehicle.last_update_ms = AP_HAL::millis(); #if HAL_LOGGING_ENABLED - // log vehicle as GPS2 + // log vehicle as VPOS if (should_log(MASK_LOG_GPS)) { Log_Write_Vehicle_Pos(vehicle.location.lat, vehicle.location.lng, vehicle.location.alt, vehicle.vel); } diff --git a/AntennaTracker/version.h b/AntennaTracker/version.h index eae1a8cad548fe..03c376adf1c849 100644 --- a/AntennaTracker/version.h +++ b/AntennaTracker/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "AntennaTracker V4.6.0-dev" +#define THISFIRMWARE "AntennaTracker V4.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 6 +#define FW_MINOR 7 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/AntennaTracker/wscript b/AntennaTracker/wscript index cecd79a19a476f..68ea44f0d1474a 100644 --- a/AntennaTracker/wscript +++ b/AntennaTracker/wscript @@ -6,11 +6,7 @@ def build(bld): bld.ap_stlib( name=vehicle + '_libs', ap_vehicle=vehicle, - ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AP_Beacon', - 'AP_Arming', - 'AP_RCMapper', - ], + ap_libraries=bld.ap_common_vehicle_libraries(), ) bld.ap_program( diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 3049e758184662..7f1ecabb7f14c6 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -1,35 +1,33 @@ // User specific config file. Any items listed in config.h can be overridden here. // 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 RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash -//#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 MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support -//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support -//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support -//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support -//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support -//#define MODE_FLIP_ENABLED DISABLED // disable flip mode support -//#define MODE_FOLLOW_ENABLED DISABLED // disable follow mode support -//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support -//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support -//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support -//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support -//#define MODE_RTL_ENABLED DISABLED // disable rtl mode support -//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support -//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support -//#define MODE_SYSTEMID_ENABLED DISABLED // disable system ID mode support -//#define MODE_THROW_ENABLED DISABLED // disable throw mode support -//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support -//#define OSD_ENABLED DISABLED // disable on-screen-display support +//#define LOGGING_ENABLED 0 // disable logging to save 11K of flash space +//#define MOUNT 0 // disable the camera gimbal to save 8K of flash space +//#define AUTOTUNE_ENABLED 0 // disable the auto tune functionality to save 7k of flash +//#define NAV_GUIDED 0 // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands +//#define MODE_ACRO_ENABLED 0 // disable acrobatic mode support +//#define MODE_AUTO_ENABLED 0 // disable auto mode support +//#define MODE_BRAKE_ENABLED 0 // disable brake mode support +//#define MODE_CIRCLE_ENABLED 0 // disable circle mode support +//#define MODE_DRIFT_ENABLED 0 // disable drift mode support +//#define MODE_FLIP_ENABLED 0 // disable flip mode support +//#define MODE_FOLLOW_ENABLED 0 // disable follow mode support +//#define MODE_GUIDED_ENABLED 0 // disable guided mode support +//#define MODE_GUIDED_NOGPS_ENABLED 0 // disable guided/nogps mode support +//#define MODE_LOITER_ENABLED 0 // disable loiter mode support +//#define MODE_POSHOLD_ENABLED 0 // disable poshold mode support +//#define MODE_RTL_ENABLED 0 // disable rtl mode support +//#define MODE_SMARTRTL_ENABLED 0 // disable smartrtl mode support +//#define MODE_SPORT_ENABLED 0 // disable sport mode support +//#define MODE_SYSTEMID_ENABLED 0 // disable system ID mode support +//#define MODE_THROW_ENABLED 0 // disable throw mode support +//#define MODE_ZIGZAG_ENABLED 0 // disable zigzag mode support +//#define OSD_ENABLED 0 // disable on-screen-display support // features below are disabled by default on all boards //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes //#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link -//#define ADVANCED_FAILSAFE ENABLED // enabled advanced failsafe which allows running a portion of the mission in failsafe events +//#define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events // other settings //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) @@ -44,5 +42,5 @@ //#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz //#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz //#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz -//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches -//#define USER_PARAMS_ENABLED ENABLED // to enable user parameters +//#define USERHOOK_AUXSWITCH 1 // for code to handle user aux switches +//#define USER_PARAMS_ENABLED 1 // to enable user parameters diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 4fbfe125ccd302..6ef06d421641a4 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #pragma GCC diagnostic push -#if defined(__clang__) +#if defined(__clang_major__) && __clang_major__ >= 14 #pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical" #endif @@ -44,7 +44,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) } // always check motors - char failure_msg[50] {}; + char failure_msg[100] {}; if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) { check_failed(display_failure, "Motors: %s", failure_msg); passed = false; @@ -179,7 +179,7 @@ bool AP_Arming_Copter::terrain_database_required() const } if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE && - copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) { + copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) { return true; } return AP_Arming::terrain_database_required(); @@ -210,7 +210,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } // acro balance parameter check -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH"); return false; @@ -224,7 +224,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } #if FRAME_CONFIG == HELI_FRAME - char fail_msg[50]; + char fail_msg[100]{}; // 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); @@ -238,17 +238,21 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } #else - if (copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_QUAD || - copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL || - copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) { + switch (copter.g2.frame_class.get()) { + case AP_Motors::MOTOR_FRAME_HELI_QUAD: + case AP_Motors::MOTOR_FRAME_HELI_DUAL: + case AP_Motors::MOTOR_FRAME_HELI: check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS"); return false; + + default: + break; } #endif // HELI_FRAME // checks when using range finder for RTL -#if MODE_RTL_ENABLED == ENABLED - if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) { +#if MODE_RTL_ENABLED + if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) { // get terrain source from wpnav const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s"; switch (copter.wp_nav->get_terrain_source()) { @@ -257,6 +261,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) return false; break; case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER: +#if AP_RANGEFINDER_ENABLED if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "no rangefinder"); return false; @@ -266,6 +271,9 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "RTL_ALT>RNGFND_MAX_CM"); return false; } +#else + check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "rangefinder not in firmware"); +#endif break; case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE: // these checks are done in AP_Arming @@ -283,7 +291,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[100] = {}; 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; @@ -300,7 +308,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) bool AP_Arming_Copter::oa_checks(bool display_failure) { #if AP_OAPATHPLANNER_ENABLED - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) { return true; } @@ -337,10 +345,10 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) { // check if fence requires GPS bool fence_requires_gps = false; - #if AP_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 +#endif // check if flight mode requires GPS bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE); @@ -431,7 +439,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) // always check if inertial nav has started and is ready const auto &ahrs = AP::ahrs(); - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "AHRS: %s", failure_msg); return false; @@ -439,28 +447,26 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) // check if fence requires GPS bool fence_requires_gps = false; - #if AP_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 +#endif - if (mode_requires_gps) { + if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) { if (!copter.position_ok()) { // vehicle level position estimate checks check_failed(display_failure, "Need Position Estimate"); return false; } - } else { - if (fence_requires_gps) { - if (!copter.position_ok()) { - // clarify to user why they need GPS in non-GPS flight mode - check_failed(display_failure, "Fence enabled, need position estimate"); - return false; - } - } else { - // return true if GPS is not required - return true; + } else if (fence_requires_gps) { + if (!copter.position_ok()) { + // clarify to user why they need GPS in non-GPS flight mode + check_failed(display_failure, "Fence enabled, need position estimate"); + return false; } + } else { + // return true if GPS is not required + return true; } // check for GPS glitch (as reported by EKF) @@ -522,7 +528,7 @@ bool AP_Arming_Copter::winch_checks(bool display_failure) const if (winch == nullptr) { return true; } - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "%s", failure_msg); return false; @@ -599,25 +605,25 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) // check throttle if (check_enabled(ARMING_CHECK_RC)) { - #if FRAME_CONFIG == HELI_FRAME +#if FRAME_CONFIG == HELI_FRAME const char *rc_item = "Collective"; - #else +#else const char *rc_item = "Throttle"; - #endif +#endif // check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto - if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) { + if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) { // above top of deadband is too always high if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) { check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); return false; } // in manual modes throttle must be at zero - #if FRAME_CONFIG != HELI_FRAME +#if FRAME_CONFIG != HELI_FRAME if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) { check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); return false; } - #endif +#endif } } @@ -722,7 +728,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ copter.update_super_simple_bearing(false); // Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED copter.g2.smart_rtl.set_home(copter.position_ok()); #endif @@ -802,15 +808,6 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che } } -#if AUTOTUNE_ENABLED == ENABLED - // save auto tuned parameters - if (copter.flightmode == &copter.mode_autotune) { - copter.mode_autotune.save_tuning_gains(); - } else { - copter.mode_autotune.reset(); - } -#endif - // we are not in the air copter.set_land_complete(true); copter.set_land_complete_maybe(true); @@ -818,7 +815,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che // send disarm command to motors copter.motors->armed(false); -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED // reset the mission copter.mode_auto.mission.reset(); #endif @@ -831,6 +828,11 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che copter.ap.in_arming_delay = false; +#if AUTOTUNE_ENABLED + // Possibly save auto tuned parameters + copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune); +#endif + return true; } diff --git a/ArduCopter/AP_ExternalControl_Copter.cpp b/ArduCopter/AP_ExternalControl_Copter.cpp index 35353a412618f6..eb16147737fd66 100644 --- a/ArduCopter/AP_ExternalControl_Copter.cpp +++ b/ArduCopter/AP_ExternalControl_Copter.cpp @@ -29,6 +29,15 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f return true; } +bool AP_ExternalControl_Copter::set_global_position(const Location& loc) +{ + // Check if copter is ready for external control and returns false if it is not. + if (!ready_for_external_control()) { + return false; + } + return copter.set_target_location(loc); +} + bool AP_ExternalControl_Copter::ready_for_external_control() { return copter.flightmode->in_guided_mode() && copter.motors->armed(); diff --git a/ArduCopter/AP_ExternalControl_Copter.h b/ArduCopter/AP_ExternalControl_Copter.h index e7601c5552fc6c..527af304f64a7f 100644 --- a/ArduCopter/AP_ExternalControl_Copter.h +++ b/ArduCopter/AP_ExternalControl_Copter.h @@ -7,7 +7,8 @@ #if AP_EXTERNAL_CONTROL_ENABLED -class AP_ExternalControl_Copter : public AP_ExternalControl { +class AP_ExternalControl_Copter : public AP_ExternalControl +{ public: /* Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. @@ -15,6 +16,11 @@ class AP_ExternalControl_Copter : public AP_ExternalControl { Yaw is in earth frame, NED [rad/s]. */ bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override WARN_IF_UNUSED; + + /* + Sets the target global position for a loiter point. + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; private: /* Return true if Copter is ready to handle external control data. diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index 67646caed9c0b8..3e71782c18c00a 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -15,7 +15,9 @@ void Copter::run_rate_controller() pos_control->set_dt(last_loop_time_s); // run low level rate controllers that only require IMU data - attitude_control->rate_controller_run(); + attitude_control->rate_controller_run(); + // reset sysid and other temporary inputs + attitude_control->rate_controller_target_reset(); } /************************************************************* @@ -64,7 +66,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control) return 0.0f; } -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED if (g2.toy_mode.enabled()) { // allow throttle to be reduced after throttle arming and for // slower descent close to the ground diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0460de12ecf821..0f263b89c0621b 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -114,7 +114,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { 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 +#if AC_CUSTOMCONTROL_MULTI_ENABLED FAST_TASK(run_custom_controller), #endif #if FRAME_CONFIG == HELI_FRAME @@ -159,12 +159,12 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { 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), SCHED_TASK(arm_motors_check, 10, 50, 21), -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24), #endif SCHED_TASK(auto_disarm_check, 10, 50, 27), SCHED_TASK(auto_trim, 10, 75, 30), -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED SCHED_TASK(read_rangefinder, 20, 100, 33), #endif #if HAL_PROXIMITY_ENABLED @@ -176,7 +176,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(update_altitude, 10, 100, 42), SCHED_TASK(run_nav_updates, 50, 100, 45), SCHED_TASK(update_throttle_hover,100, 90, 48), -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51), #endif #if HAL_SPRAYER_ENABLED @@ -186,7 +186,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), #endif - SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), #if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 69), #endif @@ -233,7 +232,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100, 138), #endif -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED SCHED_TASK(afs_fs_check, 10, 100, 141), #endif #if AP_TERRAIN_AVAILABLE @@ -273,34 +272,39 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Copter::_failsafe_priorities[7]; -#if AP_SCRIPTING_ENABLED -#if MODE_GUIDED_ENABLED == ENABLED -// start takeoff to given altitude (for use by scripting) -bool Copter::start_takeoff(float alt) + +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if MODE_GUIDED_ENABLED +// set target location (for use by external control and scripting) +bool Copter::set_target_location(const Location& target_loc) { // exit if vehicle is not in Guided mode or Auto-Guided mode if (!flightmode->in_guided_mode()) { return false; } - if (mode_guided.do_user_takeoff_start(alt * 100.0f)) { - copter.set_auto_armed(true); - return true; - } - return false; + return mode_guided.set_destination(target_loc); } -// set target location (for use by scripting) -bool Copter::set_target_location(const Location& target_loc) +// start takeoff to given altitude (for use by scripting) +bool Copter::start_takeoff(const float alt) { // exit if vehicle is not in Guided mode or Auto-Guided mode if (!flightmode->in_guided_mode()) { return false; } - return mode_guided.set_destination(target_loc); + if (mode_guided.do_user_takeoff_start(alt * 100.0f)) { + copter.set_auto_armed(true); + return true; + } + return false; } +#endif //MODE_GUIDED_ENABLED +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED +#if MODE_GUIDED_ENABLED // set target position (for use by scripting) bool Copter::set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { @@ -372,6 +376,7 @@ bool Copter::set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& return true; } +// set target roll pitch and yaw angles with throttle (for use by scripting) bool Copter::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) { // exit if vehicle is not in Guided mode or Auto-Guided mode @@ -385,9 +390,78 @@ bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, flo mode_guided.set_angle(q, Vector3f{}, climb_rate_ms*100, false); return true; } -#endif -#if MODE_CIRCLE_ENABLED == ENABLED +// set target roll pitch and yaw rates with throttle (for use by scripting) +bool Copter::set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) +{ + // exit if vehicle is not in Guided mode or Auto-Guided mode + if (!flightmode->in_guided_mode()) { + return false; + } + + // Zero quaternion indicates rate control + Quaternion q; + q.zero(); + + // Convert from degrees per second to radians per second + Vector3f ang_vel_body { roll_rate_dps, pitch_rate_dps, yaw_rate_dps }; + ang_vel_body *= DEG_TO_RAD; + + // Pass to guided mode + mode_guided.set_angle(q, ang_vel_body, throttle, true); + return true; +} + +// Register a custom mode with given number and names +AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, const char* full_name, const char* short_name) +{ + const Mode::Number number = (Mode::Number)num; + + // See if this mode has been registered already, if it has return the state for it + // This allows scripting restarts + for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) { + if (mode_guided_custom[i] == nullptr) { + break; + } + if ((mode_guided_custom[i]->mode_number() == number) && + (strcmp(mode_guided_custom[i]->name(), full_name) == 0) && + (strncmp(mode_guided_custom[i]->name4(), short_name, 4) == 0)) { + return &mode_guided_custom[i]->state; + } + } + + // Number already registered to existing mode + if (mode_from_mode_num(number) != nullptr) { + return nullptr; + } + + // Find free slot + for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) { + if (mode_guided_custom[i] == nullptr) { + // Duplicate strings so were not pointing to unknown memory + const char* full_name_copy = strdup(full_name); + const char* short_name_copy = strndup(short_name, 4); + if ((full_name_copy != nullptr) && (short_name_copy != nullptr)) { + mode_guided_custom[i] = NEW_NOTHROW ModeGuidedCustom(number, full_name_copy, short_name_copy); + } + if (mode_guided_custom[i] == nullptr) { + // Allocation failure + return nullptr; + } + + // Registration sucsessful, notify the GCS that it should re-request the avalable modes + gcs().available_modes_changed(); + + return &mode_guided_custom[i]->state; + } + } + + // No free slots + return nullptr; +} +#endif // MODE_GUIDED_ENABLED + +#if MODE_CIRCLE_ENABLED // circle mode controls bool Copter::get_circle_radius(float &radius_m) { @@ -408,7 +482,7 @@ bool Copter::set_desired_speed(float speed) return flightmode->set_speed_xy(speed * 100.0f); } -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED // returns true if mode supports NAV_SCRIPT_TIME mission commands bool Copter::nav_scripting_enable(uint8_t mode) { @@ -442,15 +516,41 @@ bool Copter::has_ekf_failsafed() const return failsafe.ekf; } +// get target location (for use by scripting) +bool Copter::get_target_location(Location& target_loc) +{ + return flightmode->get_wp(target_loc); +} + +/* + update_target_location() acts as a wrapper for set_target_location + */ +bool Copter::update_target_location(const Location &old_loc, const Location &new_loc) +{ + /* + by checking the caller has provided the correct old target + location we prevent a race condition where the user changes mode + or commands a different target in the controlling lua script + */ + Location next_WP_loc; + flightmode->get_wp(next_WP_loc); + if (!old_loc.same_loc_as(next_WP_loc) || + old_loc.get_alt_frame() != new_loc.get_alt_frame()) { + return false; + } + + return set_target_location(new_loc); +} + #endif // AP_SCRIPTING_ENABLED -// returns true if vehicle is landing. Only used by Lua scripts +// returns true if vehicle is landing. bool Copter::is_landing() const { return flightmode->is_landing(); } -// returns true if vehicle is taking off. Only used by Lua scripts +// returns true if vehicle is taking off. bool Copter::is_taking_off() const { return flightmode->is_taking_off(); @@ -458,7 +558,7 @@ bool Copter::is_taking_off() const bool Copter::current_mode_requires_mission() const { -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED return flightmode == &mode_auto; #else return false; @@ -536,7 +636,9 @@ void Copter::loop_rate_logging() // should be run at 10hz void Copter::ten_hz_logging_loop() { - // log attitude data if we're not already logging at the higher rate + // always write AHRS attitude at 10Hz + ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG); + // log attitude controller data if we're not already logging at the higher rate if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) { Log_Write_Attitude(); } @@ -548,14 +650,17 @@ void Copter::ten_hz_logging_loop() if (!should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_EKF_POS(); } - if (should_log(MASK_LOG_MOTBATT)) { + if ((FRAME_CONFIG == HELI_FRAME) || should_log(MASK_LOG_MOTBATT)) { + // always write motors log if we are a heli motors->Log_Write(); } if (should_log(MASK_LOG_RCIN)) { logger.Write_RCIN(); +#if AP_RSSI_ENABLED if (rssi.enabled()) { logger.Write_RSSI(); } +#endif } if (should_log(MASK_LOG_RCOUT)) { logger.Write_RCOUT(); @@ -575,9 +680,6 @@ void Copter::ten_hz_logging_loop() g2.beacon.log(); #endif } -#if FRAME_CONFIG == HELI_FRAME - Log_Write_Heli(); -#endif #if AP_WINCH_ENABLED if (should_log(MASK_LOG_ANY)) { g2.winch.write_log(); @@ -601,7 +703,7 @@ void Copter::twentyfive_hz_logging() AP::ins().Write_IMU(); } -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) { //update autorotation log g2.arot.Log_Write_Autorotation(); @@ -627,19 +729,36 @@ void Copter::three_hz_loop() // check for deadreckoning failsafe failsafe_deadreckon_check(); - // update ch6 in flight tuning + //update transmitter based in flight tuning tuning(); // check if avoidance should be enabled based on alt low_alt_avoidance(); } +// ap_value calculates a 32-bit bitmask representing various pieces of +// state about the Copter. It replaces a global variable which was +// used to track this state. +uint32_t Copter::ap_value() const +{ + uint32_t ret = 0; + + const bool *b = (const bool *)≈ + for (uint8_t i=0; iset_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); #endif } @@ -819,16 +938,16 @@ bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const Copter::Copter(void) : flight_modes(&g.flight_mode1), + pos_variance_filt(FS_EKF_FILT_DEFAULT), + vel_variance_filt(FS_EKF_FILT_DEFAULT), + hgt_variance_filt(FS_EKF_FILT_DEFAULT), + flightmode(&mode_stabilize), simple_cos_yaw(1.0f), super_simple_cos_yaw(1.0), 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_stabilize), - pos_variance_filt(FS_EKF_FILT_DEFAULT), - vel_variance_filt(FS_EKF_FILT_DEFAULT), - hgt_variance_filt(FS_EKF_FILT_DEFAULT) + param_loader(var_info) { } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3285f267976e5c..db74c31dc412c1 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -71,6 +71,7 @@ #include #include #include +#include // Configuration #include "defines.h" @@ -82,7 +83,7 @@ #define MOTOR_CLASS AP_MotorsMulticopter #endif -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED #include // Autorotation controllers #endif @@ -114,13 +115,13 @@ # include # include #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED # include #endif #if AP_TERRAIN_AVAILABLE # include #endif -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED # include #endif @@ -136,10 +137,10 @@ #include #endif -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED # include "afs_copter.h" #endif -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED # include "toy_mode.h" #endif #if AP_WINCH_ENABLED @@ -151,7 +152,7 @@ #include #endif -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED #include // Custom control library #endif @@ -182,7 +183,7 @@ class Copter : public AP_Vehicle { friend class ParametersG2; friend class AP_Avoidance_Copter; -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED friend class AP_AdvancedFailsafe_Copter; #endif friend class AP_Arming_Copter; @@ -251,22 +252,13 @@ class Copter : public AP_Vehicle { AP_Int8 *flight_modes; const uint8_t num_flight_modes = 6; - struct RangeFinderState { - bool enabled:1; - bool alt_healthy:1; // true if we can trust the altitude from the rangefinder - int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder - float inertial_alt_cm; // inertial alt at time of last rangefinder sample - uint32_t last_healthy_ms; - LowPassFilterFloat alt_cm_filt; // altitude filter - int16_t alt_cm_glitch_protected; // last glitch protected altitude - int8_t glitch_count; // non-zero number indicates rangefinder is glitching - uint32_t glitch_cleared_ms; // system time glitch cleared - float terrain_offset_cm; // filtered terrain offset (e.g. terrain's height above EKF origin) - } rangefinder_state, rangefinder_up_state; - - // return rangefinder height interpolated using inertial altitude + AP_SurfaceDistance rangefinder_state {ROTATION_PITCH_270, inertial_nav, 0U}; + AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, inertial_nav, 1U}; + + // helper function to get inertially interpolated rangefinder height. bool get_rangefinder_height_interpolated_cm(int32_t& ret) const; +#if AP_RANGEFINDER_ENABLED class SurfaceTracking { public: @@ -274,9 +266,9 @@ class Copter : public AP_Vehicle { // measured ground or ceiling level measured using the range finder. void update_surface_offset(); - // get/set target altitude (in cm) above ground - bool get_target_alt_cm(float &target_alt_cm) const; - void set_target_alt_cm(float target_alt_cm); + // target has already been set by terrain following so do not initalise again + // this should be called by flight modes when switching from terrain following to surface tracking (e.g. ZigZag) + void external_init(); // get target and actual distances (in m) for logging purposes bool get_target_dist_for_logging(float &target_dist) const; @@ -301,6 +293,7 @@ class Copter : public AP_Vehicle { bool valid_for_logging; // true if we have a desired target altitude bool reset_target; // true if target should be reset because of change in surface being tracked } surface_tracking; +#endif #if AP_RPM_ENABLED AP_RPM rpm_sensor; @@ -354,50 +347,51 @@ class Copter : public AP_Vehicle { # include USERHOOK_VARIABLES #endif - // Documentation of GLobals: - typedef union { - struct { - uint8_t unused1 : 1; // 0 - uint8_t unused_was_simple_mode : 2; // 1,2 - uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully - uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed - uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised - uint8_t logging_started : 1; // 6 // true if logging has started - uint8_t land_complete : 1; // 7 // true if we have detected a landing - uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio - uint8_t usb_connected_unused : 1; // 9 // UNUSED - uint8_t rc_receiver_present_unused : 1; // 10 // UNUSED - uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration - uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test - uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes - uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete) - uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock - uint8_t system_time_set_unused : 1; // 16 // true if the system time has been set from the GPS - uint8_t gps_glitching : 1; // 17 // true if GPS glitching is affecting navigation accuracy - uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use - uint8_t land_repo_active : 1; // 21 // true if the pilot is overriding the landing position - uint8_t motor_interlock_switch : 1; // 22 // true if pilot is requesting motor interlock enable - uint8_t in_arming_delay : 1; // 23 // true while we are armed but waiting to spin motors - uint8_t initialised_params : 1; // 24 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done - uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set - uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed - uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch - uint8_t prec_land_active : 1; // 28 // true if precland is active - }; - uint32_t value; - } ap_t; - - ap_t ap; + // ap_value calculates a 32-bit bitmask representing various pieces of + // state about the Copter. It replaces a global variable which was + // used to track this state. + uint32_t ap_value() const; + + // These variables are essentially global variables. These should + // be removed over time. It is critical that the offsets of these + // variables remain unchanged - the logging is dependent on this + // ordering! + struct PACKED { + bool unused1; // 0 + bool unused_was_simple_mode_byte1; // 1 + bool unused_was_simple_mode_byte2; // 2 + bool pre_arm_rc_check; // 3 true if rc input pre-arm checks have been completed successfully + bool pre_arm_check; // 4 true if all pre-arm checks (rc, accel calibration, gps lock) have been performed + bool auto_armed; // 5 stops auto missions from beginning until throttle is raised + bool unused_log_started; // 6 + bool land_complete; // 7 true if we have detected a landing + bool new_radio_frame; // 8 Set true if we have new PWM data to act on from the Radio + bool unused_usb_connected; // 9 + bool unused_receiver_present; // 10 + bool compass_mot; // 11 true if we are currently performing compassmot calibration + bool motor_test; // 12 true if we are currently performing the motors test + bool initialised; // 13 true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes + bool land_complete_maybe; // 14 true if we may have landed (less strict version of land_complete) + bool throttle_zero; // 15 true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock + bool system_time_set_unused; // 16 true if the system time has been set from the GPS + bool gps_glitching; // 17 true if GPS glitching is affecting navigation accuracy + bool using_interlock; // 18 aux switch motor interlock function is in use + bool land_repo_active; // 19 true if the pilot is overriding the landing position + bool motor_interlock_switch; // 20 true if pilot is requesting motor interlock enable + bool in_arming_delay; // 21 true while we are armed but waiting to spin motors + bool initialised_params; // 22 true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done + bool unused_compass_init_location; // 23 + bool unused2_aux_switch_rc_override_allowed; // 24 + bool armed_with_airmode_switch; // 25 we armed using a arming switch + bool prec_land_active; // 26 true if precland is active + } ap; AirMode air_mode; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled; bool force_flying; // force flying is enabled when true; - static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t"); - // This is the state of the flight control system // There are multiple states defined such as STABILIZE, ACRO, Mode *flightmode; - Mode::Number prev_control_mode; RCMapper rcmap; @@ -486,11 +480,11 @@ class Copter : public AP_Vehicle { AC_WPNav *wp_nav; AC_Loiter *loiter_nav; -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED AC_CustomControl custom_control{ahrs_view, attitude_control, motors, scheduler.get_loop_period_s()}; #endif -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED AC_Circle *circle_nav; #endif @@ -528,7 +522,7 @@ class Copter : public AP_Vehicle { #endif // Parachute release -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED AP_Parachute parachute; #endif @@ -631,11 +625,16 @@ class Copter : public AP_Vehicle { }; - enum class FlightOptions { + enum class FlightOption : uint32_t { DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1 DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2 RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4 + REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8 }; + // returns true if option is enabled for this vehicle + bool option_is_enabled(FlightOption option) const { + return (g2.flight_options & uint32_t(option)) != 0; + } static constexpr int8_t _failsafe_priorities[] = { (int8_t)FailsafeAction::TERMINATE, @@ -666,23 +665,34 @@ class Copter : public AP_Vehicle { void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; -#if AP_SCRIPTING_ENABLED -#if MODE_GUIDED_ENABLED == ENABLED - bool start_takeoff(float alt) override; +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if MODE_GUIDED_ENABLED bool set_target_location(const Location& target_loc) override; + bool start_takeoff(const float alt) override; +#endif // MODE_GUIDED_ENABLED +#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED + +#if AP_SCRIPTING_ENABLED +#if MODE_GUIDED_ENABLED + bool get_target_location(Location& target_loc) override; + bool update_target_location(const Location &old_loc, const Location &new_loc) override; bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override; bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override; bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override; bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw) override; 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 set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) override; + + // Register a custom mode with given number and names + AP_Vehicle::custom_mode_state* register_custom_mode(const uint8_t number, const char* full_name, const char* short_name) override; #endif -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED bool get_circle_radius(float &radius_m) override; bool set_circle_rate(float rate_dps) override; #endif bool set_desired_speed(float speed) override; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED bool nav_scripting_enable(uint8_t mode) override; bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override; void nav_script_time_done(uint16_t id) override; @@ -720,7 +730,7 @@ class Copter : public AP_Vehicle { uint16_t get_pilot_speed_dn() const; void run_rate_controller(); -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED void run_custom_controller() { custom_control.update(); } #endif @@ -796,7 +806,7 @@ class Copter : public AP_Vehicle { // failsafe.cpp void failsafe_enable(); void failsafe_disable(); -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED void afs_fs_check(void); #endif @@ -825,6 +835,29 @@ class Copter : public AP_Vehicle { void set_land_complete(bool b); void set_land_complete_maybe(bool b); void update_throttle_mix(); + bool get_force_flying() const; +#if HAL_LOGGING_ENABLED + enum class LandDetectorLoggingFlag : uint16_t { + LANDED = 1U << 0, + LANDED_MAYBE = 1U << 1, + LANDING = 1U << 2, + STANDBY_ACTIVE = 1U << 3, + WOW = 1U << 4, + RANGEFINDER_BELOW_2M = 1U << 5, + DESCENT_RATE_LOW = 1U << 6, + ACCEL_STATIONARY = 1U << 7, + LARGE_ANGLE_ERROR = 1U << 8, + LARGE_ANGLE_REQUEST = 1U << 8, + MOTOR_AT_LOWER_LIMIT = 1U << 9, + THROTTLE_MIX_AT_MIN = 1U << 10, + }; + struct { + uint32_t last_logged_ms; + uint32_t last_logged_count; + uint16_t last_logged_flags; + } land_detector; + void Log_LDET(uint16_t logging_flags, uint32_t land_detector_count); +#endif #if AP_LANDINGGEAR_ENABLED // landing_gear.cpp @@ -854,9 +887,6 @@ class Copter : public AP_Vehicle { 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_Video_Stabilisation(); -#if FRAME_CONFIG == HELI_FRAME - void Log_Write_Heli(void); -#endif void Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target); void 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 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); @@ -970,7 +1000,7 @@ class Copter : public AP_Vehicle { void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag); void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag); -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED #if FRAME_CONFIG == HELI_FRAME ModeAcro_Heli mode_acro; #else @@ -978,38 +1008,42 @@ class Copter : public AP_Vehicle { #endif #endif ModeAltHold mode_althold; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED ModeAuto mode_auto; #endif -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED ModeAutoTune mode_autotune; #endif -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED ModeBrake mode_brake; #endif -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED ModeCircle mode_circle; #endif -#if MODE_DRIFT_ENABLED == ENABLED +#if MODE_DRIFT_ENABLED ModeDrift mode_drift; #endif -#if MODE_FLIP_ENABLED == ENABLED +#if MODE_FLIP_ENABLED ModeFlip mode_flip; #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED ModeFollow mode_follow; #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED ModeGuided mode_guided; +#if AP_SCRIPTING_ENABLED + // Custom modes registered at runtime + ModeGuidedCustom *mode_guided_custom[5]; +#endif #endif ModeLand mode_land; -#if MODE_LOITER_ENABLED == ENABLED +#if MODE_LOITER_ENABLED ModeLoiter mode_loiter; #endif -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED ModePosHold mode_poshold; #endif -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED ModeRTL mode_rtl; #endif #if FRAME_CONFIG == HELI_FRAME @@ -1017,34 +1051,34 @@ class Copter : public AP_Vehicle { #else ModeStabilize mode_stabilize; #endif -#if MODE_SPORT_ENABLED == ENABLED +#if MODE_SPORT_ENABLED ModeSport mode_sport; #endif -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED ModeSystemId mode_systemid; #endif #if HAL_ADSB_ENABLED ModeAvoidADSB mode_avoid_adsb; #endif -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED ModeThrow mode_throw; #endif -#if MODE_GUIDED_NOGPS_ENABLED == ENABLED +#if MODE_GUIDED_NOGPS_ENABLED ModeGuidedNoGPS mode_guided_nogps; #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED ModeSmartRTL mode_smartrtl; #endif -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if MODE_FLOWHOLD_ENABLED ModeFlowHold mode_flowhold; #endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED ModeZigZag mode_zigzag; #endif -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED ModeAutorotate mode_autorotate; #endif -#if MODE_TURTLE_ENABLED == ENABLED +#if MODE_TURTLE_ENABLED ModeTurtle mode_turtle; #endif diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 2a5f776b5edd15..e5ac383df2bb47 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -42,39 +42,22 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION; - // update flightmode-specific flags: - control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; - control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; - - switch (copter.flightmode->mode_number()) { - case Mode::Number::AUTO: - case Mode::Number::AUTO_RTL: - case Mode::Number::AVOID_ADSB: - case Mode::Number::GUIDED: - case Mode::Number::LOITER: - case Mode::Number::RTL: - case Mode::Number::CIRCLE: - case Mode::Number::LAND: - case Mode::Number::POSHOLD: - case Mode::Number::BRAKE: - case Mode::Number::THROW: - case Mode::Number::SMART_RTL: - control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; - control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; - control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; - control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; - break; - case Mode::Number::ALT_HOLD: - case Mode::Number::GUIDED_NOGPS: - case Mode::Number::SPORT: - case Mode::Number::AUTOTUNE: - case Mode::Number::FLOWHOLD: - control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; - control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; - break; - default: - // stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual) - break; + // Update position controller flags + if (copter.pos_control != nullptr) { + control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; + control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; + + // XY position controller + if (copter.pos_control->is_active_xy()) { + control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; + control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; + } + + // Z altitude controller + if (copter.pos_control->is_active_z()) { + control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; + control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; + } } // optional sensors, some of which are essentially always @@ -91,7 +74,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) } #endif -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED const RangeFinder *rangefinder = RangeFinder::get_singleton(); if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; diff --git a/ArduCopter/GCS_Copter.h b/ArduCopter/GCS_Copter.h index 4e419add63084b..423857fd6f3dc7 100644 --- a/ArduCopter/GCS_Copter.h +++ b/ArduCopter/GCS_Copter.h @@ -43,7 +43,7 @@ class GCS_Copter : public GCS GCS_MAVLINK_Copter *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Copter(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Copter(params, uart); } }; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 402415038836b9..1b5833ec75824d 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -37,25 +37,11 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const // only get useful information from the custom_mode, which maps to // the APM flight mode and has a well defined meaning in the // ArduPlane documentation - switch (copter.flightmode->mode_number()) { - case Mode::Number::AUTO: - case Mode::Number::AUTO_RTL: - case Mode::Number::RTL: - case Mode::Number::LOITER: - case Mode::Number::AVOID_ADSB: - case Mode::Number::FOLLOW: - case Mode::Number::GUIDED: - case Mode::Number::CIRCLE: - case Mode::Number::POSHOLD: - case Mode::Number::BRAKE: - case Mode::Number::SMART_RTL: + if ((copter.pos_control != nullptr) && copter.pos_control->is_active_xy()) { _base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; // note that MAV_MODE_FLAG_AUTO_ENABLED does not match what // APM does in any mode, as that is defined as "system finds its own goal // positions", which APM does not currently do - break; - default: - break; } // all modes except INITIALISING have some form of manual @@ -89,6 +75,10 @@ MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const return MAV_STATE_STANDBY; } + if (!copter.ap.initialised) { + return MAV_STATE_BOOT; + } + return MAV_STATE_ACTIVE; } @@ -151,7 +141,7 @@ void GCS_MAVLINK_Copter::send_position_target_global_int() void GCS_MAVLINK_Copter::send_position_target_local_ned() { -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED if (!copter.flightmode->in_guided_mode()) { return; } @@ -346,12 +336,16 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) { switch(id) { - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE + case MSG_TERRAIN_REQUEST: CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); copter.terrain.send_request(chan); -#endif break; + case MSG_TERRAIN_REPORT: + CHECK_PAYLOAD_SIZE(TERRAIN_REPORT); + copter.terrain.send_report(chan); + break; +#endif case MSG_WIND: CHECK_PAYLOAD_SIZE(WIND); @@ -392,7 +386,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3 + // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -461,7 +455,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate - // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS + // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS // @Units: Hz // @Range: 0 50 @@ -499,6 +493,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -508,10 +505,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, // MISSION_CURRENT +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif MSG_NAV_CONTROLLER_OUTPUT, @@ -527,7 +530,9 @@ static const ap_message STREAM_POSITION_msgs[] = { static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_SERVO_OUTPUT_RAW, MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -549,7 +554,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_DISTANCE_SENSOR, #if AP_TERRAIN_AVAILABLE - MSG_TERRAIN, + MSG_TERRAIN_REQUEST, + MSG_TERRAIN_REPORT, #endif #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, @@ -583,7 +589,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; static const ap_message STREAM_ADSB_msgs[] = { MSG_ADSB_VEHICLE, @@ -615,7 +622,7 @@ MISSION_STATE GCS_MAVLINK_Copter::mission_state(const class AP_Mission &mission) bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd) { -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED return copter.mode_auto.do_guided(cmd); #else return false; @@ -632,7 +639,7 @@ void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status, copter.avoidance_adsb.handle_msg(msg); } #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED // pass message to follow library copter.g2.follow.handle_msg(msg); #endif @@ -713,7 +720,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet) { -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE; if (!copter.flightmode->in_guided_mode() && !change_modes) { return MAV_RESULT_DENIED; @@ -765,7 +772,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i case MAV_CMD_DO_CHANGE_SPEED: return handle_MAV_CMD_DO_CHANGE_SPEED(packet); -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED case MAV_CMD_DO_FOLLOW: // param1: sysid of target to follow if ((packet.param1 > 0) && (packet.param1 <= 255)) { @@ -789,7 +796,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i case MAV_CMD_NAV_VTOL_TAKEOFF: return handle_MAV_CMD_NAV_TAKEOFF(packet); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case MAV_CMD_DO_PARACHUTE: return handle_MAV_CMD_DO_PARACHUTE(packet); #endif @@ -806,7 +813,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet); #endif -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED case MAV_CMD_MISSION_START: return handle_MAV_CMD_MISSION_START(packet); #endif @@ -835,7 +842,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i } return MAV_RESULT_ACCEPTED; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED + case MAV_CMD_DO_RETURN_PATH_START: + if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; + case MAV_CMD_DO_LAND_START: if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; @@ -854,9 +867,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_int_t switch (packet.command) { 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() != AP_Mount::Type::None) && + if (((MAV_MOUNT_MODE)packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING) && + (copter.camera_mount.get_mount_type() != AP_Mount::Type::None) && !copter.camera_mount.has_pan_control()) { - copter.flightmode->auto_yaw.set_yaw_angle_rate((float)packet.param3, 0.0f); + // Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is + // equivalent to an offset to the current yaw demand. + copter.flightmode->auto_yaw.set_yaw_angle_offset(packet.param3); } break; default: @@ -945,9 +961,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_comm return MAV_RESULT_FAILED; } -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet) { + if (!is_zero(packet.param1) || !is_zero(packet.param2)) { + // first-item/last item not supported + return MAV_RESULT_DENIED; + } if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) { copter.set_auto_armed(true); if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) { @@ -961,7 +981,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_comman -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) { // configure or release parachute @@ -1074,7 +1094,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink bool shot_mode = (!is_zero(packet.param1) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS)); if (!shot_mode) { -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED if (copter.set_mode(Mode::Number::BRAKE, ModeReason::GCS_COMMAND)) { copter.mode_brake.timeout_to_loiter_ms(2500); } else { @@ -1121,11 +1141,12 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg) 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() != AP_Mount::Type::None) && + (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_MAVLINK_TARGETING) && !copter.camera_mount.has_pan_control()) { - copter.flightmode->auto_yaw.set_yaw_angle_rate( - mavlink_msg_mount_control_get_input_c(&msg) * 0.01f, - 0.0f); - + // Per the handler in AP_Mount, MOUNT_CONTROL yaw angle is in body frame, which is + // equivalent to an offset to the current yaw demand. + const float yaw_offset_d = mavlink_msg_mount_control_get_input_c(&msg) * 0.01f; + copter.flightmode->auto_yaw.set_yaw_angle_offset(yaw_offset_d); break; } } @@ -1162,7 +1183,7 @@ bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const return true; } -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED // for mavlink SET_POSITION_TARGET messages constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE = POSITION_TARGET_TYPEMASK_X_IGNORE | @@ -1187,7 +1208,7 @@ bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const POSITION_TARGET_TYPEMASK_FORCE_SET; #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_message_t &msg) { // decode packet @@ -1207,6 +1228,7 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag // ensure thrust field is not ignored if (throttle_ignore) { + // The throttle input is not defined return; } @@ -1225,6 +1247,18 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag } } + Vector3f ang_vel_body; + if (!roll_rate_ignore && !pitch_rate_ignore && !yaw_rate_ignore) { + ang_vel_body.x = packet.body_roll_rate; + ang_vel_body.y = packet.body_pitch_rate; + ang_vel_body.z = packet.body_yaw_rate; + } else if (!(roll_rate_ignore && pitch_rate_ignore && yaw_rate_ignore)) { + // The body rates are ill-defined + // input is not valid so stop + copter.mode_guided.init(true); + return; + } + // check if the message's thrust field should be interpreted as a climb rate or as thrust const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust(); @@ -1246,18 +1280,7 @@ void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_messag } } - Vector3f ang_vel; - if (!roll_rate_ignore) { - ang_vel.x = packet.body_roll_rate; - } - if (!pitch_rate_ignore) { - ang_vel.y = packet.body_pitch_rate; - } - if (!yaw_rate_ignore) { - ang_vel.z = packet.body_yaw_rate; - } - - copter.mode_guided.set_angle(attitude_quat, ang_vel, + copter.mode_guided.set_angle(attitude_quat, ang_vel_body, climb_rate_or_thrust, use_thrust); } @@ -1468,13 +1491,13 @@ void GCS_MAVLINK_Copter::handle_message_set_position_target_global_int(const mav copter.mode_guided.init(true); } } -#endif // MODE_GUIDED_ENABLED == ENABLED +#endif // MODE_GUIDED_ENABLED void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg) { switch (msg.msgid) { -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: handle_message_set_attitude_target(msg); break; @@ -1491,7 +1514,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg) copter.terrain.handle_data(chan, msg); break; #endif -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED case MAVLINK_MSG_ID_NAMED_VALUE_INT: copter.g2.toy_mode.handle_message(msg); break; @@ -1503,7 +1526,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg) } MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) { -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) { return MAV_RESULT_ACCEPTED; } @@ -1641,3 +1664,148 @@ uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const return 0; } #endif // HAL_HIGH_LATENCY2_ENABLED + +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const +{ + const Mode* modes[] { +#if MODE_AUTO_ENABLED + &copter.mode_auto, // This auto is actually auto RTL! + &copter.mode_auto, // This one is really is auto! +#endif +#if MODE_ACRO_ENABLED + &copter.mode_acro, +#endif + &copter.mode_stabilize, + &copter.mode_althold, +#if MODE_CIRCLE_ENABLED + &copter.mode_circle, +#endif +#if MODE_LOITER_ENABLED + &copter.mode_loiter, +#endif +#if MODE_GUIDED_ENABLED + &copter.mode_guided, +#endif + &copter.mode_land, +#if MODE_RTL_ENABLED + &copter.mode_rtl, +#endif +#if MODE_DRIFT_ENABLED + &copter.mode_drift, +#endif +#if MODE_SPORT_ENABLED + &copter.mode_sport, +#endif +#if MODE_FLIP_ENABLED + &copter.mode_flip, +#endif +#if AUTOTUNE_ENABLED + &copter.mode_autotune, +#endif +#if MODE_POSHOLD_ENABLED + &copter.mode_poshold, +#endif +#if MODE_BRAKE_ENABLED + &copter.mode_brake, +#endif +#if MODE_THROW_ENABLED + &copter.mode_throw, +#endif +#if HAL_ADSB_ENABLED + &copter.mode_avoid_adsb, +#endif +#if MODE_GUIDED_NOGPS_ENABLED + &copter.mode_guided_nogps, +#endif +#if MODE_SMARTRTL_ENABLED + &copter.mode_smartrtl, +#endif +#if MODE_FLOWHOLD_ENABLED + (Mode*)copter.g2.mode_flowhold_ptr, +#endif +#if MODE_FOLLOW_ENABLED + &copter.mode_follow, +#endif +#if MODE_ZIGZAG_ENABLED + &copter.mode_zigzag, +#endif +#if MODE_SYSTEMID_ENABLED + (Mode *)copter.g2.mode_systemid_ptr, +#endif +#if MODE_AUTOROTATE_ENABLED + &copter.mode_autorotate, +#endif +#if MODE_TURTLE_ENABLED + &copter.mode_turtle, +#endif + }; + + const uint8_t base_mode_count = ARRAY_SIZE(modes); + uint8_t mode_count = base_mode_count; + +#if AP_SCRIPTING_ENABLED + for (uint8_t i = 0; i < ARRAY_SIZE(copter.mode_guided_custom); i++) { + if (copter.mode_guided_custom[i] != nullptr) { + mode_count += 1; + } + } +#endif + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name; + uint8_t mode_number; + + if (index_zero < base_mode_count) { + name = modes[index_zero]->name(); + mode_number = (uint8_t)modes[index_zero]->mode_number(); + + } else { +#if AP_SCRIPTING_ENABLED + const uint8_t custom_index = index_zero - base_mode_count; + if (copter.mode_guided_custom[custom_index] == nullptr) { + // Invalid index, should not happen + return mode_count; + } + name = copter.mode_guided_custom[custom_index]->name(); + mode_number = (uint8_t)copter.mode_guided_custom[custom_index]->mode_number(); +#else + // Should not endup here + return mode_count; +#endif + } + +#if MODE_AUTO_ENABLED + // Auto RTL is odd + // Have to deal with is separately becase its number and name can change depending on if were in it or not + if (index_zero == 0) { + mode_number = (uint8_t)Mode::Number::AUTO_RTL; + name = "AUTO RTL"; + + } else if (index_zero == 1) { + mode_number = (uint8_t)Mode::Number::AUTO; + name = "AUTO"; + + } +#endif + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index e38c9b6e7aa024..558804c05e8c36 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -64,6 +64,10 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK uint32_t log_radio_bit() const override { return MASK_LOG_PM; } #endif + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: // sanity check velocity or acceleration vector components are numbers diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index d1d530ca1355e4..fffea298f10fd8 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -39,11 +39,15 @@ void Copter::Log_Write_Control_Tuning() target_climb_rate_cms = pos_control->get_vel_target_z_cms(); } - // get surface tracking alts float desired_rangefinder_alt; +#if AP_RANGEFINDER_ENABLED if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt)) { desired_rangefinder_alt = AP::logger().quiet_nan(); } +#else + // get surface tracking alts + desired_rangefinder_alt = AP::logger().quiet_nan(); +#endif struct log_Control_Tuning pkt = { LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG), @@ -56,7 +60,11 @@ void Copter::Log_Write_Control_Tuning() inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f, baro_alt : baro_alt, desired_rangefinder_alt : desired_rangefinder_alt, +#if AP_RANGEFINDER_ENABLED rangefinder_alt : surface_tracking.get_dist_for_logging(), +#else + rangefinder_alt : AP::logger().quiet_nanf(), +#endif terr_alt : terr_alt, target_climb_rate : target_climb_rate_cms, climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()) // float -> int16_t @@ -67,11 +75,9 @@ void Copter::Log_Write_Control_Tuning() // Write an attitude packet void Copter::Log_Write_Attitude() { - Vector3f targets = attitude_control->get_att_target_euler_cd(); - targets.z = wrap_360_cd(targets.z); - ahrs.Write_Attitude(targets); - ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); - } + attitude_control->Write_ANG(); + attitude_control->Write_Rate(*pos_control); +} // Write PIDS packets void Copter::Log_Write_PIDS() @@ -250,7 +256,7 @@ struct PACKED log_SysIdD { // Write an rate packet void Copter::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) { -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED struct log_SysIdD pkt_sidd = { LOG_PACKET_HEADER_INIT(LOG_SYSIDD_MSG), time_us : AP_HAL::micros64(), @@ -284,7 +290,7 @@ struct PACKED log_SysIdS { // Write an rate packet 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) { -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED struct log_SysIdS pkt_sids = { LOG_PACKET_HEADER_INIT(LOG_SYSIDS_MSG), time_us : AP_HAL::micros64(), @@ -301,31 +307,6 @@ void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitu #endif } -#if FRAME_CONFIG == HELI_FRAME -struct PACKED log_Heli { - LOG_PACKET_HEADER; - uint64_t time_us; - float desired_rotor_speed; - float main_rotor_speed; - float governor_output; - float control_output; -}; - -// Write an helicopter packet -void Copter::Log_Write_Heli() -{ - struct log_Heli pkt_heli = { - LOG_PACKET_HEADER_INIT(LOG_HELI_MSG), - time_us : AP_HAL::micros64(), - desired_rotor_speed : motors->get_desired_rotor_speed(), - main_rotor_speed : motors->get_main_rotor_speed(), - governor_output : motors->get_governor_output(), - control_output : motors->get_control_output(), - }; - logger.WriteBlock(&pkt_heli, sizeof(pkt_heli)); -} -#endif - // guided position target logging struct PACKED log_Guided_Position_Target { LOG_PACKET_HEADER; @@ -481,18 +462,6 @@ const struct LogStructure Copter::log_structure[] = { "DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" }, { LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float), "DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" }, - -// @LoggerMessage: HELI -// @Description: Helicopter related messages -// @Field: TimeUS: Time since system startup -// @Field: DRRPM: Desired rotor speed -// @Field: ERRPM: Estimated rotor speed -// @Field: Gov: Governor Output -// @Field: Throt: Throttle output -#if FRAME_CONFIG == HELI_FRAME - { LOG_HELI_MSG, sizeof(log_Heli), - "HELI", "Qffff", "TimeUS,DRRPM,ERRPM,Gov,Throt", "s----", "F----" , true }, -#endif // @LoggerMessage: SIDD // @Description: System ID data diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index f16ef8725dcc7a..fd5eea3e8626f7 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -73,7 +73,6 @@ const AP_Param::Info Copter::var_info[] = { // @DisplayName: Throttle stick behavior // @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick. // @User: Standard - // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0), @@ -92,11 +91,10 @@ const AP_Param::Info Copter::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:Roll,2:Pitch,4:Yaw,8:AccelZ // @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED // @Param: RTL_ALT // @DisplayName: RTL Altitude // @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude. @@ -251,7 +249,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: FLTMODE1 // @DisplayName: Flight Mode 1 // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) 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,27:Auto RTL + // @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,27:Auto RTL,28:Turtle // @User: Standard GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1), @@ -356,7 +354,7 @@ const AP_Param::Info Copter::var_info[] = { // @User: Advanced ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX), -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED // @Param: PHLD_BRAKE_RATE // @DisplayName: PosHold braking rate // @Description: PosHold flight mode's rotation rate during braking in deg/sec @@ -412,7 +410,7 @@ const AP_Param::Info Copter::var_info[] = { // @User: Advanced GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED), -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED // @Param: ACRO_BAL_ROLL // @DisplayName: Acro Balance Roll // @Description: rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude. @@ -432,7 +430,7 @@ const AP_Param::Info Copter::var_info[] = { // ACRO_RP_EXPO moved to Command Model class -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED // @Param: ACRO_TRAINER // @DisplayName: Acro Trainer // @Description: Type of trainer used in acro mode @@ -455,7 +453,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(relay, "RELAY", AP_Relay), #endif -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // @Group: CHUTE_ // @Path: ../libraries/AP_Parachute/AP_Parachute.cpp GOBJECT(parachute, "CHUTE_", AP_Parachute), @@ -489,7 +487,7 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter), -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED // @Group: CIRCLE_ // @Path: ../libraries/AC_WPNav/AC_Circle.cpp GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle), @@ -630,17 +628,19 @@ const AP_Param::Info Copter::var_info[] = { GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), #endif -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED // @Group: MIS_ // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission), #endif +#if AP_RSSI_ENABLED // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), - -#if RANGEFINDER_ENABLED == ENABLED +#endif + +#if AP_RANGEFINDER_ENABLED // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), @@ -684,7 +684,7 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/AP_Notify/AP_Notify.cpp GOBJECT(notify, "NTF_", AP_Notify), -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED // @Param: THROW_MOT_START // @DisplayName: Start motors before throwing is detected // @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw. @@ -713,7 +713,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(osd, "OSD", AP_OSD), #endif -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED // @Group: CC // @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp GOBJECT(custom_control, "CC", AC_CustomControl), @@ -748,7 +748,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPPTR(button_ptr, "BTN_", 2, ParametersG2, AP_Button), #endif -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED // @Param: THROW_NEXTMODE // @DisplayName: Throw mode's follow up mode // @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18) @@ -771,7 +771,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1), -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED // @Group: AFS_ // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe), @@ -798,7 +798,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // ACRO_Y_EXPO (9) moved to Command Model Class -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED // @Param: ACRO_THR_MID // @DisplayName: Acro Thr Mid // @Description: Acro Throttle Mid @@ -842,13 +842,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration), #endif -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED // @Group: TMODE // @Path: toy_mode.cpp AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode), #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED // @Group: SRTL_ // @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL), @@ -880,23 +880,23 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000), -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if MODE_FLOWHOLD_ENABLED // @Group: FHLD // @Path: mode_flowhold.cpp AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold), #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED // @Group: FOLL // @Path: ../libraries/AP_Follow/AP_Follow.cpp AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow), #endif -#if USER_PARAMS_ENABLED == ENABLED +#if USER_PARAMS_ENABLED AP_SUBGROUPINFO(user_parameters, "USR", 28, ParametersG2, UserParameters), #endif -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED // @Group: AUTOTUNE_ // @Path: ../libraries/AC_AutoTune/AC_AutoTune_Multi.cpp,../libraries/AC_AutoTune/AC_AutoTune_Heli.cpp AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune), @@ -922,7 +922,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(oa, "OA_", 33, ParametersG2, AP_OAPathPlanner), #endif -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED // @Group: SID // @Path: mode_systemid.cpp AP_SUBGROUPPTR(mode_systemid_ptr, "SID", 34, ParametersG2, ModeSystemId), @@ -938,24 +938,23 @@ 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 // @User: Advanced AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Copter::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL), -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED // @Group: AROT_ // @Path: ../libraries/AC_Autorotation/AC_Autorotation.cpp AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation), #endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED // @Group: ZIGZ_ // @Path: mode_zigzag.cpp AP_SUBGROUPPTR(mode_zigzag_ptr, "ZIGZ_", 38, ParametersG2, ModeZigZag), #endif -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED // @Param: ACRO_OPTIONS // @DisplayName: Acro mode options // @Description: A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only. @@ -964,7 +963,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("ACRO_OPTIONS", 39, ParametersG2, acro_options, 0), #endif -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED // @Param: AUTO_OPTIONS // @DisplayName: Auto mode options // @Description: A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto. @@ -973,7 +972,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0), #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED // @Param: GUID_OPTIONS // @DisplayName: Guided mode options // @Description: Options that can be applied to change guided mode behaviour @@ -991,7 +990,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5), -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED // @Param: RTL_OPTIONS // @DisplayName: RTL mode options // @Description: Options that can be applied to change RTL mode behaviour @@ -1003,11 +1002,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FLIGHT_OPTIONS // @DisplayName: Flight mode options // @Description: Flight mode specific options - // @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss + // @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming // @User: Advanced AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0), -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED // @Param: RNGFND_FILT // @DisplayName: Rangefinder filter // @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering @@ -1019,7 +1018,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("RNGFND_FILT", 45, ParametersG2, rangefinder_filt, RANGEFINDER_FILT_DEFAULT), #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED // @Param: GUID_TIMEOUT // @DisplayName: Guided mode timeout // @Description: Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control @@ -1031,6 +1030,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class +#if AP_RANGEFINDER_ENABLED // @Param: SURFTRAK_MODE // @DisplayName: Surface Tracking Mode // @Description: set which surface to track in surface tracking @@ -1038,6 +1038,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced // @RebootRequired: True AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND), +#endif // @Param: FS_DR_ENABLE // @DisplayName: DeadReckon Failsafe Action @@ -1053,7 +1054,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("FS_DR_TIMEOUT", 53, ParametersG2, failsafe_dr_timeout, 30), -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED // @Param: ACRO_RP_RATE // @DisplayName: Acro Roll and Pitch Rate // @Description: Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation @@ -1079,7 +1080,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(command_model_acro_rp, "ACRO_RP_", 54, ParametersG2, AC_CommandModel), #endif -#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED // @Param: ACRO_Y_RATE // @DisplayName: Acro Yaw Rate // @Description: Acro mode maximum yaw rate. Higher value means faster rate of rotation @@ -1146,7 +1147,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0), #endif -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED // @Group: WVANE_ // @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp AP_SUBGROUPINFO(weathervane, "WVANE_", 59, ParametersG2, AC_WeatherVane), @@ -1239,8 +1240,11 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = { /* constructor for g2 object */ -ParametersG2::ParametersG2(void) - : command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f) +ParametersG2::ParametersG2(void) : + unused_integer{17} +#if HAL_BUTTON_ENABLED + ,button_ptr(&copter.button) +#endif #if AP_TEMPCALIBRATION_ENABLED , temp_calibration() #endif @@ -1250,46 +1254,44 @@ ParametersG2::ParametersG2(void) #if HAL_PROXIMITY_ENABLED , proximity() #endif -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED ,afs() #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED ,smart_rtl() #endif -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if USER_PARAMS_ENABLED + ,user_parameters() +#endif +#if MODE_FLOWHOLD_ENABLED ,mode_flowhold_ptr(&copter.mode_flowhold) #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED ,follow() #endif -#if USER_PARAMS_ENABLED == ENABLED - ,user_parameters() -#endif -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED ,autotune_ptr(&copter.mode_autotune.autotune) #endif -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED ,mode_systemid_ptr(&copter.mode_systemid) #endif -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED ,arot() #endif -#if HAL_BUTTON_ENABLED - ,button_ptr(&copter.button) -#endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED ,mode_zigzag_ptr(&copter.mode_zigzag) #endif - -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_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 +#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED ,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f) #endif -#if WEATHERVANE_ENABLED == ENABLED + ,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f) + +#if WEATHERVANE_ENABLED ,weathervane() #endif { @@ -1344,7 +1346,7 @@ void Copter::load_parameters(void) convert_lgr_parameters(); #endif -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED // PARAMETER_CONVERSION - Added: Sep-2021 g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16); #endif diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 0e3d8920aabe80..0cf0a8cb519595 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -6,10 +6,10 @@ #include "RC_Channel.h" #include -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED # include #endif -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED #include #endif @@ -398,7 +398,7 @@ class Parameters { AP_Int16 throttle_behavior; AP_Float pilot_takeoff_alt; -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED AP_Int32 rtl_altitude; AP_Int16 rtl_speed_cms; AP_Float rtl_cone_slope; @@ -415,7 +415,7 @@ class Parameters { AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees #endif @@ -459,7 +459,7 @@ class Parameters { AP_Float fs_ekf_thresh; AP_Int16 gcs_pid_mask; -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED AP_Enum throw_motor_start; AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected @@ -467,13 +467,13 @@ class Parameters { AP_Int16 rc_speed; // speed of fast RC Channels in Hz -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED // Acro parameters AP_Float acro_balance_roll; AP_Float acro_balance_pitch; #endif -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED // Acro parameters AP_Int8 acro_trainer; #endif @@ -499,12 +499,17 @@ class ParametersG2 { // altitude at which nav control can start in takeoff AP_Float wp_navalt_min; + // unused_integer simply exists so that the constructor for + // ParametersG2 can be created with a relatively easy syntax in + // the face of many #ifs: + uint8_t unused_integer; + // button checking #if HAL_BUTTON_ENABLED AP_Button *button_ptr; #endif -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED // Throw mode parameters AP_Int8 throw_nextmode; AP_Enum throw_type; @@ -530,8 +535,8 @@ class ParametersG2 { // whether to enforce acceptance of packets only from sysid_my_gcs AP_Int8 sysid_enforce; - -#if ADVANCED_FAILSAFE == ENABLED + +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED // advanced failsafe library AP_AdvancedFailsafe_Copter afs; #endif @@ -539,7 +544,7 @@ class ParametersG2 { // developer options AP_Int32 dev_options; -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED AP_Float acro_thr_mid; #endif @@ -552,7 +557,7 @@ class ParametersG2 { // control over servo output ranges SRV_Channels servo_channels; -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED // Safe RTL library AP_SmartRTL smart_rtl; #endif @@ -568,7 +573,7 @@ class ParametersG2 { // Land alt final stage AP_Int16 land_alt_low; -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED ToyMode toy_mode; #endif @@ -577,17 +582,17 @@ class ParametersG2 { void *mode_flowhold_ptr; #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED // follow AP_Follow follow; #endif -#if USER_PARAMS_ENABLED == ENABLED +#if USER_PARAMS_ENABLED // User custom parameters UserParameters user_parameters; #endif -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED // we need a pointer to autotune for the G2 table void *autotune_ptr; #endif @@ -600,7 +605,7 @@ class ParametersG2 { AP_OAPathPlanner oa; #endif -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED // we need a pointer to the mode for the G2 table void *mode_systemid_ptr; #endif @@ -611,52 +616,52 @@ class ParametersG2 { // Failsafe options bitmask #36 AP_Int32 fs_options; -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED // Autonmous autorotation AC_Autorotation arot; #endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED // we need a pointer to the mode for the G2 table void *mode_zigzag_ptr; #endif // command model parameters -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED AC_CommandModel command_model_acro_rp; #endif -#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED AC_CommandModel command_model_acro_y; #endif AC_CommandModel command_model_pilot; -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED AP_Int8 acro_options; #endif -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED AP_Int32 auto_options; #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED AP_Int32 guided_options; #endif AP_Float fs_gcs_timeout; -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED AP_Int32 rtl_options; #endif AP_Int32 flight_options; -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED AP_Float rangefinder_filt; #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED AP_Float guided_timeout; #endif @@ -676,7 +681,7 @@ class ParametersG2 { // EKF variance filter cutoff AP_Float fs_ekf_filt_hz; -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED AC_WeatherVane weathervane; #endif diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index f39366721f4851..fdb175f80c5b8e 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -76,7 +76,8 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi // the following functions do not need to be initialised: case AUX_FUNC::ALTHOLD: case AUX_FUNC::AUTO: - case AUX_FUNC::AUTOTUNE: + case AUX_FUNC::AUTOTUNE_MODE: + case AUX_FUNC::AUTOTUNE_TEST_GAINS: case AUX_FUNC::BRAKE: case AUX_FUNC::CIRCLE: case AUX_FUNC::DRIFT: @@ -86,7 +87,9 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::GUIDED: case AUX_FUNC::LAND: case AUX_FUNC::LOITER: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif case AUX_FUNC::POSHOLD: case AUX_FUNC::RESETTOARMEDYAW: case AUX_FUNC::RTL: @@ -98,7 +101,9 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::USER_FUNC1: case AUX_FUNC::USER_FUNC2: case AUX_FUNC::USER_FUNC3: +#if AP_WINCH_ENABLED case AUX_FUNC::WINCH_CONTROL: +#endif case AUX_FUNC::ZIGZAG: case AUX_FUNC::ZIGZAG_Auto: case AUX_FUNC::ZIGZAG_SaveWP: @@ -115,19 +120,26 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::ATTCON_FEEDFWD: case AUX_FUNC::INVERTED: case AUX_FUNC::MOTOR_INTERLOCK: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release case AUX_FUNC::PARACHUTE_ENABLE: +#endif case AUX_FUNC::PRECISION_LOITER: +#if AP_RANGEFINDER_ENABLED case AUX_FUNC::RANGEFINDER: +#endif case AUX_FUNC::SIMPLE_MODE: case AUX_FUNC::STANDBY: case AUX_FUNC::SUPERSIMPLE_MODE: case AUX_FUNC::SURFACE_TRACKING: +#if AP_WINCH_ENABLED case AUX_FUNC::WINCH_ENABLE: +#endif case AUX_FUNC::AIRMODE: case AUX_FUNC::FORCEFLYING: case AUX_FUNC::CUSTOM_CONTROLLER: case AUX_FUNC::WEATHER_VANE_ENABLE: + case AUX_FUNC::TRANSMITTER_TUNING: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: @@ -144,7 +156,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode, switch(ch_flag) { case AuxSwitchPos::HIGH: { // engage mode (if not possible we remain in current flight mode) - copter.set_mode(mode, ModeReason::RC_COMMAND); + copter.set_mode(mode, ModeReason::AUX_FUNCTION); break; } default: @@ -163,7 +175,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc case AUX_FUNC::FLIP: // flip if switch is on, positive throttle and we're actually flying if (ch_flag == AuxSwitchPos::HIGH) { - copter.set_mode(Mode::Number::FLIP, ModeReason::RC_COMMAND); + copter.set_mode(Mode::Number::FLIP, ModeReason::AUX_FUNCTION); } break; @@ -188,7 +200,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED case AUX_FUNC::RTL: do_aux_function_change_mode(Mode::Number::RTL, ch_flag); break; @@ -202,7 +214,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc } break; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED case AUX_FUNC::SAVE_WP: // save waypoint when switch is brought high if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) { @@ -258,7 +270,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED case AUX_FUNC::RANGEFINDER: // enable or disable the rangefinder if ((ch_flag == AuxSwitchPos::HIGH) && @@ -268,9 +280,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc copter.rangefinder_state.enabled = false; } break; -#endif +#endif // AP_RANGEFINDER_ENABLED -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED case AUX_FUNC::ACRO_TRAINER: switch(ch_flag) { case AuxSwitchPos::LOW: @@ -289,10 +301,13 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if AUTOTUNE_ENABLED == ENABLED - case AUX_FUNC::AUTOTUNE: +#if AUTOTUNE_ENABLED + case AUX_FUNC::AUTOTUNE_MODE: do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag); break; + case AUX_FUNC::AUTOTUNE_TEST_GAINS: + copter.mode_autotune.autotune.do_aux_function(ch_flag); + break; #endif case AUX_FUNC::LAND: @@ -311,7 +326,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag); break; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_ENABLE: // Parachute enable/disable copter.parachute.enabled(ch_flag == AuxSwitchPos::HIGH); @@ -338,7 +353,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } break; -#endif +#endif // HAL_PARACHUTE_ENABLED case AUX_FUNC::ATTCON_FEEDFWD: // enable or disable feed forward @@ -378,19 +393,19 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED case AUX_FUNC::BRAKE: do_aux_function_change_mode(Mode::Number::BRAKE, ch_flag); break; #endif -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED case AUX_FUNC::THROW: do_aux_function_change_mode(Mode::Number::THROW, ch_flag); break; #endif -#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED == ENABLED +#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED case AUX_FUNC::PRECISION_LOITER: switch (ch_flag) { case AuxSwitchPos::HIGH: @@ -406,7 +421,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED case AUX_FUNC::SMART_RTL: do_aux_function_change_mode(Mode::Number::SMART_RTL, ch_flag); break; @@ -446,11 +461,11 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } break; -#endif case AUX_FUNC::WINCH_CONTROL: // do nothing, used to control the rate of the winch and is processed within AP_Winch break; +#endif // AP_WINCH_ENABLED #ifdef USERHOOK_AUXSWITCH case AUX_FUNC::USER_FUNC1: @@ -466,7 +481,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED case AUX_FUNC::ZIGZAG: do_aux_function_change_mode(Mode::Number::ZIGZAG, ch_flag); break; @@ -494,7 +509,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc do_aux_function_change_mode(Mode::Number::STABILIZE, ch_flag); break; -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED case AUX_FUNC::POSHOLD: do_aux_function_change_mode(Mode::Number::POSHOLD, ch_flag); break; @@ -504,7 +519,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc do_aux_function_change_mode(Mode::Number::ALT_HOLD, ch_flag); break; -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED case AUX_FUNC::ACRO: do_aux_function_change_mode(Mode::Number::ACRO, ch_flag); break; @@ -516,13 +531,13 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; #endif -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED case AUX_FUNC::CIRCLE: do_aux_function_change_mode(Mode::Number::CIRCLE, ch_flag); break; #endif -#if MODE_DRIFT_ENABLED == ENABLED +#if MODE_DRIFT_ENABLED case AUX_FUNC::DRIFT: do_aux_function_change_mode(Mode::Number::DRIFT, ch_flag); break; @@ -544,6 +559,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } +#if AP_RANGEFINDER_ENABLED case AUX_FUNC::SURFACE_TRACKING: switch (ch_flag) { case AuxSwitchPos::LOW: @@ -557,6 +573,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } break; +#endif case AUX_FUNC::FLIGHTMODE_PAUSE: switch (ch_flag) { @@ -573,7 +590,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc } break; -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED case AUX_FUNC::ZIGZAG_Auto: if (copter.flightmode == &copter.mode_zigzag) { switch (ch_flag) { @@ -590,7 +607,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc case AUX_FUNC::AIRMODE: do_aux_function_change_air_mode(ch_flag); -#if MODE_ACRO_ENABLED == ENABLED && FRAME_CONFIG != HELI_FRAME +#if MODE_ACRO_ENABLED && FRAME_CONFIG != HELI_FRAME copter.mode_acro.air_mode_aux_changed(); #endif break; @@ -599,13 +616,13 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc do_aux_function_change_force_flying(ch_flag); break; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED case AUX_FUNC::AUTO_RTL: do_aux_function_change_mode(Mode::Number::AUTO_RTL, ch_flag); break; #endif -#if MODE_TURTLE_ENABLED == ENABLED +#if MODE_TURTLE_ENABLED case AUX_FUNC::TURTLE: do_aux_function_change_mode(Mode::Number::TURTLE, ch_flag); break; @@ -625,13 +642,13 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc } break; -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED case AUX_FUNC::CUSTOM_CONTROLLER: copter.custom_control.set_custom_controller(ch_flag == AuxSwitchPos::HIGH); break; #endif -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED case AUX_FUNC::WEATHER_VANE_ENABLE: { switch (ch_flag) { case AuxSwitchPos::HIGH: @@ -646,6 +663,9 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc break; } #endif + case AUX_FUNC::TRANSMITTER_TUNING: + // do nothing, used in tuning.cpp for transmitter based tuning + break; default: return RC_Channel::do_aux_function(ch_option, ch_flag); diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index faf5e4df70a756..26bda5c232ac03 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,633 @@ ArduPilot Copter Release Notes: -------------------------------- +------------------------------------------------------------------ +Release 4.6.0-beta 13 Nov 2024 + +Changes from 4.5.7 + +1) Board specific changes + +- AnyLeaf H7 supports compass and onboard logging +- Blitz743Pro supports CAN +- BlueRobotics Navigator supports BMP390 baro +- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed) +- CB Unmanned Stamp H743 support +- ClearSky CSKY405 support +- CUAV-7-Nano default batt monitor fixed +- CubeRed bootloader fixes including disabling 2nd core by default +- CubeRed supports PPP networking between primary and secondary MCU +- CubeRedPrimary supports external compasses +- ESP32 main loop rate improvements +- ESP32 RC input fixes and wifi connection reliability improved +- ESP32 safety switch and GPIO pin support +- FlyingMoon no longer support MAX7456 +- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot +- Flywoo H743 Pro support +- Flywoo/Goku F405 HD 1-2S ELRS AIO v2 +- FlywooF745 supports DPS310 baro +- FPV boards lose SMBus battery support (to save flash) +- GEPRC F745BTHD support +- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash) +- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates +- Holybro Kakute F4 Wing support +- iFlight 2RAW H743 supports onboard logging +- JFB110 supports measuring servo rail voltage +- JFB110 supports safety switch LED +- JHEM-JHEF405 bootloader supports firmware updates via serial +- JHEMCU GF30H743 HD support +- JHEMCU-GF16-F405 autopilot support +- JHEMCU-GSF405A becomes FPV board (to save flash) +- KakuteF7 only supports BMP280 baro (to save flash) +- KakuteH7Mini supports ICM42688 IMU +- Linux auto detection of GPS baud rate fixed +- Linux board scheduler jitter reduced +- Linux board shutdown fixes +- MakeFlyEasy PixPilot-V6Pro support +- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash) +- MatekH7A3 support Bi-directional DShot +- MicoAir405v2 and MicoAir405Mini support optical flow and OSD +- MicoAir743 internal compass orientation fixed +- MicroAir405Mini, MicroAir743, NxtPX4v2 support +- MicroAir405v2 Bi-directional DShot and LED DMA fixes +- MicroAir405v2 defined as FPV board with reduced features (to save flash) +- ModalAI VOXL2 support including Starling 2 and Starling 2 max +- mRo Control Zero Classic supports servo rail analog input +- mRo KitCAN revC fixed +- Mugin MUPilot support +- OmnibusF7v2 loses quadplane support (to save flash) +- Pixhack-v3 board added (same as fmuv3) +- Pixhawk6C bootloader supports flashing firmware from SD card +- RadiolinkPIX6 imu orientation fixed +- RadiolinkPIX6 supports SPA06 baro +- ReaperF745 V4 FC supports MPU6000 IMU +- RPI5 support +- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed +- Solo serial ports default to MAVLink1 +- SpeedyBeeF405Wing gets Bi-directional DShot +- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash) +- Spektreworks boom board support +- TrueNavPro-G4 SPI does not share DMA +- X-MAV AP-H743v2 support + +2) AHRS/EKF enhancements and fixes + +- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back) +- AHRS_OPTION to disable innovation check for airspeed sensor +- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity +- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only) +- EK2 supports disabling external nav (see EK2_OPTIONS) +- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1) +- EK3 uses filtered velocity corrections for IMU position +- EKF2, EKF3, ExternalAHRS all use common origin +- EKF3 accepts set origin even when using GPS +- EKF3 allows earth-frame fields to be estimated with an origin but no GPS +- EKF3 copes better with GPS jamming +- EKF3 logs mag fusion selection to XKFS +- EKF3 wind estimation when using GPS-for-yaw fixed +- External AHRS improvements including handling variances, pre-arm origin check +- Inertial Labs External AHRS fixes +- VectorNav driver fix for handling of error from sensor +- VectorNav External AHRS enhancements including validation of config commands and logging improvements +- VectorNav support for sensors outside VN-100 and VN-300 + +3) Driver enhancements and bug fixes + +- ADSB fix to display last character in status text sent to GCS +- Ainstein LR-D1 radar support +- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor +- AIRSPEED message sent to GCS +- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5) +- ARSPD_OPTIONS to report calibration offset to GCS +- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only) +- Baro provides improved atmospheric model for high altitude flight +- BARO_ALT_OFFSET slew slowed to keep EKF happy +- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries +- BATTx_OPTION to not send battery voltage, current, etc to GCS +- Benewake RDS02U radar support +- Bi-directional DShot on IOMCU supports reversible mask +- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs +- BMM350 compass support +- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus) +- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS) +- CRSF baro and vertical speeed fixed +- CRSF RX bind command support +- DroneCAN battery monitor check to avoid memory corruption when type changed +- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info +- DroneCAN EFI health check fix +- DroneCAN ESC battery monitors calculate consumed mah +- DroneCAN ESCs forced to zero when disarmed +- DroneCAN RPM message support +- DroneCAN timeout fix for auxiliary frames +- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600') +- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass +- FuelLevel battery monitor fix to report capacity +- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx +- Hirth EFI logging includes modified throttle +- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter) +- Hott and LTM telemetry deprecated (still available through custom build server) +- i-BUS telemetry support +- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only) +- ICE_START_CHAN replaced with RC aux function (Plane only) +- ICEngine retry max added (see ICE_STRT_MX_RTRY) +- IE 2400 generator error message severity to GCS improved +- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params) +- MCP9600 temperature sensor I2C address fixed +- MLX90614 temperature sensor support +- MSP GPS ground course scaling fixed +- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect) +- Networking supports reconnection to TCP server or client +- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT) +- Relay inverted output support (see RELAYx_INVERTED parameter) +- ROMFS efficiency improvements +- RS-485 driver enable RTS flow control +- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt) +- Septentrio GPS sat count correctly drops to zero when 255 received +- Septentrio supports selecting constellations (see GPS_GNSS_MODE) +- Single LED for user notification supported +- SPA06 baro supported +- Sum battery monitor optionally reports minimum voltage instead of average +- Sum battery monitor reports average temp +- Torqeedo dual motor support (see TRQ1, TRQ2 params) +- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes) +- UBlox GPS time ignored until at least 2D fix +- VideoTX supports additional freq bands (RushFPV 3.3Ghz) +- Volz logs desired and actual position, voltage, current, motor and PCB temp +- Volz server feedback and logging fixed +- Volz servo output in its own thread resulting in smoother movements +- W25N02KV flash support + +4) Networking enhancements and fixes + +- Allow multiple UDP clients to connect/disconnect/reconnect +- Ethernet supports faster log downloading (raised SDMMC clock limit on H7) + +5) Camera and gimbal enhancements + +- Alexmos precision improved slightly +- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC) +- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at +- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame) +- Dual serial camera gimbal mounts fixed +- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS +- Retract Mount2 aux function added (see RCx_OPTION = 113) +- Servo gimbal reported angles respect roll, pitch and yaw limits +- Siyi driver sends autopilot location and speed (recorded in images via EXIF) +- Siyi picture and video download scripts +- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg) +- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script +- Siyi ZT6 hardware id and set-lens fixed +- Topotek gimbal support +- Trigger distance ignores GPS status and only uses EKF reported location + +6) Harmonic notch enhancements + +- Harmonic notch is active in forward flight on quadplanes +- Harmonic notch filter freq clamping and disabling reworked +- Harmonic notch handles negative ESC RPMs +- Harmonic notch supports per-motor throttle-based harmonic notch + +7) Copter specific enhancements and bug fixes + +- Attitude control fix to dt update order (reduces rate controller noise) +- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time +- Auto mode small target position jump when takeoff completes removed +- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None +- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178) +- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command +- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only) +- AutoTune fix to prevent spool up after landing +- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well) +- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180) +- Config error avoided if auto mode is paused very soon after poweron +- FLIGHT_OPTIONS bit added to require position estimate before arming +- Follow mode slowdown calcs fixed when target is moving +- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT) +- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message +- Guided mode internal error resolved when switching between thrust or climb rate based altitude control +- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle +- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down +- Landing detector logging added to ease support (see LDET message) +- Loiter unlimited command accepts NaNs (QGC sends these) +- Mavlink SYSTEM_STATUS set to BOOT during initialisation +- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values +- Payload place bug fix when aborted because gripper is already released +- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219) +- RTL_ALT minimum reduced to 30cm +- SystemID position controller support (Copter and Heli) +- TriCopter motor test and slew-up fixed +- WPNAV_SPEED min reduced to 10 cm/s (Copter only) +- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe + +8) TradHeli specific enhancements + +- Autorotation yaw behaviour fix +- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate +- Blade pitch angle logging added (see SWSH log message) +- Constrain cyclic roll for intermeshing +- ICE / turbine cool down fix +- Inverted flight extended to non manual throttle modes +- Inverted flight transitions smoothed and restricted to only Stabilize mode +- SWSH logging fix for reversed collectives + +9) Plane specific enhancements and bug fixes + +- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling +- Allow for different orientations of landing rangefinder +- Assistance requirements evaluted on mode change +- FBWB/CRUISE climb/sink rate limited by TECS limits +- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope) +- Glider pullup support (available only through custom build server) +- Loiter breakout improved to better handle destinations inside loiter circle +- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled) +- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes +- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition) +- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic +- Quadplane assistance check enhancements +- Quadplane Deca frame support +- Quadplane gets smoother takeoff by input shaping target accel and velocity +- Servo wiggles in altitude wait staged to be one after another +- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames +- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN) +- Takeoff fixes for fence autoenable +- Takeoff improvements including less overshoot of TKOFF_ALT +- TECS reset along with other controllers (important if plane dropped from balloon) +- Tilt quadplane ramp of motors on back transition fixed +- Tiltrotor tilt angles logged +- TKOFF_THR_MIN applied to SLT transitions +- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration +- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff + +10) Rover specific enhancements and bug fixes + +- Auto mode reversed state maintained if momentarily switched to Hold mode +- Circle mode tracks better and avoids getting stuck at circle edge +- Flight time stats fixed +- MAV_CMD_NAV_SET_YAW_SPEED deprecated +- Omni3Mecanum frame support +- Stopping point uses max deceleration (was incorrectly using acceleration) +- Wheel rate controller slew rate fix + +11) Antenna Tracker specific enhancements and bug fixes + +- Never track lat,lon of 0,0 + +12) Scripting enhancements + +- advance-wp.lua applet supports advancing Auto mode WP via RC switch +- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch +- battery_internal_resistance_check.lua monitors battery resistance +- CAN:get_device returns nil for unconfigured CAN device +- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only) +- Copter:get_target_location, update_target_location support +- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only) +- Display text on OLED display supported +- Docs improved for many bindings +- EFI get_last_update_ms binding +- EFI_SkyPower.lua driver accepts 2nd supply voltage +- ESC_slew_rate.lua example script supports testing ESCs +- Filesystem CRC32 check to allow scripts to check module versions +- forced arming support +- GPIO get/set mode bindings (see gpio:set_mode, get_mode) +- GPS-for-yaw angle binding (see gps:gps_yaw_deg) +- Halo6000 EFI driver can log all CAN packets for easier debugging +- handle_external_position_estimate binding allows sending position estimate from lua to EKF +- I2C:transfer support +- IMU gyros_consistent and accels_consistent bindings added +- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control +- INS bindings for is calibrating, gyro and accel sensor values +- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients +- Logging of booleans supported +- Lua language checks improved (finds more errors) +- MAVLink commands can be called from scripting +- MCU voltage binding (see analog:mcu_voltage) +- NMEA 2000 EFI driver (see EFI_NMEA2k.lua) +- "open directory failed" false warning when scripts in ROMFS fixed +- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch +- Pass by reference values are always initialized +- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras +- plane_aerobatics.lua minor enhancements +- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation +- "require" function failures in rare circumstances fixed +- "require" function works for modules in ROMFS (e.g. not on SD card) +- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_) +- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand) +- SD card formatting supported +- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation) +- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter) +- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch +- Slung payload oscillation suppression applet added (see copter-slung-payload.lua) +- Temperature sensor bindings added +- uint64 support +- Various performance and memory usage optimizations +- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8 +- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame + +13) GCS / mavlink related changes and fixes + +- BATTERY2 message deprecated (replaced by BATTERY_STATUS) +- CMD_MISSION_START/STOP rejected if first-item/last-item args provided +- Deny attempts to upload two missions simultaneously +- Fence and Rally points may be uploaded using FTP +- GPS_INPUT and HIL_GPS handles multiple GPSs +- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC) +- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196 +- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support +- MAV_CMD_SET_HAGL support (Plane only) +- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links +- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message) +- Message interval supports TERRAIN_REPORT msg +- Mission upload may be cancelled using MISSION_CLEAR_ALL +- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated +- RC_CHANNELS_RAW deprecated +- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers +- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only) +- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports + +14) Logging enhancements and fixes + +- AC_PID resets and I-term sets logged +- ANG provides attitude at high rate (equivalent to ATT) +- ATT logs angles as floats (better resolution than ints) +- CAND message gets driver index +- DCM log message includes roll/pitch and yaw error +- EDT2 log msg includes stress and status received via extended DShot Telemetry v2 +- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin) +- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct +- FMT messages written as required instead of all at beginning +- Logging restarted after download completes when LOG_DISARMED = 1 +- MISE msg logs active mission command (CMD logged when commands are uploaded) +- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN +- RPM sensor logging gets instance field, quality and health fields +- Short filename support removed (e.g log1.BIN instead of 00000001.BIN) +- Temperature sensor logging option for only sensors with no source (see TEMP_LOG) +- UART data rates logged at 1hz (see UART message) + +15) ROS2 / DDS support + +- Airspeed published +- Battery topic reports all available batteries +- Compile-time configurable rates for each publisher +- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent +- GPS global origin published at 1 Hz +- High frequency raw imu data transmission +- Joystick support +- Support sending waypoints to Copter and Rover +- Remove the XML refs file in favor of binary entity creation + +16) Safety related enhancements and fixes + +- Accel/Gyro inconsistent message fixed for using with only single IMU +- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action +- Far from EKF origin pre-arm check removed (Copter only) +- Fence breach warning message slightly improved +- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS) +- Fences can be stored to SD Card (see BRD_SD_FENCE param) +- ICEngine stopped when in E-Stop or safety engaged (Plane only) +- LEDs flash green lights based on EKF location not GPS +- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS) +- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added +- Pre-arm check if OpenDroneID is compiled in but disabled +- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions) +- Pre-arm checks alert user more quickly on failure +- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE +- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover) +- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on +- Warning of duplicate SERIALx_PROTOCOL = RCIN + +17) Other bug fixes and minor enhancements + +- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher) +- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools +- Bootloader rejects allocation of broadcast node ID +- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI) +- Dijkstras fix to correct use of uninitialised variable +- DShot rates are not limited by NeoPixel rates +- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode +- Filesystem does not show entries for empty @ files +- Filesystem efficiency improvements when reading files +- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset) +- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm) +- Internal error thrown if we lose parameters due to saving queue being too small +- MAVLink via DroneCAN baud rate fix +- SPI pins may also be used as GPIOs +- Terrain cache size configurable (see TERRAIN_CACHE_SZ) + +18) Developer focused fixes and enhancements + +- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams +- Cygwin build fix for non-SITL builds +- Cygwin build fixed with malloc wrap +- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua) +- EKF3 code generator documentation and cleanup +- GPS jamming simulator added +- MacOS compiler warnings reduced +- SFML joystick support +- SITL support for OpenBSD +- Text warning if older Fence or Rally point protocols are used +------------------------------------------------------------------ +Release 4.5.7 08 Oct 2024 + +Changes from 4.5.7-beta1 + +1) Reverted Septentrio GPS sat count correctly drops to zero when 255 received +------------------------------------------------------------------ +Release 4.5.7-beta1 26 Sep 2024 + +Changes from 4.5.6 + +1) Bug fixes and minor enhancements + +- VUAV-V7pro support +- CUAV-7-Nano correction for LEDs and battery volt and current scaling +- DroneCAN deadlock and saturation of CAN bus fixed +- DroneCAN DNA server init fix (caused logging issues and spam on bus) +- F4 boards with inverter support correctly uninvert RX/TX +- Nanoradar M72 radar driver fix for object avoidance path planning +- RC support for latest version of GHST +- Septentrio GPS sat count correctly drops to zero when 255 received +- TradHeli DDVP tail rotor pitch actuator fixed + +2) ROS2/DDS and other developer focused enhancements + +- AP quaternions normalised for ROS2 to avoid warnings +- Dependencies fixed for easier installation +- ROS2 SITL launch file enhancements including displaying console and map +- ROS_DOMAIN_ID param added to support multiple vehicles or instances of ROS2 +- Python 3.12 support +------------------------------------------------------------------ +Release 4.5.6 03 Sep 2024 + +No changes from 4.5.6-beta1 +------------------------------------------------------------------ +Release 4.5.6-beta1 20 Aug 2024 + +Changes from 4.5.5 + +1) Board specific enhancements and bug fixes + +- 3DR Control Zero H7 Rev G support +- CUAV-7-Nano support +- FoxeerF405v2 servo outputs increased from 9 to 11 +- Holybro Pixhawk6C hi-power peripheral overcurrent reporting fixed +- iFlight 2RAW H7 support +- MFT-SEMA100 support +- TMotorH743 support BMI270 baro +- ZeroOneX6 support + +2) Minor enhancements and bug fixes + +- Cameras using MAVLink report vendor and model name correctly +- DroneCAN fix to remove occasional NodeID registration error +- GPS NMEA and GSoF driver ground course corrected (now always 0 ~ 360 deg) +- ICP101XX barometer slowed to avoid I2C communication errors +- IMU temp cal param (INSn_ACCSCAL_Z) stored correctly when bootloader is flashed +- IMU gyro/accel duplicate id registration fixed to avoid possible pre-arm failure +- Logging to flash timestamp fix +- OSD displays ESC temp instead of motor temp +- PID controller error calculation bug fix (was using target from prev iteration) +- Relay on MAIN pins fixed + +3) Copter specific fixes + +- Payload place bug fix (calimb rate after releasing payload was unreliable) + +------------------------------------------------------------------ +Release 4.5.5 1st Aug 2024 + +No changes from 4.5.5-beta2 +------------------------------------------------------------------ +Release 4.5.5-beta2 27 July 2024 + +Changes from 4.5.5-beta1 + +1) Board specific enhancements and bug fixes + +- CubeRed's second core disabled at boot to avoid spurious writes to RAM +- CubeRed bootloader's dual endpoint update method fixed +------------------------------------------------------------------ +Release 4.5.5-beta1 1st July 2024 + +Changes from 4.5.4 + +1) Board specific enhancements and bug fixes + +- fixed IOMCU transmission errors when using bdshot +- update relay parameter names on various boards +- add ASP5033 airspeed in minimal builds +- added RadiolinkPIX6 +- fix Aocoda-RC H743Dual motor issue +- use ICM45686 as an ICM20649 alternative in CubeRedPrimary + +2) System level minor enhancements and bug fixes + +- correct use-after-free in script statistics +- added arming check for eeprom full +- fixed a block logging issue which caused log messages to be dropped +- enable Socket SO_REUSEADDR on LwIP +- removed IST8310 overrun message +- added Siyi ZT6 support +- added BTFL sidebar symbols to the OSD +- added CRSF extended link stats to the OSD +- use the ESC with the highest RPM in the OSD when only one can be displayed +- support all Tramp power levels on high power VTXs +- emit jump count in missions even if no limit +- improve the bitmask indicating persistent parameters on bootloader flash +- fix duplicate error condition in the MicroStrain7 + +3) AHRS / EKF fixes + +- fix infinite climb bug when using EK3_OGN_HGT_MASK + +4) Copter specific changes + +- fix MAV_CMD_CONDITION_YAW with relative angle + +5) Other minor enhancements and bug fixes + +- specify pymonocypher version in more places +- added DroneCAN dependencies to custom builds + +------------------------------------------------------------------ +Release 4.5.4 12th June 2024 + +Changes from 4.5.3 + +Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X + +------------------------------------------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Copter specific changes + +- fixed speed constraint during avoidance backoff + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Copter specific changes + +- Auto mode condition yaw fix to avoid pointing at out-of-date target +- Guided mode angle control yaw target initialisation fix (was always turning North) + +5) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + +------------------------------------------------------------------ Release 4.5.1 8th April 2024 @@ -101,7 +729,7 @@ Changes from 4.5.0-beta1: - broaden acceptance criteria for GPS yaw measurement for moving baseline yaw ------------------------------------------------------------------ -Copter 4.5.0-beta1 30-Jan-2025 +Copter 4.5.0-beta1 30-Jan-2024 Changes from 4.4.4 1) New autopilots supported - ACNS-F405AIO @@ -785,7 +1413,7 @@ Changes from 4.3.6 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 +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 ------------------------------------------------------------------ diff --git a/ArduCopter/UserParameters.cpp b/ArduCopter/UserParameters.cpp index 61f1b7122b53e2..2950597eee6430 100644 --- a/ArduCopter/UserParameters.cpp +++ b/ArduCopter/UserParameters.cpp @@ -1,7 +1,7 @@ #include "UserParameters.h" #include "config.h" -#if USER_PARAMS_ENABLED == ENABLED +#if USER_PARAMS_ENABLED // "USR" + 13 chars remaining for param name const AP_Param::GroupInfo UserParameters::var_info[] = { diff --git a/ArduCopter/afs_copter.cpp b/ArduCopter/afs_copter.cpp index 3bad987a343d3e..0d639e1276b129 100644 --- a/ArduCopter/afs_copter.cpp +++ b/ArduCopter/afs_copter.cpp @@ -4,7 +4,7 @@ #include "Copter.h" -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED /* setup radio_out values for all channels to termination values @@ -55,17 +55,7 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void) */ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void) { - switch (copter.flightmode->mode_number()) { - case Mode::Number::AUTO: - case Mode::Number::AUTO_RTL: - case Mode::Number::GUIDED: - case Mode::Number::RTL: - case Mode::Number::LAND: - return AP_AdvancedFailsafe::AFS_AUTO; - default: - break; - } - return AP_AdvancedFailsafe::AFS_STABILIZED; + return copter.flightmode->afs_mode(); } //to force entering auto mode when datalink loss @@ -73,4 +63,4 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void) { copter.set_mode(Mode::Number::AUTO,ModeReason::GCS_FAILSAFE); } -#endif // ADVANCED_FAILSAFE +#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED diff --git a/ArduCopter/afs_copter.h b/ArduCopter/afs_copter.h index b7c8bc8b21c854..4d133f6276a3d5 100644 --- a/ArduCopter/afs_copter.h +++ b/ArduCopter/afs_copter.h @@ -18,7 +18,9 @@ advanced failsafe support for copter */ -#if ADVANCED_FAILSAFE == ENABLED +#include "config.h" + +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED #include /* @@ -44,5 +46,5 @@ class AP_AdvancedFailsafe_Copter : public AP_AdvancedFailsafe void set_mode_auto(void) override; }; -#endif // ADVANCED_FAILSAFE +#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index f7042b4406cf84..9ce780a9a002f2 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -111,6 +111,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di // calculate final angle as relative to vehicle heading or absolute if (relative_angle) { + if (_mode == Mode::HOLD) { + _yaw_angle_cd = copter.ahrs.yaw_sensor; + } _fixed_yaw_offset_cd = angle_deg * 100.0 * (direction >= 0 ? 1.0 : -1.0); } else { // absolute angle @@ -146,6 +149,18 @@ void Mode::AutoYaw::set_yaw_angle_rate(float yaw_angle_d, float yaw_rate_ds) set_mode(Mode::ANGLE_RATE); } +// set_yaw_angle_offset - sets the yaw look at heading for auto mode, as an offset from the current yaw angle +void Mode::AutoYaw::set_yaw_angle_offset(const float yaw_angle_offset_d) +{ + _last_update_ms = millis(); + + _yaw_angle_cd = wrap_360_cd(_yaw_angle_cd + (yaw_angle_offset_d * 100.0)); + _yaw_rate_cds = 0.0f; + + // set yaw mode + set_mode(Mode::ANGLE_RATE); +} + // set_roi - sets the yaw to look at roi for auto mode void Mode::AutoYaw::set_roi(const Location &roi_location) { @@ -311,7 +326,7 @@ AC_AttitudeControl::HeadingCommand Mode::AutoYaw::get_heading() _pilot_yaw_rate_cds = 0.0; if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) { // get pilot's desired yaw rate - _pilot_yaw_rate_cds = copter.flightmode->get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz()); + _pilot_yaw_rate_cds = copter.flightmode->get_pilot_desired_yaw_rate(); if (!is_zero(_pilot_yaw_rate_cds)) { auto_yaw.set_mode(AutoYaw::Mode::PILOT_RATE); } @@ -320,7 +335,7 @@ AC_AttitudeControl::HeadingCommand Mode::AutoYaw::get_heading() auto_yaw.set_mode(AutoYaw::Mode::HOLD); } -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED update_weathervane(_pilot_yaw_rate_cds); #endif @@ -351,7 +366,7 @@ AC_AttitudeControl::HeadingCommand Mode::AutoYaw::get_heading() // handle the interface to the weathervane library // pilot_yaw can be an angle or a rate or rcin from yaw channel. It just needs to represent a pilot's request to yaw the vehicle to enable pilot overrides. -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED void Mode::AutoYaw::update_weathervane(const int16_t pilot_yaw_cds) { if (!copter.flightmode->allows_weathervaning()) { @@ -379,4 +394,4 @@ void Mode::AutoYaw::update_weathervane(const int16_t pilot_yaw_cds) } } } -#endif // WEATHERVANE_ENABLED == ENABLED +#endif // WEATHERVANE_ENABLED diff --git a/ArduCopter/avoidance_adsb.cpp b/ArduCopter/avoidance_adsb.cpp index bd541c355117af..5a1c306b8424e2 100644 --- a/ArduCopter/avoidance_adsb.cpp +++ b/ArduCopter/avoidance_adsb.cpp @@ -25,7 +25,7 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O // take no action in some flight modes if (copter.flightmode->mode_number() == Mode::Number::LAND || -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED copter.flightmode->mode_number() == Mode::Number::THROW || #endif copter.flightmode->mode_number() == Mode::Number::FLIP) { @@ -148,7 +148,7 @@ void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(Mode::Number mode) int32_t AP_Avoidance_Copter::get_altitude_minimum() const { -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED // do not descend if below RTL alt return copter.g.rtl_altitude; #else diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index fea41d19e55636..ec4cfd67c62087 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -30,7 +30,7 @@ void Copter::set_home_to_current_location_inflight() { return; } // we have successfully set AHRS home, set it for SmartRTL -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED g2.smart_rtl.set_home(true); #endif } @@ -45,7 +45,7 @@ bool Copter::set_home_to_current_location(bool lock) { return false; } // we have successfully set AHRS home, set it for SmartRTL -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED g2.smart_rtl.set_home(true); #endif return true; diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 532cbb243a1811..28282c35399f16 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -146,9 +146,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) read_radio(); // pass through throttle to motors - SRV_Channels::cork(); + auto &srv = AP::srv(); + srv.cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); - SRV_Channels::push(); + srv.push(); // read some compass values compass.read(); @@ -228,6 +229,12 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) #if HAL_WITH_ESC_TELEM // send ESC telemetry to monitor ESC and motor temperatures AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan()); +#endif +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + // a lot of autotest timeouts are based on receiving system time + gcs_chan.send_system_time(); + // autotesting of compassmot wants to see RC channels message + gcs_chan.send_rc_channels(); #endif } } diff --git a/ArduCopter/config.h b/ArduCopter/config.h index bd139ff23a58e4..0da560ea09099a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -70,18 +70,6 @@ // Rangefinder // -#ifndef RANGEFINDER_ENABLED - # define RANGEFINDER_ENABLED ENABLED -#endif - -#ifndef RANGEFINDER_HEALTH_MAX - # define RANGEFINDER_HEALTH_MAX 3 // number of good reads that indicates a healthy rangefinder -#endif - -#ifndef RANGEFINDER_TIMEOUT_MS -# define RANGEFINDER_TIMEOUT_MS 1000 // rangefinder filter reset if no updates from sensor in 1 second -#endif - #ifndef RANGEFINDER_FILT_DEFAULT # define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance #endif @@ -90,18 +78,6 @@ # define SURFACE_TRACKING_TIMEOUT_MS 1000 // surface tracking target alt will reset to current rangefinder alt after this many milliseconds without a good rangefinder alt #endif -#ifndef RANGEFINDER_TILT_CORRECTION // by disable tilt correction for use of range finder data by EKF - # define RANGEFINDER_TILT_CORRECTION ENABLED -#endif - -#ifndef RANGEFINDER_GLITCH_ALT_CM - # define RANGEFINDER_GLITCH_ALT_CM 200 // amount of rangefinder change to be considered a glitch -#endif - -#ifndef RANGEFINDER_GLITCH_NUM_SAMPLES - # define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading -#endif - #ifndef MAV_SYSTEM_ID # define MAV_SYSTEM_ID 1 #endif @@ -141,107 +117,101 @@ ////////////////////////////////////////////////////////////////////////////// // Auto Tuning #ifndef AUTOTUNE_ENABLED - # define AUTOTUNE_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE - # define PARACHUTE HAL_PARACHUTE_ENABLED + # define AUTOTUNE_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Nav-Guided - allows external nav computer to control vehicle #ifndef AC_NAV_GUIDED - # define AC_NAV_GUIDED ENABLED + # define AC_NAV_GUIDED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Acro - fly vehicle in acrobatic mode #ifndef MODE_ACRO_ENABLED -# define MODE_ACRO_ENABLED ENABLED +# define MODE_ACRO_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Auto mode - allows vehicle to trace waypoints and perform automated actions #ifndef MODE_AUTO_ENABLED -# define MODE_AUTO_ENABLED ENABLED +# define MODE_AUTO_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Brake mode - bring vehicle to stop #ifndef MODE_BRAKE_ENABLED -# define MODE_BRAKE_ENABLED ENABLED +# define MODE_BRAKE_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Circle - fly vehicle around a central point #ifndef MODE_CIRCLE_ENABLED -# define MODE_CIRCLE_ENABLED ENABLED +# define MODE_CIRCLE_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Drift - fly vehicle in altitude-held, coordinated-turn mode #ifndef MODE_DRIFT_ENABLED -# define MODE_DRIFT_ENABLED ENABLED +# define MODE_DRIFT_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // flip - fly vehicle in flip in pitch and roll direction mode #ifndef MODE_FLIP_ENABLED -# define MODE_FLIP_ENABLED ENABLED +# define MODE_FLIP_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Follow - follow another vehicle or GCS #ifndef MODE_FOLLOW_ENABLED #if AP_FOLLOW_ENABLED && AP_AVOIDANCE_ENABLED -#define MODE_FOLLOW_ENABLED ENABLED +#define MODE_FOLLOW_ENABLED 1 #else -#define MODE_FOLLOW_ENABLED DISABLED +#define MODE_FOLLOW_ENABLED 0 #endif #endif ////////////////////////////////////////////////////////////////////////////// // Guided mode - control vehicle's position or angles from GCS #ifndef MODE_GUIDED_ENABLED -# define MODE_GUIDED_ENABLED ENABLED +# define MODE_GUIDED_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // GuidedNoGPS mode - control vehicle's angles from GCS #ifndef MODE_GUIDED_NOGPS_ENABLED -# define MODE_GUIDED_NOGPS_ENABLED ENABLED +# define MODE_GUIDED_NOGPS_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Loiter mode - allows vehicle to hold global position #ifndef MODE_LOITER_ENABLED -# define MODE_LOITER_ENABLED ENABLED +# define MODE_LOITER_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Position Hold - enable holding of global position #ifndef MODE_POSHOLD_ENABLED -# define MODE_POSHOLD_ENABLED ENABLED +# define MODE_POSHOLD_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // RTL - Return To Launch #ifndef MODE_RTL_ENABLED -# define MODE_RTL_ENABLED ENABLED +# define MODE_RTL_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home #ifndef MODE_SMARTRTL_ENABLED -# define MODE_SMARTRTL_ENABLED ENABLED +# define MODE_SMARTRTL_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // Sport - fly vehicle in rate-controlled (earth-frame) mode #ifndef MODE_SPORT_ENABLED -# define MODE_SPORT_ENABLED DISABLED +# define MODE_SPORT_ENABLED 0 #endif ////////////////////////////////////////////////////////////////////////////// @@ -253,13 +223,13 @@ ////////////////////////////////////////////////////////////////////////////// // Throw - fly vehicle after throwing it in the air #ifndef MODE_THROW_ENABLED -# define MODE_THROW_ENABLED ENABLED +# define MODE_THROW_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// // ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B #ifndef MODE_ZIGZAG_ENABLED -# define MODE_ZIGZAG_ENABLED ENABLED +# define MODE_ZIGZAG_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// @@ -279,7 +249,7 @@ ////////////////////////////////////////////////////////////////////////////// // Weathervane - allow vehicle to yaw into wind #ifndef WEATHERVANE_ENABLED -# define WEATHERVANE_ENABLED ENABLED +# define WEATHERVANE_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// @@ -290,13 +260,13 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if FRAME_CONFIG == HELI_FRAME #ifndef MODE_AUTOROTATE_ENABLED - # define MODE_AUTOROTATE_ENABLED ENABLED + # define MODE_AUTOROTATE_ENABLED 1 #endif #else - # define MODE_AUTOROTATE_ENABLED DISABLED + # define MODE_AUTOROTATE_ENABLED 0 #endif #else - # define MODE_AUTOROTATE_ENABLED DISABLED + # define MODE_AUTOROTATE_ENABLED 0 #endif #endif @@ -382,6 +352,9 @@ #ifndef LAND_DETECTOR_ACCEL_MAX # define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s #endif +#ifndef LAND_DETECTOR_VEL_Z_MAX +# define LAND_DETECTOR_VEL_Z_MAX 1.0f // vehicle vertical velocity must be under 1m/s +#endif ////////////////////////////////////////////////////////////////////////////// // Flight mode definitions @@ -601,8 +574,8 @@ // Developer Items // -#ifndef ADVANCED_FAILSAFE -# define ADVANCED_FAILSAFE DISABLED +#ifndef AP_COPTER_ADVANCED_FAILSAFE_ENABLED +# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0 #endif #ifndef CH_MODE_DEFAULT @@ -610,17 +583,13 @@ #endif #ifndef TOY_MODE_ENABLED -#define TOY_MODE_ENABLED DISABLED +#define TOY_MODE_ENABLED 0 #endif #if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME #error Toy mode is not available on Helicopters #endif -#ifndef OSD_ENABLED - #define OSD_ENABLED DISABLED -#endif - #ifndef HAL_FRAME_TYPE_DEFAULT #define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X #endif @@ -634,5 +603,5 @@ #endif #ifndef USER_PARAMS_ENABLED - #define USER_PARAMS_ENABLED DISABLED + #define USER_PARAMS_ENABLED 0 #endif diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 560aefcd36fc32..fb9481dea80c04 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -36,18 +36,18 @@ void Copter::crash_check() } // exit immediately if in force flying - if (force_flying && !flightmode->is_landing()) { + if (get_force_flying() && !flightmode->is_landing()) { crash_counter = 0; return; } // return immediately if we are not in an angle stabilize flight mode or we are flipping - if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) { + if (!flightmode->crash_check_enabled()) { crash_counter = 0; return; } -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED //return immediately if in autorotation mode if (flightmode->mode_number() == Mode::Number::AUTOROTATE) { crash_counter = 0; @@ -102,7 +102,7 @@ void Copter::thrust_loss_check() static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed // no-op if suppressed by flight options param - if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_THRUST_LOSS_CHECK)) != 0) { + if (copter.option_is_enabled(FlightOption::DISABLE_THRUST_LOSS_CHECK)) { return; } @@ -171,7 +171,7 @@ void Copter::thrust_loss_check() // the motors library disables this when it is no longer needed to achieve the commanded output #if AP_GRIPPER_ENABLED - if ((copter.g2.flight_options & uint32_t(FlightOptions::RELEASE_GRIPPER_ON_THRUST_LOSS)) != 0) { + if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) { gripper.release(); } #endif @@ -182,7 +182,7 @@ void Copter::thrust_loss_check() void Copter::yaw_imbalance_check() { // no-op if suppressed by flight options param - if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_YAW_IMBALANCE_WARNING)) != 0) { + if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) { return; } @@ -229,7 +229,7 @@ void Copter::yaw_imbalance_check() } } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // Code to detect a crash main ArduCopter code #define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute @@ -273,7 +273,7 @@ void Copter::parachute_check() } // return immediately if we are not in an angle stabilize flight mode or we are flipping - if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) { + if (!flightmode->crash_check_enabled()) { control_loss_count = 0; return; } @@ -369,4 +369,4 @@ void Copter::parachute_manual_release() parachute_release(); } -#endif // PARACHUTE == ENABLED +#endif // HAL_PARACHUTE_ENABLED diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 7f1175552537b7..acba81d9539601 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -2,14 +2,6 @@ #include -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - // Frame types #define UNDEFINED_FRAME 0 #define MULTICOPTER_FRAME 1 diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index b4c5c119063993..0c1d7ea70e636f 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -95,9 +95,10 @@ void Copter::esc_calibration_passthrough() hal.scheduler->delay(3); // pass through to motors - SRV_Channels::cork(); + auto &srv = AP::srv(); + srv.cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); - SRV_Channels::push(); + srv.push(); } #endif // FRAME_CONFIG != HELI_FRAME } @@ -112,25 +113,26 @@ void Copter::esc_calibration_auto() esc_calibration_setup(); // raise throttle to maximum - SRV_Channels::cork(); + auto &srv = AP::srv(); + srv.cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); - SRV_Channels::push(); + srv.push(); // delay for 5 seconds while outputting pulses uint32_t tstart = millis(); while (millis() - tstart < 5000) { - SRV_Channels::cork(); + srv.cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); - SRV_Channels::push(); + srv.push(); esc_calibration_notify(); hal.scheduler->delay(3); } // block until we restart while(1) { - SRV_Channels::cork(); + srv.cork(); motors->set_throttle_passthrough_for_esc_calibration(0.0f); - SRV_Channels::push(); + srv.push(); esc_calibration_notify(); hal.scheduler->delay(3); } diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 2796846599f81c..3002e773c02e5c 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -286,7 +286,7 @@ void Copter::failsafe_terrain_on_event() if (should_disarm_on_failsafe()) { arming.disarm(AP_Arming::Method::TERRAINFAILSAFE); -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED } else if (flightmode->mode_number() == Mode::Number::RTL) { mode_rtl.restart_without_terrain(); #endif @@ -379,48 +379,53 @@ void Copter::failsafe_deadreckon_check() // this is always called from a failsafe so we trigger notification to pilot void Copter::set_mode_RTL_or_land_with_pause(ModeReason reason) { +#if MODE_RTL_ENABLED // attempt to switch to RTL, if this fails then switch to Land - if (!set_mode(Mode::Number::RTL, reason)) { - // set mode to land will trigger mode change notification to pilot - set_mode_land_with_pause(reason); - } else { - // alert pilot to mode change + if (set_mode(Mode::Number::RTL, reason)) { AP_Notify::events.failsafe_mode_change = 1; + return; } +#endif + // set mode to land will trigger mode change notification to pilot + set_mode_land_with_pause(reason); } // set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts // this is always called from a failsafe so we trigger notification to pilot void Copter::set_mode_SmartRTL_or_land_with_pause(ModeReason reason) { +#if MODE_SMARTRTL_ENABLED // attempt to switch to SMART_RTL, if this failed then switch to Land - if (!set_mode(Mode::Number::SMART_RTL, reason)) { - gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode"); - set_mode_land_with_pause(reason); - } else { + if (set_mode(Mode::Number::SMART_RTL, reason)) { AP_Notify::events.failsafe_mode_change = 1; + return; } +#endif + gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode"); + set_mode_land_with_pause(reason); } // set_mode_SmartRTL_or_RTL - sets mode to SMART_RTL if possible or RTL if possible or LAND with 4 second delay before descent starts // this is always called from a failsafe so we trigger notification to pilot void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason) { +#if MODE_SMARTRTL_ENABLED // attempt to switch to SmartRTL, if this failed then attempt to RTL // if that fails, then land - if (!set_mode(Mode::Number::SMART_RTL, reason)) { - gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode"); - set_mode_RTL_or_land_with_pause(reason); - } else { + if (set_mode(Mode::Number::SMART_RTL, reason)) { AP_Notify::events.failsafe_mode_change = 1; + return; } +#endif + gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode"); + set_mode_RTL_or_land_with_pause(reason); } // Sets mode to Auto and jumps to DO_LAND_START, as set with AUTO_RTL param // This can come from failsafe or RC option void Copter::set_mode_auto_do_land_start_or_RTL(ModeReason reason) { -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED if (set_mode(Mode::Number::AUTO_RTL, reason)) { AP_Notify::events.failsafe_mode_change = 1; return; @@ -435,7 +440,7 @@ void Copter::set_mode_auto_do_land_start_or_RTL(ModeReason reason) // This can come from failsafe or RC option void Copter::set_mode_brake_or_land_with_pause(ModeReason reason) { -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED if (set_mode(Mode::Number::BRAKE, reason)) { AP_Notify::events.failsafe_mode_change = 1; return; @@ -487,7 +492,7 @@ void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){ set_mode_SmartRTL_or_land_with_pause(reason); break; case FailsafeAction::TERMINATE: { -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED g2.afs.gcs_terminate(true, "Failsafe"); #else arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE); diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index 88ae35572f7939..f1435059779233 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -7,7 +7,7 @@ // our failsafe strategy is to detect main loop lockup and disarm the motors // -static bool failsafe_enabled = false; +static bool failsafe_enabled; static uint16_t failsafe_last_ticks; static uint32_t failsafe_last_timestamp; static bool in_failsafe; @@ -72,7 +72,7 @@ void Copter::failsafe_check() } -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED /* check for AFS failsafe check */ diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index 3bfe085c2b8697..2685f89431be60 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -10,8 +10,10 @@ void Copter::fence_check() { const uint8_t orig_breaches = fence.get_breaches(); + bool is_landing_or_landed = flightmode->is_landing() || ap.land_complete || !motors->armed(); + // check for new breaches; new_breaches is bitmask of fence types breached - const uint8_t new_breaches = fence.check(); + const uint8_t new_breaches = fence.check(is_landing_or_landed); // we still don't do anything when disarmed, but we do check for fence breaches. // fence pre-arm check actually checks if any fence has been breached @@ -24,7 +26,7 @@ void Copter::fence_check() if (new_breaches) { if (!copter.ap.land_complete) { - GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence Breached"); + fence.print_fence_message("breached", new_breaches); } // if the user wants some kind of response and motors are armed @@ -81,7 +83,10 @@ void Copter::fence_check() LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); - } else if (orig_breaches) { + } else if (orig_breaches && fence.get_breaches() == 0) { + if (!copter.ap.land_complete) { + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared"); + } // record clearing of breach LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 0be2f610b3ec25..bff2a3de170419 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -42,11 +42,13 @@ void Copter::check_dynamic_flight(void) moving = (motors->get_throttle() > 0.8f || ahrs.pitch_sensor < -1500); } +#if AP_RANGEFINDER_ENABLED if (!moving && rangefinder_state.enabled && rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) { // when we are more than 2m from the ground with good // rangefinder lock consider it to be dynamic flight moving = (rangefinder.distance_cm_orient(ROTATION_PITCH_270) > 200); } +#endif if (moving) { // if moving for 2 seconds, set the dynamic flight flag @@ -104,8 +106,9 @@ void Copter::update_heli_control_dynamics(void) bool Copter::should_use_landing_swash() const { if (flightmode->has_manual_throttle() || - flightmode->mode_number() == Mode::Number::DRIFT) { - // manual modes always uses full swash range + flightmode->mode_number() == Mode::Number::DRIFT || + attitude_control->get_inverted_flight()) { + // manual modes or modes using inverted flight uses full swash range return false; } if (flightmode->is_landing()) { @@ -186,29 +189,25 @@ void Copter::heli_update_rotor_speed_targets() // to autorotation flight mode if manual collective is not being used. void Copter::heli_update_autorotation() { - // check if flying and interlock disengaged - if (!ap.land_complete && !motors->get_interlock()) { -#if MODE_AUTOROTATE_ENABLED == ENABLED - if (g2.arot.is_enable()) { - if (!flightmode->has_manual_throttle()) { - // set autonomous autorotation flight mode - set_mode(Mode::Number::AUTOROTATE, ModeReason::AUTOROTATION_START); - } - // set flag to facilitate both auto and manual autorotations - motors->set_in_autorotation(true); - motors->set_enable_bailout(true); - } + bool in_autorotation_mode = false; +#if MODE_AUTOROTATE_ENABLED + in_autorotation_mode = flightmode == &mode_autorotate; #endif - if (flightmode->has_manual_throttle() && motors->arot_man_enabled()) { - // set flag to facilitate both auto and manual autorotations - motors->set_in_autorotation(true); - motors->set_enable_bailout(true); - } - } else { - motors->set_in_autorotation(false); - motors->set_enable_bailout(false); + + // If we have landed then we do not want to be in autorotation and we do not want to via the bailout state + if (ap.land_complete || ap.land_complete_maybe) { + motors->force_deactivate_autorotation(); + return; } + // if we got this far we are flying, check for conditions to set autorotation state + if (!motors->get_interlock() && (flightmode->has_manual_throttle() || in_autorotation_mode)) { + // set state in motors to facilitate manual and assisted autorotations + motors->set_autorotation_active(true); + } else { + // deactivate the autorotation state via the bailout case + motors->set_autorotation_active(false); + } } // update collective low flag. Use a debounce time of 400 milliseconds. diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index d7b82c497d203f..d6122e357b48c7 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -22,7 +22,7 @@ void Copter::update_land_and_crash_detectors() update_land_detector(); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // check parachute parachute_check(); #endif @@ -44,6 +44,13 @@ void Copter::update_land_detector() // range finder : tend to be problematic at very short distances // input throttle : in slow land the input throttle may be only slightly less than hover +#if HAL_LOGGING_ENABLED + uint16_t logging_flags = 0; +#define SET_LOG_FLAG(condition, flag) if (condition) { logging_flags |= (uint16_t)flag; } +#else +#define SET_LOG_FLAG(condition, flag) +#endif + if (!motors->armed()) { // if disarmed, always landed. set_land_complete(true); @@ -74,11 +81,12 @@ void Copter::update_land_detector() // check if landing const bool landing = flightmode->is_landing(); + SET_LOG_FLAG(landing, LandDetectorLoggingFlag::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) -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED || (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll()) #endif - || ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f); + || ((!get_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) @@ -91,6 +99,8 @@ void Copter::update_land_detector() throttle_mix_at_min = true; } #endif + SET_LOG_FLAG(motor_at_lower_limit, LandDetectorLoggingFlag::MOTOR_AT_LOWER_LIMIT); + SET_LOG_FLAG(throttle_mix_at_min, LandDetectorLoggingFlag::THROTTLE_MIX_AT_MIN); uint8_t land_detector_scalar = 1; #if AP_LANDINGGEAR_ENABLED @@ -100,14 +110,27 @@ void Copter::update_land_detector() } #endif + // check for aggressive flight requests - requested roll or pitch angle below 15 degrees + const Vector3f angle_target = attitude_control->get_att_target_euler_cd(); + bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD; + SET_LOG_FLAG(large_angle_request, LandDetectorLoggingFlag::LARGE_ANGLE_REQUEST); + + // check for large external disturbance - angle error over 30 degrees + const float angle_error = attitude_control->get_att_error_angle_deg(); + bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG); + SET_LOG_FLAG(large_angle_error, LandDetectorLoggingFlag::LARGE_ANGLE_ERROR); + // check that the airframe is not accelerating (not falling or braking after fast forward flight) bool accel_stationary = (land_accel_ef_filter.get().length() <= LAND_DETECTOR_ACCEL_MAX * land_detector_scalar); + SET_LOG_FLAG(accel_stationary, LandDetectorLoggingFlag::ACCEL_STATIONARY); // check that vertical speed is within 1m/s of zero - bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100 * land_detector_scalar; + bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100.0 * LAND_DETECTOR_VEL_Z_MAX * land_detector_scalar; + SET_LOG_FLAG(descent_rate_low, LandDetectorLoggingFlag::DESCENT_RATE_LOW); // if we have a healthy rangefinder only allow landing detection below 2 meters bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM); + SET_LOG_FLAG(rangefinder_check, LandDetectorLoggingFlag::RANGEFINDER_BELOW_2M); // if we have weight on wheels (WoW) or ambiguous unknown. never no WoW #if AP_LANDINGGEAR_ENABLED @@ -115,8 +138,9 @@ void Copter::update_land_detector() #else const bool WoW_check = true; #endif + SET_LOG_FLAG(WoW_check, LandDetectorLoggingFlag::WOW); - if (motor_at_lower_limit && throttle_mix_at_min && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) { + if (motor_at_lower_limit && throttle_mix_at_min && !large_angle_request && !large_angle_error && 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 < land_trigger_sec*scheduler.get_loop_rate_hz()) { land_detector_count++; @@ -130,8 +154,53 @@ void Copter::update_land_detector() } set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*scheduler.get_loop_rate_hz())); + +#if HAL_LOGGING_ENABLED +// @LoggerMessage: LDET +// @Description: Land Detector State +// @Field: TimeUS: Time since system startup +// @Field: Flags: boolean state flags +// @FieldBitmaskEnum: Flags: Copter::LandDetectorLoggingFlag +// @Field: Count: landing_detector pass count + SET_LOG_FLAG(ap.land_complete, LandDetectorLoggingFlag::LANDED); + SET_LOG_FLAG(ap.land_complete_maybe, LandDetectorLoggingFlag::LANDED_MAYBE); + SET_LOG_FLAG(standby_active, LandDetectorLoggingFlag::STANDBY_ACTIVE); + Log_LDET(logging_flags, land_detector_count); +#undef SET_LOG_FLAG +#endif } +#if HAL_LOGGING_ENABLED +void Copter::Log_LDET(uint16_t logging_flags, uint32_t detector_count) +{ + // do not log if no change: + if (logging_flags == land_detector.last_logged_flags && + detector_count == land_detector.last_logged_count) { + return; + } + // do not log more than 50Hz: + const auto now = AP_HAL::millis(); + if (now - land_detector.last_logged_ms < 20) { + return; + } + + land_detector.last_logged_count = detector_count; + land_detector.last_logged_flags = logging_flags; + land_detector.last_logged_ms = now; + + AP::logger().WriteStreaming( + "LDET", + "TimeUS," "Flags," "Count", + "s" "-" "-", + "F" "-" "-", + "Q" "H" "I", + AP_HAL::micros64(), + logging_flags, + land_detector_count + ); +} +#endif + // set land_complete flag and disarm motors if disarm-on-land is configured void Copter::set_land_complete(bool b) { @@ -243,7 +312,7 @@ void Copter::update_throttle_mix() // check if landing const bool landing = flightmode->is_landing(); - if (((large_angle_request || force_flying) && !landing) || large_angle_error || accel_moving || descent_not_demanded) { + if (((large_angle_request || get_force_flying()) && !landing) || large_angle_error || accel_moving || descent_not_demanded) { attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio()); } else { attitude_control->set_throttle_mix_min(); @@ -251,3 +320,14 @@ void Copter::update_throttle_mix() } #endif } + +// helper function for force flying flag +bool Copter::get_force_flying() const +{ +#if FRAME_CONFIG == HELI_FRAME + if (attitude_control->get_inverted_flight()) { + return true; + } +#endif + return force_flying; +} diff --git a/ArduCopter/landing_gear.cpp b/ArduCopter/landing_gear.cpp index 2aec67d2b2984e..5c77b8231f6107 100644 --- a/ArduCopter/landing_gear.cpp +++ b/ArduCopter/landing_gear.cpp @@ -14,6 +14,7 @@ void Copter::landinggear_update() int32_t height_cm = flightmode->get_alt_above_ground_cm(); // use rangefinder if available +#if AP_RANGEFINDER_ENABLED switch (rangefinder.status_orient(ROTATION_PITCH_270)) { case RangeFinder::Status::NotConnected: case RangeFinder::Status::NoData: @@ -31,6 +32,7 @@ void Copter::landinggear_update() height_cm = rangefinder_state.alt_cm_filt.get(); break; } +#endif // AP_RANGEFINDER_ENABLED landinggear.update(height_cm * 0.01f); // convert cm->m for update call } diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index fe900d307db9ae..b5900f88304791 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -32,158 +32,141 @@ PayloadPlace Mode::payload_place; // return the static controller object corresponding to supplied mode Mode *Copter::mode_from_mode_num(const Mode::Number mode) { - Mode *ret = nullptr; switch (mode) { -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED case Mode::Number::ACRO: - ret = &mode_acro; - break; + return &mode_acro; #endif case Mode::Number::STABILIZE: - ret = &mode_stabilize; - break; + return &mode_stabilize; case Mode::Number::ALT_HOLD: - ret = &mode_althold; - break; + return &mode_althold; -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED case Mode::Number::AUTO: - ret = &mode_auto; - break; + return &mode_auto; #endif -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED case Mode::Number::CIRCLE: - ret = &mode_circle; - break; + return &mode_circle; #endif -#if MODE_LOITER_ENABLED == ENABLED +#if MODE_LOITER_ENABLED case Mode::Number::LOITER: - ret = &mode_loiter; - break; + return &mode_loiter; #endif -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED case Mode::Number::GUIDED: - ret = &mode_guided; - break; + return &mode_guided; #endif case Mode::Number::LAND: - ret = &mode_land; - break; + return &mode_land; -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED case Mode::Number::RTL: - ret = &mode_rtl; - break; + return &mode_rtl; #endif -#if MODE_DRIFT_ENABLED == ENABLED +#if MODE_DRIFT_ENABLED case Mode::Number::DRIFT: - ret = &mode_drift; - break; + return &mode_drift; #endif -#if MODE_SPORT_ENABLED == ENABLED +#if MODE_SPORT_ENABLED case Mode::Number::SPORT: - ret = &mode_sport; - break; + return &mode_sport; #endif -#if MODE_FLIP_ENABLED == ENABLED +#if MODE_FLIP_ENABLED case Mode::Number::FLIP: - ret = &mode_flip; - break; + return &mode_flip; #endif -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED case Mode::Number::AUTOTUNE: - ret = &mode_autotune; - break; + return &mode_autotune; #endif -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED case Mode::Number::POSHOLD: - ret = &mode_poshold; - break; + return &mode_poshold; #endif -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED case Mode::Number::BRAKE: - ret = &mode_brake; - break; + return &mode_brake; #endif -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED case Mode::Number::THROW: - ret = &mode_throw; - break; + return &mode_throw; #endif #if HAL_ADSB_ENABLED case Mode::Number::AVOID_ADSB: - ret = &mode_avoid_adsb; - break; + return &mode_avoid_adsb; #endif -#if MODE_GUIDED_NOGPS_ENABLED == ENABLED +#if MODE_GUIDED_NOGPS_ENABLED case Mode::Number::GUIDED_NOGPS: - ret = &mode_guided_nogps; - break; + return &mode_guided_nogps; #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED case Mode::Number::SMART_RTL: - ret = &mode_smartrtl; - break; + return &mode_smartrtl; #endif -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if MODE_FLOWHOLD_ENABLED case Mode::Number::FLOWHOLD: - ret = (Mode *)g2.mode_flowhold_ptr; - break; + return (Mode *)g2.mode_flowhold_ptr; #endif -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED case Mode::Number::FOLLOW: - ret = &mode_follow; - break; + return &mode_follow; #endif -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED case Mode::Number::ZIGZAG: - ret = &mode_zigzag; - break; + return &mode_zigzag; #endif -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED case Mode::Number::SYSTEMID: - ret = (Mode *)g2.mode_systemid_ptr; - break; + return (Mode *)g2.mode_systemid_ptr; #endif -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED case Mode::Number::AUTOROTATE: - ret = &mode_autorotate; - break; + return &mode_autorotate; #endif -#if MODE_TURTLE_ENABLED == ENABLED +#if MODE_TURTLE_ENABLED case Mode::Number::TURTLE: - ret = &mode_turtle; - break; + return &mode_turtle; #endif default: break; } - return ret; +#if MODE_GUIDED_ENABLED && AP_SCRIPTING_ENABLED + // Check registered custom modes + for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) { + if ((mode_guided_custom[i] != nullptr) && (mode_guided_custom[i]->mode_number() == mode)) { + return mode_guided_custom[i]; + } + } +#endif + + return nullptr; } @@ -273,10 +256,11 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) return false; } -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED if (mode == Mode::Number::AUTO_RTL) { // Special case for AUTO RTL, not a true mode, just AUTO in disguise - return mode_auto.jump_to_landing_sequence_auto_RTL(reason); + // Attempt to join return path, fallback to do-land-start + return mode_auto.return_path_or_jump_to_landing_sequence_auto_RTL(reason); } #endif @@ -291,20 +275,9 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) #if FRAME_CONFIG == HELI_FRAME // do not allow helis to enter a non-manual throttle mode if the // rotor runup is not complete - if (!ignore_checks && !new_flightmode->has_manual_throttle() && - (motors->get_spool_state() == AP_Motors::SpoolState::SPOOLING_UP || motors->get_spool_state() == AP_Motors::SpoolState::SPOOLING_DOWN)) { - #if MODE_AUTOROTATE_ENABLED == ENABLED - //if the mode being exited is the autorotation mode allow mode change despite rotor not being at - //full speed. This will reduce altitude loss on bail-outs back to non-manual throttle modes - bool in_autorotation_check = (flightmode != &mode_autorotate || new_flightmode != &mode_autorotate); - #else - bool in_autorotation_check = false; - #endif - - if (!in_autorotation_check) { - mode_change_failed(new_flightmode, "runup not complete"); - return false; - } + if (!ignore_checks && !new_flightmode->has_manual_throttle() && !motors->rotor_runup_complete()) { + mode_change_failed(new_flightmode, "runup not complete"); + return false; } #endif @@ -314,7 +287,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) // (e.g. user arms in guided, raises throttle to 1300 (not enough to // trigger auto takeoff), then switches into manual): bool user_throttle = new_flightmode->has_manual_throttle(); -#if MODE_DRIFT_ENABLED == ENABLED +#if MODE_DRIFT_ENABLED if (new_flightmode == &mode_drift) { user_throttle = true; } @@ -346,6 +319,20 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) return false; } +#if AP_FENCE_ENABLED + // may not be allowed to change mode if recovering from fence breach + if (!ignore_checks && + fence.enabled() && + fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) && + fence.get_breaches() && + motors->armed() && + get_control_mode_reason() == ModeReason::FENCE_BREACHED && + !ap.land_complete) { + mode_change_failed(new_flightmode, "in fence recovery"); + return false; + } +#endif + if (!new_flightmode->init(ignore_checks)) { mode_change_failed(new_flightmode, "init failed"); return false; @@ -354,9 +341,6 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) // perform any cleanup required by previous flight mode exit_mode(flightmode, new_flightmode); - // store previous flight mode (only used by tradeheli's autorotation) - prev_control_mode = flightmode->mode_number(); - // update flight mode flightmode = new_flightmode; control_mode_reason = reason; @@ -370,10 +354,12 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) #endif #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 - fence.manual_recovery_start(); + if (fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY) { + // 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 + fence.manual_recovery_start(); + } #endif #if AP_CAMERA_ENABLED @@ -381,11 +367,11 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) #endif // set rate shaping time constants -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_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_ACRO_ENABLED || MODE_DRIFT_ENABLED if (mode== Mode::Number::ACRO || mode== Mode::Number::DRIFT) { attitude_control->set_yaw_rate_tc(g2.command_model_acro_y.get_rate_tc()); } @@ -419,7 +405,10 @@ bool Copter::set_mode(const uint8_t new_mode, const ModeReason reason) // called at 100hz or more void Copter::update_flight_mode() { +#if AP_RANGEFINDER_ENABLED surface_tracking.invalidate_for_logging(); // invalidate surface tracking alt, flight mode will set to true if used +#endif + attitude_control->landed_gain_reduction(copter.ap.land_complete); // Adjust gains when landed to attenuate ground oscillation flightmode->run(); } @@ -972,19 +961,19 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: - return AltHold_MotorStopped; + return AltHoldModeState::MotorStopped; case AP_Motors::SpoolState::GROUND_IDLE: - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; default: - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else if (takeoff.running() || takeoff.triggered(target_climb_rate_cms)) { // the aircraft is currently landed or taking off, asking for a positive climb rate and in THROTTLE_UNLIMITED // the aircraft should progress through the take off procedure - return AltHold_Takeoff; + return AltHoldModeState::Takeoff; } else if (!copter.ap.auto_armed || copter.ap.land_complete) { // the aircraft is armed and landed @@ -999,29 +988,32 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) if (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) { // the aircraft is waiting in ground idle - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; } else { // the aircraft can leave the ground at any time - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else { // the aircraft is in a flying state motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - return AltHold_Flying; + return AltHoldModeState::Flying; } } // transform pilot's yaw input into a desired yaw rate // returns desired yaw rate in centi-degrees per second -float Mode::get_pilot_desired_yaw_rate(float yaw_in) +float Mode::get_pilot_desired_yaw_rate() const { // throttle failsafe check if (copter.failsafe.radio || !rc().has_ever_seen_rc_input()) { return 0.0f; } + // Get yaw input + const float yaw_in = channel_yaw->norm_input_dz(); + // convert pilot input to the desired yaw rate return g2.command_model_pilot.get_rate() * 100.0 * input_expo(yaw_in, g2.command_model_pilot.get_expo()); } diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index ad0618e45df13f..4b142409bc80cd 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -3,6 +3,11 @@ #include "Copter.h" #include #include // TODO why is this needed if Copter.h includes this + +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED +#include "afs_copter.h" +#endif + class Parameters; class ParametersG2; @@ -14,7 +19,7 @@ class _AutoTakeoff { public: void run(); void start(float complete_alt_cm, bool terrain_alt); - bool get_position(Vector3p& completion_pos); + bool get_completion_pos(Vector3p& pos_neu_cm); bool complete; // true when takeoff is complete @@ -127,6 +132,15 @@ class Mode { virtual bool allows_save_trim() const { return false; } virtual bool allows_autotune() const { return false; } virtual bool allows_flip() const { return false; } + virtual bool crash_check_enabled() const { return true; } + +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED + // Return the type of this mode for use by advanced failsafe + virtual AP_AdvancedFailsafe_Copter::control_mode afs_mode() const { return AP_AdvancedFailsafe_Copter::control_mode::AFS_STABILIZED; } +#endif + + // Return true if the throttle high arming check can be skipped when arming from GCS or Scripting + virtual bool allows_GCS_or_SCR_arming_with_throttle_high() const { return false; } #if FRAME_CONFIG == HELI_FRAME virtual bool allows_inverted() const { return false; }; @@ -161,19 +175,13 @@ class Mode { // pilot input processing 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_yaw_rate() const; float get_pilot_desired_throttle() const; // returns climb target_rate reduced to avoid obstacles and // altitude fence float get_avoidance_adjusted_climbrate(float target_rate); - const Vector3f& get_vel_desired_cms() { - // note that position control isn't used in every mode, so - // this may return bogus data: - return pos_control->get_vel_desired_cms(); - } - // send output to the motors, can be overridden by subclasses virtual void output_to_motors(); @@ -184,8 +192,11 @@ class Mode { virtual bool pause() { return false; }; virtual bool resume() { return false; }; + // handle situations where the vehicle is on the ground waiting for takeoff + void make_safe_ground_handling(bool force_throttle_unlimited = false); + // true if weathervaning is allowed in the current mode -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED virtual bool allows_weathervaning() const { return false; } #endif @@ -195,7 +206,6 @@ class Mode { bool is_disarmed_or_landed() const; void zero_throttle_and_relax_ac(bool spool_up = false); void zero_throttle_and_hold_attitude(); - void make_safe_ground_handling(bool force_throttle_unlimited = false); // Return stopping point as a location with above origin alt frame Location get_stopping_point() const; @@ -231,12 +241,12 @@ class Mode { virtual float throttle_hover() const; // Alt_Hold based flight mode states used in Alt_Hold, Loiter, and Sport - enum AltHoldModeState { - AltHold_MotorStopped, - AltHold_Takeoff, - AltHold_Landed_Ground_Idle, - AltHold_Landed_Pre_Takeoff, - AltHold_Flying + enum class AltHoldModeState { + MotorStopped, + Takeoff, + Landed_Ground_Idle, + Landed_Pre_Takeoff, + Flying }; AltHoldModeState get_alt_hold_state(float target_climb_rate_cms); @@ -325,9 +335,11 @@ class Mode { void set_yaw_angle_rate(float yaw_angle_d, float yaw_rate_ds); + void set_yaw_angle_offset(const float yaw_angle_offset_d); + bool reached_fixed_yaw_target(); -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED void update_weathervane(const int16_t pilot_yaw_cds); #endif @@ -386,7 +398,7 @@ class Mode { }; -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED class ModeAcro : public Mode { public: @@ -417,6 +429,7 @@ class ModeAcro : public Mode { void air_mode_aux_changed(); bool allows_save_trim() const override { return true; } bool allows_flip() const override { return true; } + bool crash_check_enabled() const override { return false; } protected: @@ -470,7 +483,9 @@ class ModeAltHold : public Mode { } bool allows_autotune() const override { return true; } bool allows_flip() const override { return true; } - +#if FRAME_CONFIG == HELI_FRAME + bool allows_inverted() const override { return true; }; +#endif protected: const char *name() const override { return "ALT_HOLD"; } @@ -498,6 +513,17 @@ class ModeAuto : public Mode { 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; } +#if FRAME_CONFIG == HELI_FRAME + bool allows_inverted() const override { return true; }; +#endif + +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED + // Return the type of this mode for use by advanced failsafe + AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; } +#endif + + // Return true if the throttle high arming check can be skipped when arming from GCS or Scripting + bool allows_GCS_or_SCR_arming_with_throttle_high() const override { return true; } // Auto modes enum class SubMode : uint8_t { @@ -553,6 +579,12 @@ class ModeAuto : public Mode { // Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode bool jump_to_landing_sequence_auto_RTL(ModeReason reason); + // Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode + bool return_path_start_auto_RTL(ModeReason reason); + + // Try join return path else do land start + bool return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason); + // lua accessors for nav script time support bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4); void nav_script_time_done(uint16_t id); @@ -566,7 +598,7 @@ class ModeAuto : public Mode { AP_Mission_ChangeDetector mis_change_detector; // true if weathervaning is allowed in auto -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED bool allows_weathervaning(void) const override; #endif @@ -582,12 +614,16 @@ class ModeAuto : public Mode { private: - enum class Options : int32_t { + enum class Option : int32_t { AllowArming = (1 << 0U), AllowTakeOffWithoutRaisingThrottle = (1 << 1U), IgnorePilotYaw = (1 << 2U), AllowWeatherVaning = (1 << 7U), }; + bool option_is_enabled(Option option) const; + + // Enter auto rtl pseudo mode + bool enter_auto_rtl(ModeReason reason); bool start_command(const AP_Mission::Mission_Command& cmd); bool verify_command(const AP_Mission::Mission_Command& cmd); @@ -605,12 +641,17 @@ class ModeAuto : public Mode { void loiter_to_alt_run(); void nav_attitude_time_run(); + // return the Location portion of a command. If the command's lat and lon and/or alt are zero the default_loc's lat,lon and/or alt are returned instead Location loc_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc) const; SubMode _mode = SubMode::TAKEOFF; // controls which auto controller is run bool shift_alt_to_current_alt(Location& target_loc) const; + // subtract position controller offsets from target location + // should be used when the location will be used as a target for the position controller + void subtract_pos_offsets(Location& target_loc) const; + void do_takeoff(const AP_Mission::Mission_Command& cmd); void do_nav_wp(const AP_Mission::Mission_Command& cmd); bool set_next_wp(const AP_Mission::Mission_Command& current_cmd, const Location &default_loc); @@ -621,7 +662,7 @@ class ModeAuto : public Mode { void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd); void do_spline_wp(const AP_Mission::Mission_Command& cmd); void get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc, Location& dest_loc, Location& next_dest_loc, bool& next_dest_loc_is_spline); -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd); void do_guided_limits(const AP_Mission::Mission_Command& cmd); #endif @@ -633,7 +674,7 @@ class ModeAuto : public Mode { void do_set_home(const AP_Mission::Mission_Command& cmd); void do_roi(const AP_Mission::Mission_Command& cmd); void do_mount_control(const AP_Mission::Mission_Command& cmd); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED void do_parachute(const AP_Mission::Mission_Command& cmd); #endif #if AP_WINCH_ENABLED @@ -659,7 +700,7 @@ class ModeAuto : public Mode { bool verify_nav_wp(const AP_Mission::Mission_Command& cmd); bool verify_circle(const AP_Mission::Mission_Command& cmd); bool verify_spline_wp(const AP_Mission::Mission_Command& cmd); -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd); #endif bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); @@ -732,7 +773,7 @@ class ModeAuto : public Mode { } desired_speed_override; }; -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED /* wrapper class for AC_AutoTune */ @@ -776,18 +817,12 @@ class ModeAutoTune : public Mode { bool allows_arming(AP_Arming::Method method) const override { return false; } bool is_autopilot() const override { return false; } - void save_tuning_gains(); - void reset(); + AutoTune autotune; protected: const char *name() const override { return "AUTOTUNE"; } const char *name4() const override { return "ATUN"; } - -private: - - AutoTune autotune; - }; #endif @@ -893,6 +928,7 @@ class ModeFlip : public Mode { bool has_manual_throttle() const override { return false; } bool allows_arming(AP_Arming::Method method) const override { return false; }; bool is_autopilot() const override { return false; } + bool crash_check_enabled() const override { return false; } protected: @@ -920,7 +956,7 @@ class ModeFlip : public Mode { }; -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if MODE_FLOWHOLD_ENABLED /* class to support FLOWHOLD mode, which is a position hold mode using optical flow directly, avoiding the need for a rangefinder @@ -963,7 +999,7 @@ class ModeFlowHold : public Mode { // calculate attitude from flow data void flow_to_angle(Vector2f &bf_angle); - LowPassFilterVector2f flow_filter; + LowPassFilterConstDtVector2f flow_filter; bool flowhold_init(bool ignore_checks); void flowhold_run(); @@ -1032,6 +1068,14 @@ class ModeGuided : public Mode { bool requires_terrain_failsafe() const override { return true; } +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED + // Return the type of this mode for use by advanced failsafe + AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; } +#endif + + // Return true if the throttle high arming check can be skipped when arming from GCS or Scripting + bool allows_GCS_or_SCR_arming_with_throttle_high() const override { return true; } + // Sets guided's angular target submode: Using a rotation quaternion, angular velocity, and climbrate or thrust (depends on user option) // attitude_quat: IF zero: ang_vel (angular velocity) must be provided even if all zeroes // IF non-zero: attitude_control is performed using both the attitude quaternion and angular velocity @@ -1101,7 +1145,7 @@ class ModeGuided : public Mode { bool resume() override; // true if weathervaning is allowed in guided -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED bool allows_weathervaning(void) const override; #endif @@ -1117,7 +1161,7 @@ class ModeGuided : public Mode { private: // enum for GUID_OPTIONS parameter - enum class Options : int32_t { + enum class Option : uint32_t { AllowArmingFromTX = (1U << 0), // this bit is still available, pilot yaw was mapped to bit 2 for symmetry with auto IgnorePilotYaw = (1U << 2), @@ -1128,6 +1172,9 @@ class ModeGuided : public Mode { AllowWeatherVaning = (1U << 7) }; + // returns true if the Guided-mode-option is set (see GUID_OPTIONS) + bool option_is_enabled(Option option) const; + // wp controller void wp_control_start(); void wp_control_run(); @@ -1146,14 +1193,37 @@ class ModeGuided : public Mode { void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle); // controls which controller is run (pos or vel): - 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) + static SubMode guided_mode; + static bool send_notification; // used to send one time notification to ground station + static bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear) // guided mode is paused or not - bool _paused; + static bool _paused; }; +#if AP_SCRIPTING_ENABLED +// Mode which behaves as guided with custom mode number and name +class ModeGuidedCustom : public ModeGuided { +public: + // constructor registers custom number and names + ModeGuidedCustom(const Number _number, const char* _full_name, const char* _short_name); + + bool init(bool ignore_checks) override; + + Number mode_number() const override { return number; } + + const char *name() const override { return full_name; } + const char *name4() const override { return short_name; } + + // State object which can be edited by scripting + AP_Vehicle::custom_mode_state state; + +private: + const Number number; + const char* full_name; + const char* short_name; +}; +#endif class ModeGuidedNoGPS : public ModeGuided { @@ -1196,6 +1266,11 @@ class ModeLand : public Mode { bool is_landing() const override { return true; }; +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED + // Return the type of this mode for use by advanced failsafe + AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; } +#endif + void do_not_use_GPS(); // returns true if LAND mode is trying to control X/Y position @@ -1237,6 +1312,10 @@ class ModeLoiter : public Mode { bool has_user_takeoff(bool must_navigate) const override { return true; } bool allows_autotune() const override { return true; } +#if FRAME_CONFIG == HELI_FRAME + bool allows_inverted() const override { return true; }; +#endif + #if AC_PRECLAND_ENABLED void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; } #endif @@ -1369,6 +1448,11 @@ class ModeRTL : public Mode { bool requires_terrain_failsafe() const override { return true; } +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED + // Return the type of this mode for use by advanced failsafe + AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; } +#endif + // for reporting to GCS bool get_wp(Location &loc) const override; @@ -1398,8 +1482,8 @@ class ModeRTL : public Mode { // enum for RTL_ALT_TYPE parameter enum class RTLAltType : int8_t { - RTL_ALTTYPE_RELATIVE = 0, - RTL_ALTTYPE_TERRAIN = 1 + RELATIVE = 0, + TERRAIN = 1 }; ModeRTL::RTLAltType get_alt_type() const; @@ -1516,6 +1600,10 @@ class ModeSmartRTL : public ModeRTL { // point while following our path home. If we take too long we // may choose to land the vehicle. uint32_t path_follow_last_pop_fail_ms; + + // backup last popped point so that it can be restored to the path + // if vehicle exits SmartRTL mode before reaching home. invalid if zero + Vector3f dest_NED_backup; }; @@ -1622,22 +1710,29 @@ class ModeSystemId : public Mode { private: void log_data() const; + bool is_poscontrol_axis_type() const; enum class AxisType { - NONE = 0, // none - INPUT_ROLL = 1, // angle input roll axis is being excited - INPUT_PITCH = 2, // angle pitch axis is being excited - INPUT_YAW = 3, // angle yaw axis is being excited - RECOVER_ROLL = 4, // angle roll axis is being excited - RECOVER_PITCH = 5, // angle pitch axis is being excited - RECOVER_YAW = 6, // angle yaw axis is being excited - RATE_ROLL = 7, // rate roll axis is being excited - RATE_PITCH = 8, // rate pitch axis is being excited - RATE_YAW = 9, // rate yaw axis is being excited - MIX_ROLL = 10, // mixer roll axis is being excited - MIX_PITCH = 11, // mixer pitch axis is being excited - MIX_YAW = 12, // mixer pitch axis is being excited - MIX_THROTTLE = 13, // mixer throttle axis is being excited + NONE = 0, // none + INPUT_ROLL = 1, // angle input roll axis is being excited + INPUT_PITCH = 2, // angle pitch axis is being excited + INPUT_YAW = 3, // angle yaw axis is being excited + RECOVER_ROLL = 4, // angle roll axis is being excited + RECOVER_PITCH = 5, // angle pitch axis is being excited + RECOVER_YAW = 6, // angle yaw axis is being excited + RATE_ROLL = 7, // rate roll axis is being excited + RATE_PITCH = 8, // rate pitch axis is being excited + RATE_YAW = 9, // rate yaw axis is being excited + MIX_ROLL = 10, // mixer roll axis is being excited + MIX_PITCH = 11, // mixer pitch axis is being excited + MIX_YAW = 12, // mixer pitch axis is being excited + MIX_THROTTLE = 13, // mixer throttle axis is being excited + DISTURB_POS_LAT = 14, // lateral body axis measured position is being excited + DISTURB_POS_LONG = 15, // longitudinal body axis measured position is being excited + DISTURB_VEL_LAT = 16, // lateral body axis measured velocity is being excited + DISTURB_VEL_LONG = 17, // longitudinal body axis measured velocity is being excited + INPUT_VEL_LAT = 18, // lateral body axis commanded velocity is being excited + INPUT_VEL_LONG = 19, // longitudinal body axis commanded velocity is being excited }; AP_Int8 axis; // Controls which axis are being excited. Set to non-zero to display other parameters @@ -1654,7 +1749,9 @@ class ModeSystemId : public Mode { float waveform_freq_rads; // Instantaneous waveform frequency float time_const_freq; // Time at constant frequency before chirp starts int8_t log_subsample; // Subsample multiple for logging. - + Vector2f target_vel; // target velocity for position controller modes + Vector2f target_pos; // target positon + Vector2f input_vel_last; // last cycle input velocity // System ID states enum class SystemIDModeState { SYSTEMID_STATE_STOPPED, @@ -1718,7 +1815,7 @@ class ModeThrow : public Mode { float free_fall_start_velz; // vertical velocity when free fall was detected }; -#if MODE_TURTLE_ENABLED == ENABLED +#if MODE_TURTLE_ENABLED class ModeTurtle : public Mode { public: @@ -1779,7 +1876,7 @@ class ModeAvoidADSB : public ModeGuided { }; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED class ModeFollow : public ModeGuided { public: @@ -1908,7 +2005,7 @@ class ModeZigZag : public Mode { bool is_suspended; // true if zigzag auto is suspended }; -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED class ModeAutorotate : public Mode { public: @@ -1941,18 +2038,14 @@ class ModeAutorotate : public Mode { int32_t _pitch_target; // Target pitch attitude to pass to attitude controller uint32_t _entry_time_start_ms; // Time remaining until entry phase moves on to glide phase float _hs_decay; // The head accerleration during the entry phase - float _bail_time; // Timer for exiting the bail out phase (s) - uint32_t _bail_time_start_ms; // Time at start of bail out - float _target_climb_rate_adjust;// Target vertical acceleration used during bail out phase - float _target_pitch_adjust; // Target pitch rate used during bail out phase enum class Autorotation_Phase { ENTRY, SS_GLIDE, FLARE, TOUCH_DOWN, - BAIL_OUT } phase_switch; - + LANDED } phase_switch; + enum class Navigation_Decision { USER_CONTROL_STABILISED, STRAIGHT_AHEAD, @@ -1965,10 +2058,10 @@ class ModeAutorotate : public Mode { bool ss_glide_initial : 1; bool flare_initial : 1; bool touch_down_initial : 1; + bool landed_initial : 1; bool straight_ahead_initial : 1; bool level_initial : 1; bool break_initial : 1; - bool bail_out_initial : 1; bool bad_rpm : 1; } _flags; diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 03160ab2a05400..e3284d0e4a0f4e 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -2,7 +2,7 @@ #include "mode.h" -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED /* * Init and run calls for acro flight mode @@ -162,7 +162,7 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa } // convert earth-frame level rates to body-frame level rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd() * radians(0.01f), rate_ef_level_cd, rate_bf_level_cd); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level_cd, rate_bf_level_cd); // combine earth frame rate corrections with rate requests if (g.acro_trainer == (uint8_t)Trainer::LIMITED) { diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index 17dc05bad264d2..069de0c6c6a1df 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED #if FRAME_CONFIG == HELI_FRAME /* @@ -111,7 +111,7 @@ void ModeAcro_Heli::run() // if there is no external gyro then run the usual // ACRO_YAW_P gain on the input control, including // deadzone - yaw_in = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + yaw_in = get_pilot_desired_yaw_rate(); } // run attitude controller @@ -144,7 +144,7 @@ void ModeAcro_Heli::virtual_flybar( float &roll_out, float &pitch_out, float &ya rate_ef_level.z = 0; // convert earth-frame leak rates to body-frame leak rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level); // combine earth frame rate corrections with rate requests roll_out += rate_bf_level.x; @@ -153,4 +153,4 @@ void ModeAcro_Heli::virtual_flybar( float &roll_out, float &pitch_out, float &ya } #endif //HELI_FRAME -#endif //MODE_ACRO_ENABLED == ENABLED +#endif //MODE_ACRO_ENABLED diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 36c7a60143e3f9..357d701f9593ff 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -36,7 +36,7 @@ void ModeAltHold::run() get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd()); // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); @@ -48,22 +48,22 @@ void ModeAltHold::run() // Alt Hold State Machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -76,7 +76,7 @@ void ModeAltHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); #if AP_AVOIDANCE_ENABLED @@ -87,8 +87,10 @@ void ModeAltHold::run() // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index cd3060fa0f7fba..1f8460fad4a749 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED /* * Init and run calls for auto flight mode @@ -139,7 +139,7 @@ void ModeAuto::run() case SubMode::NAVGUIDED: case SubMode::NAV_SCRIPT_TIME: -#if AC_NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED +#if AC_NAV_GUIDED || AP_SCRIPTING_ENABLED nav_guided_run(); #endif break; @@ -164,7 +164,8 @@ void ModeAuto::run() } // only pretend to be in auto RTL so long as mission still thinks its in a landing sequence or the mission has completed - if (auto_RTL && (!(mission.get_in_landing_sequence_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE))) { + const bool auto_rtl_active = mission.get_in_landing_sequence_flag() || mission.get_in_return_path_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE; + if (auto_RTL && !auto_rtl_active) { auto_RTL = false; // log exit from Auto RTL #if HAL_LOGGING_ENABLED @@ -201,45 +202,98 @@ void ModeAuto::set_submode(SubMode new_submode) } } +bool ModeAuto::option_is_enabled(Option option) const +{ + return ((copter.g2.auto_options & (uint32_t)option) != 0); +} + bool ModeAuto::allows_arming(AP_Arming::Method method) const { - return ((copter.g2.auto_options & (uint32_t)Options::AllowArming) != 0) && !auto_RTL; -}; + if (auto_RTL) { + return false; + } + return option_is_enabled(Option::AllowArming); +} -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED bool ModeAuto::allows_weathervaning() const { - return (copter.g2.auto_options & (uint32_t)Options::AllowWeatherVaning) != 0; + return option_is_enabled(Option::AllowWeatherVaning); } #endif // Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason) { - if (mission.jump_to_landing_sequence(get_stopping_point())) { - mission.set_force_resume(true); - // if not already in auto switch to auto - if ((copter.flightmode == &copter.mode_auto) || set_mode(Mode::Number::AUTO, reason)) { - auto_RTL = true; + if (!mission.jump_to_landing_sequence(get_stopping_point())) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode +bool ModeAuto::return_path_start_auto_RTL(ModeReason reason) +{ + if (!mission.jump_to_closest_mission_leg(get_stopping_point())) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Try join return path else do land start +bool ModeAuto::return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason) +{ + const Location stopping_point = get_stopping_point(); + if (!mission.jump_to_closest_mission_leg(stopping_point) && !mission.jump_to_landing_sequence(stopping_point)) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path or landing sequence found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Enter auto rtl pseudo mode +bool ModeAuto::enter_auto_rtl(ModeReason reason) +{ + mission.set_force_resume(true); + + // if not already in auto switch to auto + if ((copter.flightmode == this) || set_mode(Mode::Number::AUTO, reason)) { + auto_RTL = true; #if HAL_LOGGING_ENABLED - // log entry into AUTO RTL - copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason); + // log entry into AUTO RTL + copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason); #endif - // make happy noise - if (copter.ap.initialised) { - AP_Notify::events.user_mode_change = 1; - } - return true; + // make happy noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change = 1; } - // mode change failed, revert force resume flag - mission.set_force_resume(false); - - gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed"); - } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found"); + return true; } + // mode change failed, revert force resume flag + mission.set_force_resume(false); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); // make sad noise if (copter.ap.initialised) { @@ -373,7 +427,7 @@ bool ModeAuto::wp_start(const Location& dest_loc) Vector3f stopping_point; if (_mode == SubMode::TAKEOFF) { Vector3p takeoff_complete_pos; - if (auto_takeoff.get_position(takeoff_complete_pos)) { + if (auto_takeoff.get_completion_pos(takeoff_complete_pos)) { stopping_point = takeoff_complete_pos.tofloat(); } } @@ -395,7 +449,7 @@ bool ModeAuto::wp_start(const Location& dest_loc) // 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() != AutoYaw::Mode::ROI) { + if (auto_yaw.mode() != AutoYaw::Mode::ROI && !(auto_yaw.mode() == AutoYaw::Mode::FIXED && copter.g.wp_yaw_behavior == WP_YAW_BEHAVIOR_NONE)) { auto_yaw.set_mode_to_default(false); } @@ -434,11 +488,6 @@ void ModeAuto::land_start() copter.landinggear.deploy_for_landing(); #endif -#if AP_FENCE_ENABLED - // disable the fence on landing - copter.fence.auto_disable_fence_for_landing(); -#endif - // reset flag indicating if pilot has applied roll or pitch inputs during landing copter.ap.land_repo_active = false; @@ -449,7 +498,7 @@ void ModeAuto::land_start() 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 +// circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location // we assume the caller has performed all required GPS_ok checks void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn) { @@ -468,8 +517,8 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi // check our distance from edge of circle Vector3f circle_edge_neu; - copter.circle_nav->get_closest_point_on_circle(circle_edge_neu); - float dist_to_edge = (inertial_nav.get_position_neu_cm() - circle_edge_neu).length(); + float dist_to_edge; + copter.circle_nav->get_closest_point_on_circle(circle_edge_neu, dist_to_edge); // if more than 3m then fly to edge if (dist_to_edge > 300.0f) { @@ -520,7 +569,7 @@ void ModeAuto::circle_start() set_submode(SubMode::CIRCLE); } -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode void ModeAuto::nav_guided_start() { @@ -592,7 +641,7 @@ void PayloadPlace::start_descent() // returns true if pilot's yaw input should be used to adjust vehicle's heading bool ModeAuto::use_pilot_yaw(void) const { - const bool allow_yaw_option = (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0; + const bool allow_yaw_option = !option_is_enabled(Option::IgnorePilotYaw); const bool rtl_allow_yaw = (_mode == SubMode::RTL) && copter.mode_rtl.use_pilot_yaw(); const bool landing = _mode == SubMode::LAND; return allow_yaw_option || rtl_allow_yaw || landing; @@ -622,13 +671,6 @@ bool ModeAuto::set_speed_down(float speed_down_cms) // 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) { -#if HAL_LOGGING_ENABLED - // To-Do: logging when new commands start/end - if (copter.should_log(MASK_LOG_CMD)) { - copter.logger.Write_Mission_Cmd(mission, cmd); - } -#endif - switch(cmd.id) { /// @@ -672,7 +714,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_spline_wp(cmd); break; -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer do_nav_guided_enable(cmd); break; @@ -729,24 +771,14 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_roi(cmd); break; +#if HAL_MOUNT_ENABLED case MAV_CMD_DO_MOUNT_CONTROL: // 205 // point the camera to a specified angle do_mount_control(cmd); break; - - case MAV_CMD_DO_FENCE_ENABLE: -#if AP_FENCE_ENABLED - if (cmd.p1 == 0) { //disable - copter.fence.enable(false); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); - } else { //enable fence - copter.fence.enable(true); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); - } -#endif //AP_FENCE_ENABLED - break; +#endif -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits do_guided_limits(cmd); break; @@ -758,6 +790,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; #endif + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: break; @@ -791,7 +824,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->in_guided_mode()) { return false; } @@ -921,7 +954,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) cmd_complete = verify_spline_wp(cmd); break; -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED case MAV_CMD_NAV_GUIDED_ENABLE: cmd_complete = verify_nav_guided_enable(cmd); break; @@ -960,10 +993,19 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_CHANGE_SPEED: case MAV_CMD_DO_SET_HOME: case MAV_CMD_DO_SET_ROI: +#if HAL_MOUNT_ENABLED case MAV_CMD_DO_MOUNT_CONTROL: +#endif +#if AC_NAV_GUIDED case MAV_CMD_DO_GUIDED_LIMITS: +#endif +#if AP_FENCE_ENABLED case MAV_CMD_DO_FENCE_ENABLE: +#endif +#if AP_WINCH_ENABLED case MAV_CMD_DO_WINCH: +#endif + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: cmd_complete = true; break; @@ -991,7 +1033,7 @@ void ModeAuto::takeoff_run() { // if the user doesn't want to raise the throttle we can set it automatically // note that this can defeat the disarm check on takeoff - if ((copter.g2.auto_options & (int32_t)Options::AllowTakeOffWithoutRaisingThrottle) != 0) { + if (option_is_enabled(Option::AllowTakeOffWithoutRaisingThrottle)) { copter.set_auto_armed(true); } auto_takeoff.run(); @@ -1062,7 +1104,7 @@ void ModeAuto::circle_run() attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading()); } -#if AC_NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED +#if AC_NAV_GUIDED || AP_SCRIPTING_ENABLED // auto_nav_guided_run - allows control by external navigation controller // called by auto_run at 100hz or more void ModeAuto::nav_guided_run() @@ -1149,8 +1191,10 @@ void ModeAuto::loiter_to_alt_run() // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); @@ -1205,13 +1249,20 @@ void PayloadPlace::run() const uint32_t descent_thrust_cal_duration_ms = 2000; // milliseconds const uint32_t placed_check_duration_ms = 500; // how long we have to be below a throttle threshold before considering placed - // Vertical thrust is taken from the attitude controller before angle boost is added + auto &g2 = copter.g2; + const auto &g = copter.g; auto *attitude_control = copter.attitude_control; + const auto &pos_control = copter.pos_control; + const auto &wp_nav = copter.wp_nav; + + // Vertical thrust is taken from the attitude controller before angle boost is added const float thrust_level = attitude_control->get_throttle_in(); const uint32_t now_ms = AP_HAL::millis(); + // relax position target if we might be landed // if we discover we've landed then immediately release the load: if (copter.ap.land_complete || copter.ap.land_complete_maybe) { + pos_control->soften_for_landing_xy(); switch (state) { case State::FlyToLocation: // this is handled in wp_run() @@ -1233,13 +1284,15 @@ void PayloadPlace::run() } } -#if AP_GRIPPER_ENABLED == ENABLED +#if AP_GRIPPER_ENABLED // if pilot releases load manually: if (AP::gripper().valid() && AP::gripper().released()) { switch (state) { case State::FlyToLocation: case State::Descent_Start: - gcs().send_text(MAV_SEVERITY_INFO, "%s Manual release", prefix_str); + gcs().send_text(MAV_SEVERITY_INFO, "%s Abort: Gripper Open", prefix_str); + // Descent_Start has not run so we must also initalise descent_start_altitude_cm + descent_start_altitude_cm = pos_control->get_pos_desired_z_cm(); state = State::Done; break; case State::Descent: @@ -1257,12 +1310,6 @@ void PayloadPlace::run() } #endif - auto &inertial_nav = copter.inertial_nav; - auto &g2 = copter.g2; - const auto &g = copter.g; - const auto &wp_nav = copter.wp_nav; - const auto &pos_control = copter.pos_control; - switch (state) { case State::FlyToLocation: if (copter.wp_nav->reached_wp_destination()) { @@ -1272,7 +1319,7 @@ void PayloadPlace::run() case State::Descent_Start: descent_established_time_ms = now_ms; - descent_start_altitude_cm = inertial_nav.get_position_z_up_cm(); + descent_start_altitude_cm = pos_control->get_pos_desired_z_cm(); // limiting the decent rate to the limit set in wp_nav is not necessary but done for safety descent_speed_cms = MIN((is_positive(g2.pldp_descent_speed_ms)) ? g2.pldp_descent_speed_ms * 100.0 : abs(g.land_speed), wp_nav->get_default_speed_down()); descent_thrust_level = 1.0; @@ -1282,7 +1329,7 @@ void PayloadPlace::run() case State::Descent: // check maximum decent distance if (!is_zero(descent_max_cm) && - descent_start_altitude_cm - inertial_nav.get_position_z_up_cm() > descent_max_cm) { + descent_start_altitude_cm - pos_control->get_pos_desired_z_cm() > descent_max_cm) { state = State::Ascent_Start; gcs().send_text(MAV_SEVERITY_WARNING, "%s Reached maximum descent", prefix_str); break; @@ -1332,7 +1379,7 @@ void PayloadPlace::run() case State::Release: // Reinitialise vertical position controller to remove discontinuity due to touch down of payload pos_control->init_z_controller_no_descent(); -#if AP_GRIPPER_ENABLED == ENABLED +#if AP_GRIPPER_ENABLED if (AP::gripper().valid()) { gcs().send_text(MAV_SEVERITY_INFO, "%s Releasing the gripper", prefix_str); AP::gripper().release(); @@ -1371,7 +1418,7 @@ void PayloadPlace::run() // vel_threshold_fraction * max velocity const float vel_threshold_fraction = 0.1; 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() >= descent_start_altitude_cm - stop_distance; + bool reached_altitude = pos_control->get_pos_desired_z_cm() >= descent_start_altitude_cm - stop_distance; if (reached_altitude) { state = State::Done; } @@ -1394,8 +1441,7 @@ void PayloadPlace::run() copter.flightmode->land_run_horizontal_control(); // update altitude target and call position controller pos_control->land_at_climb_rate_cm(-descent_speed_cms, true); - pos_control->update_z_controller(); - return; + break; case State::Release: case State::Releasing: case State::Delay: @@ -1403,8 +1449,7 @@ void PayloadPlace::run() copter.flightmode->land_run_horizontal_control(); // update altitude target and call position controller pos_control->land_at_climb_rate_cm(0.0, false); - pos_control->update_z_controller(); - return; + break; case State::Ascent: case State::Done: float vel = 0.0; @@ -1412,6 +1457,7 @@ void PayloadPlace::run() pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0); break; } + pos_control->update_z_controller(); } #endif @@ -1425,6 +1471,8 @@ bool ModeAuto::shift_alt_to_current_alt(Location& target_loc) const (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)) { + // subtract position offset (if any) + curr_rngfnd_alt_cm -= pos_control->get_pos_offset_z_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; @@ -1439,11 +1487,21 @@ bool ModeAuto::shift_alt_to_current_alt(Location& target_loc) const return false; } - // set target_loc's alt - target_loc.set_alt_cm(currloc.alt, currloc.get_alt_frame()); + // set target_loc's alt minus position offset (if any) + target_loc.set_alt_cm(currloc.alt - pos_control->get_pos_offset_z_cm(), currloc.get_alt_frame()); return true; } +// subtract position controller offsets from target location +// should be used when the location will be used as a target for the position controller +void ModeAuto::subtract_pos_offsets(Location& target_loc) const +{ + // subtract position controller offsets from target location + const Vector3p& pos_ofs_neu_cm = pos_control->get_pos_offset_cm(); + Vector3p pos_ofs_ned_m = Vector3p{pos_ofs_neu_cm.x * 0.01, pos_ofs_neu_cm.y * 0.01, -pos_ofs_neu_cm.z * 0.01}; + target_loc.offset(-pos_ofs_ned_m); +} + /********************************************************************************/ // Nav (Must) commands /********************************************************************************/ @@ -1455,6 +1513,7 @@ void ModeAuto::do_takeoff(const AP_Mission::Mission_Command& cmd) takeoff_start(cmd.content.location); } +// return the Location portion of a command. If the command's lat and lon and/or alt are zero the default_loc's lat,lon and/or alt are returned instead Location ModeAuto::loc_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc) const { Location ret(cmd.content.location); @@ -1484,6 +1543,10 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) { // calculate default location used when lat, lon or alt is zero Location default_loc = copter.current_loc; + + // subtract position offsets + subtract_pos_offsets(default_loc); + if (wp_nav->is_active() && wp_nav->reached_wp_destination()) { if (!wp_nav->get_wp_destination_loc(default_loc)) { // this should never happen @@ -1604,33 +1667,23 @@ void ModeAuto::do_land(const AP_Mission::Mission_Command& cmd) // note: caller should set yaw_mode void ModeAuto::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd) { - // convert back to location - Location target_loc(cmd.content.location); + // calculate default location used when lat, lon or alt is zero + Location default_loc = copter.current_loc; - // use current location if not provided - if (target_loc.lat == 0 && target_loc.lng == 0) { - // To-Do: make this simpler - Vector3f temp_pos; - copter.wp_nav->get_wp_stopping_point_xy(temp_pos.xy()); - const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN); - target_loc.lat = temp_loc.lat; - target_loc.lng = temp_loc.lng; - } - - // use current altitude if not provided - // To-Do: use z-axis stopping point instead of current alt - if (target_loc.alt == 0) { - // set to current altitude but in command's alt frame - int32_t curr_alt; - if (copter.current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) { - target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame()); - } else { - // default to current altitude as alt-above-home - target_loc.set_alt_cm(copter.current_loc.alt, - copter.current_loc.get_alt_frame()); + // subtract position offsets + subtract_pos_offsets(default_loc); + + // use previous waypoint destination as default if available + if (wp_nav->is_active() && wp_nav->reached_wp_destination()) { + if (!wp_nav->get_wp_destination_loc(default_loc)) { + // this should never happen + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } } + // get waypoint's location from command and send to wp_nav + const Location target_loc = loc_from_cmd(cmd, default_loc); + // start way point navigator and provide it the desired location if (!wp_start(target_loc)) { // failure to set next destination can only be because of missing terrain data @@ -1642,7 +1695,13 @@ void ModeAuto::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd) // do_circle - initiate moving in a circle void ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd) { - const Location circle_center = loc_from_cmd(cmd, copter.current_loc); + // calculate default location used when lat, lon or alt is zero + Location default_loc = copter.current_loc; + + // subtract position offsets + subtract_pos_offsets(default_loc); + + const Location circle_center = loc_from_cmd(cmd, default_loc); // calculate radius uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1 @@ -1710,6 +1769,10 @@ void ModeAuto::do_spline_wp(const AP_Mission::Mission_Command& cmd) { // calculate default location used when lat, lon or alt is zero Location default_loc = copter.current_loc; + + // subtract position offsets + subtract_pos_offsets(default_loc); + if (wp_nav->is_active() && wp_nav->reached_wp_destination()) { if (!wp_nav->get_wp_destination_loc(default_loc)) { // this should never happen @@ -1741,7 +1804,7 @@ void ModeAuto::do_spline_wp(const AP_Mission::Mission_Command& cmd) // 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() != AutoYaw::Mode::ROI) { + if (auto_yaw.mode() != AutoYaw::Mode::ROI && !(auto_yaw.mode() == AutoYaw::Mode::FIXED && copter.g.wp_yaw_behavior == WP_YAW_BEHAVIOR_NONE)) { auto_yaw.set_mode_to_default(false); } @@ -1767,7 +1830,7 @@ void ModeAuto::get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const } } -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED // do_nav_guided_enable - initiate accepting commands from external nav computer void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { @@ -1873,15 +1936,20 @@ void ModeAuto::do_yaw(const AP_Mission::Mission_Command& cmd) void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd) { if (cmd.content.speed.target_ms > 0) { - if (cmd.content.speed.speed_type == 2) { + switch (cmd.content.speed.speed_type) { + case SPEED_TYPE_CLIMB_SPEED: copter.wp_nav->set_speed_up(cmd.content.speed.target_ms * 100.0f); desired_speed_override.up = cmd.content.speed.target_ms; - } else if (cmd.content.speed.speed_type == 3) { + break; + case SPEED_TYPE_DESCENT_SPEED: copter.wp_nav->set_speed_down(cmd.content.speed.target_ms * 100.0f); desired_speed_override.down = cmd.content.speed.target_ms; - } else { + break; + case SPEED_TYPE_AIRSPEED: + case SPEED_TYPE_GROUNDSPEED: copter.wp_nav->set_speed_xy(cmd.content.speed.target_ms * 100.0f); desired_speed_override.xy = cmd.content.speed.target_ms; + break; } } } @@ -1908,19 +1976,21 @@ void ModeAuto::do_roi(const AP_Mission::Mission_Command& cmd) auto_yaw.set_roi(cmd.content.location); } +#if HAL_MOUNT_ENABLED // point the camera to a specified angle void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd) { -#if HAL_MOUNT_ENABLED // 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() != AP_Mount::Type::None) && !copter.camera_mount.has_pan_control()) { - auto_yaw.set_yaw_angle_rate(cmd.content.mount_control.yaw,0.0f); + // Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is + // equivalent to an offset to the current yaw demand. + auto_yaw.set_yaw_angle_offset(cmd.content.mount_control.yaw); } // pass the target angles to the camera mount copter.camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false); -#endif } +#endif // HAL_MOUNT_ENABLED #if AP_WINCH_ENABLED // control winch based on mission command @@ -2216,7 +2286,7 @@ bool ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd) return false; } -#if AC_NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED // verify_nav_guided - check if we have breached any limits bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { @@ -2281,7 +2351,7 @@ bool ModeAuto::resume() bool ModeAuto::paused() const { - return wp_nav->paused(); + return (wp_nav != nullptr) && wp_nav->paused(); } #endif diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index 85f278ac0d801d..e13bc52516251e 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -11,11 +11,11 @@ #include -#if MODE_AUTOROTATE_ENABLED == ENABLED +#if MODE_AUTOROTATE_ENABLED #define AUTOROTATE_ENTRY_TIME 2.0f // (s) number of seconds that the entry phase operates for -#define BAILOUT_MOTOR_RAMP_TIME 1.0f // (s) time set on bailout ramp up timer for motors - See AC_MotorsHeli_Single #define HEAD_SPEED_TARGET_RATIO 1.0f // Normalised target main rotor head speed (unit: -) +#define AUTOROTATION_MIN_MOVING_SPEED 100.0 // (cm/s) minimum speed used for "is moving" check bool ModeAutorotate::init(bool ignore_checks) { @@ -24,15 +24,16 @@ bool ModeAutorotate::init(bool ignore_checks) return false; #endif - // Check that mode is enabled + // Check that mode is enabled, make sure this is the first check as this is the most + // important thing for users to fix if they are planning to use autorotation mode if (!g2.arot.is_enable()) { - gcs().send_text(MAV_SEVERITY_INFO, "Autorot Mode Not Enabled"); + gcs().send_text(MAV_SEVERITY_WARNING, "Autorot Mode Not Enabled"); return false; } - // Check that interlock is disengaged - if (motors->get_interlock()) { - gcs().send_text(MAV_SEVERITY_INFO, "Autorot Mode Change Fail: Interlock Engaged"); + // Must be armed to use mode, prevent triggering state machine on the ground + if (!motors->armed() || copter.ap.land_complete || copter.ap.land_complete_maybe) { + gcs().send_text(MAV_SEVERITY_WARNING, "Autorot: Must be Armed and Flying"); return false; } @@ -52,10 +53,10 @@ bool ModeAutorotate::init(bool ignore_checks) _flags.ss_glide_initial = true; _flags.flare_initial = true; _flags.touch_down_initial = true; + _flags.landed_initial = true; _flags.level_initial = true; _flags.break_initial = true; _flags.straight_ahead_initial = true; - _flags.bail_out_initial = true; _msg_flags.bad_rpm = true; // Setting default starting switches @@ -74,20 +75,9 @@ bool ModeAutorotate::init(bool ignore_checks) void ModeAutorotate::run() { - // Check if interlock becomes engaged - if (motors->get_interlock() && !copter.ap.land_complete) { - phase_switch = Autorotation_Phase::BAIL_OUT; - } else if (motors->get_interlock() && copter.ap.land_complete) { - // Aircraft is landed and no need to bail out - set_mode(copter.prev_control_mode, ModeReason::AUTOROTATION_BAILOUT); - } - // Current time uint32_t now = millis(); //milliseconds - // Initialise internal variables - float curr_vel_z = inertial_nav.get_velocity_z_up_cms(); // Current vertical descent - //---------------------------------------------------------------- // State machine logic //---------------------------------------------------------------- @@ -97,12 +87,22 @@ void ModeAutorotate::run() // Timer from entry phase to progress to glide phase if (phase_switch == Autorotation_Phase::ENTRY){ - if ((now - _entry_time_start_ms)/1000.0f > AUTOROTATE_ENTRY_TIME) { // Flight phase can be progressed to steady state glide phase_switch = Autorotation_Phase::SS_GLIDE; } + } + + // Check if we believe we have landed. We need the landed state to zero all controls and make sure that the copter landing detector will trip + bool speed_check = inertial_nav.get_velocity_z_up_cms() < AUTOROTATION_MIN_MOVING_SPEED && + inertial_nav.get_speed_xy_cms() < AUTOROTATION_MIN_MOVING_SPEED; + if (motors->get_below_land_min_coll() && AP::ins().is_still() && speed_check) { + phase_switch = Autorotation_Phase::LANDED; + } + // Check if we are bailing out and need to re-set the spool state + if (motors->autorotation_bailout()) { + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); } @@ -199,79 +199,22 @@ void ModeAutorotate::run() { break; } - - case Autorotation_Phase::BAIL_OUT: + case Autorotation_Phase::LANDED: { - if (_flags.bail_out_initial == true) { - // Functions and settings to be done once are done here. + // Entry phase functions to be run only once + if (_flags.landed_initial == true) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - gcs().send_text(MAV_SEVERITY_INFO, "Bailing Out of Autorotation"); + gcs().send_text(MAV_SEVERITY_INFO, "Landed"); #endif - - // 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); - - // Set bail out start time - _bail_time_start_ms = now; - - // Set initial target vertical speed - _desired_v_z = curr_vel_z; - - // Initialise position and desired velocity - if (!pos_control->is_active_z()) { - pos_control->relax_z_controller(g2.arot.get_last_collective()); - } - - // Get pilot parameter limits - const float pilot_spd_dn = -get_pilot_speed_dn(); - const float pilot_spd_up = g.pilot_speed_up; - - float pilot_des_v_z = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); - pilot_des_v_z = constrain_float(pilot_des_v_z, pilot_spd_dn, pilot_spd_up); - - // Calculate target climb rate adjustment to transition from bail out descent speed to requested climb rate on stick. - _target_climb_rate_adjust = (curr_vel_z - pilot_des_v_z)/(_bail_time - BAILOUT_MOTOR_RAMP_TIME); //accounting for 0.5s motor spool time - - // Calculate pitch target adjustment rate to return to level - _target_pitch_adjust = _pitch_target/_bail_time; - - // set vertical speed and acceleration limits - pos_control->set_max_speed_accel_z(curr_vel_z, pilot_spd_up, fabsf(_target_climb_rate_adjust)); - pos_control->set_correction_speed_accel_z(curr_vel_z, pilot_spd_up, fabsf(_target_climb_rate_adjust)); - - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - - _flags.bail_out_initial = false; + _flags.landed_initial = false; } - - if ((now - _bail_time_start_ms)/1000.0f >= BAILOUT_MOTOR_RAMP_TIME) { - // Update desired vertical speed and pitch target after the bailout motor ramp timer has completed - _desired_v_z -= _target_climb_rate_adjust*G_Dt; - _pitch_target -= _target_pitch_adjust*G_Dt; - } - // Set position controller - pos_control->set_pos_target_z_from_climb_rate_cm(_desired_v_z); - - // Update controllers - pos_control->update_z_controller(); - - if ((now - _bail_time_start_ms)/1000.0f >= _bail_time) { - // Bail out timer complete. Change flight mode. Do not revert back to auto. Prevent aircraft - // from continuing mission and potentially flying further away after a power failure. - if (copter.prev_control_mode == Mode::Number::AUTO) { - set_mode(Mode::Number::ALT_HOLD, ModeReason::AUTOROTATION_BAILOUT); - } else { - set_mode(copter.prev_control_mode, ModeReason::AUTOROTATION_BAILOUT); - } - } - - break; + // don't allow controller to continually ask for more pitch to build speed when we are on the ground, decay to zero smoothly + _pitch_target *= 0.95; + break; } } - switch (nav_pos_switch) { case Navigation_Decision::USER_CONTROL_STABILISED: @@ -282,7 +225,7 @@ void ModeAutorotate::run() get_pilot_desired_lean_angles(pilot_roll, pilot_pitch, copter.aparm.angle_max, copter.aparm.angle_max); // Get pilot's desired yaw rate - float pilot_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float pilot_yaw_rate = get_pilot_desired_yaw_rate(); // Pitch target is calculated in autorotation phase switch above attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pilot_roll, _pitch_target, pilot_yaw_rate); diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 0a7da76b07932f..a997e1ea1cc71b 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -4,7 +4,7 @@ autotune mode is a wrapper around the AC_AutoTune library */ -#if AUTOTUNE_ENABLED == ENABLED +#if AUTOTUNE_ENABLED bool AutoTune::init() { @@ -38,30 +38,20 @@ void AutoTune::run() // apply SIMPLE mode transform to pilot inputs copter.update_simple_mode(); - // reset target lean angles and heading while landed + // disarm when the landing detector says we've landed and spool state is ground idle + if (copter.ap.land_complete && motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) { + copter.arming.disarm(AP_Arming::Method::LANDED); + } + + // if not armed set throttle to zero and exit immediately if (copter.ap.land_complete) { - // we are landed, shut down - float target_climb_rate = get_pilot_desired_climb_rate_cms(); - - // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) - if (target_climb_rate < 0.0f) { - copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); - } else { - copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - } - copter.attitude_control->reset_rate_controller_I_terms_smoothly(); - copter.attitude_control->reset_yaw_target_and_rate(); - - float target_roll, target_pitch, target_yaw_rate; - get_pilot_desired_rp_yrate_cd(target_roll, target_pitch, target_yaw_rate); - - copter.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); - copter.pos_control->relax_z_controller(0.0f); - copter.pos_control->update_z_controller(); - } else { - // run autotune mode - AC_AutoTune::run(); + copter.flightmode->make_safe_ground_handling(); + return; } + + // run autotune mode + AC_AutoTune::run(); + } @@ -85,7 +75,7 @@ void AutoTune::get_pilot_desired_rp_yrate_cd(float &des_roll_cd, float &des_pitc { copter.mode_autotune.get_pilot_desired_lean_angles(des_roll_cd, des_pitch_cd, copter.aparm.angle_max, copter.attitude_control->get_althold_lean_angle_max_cd()); - yaw_rate_cds = copter.mode_autotune.get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz()); + yaw_rate_cds = copter.mode_autotune.get_pilot_desired_yaw_rate(); } /* @@ -128,19 +118,9 @@ void ModeAutoTune::run() autotune.run(); } -void ModeAutoTune::save_tuning_gains() -{ - autotune.save_tuning_gains(); -} - void ModeAutoTune::exit() { autotune.stop(); } -void ModeAutoTune::reset() -{ - autotune.reset(); -} - -#endif // AUTOTUNE_ENABLED == ENABLED +#endif // AUTOTUNE_ENABLED diff --git a/ArduCopter/mode_brake.cpp b/ArduCopter/mode_brake.cpp index 65a353ebc78296..f5c4d6b3fc899a 100644 --- a/ArduCopter/mode_brake.cpp +++ b/ArduCopter/mode_brake.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_BRAKE_ENABLED == ENABLED +#if MODE_BRAKE_ENABLED /* * Init and run calls for brake flight mode diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index bb9a6612f948c5..476bdc2bb33200 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #include -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED /* * Init and run calls for circle flight mode @@ -22,17 +22,16 @@ bool ModeCircle::init(bool ignore_checks) copter.circle_nav->init(); #if HAL_MOUNT_ENABLED - AP_Mount *s = AP_Mount::get_singleton(); - // Check if the CIRCLE_OPTIONS parameter have roi_at_center if (copter.circle_nav->roi_at_center()) { const Vector3p &pos { copter.circle_nav->get_center() }; Location circle_center; - if (!AP::ahrs().get_location_from_origin_offset(circle_center, pos * 0.01)) { + if (!AP::ahrs().get_location_from_origin_offset_NED(circle_center, pos * 0.01)) { return false; } // point at the ground: circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN); + AP_Mount *s = AP_Mount::get_singleton(); s->set_roi_target(circle_center); } #endif @@ -69,7 +68,7 @@ void ModeCircle::run() } // update the orbicular rate target based on pilot roll stick inputs - // skip if using CH6 tuning knob for circle rate + // skip if using transmitter based tuning knob for circle rate if (g.radio_tuning != TUNING_CIRCLE_RATE) { const float roll_stick = channel_roll->norm_input_dz(); // roll stick normalized -1 to 1 @@ -115,8 +114,10 @@ void ModeCircle::run() // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif copter.failsafe_terrain_set_status(copter.circle_nav->update(target_climb_rate)); pos_control->update_z_controller(); diff --git a/ArduCopter/mode_drift.cpp b/ArduCopter/mode_drift.cpp index 9b48478c5a52c0..985e3ba23e717b 100644 --- a/ArduCopter/mode_drift.cpp +++ b/ArduCopter/mode_drift.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_DRIFT_ENABLED == ENABLED +#if MODE_DRIFT_ENABLED /* * Init and run calls for drift flight mode diff --git a/ArduCopter/mode_flip.cpp b/ArduCopter/mode_flip.cpp index 938b44db7db10e..76bc5bf784e431 100644 --- a/ArduCopter/mode_flip.cpp +++ b/ArduCopter/mode_flip.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_FLIP_ENABLED == ENABLED +#if MODE_FLIP_ENABLED /* * Init and run calls for flip flight mode diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index f5414e9dac29e6..467ef545cca21b 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #include -#if MODE_FLOWHOLD_ENABLED == ENABLED +#if MODE_FLOWHOLD_ENABLED /* implement FLOWHOLD mode, for position hold using optical flow @@ -240,7 +240,7 @@ void ModeFlowHold::run() // check for filter change if (!is_equal(flow_filter.get_cutoff_freq(), flow_filter_hz.get())) { - flow_filter.set_cutoff_frequency(flow_filter_hz.get()); + flow_filter.set_cutoff_frequency(copter.scheduler.get_loop_rate_hz(), flow_filter_hz.get()); } // get pilot desired climb rate @@ -248,7 +248,7 @@ void ModeFlowHold::run() target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), copter.g.pilot_speed_up); // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(copter.channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); // Flow Hold State Machine Determination AltHoldModeState flowhold_state = get_alt_hold_state(target_climb_rate); @@ -263,7 +263,7 @@ void ModeFlowHold::run() // Flow Hold State Machine switch (flowhold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); copter.attitude_control->reset_rate_controller_I_terms(); copter.attitude_control->reset_yaw_target_and_rate(); @@ -271,7 +271,7 @@ void ModeFlowHold::run() flow_pi_xy.reset_I(); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // set motors to full range copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); @@ -287,23 +287,25 @@ void ModeFlowHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); diff --git a/ArduCopter/mode_follow.cpp b/ArduCopter/mode_follow.cpp index 9d9ef816a0e866..333864364839a7 100644 --- a/ArduCopter/mode_follow.cpp +++ b/ArduCopter/mode_follow.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED /* * mode_follow.cpp - follow another mavlink-enabled vehicle by system id @@ -172,4 +172,4 @@ bool ModeFollow::get_wp(Location &loc) const return true; } -#endif // MODE_FOLLOW_ENABLED == ENABLED +#endif // MODE_FOLLOW_ENABLED diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index e52bfdae310128..ba0321a1444ecd 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -1,13 +1,13 @@ #include "Copter.h" -#if MODE_GUIDED_ENABLED == ENABLED +#if MODE_GUIDED_ENABLED /* * Init and run calls for guided flight mode */ static Vector3p guided_pos_target_cm; // position target (used by posvel controller only) -bool guided_pos_terrain_alt; // true if guided_pos_target_cm.z is an alt above terrain +static bool guided_pos_terrain_alt; // true if guided_pos_target_cm.z is an alt above terrain static Vector3f guided_vel_target_cms; // velocity target (used by pos_vel_accel controller and vel_accel controller) static Vector3f guided_accel_target_cmss; // acceleration target (used by pos_vel_accel controller vel_accel controller and accel controller) static uint32_t update_time_ms; // system time of last target update to pos_vel_accel, vel_accel or accel controller @@ -15,7 +15,7 @@ static uint32_t update_time_ms; // system time of last target update struct { uint32_t update_time_ms; Quaternion attitude_quat; - Vector3f ang_vel; + Vector3f ang_vel_body; float yaw_rate_cds; float climb_rate_cms; // climb rate in cms. Used if use_thrust is false float thrust; // thrust from -1 to 1. Used if use_thrust is true @@ -30,7 +30,15 @@ struct Guided_Limit { float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit) uint32_t start_time;// system time in milliseconds that control was handed to the external computer Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit -} guided_limit; +} static guided_limit; + +// controls which controller is run (pos or vel): +ModeGuided::SubMode ModeGuided::guided_mode = SubMode::TakeOff; +bool ModeGuided::send_notification; // used to send one time notification to ground station +bool ModeGuided::takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear) + +// guided mode is paused or not +bool ModeGuided::_paused; // init - initialise guided controller bool ModeGuided::init(bool ignore_checks) @@ -97,6 +105,12 @@ void ModeGuided::run() } } +// returns true if the Guided-mode-option is set (see GUID_OPTIONS) +bool ModeGuided::option_is_enabled(Option option) const +{ + return (copter.g2.guided_options.get() & (uint32_t)option) != 0; +} + bool ModeGuided::allows_arming(AP_Arming::Method method) const { // always allow arming from the ground station or scripting @@ -105,13 +119,13 @@ bool ModeGuided::allows_arming(AP_Arming::Method method) const } // optionally allow arming from the transmitter - return (copter.g2.guided_options & (uint32_t)Options::AllowArmingFromTX) != 0; + return option_is_enabled(Option::AllowArmingFromTX); }; -#if WEATHERVANE_ENABLED == ENABLED +#if WEATHERVANE_ENABLED bool ModeGuided::allows_weathervaning() const { - return (copter.g2.guided_options.get() & (uint32_t)Options::AllowWeatherVaning) != 0; + return option_is_enabled(Option::AllowWeatherVaning); } #endif @@ -122,6 +136,7 @@ bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm) // 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 AP_RANGEFINDER_ENABLED 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)) { @@ -132,7 +147,9 @@ bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm) // provide target altitude as alt-above-terrain alt_target_cm = takeoff_alt_cm; alt_target_terrain = true; - } else { + } else +#endif + { // interpret altitude as alt-above-home Location target_loc = copter.current_loc; target_loc.set_alt_cm(takeoff_alt_cm, Location::AltFrame::ABOVE_HOME); @@ -237,10 +254,10 @@ void ModeGuided::pos_control_start() pva_control_start(); } -// initialise guided mode's velocity controller +// initialise guided mode's acceleration controller void ModeGuided::accel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to acceleration controller guided_mode = SubMode::Accel; // initialise position controller @@ -250,7 +267,7 @@ void ModeGuided::accel_control_start() // initialise guided mode's velocity and acceleration controller void ModeGuided::velaccel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to velocity and acceleration controller guided_mode = SubMode::VelAccel; // initialise position controller @@ -260,7 +277,7 @@ void ModeGuided::velaccel_control_start() // initialise guided mode's position, velocity and acceleration controller void ModeGuided::posvelaccel_control_start() { - // set guided_mode to velocity controller + // set guided_mode to position, velocity and acceleration controller guided_mode = SubMode::PosVelAccel; // initialise position controller @@ -314,7 +331,7 @@ void ModeGuided::angle_control_start() // initialise targets guided_angle_state.update_time_ms = millis(); guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z)); - guided_angle_state.ang_vel.zero(); + guided_angle_state.ang_vel_body.zero(); guided_angle_state.climb_rate_cms = 0.0f; guided_angle_state.yaw_rate_cds = 0.0f; guided_angle_state.use_yaw_rate = false; @@ -374,10 +391,10 @@ bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, floa // convert origin to alt-above-terrain if necessary if (!guided_pos_terrain_alt) { // new destination is alt-above-terrain, previous destination was alt-above-ekf-origin - pos_control->set_pos_offset_z_cm(origin_terr_offset); + pos_control->init_pos_terrain_cm(origin_terr_offset); } } else { - pos_control->set_pos_offset_z_cm(0.0); + pos_control->init_pos_terrain_cm(0.0); } // set yaw state @@ -408,11 +425,14 @@ bool ModeGuided::get_wp(Location& destination) const case SubMode::Pos: destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); return true; - default: - return false; + case SubMode::Angle: + case SubMode::TakeOff: + case SubMode::Accel: + case SubMode::VelAccel: + case SubMode::PosVelAccel: + break; } - // should never get here but just in case return false; } @@ -456,6 +476,13 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y return true; } + // set position target and zero velocity and acceleration + Vector3f pos_target_f; + bool terrain_alt; + if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) { + return false; + } + // if configured to use position controller for position control // ensure we are in position control mode if (guided_mode != SubMode::Pos) { @@ -465,13 +492,6 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // set yaw state set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); - // set position target and zero velocity and acceleration - Vector3f pos_target_f; - bool terrain_alt; - if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) { - return false; - } - // initialise terrain following if needed if (terrain_alt) { // get current alt above terrain @@ -484,10 +504,10 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // convert origin to alt-above-terrain if necessary if (!guided_pos_terrain_alt) { // new destination is alt-above-terrain, previous destination was alt-above-ekf-origin - pos_control->set_pos_offset_z_cm(origin_terr_offset); + pos_control->init_pos_terrain_cm(origin_terr_offset); } } else { - pos_control->set_pos_offset_z_cm(0.0); + pos_control->init_pos_terrain_cm(0.0); } guided_pos_target_cm = pos_target_f.topostype(); @@ -509,7 +529,7 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // set_velaccel - sets guided mode's target velocity and acceleration void ModeGuided::set_accel(const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request) { - // check we are in velocity control mode + // check we are in acceleration control mode if (guided_mode != SubMode::Accel) { accel_control_start(); } @@ -541,7 +561,7 @@ void ModeGuided::set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_ // set_velaccel - sets guided mode's target velocity and acceleration void ModeGuided::set_velaccel(const Vector3f& velocity, const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool log_request) { - // check we are in velocity control mode + // check we are in velocity and acceleration control mode if (guided_mode != SubMode::VelAccel) { velaccel_control_start(); } @@ -583,7 +603,7 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const } #endif - // check we are in velocity control mode + // check we are in position, velocity and acceleration control mode if (guided_mode != SubMode::PosVelAccel) { posvelaccel_control_start(); } @@ -607,43 +627,46 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const // returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate bool ModeGuided::set_attitude_target_provides_thrust() const { - return ((copter.g2.guided_options.get() & uint32_t(Options::SetAttitudeTarget_ThrustAsThrust)) != 0); + return option_is_enabled(Option::SetAttitudeTarget_ThrustAsThrust); } // returns true if GUIDED_OPTIONS param specifies position should be controlled (when velocity and/or acceleration control is active) bool ModeGuided::stabilizing_pos_xy() const { - return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizePositionXY)) != 0); + return !option_is_enabled(Option::DoNotStabilizePositionXY); } // returns true if GUIDED_OPTIONS param specifies velocity should be controlled (when acceleration control is active) bool ModeGuided::stabilizing_vel_xy() const { - return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizeVelocityXY)) != 0); + return !option_is_enabled(Option::DoNotStabilizeVelocityXY); } // returns true if GUIDED_OPTIONS param specifies waypoint navigation should be used for position control (allow path planning to be used but updates must be slower) bool ModeGuided::use_wpnav_for_position_control() const { - return ((copter.g2.guided_options.get() & uint32_t(Options::WPNavUsedForPosControl)) != 0); + return option_is_enabled(Option::WPNavUsedForPosControl); } // Sets guided's angular target submode: Using a rotation quaternion, angular velocity, and climbrate or thrust (depends on user option) -// attitude_quat: IF zero: ang_vel (angular velocity) must be provided even if all zeroes -// IF non-zero: attitude_control is performed using both the attitude quaternion and angular velocity -// ang_vel: angular velocity (rad/s) +// attitude_quat: IF zero: ang_vel_body (body frame angular velocity) must be provided even if all zeroes +// IF non-zero: attitude_control is performed using both the attitude quaternion and body frame angular velocity +// ang_vel_body: body frame angular velocity (rad/s) // climb_rate_cms_or_thrust: represents either the climb_rate (cm/s) or thrust scaled from [0, 1], unitless // use_thrust: IF true: climb_rate_cms_or_thrust represents thrust // IF false: climb_rate_cms_or_thrust represents climb_rate (cm/s) -void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_vel, float climb_rate_cms_or_thrust, bool use_thrust) +void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_vel_body, float climb_rate_cms_or_thrust, bool use_thrust) { // check we are in velocity control mode if (guided_mode != SubMode::Angle) { angle_control_start(); + } else if (!use_thrust && guided_angle_state.use_thrust) { + // Already angle control but changing from thrust to climb rate + pos_control->init_z_controller(); } guided_angle_state.attitude_quat = attitude_quat; - guided_angle_state.ang_vel = ang_vel; + guided_angle_state.ang_vel_body = ang_vel_body; guided_angle_state.use_thrust = use_thrust; if (use_thrust) { @@ -662,7 +685,7 @@ void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_ #if HAL_LOGGING_ENABLED // log target - copter.Log_Write_Guided_Attitude_Target(guided_mode, roll_rad, pitch_rad, yaw_rad, ang_vel, guided_angle_state.thrust, guided_angle_state.climb_rate_cms * 0.01); + copter.Log_Write_Guided_Attitude_Target(guided_mode, roll_rad, pitch_rad, yaw_rad, ang_vel_body, guided_angle_state.thrust, guided_angle_state.climb_rate_cms * 0.01); #endif } @@ -673,6 +696,9 @@ void ModeGuided::takeoff_run() auto_takeoff.run(); if (auto_takeoff.complete && !takeoff_complete) { takeoff_complete = true; +#if AP_FENCE_ENABLED + copter.fence.auto_enable_fence_after_takeoff(); +#endif #if AP_LANDINGGEAR_ENABLED // optionally retract landing gear copter.landinggear.retract_after_takeoff(); @@ -807,8 +833,7 @@ void ModeGuided::velaccel_control_run() if (!stabilizing_vel_xy() && !do_avoid) { // set the current commanded xy vel to the desired vel - guided_vel_target_cms.x = pos_control->get_vel_desired_cms().x; - guided_vel_target_cms.y = pos_control->get_vel_desired_cms().y; + guided_vel_target_cms.xy() = pos_control->get_vel_desired_cms().xy(); } pos_control->input_vel_accel_xy(guided_vel_target_cms.xy(), guided_accel_target_cmss.xy(), false); if (!stabilizing_vel_xy() && !do_avoid) { @@ -885,14 +910,11 @@ void ModeGuided::posvelaccel_control_run() // send position and velocity targets to position controller if (!stabilizing_vel_xy()) { // set the current commanded xy pos to the target pos and xy vel to the desired vel - guided_pos_target_cm.x = pos_control->get_pos_target_cm().x; - guided_pos_target_cm.y = pos_control->get_pos_target_cm().y; - guided_vel_target_cms.x = pos_control->get_vel_desired_cms().x; - guided_vel_target_cms.y = pos_control->get_vel_desired_cms().y; + guided_pos_target_cm.xy() = pos_control->get_pos_desired_cm().xy(); + guided_vel_target_cms.xy() = pos_control->get_vel_desired_cms().xy(); } else if (!stabilizing_pos_xy()) { // set the current commanded xy pos to the target pos - guided_pos_target_cm.x = pos_control->get_pos_target_cm().x; - guided_pos_target_cm.y = pos_control->get_pos_target_cm().y; + guided_pos_target_cm.xy() = pos_control->get_pos_desired_cm().xy(); } pos_control->input_pos_vel_accel_xy(guided_pos_target_cm.xy(), guided_vel_target_cms.xy(), guided_accel_target_cmss.xy(), false); if (!stabilizing_vel_xy()) { @@ -937,7 +959,7 @@ void ModeGuided::angle_control_run() uint32_t tnow = millis(); if (tnow - guided_angle_state.update_time_ms > get_timeout_ms()) { guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z)); - guided_angle_state.ang_vel.zero(); + guided_angle_state.ang_vel_body.zero(); climb_rate_cms = 0.0f; if (guided_angle_state.use_thrust) { // initialise vertical velocity controller @@ -960,8 +982,8 @@ void ModeGuided::angle_control_run() } // TODO: use get_alt_hold_state - // landed with positive desired climb rate, takeoff - if (copter.ap.land_complete && (guided_angle_state.climb_rate_cms > 0.0f)) { + // landed with positive desired climb rate or thrust, takeoff + if (copter.ap.land_complete && positive_thrust_or_climbrate) { zero_throttle_and_relax_ac(); motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { @@ -976,9 +998,9 @@ void ModeGuided::angle_control_run() // call attitude controller if (guided_angle_state.attitude_quat.is_zero()) { - attitude_control->input_rate_bf_roll_pitch_yaw(ToDeg(guided_angle_state.ang_vel.x) * 100.0f, ToDeg(guided_angle_state.ang_vel.y) * 100.0f, ToDeg(guided_angle_state.ang_vel.z) * 100.0f); + attitude_control->input_rate_bf_roll_pitch_yaw(ToDeg(guided_angle_state.ang_vel_body.x) * 100.0f, ToDeg(guided_angle_state.ang_vel_body.y) * 100.0f, ToDeg(guided_angle_state.ang_vel_body.z) * 100.0f); } else { - attitude_control->input_quaternion(guided_angle_state.attitude_quat, guided_angle_state.ang_vel); + attitude_control->input_quaternion(guided_angle_state.attitude_quat, guided_angle_state.ang_vel_body); } // call position controller @@ -1009,7 +1031,7 @@ void ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, fl // returns true if pilot's yaw input should be used to adjust vehicle's heading bool ModeGuided::use_pilot_yaw(void) const { - return (copter.g2.guided_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0; + return !option_is_enabled(Option::IgnorePilotYaw); } // Guided Limit code diff --git a/ArduCopter/mode_guided_custom.cpp b/ArduCopter/mode_guided_custom.cpp new file mode 100644 index 00000000000000..322ed74a1f0085 --- /dev/null +++ b/ArduCopter/mode_guided_custom.cpp @@ -0,0 +1,23 @@ +#include "Copter.h" + +#if MODE_GUIDED_ENABLED && AP_SCRIPTING_ENABLED +// constructor registers custom number and names +ModeGuidedCustom::ModeGuidedCustom(const Number _number, const char* _full_name, const char* _short_name): + number(_number), + full_name(_full_name), + short_name(_short_name) +{ +} + +bool ModeGuidedCustom::init(bool ignore_checks) +{ + // Stript can block entry + if (!state.allow_entry) { + return false; + } + + // Guided entry checks must also pass + return ModeGuided::init(ignore_checks); +} + +#endif diff --git a/ArduCopter/mode_guided_nogps.cpp b/ArduCopter/mode_guided_nogps.cpp index b74aaf8f2bf720..f17e0326a12cd1 100644 --- a/ArduCopter/mode_guided_nogps.cpp +++ b/ArduCopter/mode_guided_nogps.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_GUIDED_NOGPS_ENABLED == ENABLED +#if MODE_GUIDED_NOGPS_ENABLED /* * Init and run calls for guided_nogps flight mode diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 1f34e20fbf3380..2b5b6e8879260f 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -41,11 +41,6 @@ bool ModeLand::init(bool ignore_checks) copter.landinggear.deploy_for_landing(); #endif -#if AP_FENCE_ENABLED - // disable the fence on landing - copter.fence.auto_disable_fence_for_landing(); -#endif - #if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 602aa52859a151..752f4f6115739b 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_LOITER_ENABLED == ENABLED +#if MODE_LOITER_ENABLED /* * Init and run calls for loiter flight mode @@ -102,7 +102,7 @@ void ModeLoiter::run() loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch); // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); @@ -123,7 +123,7 @@ void ModeLoiter::run() // Loiter State Machine switch (loiter_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,18 +131,18 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::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, false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -161,7 +161,7 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); @@ -191,8 +191,10 @@ void ModeLoiter::run() // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index 7b47eeb7c3592a..5474aaa84151fa 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_POSHOLD_ENABLED == ENABLED +#if MODE_POSHOLD_ENABLED /* * Init and run calls for PosHold flight mode @@ -83,7 +83,7 @@ void ModePosHold::run() get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd()); // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate (for alt-hold mode and take-off) float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); @@ -100,7 +100,7 @@ void ModePosHold::run() // state machine switch (poshold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -115,14 +115,14 @@ void ModePosHold::run() init_wind_comp_estimate(); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); attitude_control->reset_yaw_target_and_rate(); init_wind_comp_estimate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,7 +131,7 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -152,14 +152,16 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); @@ -375,7 +377,7 @@ void ModePosHold::run() pitch_mode = RPMode::BRAKE_TO_LOITER; brake.to_loiter_timer = POSHOLD_BRAKE_TO_LOITER_TIMER; // init loiter controller - loiter_nav->init_target(inertial_nav.get_position_xy_cm()); + loiter_nav->init_target(inertial_nav.get_position_xy_cm() - pos_control->get_pos_offset_cm().xy().tofloat()); // set delay to start of wind compensation estimate updates wind_comp_start_timer = POSHOLD_WIND_COMP_START_TIMER; } @@ -533,11 +535,7 @@ void ModePosHold::update_brake_angle_from_velocity(float &brake_angle, float vel } // calculate velocity-only based lean angle - if (velocity >= 0) { - lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (velocity + 60.0f)); - } else { - lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (-velocity + 60.0f)); - } + lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (fabsf(velocity) + 60.0f)); // do not let lean_angle be too far from brake_angle brake_angle = constrain_float(lean_angle, brake_angle - brake_rate, brake_angle + brake_rate); @@ -590,7 +588,7 @@ void ModePosHold::update_wind_comp_estimate() } // limit acceleration - const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * 981.0f; + const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * (GRAVITY_MSS*100); const float wind_comp_ef_len = wind_comp_ef.length(); if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) { wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len; diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index d3250e4265642f..8d7bba2dd332ae 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_RTL_ENABLED == ENABLED +#if MODE_RTL_ENABLED /* * Init and run calls for RTL flight mode @@ -52,11 +52,11 @@ ModeRTL::RTLAltType ModeRTL::get_alt_type() const { // sanity check parameter switch ((ModeRTL::RTLAltType)g.rtl_alt_type) { - case RTLAltType::RTL_ALTTYPE_RELATIVE ... RTLAltType::RTL_ALTTYPE_TERRAIN: + case RTLAltType::RELATIVE ... RTLAltType::TERRAIN: return g.rtl_alt_type; } // user has an invalid value - return RTLAltType::RTL_ALTTYPE_RELATIVE; + return RTLAltType::RELATIVE; } // rtl_run - runs the return-to-launch controller @@ -255,11 +255,6 @@ void ModeRTL::descent_start() // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif - -#if AP_FENCE_ENABLED - // disable the fence on landing - copter.fence.auto_disable_fence_for_landing(); -#endif } // rtl_descent_run - implements the final descent to the RTL_ALT @@ -347,11 +342,6 @@ void ModeRTL::land_start() // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif - -#if AP_FENCE_ENABLED - // disable the fence on landing - copter.fence.auto_disable_fence_for_landing(); -#endif } bool ModeRTL::is_landing() const @@ -415,12 +405,15 @@ void ModeRTL::compute_return_target() rtl_path.return_target = ahrs.get_home(); #endif + // get position controller Z-axis offset in cm above EKF origin + int32_t pos_offset_z = pos_control->get_pos_offset_z_cm(); + // curr_alt is current altitude above home or above terrain depending upon use_terrain - int32_t curr_alt = copter.current_loc.alt; + int32_t curr_alt = copter.current_loc.alt - pos_offset_z; // determine altitude type of return journey (alt-above-home, alt-above-terrain using range finder or alt-above-terrain using terrain database) ReturnTargetAltType alt_type = ReturnTargetAltType::RELATIVE; - if (terrain_following_allowed && (get_alt_type() == RTLAltType::RTL_ALTTYPE_TERRAIN)) { + if (terrain_following_allowed && (get_alt_type() == RTLAltType::TERRAIN)) { // convert RTL_ALT_TYPE and WPNAV_RFNG_USE parameters to ReturnTargetAltType switch (wp_nav->get_terrain_source()) { case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE: @@ -440,6 +433,8 @@ void ModeRTL::compute_return_target() // set curr_alt and return_target.alt from range finder if (alt_type == ReturnTargetAltType::RANGEFINDER) { if (copter.get_rangefinder_height_interpolated_cm(curr_alt)) { + // subtract position controller offset + curr_alt -= pos_offset_z; // set return_target.alt rtl_path.return_target.set_alt_cm(MAX(curr_alt + MAX(0, g.rtl_climb_min), MAX(g.rtl_altitude, RTL_ALT_MIN)), Location::AltFrame::ABOVE_TERRAIN); } else { @@ -458,7 +453,7 @@ void ModeRTL::compute_return_target() int32_t curr_terr_alt; if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt) && rtl_path.return_target.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) { - curr_alt = curr_terr_alt; + curr_alt = curr_terr_alt - pos_offset_z; } else { // fallback to relative alt and warn user alt_type = ReturnTargetAltType::RELATIVE; diff --git a/ArduCopter/mode_smart_rtl.cpp b/ArduCopter/mode_smart_rtl.cpp index dacd7cc5f29ab0..4ef2160282bc6e 100644 --- a/ArduCopter/mode_smart_rtl.cpp +++ b/ArduCopter/mode_smart_rtl.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED /* * Init and run calls for Smart_RTL flight mode @@ -35,6 +35,14 @@ bool ModeSmartRTL::init(bool ignore_checks) // perform cleanup required when leaving smart_rtl void ModeSmartRTL::exit() { + // restore last point if we hadn't reached it + if (smart_rtl_state == SubMode::PATH_FOLLOW && !dest_NED_backup.is_zero()) { + if (!g2.smart_rtl.add_point(dest_NED_backup)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "SmartRTL: lost one point"); + } + } + dest_NED_backup.zero(); + g2.smart_rtl.cancel_request_for_thorough_cleanup(); } @@ -83,10 +91,16 @@ void ModeSmartRTL::path_follow_run() { // if we are close to current target point, switch the next point to be our target. if (wp_nav->reached_wp_destination()) { - Vector3f dest_NED; + + // clear destination backup so that it cannot be restored + dest_NED_backup.zero(); + // this pop_point can fail if the IO task currently has the // path semaphore. + Vector3f dest_NED; if (g2.smart_rtl.pop_point(dest_NED)) { + // backup destination in case we exit smart_rtl mode and need to restore it to the path + dest_NED_backup = dest_NED; path_follow_last_pop_fail_ms = 0; if (g2.smart_rtl.get_num_points() == 0) { // this is the very last point, add 2m to the target alt and move to pre-land state diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 954a5a2b984d06..249fa06ee507dc 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_SPORT_ENABLED == ENABLED +#if MODE_SPORT_ENABLED /* * Init and run calls for sport flight mode @@ -62,7 +62,7 @@ void ModeSport::run() } // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); @@ -74,22 +74,22 @@ void ModeSport::run() // State Machine switch (sport_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -102,14 +102,16 @@ void ModeSport::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); diff --git a/ArduCopter/mode_stabilize.cpp b/ArduCopter/mode_stabilize.cpp index 5dbf2d4bdc471b..301bf991f4dac3 100644 --- a/ArduCopter/mode_stabilize.cpp +++ b/ArduCopter/mode_stabilize.cpp @@ -16,7 +16,7 @@ void ModeStabilize::run() get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max); // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); if (!motors->armed()) { // Motors should be Stopped diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index e9caa4212b4bcd..4260e4f9aa6afe 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -31,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 - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot's desired throttle pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); @@ -77,8 +77,8 @@ void ModeStabilize_Heli::run() // call attitude controller attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); - // output pilot's throttle - note that TradHeli does not used angle-boost - attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); + // output pilot's throttle + attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt); } #endif //HELI_FRAME diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 801f903205deb2..db1e0ddc2600ad 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -1,6 +1,7 @@ #include "Copter.h" +#include -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED /* * Init and run calls for systemId, flight mode @@ -12,7 +13,7 @@ const AP_Param::GroupInfo ModeSystemId::var_info[] = { // @DisplayName: System identification axis // @Description: Controls which axis are being excited. Set to non-zero to see more parameters // @User: Standard - // @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust + // @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust, 14:Measured Lateral Position, 15:Measured Longitudinal Position, 16:Measured Lateral Velocity, 17:Measured Longitudinal Velocity, 18:Input Lateral Velocity, 19:Input Longitudinal Velocity AP_GROUPINFO_FLAGS("_AXIS", 1, ModeSystemId, axis, 0, AP_PARAM_FLAG_ENABLE), // @Param: _MAGNITUDE @@ -80,15 +81,58 @@ bool ModeSystemId::init(bool ignore_checks) return false; } - // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high - if (motors->armed() && copter.ap.land_complete && !copter.flightmode->has_manual_throttle()) { + // ensure we are flying + if (!copter.motors->armed() || !copter.ap.auto_armed || copter.ap.land_complete) { + gcs().send_text(MAV_SEVERITY_WARNING, "Aircraft must be flying"); return false; } + if (!is_poscontrol_axis_type()) { + + // System ID is being done on the attitude control loops + + // Can only switch into System ID Axes 1-13 with a flight mode that has manual throttle + if (!copter.flightmode->has_manual_throttle()) { + gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires manual throttle"); + return false; + } + #if FRAME_CONFIG == HELI_FRAME - copter.input_manager.set_use_stab_col(true); + copter.input_manager.set_use_stab_col(true); #endif + } else { + + // System ID is being done on the position control loops + + // Can only switch into System ID Axes 14-19 from Loiter flight mode + if (copter.flightmode->mode_number() != Mode::Number::LOITER) { + gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires switch from Loiter"); + return false; + } + + // 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 (!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(); + } + Vector3f curr_pos; + curr_pos = inertial_nav.get_position_neu_cm(); + target_pos = curr_pos.xy(); + } + att_bf_feedforward = attitude_control->get_bf_feedforward(); waveform_time = 0.0f; time_const_freq = 2.0f / frequency_start; // Two full cycles at the starting frequency @@ -117,65 +161,74 @@ void ModeSystemId::exit() // should be called at 100hz or more void ModeSystemId::run() { - // apply simple mode transform to pilot inputs - update_simple_mode(); - - // convert pilot input to lean angles float target_roll, target_pitch; - get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max); - - // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); - - if (!motors->armed()) { - // Motors should be Stopped - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); - // Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when - // motor interlock is disabled. - } else if (copter.ap.throttle_zero && !copter.is_tradheli()) { - // 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 target_yaw_rate = 0.0f; + float pilot_throttle_scaled = 0.0f; + float target_climb_rate = 0.0f; + Vector2f input_vel; + + if (!is_poscontrol_axis_type()) { + + // 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, copter.aparm.angle_max, copter.aparm.angle_max); + + // get pilot's desired yaw rate + target_yaw_rate = get_pilot_desired_yaw_rate(); + + if (!motors->armed()) { + // Motors should be Stopped + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); + // Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when + // motor interlock is disabled. + } else if (copter.ap.throttle_zero && !copter.is_tradheli()) { + // Attempting to Land + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); + } else { + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); + } - 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(); - break; - - case AP_Motors::SpoolState::GROUND_IDLE: - // Landed - // Tradheli initializes targets when going from disarmed to armed state. - // init_targets_on_arming is always set true for multicopter. - if (motors->init_targets_on_arming()) { + 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_smoothly(); - } - break; + attitude_control->reset_rate_controller_I_terms(); + break; - case AP_Motors::SpoolState::THROTTLE_UNLIMITED: - // clear landing flag above zero throttle - if (!motors->limit.throttle_lower) { - set_land_complete(false); - } - break; + case AP_Motors::SpoolState::GROUND_IDLE: + // Landed + // Tradheli initializes targets when going from disarmed to armed state. + // init_targets_on_arming is always set true for multicopter. + if (motors->init_targets_on_arming()) { + attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_rate_controller_I_terms_smoothly(); + } + break; - case AP_Motors::SpoolState::SPOOLING_UP: - case AP_Motors::SpoolState::SPOOLING_DOWN: - // do nothing - break; - } + case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + // clear landing flag above zero throttle + if (!motors->limit.throttle_lower) { + set_land_complete(false); + } + break; + + case AP_Motors::SpoolState::SPOOLING_UP: + case AP_Motors::SpoolState::SPOOLING_DOWN: + // do nothing + break; + } - // get pilot's desired throttle + // get pilot's desired throttle #if FRAME_CONFIG == HELI_FRAME - float pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); + pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); #else - float pilot_throttle_scaled = get_pilot_desired_throttle(); + pilot_throttle_scaled = get_pilot_desired_throttle(); #endif + } + if ((systemid_state == SystemIDModeState::SYSTEMID_STATE_TESTING) && (!is_positive(frequency_start) || !is_positive(frequency_stop) || is_negative(time_fade_in) || !is_positive(time_record) || is_negative(time_fade_out) || (time_record <= time_const_freq))) { systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED; @@ -185,7 +238,7 @@ void ModeSystemId::run() waveform_time += G_Dt; waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude); waveform_freq_rads = chirp_input.get_frequency_rads(); - + Vector2f disturb_state; switch (systemid_state) { case SystemIDModeState::SYSTEMID_STATE_STOPPED: attitude_control->bf_feedforward(att_bf_feedforward); @@ -255,15 +308,79 @@ void ModeSystemId::run() case AxisType::MIX_THROTTLE: pilot_throttle_scaled += waveform_sample; break; + case AxisType::DISTURB_POS_LAT: + disturb_state.x = 0.0f; + disturb_state.y = waveform_sample * 100.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_pos_cm(disturb_state); + break; + case AxisType::DISTURB_POS_LONG: + disturb_state.x = waveform_sample * 100.0f; + disturb_state.y = 0.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_pos_cm(disturb_state); + break; + case AxisType::DISTURB_VEL_LAT: + disturb_state.x = 0.0f; + disturb_state.y = waveform_sample * 100.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_vel_cms(disturb_state); + break; + case AxisType::DISTURB_VEL_LONG: + disturb_state.x = waveform_sample * 100.0f; + disturb_state.y = 0.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_vel_cms(disturb_state); + break; + case AxisType::INPUT_VEL_LAT: + input_vel.x = 0.0f; + input_vel.y = waveform_sample * 100.0f; + input_vel.rotate(attitude_control->get_att_target_euler_rad().z); + break; + case AxisType::INPUT_VEL_LONG: + input_vel.x = waveform_sample * 100.0f; + input_vel.y = 0.0f; + input_vel.rotate(attitude_control->get_att_target_euler_rad().z); + break; } break; } - // call attitude controller - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); + if (!is_poscontrol_axis_type()) { + + // call attitude controller + 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(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); + + } else { + + // relax loiter target if we might be landed + if (copter.ap.land_complete_maybe) { + pos_control->soften_for_landing_xy(); + } - // output pilot's throttle - attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); + Vector2f accel; + target_pos += input_vel * G_Dt; + if (is_positive(G_Dt)) { + accel = (input_vel - input_vel_last) / G_Dt; + input_vel_last = input_vel; + } + pos_control->set_pos_vel_accel_xy(target_pos.topostype(), input_vel, accel); + + // run pos controller + pos_control->update_xy_controller(); + + // call attitude controller + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate, false); + + // Send the commanded climb rate to the position controller + pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); + + // run the vertical position controller and set output throttle + pos_control->update_z_controller(); + } if (log_subsample <= 0) { log_data(); @@ -298,6 +415,33 @@ void ModeSystemId::log_data() const // Full rate logging of attitude, rate and pid loops copter.Log_Write_Attitude(); copter.Log_Write_PIDS(); + + if (is_poscontrol_axis_type()) { + pos_control->write_log(); + copter.logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x()); + copter.logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y()); + + } +} + +bool ModeSystemId::is_poscontrol_axis_type() const +{ + bool ret = false; + + switch ((AxisType)axis.get()) { + case AxisType::DISTURB_POS_LAT: + case AxisType::DISTURB_POS_LONG: + case AxisType::DISTURB_VEL_LAT: + case AxisType::DISTURB_VEL_LONG: + case AxisType::INPUT_VEL_LAT: + case AxisType::INPUT_VEL_LONG: + ret = true; + break; + default: + break; + } + + return ret; } #endif diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 884b7a22be88d5..835a4e27aade00 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED // throw_init - initialise throw controller bool ModeThrow::init(bool ignore_checks) @@ -72,9 +72,9 @@ void ModeThrow::run() // initialise the demanded height to 3m above the throw height // we want to rapidly clear surrounding obstacles if (g2.throw_type == ThrowType::Drop) { - pos_control->set_pos_target_z_cm(inertial_nav.get_position_z_up_cm() - 100); + pos_control->set_pos_desired_z_cm(inertial_nav.get_position_z_up_cm() - 100); } else { - pos_control->set_pos_target_z_cm(inertial_nav.get_position_z_up_cm() + 300); + pos_control->set_pos_desired_z_cm(inertial_nav.get_position_z_up_cm() + 300); } // Set the auto_arm status to true to avoid a possible automatic disarm caused by selection of an auto mode with throttle at minimum diff --git a/ArduCopter/mode_turtle.cpp b/ArduCopter/mode_turtle.cpp index 94728d6a29be9d..8f246ef1603918 100644 --- a/ArduCopter/mode_turtle.cpp +++ b/ArduCopter/mode_turtle.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_TURTLE_ENABLED == ENABLED +#if MODE_TURTLE_ENABLED #define CRASH_FLIP_EXPO 35.0f #define CRASH_FLIP_STICK_MINF 0.15f diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index fbf43aa50ed458..7c39fb73807931 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if MODE_ZIGZAG_ENABLED == ENABLED +#if MODE_ZIGZAG_ENABLED /* * Init and run calls for zigzag flight mode @@ -161,7 +161,7 @@ void ModeZigZag::run() void ModeZigZag::save_or_move_to_destination(Destination ab_dest) { // get current position as an offset from EKF origin - const Vector2f curr_pos {inertial_nav.get_position_xy_cm()}; + const Vector2f curr_pos = pos_control->get_pos_desired_cm().xy().tofloat(); // handle state machine changes switch (stage) { @@ -170,12 +170,12 @@ void ModeZigZag::save_or_move_to_destination(Destination ab_dest) if (ab_dest == Destination::A) { // store point A dest_A = curr_pos; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point A stored"); + gcs().send_text(MAV_SEVERITY_INFO, "%s: point A stored", name()); LOGGER_WRITE_EVENT(LogEvent::ZIGZAG_STORE_A); } else { // store point B dest_B = curr_pos; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point B stored"); + gcs().send_text(MAV_SEVERITY_INFO, "%s: point B stored", name()); LOGGER_WRITE_EVENT(LogEvent::ZIGZAG_STORE_B); } // if both A and B have been stored advance state @@ -203,10 +203,10 @@ void ModeZigZag::save_or_move_to_destination(Destination ab_dest) spray(true); reach_wp_time_ms = 0; if (is_auto == false || line_num == ZIGZAG_LINE_INFINITY) { - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: moving to %s", (ab_dest == Destination::A) ? "A" : "B"); + gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s", name(), (ab_dest == Destination::A) ? "A" : "B"); } else { line_count++; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: moving to %s (line %d/%d)", (ab_dest == Destination::A) ? "A" : "B", line_count, line_num); + gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s (line %d/%d)", name(), (ab_dest == Destination::A) ? "A" : "B", line_count, line_num); } } } @@ -228,7 +228,7 @@ void ModeZigZag::move_to_side() current_terr_alt = terr_alt; reach_wp_time_ms = 0; char const *dir[] = {"forward", "right", "backward", "left"}; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: moving to %s", dir[(uint8_t)zigzag_direction]); + gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s", name(), dir[(uint8_t)zigzag_direction]); } } } @@ -244,14 +244,16 @@ void ModeZigZag::return_to_manual_control(bool maintain_target) if (maintain_target) { const Vector3f& wp_dest = wp_nav->get_wp_destination(); loiter_nav->init_target(wp_dest.xy()); - if (wp_nav->origin_and_destination_are_terrain_alt()) { - copter.surface_tracking.set_target_alt_cm(wp_dest.z); +#if AP_RANGEFINDER_ENABLED + if (copter.rangefinder_alt_ok() && wp_nav->rangefinder_used_and_healthy()) { + copter.surface_tracking.external_init(); } +#endif } else { loiter_nav->init_target(); } is_auto = false; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: manual control"); + gcs().send_text(MAV_SEVERITY_INFO, "%s: manual control", name()); } } @@ -262,7 +264,7 @@ void ModeZigZag::auto_control() float target_yaw_rate = 0; if (!copter.failsafe.radio) { // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + target_yaw_rate = get_pilot_desired_yaw_rate(); } // set motors to full range @@ -303,7 +305,7 @@ void ModeZigZag::manual_control() // process pilot's roll and pitch input loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch); // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); @@ -326,7 +328,7 @@ void ModeZigZag::manual_control() // althold state machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -334,7 +336,7 @@ void ModeZigZag::manual_control() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -353,18 +355,18 @@ void ModeZigZag::manual_control() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::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); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); @@ -377,8 +379,10 @@ void ModeZigZag::manual_control() // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); +#if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); +#endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); @@ -427,7 +431,7 @@ bool ModeZigZag::calculate_next_dest(Destination ab_dest, bool use_wpnav_alt, Ve } // get distance from vehicle to start_pos - const Vector2f curr_pos2d {inertial_nav.get_position_xy_cm()}; + const Vector2f curr_pos2d = pos_control->get_pos_desired_cm().xy().tofloat(); Vector2f veh_to_start_pos = curr_pos2d - start_pos; // lengthen AB_diff so that it is at least as long as vehicle is from start point @@ -451,14 +455,10 @@ bool ModeZigZag::calculate_next_dest(Destination ab_dest, bool use_wpnav_alt, Ve terrain_alt = wp_nav->origin_and_destination_are_terrain_alt(); next_dest.z = wp_nav->get_wp_destination().z; } else { - // if we have a downward facing range finder then use terrain altitude targets terrain_alt = copter.rangefinder_alt_ok() && wp_nav->rangefinder_used_and_healthy(); - if (terrain_alt) { - if (!copter.surface_tracking.get_target_alt_cm(next_dest.z)) { - next_dest.z = copter.rangefinder_state.alt_cm_filt.get(); - } - } else { - next_dest.z = pos_control->is_active_z() ? pos_control->get_pos_target_z_cm() : inertial_nav.get_position_z_up_cm(); + next_dest.z = pos_control->get_pos_desired_z_cm(); + if (!terrain_alt) { + next_dest.z += pos_control->get_pos_terrain_cm(); } } @@ -499,19 +499,12 @@ bool ModeZigZag::calculate_side_dest(Vector3f& next_dest, bool& terrain_alt) con float scalar = constrain_float(_side_dist, 0.1f, 100.0f) * 100 / safe_sqrt(AB_side.length_squared()); // get distance from vehicle to start_pos - const Vector2f curr_pos2d {inertial_nav.get_position_xy_cm()}; - next_dest.x = curr_pos2d.x + (AB_side.x * scalar); - next_dest.y = curr_pos2d.y + (AB_side.y * scalar); + const Vector2f curr_pos2d = pos_control->get_pos_desired_cm().xy().tofloat(); + next_dest.xy() = curr_pos2d + (AB_side * scalar); // if we have a downward facing range finder then use terrain altitude targets terrain_alt = copter.rangefinder_alt_ok() && wp_nav->rangefinder_used_and_healthy(); - if (terrain_alt) { - if (!copter.surface_tracking.get_target_alt_cm(next_dest.z)) { - next_dest.z = copter.rangefinder_state.alt_cm_filt.get(); - } - } else { - next_dest.z = pos_control->is_active_z() ? pos_control->get_pos_target_z_cm() : inertial_nav.get_position_z_up_cm(); - } + next_dest.z = pos_control->get_pos_desired_z_cm(); return true; } @@ -542,7 +535,7 @@ void ModeZigZag::run_auto() stage = AUTO; reach_wp_time_ms = 0; char const *dir[] = {"forward", "right", "backward", "left"}; - gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: moving to %s", dir[(uint8_t)zigzag_direction]); + gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s", name(), dir[(uint8_t)zigzag_direction]); } } } else { @@ -596,4 +589,4 @@ float ModeZigZag::crosstrack_error() const return is_auto ? wp_nav->crosstrack_error() : 0; } -#endif // MODE_ZIGZAG_ENABLED == ENABLED +#endif // MODE_ZIGZAG_ENABLED diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 5c5deae8995cd7..2313c30953d5d2 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -102,7 +102,7 @@ bool Copter::mavlink_motor_control_check(const GCS_MAVLINK &gcs_chan, bool check } // Check Motor test is allowed - char failure_msg[50] {}; + char failure_msg[100] {}; if (!motors->motor_test_checks(ARRAY_SIZE(failure_msg), failure_msg)) { gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"%s: %s", mode, failure_msg); return false; diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 34a3ff201b6ce3..c37a4d55a2fb31 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -16,10 +16,11 @@ void Copter::arm_motors_check() // check if arming/disarm using rudder is allowed AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type(); if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) { + arming_counter = 0; return; } -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED if (g2.toy_mode.enabled()) { // not armed with sticks in toy mode return; @@ -134,7 +135,7 @@ void Copter::auto_disarm_check() // motors_output - send output to motors library which will adjust and send to ESCs and servos void Copter::motors_output() { -#if ADVANCED_FAILSAFE == ENABLED +#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED // this is to allow the failsafe module to deliberately crash // the vehicle. Only used in extreme circumstances to meet the // OBC rules @@ -155,8 +156,10 @@ void Copter::motors_output() // output any servo channels SRV_Channels::calc_pwm(); + auto &srv = AP::srv(); + // cork now, so that all channel outputs happen at once - SRV_Channels::cork(); + srv.cork(); // update output on any aux channels, for manual passthru SRV_Channels::output_ch_all(); @@ -180,7 +183,7 @@ void Copter::motors_output() } // push all channels - SRV_Channels::push(); + srv.push(); } // check for pilot stick input to trigger lost vehicle alarm diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index ad98c2fa75552d..7f01266d824236 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -8,7 +8,9 @@ void Copter::init_precland() { - copter.precland.init(400); + // scheduler table specifies 400Hz, but we can call it no faster + // than the scheduler loop rate: + copter.precland.init(MIN(400, scheduler.get_loop_rate_hz())); } void Copter::update_precland() diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index d39d876c53761b..9873d1a2846f8f 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -20,10 +20,11 @@ void Copter::default_dead_zones() void Copter::init_rc_in() { - channel_roll = rc().channel(rcmap.roll()-1); - channel_pitch = rc().channel(rcmap.pitch()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + // the library gaurantees that these are non-nullptr: + channel_roll = &rc().get_roll_channel(); + channel_pitch = &rc().get_pitch_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_yaw = &rc().get_yaw_channel(); // set rc channel ranges channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX); @@ -44,7 +45,7 @@ void Copter::init_rc_out() 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 - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // update rate must be set after motors->init() to allow for motor mapping motors->set_update_rate(g.rc_speed); @@ -197,7 +198,7 @@ void Copter::radio_passthrough_to_motors() */ int16_t Copter::get_throttle_mid(void) { -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED if (g2.toy_mode.enabled()) { return g2.toy_mode.get_throttle_mid(); } diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 589561b8cfe406..f83a1c25e30762 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -8,9 +8,9 @@ void Copter::read_barometer(void) baro_alt = barometer.get_altitude() * 100.0f; } +#if AP_RANGEFINDER_ENABLED void Copter::init_rangefinder(void) { -#if RANGEFINDER_ENABLED == ENABLED rangefinder.set_log_rfnd_bit(MASK_LOG_CTUN); rangefinder.init(ROTATION_PITCH_270); rangefinder_state.alt_cm_filt.set_cutoff_frequency(g2.rangefinder_filt); @@ -19,123 +19,34 @@ void Copter::init_rangefinder(void) // upward facing range finder rangefinder_up_state.alt_cm_filt.set_cutoff_frequency(g2.rangefinder_filt); rangefinder_up_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_90); -#endif } // return rangefinder altitude in centimeters void Copter::read_rangefinder(void) { -#if RANGEFINDER_ENABLED == ENABLED rangefinder.update(); -#if RANGEFINDER_TILT_CORRECTION == ENABLED - const float tilt_correction = MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z); -#else - const float tilt_correction = 1.0f; -#endif - - // iterate through downward and upward facing lidar - struct { - RangeFinderState &state; - enum Rotation orientation; - } rngfnd[2] = {{rangefinder_state, ROTATION_PITCH_270}, {rangefinder_up_state, ROTATION_PITCH_90}}; - - for (uint8_t i=0; i < ARRAY_SIZE(rngfnd); i++) { - // local variables to make accessing simpler - RangeFinderState &rf_state = rngfnd[i].state; - enum Rotation rf_orient = rngfnd[i].orientation; - - // update health - rf_state.alt_healthy = ((rangefinder.status_orient(rf_orient) == RangeFinder::Status::Good) && - (rangefinder.range_valid_count_orient(rf_orient) >= RANGEFINDER_HEALTH_MAX)); - - // tilt corrected but unfiltered, not glitch protected alt - rf_state.alt_cm = tilt_correction * rangefinder.distance_cm_orient(rf_orient); - - // remember inertial alt to allow us to interpolate rangefinder - rf_state.inertial_alt_cm = inertial_nav.get_position_z_up_cm(); - - // glitch handling. rangefinder readings more than RANGEFINDER_GLITCH_ALT_CM from the last good reading - // are considered a glitch and glitch_count becomes non-zero - // glitches clear after RANGEFINDER_GLITCH_NUM_SAMPLES samples in a row. - // glitch_cleared_ms is set so surface tracking (or other consumers) can trigger a target reset - const int32_t glitch_cm = rf_state.alt_cm - rf_state.alt_cm_glitch_protected; - bool reset_terrain_offset = false; - if (glitch_cm >= RANGEFINDER_GLITCH_ALT_CM) { - rf_state.glitch_count = MAX(rf_state.glitch_count+1, 1); - } else if (glitch_cm <= -RANGEFINDER_GLITCH_ALT_CM) { - rf_state.glitch_count = MIN(rf_state.glitch_count-1, -1); - } else { - rf_state.glitch_count = 0; - rf_state.alt_cm_glitch_protected = rf_state.alt_cm; - } - if (abs(rf_state.glitch_count) >= RANGEFINDER_GLITCH_NUM_SAMPLES) { - // clear glitch and record time so consumers (i.e. surface tracking) can reset their target altitudes - rf_state.glitch_count = 0; - rf_state.alt_cm_glitch_protected = rf_state.alt_cm; - rf_state.glitch_cleared_ms = AP_HAL::millis(); - reset_terrain_offset = true; - } - - // filter rangefinder altitude - uint32_t now = AP_HAL::millis(); - const bool timed_out = now - rf_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS; - if (rf_state.alt_healthy) { - if (timed_out) { - // reset filter if we haven't used it within the last second - rf_state.alt_cm_filt.reset(rf_state.alt_cm); - reset_terrain_offset = true; + rangefinder_state.update(); + rangefinder_up_state.update(); - } else { - rf_state.alt_cm_filt.apply(rf_state.alt_cm, 0.05f); - } - rf_state.last_healthy_ms = now; - } - - // handle reset of terrain offset - if (reset_terrain_offset) { - if (rf_orient == ROTATION_PITCH_90) { - // upward facing - rf_state.terrain_offset_cm = rf_state.inertial_alt_cm + rf_state.alt_cm; - } else { - // assume downward facing - rf_state.terrain_offset_cm = rf_state.inertial_alt_cm - rf_state.alt_cm; - } - } - - // send downward facing lidar altitude and health to the libraries that require it #if HAL_PROXIMITY_ENABLED - if (rf_orient == ROTATION_PITCH_270) { - if (rangefinder_state.alt_healthy || timed_out) { - g2.proximity.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get()); - } - } -#endif + if (rangefinder_state.enabled_and_healthy() || rangefinder_state.data_stale()) { + g2.proximity.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get()); } - -#else - // downward facing rangefinder - rangefinder_state.enabled = false; - rangefinder_state.alt_healthy = false; - rangefinder_state.alt_cm = 0; - - // upward facing rangefinder - rangefinder_up_state.enabled = false; - rangefinder_up_state.alt_healthy = false; - rangefinder_up_state.alt_cm = 0; #endif } +#endif // AP_RANGEFINDER_ENABLED // return true if rangefinder_alt can be used bool Copter::rangefinder_alt_ok() const { - return (rangefinder_state.enabled && rangefinder_state.alt_healthy); + return rangefinder_state.enabled_and_healthy(); } // return true if rangefinder_alt can be used bool Copter::rangefinder_up_ok() const { - return (rangefinder_up_state.enabled && rangefinder_up_state.alt_healthy); + return rangefinder_up_state.enabled_and_healthy(); } // update rangefinder based terrain offset @@ -148,7 +59,7 @@ void Copter::update_rangefinder_terrain_offset() terrain_offset_cm = rangefinder_up_state.inertial_alt_cm + rangefinder_up_state.alt_cm_glitch_protected; rangefinder_up_state.terrain_offset_cm += (terrain_offset_cm - rangefinder_up_state.terrain_offset_cm) * (copter.G_Dt / MAX(copter.g2.surftrak_tc, copter.G_Dt)); - if (rangefinder_state.alt_healthy || (AP_HAL::millis() - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS)) { + if (rangefinder_state.alt_healthy || rangefinder_state.data_stale()) { wp_nav->set_rangefinder_terrain_offset(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.terrain_offset_cm); #if MODE_CIRCLE_ENABLED circle_nav->set_rangefinder_terrain_offset(rangefinder_state.enabled && wp_nav->rangefinder_used(), rangefinder_state.alt_healthy, rangefinder_state.terrain_offset_cm); @@ -156,19 +67,12 @@ void Copter::update_rangefinder_terrain_offset() } } -/* - get inertially interpolated rangefinder height. Inertial height is - recorded whenever we update the rangefinder height, then we use the - difference between the inertial height at that time and the current - inertial height to give us interpolation of height from rangefinder - */ +// helper function to get inertially interpolated rangefinder height. bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const { - if (!rangefinder_alt_ok()) { - return false; - } - ret = rangefinder_state.alt_cm_filt.get(); - float inertial_alt_cm = inertial_nav.get_position_z_up_cm(); - ret += inertial_alt_cm - rangefinder_state.inertial_alt_cm; - return true; +#if AP_RANGEFINDER_ENABLED + return rangefinder_state.get_rangefinder_height_interpolated_cm(ret); +#else + return false; +#endif } diff --git a/ArduCopter/surface_tracking.cpp b/ArduCopter/surface_tracking.cpp index 99b05660fbb7d9..4851df6fcc8d51 100644 --- a/ArduCopter/surface_tracking.cpp +++ b/ArduCopter/surface_tracking.cpp @@ -1,10 +1,11 @@ #include "Copter.h" +#if AP_RANGEFINDER_ENABLED + // update_surface_offset - manages the vertical offset of the position controller to follow the measured ground or ceiling // level measured using the range finder. void Copter::SurfaceTracking::update_surface_offset() { -#if RANGEFINDER_ENABLED == ENABLED // check for timeout const uint32_t now_ms = millis(); const bool timeout = (now_ms - last_update_ms) > SURFACE_TRACKING_TIMEOUT_MS; @@ -13,12 +14,11 @@ void Copter::SurfaceTracking::update_surface_offset() if (((surface == Surface::GROUND) && copter.rangefinder_alt_ok() && (copter.rangefinder_state.glitch_count == 0)) || ((surface == Surface::CEILING) && copter.rangefinder_up_ok() && (copter.rangefinder_up_state.glitch_count == 0))) { - // calculate surfaces height above the EKF origin - // 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; + // Get the appropriate surface distance state, the terrain offset is calculated in the surface distance lib. + AP_SurfaceDistance &rf_state = (surface == Surface::GROUND) ? copter.rangefinder_state : copter.rangefinder_up_state; // update position controller target offset to the surface's alt above the EKF origin - copter.pos_control->set_pos_offset_target_z_cm(rf_state.terrain_offset_cm); + copter.pos_control->set_pos_terrain_target_cm(rf_state.terrain_offset_cm); last_update_ms = now_ms; valid_for_logging = true; @@ -28,7 +28,7 @@ void Copter::SurfaceTracking::update_surface_offset() if (timeout || reset_target || (last_glitch_cleared_ms != rf_state.glitch_cleared_ms)) { - copter.pos_control->set_pos_offset_z_cm(rf_state.terrain_offset_cm); + copter.pos_control->init_pos_terrain_cm(rf_state.terrain_offset_cm); reset_target = false; last_glitch_cleared_ms = rf_state.glitch_cleared_ms; } @@ -36,44 +36,22 @@ void Copter::SurfaceTracking::update_surface_offset() } else { // reset position controller offsets if surface tracking is inactive // flag target should be reset when/if it next becomes active - if (timeout) { - copter.pos_control->set_pos_offset_z_cm(0); - copter.pos_control->set_pos_offset_target_z_cm(0); + if (timeout && !reset_target) { + copter.pos_control->init_pos_terrain_cm(0); + valid_for_logging = false; reset_target = true; } } -#else - copter.pos_control->set_pos_offset_z_cm(0); - copter.pos_control->set_pos_offset_target_z_cm(0); -#endif -} - - -// get target altitude (in cm) above ground -// returns true if there is a valid target -bool Copter::SurfaceTracking::get_target_alt_cm(float &target_alt_cm) const -{ - // fail if we are not tracking downwards - if (surface != Surface::GROUND) { - return false; - } - // check target has been updated recently - if (AP_HAL::millis() - last_update_ms > SURFACE_TRACKING_TIMEOUT_MS) { - return false; - } - target_alt_cm = (copter.pos_control->get_pos_target_z_cm() - copter.pos_control->get_pos_offset_z_cm()); - return true; } -// set target altitude (in cm) above ground -void Copter::SurfaceTracking::set_target_alt_cm(float _target_alt_cm) +// target has already been set by terrain following so do not initalise again +// this should be called by flight modes when switching from terrain following to surface tracking (e.g. ZigZag) +void Copter::SurfaceTracking::external_init() { - // fail if we are not tracking downwards - if (surface != Surface::GROUND) { - return; + if ((surface == Surface::GROUND) && copter.rangefinder_alt_ok() && (copter.rangefinder_state.glitch_count == 0)) { + last_update_ms = millis(); + reset_target = false; } - copter.pos_control->set_pos_offset_z_cm(copter.inertial_nav.get_position_z_up_cm() - _target_alt_cm); - last_update_ms = AP_HAL::millis(); } bool Copter::SurfaceTracking::get_target_dist_for_logging(float &target_dist) const @@ -83,7 +61,7 @@ bool Copter::SurfaceTracking::get_target_dist_for_logging(float &target_dist) co } const float dir = (surface == Surface::GROUND) ? 1.0f : -1.0f; - target_dist = dir * (copter.pos_control->get_pos_target_z_cm() - copter.pos_control->get_pos_offset_z_cm()) * 0.01f; + target_dist = dir * copter.pos_control->get_pos_desired_z_cm() * 0.01f; return true; } @@ -112,3 +90,5 @@ void Copter::SurfaceTracking::set_surface(Surface new_surface) surface = new_surface; reset_target = true; } + +#endif // AP_RANGEFINDER_ENABLED diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index bb2d3bc2f67879..7c5ffd3201388d 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -27,15 +27,17 @@ void Copter::init_ardupilot() // initialise battery monitor battery.init(); +#if AP_RSSI_ENABLED // Init RSSI rssi.init(); - +#endif + barometer.init(); // setup telem slots with serial ports gcs().setup_uarts(); -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED osd.init(); #endif @@ -52,9 +54,11 @@ void Copter::init_ardupilot() init_rc_in(); // sets up rc channels from radio +#if AP_RANGEFINDER_ENABLED // initialise surface to be tracked in SurfaceTracking // must be before rc init to not override initial switch position surface_tracking.init((SurfaceTracking::Surface)copter.g2.surftrak_mode.get()); +#endif // allocate the motors class allocate_motors(); @@ -133,7 +137,7 @@ void Copter::init_ardupilot() barometer.set_log_baro_bit(MASK_LOG_IMU); barometer.calibrate(); -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED // initialise rangefinder init_rangefinder(); #endif @@ -153,12 +157,15 @@ void Copter::init_ardupilot() rpm_sensor.init(); #endif -#if MODE_AUTO_ENABLED == ENABLED +#if MODE_AUTO_ENABLED // initialise mission library mode_auto.mission.init(); +#if HAL_LOGGING_ENABLED + mode_auto.mission.set_log_start_mission_item_bit(MASK_LOG_CMD); +#endif #endif -#if MODE_SMARTRTL_ENABLED == ENABLED +#if MODE_SMARTRTL_ENABLED // initialize SmartRTL g2.smart_rtl.init(); #endif @@ -170,7 +177,7 @@ void Copter::init_ardupilot() startup_INS_ground(); -#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED custom_control.init(); #endif @@ -340,7 +347,6 @@ void Copter::update_auto_armed() */ bool Copter::should_log(uint32_t mask) { - ap.logging_started = logger.logging_started(); return logger.should_log(mask); } #endif @@ -361,54 +367,54 @@ void Copter::allocate_motors(void) case AP_Motors::MOTOR_FRAME_DECA: case AP_Motors::MOTOR_FRAME_SCRIPTING_MATRIX: default: - motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix::var_info; break; case AP_Motors::MOTOR_FRAME_TRI: - motors = new AP_MotorsTri(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsTri(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsTri::var_info; AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER); break; case AP_Motors::MOTOR_FRAME_SINGLE: - motors = new AP_MotorsSingle(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsSingle(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsSingle::var_info; break; case AP_Motors::MOTOR_FRAME_COAX: - motors = new AP_MotorsCoax(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsCoax(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsCoax::var_info; break; case AP_Motors::MOTOR_FRAME_TAILSITTER: - motors = new AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsTailsitter::var_info; break; case AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING: #if AP_SCRIPTING_ENABLED - motors = new AP_MotorsMatrix_6DoF_Scripting(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsMatrix_6DoF_Scripting(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_6DoF_Scripting::var_info; #endif // AP_SCRIPTING_ENABLED break; 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 = NEW_NOTHROW AP_MotorsMatrix_Scripting_Dynamic(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; #endif // AP_SCRIPTING_ENABLED break; #else // FRAME_CONFIG == HELI_FRAME case AP_Motors::MOTOR_FRAME_HELI_DUAL: - motors = new AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsHeli_Dual::var_info; AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI); break; case AP_Motors::MOTOR_FRAME_HELI_QUAD: - motors = new AP_MotorsHeli_Quad(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsHeli_Quad(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsHeli_Quad::var_info; AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI); break; case AP_Motors::MOTOR_FRAME_HELI: default: - motors = new AP_MotorsHeli_Single(copter.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsHeli_Single(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsHeli_Single::var_info; AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI); break; @@ -427,15 +433,15 @@ void Copter::allocate_motors(void) #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); + attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors); attitude_control_var_info = AC_AttitudeControl_Multi_6DoF::var_info; #endif // AP_SCRIPTING_ENABLED } else { - attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors); + attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors); attitude_control_var_info = AC_AttitudeControl_Multi::var_info; } #else - attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors); + attitude_control = NEW_NOTHROW AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors); attitude_control_var_info = AC_AttitudeControl_Heli::var_info; #endif if (attitude_control == nullptr) { @@ -443,30 +449,30 @@ void Copter::allocate_motors(void) } AP_Param::load_object_from_eeprom(attitude_control, attitude_control_var_info); - pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); + pos_control = NEW_NOTHROW AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); if (pos_control == nullptr) { AP_BoardConfig::allocation_error("PosControl"); } AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info); #if AP_OAPATHPLANNER_ENABLED - wp_nav = new AC_WPNav_OA(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + wp_nav = NEW_NOTHROW AC_WPNav_OA(inertial_nav, *ahrs_view, *pos_control, *attitude_control); #else - wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + wp_nav = NEW_NOTHROW AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); #endif if (wp_nav == nullptr) { AP_BoardConfig::allocation_error("WPNav"); } AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info); - loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + loiter_nav = NEW_NOTHROW AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); if (loiter_nav == nullptr) { AP_BoardConfig::allocation_error("LoiterNav"); } AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info); -#if MODE_CIRCLE_ENABLED == ENABLED - circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control); +#if MODE_CIRCLE_ENABLED + circle_nav = NEW_NOTHROW AC_Circle(inertial_nav, *ahrs_view, *pos_control); if (circle_nav == nullptr) { AP_BoardConfig::allocation_error("CircleNav"); } diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 14fb7d39da7ba0..943cea8d525ac3 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -52,7 +52,7 @@ void Mode::_TakeOff::start(float alt_cm) { // initialise takeoff state _running = true; - take_off_start_alt = copter.pos_control->get_pos_target_z_cm(); + take_off_start_alt = copter.pos_control->get_pos_desired_z_cm(); take_off_complete_alt = take_off_start_alt + alt_cm; } @@ -87,7 +87,7 @@ void Mode::_TakeOff::do_pilot_takeoff(float& pilot_climb_rate_cm) if (throttle >= MIN(copter.g2.takeoff_throttle_max, 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))) { + (is_positive(take_off_complete_alt - take_off_start_alt) && copter.pos_control->get_pos_desired_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 @@ -104,7 +104,7 @@ void Mode::_TakeOff::do_pilot_takeoff(float& pilot_climb_rate_cm) // 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) { + (take_off_complete_alt - take_off_start_alt) * 0.999f < copter.pos_control->get_pos_desired_z_cm() - take_off_start_alt) { stop(); } } @@ -210,13 +210,13 @@ void _AutoTakeoff::run() 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_altitude = copter.pos_control->get_pos_desired_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; complete = reached_altitude && reached_climb_rate; // calculate completion for location in case it is needed for a smooth transition to wp_nav if (complete) { - const Vector3p& _complete_pos = copter.pos_control->get_pos_target_cm(); + const Vector3p& _complete_pos = copter.pos_control->get_pos_desired_cm(); complete_pos = Vector3p{_complete_pos.x, _complete_pos.y, pos_z}; } } @@ -239,15 +239,15 @@ void _AutoTakeoff::start(float _complete_alt_cm, bool _terrain_alt) } } -// return takeoff final position if takeoff has completed successfully -bool _AutoTakeoff::get_position(Vector3p& _complete_pos) +// return takeoff final target position in cm from the EKF origin if takeoff has completed successfully +bool _AutoTakeoff::get_completion_pos(Vector3p& pos_neu_cm) { // only provide location if takeoff has completed if (!complete) { return false; } - complete_pos = _complete_pos; + pos_neu_cm = complete_pos; return true; } diff --git a/ArduCopter/terrain.cpp b/ArduCopter/terrain.cpp index 5933de460ee752..ae02aab3b5157c 100644 --- a/ArduCopter/terrain.cpp +++ b/ArduCopter/terrain.cpp @@ -8,7 +8,7 @@ void Copter::terrain_update() // tell the rangefinder our height, so it can go into power saving // mode if available -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED float height; if (terrain.height_above_terrain(height, true)) { rangefinder.set_estimated_terrain_height(height); diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index c1cea4d4cc3328..4f5ab348828fe0 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if TOY_MODE_ENABLED == ENABLED +#if TOY_MODE_ENABLED // times in 0.1s units #define TOY_COMMAND_DELAY 15 @@ -431,7 +431,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 AP_FENCE_ENABLED - copter.fence.enable(false); + copter.fence.enable(false, AC_FENCE_ALL_FENCES); #endif if (!copter.arming.arm(AP_Arming::Method::MAVLINK)) { // go back to LOITER @@ -460,7 +460,7 @@ void ToyMode::update() #endif } else if (copter.position_ok() && set_and_remember_mode(Mode::Number::LOITER, ModeReason::TOY_MODE)) { #if AP_FENCE_ENABLED - copter.fence.enable(true); + copter.fence.enable(true, AC_FENCE_ALL_FENCES); #endif gcs().send_text(MAV_SEVERITY_INFO, "Tmode: LOITER update"); } @@ -490,7 +490,7 @@ void ToyMode::update() break; case ACTION_MODE_ACRO: -#if MODE_ACRO_ENABLED == ENABLED +#if MODE_ACRO_ENABLED new_mode = Mode::Number::ACRO; #else gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ACRO is disabled"); @@ -542,7 +542,7 @@ void ToyMode::update() break; case ACTION_MODE_THROW: -#if MODE_THROW_ENABLED == ENABLED +#if MODE_THROW_ENABLED new_mode = Mode::Number::THROW; #else gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: THROW is disabled"); @@ -644,14 +644,14 @@ void ToyMode::update() if (new_mode != copter.flightmode->mode_number()) { load_test.running = false; #if AP_FENCE_ENABLED - copter.fence.enable(false); + copter.fence.enable(false, AC_FENCE_ALL_FENCES); #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 AP_FENCE_ENABLED if (copter.flightmode->requires_GPS()) { - copter.fence.enable(true); + copter.fence.enable(true, AC_FENCE_ALL_FENCES); } #endif } else { @@ -662,7 +662,7 @@ void ToyMode::update() set_and_remember_mode(Mode::Number::LAND, ModeReason::TOY_MODE); #if AP_FENCE_ENABLED if (copter.landing_with_GPS()) { - copter.fence.enable(true); + copter.fence.enable(true, AC_FENCE_ALL_FENCES); } #endif } @@ -801,7 +801,7 @@ void ToyMode::action_arm(void) if (needs_gps && copter.arming.gps_checks(false)) { #if AP_FENCE_ENABLED // we want GPS and checks are passing, arm and enable fence - copter.fence.enable(true); + copter.fence.enable(true, AC_FENCE_ALL_FENCES); #endif copter.arming.arm(AP_Arming::Method::RUDDER); if (!copter.motors->armed()) { @@ -817,7 +817,7 @@ void ToyMode::action_arm(void) } else { #if AP_FENCE_ENABLED // non-GPS mode - copter.fence.enable(false); + copter.fence.enable(false, AC_FENCE_ALL_FENCES); #endif copter.arming.arm(AP_Arming::Method::RUDDER); if (!copter.motors->armed()) { @@ -956,7 +956,7 @@ void ToyMode::handle_message(const mavlink_message_t &msg) // immediately update AP_Notify recording flag AP_Notify::flags.video_recording = true; } else if (strncmp(m.name, "WIFICHAN", 10) == 0) { -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED AP_Radio *radio = AP_Radio::get_singleton(); if (radio) { radio->set_wifi_channel(m.value); diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index c2cea3c72f2c38..58ef26d0776457 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -1,33 +1,34 @@ #include "Copter.h" /* - * Function to update various parameters in flight using the ch6 tuning knob + * Function to update various parameters in flight using the TRANSMITTER_TUNING channel knob * This should not be confused with the AutoTune feature which can be found in control_autotune.cpp */ -// tuning - updates parameters based on the ch6 tuning knob's position +// tuning - updates parameters based on the ch6 TRANSMITTER_TUNING channel knob's position // should be called at 3.3hz void Copter::tuning() { - const RC_Channel *rc6 = rc().channel(CH_6); + const RC_Channel *rc_tuning = rc().find_channel_for_option(RC_Channel::AUX_FUNC::TRANSMITTER_TUNING); + // exit immediately if tuning channel is not set + if (rc_tuning == nullptr) { + return; + } + // exit immediately if the tuning function is not set or min and max are both zero if ((g.radio_tuning <= 0) || (is_zero(g2.tuning_min.get()) && is_zero(g2.tuning_max.get()))) { return; } // exit immediately when radio failsafe is invoked or transmitter has not been turned on - if (failsafe.radio || failsafe.radio_counter != 0 || rc6->get_radio_in() == 0) { - return; - } - - // exit immediately if a function is assigned to channel 6 - if ((RC_Channel::AUX_FUNC)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) { + if (failsafe.radio || failsafe.radio_counter != 0 || rc_tuning->get_radio_in() == 0) { return; } - const uint16_t radio_in = rc6->get_radio_in(); - float tuning_value = linear_interpolate(g2.tuning_min, g2.tuning_max, radio_in, rc6->get_radio_min(), rc6->get_radio_max()); + const uint16_t radio_in = rc_tuning->get_radio_in(); + float tuning_value = linear_interpolate(g2.tuning_min, g2.tuning_max, radio_in, rc_tuning->get_radio_min(), rc_tuning->get_radio_max()); + #if HAL_LOGGING_ENABLED Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g2.tuning_min, g2.tuning_max); #endif @@ -36,84 +37,84 @@ void Copter::tuning() // Roll, Pitch tuning case TUNING_STABILIZE_ROLL_PITCH_KP: - attitude_control->get_angle_roll_p().kP(tuning_value); - attitude_control->get_angle_pitch_p().kP(tuning_value); + attitude_control->get_angle_roll_p().set_kP(tuning_value); + attitude_control->get_angle_pitch_p().set_kP(tuning_value); break; case TUNING_RATE_ROLL_PITCH_KP: - attitude_control->get_rate_roll_pid().kP(tuning_value); - attitude_control->get_rate_pitch_pid().kP(tuning_value); + attitude_control->get_rate_roll_pid().set_kP(tuning_value); + attitude_control->get_rate_pitch_pid().set_kP(tuning_value); break; case TUNING_RATE_ROLL_PITCH_KI: - attitude_control->get_rate_roll_pid().kI(tuning_value); - attitude_control->get_rate_pitch_pid().kI(tuning_value); + attitude_control->get_rate_roll_pid().set_kI(tuning_value); + attitude_control->get_rate_pitch_pid().set_kI(tuning_value); break; case TUNING_RATE_ROLL_PITCH_KD: - attitude_control->get_rate_roll_pid().kD(tuning_value); - attitude_control->get_rate_pitch_pid().kD(tuning_value); + attitude_control->get_rate_roll_pid().set_kD(tuning_value); + attitude_control->get_rate_pitch_pid().set_kD(tuning_value); break; // Yaw tuning case TUNING_STABILIZE_YAW_KP: - attitude_control->get_angle_yaw_p().kP(tuning_value); + attitude_control->get_angle_yaw_p().set_kP(tuning_value); break; case TUNING_YAW_RATE_KP: - attitude_control->get_rate_yaw_pid().kP(tuning_value); + attitude_control->get_rate_yaw_pid().set_kP(tuning_value); break; case TUNING_YAW_RATE_KD: - attitude_control->get_rate_yaw_pid().kD(tuning_value); + attitude_control->get_rate_yaw_pid().set_kD(tuning_value); break; // Altitude and throttle tuning case TUNING_ALTITUDE_HOLD_KP: - pos_control->get_pos_z_p().kP(tuning_value); + pos_control->get_pos_z_p().set_kP(tuning_value); break; case TUNING_THROTTLE_RATE_KP: - pos_control->get_vel_z_pid().kP(tuning_value); + pos_control->get_vel_z_pid().set_kP(tuning_value); break; case TUNING_ACCEL_Z_KP: - pos_control->get_accel_z_pid().kP(tuning_value); + pos_control->get_accel_z_pid().set_kP(tuning_value); break; case TUNING_ACCEL_Z_KI: - pos_control->get_accel_z_pid().kI(tuning_value); + pos_control->get_accel_z_pid().set_kI(tuning_value); break; case TUNING_ACCEL_Z_KD: - pos_control->get_accel_z_pid().kD(tuning_value); + pos_control->get_accel_z_pid().set_kD(tuning_value); break; // Loiter and navigation tuning case TUNING_LOITER_POSITION_KP: - pos_control->get_pos_xy_p().kP(tuning_value); + pos_control->get_pos_xy_p().set_kP(tuning_value); break; case TUNING_VEL_XY_KP: - pos_control->get_vel_xy_pid().kP(tuning_value); + pos_control->get_vel_xy_pid().set_kP(tuning_value); break; case TUNING_VEL_XY_KI: - pos_control->get_vel_xy_pid().kI(tuning_value); + pos_control->get_vel_xy_pid().set_kI(tuning_value); break; case TUNING_WP_SPEED: wp_nav->set_speed_xy(tuning_value); break; -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED // Acro roll pitch rates case TUNING_ACRO_RP_RATE: g2.command_model_acro_rp.set_rate(tuning_value); break; #endif -#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED +#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED // Acro yaw rate case TUNING_ACRO_YAW_RATE: g2.command_model_acro_y.set_rate(tuning_value); @@ -126,15 +127,15 @@ void Copter::tuning() break; case TUNING_RATE_PITCH_FF: - attitude_control->get_rate_pitch_pid().ff(tuning_value); + attitude_control->get_rate_pitch_pid().set_ff(tuning_value); break; case TUNING_RATE_ROLL_FF: - attitude_control->get_rate_roll_pid().ff(tuning_value); + attitude_control->get_rate_roll_pid().set_ff(tuning_value); break; case TUNING_RATE_YAW_FF: - attitude_control->get_rate_yaw_pid().ff(tuning_value); + attitude_control->get_rate_yaw_pid().set_ff(tuning_value); break; #endif @@ -142,7 +143,7 @@ void Copter::tuning() compass.set_declination(ToRad(tuning_value), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact break; -#if MODE_CIRCLE_ENABLED == ENABLED +#if MODE_CIRCLE_ENABLED case TUNING_CIRCLE_RATE: circle_nav->set_rate(tuning_value); break; @@ -153,27 +154,27 @@ void Copter::tuning() break; case TUNING_RATE_PITCH_KP: - attitude_control->get_rate_pitch_pid().kP(tuning_value); + attitude_control->get_rate_pitch_pid().set_kP(tuning_value); break; case TUNING_RATE_PITCH_KI: - attitude_control->get_rate_pitch_pid().kI(tuning_value); + attitude_control->get_rate_pitch_pid().set_kI(tuning_value); break; case TUNING_RATE_PITCH_KD: - attitude_control->get_rate_pitch_pid().kD(tuning_value); + attitude_control->get_rate_pitch_pid().set_kD(tuning_value); break; case TUNING_RATE_ROLL_KP: - attitude_control->get_rate_roll_pid().kP(tuning_value); + attitude_control->get_rate_roll_pid().set_kP(tuning_value); break; case TUNING_RATE_ROLL_KI: - attitude_control->get_rate_roll_pid().kI(tuning_value); + attitude_control->get_rate_roll_pid().set_kI(tuning_value); break; case TUNING_RATE_ROLL_KD: - attitude_control->get_rate_roll_pid().kD(tuning_value); + attitude_control->get_rate_roll_pid().set_kD(tuning_value); break; #if FRAME_CONFIG != HELI_FRAME @@ -183,11 +184,11 @@ void Copter::tuning() #endif case TUNING_RATE_YAW_FILT: - attitude_control->get_rate_yaw_pid().filt_E_hz(tuning_value); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(tuning_value); break; case TUNING_SYSTEM_ID_MAGNITUDE: -#if MODE_SYSTEMID_ENABLED == ENABLED +#if MODE_SYSTEMID_ENABLED copter.mode_systemid.set_magnitude(tuning_value); #endif break; diff --git a/ArduCopter/version.h b/ArduCopter/version.h index 4d81279d0fdcba..a18f4742adda25 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduCopter V4.6.0-dev" +#define THISFIRMWARE "ArduCopter V4.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 6 +#define FW_MINOR 7 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/ArduCopter/wscript b/ArduCopter/wscript index 677477922a23d0..08bec013e628a5 100644 --- a/ArduCopter/wscript +++ b/ArduCopter/wscript @@ -17,12 +17,9 @@ def build(bld): 'AP_IRLock', 'AP_InertialNav', 'AP_Motors', - 'AP_RCMapper', 'AP_Avoidance', 'AP_AdvancedFailsafe', 'AP_SmartRTL', - 'AP_Beacon', - 'AP_Arming', 'AP_WheelEncoder', 'AP_Winch', 'AP_Follow', @@ -30,6 +27,7 @@ def build(bld): 'AP_Devo_Telem', 'AC_AutoTune', 'AP_KDECAN', + 'AP_SurfaceDistance' ], ) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 061cb476a07bd2..643f93a6c17cc9 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -214,7 +214,7 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters */ if (check_enabled(ARMING_CHECK_PARAMETERS) && - is_zero(plane.quadplane.assist_speed) && + is_zero(plane.quadplane.assist.speed) && !plane.quadplane.tailsitter.enabled()) { check_failed(display_failure,"Q_ASSIST_SPEED is not set"); ret = false; @@ -370,12 +370,8 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec change_arm_state(); #if QAUTOTUNE_ENABLED - //save qautotune gains if enabled and success - if (plane.control_mode == &plane.mode_qautotune) { - plane.quadplane.qautotune.save_tuning_gains(); - } else { - plane.quadplane.qautotune.reset(); - } + // Possibly save auto tuned parameters + plane.quadplane.qautotune.disarmed(plane.control_mode == &plane.mode_qautotune); #endif // re-initialize speed variable used in AUTO and GUIDED for diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 3a9dc4f70a735b..7d27791de5571d 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -31,7 +31,7 @@ All entries in this table must be ordered by priority. - This table is interleaved with the table presnet in each of the + This table is interleaved with the table present in each of the vehicles to determine the order in which tasks are run. Convenience methods SCHED_TASK and SCHED_TASK_CLASS are provided to build entries in this structure: @@ -81,8 +81,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63), #endif SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66), - SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150, 69), +#if AP_RANGEFINDER_ENABLED SCHED_TASK(read_rangefinder, 50, 100, 78), +#endif #if AP_ICENGINE_ENABLED SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81), #endif @@ -138,6 +139,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #if AC_PRECLAND_ENABLED SCHED_TASK(precland_update, 400, 50, 160), #endif +#if AP_QUICKTUNE_ENABLED + SCHED_TASK(update_quicktune, 40, 100, 163), +#endif }; void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, @@ -215,6 +219,17 @@ void Plane::update_speed_height(void) should_run_tecs = false; } #endif + + if (auto_state.idle_mode) { + should_run_tecs = false; + } + +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (mode_auto.in_pullup()) { + should_run_tecs = false; + } +#endif + if (should_run_tecs) { // Call TECS 50Hz update. Note that we call this regardless of // throttle suppressed, as this needs to be running for @@ -317,7 +332,7 @@ void Plane::one_second_loop() set_control_channels(); #if HAL_WITH_IO_MCU - iomcu.setup_mixing(&rcmap, g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask); + iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask); #endif #if HAL_ADSB_ENABLED @@ -334,7 +349,7 @@ void Plane::one_second_loop() // sync MAVLink system ID mavlink_system.sysid = g.sysid_this_mav; - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // update notify flags AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false); @@ -481,10 +496,14 @@ void Plane::update_GPS_10Hz(void) */ void Plane::update_control_mode(void) { - if (control_mode != &mode_auto) { + if ((control_mode != &mode_auto) && (control_mode != &mode_takeoff)) { // hold_course is only used in takeoff and landing steer_state.hold_course_cd = -1; } + // refresh the throttle limits, to avoid using stale values + // they will be updated once takeoff_calc_throttle is called + takeoff_state.throttle_lim_max = 100.0f; + takeoff_state.throttle_lim_min = -100.0f; update_fly_forward(); @@ -498,18 +517,29 @@ void Plane::update_fly_forward(void) // wing aircraft. This helps the EKF produce better state // estimates as it can make stronger assumptions #if HAL_QUADPLANE_ENABLED - if (quadplane.available() && - quadplane.tailsitter.is_in_fw_flight()) { - ahrs.set_fly_forward(true); - return; + if (quadplane.available()) { + if (quadplane.tailsitter.is_in_fw_flight()) { + ahrs.set_fly_forward(true); + return; + } + + if (quadplane.in_vtol_mode()) { + ahrs.set_fly_forward(false); + return; + } + + if (quadplane.in_assisted_flight()) { + ahrs.set_fly_forward(false); + return; + } } +#endif - if (quadplane.in_vtol_mode() || - quadplane.in_assisted_flight()) { + if (auto_state.idle_mode) { + // don't fuse airspeed when in balloon lift ahrs.set_fly_forward(false); return; } -#endif if (flight_stage == AP_FixedWing::FlightStage::LAND) { ahrs.set_fly_forward(landing.is_flying_forward()); @@ -558,7 +588,7 @@ void Plane::update_alt() // low pass the sink rate to take some of the noise out auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.set_sink_rate(auto_state.sink_rate); #endif @@ -577,6 +607,16 @@ void Plane::update_alt() should_run_tecs = false; } #endif + + if (auto_state.idle_mode) { + should_run_tecs = false; + } + +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (mode_auto.in_pullup()) { + should_run_tecs = false; + } +#endif if (should_run_tecs && !throttle_suppressed) { @@ -751,7 +791,9 @@ float Plane::tecs_hgt_afe(void) float hgt_afe; if (flight_stage == AP_FixedWing::FlightStage::LAND) { hgt_afe = height_above_target(); +#if AP_RANGEFINDER_ENABLED hgt_afe -= rangefinder_correction(); +#endif } else { // when in normal flight we pass the hgt_afe as relative // altitude to home @@ -830,7 +872,7 @@ bool Plane::set_target_location(const Location &target_loc) #endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED #if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +// get target location (for use by scripting) bool Plane::get_target_location(Location& target_loc) { switch (control_mode->mode_number()) { @@ -905,6 +947,16 @@ bool Plane::set_land_descent_rate(float descent_rate) #endif return false; } + +// Allow for scripting to have control over the crosstracking when exiting and resuming missions or guided flight +// It's up to the Lua script to ensure the provided location makes sense +bool Plane::set_crosstrack_start(const Location &new_start_location) +{ + prev_WP_loc = new_start_location; + auto_state.crosstrack = true; + return true; +} + #endif // AP_SCRIPTING_ENABLED // returns true if vehicle is landing. @@ -968,7 +1020,23 @@ bool Plane::flight_option_enabled(FlightOptions flight_option) const void Plane::precland_update(void) { // alt will be unused if we pass false through as the second parameter: +#if AP_RANGEFINDER_ENABLED return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range); +#else + return g2.precland.update(0, false); +#endif +} +#endif + +#if AP_QUICKTUNE_ENABLED +/* + update AP_Quicktune object. We pass the supports_quicktune() method + in so that quicktune can detect if the user changes to a + non-quicktune capable mode while tuning and the gains can be reverted + */ +void Plane::update_quicktune(void) +{ + quicktune.update(control_mode->supports_quicktune()); } #endif diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 0996a50b725ab4..17cc78bc173975 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -204,9 +204,9 @@ float Plane::stabilize_pitch_get_pitch_out() #endif // if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set #if HAL_QUADPLANE_ENABLED - const bool quadplane_in_transition = quadplane.in_transition(); + const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition(); #else - const bool quadplane_in_transition = false; + const bool quadplane_in_frwd_transition = false; #endif int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch; @@ -219,7 +219,7 @@ float Plane::stabilize_pitch_get_pitch_out() - throttle stick at zero thrust - in fixed wing non auto-throttle mode */ - if (!quadplane_in_transition && + if (!quadplane_in_frwd_transition && !control_mode->is_vtol_mode() && !control_mode->does_auto_throttle() && flare_mode == FlareMode::ENABLED_PITCH_TARGET && @@ -448,6 +448,10 @@ void Plane::stabilize() } +/* + * Set the throttle output. + * This is called by TECS-enabled flight modes, e.g. AUTO, GUIDED, etc. +*/ void Plane::calc_throttle() { if (aparm.throttle_cruise <= 1) { @@ -458,6 +462,7 @@ void Plane::calc_throttle() return; } + // Read the TECS throttle output and set it to the throttle channel. float commanded_throttle = TECS_controller.get_throttle_demand(); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, commanded_throttle); } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index aabe9cfbe536d6..298b4e47a5195b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -234,7 +234,7 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const nav_controller->nav_bearing_cd() * 0.01, nav_controller->target_bearing_cd() * 0.01, MIN(plane.auto_state.wp_distance, UINT16_MAX), - plane.altitude_error_cm * 0.01, + plane.calc_altitude_error_cm() * 0.01, plane.airspeed_error * 100, // incorrect units; see PR#7933 nav_controller->crosstrack_error()); } @@ -423,12 +423,16 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) // unused break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE + case MSG_TERRAIN_REQUEST: CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); plane.terrain.send_request(chan); -#endif break; + case MSG_TERRAIN_REPORT: + CHECK_PAYLOAD_SIZE(TERRAIN_REPORT); + plane.terrain.send_report(chan); + break; +#endif case MSG_WIND: CHECK_PAYLOAD_SIZE(WIND); @@ -508,7 +512,7 @@ void GCS_MAVLINK_Plane::send_hygrometer() const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3 + // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -577,7 +581,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate - // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS + // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -614,6 +618,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -623,10 +630,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif MSG_NAV_CONTROLLER_OUTPUT, @@ -645,7 +658,9 @@ static const ap_message STREAM_RAW_CONTROLLER_msgs[] = { static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_SERVO_OUTPUT_RAW, MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -681,7 +696,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_DISTANCE_SENSOR, MSG_SYSTEM_TIME, #if AP_TERRAIN_AVAILABLE - MSG_TERRAIN, + MSG_TERRAIN_REPORT, + MSG_TERRAIN_REQUEST, #endif #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, @@ -700,7 +716,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_VIBRATION, }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; static const ap_message STREAM_ADSB_msgs[] = { MSG_ADSB_VEHICLE, @@ -841,10 +858,21 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com return MAV_RESULT_DENIED; } +#if AP_FENCE_ENABLED + // reject destination if outside the fence + if (!plane.fence.check_destination_within_fence(requested_position)) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + return MAV_RESULT_DENIED; + } +#endif + // location is valid load and set 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); +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED + plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; +#endif // add home alt if needed if (requested_position.relative_alt) { @@ -864,12 +892,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com return MAV_RESULT_FAILED; } +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // these are GUIDED mode commands that are RATE or slew enabled, so you can have more powerful control than default controls. MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet) { switch(packet.command) { - -#if OFFBOARD_GUIDED == ENABLED case MAV_CMD_GUIDED_CHANGE_SPEED: { // command is only valid in guided mode if (plane.control_mode != &plane.mode_guided) { @@ -920,48 +947,25 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl return MAV_RESULT_DENIED; } - // the requested alt data might be relative or absolute - float new_target_alt = packet.z * 100; - float new_target_alt_rel = packet.z * 100 + plane.home.alt; - - // only global/relative/terrain frames are supported - switch(packet.frame) { - case MAV_FRAME_GLOBAL_RELATIVE_ALT: { - if (is_equal(plane.guided_state.target_alt,new_target_alt_rel) ) { // compare two floats as near-enough - // no need to process any new packet/s with the same ALT any further, if we are already doing it. - return MAV_RESULT_ACCEPTED; - } - plane.guided_state.target_alt = new_target_alt_rel; - break; - } - case MAV_FRAME_GLOBAL: { - if (is_equal(plane.guided_state.target_alt,new_target_alt) ) { // compare two floats as near-enough - // no need to process any new packet/s with the same ALT any further, if we are already doing it. - return MAV_RESULT_ACCEPTED; - } - plane.guided_state.target_alt = new_target_alt; - break; - } - default: - // MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters). - return MAV_RESULT_DENIED; + Location::AltFrame new_target_alt_frame; + if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, new_target_alt_frame)) { + return MAV_RESULT_DENIED; } + // keep a copy of what came in via MAVLink - this is needed for logging, but not for anything else + plane.guided_state.target_mav_frame = packet.frame; - plane.guided_state.target_alt_frame = packet.frame; - plane.guided_state.last_target_alt = plane.current_loc.alt; // FIXME: Reference frame is not corrected for here + const int32_t new_target_alt_cm = packet.z * 100; + plane.guided_state.target_location.set_alt_cm(new_target_alt_cm, new_target_alt_frame); plane.guided_state.target_alt_time_ms = AP_HAL::millis(); + // param3 contains the desired vertical velocity (not acceleration) if (is_zero(packet.param3)) { - // the user wanted /maximum acceleration, pick a large value as close enough - plane.guided_state.target_alt_accel = 1000.0; + // the user wanted /maximum altitude change rate, pick a large value as close enough + plane.guided_state.target_alt_rate = 1000.0; } else { - plane.guided_state.target_alt_accel = fabsf(packet.param3); + plane.guided_state.target_alt_rate = fabsf(packet.param3); } - // assign an acceleration direction - if (plane.guided_state.target_alt < plane.current_loc.alt) { - plane.guided_state.target_alt_accel *= -1.0f; - } return MAV_RESULT_ACCEPTED; } @@ -979,14 +983,20 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl float new_target_heading = radians(wrap_180(packet.param2)); - // course over ground - if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int + switch(HEADING_TYPE(packet.param1)) { + case HEADING_TYPE_COURSE_OVER_GROUND: + // course over ground plane.guided_state.target_heading_type = GUIDED_HEADING_COG; plane.prev_WP_loc = plane.current_loc; - // normal vehicle heading - } else if (int(packet.param1) == HEADING_TYPE_HEADING) { // compare as nearest int + break; + case HEADING_TYPE_HEADING: + // normal vehicle heading plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING; - } else { + break; + case HEADING_TYPE_DEFAULT: + plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; + return MAV_RESULT_ACCEPTED; + default: // MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters). return MAV_RESULT_DENIED; } @@ -998,14 +1008,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl plane.guided_state.target_heading_time_ms = AP_HAL::millis(); return MAV_RESULT_ACCEPTED; } -#endif // OFFBOARD_GUIDED == ENABLED - - } // anything else ... return MAV_RESULT_UNSUPPORTED; - } +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { @@ -1017,11 +1024,13 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in case MAV_CMD_DO_REPOSITION: return handle_command_int_do_reposition(packet); +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // special 'slew-enabled' guided commands here... for speed,alt, and direction commands case MAV_CMD_GUIDED_CHANGE_SPEED: case MAV_CMD_GUIDED_CHANGE_ALTITUDE: case MAV_CMD_GUIDED_CHANGE_HEADING: return handle_command_int_guided_slew_commands(packet); +#endif #if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED case MAV_CMD_DO_FOLLOW: @@ -1044,7 +1053,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in case MAV_CMD_DO_CHANGE_SPEED: return handle_command_DO_CHANGE_SPEED(packet); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED case MAV_CMD_DO_PARACHUTE: return handle_MAV_CMD_DO_PARACHUTE(packet); #endif @@ -1072,6 +1081,10 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in return MAV_RESULT_FAILED; case MAV_CMD_MISSION_START: + if (!is_zero(packet.param1) || !is_zero(packet.param2)) { + // first-item/last item not supported + return MAV_RESULT_DENIED; + } plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); return MAV_RESULT_ACCEPTED; @@ -1083,6 +1096,12 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in plane.set_mode(plane.mode_rtl, ModeReason::GCS_COMMAND); return MAV_RESULT_ACCEPTED; +#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + case MAV_CMD_SET_HAGL: + plane.handle_external_hagl(packet); + return MAV_RESULT_ACCEPTED; +#endif + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -1166,7 +1185,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_co return MAV_RESULT_ACCEPTED; } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) { // configure or release parachute @@ -1369,43 +1388,27 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess mavlink_set_position_target_global_int_t pos_target; mavlink_msg_set_position_target_global_int_decode(&msg, &pos_target); + + Location::AltFrame frame; + if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT"); + // Even though other parts of the command may be valid, reject the whole thing. + return; + } + // Unexpectedly, the mask is expecting "ones" for dimensions that should // be IGNORNED rather than INCLUDED. See mavlink documentation of the // SET_POSITION_TARGET_GLOBAL_INT message, type_mask field. const uint16_t alt_mask = 0b1111111111111011; // (z mask at bit 3) - bool msg_valid = true; AP_Mission::Mission_Command cmd = {0}; if (pos_target.type_mask & alt_mask) { - cmd.content.location.alt = pos_target.alt * 100; - cmd.content.location.relative_alt = false; - cmd.content.location.terrain_alt = false; - switch (pos_target.coordinate_frame) - { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_INT: - break; //default to MSL altitude - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: - cmd.content.location.relative_alt = true; - break; - case MAV_FRAME_GLOBAL_TERRAIN_ALT: - case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: - cmd.content.location.relative_alt = true; - cmd.content.location.terrain_alt = true; - break; - default: - gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT"); - msg_valid = false; - break; - } - - if (msg_valid) { - handle_change_alt_request(cmd); - } - } // end if alt_mask + const int32_t alt_cm = pos_target.alt * 100; + cmd.content.location.set_alt_cm(alt_cm, frame); + handle_change_alt_request(cmd); + } } MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet) @@ -1463,7 +1466,7 @@ int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const return (plane.control_mode != &plane.mode_qstabilize) ? 0.01 * (global_position_current.alt + quadplane.pos_control->get_pos_error_z_cm()) : 0; } #endif - return 0.01 * (global_position_current.alt + plane.altitude_error_cm); + return 0.01 * (global_position_current.alt + plane.calc_altitude_error_cm()); } uint8_t GCS_MAVLINK_Plane::high_latency_tgt_heading() const @@ -1543,3 +1546,99 @@ MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const return MAV_LANDED_STATE_ON_GROUND; } +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const +{ + // Fixed wing modes + const Mode* fw_modes[] { + &plane.mode_manual, + &plane.mode_circle, + &plane.mode_stabilize, + &plane.mode_training, + &plane.mode_acro, + &plane.mode_fbwa, + &plane.mode_fbwb, + &plane.mode_cruise, + &plane.mode_autotune, + &plane.mode_auto, + &plane.mode_rtl, + &plane.mode_loiter, +#if HAL_ADSB_ENABLED + &plane.mode_avoidADSB, +#endif + &plane.mode_guided, + &plane.mode_initializing, + &plane.mode_takeoff, +#if HAL_SOARING_ENABLED + &plane.mode_thermal, +#endif + }; + + const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes); + + // Fixedwing modes are always present + uint8_t mode_count = fw_mode_count; + +#if HAL_QUADPLANE_ENABLED + // Quadplane modes + const Mode* q_modes[] { + &plane.mode_qstabilize, + &plane.mode_qhover, + &plane.mode_qloiter, + &plane.mode_qland, + &plane.mode_qrtl, + &plane.mode_qacro, + &plane.mode_loiter_qland, +#if QAUTOTUNE_ENABLED + &plane.mode_qautotune, +#endif + }; + + // Quadplane modes must be enabled + if (plane.quadplane.available()) { + mode_count += ARRAY_SIZE(q_modes); + } +#endif // HAL_QUADPLANE_ENABLED + + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name; + uint8_t mode_number; + + if (index_zero < fw_mode_count) { + // A fixedwing mode + name = fw_modes[index_zero]->name(); + mode_number = (uint8_t)fw_modes[index_zero]->mode_number(); + + } else { +#if HAL_QUADPLANE_ENABLED + // A Quadplane mode + const uint8_t q_index = index_zero - fw_mode_count; + name = q_modes[q_index]->name(); + mode_number = (uint8_t)q_modes[q_index]->mode_number(); +#else + // Should not endup here + return mode_count; +#endif + } + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index da77d1b357d566..2fa88274e16559 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -50,6 +50,10 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override; void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override; + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); @@ -83,8 +87,6 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK MAV_MODE base_mode() const override; MAV_STATE vehicle_system_status() const override; - uint8_t radio_in_rssi() const; - float vfr_hud_airspeed() const override; int16_t vfr_hud_throttle() const override; float vfr_hud_climbrate() const override; diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index 39989dba93c64f..a193f44e0858d3 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -114,14 +114,16 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void) } #endif +#if AP_RANGEFINDER_ENABLED const RangeFinder *rangefinder = RangeFinder::get_singleton(); - if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) { + if (rangefinder && rangefinder->has_orientation(plane.rangefinder_orientation())) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; if (plane.g.rangefinder_landing) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } - if (rangefinder->has_data_orient(ROTATION_PITCH_270)) { + if (rangefinder->has_data_orient(plane.rangefinder_orientation())) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } } +#endif } diff --git a/ArduPlane/GCS_Plane.h b/ArduPlane/GCS_Plane.h index aa5d507b91de14..9d5ca814e51756 100644 --- a/ArduPlane/GCS_Plane.h +++ b/ArduPlane/GCS_Plane.h @@ -25,7 +25,7 @@ class GCS_Plane : public GCS GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Plane(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Plane(params, uart); } AP_GPS::GPS_Status min_status_for_gps_healthy() const override { diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index c712b2db1756b3..a258269779a39e 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -5,10 +5,11 @@ // Write an attitude packet void Plane::Log_Write_Attitude(void) { - Vector3f targets; // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude - targets.x = nav_roll_cd; - targets.y = nav_pitch_cd; - targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder. + Vector3f targets { // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude + nav_roll_cd * 0.01f, + nav_pitch_cd * 0.01f, + 0 //Plane does not have the concept of navyaw. This is a placeholder. + }; #if HAL_QUADPLANE_ENABLED if (quadplane.show_vtol_view()) { @@ -18,8 +19,7 @@ void Plane::Log_Write_Attitude(void) // since Euler angles are not used and it is a waste of cpu to compute them at the loop rate. // Get them from the quaternion instead: 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); + quadplane.ahrs_view->Write_AttitudeView(targets * RAD_TO_DEG); } else #endif { @@ -121,17 +121,18 @@ void Plane::Log_Write_Control_Tuning() logger.WriteBlock(&pkt, sizeof(pkt)); } -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED struct PACKED log_OFG_Guided { LOG_PACKET_HEADER; uint64_t time_us; float target_airspeed_cm; float target_airspeed_accel; float target_alt; - float target_alt_accel; - uint8_t target_alt_frame; + float target_alt_rate; + uint8_t target_mav_frame; // received MavLink frame float target_heading; float target_heading_limit; + uint8_t target_alt_frame; // internal AltFrame }; // Write a OFG Guided packet. @@ -142,11 +143,12 @@ void Plane::Log_Write_OFG_Guided() time_us : AP_HAL::micros64(), target_airspeed_cm : (float)guided_state.target_airspeed_cm*(float)0.01, target_airspeed_accel : guided_state.target_airspeed_accel, - target_alt : guided_state.target_alt, - target_alt_accel : guided_state.target_alt_accel, - target_alt_frame : guided_state.target_alt_frame, + target_alt : guided_state.target_location.alt * 0.01, + target_alt_rate : guided_state.target_alt_rate, + target_mav_frame : guided_state.target_mav_frame, target_heading : guided_state.target_heading, - target_heading_limit : guided_state.target_heading_accel_limit + target_heading_limit : guided_state.target_heading_accel_limit, + target_alt_frame : static_cast(guided_state.target_location.get_alt_frame()), }; logger.WriteBlock(&pkt, sizeof(pkt)); } @@ -178,7 +180,7 @@ void Plane::Log_Write_Nav_Tuning() wp_distance : auto_state.wp_distance, target_bearing_cd : (int16_t)nav_controller->target_bearing_cd(), nav_bearing_cd : (int16_t)nav_controller->nav_bearing_cd(), - altitude_error_cm : (int16_t)altitude_error_cm, + altitude_error_cm : (int16_t)plane.calc_altitude_error_cm(), xtrack_error : nav_controller->crosstrack_error(), xtrack_error_i : nav_controller->crosstrack_error_integrator(), airspeed_error : airspeed_error, @@ -255,15 +257,17 @@ void Plane::Log_Write_RC(void) { logger.Write_RCIN(); logger.Write_RCOUT(); +#if AP_RSSI_ENABLED if (rssi.enabled()) { logger.Write_RSSI(); } +#endif Log_Write_AETR(); } void Plane::Log_Write_Guided(void) { -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED if (control_mode != &mode_guided) { return; } @@ -272,10 +276,10 @@ void Plane::Log_Write_Guided(void) logger.Write_PID(LOG_PIDG_MSG, g2.guidedHeading.get_pid_info()); } - if ( is_positive(guided_state.target_alt) || is_positive(guided_state.target_airspeed_cm) ) { + if ( guided_state.target_location.alt != -1 || is_positive(guided_state.target_airspeed_cm) ) { Log_Write_OFG_Guided(); } -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED } // incoming-to-vehicle mavlink COMMAND_INT can be logged @@ -314,9 +318,9 @@ const struct LogStructure Plane::log_structure[] = { // @Field: RdO: scaled output rudder // @Field: ThD: demanded speed-height-controller throttle // @Field: As: airspeed estimate (or measurement if airspeed sensor healthy and ARSPD_USE>0) -// @Field: SAs: DCM's airspeed estimate, NaN if not available // @Field: AsT: airspeed type ( old estimate or source of new estimate) // @FieldValueEnum: AsT: AP_AHRS::AirspeedEstimateType +// @Field: SAs: DCM's airspeed estimate, NaN if not available // @Field: E2T: equivalent to true airspeed ratio // @Field: GU: groundspeed undershoot when flying with minimum groundspeed @@ -389,7 +393,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value // @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done -// @Field: Ast: Q assist active +// @Field: Ast: bitmask of assistance flags +// @FieldBitmaskEnum: Ast: log_assistance_flags #if HAL_QUADPLANE_ENABLED { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), "QTUN", "QffffffeccfBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Trn,Ast", "s----mmmnn---", "F----00000---" , true }, @@ -430,7 +435,7 @@ const struct LogStructure Plane::log_structure[] = { // @LoggerMessage: TSIT // @Description: tailsitter speed scailing values // @Field: TimeUS: Time since system startup -// @Field: Ts: throttle scailing used for tilt motors +// @Field: Ts: throttle scaling used for tilt motors // @Field: Ss: speed scailing used for control surfaces method from Q_TAILSIT_GSCMSK // @Field: Tmin: minimum output throttle caculated from disk thoery gain scale with Q_TAILSIT_MIN_VO #if HAL_QUADPLANE_ENABLED @@ -438,6 +443,17 @@ const struct LogStructure Plane::log_structure[] = { "TSIT", "Qfff", "TimeUS,Ts,Ss,Tmin", "s---", "F---" , true }, #endif +// @LoggerMessage: TILT +// @Description: Tiltrotor tilt values +// @Field: TimeUS: Time since system startup +// @Field: Tilt: Current tilt angle, 0 deg vertical, 90 deg horizontal +// @Field: FL: Front left tilt angle, 0 deg vertical, 90 deg horizontal +// @Field: FR: Front right tilt angle, 0 deg vertical, 90 deg horizontal +#if HAL_QUADPLANE_ENABLED + { LOG_TILT_MSG, sizeof(Tiltrotor::log_tiltrotor), + "TILT", "Qfff", "TimeUS,Tilt,FL,FR", "sddd", "F---" , true }, +#endif + // @LoggerMessage: PIDG // @Description: Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control. // @Field: TimeUS: Time since system startup @@ -469,19 +485,20 @@ const struct LogStructure Plane::log_structure[] = { { LOG_AETR_MSG, sizeof(log_AETR), "AETR", "Qfffffff", "TimeUS,Ail,Elev,Thr,Rudd,Flap,Steer,SS", "s-------", "F-------" , true }, -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // @LoggerMessage: OFG // @Description: OFfboard-Guided - an advanced version of GUIDED for companion computers that includes rate/s. // @Field: TimeUS: Time since system startup // @Field: Arsp: target airspeed cm // @Field: ArspA: target airspeed accel // @Field: Alt: target alt -// @Field: AltA: target alt accel -// @Field: AltF: target alt frame +// @Field: AltA: target alt velocity (rate of change) +// @Field: AltF: target alt frame (MAVLink) // @Field: Hdg: target heading // @Field: HdgA: target heading lim +// @Field: AltL: target alt frame (Location) { LOG_OFG_MSG, sizeof(log_OFG_Guided), - "OFG", "QffffBff", "TimeUS,Arsp,ArspA,Alt,AltA,AltF,Hdg,HdgA", "s-------", "F-------" , true }, + "OFG", "QffffBffB", "TimeUS,Arsp,ArspA,Alt,AltA,AltF,Hdg,HdgA,AltL", "snnmo-d--", "F--------" , true }, #endif }; diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 419283a14fd49e..04a5ba3a595258 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -60,7 +60,7 @@ const AP_Param::Info Plane::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing + // @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), // @Param: KFF_RDDRMIX @@ -142,12 +142,37 @@ const AP_Param::Info Plane::var_info[] = { // @Param: TKOFF_THR_MAX_T // @DisplayName: Takeoff throttle maximum time - // @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff without an airspeed sensor. If an airspeed sensor is being used then the throttle is set to maximum until the takeoff airspeed is reached. + // @Description: This sets the time that maximum throttle will be forced during a fixed wing takeoff. // @Units: s // @Range: 0 10 // @Increment: 0.5 // @User: Standard ASCALAR(takeoff_throttle_max_t, "TKOFF_THR_MAX_T", 4), + + // @Param: TKOFF_THR_MIN + // @DisplayName: Takeoff minimum throttle + // @Description: The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_OPTIONS bit 0 is set. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead. + // @Units: % + // @Range: 0 100 + // @Increment: 1 + // @User: Standard + ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0), + + // @Param: TKOFF_THR_IDLE + // @DisplayName: Takeoff idle throttle + // @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes. + // @Units: % + // @Range: 0 100 + // @Increment: 1 + // @User: Standard + ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0), + + // @Param: TKOFF_OPTIONS + // @DisplayName: Takeoff options + // @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes. + // @Bitmask: 0: When unset the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX) during takeoff. When set TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor. + // @User: Advanced + ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0), // @Param: TKOFF_TDRAG_ELEV // @DisplayName: Takeoff tail dragger elevator @@ -215,7 +240,6 @@ const AP_Param::Info Plane::var_info[] = { // @Param: USE_REV_THRUST // @DisplayName: Bitmask for when to allow negative reverse thrust // @Description: This controls when to use reverse thrust. If set to zero then reverse thrust is never used. If set to a non-zero value then the bits correspond to flight stages where reverse thrust may be used. The most commonly used value for USE_REV_THRUST is 2, which means AUTO_LAND only. That enables reverse thrust in the landing stage of AUTO mode. Another common choice is 1, which means to use reverse thrust in all auto flight stages. Reverse thrust is always used in MANUAL mode if enabled with THR_MIN < 0. In non-autothrottle controlled modes, if reverse thrust is not used, then THR_MIN is effectively set to 0 for that mode. - // @Values: 0:MANUAL ONLY,1:AutoAlways,2:AutoLanding // @Bitmask: 0:AUTO_ALWAYS,1:AUTO_LAND,2:AUTO_LOITER_TO_ALT,3:AUTO_LOITER_ALL,4:AUTO_WAYPOINTS,5:LOITER,6:RTL,7:CIRCLE,8:CRUISE,9:FBWB,10:GUIDED,11:AUTO_LANDING_PATTERN,12:FBWA,13:ACRO,14:STABILIZE,15:THERMAL // @User: Advanced GSCALAR(use_reverse_thrust, "USE_REV_THRUST", USE_REVERSE_THRUST_AUTO_LAND_APPROACH), @@ -297,6 +321,14 @@ const AP_Param::Info Plane::var_info[] = { // @User: Standard ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX), + // @Param: AIRSPEED_STALL + // @DisplayName: Stall airspeed + // @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed. + // @Units: m/s + // @Range: 5 75 + // @User: Standard + ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0), + // @Param: FBWB_ELEV_REV // @DisplayName: Fly By Wire elevator reverse // @Description: Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to lower altitude. When set to 1, up elevator means to raise altitude. @@ -308,7 +340,6 @@ const AP_Param::Info Plane::var_info[] = { // @Param: TERRAIN_FOLLOW // @DisplayName: Use terrain following // @Description: This enables terrain following for CRUISE mode, FBWB mode, RTL and for rally points. To use this option you also need to set TERRAIN_ENABLE to 1, which enables terrain data fetching from the GCS, and you need to have a GCS that supports sending terrain data to the aircraft. When terrain following is enabled then CRUISE and FBWB mode will hold height above terrain rather than height above home. In RTL the return to launch altitude will be considered to be a height above the terrain. Rally point altitudes will be taken as height above the terrain. This option does not affect mission items, which have a per-waypoint flag for whether they are height above home or height above the terrain. To use terrain following missions you need a ground station which can set the waypoint type to be a terrain height waypoint when creating the mission. - // @Values: 0:Disabled,1:Enabled // @Bitmask: 0: Enable all modes, 1:FBWB, 2:Cruise, 3:Auto, 4:RTL, 5:Avoid_ADSB, 6:Guided, 7:Loiter, 8:Circle, 9:QRTL, 10:QLand, 11:Qloiter // @User: Standard GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0), @@ -517,7 +548,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls. // @Units: deg // @Range: 0 90 - // @Increment: 0.1 + // @Increment: 1 // @User: Standard ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG), @@ -526,7 +557,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum pitch up angle commanded in modes with stabilized limits. // @Units: deg // @Range: 0 90 - // @Increment: 10 + // @Increment: 1 // @User: Standard ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX), @@ -535,7 +566,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum pitch down angle commanded in modes with stabilized limits // @Units: deg // @Range: -90 0 - // @Increment: 10 + // @Increment: 1 // @User: Standard ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN), @@ -639,7 +670,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: MIN_GROUNDSPEED // @DisplayName: Minimum ground speed - // @Description: Minimum ground speed in cm/s when under airspeed control + // @Description: Minimum ground speed when under airspeed control // @Units: m/s // @User: Advanced ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED), @@ -731,7 +762,6 @@ const AP_Param::Info Plane::var_info[] = { // @Param: CRASH_DETECT // @DisplayName: Crash Detection // @Description: Automatically detect a crash during AUTO flight and perform the bitmask selected action(s). Disarm will turn off motor for safety and to help against burning out ESC and motor. Set to 0 to disable crash detection. - // @Values: 0:Disabled // @Bitmask: 0:Disarm // @User: Advanced ASCALAR(crash_detection_enable, "CRASH_DETECT", 0), @@ -761,12 +791,13 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(relay, "RELAY", AP_Relay), #endif -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED // @Group: CHUTE_ // @Path: ../libraries/AP_Parachute/AP_Parachute.cpp GOBJECT(parachute, "CHUTE_", AP_Parachute), #endif +#if AP_RANGEFINDER_ENABLED // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), @@ -777,6 +808,7 @@ const AP_Param::Info Plane::var_info[] = { // @Values: 0:Disabled,1:Enabled // @User: Standard GSCALAR(rangefinder_landing, "RNGFND_LANDING", 0), +#endif #if AP_TERRAIN_AVAILABLE // @Group: TERRAIN_ @@ -968,9 +1000,11 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(rpm_sensor, "RPM", AP_RPM), #endif +#if AP_RSSI_ENABLED // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), +#endif // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp @@ -994,10 +1028,22 @@ const AP_Param::Info Plane::var_info[] = { // @Path: mode_takeoff.cpp GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff), +#if AP_PLANE_GLIDER_PULLUP_ENABLED + // @Group: PUP_ + // @Path: pullup.cpp + GOBJECTN(mode_auto.pullup, pullup, "PUP_", GliderPullup), +#endif + // @Group: // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp PARAM_VEHICLE_INFO, +#if AP_QUICKTUNE_ENABLED + // @Group: QWIK_ + // @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp + GOBJECT(quicktune, "QWIK_", AP_Quicktune), +#endif + AP_VAREND }; @@ -1087,6 +1133,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode // @Bitmask: 12: Enable FBWB style loiter altitude control // @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces + // @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb // @User: Advanced AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0), @@ -1134,9 +1181,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: DSPOILER_OPTS // @DisplayName: Differential spoiler and crow flaps options - // @Description: Differential spoiler and crow flaps options - // @Values: 0: none, 1: D spoilers have pitch input, 2: use both control surfaces on each wing for roll, 4: Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in) - // @Bitmask: 0:pitch control, 1:full span, 2:Progressive crow + // @Description: Differential spoiler and crow flaps options. Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in). + // @Bitmask: 0:Pitch input, 1:use both control surfaces on each wing for roll, 2:Progressive crow flaps // @User: Advanced AP_GROUPINFO("DSPOILER_OPTS", 20, ParametersG2, crow_flap_options, 3), @@ -1193,11 +1239,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("RTL_CLIMB_MIN", 27, ParametersG2, rtl_climb_min, 0), -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // @Group: GUIDED_ // @Path: ../libraries/AC_PID/AC_PID.cpp AP_SUBGROUPINFO(guidedHeading, "GUIDED_", 28, ParametersG2, AC_PID), -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // @Param: MAN_EXPO_ROLL // @DisplayName: Manual control expo for roll @@ -1249,17 +1295,26 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(precland, "PLND_", 35, ParametersG2, AC_PrecLand), #endif +#if AP_RANGEFINDER_ENABLED + // @Param: RNGFND_LND_ORNT + // @DisplayName: rangefinder landing orientation + // @Description: The orientation of rangefinder to use for landing detection. Should be set to Down for normal downward facing rangefinder and Back for rearward facing rangefinder for quadplane tailsitters. Custom orientation can be used with Custom1 or Custom2. The orientation must match at least one of the available rangefinders. + // @Values: 4:Back, 25:Down, 101:Custom1, 102:Custom2 + // @User: Standard + AP_GROUPINFO("RNGFND_LND_ORNT", 36, ParametersG2, rangefinder_land_orient, ROTATION_PITCH_270), +#endif + AP_GROUPEND }; ParametersG2::ParametersG2(void) : unused_integer{1} -#if HAL_SOARING_ENABLED - ,soaring_controller(plane.TECS_controller, plane.aparm) -#endif #if HAL_BUTTON_ENABLED ,button_ptr(&plane.button) #endif +#if HAL_SOARING_ENABLED + ,soaring_controller(plane.TECS_controller, plane.aparm) +#endif { AP_Param::setup_object_defaults(this, var_info); } @@ -1337,9 +1392,15 @@ struct RCConversionInfo { static const RCConversionInfo rc_option_conversion[] = { { Parameters::k_param_flapin_channel_old, 0, RC_Channel::AUX_FUNC::FLAP}, { Parameters::k_param_g2, 968, RC_Channel::AUX_FUNC::SOARING}, +#if AP_FENCE_ENABLED { Parameters::k_param_fence_channel, 0, RC_Channel::AUX_FUNC::FENCE}, +#endif +#if AP_MISSION_ENABLED { Parameters::k_param_reset_mission_chan, 0, RC_Channel::AUX_FUNC::MISSION_RESET}, +#endif +#if HAL_PARACHUTE_ENABLED { Parameters::k_param_parachute_channel, 0, RC_Channel::AUX_FUNC::PARACHUTE_RELEASE}, +#endif { Parameters::k_param_fbwa_tdrag_chan, 0, RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER}, { Parameters::k_param_reset_switch_chan, 0, RC_Channel::AUX_FUNC::MODE_SWITCH_RESET}, }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index ba89c457728112..e7cc5326f4280f 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -343,6 +343,7 @@ class Parameters { k_param_mixing_offset, k_param_dspoiler_rud_rate, + k_param_airspeed_stall, k_param_logger = 253, // Logging Group @@ -356,6 +357,12 @@ class Parameters { k_param_acro_yaw_rate, k_param_takeoff_throttle_max_t, k_param_autotune_options, + k_param_takeoff_throttle_min, + k_param_takeoff_options, + k_param_takeoff_throttle_idle, + + k_param_pullup = 270, + k_param_quicktune, }; AP_Int16 format_version; @@ -478,6 +485,9 @@ class ParametersG2 { // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; + // just to make compilation easier when all things are compiled out... + uint8_t unused_integer; + // button reporting library #if HAL_BUTTON_ENABLED AP_Button *button_ptr; @@ -552,7 +562,7 @@ class ParametersG2 { } fwd_batt_cmp; -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // guided yaw heading PID AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0}; #endif @@ -574,8 +584,10 @@ class ParametersG2 { AP_Int8 axis_bitmask; // axes to be autotuned - // just to make compilation easier when all things are compiled out... - uint8_t unused_integer; +#if AP_RANGEFINDER_ENABLED + // orientation of rangefinder to use for landing + AP_Int8 rangefinder_land_orient; +#endif }; extern const AP_Param::Info var_info[]; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 71b450256c4d9d..d2d35a7b14e0a6 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -39,7 +39,7 @@ #include // interface and maths for accelerometer calibration #include // ArduPilot Mega DCM Library #include -#include // Range finder library +#include // Range finder library #include // Filter library #include // Photo or video camera #include @@ -121,6 +121,7 @@ #include "avoidance_adsb.h" #endif #include "AP_Arming.h" +#include "pullup.h" /* main APM:Plane class @@ -143,6 +144,7 @@ class Plane : public AP_Vehicle { friend class Tiltrotor; friend class SLT_Transition; friend class Tailsitter_Transition; + friend class VTOL_Assist; friend class Mode; friend class ModeCircle; @@ -174,6 +176,9 @@ class Plane : public AP_Vehicle { #if AP_EXTERNAL_CONTROL_ENABLED friend class AP_ExternalControl_Plane; #endif +#if AP_PLANE_GLIDER_PULLUP_ENABLED + friend class GliderPullup; +#endif Plane(void); @@ -205,8 +210,31 @@ class Plane : public AP_Vehicle { AP_Int8 *flight_modes = &g.flight_mode1; const uint8_t num_flight_modes = 6; +#if AP_RANGEFINDER_ENABLED AP_FixedWing::Rangefinder_State rangefinder_state; + /* + orientation of rangefinder to use for landing + */ + Rotation rangefinder_orientation(void) const { + return Rotation(g2.rangefinder_land_orient.get()); + } +#endif + +#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + struct { + // allow for external height above ground estimate + float hagl; + uint32_t last_update_ms; + uint32_t timeout_ms; + } external_hagl; + bool get_external_HAGL(float &height_agl); + void handle_external_hagl(const mavlink_command_int_t &packet); +#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + + float get_landing_height(bool &using_rangefinder); + + #if AP_RPM_ENABLED AP_RPM rpm_sensor; #endif @@ -302,6 +330,10 @@ class Plane : public AP_Vehicle { ModeThermal mode_thermal; #endif +#if AP_QUICKTUNE_ENABLED + AP_Quicktune quicktune; +#endif + // This is the state of the flight control system // There are multiple states defined such as MANUAL, FBW-A, AUTO Mode *control_mode = &mode_initializing; @@ -349,19 +381,20 @@ class Plane : public AP_Vehicle { uint32_t AFS_last_valid_rc_ms; } failsafe; - enum Landing_ApproachStage { - RTL, - LOITER_TO_ALT, - ENSURE_RADIUS, - WAIT_FOR_BREAKOUT, - APPROACH_LINE, - VTOL_LANDING, - }; - #if HAL_QUADPLANE_ENABLED // Landing - struct { - enum Landing_ApproachStage approach_stage; + class VTOLApproach { + public: + enum class Stage { + RTL, + LOITER_TO_ALT, + ENSURE_RADIUS, + WAIT_FOR_BREAKOUT, + APPROACH_LINE, + VTOL_LANDING, + }; + + Stage approach_stage; float approach_direction_deg; } vtol_approach_s; #endif @@ -399,9 +432,6 @@ class Plane : public AP_Vehicle { int32_t groundspeed_undershoot; bool groundspeed_undershoot_is_valid; - // Difference between current altitude and desired altitude. Centimeters - int32_t altitude_error_cm; - // speed scaler for control surfaces, updated at 10Hz float surface_speed_scaler = 1.0; @@ -420,6 +450,10 @@ class Plane : public AP_Vehicle { uint32_t accel_event_ms; uint32_t start_time_ms; bool waiting_for_rudder_neutral; + float throttle_lim_max; + float throttle_lim_min; + uint32_t throttle_max_timer_ms; + // Good candidate for keeping the initial time for TKOFF_THR_MAX_T. } takeoff_state; // ground steering controller state @@ -479,10 +513,6 @@ class Plane : public AP_Vehicle { // Minimum pitch to hold during takeoff command execution. Hundredths of a degree int16_t takeoff_pitch_cd; - // used to 'wiggle' servos in idle mode to prevent them freezing - // at high altitudes - uint8_t idle_wiggle_stage; - // Flag for using gps ground course instead of INS yaw. Set false when takeoff command in process. bool takeoff_complete; @@ -504,6 +534,11 @@ class Plane : public AP_Vehicle { // have we checked for an auto-land? bool checked_for_autoland; + // Altitude threshold to complete a takeoff command in autonomous modes. Centimeters + // are we in idle mode? used for balloon launch to stop servo + // movement until altitude is reached + bool idle_mode; + // are we in VTOL mode in AUTO? bool vtol_mode; @@ -543,18 +578,17 @@ class Plane : public AP_Vehicle { float forced_throttle; uint32_t last_forced_throttle_ms; -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // airspeed adjustments float target_airspeed_cm = -1; // don't default to zero here, as zero is a valid speed. float target_airspeed_accel; uint32_t target_airspeed_time_ms; // altitude adjustments - float target_alt = -1; // don't default to zero here, as zero is a valid alt. - uint32_t last_target_alt = 0; - float target_alt_accel; + Location target_location; + float target_alt_rate; uint32_t target_alt_time_ms = 0; - uint8_t target_alt_frame = 0; + uint8_t target_mav_frame = -1; // heading track float target_heading = -4; // don't default to zero or -1 here, as both are valid headings in radians @@ -562,7 +596,7 @@ class Plane : public AP_Vehicle { uint32_t target_heading_time_ms; guided_heading_type_t target_heading_type; bool target_heading_limit; -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED } guided_state; #if AP_LANDINGGEAR_ENABLED @@ -639,7 +673,7 @@ class Plane : public AP_Vehicle { FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)}; -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED AP_Parachute parachute; #endif @@ -845,6 +879,10 @@ class Plane : public AP_Vehicle { static const TerrainLookupTable Terrain_lookup[]; #endif +#if AP_QUICKTUNE_ENABLED + void update_quicktune(void); +#endif + // Attitude.cpp void adjust_nav_pitch_throttle(void); void update_load_factor(void); @@ -871,9 +909,11 @@ class Plane : public AP_Vehicle { float mission_alt_offset(void); float height_above_target(void); float lookahead_adjustment(void); +#if AP_RANGEFINDER_ENABLED float rangefinder_correction(void); void rangefinder_height_update(void); void rangefinder_terrain_correction(float &height); +#endif void stabilize(); void calc_throttle(); void calc_nav_roll(); @@ -911,7 +951,6 @@ class Plane : public AP_Vehicle { void Log_Write_RC(void); void Log_Write_Vehicle_Startup_Messages(); void Log_Write_AETR(); - void log_init(); #endif // Parameters.cpp @@ -946,6 +985,7 @@ class Plane : public AP_Vehicle { void do_loiter_turns(const AP_Mission::Mission_Command& cmd); void do_loiter_time(const AP_Mission::Mission_Command& cmd); void do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd); + void do_altitude_wait(const AP_Mission::Mission_Command& cmd); void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd); void do_vtol_takeoff(const AP_Mission::Mission_Command& cmd); void do_vtol_land(const AP_Mission::Mission_Command& cmd); @@ -1080,18 +1120,19 @@ class Plane : public AP_Vehicle { bool rc_throttle_value_ok(void) const; bool rc_failsafe_active(void) const; +#if AP_RANGEFINDER_ENABLED // sensors.cpp void read_rangefinder(void); +#endif // system.cpp void init_ardupilot() override; - void startup_ground(void); 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); void check_long_failsafe(); void check_short_failsafe(); - void startup_INS_ground(void); + void startup_INS(void); bool should_log(uint32_t mask); int8_t throttle_percentage(void); void notify_mode(const Mode& mode); @@ -1101,6 +1142,7 @@ class Plane : public AP_Vehicle { bool auto_takeoff_check(void); void takeoff_calc_roll(void); void takeoff_calc_pitch(void); + void takeoff_calc_throttle(); int8_t takeoff_tail_hold(void); int16_t get_takeoff_pitch_min_cd(void); void landing_gear_update(void); @@ -1110,7 +1152,6 @@ class Plane : public AP_Vehicle { void avoidance_adsb_update(void); // servos.cpp - void set_servos_idle(void); void set_servos(); float apply_throttle_limits(float throttle_in); void set_throttle(void); @@ -1126,7 +1167,7 @@ class Plane : public AP_Vehicle { void servos_twin_engine_mix(); void force_flare(); void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle); - void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func); + void throttle_slew_limit(); bool suppress_throttle(void); void update_throttle_hover(); void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in, @@ -1142,7 +1183,7 @@ class Plane : public AP_Vehicle { // parachute.cpp void parachute_check(); -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED void do_parachute(const AP_Mission::Mission_Command& cmd); void parachute_release(); bool parachute_manual_release(); @@ -1272,6 +1313,11 @@ class Plane : public AP_Vehicle { // allow for landing descent rate to be overridden by a script, may be -ve to climb bool set_land_descent_rate(float descent_rate) override; + + // allow scripts to override mission/guided crosstrack behaviour + // It's up to the Lua script to ensure the provided location makes sense + bool set_crosstrack_start(const Location &new_start_location) override; + #endif // AP_SCRIPTING_ENABLED }; diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 1fc5b0ad222a19..2dc6f1edaab017 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -1,6 +1,7 @@ #include "Plane.h" #include "RC_Channel.h" +#include "qautotune.h" // defining these two macros and including the RC_Channels_VarInfo // header defines the parameter information common to all vehicle @@ -43,7 +44,7 @@ void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number, switch(ch_flag) { case AuxSwitchPos::HIGH: { // engage mode (if not possible we remain in current flight mode) - plane.set_mode_by_number(number, ModeReason::RC_COMMAND); + plane.set_mode_by_number(number, ModeReason::AUX_FUNCTION); break; } default: @@ -61,17 +62,17 @@ void RC_Channel_Plane::do_aux_function_q_assist_state(AuxSwitchPos ch_flag) switch(ch_flag) { case AuxSwitchPos::HIGH: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Force enabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); break; case AuxSwitchPos::MIDDLE: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Enabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_ENABLED); break; case AuxSwitchPos::LOW: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Disabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_DISABLED); break; } } @@ -95,9 +96,9 @@ void RC_Channel_Plane::do_aux_function_crow_mode(AuxSwitchPos ch_flag) } } +#if HAL_SOARING_ENABLED void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag) { -#if HAL_SOARING_ENABLED SoaringController::ActiveStatus desired_state = SoaringController::ActiveStatus::SOARING_DISABLED; switch (ch_flag) { @@ -113,28 +114,19 @@ void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag) } plane.g2.soaring_controller.set_pilot_desired_state(desired_state); -#endif } +#endif void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag) { switch(ch_flag) { case AuxSwitchPos::HIGH: plane.flare_mode = Plane::FlareMode::ENABLED_PITCH_TARGET; -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); -#endif break; case AuxSwitchPos::MIDDLE: plane.flare_mode = Plane::FlareMode::ENABLED_NO_PITCH_TARGET; -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); -#endif break; case AuxSwitchPos::LOW: -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED); -#endif plane.flare_mode = Plane::FlareMode::FLARE_DISABLED; break; } @@ -166,7 +158,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option, case AUX_FUNC::FBWA_TAILDRAGGER: case AUX_FUNC::FWD_THR: case AUX_FUNC::LANDING_FLARE: +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif case AUX_FUNC::MODE_SWITCH_RESET: case AUX_FUNC::CRUISE: #if HAL_QUADPLANE_ENABLED @@ -178,6 +172,15 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option, case AUX_FUNC::FW_AUTOTUNE: case AUX_FUNC::VFWD_THR_OVERRIDE: case AUX_FUNC::PRECISION_LOITER: +#if AP_ICENGINE_ENABLED + case AUX_FUNC::ICE_START_STOP: +#endif +#if QAUTOTUNE_ENABLED + case AUX_FUNC::AUTOTUNE_TEST_GAINS: +#endif +#if AP_QUICKTUNE_ENABLED + case AUX_FUNC::QUICKTUNE: +#endif break; case AUX_FUNC::SOARING: @@ -284,13 +287,18 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch } #endif +#if HAL_SOARING_ENABLED case AUX_FUNC::SOARING: do_aux_function_soaring_3pos(ch_flag); break; +#endif case AUX_FUNC::FLAP: case AUX_FUNC::FBWA_TAILDRAGGER: case AUX_FUNC::AIRBRAKE: +#if AP_ICENGINE_ENABLED + case AUX_FUNC::ICE_START_STOP: +#endif break; // input labels, nothing to do #if HAL_QUADPLANE_ENABLED @@ -342,8 +350,8 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch break; #endif - case AUX_FUNC::ARSPD_CALIBRATE: #if AP_AIRSPEED_AUTOCAL_ENABLE + case AUX_FUNC::ARSPD_CALIBRATE: switch (ch_flag) { case AuxSwitchPos::HIGH: plane.airspeed.set_calibration_enabled(true); @@ -354,20 +362,20 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch plane.airspeed.set_calibration_enabled(false); break; } -#endif break; +#endif case AUX_FUNC::LANDING_FLARE: do_aux_function_flare(ch_flag); break; +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: -#if PARACHUTE == ENABLED if (ch_flag == AuxSwitchPos::HIGH) { plane.parachute_manual_release(); } -#endif break; +#endif case AUX_FUNC::MODE_SWITCH_RESET: rc().reset_mode_switch(); @@ -448,6 +456,18 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch // handled by lua scripting, just ignore here break; +#if QAUTOTUNE_ENABLED + case AUX_FUNC::AUTOTUNE_TEST_GAINS: + plane.quadplane.qautotune.do_aux_function(ch_flag); + break; +#endif + +#if AP_QUICKTUNE_ENABLED + case AUX_FUNC::QUICKTUNE: + plane.quicktune.update_switch_pos(ch_flag); + break; +#endif + default: return RC_Channel::do_aux_function(ch_option, ch_flag); } diff --git a/ArduPlane/RC_Channel.h b/ArduPlane/RC_Channel.h index 858034478c9bf1..e9b4804aac5454 100644 --- a/ArduPlane/RC_Channel.h +++ b/ArduPlane/RC_Channel.h @@ -30,7 +30,6 @@ class RC_Channel_Plane : public RC_Channel void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag); void do_aux_function_flare(AuxSwitchPos ch_flag); - }; class RC_Channels_Plane : public RC_Channels diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index f83e0cf44e9db2..ed28f55e6d524a 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,631 @@ +ArduPilot Plane Release Notes: +------------------------------------------------------------------ +Release 4.6.0-beta 13 Nov 2024 + +Changes from 4.5.7 + +1) Board specific changes + +- AnyLeaf H7 supports compass and onboard logging +- Blitz743Pro supports CAN +- BlueRobotics Navigator supports BMP390 baro +- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed) +- CB Unmanned Stamp H743 support +- ClearSky CSKY405 support +- CUAV-7-Nano default batt monitor fixed +- CubeRed bootloader fixes including disabling 2nd core by default +- CubeRed supports PPP networking between primary and secondary MCU +- CubeRedPrimary supports external compasses +- ESP32 main loop rate improvements +- ESP32 RC input fixes and wifi connection reliability improved +- ESP32 safety switch and GPIO pin support +- FlyingMoon no longer support MAX7456 +- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot +- Flywoo H743 Pro support +- Flywoo/Goku F405 HD 1-2S ELRS AIO v2 +- FlywooF745 supports DPS310 baro +- FPV boards lose SMBus battery support (to save flash) +- GEPRC F745BTHD support +- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash) +- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates +- Holybro Kakute F4 Wing support +- iFlight 2RAW H743 supports onboard logging +- JFB110 supports measuring servo rail voltage +- JFB110 supports safety switch LED +- JHEM-JHEF405 bootloader supports firmware updates via serial +- JHEMCU GF30H743 HD support +- JHEMCU-GF16-F405 autopilot support +- JHEMCU-GSF405A becomes FPV board (to save flash) +- KakuteF7 only supports BMP280 baro (to save flash) +- KakuteH7Mini supports ICM42688 IMU +- Linux auto detection of GPS baud rate fixed +- Linux board scheduler jitter reduced +- Linux board shutdown fixes +- MakeFlyEasy PixPilot-V6Pro support +- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash) +- MatekH7A3 support Bi-directional DShot +- MicoAir405v2 and MicoAir405Mini support optical flow and OSD +- MicoAir743 internal compass orientation fixed +- MicroAir405Mini, MicroAir743, NxtPX4v2 support +- MicroAir405v2 Bi-directional DShot and LED DMA fixes +- MicroAir405v2 defined as FPV board with reduced features (to save flash) +- ModalAI VOXL2 support including Starling 2 and Starling 2 max +- mRo Control Zero Classic supports servo rail analog input +- mRo KitCAN revC fixed +- Mugin MUPilot support +- OmnibusF7v2 loses quadplane support (to save flash) +- Pixhack-v3 board added (same as fmuv3) +- Pixhawk6C bootloader supports flashing firmware from SD card +- RadiolinkPIX6 imu orientation fixed +- RadiolinkPIX6 supports SPA06 baro +- ReaperF745 V4 FC supports MPU6000 IMU +- RPI5 support +- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed +- Solo serial ports default to MAVLink1 +- SpeedyBeeF405Wing gets Bi-directional DShot +- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash) +- Spektreworks boom board support +- TrueNavPro-G4 SPI does not share DMA +- X-MAV AP-H743v2 support + +2) AHRS/EKF enhancements and fixes + +- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back) +- AHRS_OPTION to disable innovation check for airspeed sensor +- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity +- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only) +- EK2 supports disabling external nav (see EK2_OPTIONS) +- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1) +- EK3 uses filtered velocity corrections for IMU position +- EKF2, EKF3, ExternalAHRS all use common origin +- EKF3 accepts set origin even when using GPS +- EKF3 allows earth-frame fields to be estimated with an origin but no GPS +- EKF3 copes better with GPS jamming +- EKF3 logs mag fusion selection to XKFS +- EKF3 wind estimation when using GPS-for-yaw fixed +- External AHRS improvements including handling variances, pre-arm origin check +- Inertial Labs External AHRS fixes +- VectorNav driver fix for handling of error from sensor +- VectorNav External AHRS enhancements including validation of config commands and logging improvements +- VectorNav support for sensors outside VN-100 and VN-300 + +3) Driver enhancements and bug fixes + +- ADSB fix to display last character in status text sent to GCS +- Ainstein LR-D1 radar support +- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor +- AIRSPEED message sent to GCS +- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5) +- ARSPD_OPTIONS to report calibration offset to GCS +- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only) +- Baro provides improved atmospheric model for high altitude flight +- BARO_ALT_OFFSET slew slowed to keep EKF happy +- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries +- BATTx_OPTION to not send battery voltage, current, etc to GCS +- Benewake RDS02U radar support +- Bi-directional DShot on IOMCU supports reversible mask +- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs +- BMM350 compass support +- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus) +- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS) +- CRSF baro and vertical speeed fixed +- CRSF RX bind command support +- DroneCAN battery monitor check to avoid memory corruption when type changed +- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info +- DroneCAN EFI health check fix +- DroneCAN ESC battery monitors calculate consumed mah +- DroneCAN ESCs forced to zero when disarmed +- DroneCAN RPM message support +- DroneCAN timeout fix for auxiliary frames +- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600') +- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass +- FuelLevel battery monitor fix to report capacity +- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx +- Hirth EFI logging includes modified throttle +- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter) +- Hott and LTM telemetry deprecated (still available through custom build server) +- i-BUS telemetry support +- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only) +- ICE_START_CHAN replaced with RC aux function (Plane only) +- ICEngine retry max added (see ICE_STRT_MX_RTRY) +- IE 2400 generator error message severity to GCS improved +- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params) +- MCP9600 temperature sensor I2C address fixed +- MLX90614 temperature sensor support +- MSP GPS ground course scaling fixed +- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect) +- Networking supports reconnection to TCP server or client +- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT) +- Relay inverted output support (see RELAYx_INVERTED parameter) +- ROMFS efficiency improvements +- RS-485 driver enable RTS flow control +- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt) +- Septentrio GPS sat count correctly drops to zero when 255 received +- Septentrio supports selecting constellations (see GPS_GNSS_MODE) +- Single LED for user notification supported +- SPA06 baro supported +- Sum battery monitor optionally reports minimum voltage instead of average +- Sum battery monitor reports average temp +- Torqeedo dual motor support (see TRQ1, TRQ2 params) +- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes) +- UBlox GPS time ignored until at least 2D fix +- VideoTX supports additional freq bands (RushFPV 3.3Ghz) +- Volz logs desired and actual position, voltage, current, motor and PCB temp +- Volz server feedback and logging fixed +- Volz servo output in its own thread resulting in smoother movements +- W25N02KV flash support + +4) Networking enhancements and fixes + +- Allow multiple UDP clients to connect/disconnect/reconnect +- Ethernet supports faster log downloading (raised SDMMC clock limit on H7) + +5) Camera and gimbal enhancements + +- Alexmos precision improved slightly +- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC) +- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at +- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame) +- Dual serial camera gimbal mounts fixed +- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS +- Retract Mount2 aux function added (see RCx_OPTION = 113) +- Servo gimbal reported angles respect roll, pitch and yaw limits +- Siyi driver sends autopilot location and speed (recorded in images via EXIF) +- Siyi picture and video download scripts +- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg) +- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script +- Siyi ZT6 hardware id and set-lens fixed +- Topotek gimbal support +- Trigger distance ignores GPS status and only uses EKF reported location + +6) Harmonic notch enhancements + +- Harmonic notch is active in forward flight on quadplanes +- Harmonic notch filter freq clamping and disabling reworked +- Harmonic notch handles negative ESC RPMs +- Harmonic notch supports per-motor throttle-based harmonic notch + +7) Copter specific enhancements and bug fixes + +- Attitude control fix to dt update order (reduces rate controller noise) +- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time +- Auto mode small target position jump when takeoff completes removed +- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None +- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178) +- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command +- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only) +- AutoTune fix to prevent spool up after landing +- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well) +- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180) +- Config error avoided if auto mode is paused very soon after poweron +- FLIGHT_OPTIONS bit added to require position estimate before arming +- Follow mode slowdown calcs fixed when target is moving +- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT) +- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message +- Guided mode internal error resolved when switching between thrust or climb rate based altitude control +- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle +- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down +- Landing detector logging added to ease support (see LDET message) +- Loiter unlimited command accepts NaNs (QGC sends these) +- Mavlink SYSTEM_STATUS set to BOOT during initialisation +- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values +- Payload place bug fix when aborted because gripper is already released +- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219) +- RTL_ALT minimum reduced to 30cm +- SystemID position controller support (Copter and Heli) +- TriCopter motor test and slew-up fixed +- WPNAV_SPEED min reduced to 10 cm/s (Copter only) +- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe + +8) TradHeli specific enhancements + +- Autorotation yaw behaviour fix +- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate +- Blade pitch angle logging added (see SWSH log message) +- Constrain cyclic roll for intermeshing +- ICE / turbine cool down fix +- Inverted flight extended to non manual throttle modes +- Inverted flight transitions smoothed and restricted to only Stabilize mode +- SWSH logging fix for reversed collectives + +9) Plane specific enhancements and bug fixes + +- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling +- Allow for different orientations of landing rangefinder +- Assistance requirements evaluted on mode change +- FBWB/CRUISE climb/sink rate limited by TECS limits +- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope) +- Glider pullup support (available only through custom build server) +- Loiter breakout improved to better handle destinations inside loiter circle +- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled) +- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes +- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition) +- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic +- Quadplane assistance check enhancements +- Quadplane Deca frame support +- Quadplane gets smoother takeoff by input shaping target accel and velocity +- Servo wiggles in altitude wait staged to be one after another +- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames +- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN) +- Takeoff fixes for fence autoenable +- Takeoff improvements including less overshoot of TKOFF_ALT +- TECS reset along with other controllers (important if plane dropped from balloon) +- Tilt quadplane ramp of motors on back transition fixed +- Tiltrotor tilt angles logged +- TKOFF_THR_MIN applied to SLT transitions +- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration +- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff + +10) Rover specific enhancements and bug fixes + +- Auto mode reversed state maintained if momentarily switched to Hold mode +- Circle mode tracks better and avoids getting stuck at circle edge +- Flight time stats fixed +- MAV_CMD_NAV_SET_YAW_SPEED deprecated +- Omni3Mecanum frame support +- Stopping point uses max deceleration (was incorrectly using acceleration) +- Wheel rate controller slew rate fix + +11) Antenna Tracker specific enhancements and bug fixes + +- Never track lat,lon of 0,0 + +12) Scripting enhancements + +- advance-wp.lua applet supports advancing Auto mode WP via RC switch +- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch +- battery_internal_resistance_check.lua monitors battery resistance +- CAN:get_device returns nil for unconfigured CAN device +- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only) +- Copter:get_target_location, update_target_location support +- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only) +- Display text on OLED display supported +- Docs improved for many bindings +- EFI get_last_update_ms binding +- EFI_SkyPower.lua driver accepts 2nd supply voltage +- ESC_slew_rate.lua example script supports testing ESCs +- Filesystem CRC32 check to allow scripts to check module versions +- forced arming support +- GPIO get/set mode bindings (see gpio:set_mode, get_mode) +- GPS-for-yaw angle binding (see gps:gps_yaw_deg) +- Halo6000 EFI driver can log all CAN packets for easier debugging +- handle_external_position_estimate binding allows sending position estimate from lua to EKF +- I2C:transfer support +- IMU gyros_consistent and accels_consistent bindings added +- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control +- INS bindings for is calibrating, gyro and accel sensor values +- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients +- Logging of booleans supported +- Lua language checks improved (finds more errors) +- MAVLink commands can be called from scripting +- MCU voltage binding (see analog:mcu_voltage) +- NMEA 2000 EFI driver (see EFI_NMEA2k.lua) +- "open directory failed" false warning when scripts in ROMFS fixed +- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch +- Pass by reference values are always initialized +- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras +- plane_aerobatics.lua minor enhancements +- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation +- "require" function failures in rare circumstances fixed +- "require" function works for modules in ROMFS (e.g. not on SD card) +- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_) +- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand) +- SD card formatting supported +- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation) +- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter) +- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch +- Slung payload oscillation suppression applet added (see copter-slung-payload.lua) +- Temperature sensor bindings added +- uint64 support +- Various performance and memory usage optimizations +- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8 +- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame + +13) GCS / mavlink related changes and fixes + +- BATTERY2 message deprecated (replaced by BATTERY_STATUS) +- CMD_MISSION_START/STOP rejected if first-item/last-item args provided +- Deny attempts to upload two missions simultaneously +- Fence and Rally points may be uploaded using FTP +- GPS_INPUT and HIL_GPS handles multiple GPSs +- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC) +- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196 +- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support +- MAV_CMD_SET_HAGL support (Plane only) +- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links +- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message) +- Message interval supports TERRAIN_REPORT msg +- Mission upload may be cancelled using MISSION_CLEAR_ALL +- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated +- RC_CHANNELS_RAW deprecated +- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers +- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only) +- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports + +14) Logging enhancements and fixes + +- AC_PID resets and I-term sets logged +- ANG provides attitude at high rate (equivalent to ATT) +- ATT logs angles as floats (better resolution than ints) +- CAND message gets driver index +- DCM log message includes roll/pitch and yaw error +- EDT2 log msg includes stress and status received via extended DShot Telemetry v2 +- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin) +- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct +- FMT messages written as required instead of all at beginning +- Logging restarted after download completes when LOG_DISARMED = 1 +- MISE msg logs active mission command (CMD logged when commands are uploaded) +- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN +- RPM sensor logging gets instance field, quality and health fields +- Short filename support removed (e.g log1.BIN instead of 00000001.BIN) +- Temperature sensor logging option for only sensors with no source (see TEMP_LOG) +- UART data rates logged at 1hz (see UART message) + +15) ROS2 / DDS support + +- Airspeed published +- Battery topic reports all available batteries +- Compile-time configurable rates for each publisher +- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent +- GPS global origin published at 1 Hz +- High frequency raw imu data transmission +- Joystick support +- Support sending waypoints to Copter and Rover +- Remove the XML refs file in favor of binary entity creation + +16) Safety related enhancements and fixes + +- Accel/Gyro inconsistent message fixed for using with only single IMU +- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action +- Far from EKF origin pre-arm check removed (Copter only) +- Fence breach warning message slightly improved +- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS) +- Fences can be stored to SD Card (see BRD_SD_FENCE param) +- ICEngine stopped when in E-Stop or safety engaged (Plane only) +- LEDs flash green lights based on EKF location not GPS +- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS) +- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added +- Pre-arm check if OpenDroneID is compiled in but disabled +- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions) +- Pre-arm checks alert user more quickly on failure +- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE +- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover) +- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on +- Warning of duplicate SERIALx_PROTOCOL = RCIN + +17) Other bug fixes and minor enhancements + +- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher) +- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools +- Bootloader rejects allocation of broadcast node ID +- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI) +- Dijkstras fix to correct use of uninitialised variable +- DShot rates are not limited by NeoPixel rates +- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode +- Filesystem does not show entries for empty @ files +- Filesystem efficiency improvements when reading files +- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset) +- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm) +- Internal error thrown if we lose parameters due to saving queue being too small +- MAVLink via DroneCAN baud rate fix +- SPI pins may also be used as GPIOs +- Terrain cache size configurable (see TERRAIN_CACHE_SZ) + +18) Developer focused fixes and enhancements + +- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams +- Cygwin build fix for non-SITL builds +- Cygwin build fixed with malloc wrap +- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua) +- EKF3 code generator documentation and cleanup +- GPS jamming simulator added +- MacOS compiler warnings reduced +- SFML joystick support +- SITL support for OpenBSD +- Text warning if older Fence or Rally point protocols are used +------------------------------------------------------------------ +Release 4.5.7 08 Oct 2024 + +Changes from 4.5.7-beta1 + +1) Reverted Septentrio GPS sat count correctly drops to zero when 255 received +------------------------------------------------------------------ +Release 4.5.7-beta1 26 Sep 2024 + +Changes from 4.5.6 + +1) Bug fixes and minor enhancements + +- VUAV-V7pro support +- CUAV-7-Nano correction for LEDs and battery volt and current scaling +- DroneCAN deadlock and saturation of CAN bus fixed +- DroneCAN DNA server init fix (caused logging issues and spam on bus) +- F4 boards with inverter support correctly uninvert RX/TX +- Nanoradar M72 radar driver fix for object avoidance path planning +- Plane fix to ability to disable the takeoff atititude checks +- RC support for latest version of GHST +- Septentrio GPS sat count correctly drops to zero when 255 received + +2) ROS2/DDS and other developer focused enhancements + +- AP quaternions normalised for ROS2 to avoid warnings +- Dependencies fixed for easier installation +- ROS2 SITL launch file enhancements including displaying console and map +- ROS_DOMAIN_ID param added to support multiple vehicles or instances of ROS2 +- Python 3.12 support +------------------------------------------------------------------ +Release 4.5.6 03 Sep 2024 + +No changes from 4.5.6-beta1 +------------------------------------------------------------------ +Release 4.5.6-beta1 20 Aug 2024 + +Changes from 4.5.5 + +1) Board specific enhancements and bug fixes + +- 3DR Control Zero H7 Rev G support +- CUAV-7-Nano support +- FoxeerF405v2 servo outputs increased from 9 to 11 +- Holybro Pixhawk6C hi-power peripheral overcurrent reporting fixed +- iFlight 2RAW H7 support +- MFT-SEMA100 support +- TMotorH743 support BMI270 baro +- ZeroOneX6 support + +2) Minor enhancements and bug fixes + +- Cameras using MAVLink report vendor and model name correctly +- DroneCAN fix to remove occasional NodeID registration error +- GPS NMEA and GSoF driver ground course corrected (now always 0 ~ 360 deg) +- ICP101XX barometer slowed to avoid I2C communication errors +- IMU temp cal param (INSn_ACCSCAL_Z) stored correctly when bootloader is flashed +- IMU gyro/accel duplicate id registration fixed to avoid possible pre-arm failure +- Logging to flash timestamp fix +- OSD displays ESC temp instead of motor temp +- PID controller error calculation bug fix (was using target from prev iteration) +- Relay on MAIN pins fixed +------------------------------------------------------------------ +Release 4.5.5 1st Aug 2024 + +No changes from 4.5.5-beta2 +------------------------------------------------------------------ +Release 4.5.5-beta2 27 July 2024 + +Changes from 4.5.5-beta1 + +1) Board specific enhancements and bug fixes + +- CubeRed's second core disabled at boot to avoid spurious writes to RAM +- CubeRed bootloader's dual endpoint update method fixed +------------------------------------------------------------------ +Release 4.5.5-beta1 1st July 2024 + +Changes from 4.5.4 + +1) Board specific enhancements and bug fixes + +- fixed IOMCU transmission errors when using bdshot +- update relay parameter names on various boards +- add ASP5033 airspeed in minimal builds +- added RadiolinkPIX6 +- fix Aocoda-RC H743Dual motor issue +- use ICM45686 as an ICM20649 alternative in CubeRedPrimary + +2) System level minor enhancements and bug fixes + +- correct use-after-free in script statistics +- added arming check for eeprom full +- fixed a block logging issue which caused log messages to be dropped +- enable Socket SO_REUSEADDR on LwIP +- removed IST8310 overrun message +- added Siyi ZT6 support +- added BTFL sidebar symbols to the OSD +- added CRSF extended link stats to the OSD +- use the ESC with the highest RPM in the OSD when only one can be displayed +- support all Tramp power levels on high power VTXs +- emit jump count in missions even if no limit +- improve the bitmask indicating persistent parameters on bootloader flash +- fix duplicate error condition in the MicroStrain7 + +3) AHRS / EKF fixes + +- fix infinite climb bug when using EK3_OGN_HGT_MASK + +4) Plane specific changes + +- fix rangefinder correction when terrain following is off +- correct description of MIN_GROUNDSPEED parameter +- correct Q_TRIM_PITCH description +- ensure the dshot type gets set at startup + +5) Other minor enhancements and bug fixes + +- specify pymonocypher version in more places +- added DroneCAN dependencies to custom builds + +------------------------------------------------------------------ +Release 4.5.4 12th June 2024 + +Changes from 4.5.3 + +Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X + +------------------------------------------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Plane specific changes + +- fixed cancelling of FWD_GAIN setting for tiltrotors + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Plane specific changes + +- Drop min Q_TRANSITION_MS to 500ms +- FBWB/CRUISE missing zero crossing of elevator input fix +- PTCH_LIM_MIN_DEG param units fixed to be deg + +5) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + Release 4.5.1 8th April 2024 ---------------------------- diff --git a/ArduPlane/VTOL_Assist.cpp b/ArduPlane/VTOL_Assist.cpp new file mode 100644 index 00000000000000..f071b5865d49bf --- /dev/null +++ b/ArduPlane/VTOL_Assist.cpp @@ -0,0 +1,143 @@ +#include "Plane.h" + +#if HAL_QUADPLANE_ENABLED + +// Assistance hysteresis helpers + +// Reset state +void VTOL_Assist::Assist_Hysteresis::reset() +{ + start_ms = 0; + last_ms = 0; + active = false; +} + +// Update state, return true when first triggered +bool VTOL_Assist::Assist_Hysteresis::update(const bool trigger, const uint32_t &now_ms, const uint32_t &trigger_delay_ms, const uint32_t &clear_delay_ms) +{ + bool ret = false; + + if (trigger) { + last_ms = now_ms; + if (start_ms == 0) { + start_ms = now_ms; + } + if ((now_ms - start_ms) > trigger_delay_ms) { + // trigger delay has elapsed + if (!active) { + // return true on first trigger + ret = true; + } + active = true; + } + + } else if (active) { + if ((last_ms == 0) || ((now_ms - last_ms) > clear_delay_ms)) { + // Clear delay passed + reset(); + } + + } else { + reset(); + } + + return ret; +} + +// Assistance not needed, reset any state +void VTOL_Assist::reset() +{ + force_assist = false; + speed_assist = false; + angle_error.reset(); + alt_error.reset(); +} + +/* + return true if the quadplane should provide stability assistance + */ +bool VTOL_Assist::should_assist(float aspeed, bool have_airspeed) +{ + if (!plane.arming.is_armed_and_safety_off() || (state == STATE::ASSIST_DISABLED) || quadplane.tailsitter.is_control_surface_tailsitter()) { + // disarmed or disabled by aux switch or because a control surface tailsitter + reset(); + return false; + } + + if (!quadplane.tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) + || is_positive(plane.get_throttle_input()) + || plane.is_flying() ) ) { + // not in a flight mode and condition where it would be safe to turn on vertial lift motors + // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes + reset(); + return false; + } + + if (plane.flare_mode != Plane::FlareMode::FLARE_DISABLED) { + // Never active in fixed wing flare + reset(); + return false; + } + + force_assist = state == STATE::FORCE_ENABLED; + + if (speed <= 0) { + // all checks disabled via speed threshold, still allow force enabled + speed_assist = false; + alt_error.reset(); + angle_error.reset(); + return force_assist; + } + + // assistance due to Q_ASSIST_SPEED + // if option bit is enabled only allow assist with real airspeed sensor + speed_assist = (have_airspeed && aspeed < speed) && + (!quadplane.option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || plane.ahrs.using_airspeed_sensor()); + + const uint32_t now_ms = AP_HAL::millis(); + const uint32_t tigger_delay_ms = delay * 1000; + const uint32_t clear_delay_ms = tigger_delay_ms * 2; + + /* + optional assistance when altitude is too close to the ground + */ + if (alt <= 0) { + // Alt assist disabled + alt_error.reset(); + + } else { + const float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); + if (alt_error.update(height_above_ground < alt, now_ms, tigger_delay_ms, clear_delay_ms)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground); + } + } + + if (angle <= 0) { + // Angle assist disabled + angle_error.reset(); + + } else { + + /* + now check if we should provide assistance due to attitude error + */ + const uint16_t allowed_envelope_error_cd = 500U; + const bool inside_envelope = (labs(plane.ahrs.roll_sensor) <= (plane.aparm.roll_limit*100 + allowed_envelope_error_cd)) && + (plane.ahrs.pitch_sensor < (plane.aparm.pitch_limit_max*100 + allowed_envelope_error_cd)) && + (plane.ahrs.pitch_sensor > (plane.aparm.pitch_limit_min*100 - allowed_envelope_error_cd)); + + const int32_t max_angle_cd = 100U*angle; + const bool inside_angle_error = (labs(plane.ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd) && + (labs(plane.ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd); + + if (angle_error.update(!inside_envelope && !inside_angle_error, now_ms, tigger_delay_ms, clear_delay_ms)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d", + (int)(plane.ahrs.roll_sensor/100), + (int)(plane.ahrs.pitch_sensor/100)); + } + } + + return force_assist || speed_assist || alt_error.is_active() || angle_error.is_active(); +} + +#endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/VTOL_Assist.h b/ArduPlane/VTOL_Assist.h new file mode 100644 index 00000000000000..c3582236501736 --- /dev/null +++ b/ArduPlane/VTOL_Assist.h @@ -0,0 +1,72 @@ +#pragma once + +// VTOL assistance in a forward flight mode + +class QuadPlane; +class VTOL_Assist { +public: + VTOL_Assist(QuadPlane& _quadplane):quadplane(_quadplane) {}; + + // check for assistance needed + bool should_assist(float aspeed, bool have_airspeed); + + // Assistance not needed, reset any state + void reset(); + + // speed below which quad assistance is given + AP_Float speed; + + // angular error at which quad assistance is given + AP_Int8 angle; + + // altitude to trigger assistance + AP_Int16 alt; + + // Time hysteresis for triggering of assistance + AP_Float delay; + + // State from pilot + enum class STATE { + ASSIST_DISABLED, + ASSIST_ENABLED, + FORCE_ENABLED, + }; + void set_state(STATE _state) { state = _state; } + + // Logging getters for assist types + bool in_force_assist() const { return force_assist; } + bool in_speed_assist() const { return speed_assist; } + bool in_alt_assist() const { return alt_error.is_active(); } + bool in_angle_assist() const { return angle_error.is_active(); } + +private: + + // Default to enabled + STATE state = STATE::ASSIST_ENABLED; + + class Assist_Hysteresis { + public: + // Reset state + void reset(); + + // Update state, return true when first triggered + bool update(const bool trigger, const uint32_t &now_ms, const uint32_t &trigger_delay_ms, const uint32_t &clear_delay_ms); + + // Return true if the output is active + bool is_active() const { return active; } + + private: + uint32_t start_ms; + uint32_t last_ms; + bool active; + }; + Assist_Hysteresis angle_error; + Assist_Hysteresis alt_error; + + // Force and speed assist have no hysteresis + bool force_assist; + bool speed_assist; + + // Reference to access quadplane + QuadPlane& quadplane; +}; diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 04ca8440570745..230a16d067d0e9 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -44,7 +44,7 @@ void Plane::check_home_alt_change(void) next_WP_loc.alt += alt_change_cm; } // reset TECS to force the field elevation estimate to reset - TECS_controller.reset(); + TECS_controller.offset_altitude(alt_change_cm * 0.01f); } auto_state.last_home_alt_cm = home_alt_cm; } @@ -81,6 +81,13 @@ void Plane::setup_glide_slope(void) break; case Mode::Number::AUTO: + + //climb without doing glide slope if option is enabled + if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) { + reset_offset_altitude(); + break; + } + // we only do glide slide handling in AUTO when above 20m or // when descending. The 20 meter threshold is arbitrary, and // is basically to prevent situations where we try to slowly @@ -115,13 +122,23 @@ int32_t Plane::get_RTL_altitude_cm() const */ float Plane::relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available) { +#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + float height_AGL; + // use external HAGL if available + if (get_external_HAGL(height_AGL)) { + return height_AGL; + } +#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + +#if AP_RANGEFINDER_ENABLED if (use_rangefinder_if_available && rangefinder_state.in_range) { return rangefinder_state.height_estimate; } +#endif -#if HAL_QUADPLANE_ENABLED +#if HAL_QUADPLANE_ENABLED && AP_RANGEFINDER_ENABLED if (use_rangefinder_if_available && quadplane.in_vtol_land_final() && - rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow) { + rangefinder.status_orient(rangefinder_orientation()) == RangeFinder::Status::OutOfRangeLow) { // a special case for quadplane landing when rangefinder goes // below minimum. Consider our height above ground to be zero return 0; @@ -252,8 +269,10 @@ int32_t Plane::relative_target_altitude_cm(void) target_altitude.lookahead = lookahead_adjustment(); relative_home_height += target_altitude.lookahead; +#if AP_RANGEFINDER_ENABLED // correct for rangefinder data relative_home_height += rangefinder_correction(); +#endif // we are following terrain, and have terrain data for the // current location. Use it. @@ -262,7 +281,9 @@ int32_t Plane::relative_target_altitude_cm(void) #endif int32_t relative_alt = target_altitude.amsl_cm - home.alt; relative_alt += mission_alt_offset()*100; +#if AP_RANGEFINDER_ENABLED relative_alt += rangefinder_correction() * 100; +#endif return relative_alt; } @@ -499,9 +520,9 @@ int32_t Plane::adjusted_altitude_cm(void) } /* - return home-relative altitude adjusted for ALT_OFFSET This is useful + return home-relative altitude adjusted for ALT_OFFSET. This is useful during long flights to account for barometer changes from the GCS, - or to adjust the flying height of a long mission + or to adjust the flying height of a long mission. */ int32_t Plane::adjusted_relative_altitude_cm(void) { @@ -608,6 +629,7 @@ float Plane::lookahead_adjustment(void) } +#if AP_RANGEFINDER_ENABLED /* correct target altitude using rangefinder data. Returns offset in meters to correct target altitude. A positive number means we need @@ -657,16 +679,36 @@ void Plane::rangefinder_terrain_correction(float &height) */ void Plane::rangefinder_height_update(void) { - float distance = rangefinder.distance_orient(ROTATION_PITCH_270); - - if ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::Good) && ahrs.home_is_set()) { + const auto orientation = rangefinder_orientation(); + bool range_ok = rangefinder.status_orient(orientation) == RangeFinder::Status::Good; + float distance = rangefinder.distance_orient(orientation); + float corrected_distance = distance; + + /* + correct distance for attitude + */ + if (range_ok) { + // correct the range for attitude + const auto &dcm = ahrs.get_rotation_body_to_ned(); + + Vector3f v{corrected_distance, 0, 0}; + v.rotate(orientation); + v = dcm * v; + + if (!is_positive(v.z)) { + // not pointing at the ground + range_ok = false; + } else { + corrected_distance = v.z; + } + } + + if (range_ok && ahrs.home_is_set()) { if (!rangefinder_state.have_initial_reading) { rangefinder_state.have_initial_reading = true; rangefinder_state.initial_range = distance; } - // correct the range for attitude (multiply by DCM.c.z, which - // is cos(roll)*cos(pitch)) - rangefinder_state.height_estimate = distance * ahrs.get_rotation_body_to_ned().c.z; + rangefinder_state.height_estimate = corrected_distance; rangefinder_terrain_correction(rangefinder_state.height_estimate); @@ -677,10 +719,10 @@ void Plane::rangefinder_height_update(void) // to misconfiguration or a faulty sensor if (rangefinder_state.in_range_count < 10) { if (!is_equal(distance, rangefinder_state.last_distance) && - fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)*0.01f) { + fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01f) { rangefinder_state.in_range_count++; } - if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)*0.01*0.2) { + if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01*0.2) { // changes by more than 20% of full range will reset counter rangefinder_state.in_range_count = 0; } @@ -711,9 +753,8 @@ void Plane::rangefinder_height_update(void) } if (rangefinder_state.in_range) { - // base correction is the difference between baro altitude and - // rangefinder estimate - float correction = adjusted_relative_altitude_cm()*0.01 - rangefinder_state.height_estimate; + // If not using terrain data, we expect zero correction when our height above target is equal to our rangefinder measurement + float correction = height_above_target() - rangefinder_state.height_estimate; #if AP_TERRAIN_AVAILABLE // if we are terrain following then correction is based on terrain data @@ -748,6 +789,7 @@ void Plane::rangefinder_height_update(void) } } +#endif // AP_RANGEFINDER_ENABLED /* determine if Non Auto Terrain Disable is active and allowed in present control mode @@ -803,3 +845,67 @@ bool Plane::terrain_enabled_in_mode(Mode::Number num) const return false; } #endif + +#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED +/* + handle a MAV_CMD_SET_HAGL request. The accuracy is ignored + */ +void Plane::handle_external_hagl(const mavlink_command_int_t &packet) +{ + auto &hagl = plane.external_hagl; + hagl.hagl = packet.param1; + hagl.last_update_ms = AP_HAL::millis(); + hagl.timeout_ms = uint32_t(packet.param3 * 1000); +} + +/* + get HAGL from external source if current + */ +bool Plane::get_external_HAGL(float &height_agl) +{ + auto &hagl = plane.external_hagl; + if (hagl.last_update_ms != 0) { + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - hagl.last_update_ms <= hagl.timeout_ms) { + height_agl = hagl.hagl; + return true; + } + hagl.last_update_ms = 0; + } + return false; +} +#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + +/* + get height for landing. Set using_rangefinder to true if a rangefinder + or external HAGL source is active + */ +float Plane::get_landing_height(bool &rangefinder_active) +{ + float height; + +#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED + // if external HAGL is active use that + if (get_external_HAGL(height)) { + // ensure no terrain correction is applied - that is the job + // of the external system if it is wanted + auto_state.terrain_correction = 0; + + // an external HAGL is considered to be a type of rangefinder + rangefinder_active = true; + return height; + } +#endif + + // get basic height above target + height = height_above_target(); + rangefinder_active = false; + +#if AP_RANGEFINDER_ENABLED + // possibly correct with rangefinder + height -= rangefinder_correction(); + rangefinder_active = g.rangefinder_landing && rangefinder_state.in_range; +#endif + + return height; +} diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 215b4cf05e20d1..90c3e024800c6e 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -12,13 +12,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) plane.target_altitude.terrain_following_pending = false; #endif -#if HAL_LOGGING_ENABLED - // log when new commands start - if (should_log(MASK_LOG_CMD)) { - logger.Write_Mission_Cmd(mission, cmd); - } -#endif - // special handling for nav vs non-nav commands if (AP_Mission::is_nav_cmd(cmd)) { // set takeoff_complete to true so we don't add extra elevator @@ -27,6 +20,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) nav_controller->set_data_is_stale(); + // start non-idle + auto_state.idle_mode = false; + // reset loiter start time. New command is a new loiter loiter.start_time_ms = 0; @@ -92,6 +88,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_NAV_ALTITUDE_WAIT: + do_altitude_wait(cmd); break; #if HAL_QUADPLANE_ENABLED @@ -144,21 +141,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_LAND_START: break; - case MAV_CMD_DO_FENCE_ENABLE: -#if AP_FENCE_ENABLED - if (cmd.p1 == 0) { // disable fence - plane.fence.enable(false); - gcs().send_text(MAV_SEVERITY_INFO, "Fence disabled"); - } else if (cmd.p1 == 1) { // enable fence - plane.fence.enable(true); - gcs().send_text(MAV_SEVERITY_INFO, "Fence enabled"); - } else if (cmd.p1 == 2) { // disable fence floor only - plane.fence.disable_floor(); - gcs().send_text(MAV_SEVERITY_INFO, "Fence floor disabled"); - } -#endif - break; - case MAV_CMD_DO_AUTOTUNE_ENABLE: autotune_enable(cmd.p1); break; @@ -255,14 +237,16 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret } else { // use rangefinder to correct if possible - float height = height_above_target() - rangefinder_correction(); + bool rangefinder_active = false; + float height = plane.get_landing_height(rangefinder_active); + // for flare calculations we don't want to use the terrain // correction as otherwise we will flare early on rising // ground height -= auto_state.terrain_correction; return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc, height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(), - g.rangefinder_landing && rangefinder_state.in_range); + rangefinder_active); } case MAV_CMD_NAV_LOITER_UNLIM: @@ -284,7 +268,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret return verify_continue_and_change_alt(); case MAV_CMD_NAV_ALTITUDE_WAIT: - return verify_altitude_wait(cmd); + return mode_auto.verify_altitude_wait(cmd); #if HAL_QUADPLANE_ENABLED case MAV_CMD_NAV_VTOL_TAKEOFF: @@ -350,7 +334,6 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm); setup_terrain_target_alt(next_WP_loc); set_target_altitude_location(next_WP_loc); - plane.altitude_error_cm = calc_altitude_error_cm(); if (aparm.loiter_radius < 0) { loiter.direction = -1; @@ -390,7 +373,7 @@ void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd) next_WP_loc.lat = home.lat + 10; next_WP_loc.lng = home.lng + 10; auto_state.takeoff_speed_time_ms = 0; - auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction + auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction. auto_state.height_below_takeoff_to_level_off_cm = 0; // Flag also used to override "on the ground" throttle disable @@ -410,7 +393,7 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd) set_next_WP(cmd.content.location); // configure abort altitude and pitch - // if NAV_LAND has an abort altitude then use it, else use last takeoff, else use 50m + // if NAV_LAND has an abort altitude then use it, else use last takeoff, else use 30m if (cmd.p1 > 0) { auto_state.takeoff_altitude_rel_cm = (int16_t)cmd.p1 * 100; } else if (auto_state.takeoff_altitude_rel_cm <= 0) { @@ -422,8 +405,10 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd) auto_state.takeoff_pitch_cd = 1000; } +#if AP_RANGEFINDER_ENABLED // zero rangefinder state, start to accumulate good samples now memset(&rangefinder_state, 0, sizeof(rangefinder_state)); +#endif landing.do_land(cmd, relative_altitude); @@ -431,10 +416,6 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd) // if we were in an abort we need to explicitly move out of the abort state, as it's sticky set_flight_stage(AP_FixedWing::FlightStage::LAND); } - -#if AP_FENCE_ENABLED - plane.fence.auto_disable_fence_for_landing(); -#endif } #if HAL_QUADPLANE_ENABLED @@ -445,7 +426,7 @@ void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd) loc.sanitize(current_loc); set_next_WP(loc); - vtol_approach_s.approach_stage = LOITER_TO_ALT; + vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT; } #endif @@ -517,6 +498,15 @@ void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd) reset_offset_altitude(); } +void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd) +{ + // set all servos to trim until we reach altitude or descent speed + auto_state.idle_mode = true; +#if AP_PLANE_GLIDER_PULLUP_ENABLED + mode_auto.pullup.reset(); +#endif +} + void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) { //set target alt @@ -845,26 +835,54 @@ bool Plane::verify_continue_and_change_alt() /* see if we have reached altitude or descent speed */ -bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) +bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) { - if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) { +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (pullup.in_pullup()) { + return pullup.verify_pullup(); + } +#endif + + /* + the target altitude in param1 is always AMSL + */ + const float alt_diff = plane.current_loc.alt*0.01 - cmd.content.altitude_wait.altitude; + bool completed = false; + if (alt_diff > 0) { gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude"); - return true; + completed = true; + } else if (cmd.content.altitude_wait.descent_rate > 0 && + plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) { + gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate); + completed = true; } - if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) { - gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)auto_state.sink_rate); - return true; + + if (completed) { +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (pullup.pullup_start()) { + // we are doing a pullup, ALTITUDE_WAIT not complete until pullup is done + return false; + } +#endif + return true; } - // if requested, wiggle servos - if (cmd.content.altitude_wait.wiggle_time != 0) { - static uint32_t last_wiggle_ms; - if (auto_state.idle_wiggle_stage == 0 && - AP_HAL::millis() - last_wiggle_ms > cmd.content.altitude_wait.wiggle_time*1000) { - auto_state.idle_wiggle_stage = 1; - last_wiggle_ms = AP_HAL::millis(); + const float time_to_alt = alt_diff / MIN(plane.auto_state.sink_rate, -0.01); + + /* + if requested, wiggle servos + + we don't start a wiggle if we expect to release soon as we don't + want the servos to be off trim at the time of release + */ + if (cmd.content.altitude_wait.wiggle_time != 0 && + (plane.auto_state.sink_rate > 0 || time_to_alt > cmd.content.altitude_wait.wiggle_time*5)) { + if (wiggle.stage == 0 && + AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) { + wiggle.stage = 1; + wiggle.last_ms = AP_HAL::millis(); + // idle_wiggle_stage is updated in wiggle_servos() } - // idle_wiggle_stage is updated in set_servos_idle() } return false; @@ -1033,7 +1051,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) loiter.direction = direction; switch (vtol_approach_s.approach_stage) { - case RTL: + case VTOLApproach::Stage::RTL: { // fly home and loiter at RTL alt nav_controller->update_loiter(cmd.content.location, abs_radius, direction); @@ -1041,11 +1059,11 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) // decend to Q RTL alt plane.do_RTL(plane.home.alt + plane.quadplane.qrtl_alt*100UL); plane.loiter_angle_reset(); - vtol_approach_s.approach_stage = LOITER_TO_ALT; + vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT; } break; } - case LOITER_TO_ALT: + case VTOLApproach::Stage::LOITER_TO_ALT: { nav_controller->update_loiter(cmd.content.location, abs_radius, direction); @@ -1053,11 +1071,11 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) Vector3f wind = ahrs.wind_estimate(); vtol_approach_s.approach_direction_deg = degrees(atan2f(-wind.y, -wind.x)); gcs().send_text(MAV_SEVERITY_INFO, "Selected an approach path of %.1f", (double)vtol_approach_s.approach_direction_deg); - vtol_approach_s.approach_stage = ENSURE_RADIUS; + vtol_approach_s.approach_stage = VTOLApproach::Stage::ENSURE_RADIUS; } break; } - case ENSURE_RADIUS: + case VTOLApproach::Stage::ENSURE_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 @@ -1067,10 +1085,10 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) nav_controller->update_loiter(cmd.content.location, abs_radius, direction); break; } - vtol_approach_s.approach_stage = WAIT_FOR_BREAKOUT; + vtol_approach_s.approach_stage = VTOLApproach::Stage::WAIT_FOR_BREAKOUT; FALLTHROUGH; } - case WAIT_FOR_BREAKOUT: + case VTOLApproach::Stage::WAIT_FOR_BREAKOUT: { nav_controller->update_loiter(cmd.content.location, radius, direction); @@ -1079,7 +1097,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) // breakout when within 5 degrees of the opposite direction if (fabsF(wrap_PI(ahrs.get_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; + vtol_approach_s.approach_stage = VTOLApproach::Stage::APPROACH_LINE; set_next_WP(cmd.content.location); // fallthrough } else { @@ -1087,7 +1105,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } FALLTHROUGH; } - case APPROACH_LINE: + case VTOLApproach::Stage::APPROACH_LINE: { // project an apporach path Location start = cmd.content.location; @@ -1116,7 +1134,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } if (past_finish_line && (lined_up || half_radius)) { - vtol_approach_s.approach_stage = VTOL_LANDING; + vtol_approach_s.approach_stage = VTOLApproach::Stage::VTOL_LANDING; quadplane.do_vtol_land(cmd); // fallthrough } else { @@ -1124,7 +1142,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } FALLTHROUGH; } - case VTOL_LANDING: + case VTOLApproach::Stage::VTOL_LANDING: // nothing to do here, we should be into the quadplane landing code return true; } @@ -1308,3 +1326,4 @@ bool Plane::in_auto_mission_id(uint16_t command) const { return control_mode == &mode_auto && mission.get_current_nav_id() == command; } + diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 254165a0027e60..52a54c467339da 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -2,14 +2,6 @@ #include "defines.h" -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// // HARDWARE CONFIGURATION AND CONNECTIONS @@ -213,18 +205,8 @@ # define FENCE_TRIGGERED_PIN -1 #endif -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE -#define PARACHUTE HAL_PARACHUTE_ENABLED -#endif - -#ifndef OSD_ENABLED - #define OSD_ENABLED DISABLED -#endif - -#ifndef OFFBOARD_GUIDED - #define OFFBOARD_GUIDED 1 +#ifndef AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED + #define AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index fac041ad667e41..a3da572611c77c 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -64,18 +64,6 @@ enum class RtlAutoland { }; -enum ChannelMixing { - MIXING_DISABLED = 0, - MIXING_UPUP = 1, - MIXING_UPDN = 2, - MIXING_DNUP = 3, - MIXING_DNDN = 4, - MIXING_UPUP_SWP = 5, - MIXING_UPDN_SWP = 6, - MIXING_DNUP_SWP = 7, - MIXING_DNDN_SWP = 8, -}; - // PID broadcast bitmask enum tuning_pid_bits { TUNING_BITS_ROLL = (1 << 0), @@ -103,6 +91,7 @@ enum log_messages { LOG_AETR_MSG, LOG_OFG_MSG, LOG_TSIT_MSG, + LOG_TILT_MSG, }; #define MASK_LOG_ATTITUDE_FAST (1<<0) @@ -167,6 +156,7 @@ enum FlightOptions { DISABLE_GROUND_PID_SUPPRESSION = (1<<11), ENABLE_LOITER_ALT_CONTROL = (1<<12), INDICATE_WAITING_FOR_RUDDER_NEUTRAL = (1<<13), + IMMEDIATE_CLIMB_IN_AUTO = (1<<14), }; enum CrowFlapOptions { diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 12abb98e3ba5af..64127c633c1818 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -138,7 +138,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason break; } if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { @@ -187,7 +187,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason case Mode::Number::GUIDED: if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { @@ -311,7 +311,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) break; case Failsafe_Action_Parachute: -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute_release(); #endif break; diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index 33062460df6b0e..1890e709d25b0c 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -8,9 +8,32 @@ void Plane::fence_check() { const uint8_t orig_breaches = fence.get_breaches(); + const bool armed = arming.is_armed(); + + uint16_t mission_id = plane.mission.get_current_nav_cmd().id; + bool landing_or_landed = plane.flight_stage == AP_FixedWing::FlightStage::LAND + || !armed +#if HAL_QUADPLANE_ENABLED + || control_mode->mode_number() == Mode::Number::QLAND + || quadplane.in_vtol_land_descent() +#endif + || (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING); // check for new breaches; new_breaches is bitmask of fence types breached - const uint8_t new_breaches = fence.check(); + const uint8_t new_breaches = fence.check(landing_or_landed); + + /* + if we are either disarmed or we are currently not in breach and + we are not flying then clear the state associated with the + previous mode breach handling. This allows the fence state + machine to reset at the end of a fence breach action such as an + RTL and autoland + */ + if (plane.previous_mode_reason == ModeReason::FENCE_BREACHED) { + if (!armed || ((new_breaches == 0 && orig_breaches == 0) && !plane.is_flying())) { + plane.previous_mode_reason = ModeReason::UNKNOWN; + } + } if (!fence.enabled()) { // Switch back to the chosen control mode if still in @@ -34,7 +57,7 @@ void Plane::fence_check() // we still don't do anything when disarmed, but we do check for fence breaches. // fence pre-arm check actually checks if any fence has been breached // that's not ever going to be true if we don't call check on AP_Fence while disarmed - if (!arming.is_armed()) { + if (!armed) { return; } @@ -50,7 +73,7 @@ void Plane::fence_check() } if (new_breaches) { - GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence Breached"); + fence.print_fence_message("breached", new_breaches); // if the user wants some kind of response and motors are armed const uint8_t fence_act = fence.get_action(); @@ -115,7 +138,8 @@ void Plane::fence_check() } LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); - } else if (orig_breaches) { + } else if (orig_breaches && fence.get_breaches() == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared"); // record clearing of breach LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 979a640a69ee4a..7118f352fe20f2 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -162,7 +162,7 @@ void Plane::update_is_flying_5Hz(void) #if HAL_ADSB_ENABLED adsb.set_is_flying(new_is_flying); #endif -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.set_is_flying(new_is_flying); #endif #if AP_STATS_ENABLED diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index 30ec5fc5b0fb1b..8bece6d4187c32 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -1,14 +1,15 @@ #include "Plane.h" Mode::Mode() : - ahrs(plane.ahrs) + unused_integer{17}, #if HAL_QUADPLANE_ENABLED - , quadplane(plane.quadplane), pos_control(plane.quadplane.pos_control), attitude_control(plane.quadplane.attitude_control), loiter_nav(plane.quadplane.loiter_nav), - poscontrol(plane.quadplane.poscontrol) + quadplane(plane.quadplane), + poscontrol(plane.quadplane.poscontrol), #endif + ahrs(plane.ahrs) { } @@ -54,13 +55,12 @@ bool Mode::enter() plane.guided_state.last_forced_rpy_ms.zero(); plane.guided_state.last_forced_throttle_ms = 0; -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED plane.guided_state.target_heading = -4; // radians here are in range -3.14 to 3.14, so a default value needs to be outside that range 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; + plane.guided_state.target_location.set_alt_cm(-1, Location::AltFrame::ABSOLUTE); #endif #if AP_CAMERA_ENABLED @@ -101,6 +101,9 @@ bool Mode::enter() plane.target_altitude.terrain_following_pending = false; #endif + // disable auto mode servo idle during altitude wait command + plane.auto_state.idle_mode = false; + bool enter_result = _enter(); if (enter_result) { @@ -138,6 +141,14 @@ bool Mode::enter() // Make sure the flight stage is correct for the new mode plane.update_flight_stage(); + +#if HAL_QUADPLANE_ENABLED + if (quadplane.enabled()) { + float aspeed; + bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); + quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed); + } +#endif } return enter_result; @@ -168,7 +179,9 @@ void Mode::update_target_altitude() plane.set_target_altitude_location(plane.next_WP_loc); } else if (plane.landing.is_on_approach()) { plane.landing.setup_landing_glide_slope(plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.target_altitude.offset_cm); +#if AP_RANGEFINDER_ENABLED plane.landing.adjust_landing_slope_for_rangefinder_bump(plane.rangefinder_state, plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.auto_state.wp_distance, plane.target_altitude.offset_cm); +#endif } else if (plane.landing.get_target_altitude_location(target_location)) { plane.set_target_altitude_location(target_location); #if HAL_SOARING_ENABLED @@ -191,8 +204,6 @@ void Mode::update_target_altitude() } else { plane.set_target_altitude_location(plane.next_WP_loc); } - - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } // returns true if the vehicle can be armed in this mode @@ -245,6 +256,9 @@ void Mode::reset_controllers() // reset steering controls plane.steer_state.locked_course = false; plane.steer_state.locked_course_err = 0; + + // reset TECS + plane.TECS_controller.reset(); } bool Mode::is_taking_off() const diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index a217c2bf7d8e18..213e547c6a6682 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -9,6 +9,13 @@ #include "quadplane.h" #include #include +#include "pullup.h" + +#ifndef AP_QUICKTUNE_ENABLED +#define AP_QUICKTUNE_ENABLED HAL_QUADPLANE_ENABLED +#endif + +#include class AC_PosControl; class AC_AttitudeControl_Multi; @@ -80,7 +87,7 @@ class Mode // returns true if the vehicle can be armed in this mode bool pre_arm_checks(size_t buflen, char *buffer) const; - // Reset rate and steering controllers + // Reset rate and steering and TECS controllers void reset_controllers(); // @@ -141,6 +148,11 @@ class Mode // true if voltage correction should be applied to throttle virtual bool use_battery_compensation() const; +#if AP_QUICKTUNE_ENABLED + // does this mode support VTOL quicktune? + virtual bool supports_quicktune() const { return false; } +#endif + protected: // subclasses override this to perform checks before entering the mode @@ -158,6 +170,9 @@ class Mode // Output pilot throttle, this is used in stabilized modes without auto throttle control void output_pilot_throttle(); + // makes the initialiser list in the constructor manageable + uint8_t unused_integer; + #if HAL_QUADPLANE_ENABLED // References for convenience, used by QModes AC_PosControl*& pos_control; @@ -208,6 +223,7 @@ friend class ModeQAcro; class ModeAuto : public Mode { public: + friend class Plane; Number mode_number() const override { return Number::AUTO; } const char *name() const override { return "AUTO"; } @@ -233,8 +249,14 @@ class ModeAuto : public Mode void do_nav_delay(const AP_Mission::Mission_Command& cmd); bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); + bool verify_altitude_wait(const AP_Mission::Mission_Command& cmd); + void run() override; +#if AP_PLANE_GLIDER_PULLUP_ENABLED + bool in_pullup() const { return pullup.in_pullup(); } +#endif + protected: bool _enter() override; @@ -249,6 +271,16 @@ class ModeAuto : public Mode uint32_t time_start_ms; } nav_delay; + // wiggle state and timer for NAV_ALTITUDE_WAIT + void wiggle_servos(); + struct { + uint8_t stage; + uint32_t last_ms; + } wiggle; + +#if AP_PLANE_GLIDER_PULLUP_ENABLED + GliderPullup pullup; +#endif // AP_PLANE_GLIDER_PULLUP_ENABLED }; @@ -304,6 +336,9 @@ class ModeGuided : public Mode bool _enter() override; bool _pre_arm_checks(size_t buflen, char *buffer) const override { return true; } +#if AP_QUICKTUNE_ENABLED + bool supports_quicktune() const override { return true; } +#endif private: float active_radius_m; @@ -641,6 +676,9 @@ class ModeQHover : public Mode protected: bool _enter() override; +#if AP_QUICKTUNE_ENABLED + bool supports_quicktune() const override { return true; } +#endif }; class ModeQLoiter : public Mode @@ -667,6 +705,10 @@ friend class Plane; bool _enter() override; uint32_t last_target_loc_set_ms; + +#if AP_QUICKTUNE_ENABLED + bool supports_quicktune() const override { return true; } +#endif }; class ModeQLand : public Mode @@ -808,6 +850,12 @@ class ModeTakeoff: public Mode Location start_loc; bool _enter() override; + +private: + + // flag that we have already called autoenable fences once in MODE TAKEOFF + bool have_autoenabled_fences; + }; #if HAL_SOARING_ENABLED diff --git a/ArduPlane/mode_LoiterAltQLand.cpp b/ArduPlane/mode_LoiterAltQLand.cpp index 8fbfd59735cd24..72ac41a5557aad 100644 --- a/ArduPlane/mode_LoiterAltQLand.cpp +++ b/ArduPlane/mode_LoiterAltQLand.cpp @@ -43,12 +43,12 @@ bool ModeLoiterAltQLand::handle_guided_request(Location target_loc) // setup altitude #if AP_TERRAIN_AVAILABLE if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) { - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_TERRAIN); } else { - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME); } #else - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME); #endif plane.set_guided_WP(target_loc); diff --git a/ArduPlane/mode_auto.cpp b/ArduPlane/mode_auto.cpp index 73753e1fa44ca5..287ce0e727420c 100644 --- a/ArduPlane/mode_auto.cpp +++ b/ArduPlane/mode_auto.cpp @@ -79,11 +79,17 @@ void ModeAuto::update() } #endif +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (pullup.in_pullup()) { + return; + } +#endif + if (nav_cmd_id == MAV_CMD_NAV_TAKEOFF || (nav_cmd_id == MAV_CMD_NAV_LAND && plane.flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING)) { plane.takeoff_calc_roll(); plane.takeoff_calc_pitch(); - plane.calc_throttle(); + plane.takeoff_calc_throttle(); } else if (nav_cmd_id == MAV_CMD_NAV_LAND) { plane.calc_nav_roll(); plane.calc_nav_pitch(); @@ -166,9 +172,24 @@ bool ModeAuto::is_landing() const void ModeAuto::run() { +#if AP_PLANE_GLIDER_PULLUP_ENABLED + if (pullup.in_pullup()) { + pullup.stabilize_pullup(); + return; + } +#endif + if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) { - // Wiggle servos - plane.set_servos_idle(); + + wiggle_servos(); + + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); + + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); // Relax attitude control reset_controllers(); diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index 85462166d1bc7f..a97bedcd7dffbb 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -42,7 +42,7 @@ void ModeGuided::update() plane.nav_roll_cd = constrain_int32(plane.guided_state.forced_rpy_cd.x, -plane.roll_limit_cd, plane.roll_limit_cd); plane.update_load_factor(); -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED // guided_state.target_heading is radians at this point between -pi and pi ( defaults to -4 ) // This function is used in Guided and AvoidADSB, check for guided } else if ((plane.control_mode == &plane.mode_guided) && (plane.guided_state.target_heading_type != GUIDED_HEADING_NONE) ) { @@ -70,7 +70,7 @@ void ModeGuided::update() plane.nav_roll_cd = constrain_int32(desired, -bank_limit, bank_limit); plane.update_load_factor(); -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED } else { plane.calc_nav_roll(); } @@ -128,28 +128,32 @@ void ModeGuided::set_radius_and_direction(const float radius, const bool directi void ModeGuided::update_target_altitude() { -#if OFFBOARD_GUIDED == ENABLED - if (((plane.guided_state.target_alt_time_ms != 0) || plane.guided_state.target_alt > -0.001 )) { // target_alt now defaults to -1, and _time_ms defaults to zero. +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED + // target altitude can be negative (e.g. flying below home altitude from the top of a mountain) + if (((plane.guided_state.target_alt_time_ms != 0) || plane.guided_state.target_location.alt != -1 )) { // target_alt now defaults to -1, and _time_ms defaults to zero. // offboard altitude demanded uint32_t now = AP_HAL::millis(); float delta = 1e-3f * (now - plane.guided_state.target_alt_time_ms); plane.guided_state.target_alt_time_ms = now; // determine delta accurately as a float - float delta_amt_f = delta * plane.guided_state.target_alt_accel; + float delta_amt_f = delta * plane.guided_state.target_alt_rate; // then scale x100 to match last_target_alt and convert to a signed int32_t as it may be negative int32_t delta_amt_i = (int32_t)(100.0 * delta_amt_f); - Location temp {}; - temp.alt = plane.guided_state.last_target_alt + delta_amt_i; // ...to avoid floats here, - if (is_positive(plane.guided_state.target_alt_accel)) { - temp.alt = MIN(plane.guided_state.target_alt, temp.alt); - } else { - temp.alt = MAX(plane.guided_state.target_alt, temp.alt); + // To calculate the required velocity (up or down), we need to target and current altitudes in the target frame + const Location::AltFrame target_frame = plane.guided_state.target_location.get_alt_frame(); + int32_t target_alt_previous_cm; + if (plane.current_loc.initialised() && plane.guided_state.target_location.initialised() && + plane.current_loc.get_alt_cm(target_frame, target_alt_previous_cm)) { + // create a new interim target location that that takes current_location and moves delta_amt_i in the right direction + int32_t temp_alt_cm = constrain_int32(plane.guided_state.target_location.alt, target_alt_previous_cm - delta_amt_i, target_alt_previous_cm + delta_amt_i); + Location temp_location = plane.guided_state.target_location; + temp_location.set_alt_cm(temp_alt_cm, target_frame); + + // incrementally step the altitude towards the target + plane.set_target_altitude_location(temp_location); } - plane.guided_state.last_target_alt = temp.alt; - plane.set_target_altitude_location(temp); - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } else -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED { Mode::update_target_altitude(); } diff --git a/ArduPlane/mode_qland.cpp b/ArduPlane/mode_qland.cpp index 4205960f871c30..e59e3c9a50e954 100644 --- a/ArduPlane/mode_qland.cpp +++ b/ArduPlane/mode_qland.cpp @@ -9,16 +9,12 @@ bool ModeQLand::_enter() quadplane.throttle_wait = false; quadplane.setup_target_position(); poscontrol.set_state(QuadPlane::QPOS_LAND_DESCEND); - poscontrol.pilot_correction_done = false; quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing); quadplane.landing_detect.lower_limit_start_ms = 0; quadplane.landing_detect.land_start_ms = 0; #if AP_LANDINGGEAR_ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif -#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 90a4d9f2273a42..6ab2c1bd3d81db 100644 --- a/ArduPlane/mode_qloiter.cpp +++ b/ArduPlane/mode_qloiter.cpp @@ -48,7 +48,7 @@ void ModeQLoiter::run() // we have an active landing target override Vector2f rel_origin; if (plane.next_WP_loc.get_vector_xy_from_origin_NE(rel_origin)) { - quadplane.pos_control->set_pos_target_xy_cm(rel_origin.x, rel_origin.y); + quadplane.pos_control->set_pos_desired_xy_cm(rel_origin); last_target_loc_set_ms = 0; } } diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index 7de44dbc9e030c..87c3b7712874b1 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -211,7 +211,6 @@ void ModeQRTL::update_target_altitude() Location loc = plane.next_WP_loc; loc.alt += alt*100; plane.set_target_altitude_location(loc); - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } // only nudge during approach diff --git a/ArduPlane/mode_rtl.cpp b/ArduPlane/mode_rtl.cpp index c35a3b64a6abd5..b0d8cfbfd667b7 100644 --- a/ArduPlane/mode_rtl.cpp +++ b/ArduPlane/mode_rtl.cpp @@ -7,7 +7,7 @@ bool ModeRTL::_enter() plane.do_RTL(plane.get_RTL_altitude_cm()); plane.rtl.done_climb = false; #if HAL_QUADPLANE_ENABLED - plane.vtol_approach_s.approach_stage = Plane::Landing_ApproachStage::RTL; + plane.vtol_approach_s.approach_stage = Plane::VTOLApproach::Stage::RTL; // Quadplane specific checks if (plane.quadplane.available()) { @@ -83,7 +83,7 @@ void ModeRTL::navigate() AP_Mission::Mission_Command cmd; cmd.content.location = plane.next_WP_loc; plane.verify_landing_vtol_approach(cmd); - if (plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING) { + if (plane.vtol_approach_s.approach_stage == Plane::VTOLApproach::Stage::VTOL_LANDING) { plane.set_mode(plane.mode_qrtl, ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL); } return; @@ -106,7 +106,7 @@ void ModeRTL::navigate() if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) || (plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START && plane.reached_loiter_target() && - labs(plane.altitude_error_cm) < 1000)) + labs(plane.calc_altitude_error_cm()) < 1000)) { // we've reached the RTL point, see if we have a landing sequence if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) { diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index 37d0203fcf413f..5f93cc4729b2b5 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -22,11 +22,11 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = { // @Increment: 1 // @Units: m // @User: Standard - AP_GROUPINFO("LVL_ALT", 2, ModeTakeoff, level_alt, 5), + AP_GROUPINFO("LVL_ALT", 2, ModeTakeoff, level_alt, 10), // @Param: LVL_PITCH // @DisplayName: Takeoff mode altitude initial pitch - // @Description: This is the target pitch for the initial climb to TKOFF_LVL_ALT + // @Description: This is the target pitch during the takeoff. // @Range: 0 30 // @Increment: 1 // @Units: deg @@ -63,6 +63,7 @@ ModeTakeoff::ModeTakeoff() : bool ModeTakeoff::_enter() { takeoff_mode_setup = false; + have_autoenabled_fences = false; return true; } @@ -80,6 +81,7 @@ void ModeTakeoff::update() const float alt = target_alt; const float dist = target_dist; if (!takeoff_mode_setup) { + plane.auto_state.takeoff_altitude_rel_cm = alt * 100; const uint16_t altitude = plane.relative_ground_altitude(false,true); const float direction = degrees(ahrs.get_yaw()); // see if we will skip takeoff as already flying @@ -91,11 +93,12 @@ void ModeTakeoff::update() plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL); } else { gcs().send_text(MAV_SEVERITY_INFO, "Climbing to TKOFF alt then loitering"); + start_loc = plane.current_loc; plane.next_WP_loc = plane.current_loc; plane.next_WP_loc.alt += ((alt - altitude) *100); plane.next_WP_loc.offset_bearing(direction, dist); takeoff_mode_setup = true; - plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL); + plane.set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF); } // not flying so do a full takeoff sequence } else { @@ -116,8 +119,9 @@ void ModeTakeoff::update() gcs().send_text(MAV_SEVERITY_INFO, "Takeoff to %.0fm for %.1fm heading %.1f deg", alt, dist, direction); plane.takeoff_state.start_time_ms = millis(); + plane.takeoff_state.throttle_max_timer_ms = millis(); takeoff_mode_setup = true; - + plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function. } } } @@ -125,45 +129,49 @@ void ModeTakeoff::update() if (plane.check_takeoff_timeout()) { plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL); takeoff_mode_setup = false; - } - - // we finish the initial level takeoff if we climb past - // TKOFF_LVL_ALT or we pass the target location. The check for - // target location prevents us flying forever if we can't climb - // reset the loiter waypoint target to be correct bearing and dist - // from starting location in case original yaw used to set it was off due to EKF - // reset or compass interference from max throttle + + // We update the waypoint to follow once we're past TKOFF_LVL_ALT or we + // pass the target location. The check for target location prevents us + // flying towards a wrong location if we can't climb. + // This will correct any yaw estimation errors (caused by EKF reset + // or compass interference from max throttle), since it's using position bearing. const float altitude_cm = plane.current_loc.alt - start_loc.alt; - if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF && - (altitude_cm >= level_alt*100 || - start_loc.get_distance(plane.current_loc) >= dist)) { - // reset the target loiter waypoint using current yaw which should be close to correct starting heading + if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF + && plane.steer_state.hold_course_cd == -1 // This is the enter-once flag. + && (altitude_cm >= (level_alt * 100.0f) || start_loc.get_distance(plane.current_loc) >= dist) + ) { const float direction = start_loc.get_bearing_to(plane.current_loc) * 0.01; plane.next_WP_loc = start_loc; plane.next_WP_loc.offset_bearing(direction, dist); plane.next_WP_loc.alt += alt*100.0; + plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function. + } + + // We finish the initial level takeoff if we climb past + // TKOFF_ALT or we pass the target location. The check for + // target location prevents us flying forever if we can't climb. + if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF && + (altitude_cm >= (alt*100 - 200) || + start_loc.get_distance(plane.current_loc) >= dist)) { plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL); } if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) { - //below TAKOFF_LVL_ALT - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 100.0); + //below TKOFF_ALT plane.takeoff_calc_roll(); plane.takeoff_calc_pitch(); + plane.takeoff_calc_throttle(); } else { - if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT ,or above and loitering #if AP_FENCE_ENABLED + if (!have_autoenabled_fences) { plane.fence.auto_enable_fence_after_takeoff(); -#endif - plane.calc_nav_roll(); - plane.calc_nav_pitch(); - plane.calc_throttle(); - } else { // still climbing to TAKEOFF_ALT; may be loitering - plane.calc_throttle(); - plane.takeoff_calc_roll(); - plane.takeoff_calc_pitch(); + have_autoenabled_fences = true; } +#endif + plane.calc_nav_roll(); + plane.calc_nav_pitch(); + plane.calc_throttle(); //check if in long failsafe due to being in initial TAKEOFF stage; if it is, recall long failsafe now to get fs action via events call if (plane.long_failsafe_pending) { diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 762b190ffee722..b47160836aff84 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -116,8 +116,8 @@ float Plane::mode_auto_target_airspeed_cm() { #if HAL_QUADPLANE_ENABLED 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))) { + ((vtol_approach_s.approach_stage == VTOLApproach::Stage::APPROACH_LINE) || + (vtol_approach_s.approach_stage == VTOLApproach::Stage::VTOL_LANDING))) { const float land_airspeed = TECS_controller.get_land_airspeed(); if (is_positive(land_airspeed)) { return land_airspeed * 100; @@ -187,7 +187,7 @@ void Plane::calc_airspeed_errors() target_airspeed_cm = ((int32_t)(aparm.airspeed_max - aparm.airspeed_min) * get_throttle_input()) + ((int32_t)aparm.airspeed_min * 100); } -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED } else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offboard guided speed change cmd not set, then this section is skipped // offboard airspeed demanded uint32_t now = AP_HAL::millis(); @@ -203,7 +203,7 @@ void Plane::calc_airspeed_errors() target_airspeed_cm = constrain_float(MAX(guided_state.target_airspeed_cm, target_airspeed_cm), aparm.airspeed_min *100, aparm.airspeed_max *100); } -#endif // OFFBOARD_GUIDED == ENABLED +#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED #if HAL_SOARING_ENABLED } else if (g2.soaring_controller.is_active() && g2.soaring_controller.get_throttle_suppressed()) { @@ -256,7 +256,7 @@ void Plane::calc_airspeed_errors() } // when using the special GUIDED mode features for slew control, don't allow airspeed nudging as it doesn't play nicely. -#if OFFBOARD_GUIDED == ENABLED +#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED if (control_mode == &mode_guided && !is_zero(guided_state.target_airspeed_cm) && (airspeed_nudge_cm != 0)) { airspeed_nudge_cm = 0; //airspeed_nudge_cm forced to zero } @@ -321,7 +321,7 @@ void Plane::update_loiter_update_nav(uint16_t radius) if ((loiter.start_time_ms == 0 && (control_mode == &mode_auto || control_mode == &mode_guided) && auto_state.crosstrack && - current_loc.get_distance(next_WP_loc) > radius*3) || + current_loc.get_distance(next_WP_loc) > 3 * nav_controller->loiter_radius(radius)) || quadplane_qrtl_switch) { /* if never reached loiter point and using crosstrack and somewhat far away from loiter point @@ -394,15 +394,19 @@ void Plane::update_fbwb_speed_height(void) elevator_input = -elevator_input; } - int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100; - change_target_altitude(alt_change_cm); - - if (is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) { - // the user has just released the elevator, lock in - // the current altitude + bool input_stop_climb = !is_positive(elevator_input) && is_positive(target_altitude.last_elevator_input); + bool input_stop_descent = !is_negative(elevator_input) && is_negative(target_altitude.last_elevator_input); + if (input_stop_climb || input_stop_descent) { + // user elevator input reached or passed zero, lock in the current altitude set_target_altitude_current(); } + float climb_rate = g.flybywire_climb_rate * elevator_input; + climb_rate = constrain_float(climb_rate, -TECS_controller.get_max_sinkrate(), TECS_controller.get_max_climbrate()); + + int32_t alt_change_cm = climb_rate * dt * 100; + change_target_altitude(alt_change_cm); + #if HAL_SOARING_ENABLED if (g2.soaring_controller.is_active()) { if (g2.soaring_controller.get_throttle_suppressed()) { @@ -421,8 +425,6 @@ void Plane::update_fbwb_speed_height(void) check_fbwb_altitude(); - altitude_error_cm = calc_altitude_error_cm(); - calc_throttle(); calc_nav_pitch(); } diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 61cec7ae0abc43..7023d3371198c4 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -6,13 +6,13 @@ */ void Plane::parachute_check() { -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED parachute.update(); parachute.check_sink_rate(); #endif } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED /* parachute_release - trigger the release of the parachute diff --git a/ArduPlane/pullup.cpp b/ArduPlane/pullup.cpp new file mode 100644 index 00000000000000..b8cb1a7727b612 --- /dev/null +++ b/ArduPlane/pullup.cpp @@ -0,0 +1,239 @@ +#include "Plane.h" +/* + support for pullup after an alitude wait. Used for high altitude gliders + */ + +#if AP_PLANE_GLIDER_PULLUP_ENABLED + +// Pullup control parameters +const AP_Param::GroupInfo GliderPullup::var_info[] = { + + // @Param: ENABLE + // @DisplayName: Enable pullup after altitude wait + // @Description: Enable pullup after altitude wait + // @Values: 0:Disabled, 1:Enabled + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLE", 1, GliderPullup, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: ELEV_OFS + // @DisplayName: Elevator deflection used before starting pullup + // @Description: Elevator deflection offset from -1 to 1 while waiting for airspeed to rise before starting close loop control of the pullup. + // @Range: -1.0 1.0 + // @User: Advanced + AP_GROUPINFO("ELEV_OFS", 2, GliderPullup, elev_offset, 0.1f), + + // @Param: NG_LIM + // @DisplayName: Maximum normal load factor during pullup + // @Description: This is the nominal maximum value of normal load factor used during the closed loop pitch rate control of the pullup. + // @Range: 1.0 4.0 + // @User: Advanced + AP_GROUPINFO("NG_LIM", 3, GliderPullup, ng_limit, 2.0f), + + // @Param: NG_JERK_LIM + // @DisplayName: Maximum normal load factor rate of change during pullup + // @Description: The normal load factor used for closed loop pitch rate control of the pullup will be ramped up to the value set by PUP_NG_LIM at the rate of change set by this parameter. The parameter value specified will be scaled internally by 1/EAS2TAS. + // @Units: 1/s + // @Range: 0.1 10.0 + // @User: Advanced + AP_GROUPINFO("NG_JERK_LIM", 4, GliderPullup, ng_jerk_limit, 4.0f), + + // @Param: PITCH + // @DisplayName: Target pitch angle during pullup + // @Description: The vehicle will attempt achieve this pitch angle during the pull-up maneouvre. + // @Units: deg + // @Range: -5 15 + // @User: Advanced + AP_GROUPINFO("PITCH", 5, GliderPullup, pitch_dem, 3), + + // @Param: ARSPD_START + // @DisplayName: Pullup target airspeed + // @Description: Target airspeed for initial airspeed wait + // @Units: m/s + // @Range: 0 100 + // @User: Advanced + AP_GROUPINFO("ARSPD_START", 6, GliderPullup, airspeed_start, 30), + + // @Param: PITCH_START + // @DisplayName: Pullup target pitch + // @Description: Target pitch for initial pullup + // @Units: deg + // @Range: -80 0 + // @User: Advanced + AP_GROUPINFO("PITCH_START", 7, GliderPullup, pitch_start, -60), + + AP_GROUPEND +}; + +// constructor +GliderPullup::GliderPullup(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +/* + return true if in a pullup manoeuvre at the end of NAV_ALTITUDE_WAIT +*/ +bool GliderPullup::in_pullup(void) const +{ + return plane.control_mode == &plane.mode_auto && + plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT && + stage != Stage::NONE; +} + +/* + start a pullup maneouvre, called when NAV_ALTITUDE_WAIT has reached + altitude or exceeded descent rate +*/ +bool GliderPullup::pullup_start(void) +{ + if (enable != 1) { + return false; + } + + // release balloon + SRV_Channels::set_output_scaled(SRV_Channel::k_lift_release, 100); + + stage = Stage::WAIT_AIRSPEED; + plane.auto_state.idle_mode = false; + float aspeed; + if (!plane.ahrs.airspeed_estimate(aspeed)) { + aspeed = -1; + } + gcs().send_text(MAV_SEVERITY_INFO, "Start pullup airspeed %.1fm/s at %.1fm AMSL", aspeed, plane.current_loc.alt*0.01); + return true; +} + +/* + first stage pullup from balloon release, verify completion + */ +bool GliderPullup::verify_pullup(void) +{ + const auto &ahrs = plane.ahrs; + const auto ¤t_loc = plane.current_loc; + const auto &aparm = plane.aparm; + + switch (stage) { + case Stage::WAIT_AIRSPEED: { + float aspeed; + if (ahrs.airspeed_estimate(aspeed) && (aspeed > airspeed_start || ahrs.pitch_sensor*0.01 > pitch_start)) { + gcs().send_text(MAV_SEVERITY_INFO, "Pullup airspeed %.1fm/s alt %.1fm AMSL", aspeed, current_loc.alt*0.01); + stage = Stage::WAIT_PITCH; + } + return false; + } + + case Stage::WAIT_PITCH: { + if (ahrs.pitch_sensor*0.01 > pitch_start && fabsf(ahrs.roll_sensor*0.01) < 90) { + gcs().send_text(MAV_SEVERITY_INFO, "Pullup pitch p=%.1f r=%.1f alt %.1fm AMSL", + ahrs.pitch_sensor*0.01, + ahrs.roll_sensor*0.01, + current_loc.alt*0.01); + stage = Stage::WAIT_LEVEL; + } + return false; + } + + case Stage::PUSH_NOSE_DOWN: { + if (fabsf(ahrs.roll_sensor*0.01) < aparm.roll_limit) { + stage = Stage::WAIT_LEVEL; + } + return false; + } + + case Stage::WAIT_LEVEL: { + // When pitch has raised past lower limit used by speed controller, wait for airspeed to approach + // target value before handing over control of pitch demand to speed controller + bool pitchup_complete = ahrs.pitch_sensor*0.01 > MIN(0, aparm.pitch_limit_min); + const float pitch_lag_time = 1.0f * sqrtf(ahrs.get_EAS2TAS()); + float aspeed; + const float aspeed_derivative = (ahrs.get_accel().x + GRAVITY_MSS * ahrs.get_DCM_rotation_body_to_ned().c.x) / ahrs.get_EAS2TAS(); + bool airspeed_low = ahrs.airspeed_estimate(aspeed) ? (aspeed + aspeed_derivative * pitch_lag_time) < 0.01f * (float)plane.target_airspeed_cm : true; + bool roll_control_lost = fabsf(ahrs.roll_sensor*0.01) > aparm.roll_limit; + if (pitchup_complete && airspeed_low && !roll_control_lost) { + gcs().send_text(MAV_SEVERITY_INFO, "Pullup level r=%.1f p=%.1f alt %.1fm AMSL", + ahrs.roll_sensor*0.01, ahrs.pitch_sensor*0.01, current_loc.alt*0.01); + break; + } else if (pitchup_complete && roll_control_lost) { + // push nose down and wait to get roll control back + gcs().send_text(MAV_SEVERITY_ALERT, "Pullup level roll bad r=%.1f p=%.1f", + ahrs.roll_sensor*0.01, + ahrs.pitch_sensor*0.01); + stage = Stage::PUSH_NOSE_DOWN; + } + return false; + } + case Stage::NONE: + break; + } + + // all done + stage = Stage::NONE; + return true; +} + +/* + stabilize during pullup from balloon drop + */ +void GliderPullup::stabilize_pullup(void) +{ + const float speed_scaler = plane.get_speed_scaler(); + switch (stage) { + case Stage::WAIT_AIRSPEED: { + plane.pitchController.reset_I(); + plane.yawController.reset_I(); + SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elev_offset*4500); + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0); + plane.nav_pitch_cd = 0; + plane.nav_roll_cd = 0; + SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_rate_out(0, speed_scaler)); + ng_demand = 0.0; + break; + } + case Stage::WAIT_PITCH: { + plane.yawController.reset_I(); + plane.nav_roll_cd = 0; + plane.nav_pitch_cd = 0; + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0); + SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_rate_out(0, speed_scaler)); + float aspeed; + const auto &ahrs = plane.ahrs; + if (ahrs.airspeed_estimate(aspeed)) { + // apply a rate of change limit to the ng pullup demand + ng_demand += MAX(ng_jerk_limit / ahrs.get_EAS2TAS(), 0.1f) * plane.scheduler.get_loop_period_s(); + ng_demand = MIN(ng_demand, ng_limit); + const float VTAS_ref = ahrs.get_EAS2TAS() * aspeed; + const float pullup_accel = ng_demand * GRAVITY_MSS; + const float demanded_rate_dps = degrees(pullup_accel / VTAS_ref); + const uint32_t elev_trim_offset_cd = 4500.0f * elev_offset * (1.0f - ng_demand / ng_limit); + SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elev_trim_offset_cd + plane.pitchController.get_rate_out(demanded_rate_dps, speed_scaler)); + } else { + SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elev_offset*4500); + } + break; + } + case Stage::PUSH_NOSE_DOWN: { + plane.nav_pitch_cd = plane.aparm.pitch_limit_min*100; + plane.stabilize_pitch(); + plane.nav_roll_cd = 0; + plane.stabilize_roll(); + plane.stabilize_yaw(); + ng_demand = 0.0f; + break; + } + case Stage::WAIT_LEVEL: + plane.nav_pitch_cd = MAX((plane.aparm.pitch_limit_min + 5), pitch_dem)*100; + plane.stabilize_pitch(); + plane.nav_roll_cd = 0; + plane.stabilize_roll(); + plane.stabilize_yaw(); + ng_demand = 0.0f; + break; + case Stage::NONE: + break; + } + + // we have done stabilisation + plane.last_stabilize_ms = AP_HAL::millis(); +} + +#endif // AP_PLANE_GLIDER_PULLUP_ENABLED diff --git a/ArduPlane/pullup.h b/ArduPlane/pullup.h new file mode 100644 index 00000000000000..d285b4bfc5eea7 --- /dev/null +++ b/ArduPlane/pullup.h @@ -0,0 +1,50 @@ +#pragma once + +/* + support for pullup after NAV_ALTITUDE_WAIT for gliders + */ + +#ifndef AP_PLANE_GLIDER_PULLUP_ENABLED +#define AP_PLANE_GLIDER_PULLUP_ENABLED CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif + +#if AP_PLANE_GLIDER_PULLUP_ENABLED + +class GliderPullup +{ +public: + GliderPullup(void); + + void reset(void) { + stage = Stage::NONE; + } + bool in_pullup() const; + bool verify_pullup(void); + void stabilize_pullup(void); + bool pullup_complete(void); + bool pullup_start(void); + + enum class Stage : uint8_t { + NONE=0, + WAIT_AIRSPEED, + WAIT_PITCH, + WAIT_LEVEL, + PUSH_NOSE_DOWN, + }; + + static const struct AP_Param::GroupInfo var_info[]; + +private: + Stage stage; + AP_Int8 enable; + AP_Float elev_offset; // fraction of full elevator applied during WAIT_AIRSPEED and released during WAIT_PITCH + AP_Float ng_limit; + AP_Float airspeed_start; + AP_Float pitch_start; + AP_Float ng_jerk_limit; + AP_Float pitch_dem; + float ng_demand; +}; + +#endif // AP_PLANE_GLIDER_PULLUP_ENABLED + diff --git a/ArduPlane/qautotune.h b/ArduPlane/qautotune.h index 938c8e47e43323..684fe5e54783df 100644 --- a/ArduPlane/qautotune.h +++ b/ArduPlane/qautotune.h @@ -8,7 +8,7 @@ #include "quadplane.h" #ifndef QAUTOTUNE_ENABLED - #define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED +#define QAUTOTUNE_ENABLED (HAL_QUADPLANE_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif #if QAUTOTUNE_ENABLED diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index a96d70aeb50f82..87be3e11604369 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -103,12 +103,12 @@ 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. 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. + // @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. The default value of 0 disables assistance but will generate a pre-arm failure to encourage users to set this parameter to -1, or a positive, non-zero value. If this is set to -1 then all Q_ASSIST features are disabled except during transitions. A high non-zero,positive 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. // @Units: m/s // @Range: 0 100 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("ASSIST_SPEED", 24, QuadPlane, assist_speed, 0), + AP_GROUPINFO("ASSIST_SPEED", 24, QuadPlane, assist.speed, 0), // @Param: YAW_RATE_MAX // @DisplayName: Maximum yaw rate @@ -150,7 +150,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { AP_GROUPINFO("TRAN_PIT_MAX", 29, QuadPlane, transition_pitch_max, 3), // frame class was moved from 30 when consolidating AP_Motors classes -#define FRAME_CLASS_OLD_IDX 30 + // @Param: FRAME_CLASS // @DisplayName: Frame Class // @Description: Controls major frame class for multicopter component @@ -231,12 +231,12 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: ASSIST_ANGLE // @DisplayName: Quadplane assistance angle - // @Description: This is the angular error in attitude beyond which the quadplane VTOL motors will provide stability assistance. This will only be used if Q_ASSIST_SPEED is also non-zero. Assistance will be given if the attitude is outside the normal attitude limits by at least 5 degrees and the angular error in roll or pitch is greater than this angle for at least Q_ASSIST_DELAY seconds. Set to zero to disable angle assistance. + // @Description: This is the angular error in attitude beyond which the quadplane VTOL motors will provide stability assistance. This will only be used if Q_ASSIST_SPEED is also positive and non-zero. Assistance will be given if the attitude is outside the normal attitude limits by at least 5 degrees and the angular error in roll or pitch is greater than this angle for at least Q_ASSIST_DELAY seconds. Set to zero to disable angle assistance. // @Units: deg // @Range: 0 90 // @Increment: 1 // @User: Standard - AP_GROUPINFO("ASSIST_ANGLE", 45, QuadPlane, assist_angle, 30), + AP_GROUPINFO("ASSIST_ANGLE", 45, QuadPlane, assist.angle, 30), // 47: TILT_TYPE // 48: TAILSIT_ANGLE @@ -279,7 +279,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Bitmask: 19: CompleteTransition-to fixed wing if Q_TRANS_FAIL timer times out instead of QLAND // @Bitmask: 20: Force RTL mode-forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL) // @Bitmask: 21: Tilt rotor-tilt motors up when disarmed in FW modes (except manual) to prevent ground strikes. - // @Bitmask: 22: Scale FF by the ratio of VTOL/plane angle P gains in VTOL modes rather than reducing VTOL angle P based on airspeed. + // @Bitmask: 22: Scale FF by the ratio of VTOL to plane angle P gains in Position 1 phase of transition into VTOL flight as well as reducing VTOL angle P based on airspeed. AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0), AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2), @@ -310,7 +310,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: TRIM_PITCH // @DisplayName: Quadplane AHRS trim pitch - // @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes TRIM_PITCH. For tailsitters, this is relative to a baseline of 90 degrees in AHRS. + // @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes PTCH_TRIM_DEG. For tailsitters, this is relative to a baseline of 90 degrees in AHRS. // @Units: deg // @Range: -10 +10 // @Increment: 0.1 @@ -405,7 +405,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Range: 0 120 // @Increment: 1 // @User: Standard - AP_GROUPINFO("ASSIST_ALT", 16, QuadPlane, assist_alt, 0), + AP_GROUPINFO("ASSIST_ALT", 16, QuadPlane, assist.alt, 0), // 17: TAILSIT_GSCMSK // 18: TAILSIT_GSCMIN @@ -417,7 +417,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Range: 0 2 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("ASSIST_DELAY", 19, QuadPlane, assist_delay, 0.5), + AP_GROUPINFO("ASSIST_DELAY", 19, QuadPlane, assist.delay, 0.5), // @Param: FWD_MANTHR_MAX // @DisplayName: VTOL manual forward throttle max percent @@ -538,6 +538,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @User: Standard AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f), + // @Param: APPROACH_DIST + // @DisplayName: Q mode approach distance + // @Description: The minimum distance from the destination to use the fixed wing airbrake and approach code for landing approach. This is useful if you don't want the fixed wing approach logic to be used when you are close to the destination. Set to zero to always use fixed wing approach. + // @Units: m + // @Range: 0.0 1000 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("APPROACH_DIST", 39, QuadPlane, approach_distance, 0), + AP_GROUPEND }; @@ -671,34 +680,6 @@ bool QuadPlane::setup(void) return false; } - /* - cope with upgrade from old AP_Motors values for frame_class - */ - AP_Int8 old_class; - const AP_Param::ConversionInfo cinfo { Parameters::k_param_quadplane, FRAME_CLASS_OLD_IDX, AP_PARAM_INT8, nullptr }; - if (AP_Param::find_old_parameter(&cinfo, &old_class) && !frame_class.load()) { - uint8_t new_value = 0; - // map from old values to new values - switch (old_class.get()) { - case 0: - new_value = AP_Motors::MOTOR_FRAME_QUAD; - break; - case 1: - new_value = AP_Motors::MOTOR_FRAME_HEXA; - break; - case 2: - new_value = AP_Motors::MOTOR_FRAME_OCTA; - break; - case 3: - new_value = AP_Motors::MOTOR_FRAME_OCTAQUAD; - break; - case 4: - new_value = AP_Motors::MOTOR_FRAME_Y6; - break; - } - frame_class.set_and_save(new_value); - } - if (hal.util->available_memory() < 4096 + sizeof(*motors) + sizeof(*attitude_control) + sizeof(*pos_control) + sizeof(*wp_nav) + sizeof(*ahrs_view) + sizeof(*loiter_nav) + sizeof(*weathervane)) { AP_BoardConfig::config_error("Not enough memory for quadplane"); @@ -723,6 +704,9 @@ bool QuadPlane::setup(void) case AP_Motors::MOTOR_FRAME_Y6: setup_default_channels(7); break; + case AP_Motors::MOTOR_FRAME_DECA: + setup_default_channels(10); + break; case AP_Motors::MOTOR_FRAME_TRI: SRV_Channels::set_default_function(CH_5, SRV_Channel::k_motor1); SRV_Channels::set_default_function(CH_6, SRV_Channel::k_motor2); @@ -745,23 +729,23 @@ bool QuadPlane::setup(void) switch ((AP_Motors::motor_frame_class)frame_class) { case AP_Motors::MOTOR_FRAME_TRI: - motors = new AP_MotorsTri(rc_speed); + motors = NEW_NOTHROW 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(rc_speed); + tailsitter.tailsitter_motors = NEW_NOTHROW AP_MotorsTailsitter(rc_speed); motors = tailsitter.tailsitter_motors; motors_var_info = AP_MotorsTailsitter::var_info; break; case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: #if AP_SCRIPTING_ENABLED - motors = new AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; #endif // AP_SCRIPTING_ENABLED break; default: - motors = new AP_MotorsMatrix(rc_speed); + motors = NEW_NOTHROW AP_MotorsMatrix(rc_speed); motors_var_info = AP_MotorsMatrix::var_info; break; } @@ -778,30 +762,30 @@ bool QuadPlane::setup(void) AP_BoardConfig::allocation_error("ahrs_view"); } - attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors); + attitude_control = NEW_NOTHROW 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); + pos_control = NEW_NOTHROW AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); if (!pos_control) { AP_BoardConfig::allocation_error("pos_control"); } AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info); - wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + wp_nav = NEW_NOTHROW AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); if (!wp_nav) { AP_BoardConfig::allocation_error("wp_nav"); } AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info); - loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + loiter_nav = NEW_NOTHROW AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); if (!loiter_nav) { AP_BoardConfig::allocation_error("loiter_nav"); } AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info); - weathervane = new AC_WeatherVane(); + weathervane = NEW_NOTHROW AC_WeatherVane(); if (!weathervane) { AP_BoardConfig::allocation_error("weathervane"); } @@ -825,7 +809,7 @@ bool QuadPlane::setup(void) // default QAssist state as set with Q_OPTIONS if (option_is_set(QuadPlane::OPTION::Q_ASSIST_FORCE_ENABLE)) { - q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; + assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); } setup_defaults(); @@ -838,12 +822,16 @@ bool QuadPlane::setup(void) pilot_speed_z_max_dn.convert_centi_parameter(AP_PARAM_INT16); pilot_accel_z.convert_centi_parameter(AP_PARAM_INT16); + // Provisionally assign the SLT thrust type. + // It will be overwritten by tailsitter or tiltorotor setups. + thrust_type = ThrustType::SLT; + tailsitter.setup(); tiltrotor.setup(); if (!transition) { - transition = new SLT_Transition(*this, motors); + transition = NEW_NOTHROW SLT_Transition(*this, motors); } if (!transition) { AP_BoardConfig::allocation_error("transition"); @@ -1417,7 +1405,7 @@ float QuadPlane::assist_climb_rate_cms(void) const float climb_rate; if (plane.control_mode->does_auto_throttle()) { // use altitude_error_cm, spread over 10s interval - climb_rate = plane.altitude_error_cm * 0.1f; + climb_rate = plane.calc_altitude_error_cm() * 0.1f; } else { // otherwise estimate from pilot input climb_rate = plane.g.flybywire_climb_rate * (plane.nav_pitch_cd/(plane.aparm.pitch_limit_max*100)); @@ -1451,118 +1439,6 @@ float QuadPlane::desired_auto_yaw_rate_cds(void) const return yaw_rate; } -/* - return true if the quadplane should provide stability assistance - */ -bool QuadPlane::should_assist(float aspeed, bool have_airspeed) -{ - if (!plane.arming.is_armed_and_safety_off() || (q_assist_state == Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED) || tailsitter.is_control_surface_tailsitter()) { - // disarmed or disabled by aux switch or because a control surface tailsitter - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - if (!tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) - || is_positive(plane.get_throttle_input()) - || plane.is_flying() ) ) { - // not in a flight mode and condition where it would be safe to turn on vertial lift motors - // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - if (q_assist_state == Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE) { - // force enabled, no need to check thresholds - in_angle_assist = false; - angle_error_start_ms = 0; - return true; - } - - if (assist_speed <= 0) { - // disabled via speed threshold - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - // assistance due to Q_ASSIST_SPEED - // if option bit is enabled only allow assist with real airspeed sensor - if ((have_airspeed && aspeed < assist_speed) && - (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.using_airspeed_sensor())) { - in_angle_assist = false; - angle_error_start_ms = 0; - return true; - } - - const uint32_t now = AP_HAL::millis(); - - /* - optional assistance when altitude is too close to the ground - */ - if (assist_alt > 0) { - float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); - if (height_above_ground < assist_alt) { - if (alt_error_start_ms == 0) { - alt_error_start_ms = now; - } - if (now - alt_error_start_ms > assist_delay*1000) { - // we've been below assistant alt for Q_ASSIST_DELAY seconds - if (!in_alt_assist) { - in_alt_assist = true; - gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground); - } - return true; - } - } else { - in_alt_assist = false; - alt_error_start_ms = 0; - } - } - - if (assist_angle <= 0) { - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - /* - now check if we should provide assistance due to attitude error - */ - - const uint16_t allowed_envelope_error_cd = 500U; - if (labs(ahrs.roll_sensor) <= plane.aparm.roll_limit*100 + allowed_envelope_error_cd && - ahrs.pitch_sensor < plane.aparm.pitch_limit_max*100+allowed_envelope_error_cd && - ahrs.pitch_sensor > -(allowed_envelope_error_cd-plane.aparm.pitch_limit_min*100)) { - // we are inside allowed attitude envelope - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - int32_t max_angle_cd = 100U*assist_angle; - if ((labs(ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd && - labs(ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd)) { - // not beyond angle error - angle_error_start_ms = 0; - in_angle_assist = false; - return false; - } - - if (angle_error_start_ms == 0) { - angle_error_start_ms = now; - } - bool ret = (now - angle_error_start_ms) >= assist_delay*1000; - if (ret && !in_angle_assist) { - in_angle_assist = true; - gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d", - (int)(ahrs.roll_sensor/100), - (int)(ahrs.pitch_sensor/100)); - } - return ret; -} - /* update for transition from quadplane to fixed wing mode */ @@ -1581,7 +1457,7 @@ void SLT_Transition::update() /* see if we should provide some assistance */ - if (quadplane.should_assist(aspeed, have_airspeed)) { + if (quadplane.assist.should_assist(aspeed, have_airspeed)) { // the quad should provide some assistance to the plane quadplane.assisted_flight = true; // update transition state for vehicles using airspeed wait @@ -1790,6 +1666,9 @@ void SLT_Transition::VTOL_update() transition_state = TRANSITION_AIRSPEED_WAIT; } last_throttle = motors->get_throttle(); + + // Keep assistance reset while not checking + quadplane.assist.reset(); } /* @@ -1893,8 +1772,12 @@ void QuadPlane::update(void) if (motors->armed()) { const bool motors_active = in_vtol_mode() || assisted_flight; if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) { + // log ANG at main loop rate + if (show_vtol_view()) { + attitude_control->Write_ANG(); + } // log RATE at main loop rate - ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); + attitude_control->Write_Rate(*pos_control); // log CTRL and MOTB at 10 Hz if (now - last_ctrl_log_ms > 100) { @@ -2085,6 +1968,8 @@ void QuadPlane::motors_output(bool run_rate_controller) attitude_control->set_dt(last_loop_time_s); pos_control->set_dt(last_loop_time_s); attitude_control->rate_controller_run(); + // reset sysid and other temporary inputs + attitude_control->rate_controller_target_reset(); last_att_control_ms = now; } @@ -2290,7 +2175,8 @@ void QuadPlane::run_xy_controller(float accel_limit) void QuadPlane::poscontrol_init_approach(void) { const float dist = plane.current_loc.get_distance(plane.next_WP_loc); - if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) { + if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH) || + (is_positive(approach_distance) && dist < approach_distance)) { // go straight to QPOS_POSITION1 poscontrol.set_state(QPOS_POSITION1); gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); @@ -2327,6 +2213,16 @@ void QuadPlane::poscontrol_init_approach(void) */ void QuadPlane::log_QPOS(void) { +// @LoggerMessage: QPOS +// @Description: Quadplane position data +// @Field: TimeUS: Time since system startup +// @Field: State: Position control state +// @FieldValueEnum: State: QuadPlane::position_control_state +// @Field: Dist: Distance to next waypoint +// @Field: TSpd: Target speed +// @Field: TAcc: Target acceleration +// @Field: OShoot: True if landing point is overshot or heading off by more than 60 degrees + AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist,TSpd,TAcc,OShoot", "QBfffB", AP_HAL::micros64(), poscontrol.get_state(), @@ -2468,7 +2364,7 @@ void QuadPlane::vtol_position_controller(void) } // speed for crossover to POSITION1 controller - const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist_speed); + const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist.speed); // run fixed wing navigation plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc, loc); @@ -3009,7 +2905,8 @@ QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const /* map from pitch tilt to fwd throttle when enabled */ -void QuadPlane::assign_tilt_to_fwd_thr(void) { +void QuadPlane::assign_tilt_to_fwd_thr(void) +{ const auto fwd_thr_active = get_vfwd_method(); if (fwd_thr_active != ActiveFwdThr::NEW) { @@ -3226,8 +3123,6 @@ void QuadPlane::takeoff_controller(void) if (no_navigation) { 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 @@ -3507,7 +3402,8 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) return false; } transition->restart(); - plane.TECS_controller.set_pitch_max_limit(transition_pitch_max); + plane.TECS_controller.set_pitch_max(transition_pitch_max); + plane.TECS_controller.set_pitch_min(-transition_pitch_max); // todo: why are you doing this, I want to delete it. set_alt_target_current(); @@ -3653,9 +3549,6 @@ bool QuadPlane::verify_vtol_land(void) poscontrol.pilot_correction_done = false; 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 AP_LANDINGGEAR_ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif @@ -3717,10 +3610,36 @@ 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() * 0.01f; + des_alt_m = pos_control->get_pos_desired_z_cm() * 0.01f; target_climb_rate_cms = pos_control->get_vel_target_z_cms(); } + // Asemble assistance bitmask, defintion here is used to generate log documentation + enum class log_assistance_flags { + in_assisted_flight = 1U<<0, // true if VTOL assist is active + forced = 1U<<1, // true if assistance is forced + speed = 1U<<2, // true if assistance due to low airspeed + alt = 1U<<3, // true if assistance due to low altitude + angle = 1U<<4, // true if assistance due to attitude error + }; + + uint8_t assist_flags = 0; + if (assisted_flight) { + assist_flags |= (uint8_t)log_assistance_flags::in_assisted_flight; + } + if (assist.in_force_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::forced; + } + if (assist.in_speed_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::speed; + } + if (assist.in_alt_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::alt; + } + if (assist.in_angle_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::angle; + } + struct log_QControl_Tuning pkt = { LOG_PACKET_HEADER_INIT(LOG_QTUN_MSG), time_us : AP_HAL::micros64(), @@ -3735,12 +3654,15 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()), throttle_mix : attitude_control->get_throttle_mix(), transition_state : transition->get_log_transition_state(), - assist : assisted_flight, + assist : assist_flags, }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); // write multicopter position control message pos_control->write_log(); + + // Write tiltrotor tilt angle log + tiltrotor.write_log(); } #endif @@ -3847,7 +3769,11 @@ float QuadPlane::forward_throttle_pct() // approach the landing point when landing below the takeoff point vel_forward.last_pct = vel_forward.integrator; } else if ((in_vtol_land_final() && motors->limit.throttle_lower) || - (plane.g.rangefinder_landing && (plane.rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow))) { +#if AP_RANGEFINDER_ENABLED + (plane.g.rangefinder_landing && (plane.rangefinder.status_orient(plane.rangefinder_orientation()) == RangeFinder::Status::OutOfRangeLow))) { +#else + false) { +#endif // we're in the settling phase of landing or using a rangefinder that is out of range low, disable fwd motor vel_forward.last_pct = 0; vel_forward.integrator = 0; @@ -3977,7 +3903,7 @@ bool QuadPlane::guided_mode_enabled(void) */ void QuadPlane::set_alt_target_current(void) { - pos_control->set_pos_target_z_cm(inertial_nav.get_position_z_up_cm()); + pos_control->set_pos_desired_z_cm(inertial_nav.get_position_z_up_cm()); } // user initiated takeoff for guided mode @@ -4051,7 +3977,7 @@ bool QuadPlane::is_vtol_land(uint16_t id) const { if (id == MAV_CMD_NAV_VTOL_LAND || id == MAV_CMD_NAV_PAYLOAD_PLACE) { if (landing_with_fixed_wing_spiral_approach()) { - return plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING; + return plane.vtol_approach_s.approach_stage == Plane::VTOLApproach::Stage::VTOL_LANDING; } else { return true; } @@ -4066,9 +3992,9 @@ bool QuadPlane::is_vtol_land(uint16_t id) const /* return true if we are in a transition to fwd flight from hover */ -bool QuadPlane::in_transition(void) const +bool QuadPlane::in_frwd_transition(void) const { - return available() && transition->active(); + return available() && transition->active_frwd(); } /* @@ -4276,7 +4202,7 @@ uint16_t QuadPlane::get_pilot_velocity_z_max_dn() const { if (is_zero(pilot_speed_z_max_dn)) { return abs(pilot_speed_z_max_up*100); - } + } return abs(pilot_speed_z_max_dn*100); } @@ -4447,9 +4373,22 @@ bool SLT_Transition::allow_update_throttle_mix() const return !(quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER)); } -bool SLT_Transition::active() const +bool SLT_Transition::active_frwd() const { - return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)); + // We need to be in assisted flight... + if (!quadplane.assisted_flight) { + return false; + } + // ... and a transition must be active... + if (!((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER))) { + return false; + } + // ... but not executing a QPOS_AIRBRAKE maneuver during an automated landing. + if (quadplane.in_vtol_airbrake()) { + return false; + } + + return true; } /* @@ -4561,12 +4500,16 @@ void SLT_Transition::set_last_fw_pitch() last_fw_nav_pitch_cd = plane.nav_pitch_cd; } -void SLT_Transition::force_transition_complete() { - transition_state = TRANSITION_DONE; +void SLT_Transition::force_transition_complete() +{ + transition_state = TRANSITION_DONE; in_forced_transition = false; transition_start_ms = 0; transition_low_airspeed_ms = 0; set_last_fw_pitch(); + + // Keep assistance reset while not checking + quadplane.assist.reset(); } MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const @@ -4624,7 +4567,8 @@ void SLT_Transition::set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_ } // set a single loop pitch limit in TECS - plane.TECS_controller.set_pitch_max_limit(max_pitch); + plane.TECS_controller.set_pitch_max(max_pitch); + plane.TECS_controller.set_pitch_min(-max_pitch); // ensure pitch is constrained to limit nav_pitch_cd = constrain_int32(nav_pitch_cd, -max_pitch*100.0, max_pitch*100.0); @@ -4652,6 +4596,11 @@ void QuadPlane::mode_enter(void) poscontrol.last_velocity_match_ms = 0; poscontrol.set_state(QuadPlane::QPOS_NONE); + // Clear any pilot corrections + poscontrol.pilot_correction_done = false; + poscontrol.pilot_correction_active = false; + poscontrol.target_vel_cms.zero(); + // clear guided takeoff wait on any mode change, but remember the // state for special behaviour guided_wait_takeoff_on_mode_enter = guided_wait_takeoff; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 5b2b35fa92dffe..e4489fd0d17c17 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -26,6 +26,7 @@ #include "tailsitter.h" #include "tiltrotor.h" #include "transition.h" +#include "VTOL_Assist.h" /* QuadPlane specific functionality @@ -45,6 +46,7 @@ class QuadPlane friend class Tiltrotor; friend class SLT_Transition; friend class Tailsitter_Transition; + friend class VTOL_Assist; friend class Mode; friend class ModeManual; @@ -74,6 +76,13 @@ class QuadPlane void control_auto(void); bool setup(void); + enum class ThrustType : uint8_t { + SLT=0, // Traditional quadplane, with a pusher motor and independent multicopter lift. + TAILSITTER, + TILTROTOR, + }; + ThrustType get_thrust_type(void) {return thrust_type;} + void vtol_position_controller(void); void setup_target_position(void); void takeoff_controller(void); @@ -101,10 +110,7 @@ class QuadPlane // abort landing, only valid when in a VTOL landing descent bool abort_landing(void); - /* - return true if we are in a transition to fwd flight from hover - */ - bool in_transition(void) const; + bool in_frwd_transition(void) const; bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const; @@ -162,13 +168,6 @@ class QuadPlane MAV_TYPE get_mav_type(void) const; - enum Q_ASSIST_STATE_ENUM { - Q_ASSIST_DISABLED, - Q_ASSIST_ENABLED, - Q_ASSIST_FORCE, - }; - 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); @@ -203,6 +202,9 @@ class QuadPlane AP_Enum frame_class; AP_Enum frame_type; + // Types of different "quadplane" configurations. + ThrustType thrust_type; + // Initialise motors to allow passing it to tailsitter in its constructor AP_MotorsMulticopter *motors = nullptr; const struct AP_Param::GroupInfo *motors_var_info; @@ -232,9 +234,6 @@ class QuadPlane // return true if airmode should be active bool air_mode_active() const; - // check for quadplane assistance needed - bool should_assist(float aspeed, bool have_airspeed); - // check for an EKF yaw reset void check_yaw_reset(void); @@ -336,18 +335,8 @@ class QuadPlane AP_Int16 rc_speed; - // speed below which quad assistance is given - AP_Float assist_speed; - - // angular error at which quad assistance is given - AP_Int8 assist_angle; - uint32_t angle_error_start_ms; - AP_Float assist_delay; - - // altitude to trigger assistance - AP_Int16 assist_alt; - uint32_t alt_error_start_ms; - bool in_alt_assist; + // VTOL assistance in a forward flight mode + VTOL_Assist assist {*this}; // landing speed in m/s AP_Float land_final_speed; @@ -454,16 +443,13 @@ class QuadPlane Transition *transition = nullptr; // true when waiting for pilot throttle - bool throttle_wait:1; + bool throttle_wait; // true when quad is assisting a fixed wing mode - bool assisted_flight:1; - - // true when in angle assist - bool in_angle_assist:1; + bool assisted_flight; // are we in a guided takeoff? - bool guided_takeoff:1; + bool guided_takeoff; /* 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 @@ -623,6 +609,9 @@ class QuadPlane return (options.get() & int32_t(option)) != 0; } + // minimum distance to be from destination to use approach logic + AP_Float approach_distance; + AP_Float takeoff_failure_scalar; AP_Float maximum_takeoff_airspeed; uint32_t takeoff_start_time_ms; @@ -685,9 +674,6 @@ class QuadPlane // 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; - /* return true if we should use the fixed wing attitude control loop */ diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index e601c94fde10eb..49835adcfdf66a 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -8,16 +8,17 @@ */ void Plane::set_control_channels(void) { + // the library gaurantees that these are non-nullptr: if (g.rudder_only) { // in rudder only mode the roll and rudder channels are the // same. - channel_roll = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_roll = &rc().get_yaw_channel(); } else { - channel_roll = RC_Channels::rc_channel(rcmap.roll()-1); + channel_roll = &rc().get_roll_channel(); } - channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1); - channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1); - channel_rudder = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_pitch = &rc().get_pitch_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_rudder = &rc().get_yaw_channel(); // set rc channel ranges channel_roll->set_angle(SERVO_MAX); @@ -57,6 +58,8 @@ void Plane::set_control_channels(void) // setup correct scaling for ESCs like the UAVCAN ESCs which // take a proportion of speed. For quadplanes we use AP_Motors // scaling + g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttleLeft); + g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttleRight); g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); } } @@ -104,7 +107,7 @@ void Plane::init_rc_out_main() */ void Plane::init_rc_out_aux() { - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); servos_output(); diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index 91d3ed5b77a995..a0aebe06b8dfd3 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -2,6 +2,7 @@ #include #include +#if AP_RANGEFINDER_ENABLED /* read the rangefinder and update height estimate */ @@ -33,3 +34,5 @@ void Plane::read_rangefinder(void) rangefinder_height_update(); } + +#endif // AP_RANGEFINDER_ENABLED diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 24c8659d0e54d2..2ded238cf2f5ba 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -22,7 +22,7 @@ /***************************************** * Throttle slew limit *****************************************/ -void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func) +void Plane::throttle_slew_limit() { #if HAL_QUADPLANE_ENABLED const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode()); @@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func) if (!do_throttle_slew) { // only do throttle slew limiting in modes where throttle control is automatic - SRV_Channels::set_slew_rate(func, 0.0, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt); return; } @@ -51,11 +53,13 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func) slewrate = g.takeoff_throttle_slewrate; } #if HAL_QUADPLANE_ENABLED - if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) { + if (g.takeoff_throttle_slewrate != 0 && quadplane.in_frwd_transition()) { slewrate = g.takeoff_throttle_slewrate; } #endif - SRV_Channels::set_slew_rate(func, slewrate, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt); + SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt); } /* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode. @@ -78,7 +82,7 @@ bool Plane::suppress_throttle(void) return false; } -#if PARACHUTE == ENABLED +#if HAL_PARACHUTE_ENABLED if (control_mode->does_auto_throttle() && parachute.release_initiated()) { // throttle always suppressed in auto-throttle modes after parachute release initiated throttle_suppressed = true; @@ -348,42 +352,52 @@ void Plane::airbrake_update(void) } /* - setup servos for idle mode + setup servos for idle wiggle mode Idle mode is used during balloon launch to keep servos still, apart from occasional wiggle to prevent freezing up */ -void Plane::set_servos_idle(void) +void ModeAuto::wiggle_servos() { - int16_t servo_value; - // move over full range for 2 seconds - if (auto_state.idle_wiggle_stage != 0) { - auto_state.idle_wiggle_stage += 2; - } - if (auto_state.idle_wiggle_stage == 0) { - servo_value = 0; - } else if (auto_state.idle_wiggle_stage < 50) { - servo_value = auto_state.idle_wiggle_stage * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 100) { - servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 150) { - servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 200) { - servo_value = (auto_state.idle_wiggle_stage-200) * (4500 / 50); - } else { - auto_state.idle_wiggle_stage = 0; - servo_value = 0; + // This is only active while in AUTO running NAV_ALTITUDE_WAIT with wiggle_time > 0 + if (wiggle.last_ms == 0) { + return; } - SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value); - SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value); - SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value); - - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); + int16_t servo_valueElevator; + int16_t servo_valueAileronRudder; + // Wiggle the control surfaces in stages: elevators first, then rudders + ailerons, through the full range over 4 seconds + if (wiggle.stage != 0) { + wiggle.stage += 1; + } + if (wiggle.stage == 0) { + servo_valueElevator = 0; + servo_valueAileronRudder = 0; + } else if (wiggle.stage < 25) { + servo_valueElevator = wiggle.stage * (4500 / 25); + servo_valueAileronRudder = 0; + } else if (wiggle.stage < 75) { + servo_valueElevator = (50 - wiggle.stage) * (4500 / 25); + servo_valueAileronRudder = 0; + } else if (wiggle.stage < 100) { + servo_valueElevator = (wiggle.stage - 100) * (4500 / 25); + servo_valueAileronRudder = 0; + } else if (wiggle.stage < 125) { + servo_valueElevator = 0; + servo_valueAileronRudder = (wiggle.stage - 100) * (4500 / 25); + } else if (wiggle.stage < 175) { + servo_valueElevator = 0; + servo_valueAileronRudder = (150 - wiggle.stage) * (4500 / 25); + } else if (wiggle.stage < 200) { + servo_valueElevator = 0; + servo_valueAileronRudder = (wiggle.stage - 200) * (4500 / 25); + } else { + wiggle.stage = 0; + servo_valueElevator = 0; + servo_valueAileronRudder = 0; + } + SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_valueAileronRudder); + SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_valueElevator); + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_valueAileronRudder); } @@ -502,47 +516,80 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle) #endif // #if AP_BATTERY_WATT_MAX_ENABLED /* - Apply min/max limits to throttle + Apply min/max safety limits to throttle. */ float Plane::apply_throttle_limits(float throttle_in) { - // convert 0 to 100% (or -100 to +100) into PWM + // Pull the base throttle limits. + // These are usually set to map the ESC operating range. int8_t min_throttle = aparm.throttle_min.get(); int8_t max_throttle = aparm.throttle_max.get(); #if AP_ICENGINE_ENABLED - // apply idle governor + // Apply idle governor. g2.ice_control.update_idle_governor(min_throttle); #endif + // If reverse thrust is enabled not allowed right now, the minimum throttle must not fall below 0. if (min_throttle < 0 && !allow_reverse_thrust()) { // reverse thrust is available but inhibited. min_throttle = 0; } - const bool use_takeoff_throttle_max = -#if HAL_QUADPLANE_ENABLED - quadplane.in_transition() || -#endif + // Handle throttle limits for takeoff conditions. + // Query the conditions where TKOFF_THR_MAX applies. + const bool use_takeoff_throttle = (flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING); - if (use_takeoff_throttle_max) { + // Handle throttle limits for takeoff conditions. + if (use_takeoff_throttle) { + // Read from takeoff_state + max_throttle = takeoff_state.throttle_lim_max; + min_throttle = takeoff_state.throttle_lim_min; + } else if (landing.is_flaring()) { + // Allow throttle cutoff when flaring. + // This is to allow the aircraft to bleed speed faster and land with a shut off thruster. + min_throttle = 0; + } + + // Handle throttle limits for transition conditions. +#if HAL_QUADPLANE_ENABLED + if (quadplane.in_frwd_transition()) { if (aparm.takeoff_throttle_max != 0) { max_throttle = aparm.takeoff_throttle_max.get(); } - } else if (landing.is_flaring()) { - min_throttle = 0; + + // Apply minimum throttle limits only for SLT thrust types. + // The other types don't support it well. + if (quadplane.get_thrust_type() == QuadPlane::ThrustType::SLT + && control_mode->does_auto_throttle() + ) { + if (aparm.takeoff_throttle_min.get() != 0) { + min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get()); + } else { + min_throttle = MAX(min_throttle, aparm.throttle_cruise.get()); + } + } } +#endif - // compensate for battery voltage drop + // Compensate the limits for battery voltage drop. + // This relaxes the limits when the battery is getting depleted. g2.fwd_batt_cmp.apply_min_max(min_throttle, max_throttle); #if AP_BATTERY_WATT_MAX_ENABLED - // apply watt limiter + // Ensure that the power draw limits are not exceeded. throttle_watt_limiter(min_throttle, max_throttle); #endif + // Do a sanity check on them. Constrain down if necessary. + min_throttle = MIN(min_throttle, max_throttle); + + // Let TECS know about the updated throttle limits. + // These will be taken into account on the next iteration. + TECS_controller.set_throttle_min(0.01f*min_throttle); + TECS_controller.set_throttle_max(0.01f*max_throttle); return constrain_float(throttle_in, min_throttle, max_throttle); } @@ -576,6 +623,11 @@ void Plane::set_throttle(void) // throttle is suppressed (above) to zero in final flare in auto mode, but we allow instead thr_min if user prefers, eg turbines: SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.throttle_min.get()); + } else if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF) + && (aparm.takeoff_throttle_idle.get() > 0) + ) { + // we want to spin at idle throttle before the takeoff conditions are met + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.takeoff_throttle_idle.get()); } else { // default SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); @@ -745,8 +797,6 @@ void Plane::servos_twin_engine_mix(void) } else { SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left); SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right); - throttle_slew_limit(SRV_Channel::k_throttleLeft); - throttle_slew_limit(SRV_Channel::k_throttleRight); } } @@ -759,7 +809,7 @@ void Plane::servos_twin_engine_mix(void) void Plane::force_flare(void) { #if HAL_QUADPLANE_ENABLED - if (quadplane.in_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts + if (quadplane.in_frwd_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts return; } if (control_mode->is_vtol_mode()) { @@ -810,8 +860,8 @@ void Plane::set_servos(void) // start with output corked. the cork is released when we run // servos_output(), which is run from all code paths in this // function - SRV_Channels::cork(); - + AP::srv().cork(); + // this is to allow the failsafe module to deliberately crash // the plane. Only used in extreme circumstances to meet the // OBC rules @@ -865,7 +915,7 @@ void Plane::set_servos(void) airbrake_update(); // slew rate limit throttle - throttle_slew_limit(SRV_Channel::k_throttle); + throttle_slew_limit(); int8_t min_throttle = 0; #if AP_ICENGINE_ENABLED @@ -969,7 +1019,8 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void) */ void Plane::servos_output(void) { - SRV_Channels::cork(); + auto &srv = AP::srv(); + srv.cork(); // support twin-engine aircraft servos_twin_engine_mix(); @@ -1007,7 +1058,7 @@ void Plane::servos_output(void) SRV_Channels::output_ch_all(); - SRV_Channels::push(); + srv.push(); if (g2.servo_channels.auto_trim_enabled()) { servos_auto_trim(); diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 0191184d505b6b..5aabf77331ca0f 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -2,13 +2,6 @@ #include "qautotune.h" -/***************************************************************************** -* The init_ardupilot function processes everything we need for an in - air restart -* We will determine later if we are actually on the ground and process a -* ground start in that case. -* -*****************************************************************************/ - static void failsafe_check_static() { plane.failsafe_check(); @@ -23,6 +16,7 @@ void Plane::init_ardupilot() pitchController.convert_pid(); // initialise rc channels including setting mode + // CONVERSION: Added for upgrade to ArduPlane 4.2, Sep 2021 #if HAL_QUADPLANE_ENABLED 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 @@ -43,14 +37,18 @@ void Plane::init_ardupilot() // init baro barometer.init(); +#if AP_RANGEFINDER_ENABLED // initialise rangefinder rangefinder.set_log_rfnd_bit(MASK_LOG_SONAR); rangefinder.init(ROTATION_PITCH_270); +#endif // initialise battery monitoring battery.init(); +#if AP_RSSI_ENABLED rssi.init(); +#endif #if AP_RPM_ENABLED rpm_sensor.init(); @@ -60,7 +58,7 @@ void Plane::init_ardupilot() gcs().setup_uarts(); -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED osd.init(); #endif @@ -109,40 +107,7 @@ void Plane::init_ardupilot() #endif AP_Param::reload_defaults_file(true); - - startup_ground(); - - // don't initialise aux rc output until after quadplane is setup as - // that can change initial values of channels - init_rc_out_aux(); - - if (g2.oneshot_mask != 0) { - hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); - } - - set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); - - // set the correct flight mode - // --------------------------- - rc().reset_mode_switch(); - // initialise sensor -#if AP_OPTICALFLOW_ENABLED - if (optflow.enabled()) { - optflow.init(-1); - } -#endif - -#if AC_PRECLAND_ENABLED - g2.precland.init(scheduler.get_loop_rate_hz()); -#endif -} - -//******************************************************************************** -//This function does all the calibrations, etc. that we need during a ground start -//******************************************************************************** -void Plane::startup_ground(void) -{ set_mode(mode_initializing, ModeReason::INITIALISED); #if (GROUND_START_DELAY > 0) @@ -155,7 +120,7 @@ void Plane::startup_ground(void) //INS ground start //------------------------ // - startup_INS_ground(); + startup_INS(); // Save the settings for in-air restart // ------------------------------------ @@ -163,6 +128,9 @@ void Plane::startup_ground(void) // initialise mission library mission.init(); +#if HAL_LOGGING_ENABLED + mission.set_log_start_mission_item_bit(MASK_LOG_CMD); +#endif // initialise AP_Logger library #if HAL_LOGGING_ENABLED @@ -174,8 +142,40 @@ void Plane::startup_ground(void) // reset last heartbeat time, so we don't trigger failsafe on slow // startup gcs().sysid_myggcs_seen(AP_HAL::millis()); -} + // don't initialise aux rc output until after quadplane is setup as + // that can change initial values of channels + init_rc_out_aux(); + + if (g2.oneshot_mask != 0) { + hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); + } + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); + + set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); + + // set the correct flight mode + // --------------------------- + rc().reset_mode_switch(); + + // initialise sensor +#if AP_OPTICALFLOW_ENABLED + if (optflow.enabled()) { + optflow.init(-1); + } +#endif + +#if AC_PRECLAND_ENABLED + // scheduler table specifies 400Hz, but we can call it no faster + // than the scheduler loop rate: + g2.precland.init(MIN(400, scheduler.get_loop_rate_hz())); +#endif + +#if AP_ICENGINE_ENABLED + g2.ice_control.init(); +#endif + +} #if AP_FENCE_ENABLED /* @@ -418,7 +418,7 @@ void Plane::check_short_failsafe() } -void Plane::startup_INS_ground(void) +void Plane::startup_INS(void) { if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) { gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane"); diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 4e28d534440a3e..759fa3d1a44684 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -208,6 +208,8 @@ void Tailsitter::setup() return; } + quadplane.thrust_type = QuadPlane::ThrustType::TAILSITTER; + // Set tailsitter transition rate to match old calculation if (!transition_rate_fw.configured()) { transition_rate_fw.set_and_save(transition_angle_fw / (quadplane.transition_time_ms/2000.0f)); @@ -233,7 +235,7 @@ void Tailsitter::setup() // Setup for control surface less operation if (enable == 2) { - quadplane.q_assist_state = QuadPlane::Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; + quadplane.assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); quadplane.air_mode = AirMode::ASSISTED_FLIGHT_ONLY; // Do not allow arming in forward flight modes @@ -241,7 +243,7 @@ void Tailsitter::setup() quadplane.options.set(quadplane.options.get() | int32_t(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)); } - transition = new Tailsitter_Transition(quadplane, motors, *this); + transition = NEW_NOTHROW Tailsitter_Transition(quadplane, motors, *this); if (!transition) { AP_BoardConfig::allocation_error("tailsitter transition"); } @@ -287,9 +289,6 @@ void Tailsitter::output(void) return; } - float tilt_left = 0.0f; - float tilt_right = 0.0f; - // throttle 0 to 1 float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01; @@ -339,6 +338,10 @@ void Tailsitter::output(void) // set AP_MotorsMatrix throttles for forward flight motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt); + // No tilt output unless forward gain is set + float tilt_left = 0.0; + float tilt_right = 0.0; + // in forward flight: set motor tilt servos and throttles using FW controller if (vectored_forward_gain > 0) { // remove scaling from surface speed scaling and apply throttle scaling @@ -396,8 +399,11 @@ void Tailsitter::output(void) } // output tilt motors - tilt_left = 0.0f; - tilt_right = 0.0f; + + // No output unless hover gain is set + float tilt_left = 0.0; + float tilt_right = 0.0; + if (vectored_hover_gain > 0) { const float hover_throttle = motors->get_throttle_hover(); const float output_throttle = motors->get_throttle(); @@ -436,8 +442,10 @@ void Tailsitter::output(void) tailsitter_motors->set_min_throttle(0.0); } - tilt_left = 0.0f; - tilt_right = 0.0f; + // No tilt output unless hover gain is set + float tilt_left = 0.0; + float tilt_right = 0.0; + if (vectored_hover_gain > 0) { // thrust vectoring VTOL modes tilt_left = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft); @@ -707,7 +715,7 @@ void Tailsitter::speed_scaling(void) // (mass / A) is disk loading DL so: // Ue^2 = (((t / t_h) * DL * 9.81)/(0.5 * rho)) + U0^2 - const float rho = SSL_AIR_DENSITY * plane.barometer.get_air_density_ratio(); + const float rho = SSL_AIR_DENSITY * quadplane.ahrs.get_air_density_ratio(); float hover_rho = rho; if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // if applying altitude correction use sea level density for hover case @@ -752,7 +760,7 @@ void Tailsitter::speed_scaling(void) if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // air density correction - spd_scaler /= plane.barometer.get_air_density_ratio(); + spd_scaler /= quadplane.ahrs.get_air_density_ratio(); } const SRV_Channel::Aux_servo_function_t functions[] = { @@ -819,7 +827,7 @@ void Tailsitter_Transition::update() float aspeed; bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); - quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); + quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed); if (transition_state < TRANSITION_DONE) { // during transition we ask TECS to use a synthetic @@ -885,7 +893,7 @@ void Tailsitter_Transition::VTOL_update() float aspeed; bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); // provide assistance in forward flight portion of tailsitter transition - quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); + quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed); if (!quadplane.tailsitter.transition_vtol_complete()) { return; } @@ -894,6 +902,9 @@ void Tailsitter_Transition::VTOL_update() vtol_limit_start_ms = now; vtol_limit_initial_pitch = quadplane.ahrs_view->pitch_sensor; } + } else { + // Keep assistance reset while not checking + quadplane.assist.reset(); } restart(); } @@ -1006,6 +1017,8 @@ void Tailsitter_Transition::force_transition_complete() vtol_transition_start_ms = AP_HAL::millis(); vtol_transition_initial_pitch = constrain_float(plane.nav_pitch_cd,-8500,8500); fw_limit_start_ms = 0; + + quadplane.assist.reset(); } MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const diff --git a/ArduPlane/tailsitter.h b/ArduPlane/tailsitter.h index fbf26702f8ca9f..143c26cb9beaaf 100644 --- a/ArduPlane/tailsitter.h +++ b/ArduPlane/tailsitter.h @@ -175,7 +175,7 @@ friend class Tailsitter; uint8_t get_log_transition_state() const override { return static_cast(transition_state); } - bool active() const override { return transition_state != TRANSITION_DONE; } + bool active_frwd() const override { return transition_state == TRANSITION_ANGLE_WAIT_FW; } bool show_vtol_view() const override; diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index faa220412fd914..dda412d5ee05f8 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -57,7 +57,7 @@ bool Plane::auto_takeoff_check(void) bool do_takeoff_attitude_check = !(flight_option_enabled(FlightOptions::DISABLE_TOFF_ATTITUDE_CHK)); #if HAL_QUADPLANE_ENABLED // disable attitude check on tailsitters - do_takeoff_attitude_check = !quadplane.tailsitter.enabled(); + do_takeoff_attitude_check &= !quadplane.tailsitter.enabled(); #endif if (!takeoff_state.launchTimerStarted && !is_zero(g.takeoff_throttle_min_accel)) { @@ -121,6 +121,7 @@ bool Plane::auto_takeoff_check(void) takeoff_state.launchTimerStarted = false; takeoff_state.last_tkoff_arm_time = 0; takeoff_state.start_time_ms = now; + takeoff_state.throttle_max_timer_ms = now; steer_state.locked_course_err = 0; // use current heading without any error offset return true; } @@ -179,47 +180,115 @@ void Plane::takeoff_calc_roll(void) */ void Plane::takeoff_calc_pitch(void) { - if (auto_state.highest_airspeed < g.takeoff_rotate_speed) { - // we have not reached rotate speed, use the specified takeoff target pitch angle - nav_pitch_cd = int32_t(100.0f * mode_takeoff.ground_pitch); - return; + // First see if TKOFF_ROTATE_SPD applies. + // This will set the pitch for the first portion of the takeoff, up until cruise speed is reached. + if (g.takeoff_rotate_speed > 0) { + // A non-zero rotate speed is recommended for ground takeoffs. + if (auto_state.highest_airspeed < g.takeoff_rotate_speed) { + // We have not reached rotate speed, use the specified takeoff target pitch angle. + nav_pitch_cd = int32_t(100.0f * mode_takeoff.ground_pitch); + TECS_controller.set_pitch_min(0.01f*nav_pitch_cd); + TECS_controller.set_pitch_max(0.01f*nav_pitch_cd); + return; + } else if (gps.ground_speed() <= (float)aparm.airspeed_cruise) { + // If rotate speed applied, gradually transition from TKOFF_GND_PITCH to the climb angle. + // This is recommended for ground takeoffs, so delay rotation until ground speed indicates adequate airspeed. + const uint16_t min_pitch_cd = 500; // Set a minimum of 5 deg climb angle. + nav_pitch_cd = (gps.ground_speed() / (float)aparm.airspeed_cruise) * auto_state.takeoff_pitch_cd; + nav_pitch_cd = constrain_int32(nav_pitch_cd, min_pitch_cd, auto_state.takeoff_pitch_cd); + TECS_controller.set_pitch_min(0.01f*nav_pitch_cd); + TECS_controller.set_pitch_max(0.01f*nav_pitch_cd); + return; + } } + // We are now past the rotation. + // Initialize pitch limits for TECS. + int16_t pitch_min_cd = get_takeoff_pitch_min_cd(); + bool pitch_clipped_max = false; + + // If we're using an airspeed sensor, we consult TECS. if (ahrs.using_airspeed_sensor()) { - int16_t takeoff_pitch_min_cd = get_takeoff_pitch_min_cd(); calc_nav_pitch(); - if (nav_pitch_cd < takeoff_pitch_min_cd) { - nav_pitch_cd = takeoff_pitch_min_cd; + // At any rate, we don't want to go lower than the minimum pitch bound. + if (nav_pitch_cd < pitch_min_cd) { + nav_pitch_cd = pitch_min_cd; } } else { - if (g.takeoff_rotate_speed > 0) { - // Rise off ground takeoff so delay rotation until ground speed indicates adequate airspeed - nav_pitch_cd = (gps.ground_speed() / (float)aparm.airspeed_cruise) * auto_state.takeoff_pitch_cd; - nav_pitch_cd = constrain_int32(nav_pitch_cd, 500, auto_state.takeoff_pitch_cd); - } else { - // Doing hand or catapult launch so need at least 5 deg pitch to prevent initial height loss - nav_pitch_cd = MAX(auto_state.takeoff_pitch_cd, 500); - } + // If not, we will use the minimum allowed angle. + nav_pitch_cd = pitch_min_cd; + + pitch_clipped_max = true; } + // Check if we have trouble with roll control. if (aparm.stall_prevention != 0) { - if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_TAKEOFF || - control_mode == &mode_takeoff) { - // during takeoff we want to prioritise roll control over - // pitch. Apply a reduction in pitch demand if our roll is - // significantly off. The aim of this change is to - // increase the robustness of hand launches, particularly - // in cross-winds. If we start to roll over then we reduce - // pitch demand until the roll recovers - float roll_error_rad = radians(constrain_float(labs(nav_roll_cd - ahrs.roll_sensor) * 0.01, 0, 90)); - float reduction = sq(cosf(roll_error_rad)); - nav_pitch_cd *= reduction; + // during takeoff we want to prioritise roll control over + // pitch. Apply a reduction in pitch demand if our roll is + // significantly off. The aim of this change is to + // increase the robustness of hand launches, particularly + // in cross-winds. If we start to roll over then we reduce + // pitch demand until the roll recovers + float roll_error_rad = radians(constrain_float(labs(nav_roll_cd - ahrs.roll_sensor) * 0.01, 0, 90)); + float reduction = sq(cosf(roll_error_rad)); + nav_pitch_cd *= reduction; + + if (nav_pitch_cd < pitch_min_cd) { + pitch_min_cd = nav_pitch_cd; } } + // Notify TECS about the external pitch setting, for the next iteration. + TECS_controller.set_pitch_min(0.01f*pitch_min_cd); + if (pitch_clipped_max) {TECS_controller.set_pitch_max(0.01f*nav_pitch_cd);} } /* - * get the pitch min used during takeoff. This matches the mission pitch until near the end where it allows it to levels off + * Calculate the throttle limits to run at during a takeoff. + * These limits are meant to be used exclusively by Plane::apply_throttle_limits(). + */ +void Plane::takeoff_calc_throttle() { + // Initialize the maximum throttle limit. + if (aparm.takeoff_throttle_max != 0) { + takeoff_state.throttle_lim_max = aparm.takeoff_throttle_max; + } else { + takeoff_state.throttle_lim_max = aparm.throttle_max; + } + + // Initialize the minimum throttle limit. + if (aparm.takeoff_throttle_min != 0) { + takeoff_state.throttle_lim_min = aparm.takeoff_throttle_min; + } else { + takeoff_state.throttle_lim_min = aparm.throttle_cruise; + } + + // Raise min to force max throttle for TKOFF_THR_MAX_T after a takeoff. + // It only applies if the timer has been started externally. + if (takeoff_state.throttle_max_timer_ms != 0) { + const uint32_t dt = AP_HAL::millis() - takeoff_state.throttle_max_timer_ms; + if (dt*0.001 < aparm.takeoff_throttle_max_t) { + takeoff_state.throttle_lim_min = takeoff_state.throttle_lim_max; + } else { + // Reset the timer for future use. + takeoff_state.throttle_max_timer_ms = 0; + } + } + + // Enact the TKOFF_OPTIONS logic. + const float current_baro_alt = barometer.get_altitude(); + const bool below_lvl_alt = current_baro_alt < auto_state.baro_takeoff_alt + mode_takeoff.level_alt; + // Set the minimum throttle limit. + const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE); + if (!use_throttle_range // We don't want to employ a throttle range. + || !ahrs.using_airspeed_sensor() // We don't have an airspeed sensor. + || below_lvl_alt // We are below TKOFF_LVL_ALT. + ) { // Traditional takeoff throttle limit. + takeoff_state.throttle_lim_min = takeoff_state.throttle_lim_max; + } + + calc_throttle(); +} + +/* get the pitch min used during takeoff. This matches the mission pitch until near the end where it allows it to levels off */ int16_t Plane::get_takeoff_pitch_min_cd(void) { diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 0be2a078452826..fe893b01cd730d 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -106,6 +106,8 @@ void Tiltrotor::setup() return; } + quadplane.thrust_type = QuadPlane::ThrustType::TILTROTOR; + _is_vectored = tilt_mask != 0 && type == TILT_TYPE_VECTORED_YAW; // true if a fixed forward motor is configured, either throttle, throttle left or throttle right. @@ -142,7 +144,7 @@ void Tiltrotor::setup() } } - transition = new Tiltrotor_Transition(quadplane, motors, *this); + transition = NEW_NOTHROW Tiltrotor_Transition(quadplane, motors, *this); if (!transition) { AP_BoardConfig::allocation_error("tiltrotor transition"); } @@ -295,7 +297,7 @@ void Tiltrotor::continuous_update(void) // operate in all VTOL modes except Q_AUTOTUNE. Forward rotor tilt is used to produce // forward thrust equivalent to what would have been produced by a forward thrust motor // set to quadplane.forward_throttle_pct() - const float fwd_g_demand = 0.01f * quadplane.forward_throttle_pct() / plane.quadplane.q_fwd_thr_gain; + const float fwd_g_demand = 0.01 * quadplane.forward_throttle_pct(); const float fwd_tilt_deg = MIN(degrees(atanf(fwd_g_demand)), (float)max_angle_deg); slew(MIN(fwd_tilt_deg * (1/90.0), get_forward_flight_tilt())); return; @@ -394,6 +396,33 @@ void Tiltrotor::update(void) } } +#if HAL_LOGGING_ENABLED +// Write tiltrotor specific log +void Tiltrotor::write_log() +{ + struct log_tiltrotor pkt { + LOG_PACKET_HEADER_INIT(LOG_TILT_MSG), + time_us : AP_HAL::micros64(), + current_tilt : current_tilt * 90.0, + }; + + if (type != TILT_TYPE_VECTORED_YAW) { + // Left and right tilt are invalid + pkt.front_left_tilt = plane.logger.quiet_nanf(); + pkt.front_right_tilt = plane.logger.quiet_nanf(); + + } else { + // Calculate tilt angle from servo outputs + const float total_angle = 90.0 + tilt_yaw_angle + fixed_angle; + const float scale = total_angle * 0.001; + pkt.front_left_tilt = (SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft) * scale) - tilt_yaw_angle; + pkt.front_right_tilt = (SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorRight) * scale) - tilt_yaw_angle; + } + + plane.logger.WriteBlock(&pkt, sizeof(pkt)); +} +#endif + /* tilt compensation for angle of tilt. When the rotors are tilted the roll effect of differential thrust on the tilted rotors is decreased diff --git a/ArduPlane/tiltrotor.h b/ArduPlane/tiltrotor.h index 95ddd84181b81e..3add549b7113d4 100644 --- a/ArduPlane/tiltrotor.h +++ b/ArduPlane/tiltrotor.h @@ -16,6 +16,7 @@ #include #include "transition.h" +#include class QuadPlane; class AP_MotorsMulticopter; @@ -69,6 +70,9 @@ friend class Tiltrotor_Transition; // always return true if not enabled or not a continuous type bool tilt_angle_achieved() const { return !enabled() || (type != TILT_TYPE_CONTINUOUS) || angle_achieved; } + // Write tiltrotor specific log + void write_log(); + AP_Int8 enable; AP_Int16 tilt_mask; AP_Int16 max_rate_up_dps; @@ -98,6 +102,15 @@ friend class Tiltrotor_Transition; private: + // Tiltrotor specific log message + struct PACKED log_tiltrotor { + LOG_PACKET_HEADER; + uint64_t time_us; + float current_tilt; + float front_left_tilt; + float front_right_tilt; + }; + bool setup_complete; // true if a fixed forward motor is setup diff --git a/ArduPlane/transition.h b/ArduPlane/transition.h index b31e45ff040ece..bf0e0dc5029d8b 100644 --- a/ArduPlane/transition.h +++ b/ArduPlane/transition.h @@ -36,7 +36,7 @@ class Transition virtual uint8_t get_log_transition_state() const = 0; - virtual bool active() const = 0; + virtual bool active_frwd() const = 0; virtual bool show_vtol_view() const = 0; @@ -85,7 +85,7 @@ class SLT_Transition : public Transition uint8_t get_log_transition_state() const override { return static_cast(transition_state); } - bool active() const override; + bool active_frwd() const override; bool show_vtol_view() const override; diff --git a/ArduPlane/version.h b/ArduPlane/version.h index 2cc0a0941a1605..1994c5d7dba224 100644 --- a/ArduPlane/version.h +++ b/ArduPlane/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduPlane V4.6.0-dev" +#define THISFIRMWARE "ArduPlane V4.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 6 +#define FW_MINOR 7 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/ArduPlane/wscript b/ArduPlane/wscript index d983bb59baceec..930fec0b537634 100644 --- a/ArduPlane/wscript +++ b/ArduPlane/wscript @@ -10,18 +10,15 @@ def build(bld): 'APM_Control', 'AP_AdvancedFailsafe', 'AP_Avoidance', - 'AP_Arming', 'AP_Camera', 'AP_L1_Control', 'AP_Navigation', - 'AP_RCMapper', 'AP_TECS', 'AP_InertialNav', 'AC_WPNav', 'AC_AttitudeControl', 'AP_Motors', 'AP_Landing', - 'AP_Beacon', 'PID', 'AP_Soaring', 'AP_LTM_Telem', @@ -30,6 +27,7 @@ def build(bld): 'AP_Follow', 'AC_PrecLand', 'AP_IRLock', + 'AP_Quicktune', ], ) diff --git a/ArduSub/AP_Arming_Sub.cpp b/ArduSub/AP_Arming_Sub.cpp index c3749c3f0cb2dc..6c1c0504c4ee86 100644 --- a/ArduSub/AP_Arming_Sub.cpp +++ b/ArduSub/AP_Arming_Sub.cpp @@ -149,6 +149,14 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks) // flag exiting this function in_arm_motors = false; + // if we do not have an ekf origin then we can't use the WMM tables + if (!sub.ensure_ekf_origin()) { + gcs().send_text(MAV_SEVERITY_WARNING, "Compass performance degraded"); + if (check_enabled(ARMING_CHECK_PARAMETERS)) { + check_failed(ARMING_CHECK_PARAMETERS, true, "No world position, check ORIGIN_* parameters"); + return false; + } + } // return success return true; } diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 507a22fb1b814c..002fbfbaad5915 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -79,7 +79,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(update_altitude, 10, 100, 18), SCHED_TASK(three_hz_loop, 3, 75, 21), SCHED_TASK(update_turn_counter, 10, 50, 24), - SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90, 27), 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), @@ -159,10 +158,7 @@ void Sub::fifty_hz_loop() failsafe_sensors_check(); - // Update rc input/output rc().read_input(); - SRV_Channels::calc_pwm(); - SRV_Channels::output_ch_all(); } // update_batt_compass - read battery and compass @@ -187,7 +183,8 @@ void Sub::ten_hz_logging_loop() // log attitude data if we're not already logging at the higher rate if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); - ahrs_view.Write_Rate(motors, attitude_control, pos_control); + attitude_control.Write_ANG(); + attitude_control.Write_Rate(pos_control); 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()); @@ -226,7 +223,8 @@ void Sub::twentyfive_hz_logging() { if (should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); - ahrs_view.Write_Rate(motors, attitude_control, pos_control); + attitude_control.Write_ANG(); + attitude_control.Write_Rate(pos_control); 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()); @@ -272,6 +270,9 @@ void Sub::three_hz_loop() // one_hz_loop - runs at 1Hz void Sub::one_hz_loop() { + // sync MAVLink system ID + mavlink_system.sysid = g.sysid_this_mav; + bool arm_check = arming.pre_arm_checks(false); ap.pre_arm_check = arm_check; AP_Notify::flags.pre_arm_check = arm_check; @@ -289,7 +290,7 @@ void Sub::one_hz_loop() } // update assigned functions and enable auxiliary servos - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); #if HAL_LOGGING_ENABLED // log terrain data @@ -430,4 +431,51 @@ float Sub::get_alt_msl() const return -posD; } +bool Sub::ensure_ekf_origin() +{ + Location ekf_origin; + if (ahrs.get_origin(ekf_origin)) { + // ekf origin is set + return true; + } + + if (gps.num_sensors() > 0) { + // wait for the gps sensor to set the origin + // alert the pilot to poor compass performance + return false; + } + + auto backup_origin = Location(static_cast(sub.g2.backup_origin_lat * 1e7), + static_cast(sub.g2.backup_origin_lon * 1e7), + static_cast(sub.g2.backup_origin_alt * 100), + Location::AltFrame::ABSOLUTE); + + if (backup_origin.lat == 0 || backup_origin.lng == 0) { + gcs().send_text(MAV_SEVERITY_WARNING, "Backup location parameters are missing or zero"); + return false; + } + + if (!check_latlng(backup_origin.lat, backup_origin.lng)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Backup location parameters are not valid"); + return false; + } + + if (!ahrs.set_origin(backup_origin)) { + // a possible problem is that ek3_srcn_posxy is set to 3 (gps) + gcs().send_text(MAV_SEVERITY_WARNING, "Failed to set origin, check EK3_SRC parameters"); + return false; + } + + gcs().send_text(MAV_SEVERITY_INFO, "Using backup location"); + +#if HAL_LOGGING_ENABLED + ahrs.Log_Write_Home_And_Origin(); +#endif + + // send ekf origin to GCS + gcs().send_message(MSG_ORIGIN); + + return true; +} + AP_HAL_MAIN_CALLBACKS(&sub); diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index dbea46d35ce448..f17901638d76a5 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -63,6 +63,9 @@ MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const if (sub.motors.armed()) { return MAV_STATE_ACTIVE; } + if (!sub.ap.initialised) { + return MAV_STATE_BOOT; + } return MAV_STATE_STANDBY; } @@ -245,12 +248,16 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) send_info(); break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE + case MSG_TERRAIN_REQUEST: CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); sub.terrain.send_request(chan); -#endif break; + case MSG_TERRAIN_REPORT: + CHECK_PAYLOAD_SIZE(TERRAIN_REPORT); + sub.terrain.send_report(chan); + break; +#endif default: return GCS_MAVLINK::try_send_message(id); @@ -263,13 +270,13 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station + // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, AIRSPEED, and SENSOR_OFFSETS to ground station // @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), + AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 2), // @Param: EXT_STAT // @DisplayName: Extended status stream rate to ground station @@ -279,7 +286,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 0), + AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 2), // @Param: RC_CHAN // @DisplayName: RC Channel stream rate to ground station @@ -289,7 +296,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 0), + AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 2), // @Param: POSITION // @DisplayName: Position stream rate to ground station @@ -299,7 +306,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 0), + AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 3), // @Param: EXTRA1 // @DisplayName: Extra data type 1 stream rate to ground station @@ -309,7 +316,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 0), + AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 10), // @Param: EXTRA2 // @DisplayName: Extra data type 2 stream rate to ground station @@ -319,7 +326,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 0), + AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 10), // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate to ground station @@ -329,7 +336,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 0), + AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 3), // @Param: PARAMS // @DisplayName: Parameter stream rate to ground station @@ -350,6 +357,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -359,10 +369,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif MSG_NAV_CONTROLLER_OUTPUT, @@ -378,7 +394,9 @@ static const ap_message STREAM_POSITION_msgs[] = { static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_SERVO_OUTPUT_RAW, MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -399,7 +417,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_DISTANCE_SENSOR, #if AP_TERRAIN_AVAILABLE - MSG_TERRAIN, + MSG_TERRAIN_REQUEST, + MSG_TERRAIN_REPORT, #endif #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, @@ -424,7 +443,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { @@ -480,6 +500,46 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc) return MAV_RESULT_ACCEPTED; } +MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_do_reposition(const mavlink_command_int_t &packet) +{ + const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE; + if (!sub.flightmode->in_guided_mode() && !change_modes) { + return MAV_RESULT_DENIED; + } + + // sanity check location + if (!check_latlng(packet.x, packet.y)) { + return MAV_RESULT_DENIED; + } + + Location request_location; + if (!location_from_command_t(packet, request_location)) { + return MAV_RESULT_DENIED; + } + + if (request_location.sanitize(sub.current_loc)) { + // if the location wasn't already sane don't load it + return MAV_RESULT_DENIED; // failed as the location is not valid + } + + // we need to do this first, as we don't want to change the flight mode unless we can also set the target + if (!sub.mode_guided.guided_set_destination(request_location)) { + return MAV_RESULT_FAILED; + } + + if (!sub.flightmode->in_guided_mode()) { + if (!sub.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_FAILED; + } + // the position won't have been loaded if we had to change the flight mode, so load it again + if (!sub.mode_guided.guided_set_destination(request_location)) { + return MAV_RESULT_FAILED; + } + } + + return MAV_RESULT_ACCEPTED; +} + MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { @@ -493,7 +553,14 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_ case MAV_CMD_DO_MOTOR_TEST: return handle_MAV_CMD_DO_MOTOR_TEST(packet); + case MAV_CMD_DO_REPOSITION: + return handle_command_int_do_reposition(packet); + case MAV_CMD_MISSION_START: + if (!is_zero(packet.param1) || !is_zero(packet.param2)) { + // first-item/last item not supported + return MAV_RESULT_DENIED; + } return handle_MAV_CMD_MISSION_START(packet); case MAV_CMD_NAV_LOITER_UNLIM: @@ -762,7 +829,7 @@ void GCS_MAVLINK_Sub::handle_message(const mavlink_message_t &msg) */ if (!z_ignore && sub.control_mode == Mode::Number::ALT_HOLD) { // Control only target depth when in ALT_HOLD - sub.pos_control.set_pos_target_z_cm(packet.alt*100); + sub.pos_control.set_pos_desired_z_cm(packet.alt*100); break; } @@ -902,3 +969,47 @@ uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const return 0; } #endif // HAL_HIGH_LATENCY2_ENABLED + +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const +{ + const Mode* modes[] { + &sub.mode_manual, + &sub.mode_stabilize, + &sub.mode_acro, + &sub.mode_althold, + &sub.mode_surftrak, + &sub.mode_poshold, + &sub.mode_auto, + &sub.mode_guided, + &sub.mode_circle, + &sub.mode_surface, + &sub.mode_motordetect, + }; + + const uint8_t mode_count = ARRAY_SIZE(modes); + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name = modes[index_zero]->name(); + const uint8_t mode_number = (uint8_t)modes[index_zero]->number(); + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 4ca41e1d8c9e84..7dc2d0c1a25863 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -22,6 +22,7 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK { MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); // override sending of scaled_pressure3 to send on-board temperature: void send_scaled_pressure3() override; @@ -36,6 +37,10 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK { uint64_t capabilities() const override; + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: void handle_message(const mavlink_message_t &msg) override; diff --git a/ArduSub/GCS_Sub.cpp b/ArduSub/GCS_Sub.cpp index b57839c9bc842e..bd99d9b0804907 100644 --- a/ArduSub/GCS_Sub.cpp +++ b/ArduSub/GCS_Sub.cpp @@ -73,7 +73,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags() } #endif -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED const RangeFinder *rangefinder = RangeFinder::get_singleton(); if (sub.rangefinder_state.enabled) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; diff --git a/ArduSub/GCS_Sub.h b/ArduSub/GCS_Sub.h index b0b6c373f55ecf..b99f2d4ec10df9 100644 --- a/ArduSub/GCS_Sub.h +++ b/ArduSub/GCS_Sub.h @@ -37,7 +37,7 @@ class GCS_Sub : public GCS GCS_MAVLINK_Sub *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Sub(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Sub(params, uart); } }; diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index e197ad3ba4d9cb..88642afe26e3d2 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -59,9 +59,7 @@ void Sub::Log_Write_Control_Tuning() // Write an attitude packet void Sub::Log_Write_Attitude() { - Vector3f targets = attitude_control.get_att_target_euler_cd(); - targets.z = wrap_360_cd(targets.z); - ahrs.Write_Attitude(targets); + ahrs.Write_Attitude(attitude_control.get_att_target_euler_rad() * RAD_TO_DEG); AP::ahrs().Log_Write(); } diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 1ff768051f0fbb..0314f28cedabd8 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -68,7 +68,6 @@ const AP_Param::Info Sub::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:Roll,2:Pitch,4:Yaw // @Bitmask: 0:Roll,1:Pitch,2:Yaw GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), @@ -79,6 +78,14 @@ const AP_Param::Info Sub::var_info[] = { // @User: Standard GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM), + // @Param: FS_GCS_TIMEOUT + // @DisplayName: GCS failsafe timeout + // @Description: Timeout before triggering the GCS failsafe + // @Units: s + // @Increment: 1 + // @User: Standard + GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S), + // @Param: FS_LEAK_ENABLE // @DisplayName: Leak Failsafe Enable // @Description: Controls what action to take if a leak is detected. @@ -154,7 +161,7 @@ const AP_Param::Info Sub::var_info[] = { // @DisplayName: Pilot maximum vertical ascending speed // @Description: The maximum vertical ascending velocity the pilot may request in cm/s // @Units: cm/s - // @Range: 50 500 + // @Range: 20 500 // @Increment: 10 // @User: Standard GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX), @@ -163,7 +170,7 @@ const AP_Param::Info Sub::var_info[] = { // @DisplayName: Pilot maximum vertical descending speed // @Description: The maximum vertical descending velocity the pilot may request in cm/s // @Units: cm/s - // @Range: 50 500 + // @Range: 20 500 // @Increment: 10 // @User: Standard GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0), @@ -189,7 +196,6 @@ const AP_Param::Info Sub::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask // @Description: 4 byte bitmap of log types to enable - // @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled // @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 // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), @@ -486,7 +492,7 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp GOBJECT(loiter_nav, "LOIT_", AC_Loiter), -#if CIRCLE_NAV_ENABLED == ENABLED +#if CIRCLE_NAV_ENABLED // @Group: CIRCLE_ // @Path: ../libraries/AC_WPNav/AC_Circle.cpp GOBJECT(circle_nav, "CIRCLE_", AC_Circle), @@ -592,7 +598,7 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), -#if AVOIDANCE_ENABLED == ENABLED +#if AVOIDANCE_ENABLED // @Group: AVOID_ // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp GOBJECT(avoid, "AVOID_", AC_Avoid), @@ -608,7 +614,7 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp,../libraries/AP_Motors/AP_MotorsMulticopter.cpp GOBJECT(motors, "MOT_", AP_Motors6DOF), -#if RCMAP_ENABLED == ENABLED +#if RCMAP_ENABLED // @Group: RCMAP_ // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp GOBJECT(rcmap, "RCMAP_", RCMapper), @@ -630,7 +636,7 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECT(mission, "MIS_", AP_Mission), -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), @@ -708,7 +714,26 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // 18 was scripting - // 19 was airspeed + // @Param: ORIGIN_LAT + // @DisplayName: Backup latitude for EKF origin + // @Description: Backup EKF origin latitude used when not using a positioning system. + // @Units: deg + // @User: Standard + AP_GROUPINFO("ORIGIN_LAT", 19, ParametersG2, backup_origin_lat, 0), + + // @Param: ORIGIN_LON + // @DisplayName: Backup longitude for EKF origin + // @Description: Backup EKF origin longitude used when not using a positioning system. + // @Units: deg + // @User: Standard + AP_GROUPINFO("ORIGIN_LON", 20, ParametersG2, backup_origin_lon, 0), + + // @Param: ORIGIN_ALT + // @DisplayName: Backup altitude (MSL) for EKF origin + // @Description: Backup EKF origin altitude (MSL) used when not using a positioning system. + // @Units: m + // @User: Standard + AP_GROUPINFO("ORIGIN_ALT", 21, ParametersG2, backup_origin_alt, 0), AP_GROUPEND }; diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 5795c5016843d7..fe176e400e6c97 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -185,6 +185,7 @@ class Parameters { k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor k_param_failsafe_pilot_input, k_param_failsafe_pilot_input_timeout, + k_param_failsafe_gcs_timeout, // Misc Sub settings @@ -243,7 +244,7 @@ class Parameters { AP_Float throttle_filt; -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED AP_Int8 rangefinder_signal_min; // minimum signal quality for good rangefinder readings AP_Float surftrak_depth; // surftrak will try to keep sub below this depth #endif @@ -257,6 +258,7 @@ class Parameters { AP_Int8 failsafe_terrain; AP_Int8 failsafe_pilot_input; // pilot input failsafe behavior AP_Float failsafe_pilot_input_timeout; + AP_Float failsafe_gcs_timeout; // ground station failsafe timeout (seconds) AP_Int8 xtrack_angle_limit; @@ -366,6 +368,9 @@ class ParametersG2 { // control over servo output ranges SRV_Channels servo_channels; + AP_Float backup_origin_lat; + AP_Float backup_origin_lon; + AP_Float backup_origin_alt; }; extern const AP_Param::Info var_info[]; @@ -382,9 +387,11 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "RC3_TRIM", 1100}, { "COMPASS_OFFS_MAX", 1000}, { "INS_GYR_CAL", 0}, +#if HAL_MOUNT_ENABLED { "MNT1_TYPE", 1}, { "MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING}, { "MNT1_RC_RATE", 30}, +#endif { "RC7_OPTION", 214}, // MOUNT1_YAW { "RC8_OPTION", 213}, // MOUNT1_PITCH { "MOT_PWM_MIN", 1100}, @@ -395,7 +402,9 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "PSC_VELXY_P", 6.0f}, { "EK3_SRC1_VELZ", 0}, #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR +#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED { "BARO_PROBE_EXT", 0}, +#endif { "BATT_MONITOR", 4}, { "BATT_CAPACITY", 0}, { "LEAK1_PIN", 27}, @@ -405,7 +414,9 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "SERVO16_FUNCTION", 7}, // k_mount_tilt { "SERVO16_REVERSED", 1}, #else +#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED { "BARO_PROBE_EXT", 768}, +#endif { "SERVO9_FUNCTION", 59}, // k_rcin9, lights 1 { "SERVO10_FUNCTION", 7}, // k_mount_tilt #endif diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 877f3bf8c17cae..6f74102ef0d047 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -27,8 +27,6 @@ Sub::Sub() : control_mode(Mode::Number::MANUAL), motors(MAIN_LOOP_RATE), - auto_mode(Auto_WP), - guided_mode(Guided_WP), auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP), inertial_nav(ahrs), ahrs_view(ahrs, ROTATION_NONE), @@ -38,7 +36,9 @@ Sub::Sub() loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control), circle_nav(inertial_nav, ahrs_view, pos_control), param_loader(var_info), - flightmode(&mode_manual) + flightmode(&mode_manual), + auto_mode(Auto_WP), + guided_mode(Guided_WP) { #if CONFIG_HAL_BOARD != HAL_BOARD_SITL failsafe.pilot_input = true; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 6aba8c71861ef4..9c6e621bc45f10 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -78,7 +78,7 @@ #include // Optical Flow library // libraries which are dependent on #defines in defines.h and/or config.h -#if RCMAP_ENABLED == ENABLED +#if RCMAP_ENABLED #include // RC input mapping library #endif @@ -88,7 +88,7 @@ #include #endif -#if AVOIDANCE_ENABLED == ENABLED +#if AVOIDANCE_ENABLED #include // Stop at fence library #endif @@ -206,7 +206,7 @@ class Sub : public AP_Vehicle { Mode::Number prev_control_mode; -#if RCMAP_ENABLED == ENABLED +#if RCMAP_ENABLED RCMapper rcmap; #endif @@ -232,7 +232,18 @@ class Sub : public AP_Vehicle { } failsafe; bool any_failsafe_triggered() const { - return (failsafe.pilot_input || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain); + return ( + failsafe.pilot_input + || battery.has_failsafed() + || failsafe.gcs + || failsafe.ekf + || failsafe.terrain + || failsafe.leak + || failsafe.internal_pressure + || failsafe.internal_temperature + || failsafe.crash + || failsafe.sensor_health + ); } // sensor health for logging @@ -344,7 +355,7 @@ class Sub : public AP_Vehicle { AP_Mount camera_mount; #endif -#if AVOIDANCE_ENABLED == ENABLED +#if AVOIDANCE_ENABLED AC_Avoid avoid; #endif @@ -428,6 +439,8 @@ class Sub : public AP_Vehicle { float get_alt_rel() const WARN_IF_UNUSED; float get_alt_msl() const WARN_IF_UNUSED; void exit_mission(); + void set_origin(const Location& loc); + bool ensure_ekf_origin(); bool verify_loiter_unlimited(); bool verify_loiter_time(); bool verify_wait_delay(); @@ -501,7 +514,7 @@ class Sub : public AP_Vehicle { void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd); void do_circle(const AP_Mission::Mission_Command& cmd); void do_loiter_time(const AP_Mission::Mission_Command& cmd); -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd); void do_guided_limits(const AP_Mission::Mission_Command& cmd); #endif @@ -518,13 +531,11 @@ class Sub : public AP_Vehicle { bool verify_surface(const AP_Mission::Mission_Command& cmd); bool verify_RTL(void); bool verify_circle(const AP_Mission::Mission_Command& cmd); -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd); #endif bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); - void log_init(void); - void failsafe_leak_check(); void failsafe_internal_pressure_check(); void failsafe_internal_temperature_check(); @@ -614,10 +625,10 @@ class Sub : public AP_Vehicle { // For Lua scripting, so index is 1..4, not 0..3 uint8_t get_and_clear_button_count(uint8_t index); -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED float get_rangefinder_target_cm() const WARN_IF_UNUSED { return mode_surftrak.get_rangefinder_target_cm(); } bool set_rangefinder_target_cm(float new_target_cm) { return mode_surftrak.set_rangefinder_target_cm(new_target_cm); } -#endif // RANGEFINDER_ENABLED +#endif // AP_RANGEFINDER_ENABLED #endif // AP_SCRIPTING_ENABLED }; diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index a77f4111e7254f..c24ac74aa115f2 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -7,13 +7,6 @@ static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCAT // start_command - this function will be called when the ap_mission lib wishes to start a new command bool Sub::start_command(const AP_Mission::Mission_Command& cmd) { -#if HAL_LOGGING_ENABLED - // To-Do: logging when new commands start/end - if (should_log(MASK_LOG_CMD)) { - logger.Write_Mission_Cmd(mission, cmd); - } -#endif - const Location &target_loc = cmd.content.location; auto alt_frame = target_loc.get_alt_frame(); @@ -61,7 +54,7 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd) do_loiter_time(cmd); break; -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer do_nav_guided_enable(cmd); break; @@ -107,7 +100,7 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd) do_mount_control(cmd); break; -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits do_guided_limits(cmd); break; @@ -170,7 +163,7 @@ bool Sub::verify_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_NAV_LOITER_TIME: return verify_loiter_time(); -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED case MAV_CMD_NAV_GUIDED_ENABLE: return verify_nav_guided_enable(cmd); #endif @@ -384,7 +377,7 @@ void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd) loiter_time_max = cmd.p1; // units are (seconds) } -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED // do_nav_guided_enable - initiate accepting commands from external nav computer void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { @@ -417,7 +410,7 @@ void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd) gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); } -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED // do_guided_limits - pass guided limits to guided controller void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd) { @@ -550,7 +543,7 @@ bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd) return fabsf(sub.circle_nav.get_angle_total()/M_2PI) >= turns; } -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED // verify_nav_guided - check if we have breached any limits bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { diff --git a/ArduSub/config.h b/ArduSub/config.h index 673cd17ae81a6f..7e2f5686266e33 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -31,7 +31,7 @@ // #ifndef CIRCLE_NAV_ENABLED -# define CIRCLE_NAV_ENABLED ENABLED +# define CIRCLE_NAV_ENABLED 1 #endif ////////////////////////////////////////////////////////////////////////////// @@ -39,17 +39,13 @@ // #ifndef RCMAP_ENABLED -# define RCMAP_ENABLED DISABLED +# define RCMAP_ENABLED 0 #endif ////////////////////////////////////////////////////////////////////////////// // Rangefinder // -#ifndef RANGEFINDER_ENABLED -# define RANGEFINDER_ENABLED ENABLED -#endif - #ifndef RANGEFINDER_HEALTH_MAX # define RANGEFINDER_HEALTH_MAX 3 // number of good reads that indicates a healthy rangefinder #endif @@ -63,7 +59,7 @@ #endif #ifndef RANGEFINDER_TILT_CORRECTION // by disable tilt correction for use of range finder data by EKF -# define RANGEFINDER_TILT_CORRECTION DISABLED +# define RANGEFINDER_TILT_CORRECTION 0 #endif #ifndef RANGEFINDER_SIGNAL_MIN_DEFAULT @@ -76,11 +72,11 @@ // Avoidance (relies on Proximity and Fence) #ifndef AVOIDANCE_ENABLED -# define AVOIDANCE_ENABLED DISABLED +# define AVOIDANCE_ENABLED 0 #endif -#if AVOIDANCE_ENABLED == ENABLED // Avoidance Library relies on Fence -# define FENCE_ENABLED ENABLED +#if AVOIDANCE_ENABLED // Avoidance Library relies on Fence +# define FENCE_ENABLED 1 #endif #ifndef MAV_SYSTEM_ID @@ -94,7 +90,7 @@ ////////////////////////////////////////////////////////////////////////////// // Nav-Guided - allows external nav computer to control vehicle #ifndef NAV_GUIDED -# define NAV_GUIDED ENABLED +# define NAV_GUIDED 1 #endif ////////////////////////////////////////////////////////////////////////////// @@ -160,7 +156,7 @@ // PosHold parameter defaults // #ifndef POSHOLD_ENABLED -# define POSHOLD_ENABLED ENABLED // PosHold flight mode enabled by default +# define POSHOLD_ENABLED 1 // PosHold flight mode enabled by default #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduSub/defines.h b/ArduSub/defines.h index 87e45820bc9828..af49e7ccd199c2 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -2,14 +2,6 @@ #include -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - #define BOTTOM_DETECTOR_TRIGGER_SEC 1.0 #define SURFACE_DETECTOR_TRIGGER_SEC 1.0 @@ -77,10 +69,10 @@ enum LoggingParameters { // GCS failsafe #ifndef FS_GCS -# define FS_GCS DISABLED +# define FS_GCS 0 #endif -#ifndef FS_GCS_TIMEOUT_MS -# define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after this number of milliseconds with no GCS heartbeat +#ifndef FS_GCS_TIMEOUT_S +# define FS_GCS_TIMEOUT_S 5.0 // gcs failsafe triggers after this number of seconds with no GCS heartbeat #endif // missing terrain data failsafe diff --git a/ArduSub/failsafe.cpp b/ArduSub/failsafe.cpp index 80c74ed45829d1..7807daed146be9 100644 --- a/ArduSub/failsafe.cpp +++ b/ArduSub/failsafe.cpp @@ -321,7 +321,8 @@ void Sub::failsafe_gcs_check() uint32_t tnow = AP_HAL::millis(); // Check if we have gotten a GCS heartbeat recently (GCS sysid must match SYSID_MYGCS parameter) - if (tnow - gcs_last_seen_ms < FS_GCS_TIMEOUT_MS) { + const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g.failsafe_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX)); + if (tnow - gcs_last_seen_ms < gcs_timeout_ms) { // Log event if we are recovering from previous gcs failsafe if (failsafe.gcs) { LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index ad2710c6c1ae38..5e12c0eeae8627 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -190,7 +190,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) case JSButton::button_function_t::k_mode_poshold: set_mode(Mode::Number::POSHOLD, ModeReason::RC_COMMAND); break; -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED case JSButton::button_function_t::k_mode_surftrak: set_mode(Mode::Number::SURFTRAK, ModeReason::RC_COMMAND); break; @@ -525,6 +525,16 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed } break; + case JSButton::button_function_t::k_servo_2_min_toggle: + if(!held) { + SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed + if(chan->get_output_pwm() != chan->get_output_min()) { + ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed + } else { + ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed + } + } + break; case JSButton::button_function_t::k_servo_2_max: case JSButton::button_function_t::k_servo_2_max_momentary: { @@ -532,6 +542,16 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed } break; + case JSButton::button_function_t::k_servo_2_max_toggle: + if(!held) { + SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed + if(chan->get_output_pwm() != chan->get_output_max()) { + ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed + } else { + ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed + } + } + break; case JSButton::button_function_t::k_servo_2_center: { SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed @@ -562,6 +582,16 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed } break; + case JSButton::button_function_t::k_servo_3_min_toggle: + if(!held) { + SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed + if(chan->get_output_pwm() != chan->get_output_min()) { + ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed + } else { + ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed + } + } + break; case JSButton::button_function_t::k_servo_3_max: case JSButton::button_function_t::k_servo_3_max_momentary: { @@ -569,6 +599,16 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed } break; + case JSButton::button_function_t::k_servo_3_max_toggle: + if(!held) { + SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed + if(chan->get_output_pwm() != chan->get_output_max()) { + ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed + } else { + ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed + } + } + break; case JSButton::button_function_t::k_servo_3_center: { SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed diff --git a/ArduSub/mode.cpp b/ArduSub/mode.cpp index 29d314d72af47b..cb3b10c53c1f88 100644 --- a/ArduSub/mode.cpp +++ b/ArduSub/mode.cpp @@ -112,7 +112,7 @@ bool Sub::set_mode(Mode::Number mode, ModeReason reason) // perform any cleanup required by previous flight mode exit_mode(flightmode, new_flightmode); - // store previous flight mode (only used by tradeheli's autorotation) + // store previous flight mode prev_control_mode = control_mode; // update flight mode @@ -249,7 +249,7 @@ void Mode::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int1 } // convert earth-frame level rates to body-frame level rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level); // combine earth frame rate corrections with rate requests if (g.acro_trainer == ACRO_TRAINER_LIMITED) { diff --git a/ArduSub/mode.h b/ArduSub/mode.h index 7e584120c23b1a..35780cb9c04d0b 100644 --- a/ArduSub/mode.h +++ b/ArduSub/mode.h @@ -72,6 +72,9 @@ class Mode virtual const char *name() const = 0; virtual const char *name4() const = 0; + // returns a unique number specific to this mode + virtual Mode::Number number() const = 0; + // functions for reporting to GCS virtual bool get_wp(Location &loc) { return false; } virtual int32_t wp_bearing() const { return 0; } @@ -202,6 +205,7 @@ class ModeManual : public Mode const char *name() const override { return "MANUAL"; } const char *name4() const override { return "MANU"; } + Mode::Number number() const override { return Mode::Number::MANUAL; } }; @@ -224,6 +228,7 @@ class ModeAcro : public Mode const char *name() const override { return "ACRO"; } const char *name4() const override { return "ACRO"; } + Mode::Number number() const override { return Mode::Number::ACRO; } }; @@ -246,6 +251,7 @@ class ModeStabilize : public Mode const char *name() const override { return "STABILIZE"; } const char *name4() const override { return "STAB"; } + Mode::Number number() const override { return Mode::Number::STABILIZE; } }; @@ -272,6 +278,7 @@ class ModeAlthold : public Mode const char *name() const override { return "ALT_HOLD"; } const char *name4() const override { return "ALTH"; } + Mode::Number number() const override { return Mode::Number::ALT_HOLD; } }; @@ -293,6 +300,7 @@ class ModeSurftrak : public ModeAlthold const char *name() const override { return "SURFTRAK"; } const char *name4() const override { return "STRK"; } + Mode::Number number() const override { return Mode::Number::SURFTRAK; } private: @@ -320,6 +328,7 @@ class ModeGuided : public Mode bool has_manual_throttle() const override { return false; } bool allows_arming(bool from_gcs) const override { return true; } bool is_autopilot() const override { return true; } + bool in_guided_mode() const override { return true; } bool guided_limit_check(); void guided_limit_init_time_and_pos(); void guided_set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads); @@ -341,6 +350,8 @@ class ModeGuided : public Mode const char *name() const override { return "GUIDED"; } const char *name4() const override { return "GUID"; } + Mode::Number number() const override { return Mode::Number::GUIDED; } + autopilot_yaw_mode get_default_auto_yaw_mode(bool rtl) const; private: @@ -386,6 +397,7 @@ class ModeAuto : public ModeGuided const char *name() const override { return "AUTO"; } const char *name4() const override { return "AUTO"; } + Mode::Number number() const override { return Mode::Number::AUTO; } private: void auto_wp_run(); @@ -416,6 +428,7 @@ class ModePoshold : public ModeAlthold const char *name() const override { return "POSHOLD"; } const char *name4() const override { return "POSH"; } + Mode::Number number() const override { return Mode::Number::POSHOLD; } }; @@ -438,6 +451,7 @@ class ModeCircle : public Mode const char *name() const override { return "CIRCLE"; } const char *name4() const override { return "CIRC"; } + Mode::Number number() const override { return Mode::Number::CIRCLE; } }; class ModeSurface : public Mode @@ -459,6 +473,7 @@ class ModeSurface : public Mode const char *name() const override { return "SURFACE"; } const char *name4() const override { return "SURF"; } + Mode::Number number() const override { return Mode::Number::CIRCLE; } }; @@ -472,7 +487,7 @@ class ModeMotordetect : public Mode virtual void run() override; bool init(bool ignore_checks) override; - bool requires_GPS() const override { return true; } + bool requires_GPS() const override { return false; } bool has_manual_throttle() const override { return false; } bool allows_arming(bool from_gcs) const override { return true; } bool is_autopilot() const override { return true; } @@ -481,4 +496,5 @@ class ModeMotordetect : public Mode const char *name() const override { return "MOTORDETECT"; } const char *name4() const override { return "DETE"; } + Mode::Number number() const override { return Mode::Number::MOTOR_DETECT; } }; diff --git a/ArduSub/mode_acro.cpp b/ArduSub/mode_acro.cpp index 29b1e61891667c..534066938a2ab7 100644 --- a/ArduSub/mode_acro.cpp +++ b/ArduSub/mode_acro.cpp @@ -7,7 +7,7 @@ bool ModeAcro::init(bool ignore_checks) { // set target altitude to zero for reporting - position_control->set_pos_target_z_cm(0); + position_control->set_pos_desired_z_cm(0); // attitude hold inputs become thrust inputs in acro mode // set to neutral to prevent chaotic behavior (esp. roll/pitch) diff --git a/ArduSub/mode_althold.cpp b/ArduSub/mode_althold.cpp index cf5b2a952f508c..4af9c04bf64768 100644 --- a/ArduSub/mode_althold.cpp +++ b/ArduSub/mode_althold.cpp @@ -111,9 +111,9 @@ void ModeAlthold::control_depth() { //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 (sub.ap.at_surface) { - position_control->set_pos_target_z_cm(MIN(position_control->get_pos_target_z_cm(), g.surface_depth - 5.0f)); // set target to 5 cm below surface level + position_control->set_pos_desired_z_cm(MIN(position_control->get_pos_desired_z_cm(), g.surface_depth - 5.0f)); // set target to 5 cm below surface level } else if (sub.ap.at_bottom) { - position_control->set_pos_target_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_target_z_cm())); // set target to 10 cm above bottom + position_control->set_pos_desired_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_z_cm())); // set target to 10 cm above bottom } } diff --git a/ArduSub/mode_auto.cpp b/ArduSub/mode_auto.cpp index 57e086118982e4..67f9e4d78264db 100644 --- a/ArduSub/mode_auto.cpp +++ b/ArduSub/mode_auto.cpp @@ -50,7 +50,7 @@ void ModeAuto::run() break; case Auto_NavGuided: -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED auto_nav_guided_run(); #endif break; @@ -187,8 +187,8 @@ void ModeAuto::auto_circle_movetoedge_start(const Location &circle_center, float // check our distance from edge of circle Vector3f circle_edge_neu; - sub.circle_nav.get_closest_point_on_circle(circle_edge_neu); - float dist_to_edge = (inertial_nav.get_position_neu_cm() - circle_edge_neu).length(); + float dist_to_edge; + sub.circle_nav.get_closest_point_on_circle(circle_edge_neu, dist_to_edge); // if more than 3m then fly to edge if (dist_to_edge > 300.0f) { @@ -252,7 +252,7 @@ void ModeAuto::auto_circle_run() attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), sub.circle_nav.get_yaw(), true); } -#if NAV_GUIDED == ENABLED +#if NAV_GUIDED // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode void ModeAuto::auto_nav_guided_start() { @@ -426,6 +426,7 @@ void ModeAuto::set_auto_yaw_roi(const Location &roi_location) // Return true if it is possible to recover from a rangefinder failure bool ModeAuto::auto_terrain_recover_start() { +#if AP_RANGEFINDER_ENABLED // Check rangefinder status to see if recovery is possible switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) { @@ -462,6 +463,9 @@ bool ModeAuto::auto_terrain_recover_start() gcs().send_text(MAV_SEVERITY_WARNING, "Attempting auto failsafe recovery"); return true; +#else + return false; +#endif } // Attempt recovery from terrain failsafe @@ -470,7 +474,6 @@ bool ModeAuto::auto_terrain_recover_start() void ModeAuto::auto_terrain_recover_run() { float target_climb_rate = 0; - static uint32_t rangefinder_recovery_ms = 0; // if not armed set throttle to zero and exit immediately if (!motors.armed()) { @@ -483,6 +486,8 @@ void ModeAuto::auto_terrain_recover_run() return; } +#if AP_RANGEFINDER_ENABLED + static uint32_t rangefinder_recovery_ms = 0; switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) { case RangeFinder::Status::OutOfRangeLow: @@ -529,6 +534,10 @@ void ModeAuto::auto_terrain_recover_run() rangefinder_recovery_ms = 0; return; } +#else + gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!"); + sub.failsafe_terrain_act(); +#endif // exit on failure (timeout) if (AP_HAL::millis() > sub.fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS) { diff --git a/ArduSub/mode_guided.cpp b/ArduSub/mode_guided.cpp index ff1bb07df5681a..64dbcb0f83a9c0 100644 --- a/ArduSub/mode_guided.cpp +++ b/ArduSub/mode_guided.cpp @@ -93,6 +93,7 @@ void ModeGuided::guided_pos_control_start() sub.wp_nav.set_wp_destination(stopping_point, false); // initialise yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(get_default_auto_yaw_mode(false)); } @@ -111,6 +112,7 @@ void ModeGuided::guided_vel_control_start() position_control->init_xy_controller(); // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); } @@ -129,6 +131,7 @@ void ModeGuided::guided_posvel_control_start() position_control->init_xy_controller(); // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); } @@ -153,6 +156,7 @@ void ModeGuided::guided_angle_control_start() guided_angle_state.climb_rate_cms = 0.0f; // pilot always controls yaw + sub.yaw_rate_only = false; set_auto_yaw_mode(AUTO_YAW_HOLD); } @@ -161,11 +165,6 @@ void ModeGuided::guided_angle_control_start() // else return false if the waypoint is outside the fence bool ModeGuided::guided_set_destination(const Vector3f& destination) { - // ensure we are in position control mode - if (sub.guided_mode != Guided_WP) { - guided_pos_control_start(); - } - #if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); @@ -176,6 +175,11 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination) } #endif + // ensure we are in position control mode + if (sub.guided_mode != Guided_WP) { + guided_pos_control_start(); + } + // no need to check return status because terrain data is not used sub.wp_nav.set_wp_destination(destination, false); @@ -192,11 +196,6 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination) // or if the fence is enabled and guided waypoint is outside the fence bool ModeGuided::guided_set_destination(const Location& dest_loc) { - // ensure we are in position control mode - if (sub.guided_mode != Guided_WP) { - guided_pos_control_start(); - } - #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 @@ -207,6 +206,11 @@ bool ModeGuided::guided_set_destination(const Location& dest_loc) } #endif + // ensure we are in position control mode + if (sub.guided_mode != Guided_WP) { + guided_pos_control_start(); + } + if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) { // failure to set destination can only be because of missing terrain data LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); @@ -227,11 +231,6 @@ bool ModeGuided::guided_set_destination(const Location& dest_loc) // else return false if the waypoint is outside the fence bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { - // ensure we are in position control mode - if (sub.guided_mode != Guided_WP) { - guided_pos_control_start(); - } - #if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); @@ -242,6 +241,11 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_ya } #endif + // ensure we are in position control mode + if (sub.guided_mode != Guided_WP) { + guided_pos_control_start(); + } + // set yaw state guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); @@ -293,11 +297,6 @@ void ModeGuided::guided_set_velocity(const Vector3f& velocity, bool use_yaw, flo // set guided mode posvel target bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity) { - // check we are in velocity control mode - if (sub.guided_mode != Guided_PosVel) { - guided_posvel_control_start(); - } - #if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); @@ -308,6 +307,11 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons } #endif + // check we are in posvel control mode + if (sub.guided_mode != Guided_PosVel) { + guided_posvel_control_start(); + } + update_time_ms = AP_HAL::millis(); posvel_pos_target_cm = destination.topostype(); posvel_vel_target_cms = velocity; @@ -328,11 +332,6 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons // set guided mode posvel target bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { - // check we are in velocity control mode - if (sub.guided_mode != Guided_PosVel) { - guided_posvel_control_start(); - } - #if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); @@ -343,6 +342,11 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons } #endif + // check we are in posvel control mode + if (sub.guided_mode != Guided_PosVel) { + guided_posvel_control_start(); + } + // set yaw state guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); @@ -367,7 +371,7 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons // set guided mode angle target void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms) { - // check we are in velocity control mode + // check we are in angle control mode if (sub.guided_mode != Guided_Angle) { guided_angle_control_start(); } @@ -807,7 +811,7 @@ float ModeGuided::get_auto_heading() float track_bearing = get_bearing_cd(sub.wp_nav.get_wp_origin().xy(), sub.wp_nav.get_wp_destination().xy()); // Bearing from current position towards intermediate position target (centidegrees) - const Vector2f target_vel_xy{position_control->get_vel_target_cms().x, position_control->get_vel_target_cms().y}; + const Vector2f target_vel_xy = position_control->get_vel_target_cms().xy(); float angle_error = 0.0f; if (target_vel_xy.length() >= position_control->get_max_speed_xy_cms() * 0.1f) { const float desired_angle_cd = degrees(target_vel_xy.angle()) * 100.0f; diff --git a/ArduSub/mode_manual.cpp b/ArduSub/mode_manual.cpp index 9d6e29892ea91a..6bbb92eef617a6 100644 --- a/ArduSub/mode_manual.cpp +++ b/ArduSub/mode_manual.cpp @@ -3,7 +3,7 @@ bool ModeManual::init(bool ignore_checks) { // set target altitude to zero for reporting - position_control->set_pos_target_z_cm(0); + position_control->set_pos_desired_z_cm(0); // attitude hold inputs become thrust inputs in manual mode // set to neutral to prevent chaotic behavior (esp. roll/pitch) diff --git a/ArduSub/mode_poshold.cpp b/ArduSub/mode_poshold.cpp index a5cb3d9bfd050d..479cdcb5435b6a 100644 --- a/ArduSub/mode_poshold.cpp +++ b/ArduSub/mode_poshold.cpp @@ -4,7 +4,7 @@ #include "Sub.h" -#if POSHOLD_ENABLED == ENABLED +#if POSHOLD_ENABLED // poshold_init - initialise PosHold controller bool ModePoshold::init(bool ignore_checks) @@ -111,4 +111,4 @@ void ModePoshold::run() // Update z axis // control_depth(); } -#endif // POSHOLD_ENABLED == ENABLED +#endif // POSHOLD_ENABLED diff --git a/ArduSub/mode_stabilize.cpp b/ArduSub/mode_stabilize.cpp index 52620b8d5d0b6a..51f9ef4732bcfd 100644 --- a/ArduSub/mode_stabilize.cpp +++ b/ArduSub/mode_stabilize.cpp @@ -3,7 +3,7 @@ bool ModeStabilize::init(bool ignore_checks) { // set target altitude to zero for reporting - position_control->set_pos_target_z_cm(0); + position_control->set_pos_desired_z_cm(0); sub.last_pilot_heading = ahrs.yaw_sensor; return true; diff --git a/ArduSub/mode_surftrak.cpp b/ArduSub/mode_surftrak.cpp index 23f90271c5b9bb..f119e02a8981f8 100644 --- a/ArduSub/mode_surftrak.cpp +++ b/ArduSub/mode_surftrak.cpp @@ -39,8 +39,10 @@ bool ModeSurftrak::init(bool ignore_checks) if (!sub.rangefinder_alt_ok()) { sub.gcs().send_text(MAV_SEVERITY_INFO, "waiting for a rangefinder reading"); +#if AP_RANGEFINDER_ENABLED } else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) { sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to hold range", sub.g.surftrak_depth * 0.01f); +#endif } return true; @@ -60,6 +62,7 @@ bool ModeSurftrak::set_rangefinder_target_cm(float target_cm) { bool success = false; +#if AP_RANGEFINDER_ENABLED if (sub.control_mode != Number::SURFTRAK) { sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set"); } else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) { @@ -78,12 +81,12 @@ bool ModeSurftrak::set_rangefinder_target_cm(float target_cm) // Initialize the terrain offset auto terrain_offset_cm = sub.inertial_nav.get_position_z_up_cm() - rangefinder_target_cm; - sub.pos_control.set_pos_offset_z_cm(terrain_offset_cm); - sub.pos_control.set_pos_offset_target_z_cm(terrain_offset_cm); + sub.pos_control.init_pos_terrain_cm(terrain_offset_cm); } else { reset(); } +#endif return success; } @@ -93,8 +96,7 @@ void ModeSurftrak::reset() rangefinder_target_cm = INVALID_TARGET; // Reset the terrain offset - sub.pos_control.set_pos_offset_z_cm(0); - sub.pos_control.set_pos_offset_target_z_cm(0); + sub.pos_control.init_pos_terrain_cm(0); } /* @@ -113,11 +115,11 @@ void ModeSurftrak::control_range() { } if (sub.ap.at_surface) { // Set target depth to 5 cm below SURFACE_DEPTH and reset - position_control->set_pos_target_z_cm(MIN(position_control->get_pos_target_z_cm(), g.surface_depth - 5.0f)); + position_control->set_pos_desired_z_cm(MIN(position_control->get_pos_desired_z_cm(), g.surface_depth - 5.0f)); reset(); } else if (sub.ap.at_bottom) { // Set target depth to 10 cm above bottom and reset - position_control->set_pos_target_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_target_z_cm())); + position_control->set_pos_desired_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_z_cm())); reset(); } else { // Typical operation @@ -141,6 +143,7 @@ void ModeSurftrak::control_range() { */ void ModeSurftrak::update_surface_offset() { +#if AP_RANGEFINDER_ENABLED if (sub.rangefinder_alt_ok()) { // Get the latest terrain offset float rangefinder_terrain_offset_cm = sub.rangefinder_state.rangefinder_terrain_offset_cm; @@ -159,7 +162,8 @@ void ModeSurftrak::update_surface_offset() } // Set the offset target, AC_PosControl will do the rest - sub.pos_control.set_pos_offset_target_z_cm(rangefinder_terrain_offset_cm); + sub.pos_control.set_pos_terrain_target_cm(rangefinder_terrain_offset_cm); } } +#endif // AP_RANGEFINDER_ENABLED } diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 895ade8c8c53b5..504c6651d933bd 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -18,7 +18,12 @@ void Sub::motors_output() verify_motor_test(); } else { motors.set_interlock(true); + auto &srv = AP::srv(); + srv.cork(); + SRV_Channels::calc_pwm(); + SRV_Channels::output_ch_all(); motors.output(); + srv.push(); } } diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index a8cb75c7fd9212..f918e81a71f516 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -17,7 +17,7 @@ void Sub::read_barometer() void Sub::init_rangefinder() { -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED rangefinder.set_log_rfnd_bit(MASK_LOG_CTUN); rangefinder.init(ROTATION_PITCH_270); rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ); @@ -28,7 +28,7 @@ void Sub::init_rangefinder() // return rangefinder altitude in centimeters void Sub::read_rangefinder() { -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED rangefinder.update(); // signal quality ranges from 0 (worst) to 100 (perfect), -1 means n/a @@ -41,7 +41,7 @@ void Sub::read_rangefinder() int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270); -#if RANGEFINDER_TILT_CORRECTION == ENABLED +#if RANGEFINDER_TILT_CORRECTION // correct alt for angle of the rangefinder temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z); #endif diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index a41524e7e64316..72803e6d47637f 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -129,7 +129,7 @@ void Sub::init_ardupilot() last_pilot_heading = ahrs.yaw_sensor; // initialise rangefinder -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED init_rangefinder(); #endif @@ -140,6 +140,9 @@ void Sub::init_ardupilot() // initialise mission library mission.init(); +#if HAL_LOGGING_ENABLED + mission.set_log_start_mission_item_bit(MASK_LOG_CMD); +#endif // initialise AP_Logger library #if HAL_LOGGING_ENABLED @@ -166,6 +169,7 @@ void Sub::startup_INS_ground() // initialise ahrs (may push imu calibration into the mpu6000 if using that device). ahrs.init(); ahrs.set_vehicle_class(AP_AHRS::VehicleClass::SUBMARINE); + ahrs.set_fly_forward(false); // Warm up and calibrate gyro offsets ins.init(scheduler.get_loop_rate_hz()); diff --git a/ArduSub/terrain.cpp b/ArduSub/terrain.cpp index 50249ade7b3322..217728b8e87842 100644 --- a/ArduSub/terrain.cpp +++ b/ArduSub/terrain.cpp @@ -8,7 +8,7 @@ void Sub::terrain_update() // tell the rangefinder our height, so it can go into power saving // mode if available -#if RANGEFINDER_ENABLED == ENABLED +#if AP_RANGEFINDER_ENABLED float height; if (terrain.height_above_terrain(height, true)) { rangefinder.set_estimated_terrain_height(height); diff --git a/ArduSub/wscript b/ArduSub/wscript index 11361fbadce0de..ab0b8ce25da6d9 100644 --- a/ArduSub/wscript +++ b/ArduSub/wscript @@ -14,10 +14,7 @@ def build(bld): 'AP_JSButton', 'AP_LeakDetector', 'AP_Motors', - 'AP_RCMapper', - 'AP_Beacon', 'AP_TemperatureSensor', - 'AP_Arming', ], ) diff --git a/BUILD.md b/BUILD.md index 5e11d2c83808ee..4a221bef832f16 100644 --- a/BUILD.md +++ b/BUILD.md @@ -191,6 +191,27 @@ list some basic and more used commands as example. Also, take a look on the [Advanced section](#advanced-usage) below. +### Using Docker ### + +A docker environment is provided which may be helpful for building in a clean +environment and avoiding modification of the host environment. + +To build the docker image (should only need to be done once), run: + +```bash +docker build --rm -t ardupilot-dev . +``` + +To build inside the container, prefix your `waf` commands, e.g.: + +```bash +docker run --rm -it -v $PWD:/ardupilot ardupilot-dev ./waf configure --board=sitl +docker run --rm -it -v $PWD:/ardupilot ardupilot-dev ./waf copter +``` + +Alternatively, simply run `docker run --rm -it -v $PWD:/ardupilot ardupilot-dev` to +start a `bash` shell in which you can run other commands from this document. + ## Advanced usage ## This section contains some explanations on how the Waf build system works diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index b4e50b2e6e0bf3..8ae8c0b704aa39 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -75,7 +75,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { #if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27), #endif - SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30), #if HAL_LOGGING_ENABLED SCHED_TASK(full_rate_logging, 50, 50, 33), #endif @@ -166,9 +165,11 @@ void Blimp::ten_hz_logging_loop() } if (should_log(MASK_LOG_RCIN)) { logger.Write_RCIN(); +#if AP_RSSI_ENABLED if (rssi.enabled()) { logger.Write_RSSI(); } +#endif } if (should_log(MASK_LOG_RCOUT)) { logger.Write_RCOUT(); @@ -209,7 +210,7 @@ void Blimp::one_hz_loop() #endif // update assigned functions and enable auxiliary servos - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); AP_Notify::flags.flying = !ap.land_complete; diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 086f17f44a552c..aa4d2e449d3cc4 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -168,7 +168,6 @@ class Blimp : public AP_Vehicle // There are multiple states defined such as STABILIZE, ACRO, Mode::Number control_mode; ModeReason control_mode_reason = ModeReason::UNKNOWN; - Mode::Number prev_control_mode; RCMapper rcmap; diff --git a/Blimp/GCS_Blimp.h b/Blimp/GCS_Blimp.h index 830e0abc209431..315d1224984638 100644 --- a/Blimp/GCS_Blimp.h +++ b/Blimp/GCS_Blimp.h @@ -41,7 +41,7 @@ class GCS_Blimp : public GCS GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Blimp(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Blimp(params, uart); } }; diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index ff52827562b4af..1eb5985e81a1cc 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -40,6 +40,9 @@ MAV_STATE GCS_MAVLINK_Blimp::vehicle_system_status() const if (blimp.ap.land_complete) { return MAV_STATE_STANDBY; } + if (!blimp.ap.initialised) { + return MAV_STATE_BOOT; + } return MAV_STATE_ACTIVE; } @@ -215,7 +218,7 @@ bool GCS_MAVLINK_Blimp::try_send_message(enum ap_message id) const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station + // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3, AIRSPEED and SENSOR_OFFSETS to ground station // @Units: Hz // @Range: 0 10 // @Increment: 1 @@ -285,7 +288,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate to ground station - // @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station + // @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, 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 @@ -312,6 +315,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -321,10 +327,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, // MISSION_CURRENT +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif MSG_NAV_CONTROLLER_OUTPUT, @@ -340,7 +352,9 @@ static const ap_message STREAM_POSITION_msgs[] = { static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_SERVO_OUTPUT_RAW, MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -387,7 +401,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; static const ap_message STREAM_ADSB_msgs[] = { MSG_ADSB_VEHICLE, @@ -600,3 +615,41 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2; } #endif // HAL_HIGH_LATENCY2_ENABLED + +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Blimp::send_available_mode(uint8_t index) const +{ + const Mode* modes[] { + &blimp.mode_land, + &blimp.mode_manual, + &blimp.mode_velocity, + &blimp.mode_loiter, + &blimp.mode_rtl, + }; + + const uint8_t mode_count = ARRAY_SIZE(modes); + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name = modes[index_zero]->name(); + const uint8_t mode_number = (uint8_t)modes[index_zero]->number(); + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/Blimp/GCS_Mavlink.h b/Blimp/GCS_Mavlink.h index 35276b03a46d5c..90c4881b2adf49 100644 --- a/Blimp/GCS_Mavlink.h +++ b/Blimp/GCS_Mavlink.h @@ -48,6 +48,10 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK uint32_t log_radio_bit() const override { return MASK_LOG_PM; } #endif + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: void handle_message(const mavlink_message_t &msg) override; diff --git a/Blimp/Loiter.cpp b/Blimp/Loiter.cpp index 2553e6d3e7c65e..7385edfb922075 100644 --- a/Blimp/Loiter.cpp +++ b/Blimp/Loiter.cpp @@ -125,9 +125,9 @@ void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled } #if HAL_LOGGING_ENABLED - AC_PosControl::Write_PSCN(target_pos.x * 100.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); - AC_PosControl::Write_PSCE(target_pos.y * 100.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); - AC_PosControl::Write_PSCD(-target_pos.z * 100.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCN(0.0, target_pos.x * 100.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCE(0.0, target_pos.y * 100.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCD(0.0, -target_pos.z * 100.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); #endif } @@ -203,8 +203,8 @@ void Loiter::run_vel(Vector3f& target_vel_ef, float& target_vel_yaw, Vector4b ax } #if HAL_LOGGING_ENABLED - AC_PosControl::Write_PSCN(0.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); - AC_PosControl::Write_PSCE(0.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); - AC_PosControl::Write_PSCD(0.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCN(0.0, 0.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCE(0.0, 0.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); + AC_PosControl::Write_PSCD(0.0, 0.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); #endif } diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index a879805314d633..7a1d34c239f36b 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -57,7 +57,6 @@ const AP_Param::Info Blimp::var_info[] = { // @DisplayName: Throttle stick behavior // @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick. // @User: Standard - // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0), @@ -76,7 +75,6 @@ const AP_Param::Info Blimp::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:VELX,2:VELY,4:VELZ,8:VELYAW,16:POSX,32:POSY,64:POSZ,128:POSYAW,15:Vel only,51:XY only,204:ZYaw only,240:Pos only,255:All // @Bitmask: 0:VELX,1:VELY,2:VELZ,3:VELYAW,4:POSX,5:POSY,6:POZ,7:POSYAW GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), @@ -262,7 +260,6 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: DIS_MASK // @DisplayName: Disable output mask // @Description: Mask for disabling (setting to zero) one or more of the 4 output axis in mode Velocity or Loiter - // @Values: 0:All enabled,1:Right,2:Front,4:Down,8:Yaw,3:Down and Yaw only,12:Front & Right only // @Bitmask: 0:Right,1:Front,2:Down,3:Yaw // @User: Standard GSCALAR(dis_mask, "DIS_MASK", 0), @@ -385,9 +382,11 @@ const AP_Param::Info Blimp::var_info[] = { GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), #endif +#if AP_RSSI_ENABLED // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), +#endif // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp @@ -810,7 +809,6 @@ 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, 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), diff --git a/Blimp/RC_Channel.cpp b/Blimp/RC_Channel.cpp index 8742d3e347953e..1132d82330b14e 100644 --- a/Blimp/RC_Channel.cpp +++ b/Blimp/RC_Channel.cpp @@ -79,7 +79,7 @@ void RC_Channel_Blimp::do_aux_function_change_mode(const Mode::Number mode, switch (ch_flag) { case AuxSwitchPos::HIGH: { // engage mode (if not possible we remain in current flight mode) - const bool success = blimp.set_mode(mode, ModeReason::RC_COMMAND); + const bool success = blimp.set_mode(mode, ModeReason::AUX_FUNCTION); if (blimp.ap.initialised) { if (success) { AP_Notify::events.user_mode_change = 1; diff --git a/Blimp/defines.h b/Blimp/defines.h index 0a73072a1aea5f..619547d2fda0f1 100644 --- a/Blimp/defines.h +++ b/Blimp/defines.h @@ -2,14 +2,6 @@ #include -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - // bit options for DEV_OPTIONS parameter enum DevOptions { DevOptionADSBMAVLink = 1, diff --git a/Blimp/mode.cpp b/Blimp/mode.cpp index 849b4af27568d1..dd7299d4cf29d5 100644 --- a/Blimp/mode.cpp +++ b/Blimp/mode.cpp @@ -102,9 +102,6 @@ bool Blimp::set_mode(Mode::Number mode, ModeReason reason) // perform any cleanup required by previous flight mode exit_mode(flightmode, new_flightmode); - // store previous flight mode (only used by tradeheli's autorotation) - prev_control_mode = control_mode; - // update flight mode flightmode = new_flightmode; control_mode = mode; diff --git a/Blimp/mode.h b/Blimp/mode.h index 8a990fbb31b30c..8718d47fa144e5 100644 --- a/Blimp/mode.h +++ b/Blimp/mode.h @@ -52,6 +52,9 @@ class Mode virtual const char *name() const = 0; virtual const char *name4() const = 0; + // returns a unique number specific to this mode + virtual Mode::Number number() const = 0; + virtual bool is_landing() const { return false; @@ -159,6 +162,8 @@ class ModeManual : public Mode return "MANU"; } + Mode::Number number() const override { return Mode::Number::MANUAL; } + private: }; @@ -201,6 +206,8 @@ class ModeVelocity : public Mode return "VELY"; } + Mode::Number number() const override { return Mode::Number::VELOCITY; } + private: }; @@ -244,6 +251,8 @@ class ModeLoiter : public Mode return "LOIT"; } + Mode::Number number() const override { return Mode::Number::LOITER; } + private: Vector3f target_pos; float target_yaw; @@ -286,6 +295,8 @@ class ModeLand : public Mode return "LAND"; } + Mode::Number number() const override { return Mode::Number::LAND; } + private: }; @@ -328,4 +339,7 @@ class ModeRTL : public Mode { return "RTL"; } + + Mode::Number number() const override { return Mode::Number::RTL; } + }; diff --git a/Blimp/motors.cpp b/Blimp/motors.cpp index 35ba08b90cce93..90fb3308a925bf 100644 --- a/Blimp/motors.cpp +++ b/Blimp/motors.cpp @@ -78,8 +78,10 @@ void Blimp::motors_output() // output any servo channels SRV_Channels::calc_pwm(); + auto &srv = AP::srv(); + // cork now, so that all channel outputs happen at once - SRV_Channels::cork(); + srv.cork(); // update output on any aux channels, for manual passthru SRV_Channels::output_ch_all(); @@ -88,5 +90,5 @@ void Blimp::motors_output() motors->output(); // push all channels - SRV_Channels::push(); -} \ No newline at end of file + srv.push(); +} diff --git a/Blimp/radio.cpp b/Blimp/radio.cpp index fddce3e914dd21..47212c501272cf 100644 --- a/Blimp/radio.cpp +++ b/Blimp/radio.cpp @@ -15,10 +15,11 @@ void Blimp::default_dead_zones() void Blimp::init_rc_in() { - channel_right = rc().channel(rcmap.roll()-1); - channel_front = rc().channel(rcmap.pitch()-1); - channel_up = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + // the library gaurantees that these are non-nullptr: + channel_right = &rc().get_roll_channel(); + channel_front = &rc().get_pitch_channel(); + channel_up = &rc().get_throttle_channel(); + channel_yaw = &rc().get_yaw_channel(); // set rc channel ranges channel_right->set_angle(RC_SCALE); @@ -37,7 +38,7 @@ void Blimp::init_rc_in() void Blimp::init_rc_out() { // enable aux servos to cope with multiple output channels per motor - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // refresh auxiliary channel to function map SRV_Channels::update_aux_servo_function(); diff --git a/Blimp/system.cpp b/Blimp/system.cpp index 7370ebbcad865a..9c1df237c82659 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -21,8 +21,10 @@ void Blimp::init_ardupilot() // initialise battery monitor battery.init(); +#if AP_RSSI_ENABLED // Init RSSI rssi.init(); +#endif barometer.init(); @@ -33,7 +35,7 @@ void Blimp::init_ardupilot() // allocate the motors class allocate_motors(); - loiter = new Loiter(blimp.scheduler.get_loop_rate_hz()); + loiter = NEW_NOTHROW Loiter(blimp.scheduler.get_loop_rate_hz()); // initialise rc channels including setting mode rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); @@ -240,7 +242,7 @@ void Blimp::allocate_motors(void) switch ((Fins::motor_frame_class)g2.frame_class.get()) { case Fins::MOTOR_FRAME_AIRFISH: default: - motors = new Fins(blimp.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW Fins(blimp.scheduler.get_loop_rate_hz()); break; } if (motors == nullptr) { diff --git a/Blimp/version.h b/Blimp/version.h index f60d3c197858dd..b52a011aaa6c90 100644 --- a/Blimp/version.h +++ b/Blimp/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "Blimp V4.5.0-dev" +#define THISFIRMWARE "Blimp V4.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,5,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 5 +#define FW_MINOR 7 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/Blimp/wscript b/Blimp/wscript index 664dd1aeb4dbd2..2314b7504443f0 100644 --- a/Blimp/wscript +++ b/Blimp/wscript @@ -9,13 +9,10 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AC_InputManager', 'AP_InertialNav', - 'AP_RCMapper', 'AP_Avoidance', - 'AP_Arming', 'AP_LTM_Telem', 'AP_Devo_Telem', 'AP_KDECAN', - 'AP_Beacon', 'AP_AdvancedFailsafe', # TODO for some reason compiling GCS_Common.cpp (in libraries) fails if this isn't included. 'AC_AttitudeControl', # for PSCx logging ], diff --git a/Dockerfile b/Dockerfile index fd24eaff53574c..dba07249d65e8c 100644 --- a/Dockerfile +++ b/Dockerfile @@ -7,10 +7,11 @@ ARG DEBIAN_FRONTEND=noninteractive ARG USER_NAME=ardupilot ARG USER_UID=1000 ARG USER_GID=1000 -ARG SKIP_AP_EXT_ENV=1 +ARG SKIP_AP_EXT_ENV=0 ARG SKIP_AP_GRAPHIC_ENV=1 ARG SKIP_AP_COV_ENV=1 ARG SKIP_AP_GIT_CHECK=1 +ARG DO_AP_STM_ENV=1 RUN groupadd ${USER_NAME} --gid ${USER_GID}\ && useradd -l -m ${USER_NAME} -u ${USER_UID} -g ${USER_GID} -s /bin/bash @@ -19,14 +20,14 @@ RUN apt-get update && apt-get install --no-install-recommends -y \ lsb-release \ sudo \ tzdata \ + git \ + default-jre \ 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=${USER_NAME} - RUN echo "ardupilot ALL=(ALL) NOPASSWD:ALL" > /etc/sudoers.d/${USER_NAME} RUN chmod 0440 /etc/sudoers.d/${USER_NAME} @@ -34,15 +35,25 @@ RUN chown -R ${USER_NAME}:${USER_NAME} /${USER_NAME} USER ${USER_NAME} -ENV SKIP_AP_EXT_ENV=$SKIP_AP_EXT_ENV SKIP_AP_GRAPHIC_ENV=$SKIP_AP_GRAPHIC_ENV SKIP_AP_COV_ENV=$SKIP_AP_COV_ENV SKIP_AP_GIT_CHECK=$SKIP_AP_GIT_CHECK -RUN Tools/environment_install/install-prereqs-ubuntu.sh -y +RUN SKIP_AP_EXT_ENV=$SKIP_AP_EXT_ENV SKIP_AP_GRAPHIC_ENV=$SKIP_AP_GRAPHIC_ENV SKIP_AP_COV_ENV=$SKIP_AP_COV_ENV SKIP_AP_GIT_CHECK=$SKIP_AP_GIT_CHECK \ + DO_AP_STM_ENV=$DO_AP_STM_ENV \ + AP_DOCKER_BUILD=1 \ + USER=${USER_NAME} \ + Tools/environment_install/install-prereqs-ubuntu.sh -y -# add waf alias to ardupilot waf to .ardupilot_env -RUN echo "alias waf=\"/${USER_NAME}/waf\"" >> ~/.ardupilot_env +# Rectify git perms issue that seems to crop up only on OSX +RUN git config --global --add safe.directory $PWD # 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" >> ~/.ardupilot_env +# Clone & install Micro-XRCE-DDS-Gen dependancy +RUN git clone --recurse-submodules https://github.com/ardupilot/Micro-XRCE-DDS-Gen.git /home/${USER_NAME}/Micro-XRCE-DDS-Gen \ + && cd /home/${USER_NAME}/Micro-XRCE-DDS-Gen \ + && ./gradlew assemble \ + && export AP_ENV_LOC="/home/${USER_NAME}/.ardupilot_env" \ + && echo "export PATH=\$PATH:$PWD/scripts" >> $AP_ENV_LOC + # Create entrypoint as docker cannot do shell substitution correctly RUN export ARDUPILOT_ENTRYPOINT="/home/${USER_NAME}/ardupilot_entrypoint.sh" \ && echo "#!/bin/bash" > $ARDUPILOT_ENTRYPOINT \ diff --git a/README.md b/README.md index e015b750ff32b0..67f28a75bc1d59 100644 --- a/README.md +++ b/README.md @@ -96,8 +96,7 @@ for reviewing patches on their specific area. - ***Vehicle***: Rover - [Willian Galvani](https://github.com/williangalvani): - ***Vehicle***: Sub -- [Lucas De Marchi](https://github.com/lucasdemarchi): - - ***Subsystem***: Linux + - ***Board***: Navigator - [Michael du Breuil](https://github.com/WickedShell): - ***Subsystem***: Batteries - ***Subsystem***: GPS diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index aa19de8f41d073..0b8799c3f9c2f8 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -168,12 +168,7 @@ bool AP_Arming_Rover::oa_check(bool report) return true; } - // display failure - if (strlen(failure_msg) == 0) { - check_failed(report, "Check Object Avoidance"); - } else { - check_failed(report, "%s", failure_msg); - } + check_failed(report, "%s", failure_msg); return false; } #endif // AP_OAPATHPLANNER_ENABLED diff --git a/Rover/AP_ExternalControl_Rover.cpp b/Rover/AP_ExternalControl_Rover.cpp index 1c08f92a9b5fdf..d7511f6f0f8326 100644 --- a/Rover/AP_ExternalControl_Rover.cpp +++ b/Rover/AP_ExternalControl_Rover.cpp @@ -29,6 +29,12 @@ bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f & return true; } +bool AP_ExternalControl_Rover::set_global_position(const Location& loc) +{ + // set_target_location only checks if the rover is in guided mode or not + return rover.set_target_location(loc); +} + bool AP_ExternalControl_Rover::ready_for_external_control() { return rover.control_mode->in_guided_mode() && rover.arming.is_armed(); diff --git a/Rover/AP_ExternalControl_Rover.h b/Rover/AP_ExternalControl_Rover.h index 434972833e45dc..e7350ebbe2c62b 100644 --- a/Rover/AP_ExternalControl_Rover.h +++ b/Rover/AP_ExternalControl_Rover.h @@ -7,7 +7,8 @@ #if AP_EXTERNAL_CONTROL_ENABLED -class AP_ExternalControl_Rover : public AP_ExternalControl { +class AP_ExternalControl_Rover : public AP_ExternalControl +{ public: /* Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. @@ -15,6 +16,12 @@ class AP_ExternalControl_Rover : public AP_ExternalControl { Yaw is in earth frame, NED [rad/s]. */ bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)override WARN_IF_UNUSED; + + /* + Sets the global position for loiter point + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; + private: /* Return true if Rover is ready to handle external control data. diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index f38e8f3dd04989..a903e591c6e62c 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -124,11 +124,11 @@ void GCS_MAVLINK_Rover::send_servo_out() { float motor1, motor3; if (rover.g2.motors.have_skid_steering()) { - motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) / 1000.0f); - motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) / 1000.0f); + motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) * 0.001f); + motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) * 0.001f); } else { motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_steering) / 4500.0f); - motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 100.0f); + motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f); } mavlink_msg_rc_channels_scaled_send( chan, @@ -142,7 +142,12 @@ void GCS_MAVLINK_Rover::send_servo_out() 0, 0, 0, - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 +#endif + ); } int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const @@ -416,7 +421,7 @@ void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mav const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3 + // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -524,6 +529,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, +#if AP_AIRSPEED_ENABLED + MSG_AIRSPEED, +#endif }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, @@ -533,10 +541,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { #endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED MSG_GPS_RAW, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED MSG_GPS_RTK, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED MSG_GPS2_RAW, +#endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED MSG_GPS2_RTK, #endif MSG_NAV_CONTROLLER_OUTPUT, @@ -555,7 +569,9 @@ static const ap_message STREAM_RAW_CONTROLLER_msgs[] = { static const ap_message STREAM_RC_CHANNELS_msgs[] = { MSG_SERVO_OUTPUT_RAW, MSG_RC_CHANNELS, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection +#endif }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, @@ -603,7 +619,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif }; static const ap_message STREAM_PARAMS_msgs[] = { - MSG_NEXT_PARAM + MSG_NEXT_PARAM, + MSG_AVAILABLE_MODES }; static const ap_message STREAM_ADSB_msgs[] = { MSG_ADSB_VEHICLE, @@ -694,6 +711,10 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in packet.param4); case MAV_CMD_MISSION_START: + if (!is_zero(packet.param1) || !is_zero(packet.param2)) { + // first-item/last item not supported + return MAV_RESULT_DENIED; + } if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; } @@ -851,10 +872,14 @@ void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_messa } // check for supported coordinate frames - if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED && - packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED && - packet.coordinate_frame != MAV_FRAME_BODY_NED && - packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) { + switch (packet.coordinate_frame) { + case MAV_FRAME_LOCAL_NED: + case MAV_FRAME_LOCAL_OFFSET_NED: + case MAV_FRAME_BODY_NED: + case MAV_FRAME_BODY_OFFSET_NED: + break; + + default: return; } @@ -970,14 +995,19 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess return; } // check for supported coordinate frames - if (packet.coordinate_frame != MAV_FRAME_GLOBAL && - packet.coordinate_frame != MAV_FRAME_GLOBAL_INT && - packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && - packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT && - packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT && - packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) { + switch (packet.coordinate_frame) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_INT: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: + case MAV_FRAME_GLOBAL_TERRAIN_ALT: + case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: + break; + + default: return; } + 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; @@ -1125,3 +1155,54 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const return 0; } #endif // HAL_HIGH_LATENCY2_ENABLED + +// Send the mode with the given index (not mode number!) return the total number of modes +// Index starts at 1 +uint8_t GCS_MAVLINK_Rover::send_available_mode(uint8_t index) const +{ + const Mode* modes[] { + &rover.mode_manual, + &rover.mode_acro, + &rover.mode_steering, + &rover.mode_hold, + &rover.mode_loiter, +#if MODE_FOLLOW_ENABLED + &rover.mode_follow, +#endif + &rover.mode_simple, + &rover.g2.mode_circle, + &rover.mode_auto, + &rover.mode_rtl, + &rover.mode_smartrtl, + &rover.mode_guided, + &rover.mode_initializing, +#if MODE_DOCK_ENABLED + (Mode *)rover.g2.mode_dock_ptr, +#endif + }; + + const uint8_t mode_count = ARRAY_SIZE(modes); + + // Convert to zero indexed + const uint8_t index_zero = index - 1; + if (index_zero >= mode_count) { + // Mode does not exist!? + return mode_count; + } + + // Ask the mode for its name and number + const char* name = modes[index_zero]->name4(); + const uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number(); + + mavlink_msg_available_modes_send( + chan, + mode_count, + index, + MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD, + mode_number, + 0, // MAV_MODE_PROPERTY bitmask + name + ); + + return mode_count; +} diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 2d4ca700a29db8..fd92cac3d5cfa3 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -4,7 +4,7 @@ // set 0 in 4.6, remove feature in 4.7: #ifndef AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED -#define AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED 1 +#define AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED 0 #endif #include "defines.h" @@ -40,6 +40,10 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK uint32_t log_radio_bit() const override { return MASK_LOG_PM; } #endif + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + uint8_t send_available_mode(uint8_t index) const override; + private: void handle_message(const mavlink_message_t &msg) override; diff --git a/Rover/GCS_Rover.cpp b/Rover/GCS_Rover.cpp index 3e72643d14bbe3..0ed6c863f6b9be 100644 --- a/Rover/GCS_Rover.cpp +++ b/Rover/GCS_Rover.cpp @@ -58,17 +58,7 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) } #endif -#if AP_OPTICALFLOW_ENABLED - 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; - } - if (optflow && optflow->healthy()) { - control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; - } -#endif - +#if AP_RANGEFINDER_ENABLED const RangeFinder *rangefinder = RangeFinder::get_singleton(); if (rangefinder && rangefinder->num_sensors() > 0) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; @@ -78,4 +68,5 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } } +#endif } diff --git a/Rover/GCS_Rover.h b/Rover/GCS_Rover.h index acd1dd24260d58..cbd6a9f79ae96c 100644 --- a/Rover/GCS_Rover.h +++ b/Rover/GCS_Rover.h @@ -32,7 +32,7 @@ class GCS_Rover : public GCS GCS_MAVLINK_Rover *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Rover(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Rover(params, uart); } }; diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 99fd471dccee4d..f13ad700add8d5 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -7,8 +7,8 @@ // Write an attitude packet void Rover::Log_Write_Attitude() { - float desired_pitch_cd = degrees(g2.attitude_control.get_desired_pitch()) * 100.0f; - const Vector3f targets(0.0f, desired_pitch_cd, 0.0f); + float desired_pitch = degrees(g2.attitude_control.get_desired_pitch()); + const Vector3f targets(0.0f, desired_pitch, 0.0f); ahrs.Write_Attitude(targets); @@ -24,11 +24,12 @@ void Rover::Log_Write_Attitude() } // log heel to sail control for sailboats - if (rover.g2.sailboat.sail_enabled()) { + if (g2.sailboat.sail_enabled()) { logger.Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info()); } } +#if AP_RANGEFINDER_ENABLED // Write a range finder depth message void Rover::Log_Write_Depth() { @@ -83,6 +84,7 @@ void Rover::Log_Write_Depth() gcs().send_message(MSG_WATER_DEPTH); #endif } +#endif // guided mode logging struct PACKED log_GuidedTarget { @@ -142,13 +144,13 @@ void Rover::Log_Write_Nav_Tuning() void Rover::Log_Write_Sail() { // only log sail if present - if (!rover.g2.sailboat.sail_enabled()) { + if (!g2.sailboat.sail_enabled()) { return; } float wind_dir_tack = logger.quiet_nanf(); uint8_t current_tack = 0; - if (rover.g2.windvane.enabled()) { + if (g2.windvane.enabled()) { wind_dir_tack = degrees(g2.windvane.get_tack_threshold_wind_dir_rad()); current_tack = uint8_t(g2.windvane.get_current_tack()); } @@ -235,9 +237,11 @@ void Rover::Log_Write_RC(void) { logger.Write_RCIN(); logger.Write_RCOUT(); +#if AP_RSSI_ENABLED if (rssi.enabled()) { logger.Write_RSSI(); } +#endif } void Rover::Log_Write_Vehicle_Startup_Messages() diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 79b3c109e659c4..1f2c5dbfce61cb 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -61,7 +61,6 @@ 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,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), @@ -110,7 +109,7 @@ const AP_Param::Info Rover::var_info[] = { // @Param: FS_ACTION // @DisplayName: Failsafe Action // @Description: What to do on a failsafe event - // @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold + // @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold,5:Terminate // @User: Standard GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold), @@ -276,9 +275,11 @@ const AP_Param::Info Rover::var_info[] = { // AP_SerialManager was here +#if AP_RANGEFINDER_ENABLED // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), +#endif // @Group: INS // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -357,9 +358,11 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission), +#if AP_RSSI_ENABLED // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), +#endif // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp @@ -415,7 +418,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover), -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED // @Group: AFS_ // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), @@ -522,7 +525,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FRAME_TYPE // @DisplayName: Frame Type // @Description: Frame Type - // @Values: 0:Undefined,1:Omni3,2:OmniX,3:OmniPlus + // @Values: 0:Undefined,1:Omni3,2:OmniX,3:OmniPlus,4:Omni3Mecanum // @User: Standard // @RebootRequired: True AP_GROUPINFO("FRAME_TYPE", 24, ParametersG2, frame_type, 0), @@ -636,15 +639,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FS_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 AP_GROUPINFO("FS_OPTIONS", 48, ParametersG2, fs_options, 0), #if HAL_TORQEEDO_ENABLED - // @Group: TRQD_ + // @Group: TRQ // @Path: ../libraries/AP_Torqeedo/AP_Torqeedo.cpp - AP_SUBGROUPINFO(torqeedo, "TRQD_", 49, ParametersG2, AP_Torqeedo), + AP_SUBGROUPINFO(torqeedo, "TRQ", 49, ParametersG2, AP_Torqeedo), #endif // @Group: PSC @@ -665,7 +667,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0), -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED // @Group: DOCK // @Path: mode_dock.cpp AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock), @@ -733,22 +735,22 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { ParametersG2::ParametersG2(void) : -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED afs(), #endif #if AP_BEACON_ENABLED beacon(), #endif - motors(wheel_rate_control), wheel_rate_control(wheel_encoder), + motors(wheel_rate_control), attitude_control(), smart_rtl(), -#if MODE_DOCK_ENABLED == ENABLED - mode_dock_ptr(&rover.mode_dock), -#endif #if HAL_PROXIMITY_ENABLED proximity(), #endif +#if MODE_DOCK_ENABLED + mode_dock_ptr(&rover.mode_dock), +#endif #if AP_AVOIDANCE_ENABLED avoid(), #endif @@ -756,9 +758,9 @@ ParametersG2::ParametersG2(void) follow(), #endif windvane(), - pos_control(attitude_control), wp_nav(attitude_control, pos_control), - sailboat() + sailboat(), + pos_control(attitude_control) { AP_Param::setup_object_defaults(this, var_info); } @@ -814,6 +816,13 @@ const AP_Param::ConversionInfo conversion_table[] = { { 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" }, + { Parameters::k_param_g2, 113, AP_PARAM_INT8, "TRQ1_TYPE" }, + { Parameters::k_param_g2, 177, AP_PARAM_INT8, "TRQ1_ONOFF_PIN" }, + { Parameters::k_param_g2, 241, AP_PARAM_INT8, "TRQ1_DE_PIN" }, + { Parameters::k_param_g2, 305, AP_PARAM_INT16, "TRQ1_OPTIONS" }, + { Parameters::k_param_g2, 369, AP_PARAM_INT8, "TRQ1_POWER" }, + { Parameters::k_param_g2, 433, AP_PARAM_FLOAT, "TRQ1_SLEW_TIME" }, + { Parameters::k_param_g2, 497, AP_PARAM_FLOAT, "TRQ1_DIR_DELAY" }, }; diff --git a/Rover/Parameters.h b/Rover/Parameters.h index a7529f246b2e09..d9990c6c416fc6 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -258,7 +258,7 @@ class Parameters { // Throttle // AP_Int8 throttle_cruise; - AP_Int8 pilot_steer_type; + AP_Enum pilot_steer_type; // failsafe control AP_Int8 fs_action; @@ -302,7 +302,7 @@ class ParametersG2 { // control over servo output ranges SRV_Channels servo_channels; -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED // advanced failsafe library AP_AdvancedFailsafe_Rover afs; #endif @@ -341,7 +341,7 @@ class ParametersG2 { AP_Proximity proximity; #endif -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED // we need a pointer to the mode for the G2 table class ModeDock *mode_dock_ptr; #endif @@ -385,8 +385,10 @@ class ParametersG2 { // windvane AP_WindVane windvane; +#if AP_MISSION_ENABLED // mission behave - AP_Int8 mis_done_behave; + AP_Enum mis_done_behave; +#endif // balance both pitch trim AP_Float bal_pitch_trim; diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index eba85331194459..75cd088a757a26 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -86,7 +86,7 @@ void RC_Channel_Rover::do_aux_function_change_mode(Mode &mode, { switch (ch_flag) { case AuxSwitchPos::HIGH: - rover.set_mode(mode, ModeReason::RC_COMMAND); + rover.set_mode(mode, ModeReason::AUX_FUNCTION); break; case AuxSwitchPos::MIDDLE: // do nothing @@ -215,7 +215,7 @@ bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch do_aux_function_change_mode(rover.mode_loiter, ch_flag); break; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED // Set mode to Follow case AUX_FUNC::FOLLOW: do_aux_function_change_mode(rover.mode_follow, ch_flag); diff --git a/Rover/ReleaseNotes.txt b/Rover/ReleaseNotes.txt index 940bcb44de0d14..9722121b97a890 100644 --- a/Rover/ReleaseNotes.txt +++ b/Rover/ReleaseNotes.txt @@ -1,5 +1,614 @@ Rover Release Notes: --------------------- +------------------------------------------------------------------ +Release 4.6.0-beta 13 Nov 2024 + +Changes from 4.5.7 + +1) Board specific changes + +- AnyLeaf H7 supports compass and onboard logging +- Blitz743Pro supports CAN +- BlueRobotics Navigator supports BMP390 baro +- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed) +- CB Unmanned Stamp H743 support +- ClearSky CSKY405 support +- CUAV-7-Nano default batt monitor fixed +- CubeRed bootloader fixes including disabling 2nd core by default +- CubeRed supports PPP networking between primary and secondary MCU +- CubeRedPrimary supports external compasses +- ESP32 main loop rate improvements +- ESP32 RC input fixes and wifi connection reliability improved +- ESP32 safety switch and GPIO pin support +- FlyingMoon no longer support MAX7456 +- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot +- Flywoo H743 Pro support +- Flywoo/Goku F405 HD 1-2S ELRS AIO v2 +- FlywooF745 supports DPS310 baro +- FPV boards lose SMBus battery support (to save flash) +- GEPRC F745BTHD support +- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash) +- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates +- Holybro Kakute F4 Wing support +- iFlight 2RAW H743 supports onboard logging +- JFB110 supports measuring servo rail voltage +- JFB110 supports safety switch LED +- JHEM-JHEF405 bootloader supports firmware updates via serial +- JHEMCU GF30H743 HD support +- JHEMCU-GF16-F405 autopilot support +- JHEMCU-GSF405A becomes FPV board (to save flash) +- KakuteF7 only supports BMP280 baro (to save flash) +- KakuteH7Mini supports ICM42688 IMU +- Linux auto detection of GPS baud rate fixed +- Linux board scheduler jitter reduced +- Linux board shutdown fixes +- MakeFlyEasy PixPilot-V6Pro support +- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash) +- MatekH7A3 support Bi-directional DShot +- MicoAir405v2 and MicoAir405Mini support optical flow and OSD +- MicoAir743 internal compass orientation fixed +- MicroAir405Mini, MicroAir743, NxtPX4v2 support +- MicroAir405v2 Bi-directional DShot and LED DMA fixes +- MicroAir405v2 defined as FPV board with reduced features (to save flash) +- ModalAI VOXL2 support including Starling 2 and Starling 2 max +- mRo Control Zero Classic supports servo rail analog input +- mRo KitCAN revC fixed +- Mugin MUPilot support +- OmnibusF7v2 loses quadplane support (to save flash) +- Pixhack-v3 board added (same as fmuv3) +- Pixhawk6C bootloader supports flashing firmware from SD card +- RadiolinkPIX6 imu orientation fixed +- RadiolinkPIX6 supports SPA06 baro +- ReaperF745 V4 FC supports MPU6000 IMU +- RPI5 support +- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed +- Solo serial ports default to MAVLink1 +- SpeedyBeeF405Wing gets Bi-directional DShot +- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash) +- Spektreworks boom board support +- TrueNavPro-G4 SPI does not share DMA +- X-MAV AP-H743v2 support + +2) AHRS/EKF enhancements and fixes + +- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back) +- AHRS_OPTION to disable innovation check for airspeed sensor +- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity +- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only) +- EK2 supports disabling external nav (see EK2_OPTIONS) +- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1) +- EK3 uses filtered velocity corrections for IMU position +- EKF2, EKF3, ExternalAHRS all use common origin +- EKF3 accepts set origin even when using GPS +- EKF3 allows earth-frame fields to be estimated with an origin but no GPS +- EKF3 copes better with GPS jamming +- EKF3 logs mag fusion selection to XKFS +- EKF3 wind estimation when using GPS-for-yaw fixed +- External AHRS improvements including handling variances, pre-arm origin check +- Inertial Labs External AHRS fixes +- VectorNav driver fix for handling of error from sensor +- VectorNav External AHRS enhancements including validation of config commands and logging improvements +- VectorNav support for sensors outside VN-100 and VN-300 + +3) Driver enhancements and bug fixes + +- ADSB fix to display last character in status text sent to GCS +- Ainstein LR-D1 radar support +- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor +- AIRSPEED message sent to GCS +- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5) +- ARSPD_OPTIONS to report calibration offset to GCS +- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only) +- Baro provides improved atmospheric model for high altitude flight +- BARO_ALT_OFFSET slew slowed to keep EKF happy +- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries +- BATTx_OPTION to not send battery voltage, current, etc to GCS +- Benewake RDS02U radar support +- Bi-directional DShot on IOMCU supports reversible mask +- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs +- BMM350 compass support +- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus) +- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS) +- CRSF baro and vertical speeed fixed +- CRSF RX bind command support +- DroneCAN battery monitor check to avoid memory corruption when type changed +- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info +- DroneCAN EFI health check fix +- DroneCAN ESC battery monitors calculate consumed mah +- DroneCAN ESCs forced to zero when disarmed +- DroneCAN RPM message support +- DroneCAN timeout fix for auxiliary frames +- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600') +- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass +- FuelLevel battery monitor fix to report capacity +- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx +- Hirth EFI logging includes modified throttle +- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter) +- Hott and LTM telemetry deprecated (still available through custom build server) +- i-BUS telemetry support +- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only) +- ICE_START_CHAN replaced with RC aux function (Plane only) +- ICEngine retry max added (see ICE_STRT_MX_RTRY) +- IE 2400 generator error message severity to GCS improved +- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params) +- MCP9600 temperature sensor I2C address fixed +- MLX90614 temperature sensor support +- MSP GPS ground course scaling fixed +- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect) +- Networking supports reconnection to TCP server or client +- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT) +- Relay inverted output support (see RELAYx_INVERTED parameter) +- ROMFS efficiency improvements +- RS-485 driver enable RTS flow control +- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt) +- Septentrio GPS sat count correctly drops to zero when 255 received +- Septentrio supports selecting constellations (see GPS_GNSS_MODE) +- Single LED for user notification supported +- SPA06 baro supported +- Sum battery monitor optionally reports minimum voltage instead of average +- Sum battery monitor reports average temp +- Torqeedo dual motor support (see TRQ1, TRQ2 params) +- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes) +- UBlox GPS time ignored until at least 2D fix +- VideoTX supports additional freq bands (RushFPV 3.3Ghz) +- Volz logs desired and actual position, voltage, current, motor and PCB temp +- Volz server feedback and logging fixed +- Volz servo output in its own thread resulting in smoother movements +- W25N02KV flash support + +4) Networking enhancements and fixes + +- Allow multiple UDP clients to connect/disconnect/reconnect +- Ethernet supports faster log downloading (raised SDMMC clock limit on H7) + +5) Camera and gimbal enhancements + +- Alexmos precision improved slightly +- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC) +- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at +- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame) +- Dual serial camera gimbal mounts fixed +- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS +- Retract Mount2 aux function added (see RCx_OPTION = 113) +- Servo gimbal reported angles respect roll, pitch and yaw limits +- Siyi driver sends autopilot location and speed (recorded in images via EXIF) +- Siyi picture and video download scripts +- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg) +- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script +- Siyi ZT6 hardware id and set-lens fixed +- Topotek gimbal support +- Trigger distance ignores GPS status and only uses EKF reported location + +6) Harmonic notch enhancements + +- Harmonic notch is active in forward flight on quadplanes +- Harmonic notch filter freq clamping and disabling reworked +- Harmonic notch handles negative ESC RPMs +- Harmonic notch supports per-motor throttle-based harmonic notch + +7) Copter specific enhancements and bug fixes + +- Attitude control fix to dt update order (reduces rate controller noise) +- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time +- Auto mode small target position jump when takeoff completes removed +- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None +- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178) +- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command +- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only) +- AutoTune fix to prevent spool up after landing +- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well) +- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180) +- Config error avoided if auto mode is paused very soon after poweron +- FLIGHT_OPTIONS bit added to require position estimate before arming +- Follow mode slowdown calcs fixed when target is moving +- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT) +- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message +- Guided mode internal error resolved when switching between thrust or climb rate based altitude control +- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle +- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down +- Landing detector logging added to ease support (see LDET message) +- Loiter unlimited command accepts NaNs (QGC sends these) +- Mavlink SYSTEM_STATUS set to BOOT during initialisation +- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values +- Payload place bug fix when aborted because gripper is already released +- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219) +- RTL_ALT minimum reduced to 30cm +- SystemID position controller support (Copter and Heli) +- TriCopter motor test and slew-up fixed +- WPNAV_SPEED min reduced to 10 cm/s (Copter only) +- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe + +8) TradHeli specific enhancements + +- Autorotation yaw behaviour fix +- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate +- Blade pitch angle logging added (see SWSH log message) +- Constrain cyclic roll for intermeshing +- ICE / turbine cool down fix +- Inverted flight extended to non manual throttle modes +- Inverted flight transitions smoothed and restricted to only Stabilize mode +- SWSH logging fix for reversed collectives + +9) Plane specific enhancements and bug fixes + +- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling +- Allow for different orientations of landing rangefinder +- Assistance requirements evaluted on mode change +- FBWB/CRUISE climb/sink rate limited by TECS limits +- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope) +- Glider pullup support (available only through custom build server) +- Loiter breakout improved to better handle destinations inside loiter circle +- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled) +- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes +- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition) +- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic +- Quadplane assistance check enhancements +- Quadplane Deca frame support +- Quadplane gets smoother takeoff by input shaping target accel and velocity +- Servo wiggles in altitude wait staged to be one after another +- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames +- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN) +- Takeoff fixes for fence autoenable +- Takeoff improvements including less overshoot of TKOFF_ALT +- TECS reset along with other controllers (important if plane dropped from balloon) +- Tilt quadplane ramp of motors on back transition fixed +- Tiltrotor tilt angles logged +- TKOFF_THR_MIN applied to SLT transitions +- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration +- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff + +10) Rover specific enhancements and bug fixes + +- Auto mode reversed state maintained if momentarily switched to Hold mode +- Circle mode tracks better and avoids getting stuck at circle edge +- Flight time stats fixed +- MAV_CMD_NAV_SET_YAW_SPEED deprecated +- Omni3Mecanum frame support +- Stopping point uses max deceleration (was incorrectly using acceleration) +- Wheel rate controller slew rate fix + +11) Antenna Tracker specific enhancements and bug fixes + +- Never track lat,lon of 0,0 + +12) Scripting enhancements + +- advance-wp.lua applet supports advancing Auto mode WP via RC switch +- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch +- battery_internal_resistance_check.lua monitors battery resistance +- CAN:get_device returns nil for unconfigured CAN device +- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only) +- Copter:get_target_location, update_target_location support +- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only) +- Display text on OLED display supported +- Docs improved for many bindings +- EFI get_last_update_ms binding +- EFI_SkyPower.lua driver accepts 2nd supply voltage +- ESC_slew_rate.lua example script supports testing ESCs +- Filesystem CRC32 check to allow scripts to check module versions +- forced arming support +- GPIO get/set mode bindings (see gpio:set_mode, get_mode) +- GPS-for-yaw angle binding (see gps:gps_yaw_deg) +- Halo6000 EFI driver can log all CAN packets for easier debugging +- handle_external_position_estimate binding allows sending position estimate from lua to EKF +- I2C:transfer support +- IMU gyros_consistent and accels_consistent bindings added +- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control +- INS bindings for is calibrating, gyro and accel sensor values +- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients +- Logging of booleans supported +- Lua language checks improved (finds more errors) +- MAVLink commands can be called from scripting +- MCU voltage binding (see analog:mcu_voltage) +- NMEA 2000 EFI driver (see EFI_NMEA2k.lua) +- "open directory failed" false warning when scripts in ROMFS fixed +- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch +- Pass by reference values are always initialized +- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras +- plane_aerobatics.lua minor enhancements +- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation +- "require" function failures in rare circumstances fixed +- "require" function works for modules in ROMFS (e.g. not on SD card) +- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_) +- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand) +- SD card formatting supported +- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation) +- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter) +- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch +- Slung payload oscillation suppression applet added (see copter-slung-payload.lua) +- Temperature sensor bindings added +- uint64 support +- Various performance and memory usage optimizations +- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8 +- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame + +13) GCS / mavlink related changes and fixes + +- BATTERY2 message deprecated (replaced by BATTERY_STATUS) +- CMD_MISSION_START/STOP rejected if first-item/last-item args provided +- Deny attempts to upload two missions simultaneously +- Fence and Rally points may be uploaded using FTP +- GPS_INPUT and HIL_GPS handles multiple GPSs +- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC) +- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196 +- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support +- MAV_CMD_SET_HAGL support (Plane only) +- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links +- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message) +- Message interval supports TERRAIN_REPORT msg +- Mission upload may be cancelled using MISSION_CLEAR_ALL +- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated +- RC_CHANNELS_RAW deprecated +- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers +- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only) +- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports + +14) Logging enhancements and fixes + +- AC_PID resets and I-term sets logged +- ANG provides attitude at high rate (equivalent to ATT) +- ATT logs angles as floats (better resolution than ints) +- CAND message gets driver index +- DCM log message includes roll/pitch and yaw error +- EDT2 log msg includes stress and status received via extended DShot Telemetry v2 +- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin) +- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct +- FMT messages written as required instead of all at beginning +- Logging restarted after download completes when LOG_DISARMED = 1 +- MISE msg logs active mission command (CMD logged when commands are uploaded) +- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN +- RPM sensor logging gets instance field, quality and health fields +- Short filename support removed (e.g log1.BIN instead of 00000001.BIN) +- Temperature sensor logging option for only sensors with no source (see TEMP_LOG) +- UART data rates logged at 1hz (see UART message) + +15) ROS2 / DDS support + +- Airspeed published +- Battery topic reports all available batteries +- Compile-time configurable rates for each publisher +- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent +- GPS global origin published at 1 Hz +- High frequency raw imu data transmission +- Joystick support +- Support sending waypoints to Copter and Rover +- Remove the XML refs file in favor of binary entity creation + +16) Safety related enhancements and fixes + +- Accel/Gyro inconsistent message fixed for using with only single IMU +- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action +- Far from EKF origin pre-arm check removed (Copter only) +- Fence breach warning message slightly improved +- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS) +- Fences can be stored to SD Card (see BRD_SD_FENCE param) +- ICEngine stopped when in E-Stop or safety engaged (Plane only) +- LEDs flash green lights based on EKF location not GPS +- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS) +- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added +- Pre-arm check if OpenDroneID is compiled in but disabled +- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions) +- Pre-arm checks alert user more quickly on failure +- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE +- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover) +- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on +- Warning of duplicate SERIALx_PROTOCOL = RCIN + +17) Other bug fixes and minor enhancements + +- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher) +- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools +- Bootloader rejects allocation of broadcast node ID +- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI) +- Dijkstras fix to correct use of uninitialised variable +- DShot rates are not limited by NeoPixel rates +- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode +- Filesystem does not show entries for empty @ files +- Filesystem efficiency improvements when reading files +- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset) +- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm) +- Internal error thrown if we lose parameters due to saving queue being too small +- MAVLink via DroneCAN baud rate fix +- SPI pins may also be used as GPIOs +- Terrain cache size configurable (see TERRAIN_CACHE_SZ) + +18) Developer focused fixes and enhancements + +- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams +- Cygwin build fix for non-SITL builds +- Cygwin build fixed with malloc wrap +- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua) +- EKF3 code generator documentation and cleanup +- GPS jamming simulator added +- MacOS compiler warnings reduced +- SFML joystick support +- SITL support for OpenBSD +- Text warning if older Fence or Rally point protocols are used +------------------------------------------------------------------ +Release 4.5.7 08 Oct 2024 + +Changes from 4.5.7-beta1 + +1) Reverted Septentrio GPS sat count correctly drops to zero when 255 received +------------------------------------------------------------------ +Release 4.5.7-beta1 26 Sep 2024 + +Changes from 4.5.6 + +1) Bug fixes and minor enhancements + +- VUAV-V7pro support +- CUAV-7-Nano correction for LEDs and battery volt and current scaling +- DroneCAN deadlock and saturation of CAN bus fixed +- DroneCAN DNA server init fix (caused logging issues and spam on bus) +- F4 boards with inverter support correctly uninvert RX/TX +- Nanoradar M72 radar driver fix for object avoidance path planning +- RC support for latest version of GHST +- Septentrio GPS sat count correctly drops to zero when 255 received + +2) ROS2/DDS and other developer focused enhancements + +- AP quaternions normalised for ROS2 to avoid warnings +- Dependencies fixed for easier installation +- ROS2 SITL launch file enhancements including displaying console and map +- ROS_DOMAIN_ID param added to support multiple vehicles or instances of ROS2 +- Python 3.12 support +------------------------------------------------------------------ +Release 4.5.6 03 Sep 2024 + +No changes from 4.5.6-beta1 +------------------------------------------------------------------ +Release 4.5.6-beta1 20 Aug 2024 + +Changes from 4.5.5 + +1) Board specific enhancements and bug fixes + +- 3DR Control Zero H7 Rev G support +- CUAV-7-Nano support +- FoxeerF405v2 servo outputs increased from 9 to 11 +- Holybro Pixhawk6C hi-power peripheral overcurrent reporting fixed +- iFlight 2RAW H7 support +- MFT-SEMA100 support +- TMotorH743 support BMI270 baro +- ZeroOneX6 support + +2) Minor enhancements and bug fixes + +- Cameras using MAVLink report vendor and model name correctly +- DroneCAN fix to remove occasional NodeID registration error +- GPS NMEA and GSoF driver ground course corrected (now always 0 ~ 360 deg) +- ICP101XX barometer slowed to avoid I2C communication errors +- IMU temp cal param (INSn_ACCSCAL_Z) stored correctly when bootloader is flashed +- IMU gyro/accel duplicate id registration fixed to avoid possible pre-arm failure +- Logging to flash timestamp fix +- OSD displays ESC temp instead of motor temp +- PID controller error calculation bug fix (was using target from prev iteration) +- Relay on MAIN pins fixed +------------------------------------------------------------------ +Release 4.5.5 1st Aug 2024 + +No changes from 4.5.5-beta2 +------------------------------------------------------------------ +Release 4.5.5-beta2 27 July 2024 + +Changes from 4.5.5-beta1 + +1) Board specific enhancements and bug fixes + +- CubeRed's second core disabled at boot to avoid spurious writes to RAM +- CubeRed bootloader's dual endpoint update method fixed +------------------------------------------------------------------ +Release 4.5.5-beta1 1st July 2024 + +Changes from 4.5.4 + +1) Board specific enhancements and bug fixes + +- fixed IOMCU transmission errors when using bdshot +- update relay parameter names on various boards +- add ASP5033 airspeed in minimal builds +- added RadiolinkPIX6 +- fix Aocoda-RC H743Dual motor issue +- use ICM45686 as an ICM20649 alternative in CubeRedPrimary + +2) System level minor enhancements and bug fixes + +- correct use-after-free in script statistics +- added arming check for eeprom full +- fixed a block logging issue which caused log messages to be dropped +- enable Socket SO_REUSEADDR on LwIP +- removed IST8310 overrun message +- added Siyi ZT6 support +- added BTFL sidebar symbols to the OSD +- added CRSF extended link stats to the OSD +- use the ESC with the highest RPM in the OSD when only one can be displayed +- support all Tramp power levels on high power VTXs +- emit jump count in missions even if no limit +- improve the bitmask indicating persistent parameters on bootloader flash +- fix duplicate error condition in the MicroStrain7 + +5) Other minor enhancements and bug fixes + +- specify pymonocypher version in more places +- added DroneCAN dependencies to custom builds + +------------------------------------------------------------------ +Release 4.5.4 12th June 2024 + +Changes from 4.5.3 + +Disable highres IMU sampling on ICM42670 fixing an issue on some versions of Pixhawk6X + +------------------------------------------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Rover specific changes + +- correct clamping of RTL_SPEED for fractional speed values + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + +------------------------------------------------------------------ Release 4.5.1 8th April 2024 This release fixes a critical bug in the CRSF R/C protocol parser that diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index f1a47b452545da..7460a561e056b6 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -70,7 +70,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { // Function name, Hz, us, SCHED_TASK(read_radio, 50, 200, 3), SCHED_TASK(ahrs_update, 400, 400, 6), +#if AP_RANGEFINDER_ENABLED SCHED_TASK(read_rangefinders, 50, 200, 9), +#endif #if AP_OPTICALFLOW_ENABLED SCHED_TASK_CLASS(AP_OpticalFlow, &rover.optflow, update, 200, 160, 11), #endif @@ -132,7 +134,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #endif SCHED_TASK(crash_check, 10, 200, 123), SCHED_TASK(cruise_learn_update, 50, 200, 126), -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED SCHED_TASK(afs_fs_check, 10, 200, 129), #endif }; @@ -157,8 +159,8 @@ Rover::Rover(void) : { } -#if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +// set target location (for use by external control and scripting) bool Rover::set_target_location(const Location& target_loc) { // exit if vehicle is not in Guided mode or Auto-Guided mode @@ -168,7 +170,9 @@ bool Rover::set_target_location(const Location& target_loc) return mode_guided.set_desired_location(target_loc); } +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED // set target velocity (for use by scripting) bool Rover::set_target_velocity_NED(const Vector3f& vel_ned) { @@ -244,19 +248,19 @@ bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float & control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Throttle: - control_value = constrain_float(g2.motors.get_throttle() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Yaw: control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Lateral: - control_value = constrain_float(g2.motors.get_lateral() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::MainSail: - control_value = constrain_float(g2.motors.get_mainsail() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::WingSail: - control_value = constrain_float(g2.motors.get_wingsail() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f); return true; default: return false; @@ -291,17 +295,6 @@ void Rover::nav_script_time_done(uint16_t id) } #endif // AP_SCRIPTING_ENABLED -#if AP_STATS_ENABLED -/* - update AP_Stats -*/ -void Rover::stats_update(void) -{ - AP::stats()->set_flying(g2.motors.active()); -} -#endif - - // update AHRS system void Rover::ahrs_update() { @@ -442,7 +435,7 @@ void Rover::one_second_loop(void) set_control_channels(); // cope with changes to aux functions - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // update notify flags AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false); @@ -466,6 +459,11 @@ void Rover::one_second_loop(void) 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()); g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); + +#if AP_STATS_ENABLED + // Update stats "flying" time + AP::stats()->set_flying(g2.motors.active()); +#endif } void Rover::update_current_mode(void) diff --git a/Rover/Rover.h b/Rover/Rover.h index 8873b844e2946c..93c7c5c64cab4f 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -60,7 +60,7 @@ // Local modules #include "AP_Arming.h" #include "sailboat.h" -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED #include "afs_rover.h" #endif #include "Parameters.h" @@ -81,7 +81,7 @@ class Rover : public AP_Vehicle { friend class ParametersG2; friend class AP_Rally_Rover; friend class AP_Arming_Rover; -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED friend class AP_AdvancedFailsafe_Rover; #endif #if AP_EXTERNAL_CONTROL_ENABLED @@ -99,11 +99,11 @@ class Rover : public AP_Vehicle { friend class ModeManual; friend class ModeRTL; friend class ModeSmartRTL; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED friend class ModeFollow; #endif friend class ModeSimple; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED friend class ModeDock; #endif @@ -206,8 +206,10 @@ class Rover : public AP_Vehicle { // true if we have a position estimate from AHRS bool have_position; +#if AP_RANGEFINDER_ENABLED // range finder last update for each instance (used for DPTH logging) uint32_t rangefinder_last_reading_ms[RANGEFINDER_MAX_INSTANCES]; +#endif // Ground speed // The amount current ground speed is below min ground speed. meters per second @@ -251,11 +253,11 @@ class Rover : public AP_Vehicle { ModeSteering mode_steering; ModeRTL mode_rtl; ModeSmartRTL mode_smartrtl; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED ModeFollow mode_follow; #endif ModeSimple mode_simple; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED ModeDock mode_dock; #endif @@ -269,8 +271,11 @@ class Rover : public AP_Vehicle { cruise_learn_t cruise_learn; // Rover.cpp -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED bool set_target_location(const Location& target_loc) override; +#endif + +#if AP_SCRIPTING_ENABLED bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_steering_and_throttle(float steering, float throttle) override; bool get_steering_and_throttle(float& steering, float& throttle) override; @@ -282,7 +287,6 @@ class Rover : public AP_Vehicle { bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override; void nav_script_time_done(uint16_t id) override; #endif // AP_SCRIPTING_ENABLED - void stats_update(); void ahrs_update(); void gcs_failsafe_check(void); void update_logging1(void); @@ -318,7 +322,7 @@ class Rover : public AP_Vehicle { // failsafe.cpp void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on); void handle_battery_failsafe(const char* type_str, const int8_t action); -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED void afs_fs_check(void); #endif @@ -370,7 +374,9 @@ class Rover : public AP_Vehicle { void update_compass(void); void compass_save(void); void update_wheel_encoder(); +#if AP_RANGEFINDER_ENABLED void read_rangefinders(void); +#endif // Steering.cpp void set_servos(void); @@ -393,7 +399,7 @@ class Rover : public AP_Vehicle { return control_mode == &mode_auto; } - void startup_INS_ground(void); + void startup_INS(void); void notify_mode(const Mode *new_mode); uint8_t check_digital_pin(uint8_t pin); bool should_log(uint32_t mask); diff --git a/Rover/Steering.cpp b/Rover/Steering.cpp index 5253c2dfbebb61..5724c46976b9c6 100644 --- a/Rover/Steering.cpp +++ b/Rover/Steering.cpp @@ -10,10 +10,8 @@ void Rover::set_servos(void) motor_test_output(); } else { // get ground speed - float speed; - if (!g2.attitude_control.get_forward_speed(speed)) { - speed = 0.0f; - } + float speed = 0.0f; + g2.attitude_control.get_forward_speed(speed); g2.motors.output(arming.is_armed(), speed, G_Dt); } diff --git a/Rover/afs_rover.cpp b/Rover/afs_rover.cpp index 4265a20887ebb2..29e1f12da1c1da 100644 --- a/Rover/afs_rover.cpp +++ b/Rover/afs_rover.cpp @@ -4,7 +4,7 @@ #include "Rover.h" -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED /* Setup radio_out values for all channels to termination values @@ -32,6 +32,6 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Rover::afs_mode(void) //to force entering auto mode when datalink loss void AP_AdvancedFailsafe_Rover::set_mode_auto(void) { - over.set_mode(rover.mode_auto,ModeReason::GCS_FAILSAFE); + rover.set_mode(rover.mode_auto,ModeReason::GCS_FAILSAFE); } -#endif // ADVANCED_FAILSAFE +#endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED diff --git a/Rover/afs_rover.h b/Rover/afs_rover.h index aa3473ddc39d54..f8b291eedaecb3 100644 --- a/Rover/afs_rover.h +++ b/Rover/afs_rover.h @@ -18,7 +18,7 @@ advanced failsafe support for rover */ -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED #include /* diff --git a/Rover/config.h b/Rover/config.h index 03ddc70945998e..7685a875b88682 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -72,11 +72,6 @@ #define RESET_SWITCH_CHAN_PWM 1750 #endif -#ifndef ADVANCED_FAILSAFE - #define ADVANCED_FAILSAFE DISABLED +#ifndef AP_ROVER_ADVANCED_FAILSAFE_ENABLED + #define AP_ROVER_ADVANCED_FAILSAFE_ENABLED 0 #endif - -#ifndef OSD_ENABLED - #define OSD_ENABLED DISABLED -#endif - diff --git a/Rover/defines.h b/Rover/defines.h index 5fd45c2a2c9a93..0db0a92ba3b6ee 100644 --- a/Rover/defines.h +++ b/Rover/defines.h @@ -3,14 +3,6 @@ // Internal defines, don't edit and expect things to work // ------------------------------------------------------- -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - #define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an arbitrary representation of servo max travel. // types of failsafe events @@ -88,11 +80,11 @@ enum fs_ekf_action { #define DISTANCE_HOME_MINCHANGE 0.5f // minimum distance to adjust home location -enum pilot_steer_type_t { - PILOT_STEER_TYPE_DEFAULT = 0, - PILOT_STEER_TYPE_TWO_PADDLES = 1, - PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING = 2, - PILOT_STEER_TYPE_DIR_UNCHANGED_WHEN_REVERSING = 3, +enum class PilotSteerType : uint8_t { + DEFAULT = 0, + TWO_PADDLES = 1, + DIR_REVERSED_WHEN_REVERSING = 2, + DIR_UNCHANGED_WHEN_REVERSING = 3, }; // frame class enum used for FRAME_CLASS parameter diff --git a/Rover/failsafe.cpp b/Rover/failsafe.cpp index da877c2bb7482a..3aabdfbacf1d6f 100644 --- a/Rover/failsafe.cpp +++ b/Rover/failsafe.cpp @@ -84,17 +84,17 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool o case FailsafeAction::None: break; case FailsafeAction::SmartRTL: - if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { break; } FALLTHROUGH; case FailsafeAction::RTL: - if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_rtl, ModeReason::FAILSAFE)) { break; } FALLTHROUGH; case FailsafeAction::Hold: - set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); + set_mode(mode_hold, ModeReason::FAILSAFE); break; case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { @@ -133,18 +133,18 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action) } break; case FailsafeAction::Terminate: -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED char battery_type_str[17]; snprintf(battery_type_str, 17, "%s battery", type_str); g2.afs.gcs_terminate(true, battery_type_str); #else arming.disarm(AP_Arming::Method::BATTERYFAILSAFE); -#endif // ADVANCED_FAILSAFE == ENABLED +#endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED break; } } -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED /* check for AFS failsafe check */ diff --git a/Rover/fence.cpp b/Rover/fence.cpp index 4c29b48d243dcd..2706bf91d376f9 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -25,17 +25,17 @@ void Rover::fence_check() case FailsafeAction::None: break; case FailsafeAction::SmartRTL: - if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) { break; } FALLTHROUGH; case FailsafeAction::RTL: - if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) { break; } FALLTHROUGH; case FailsafeAction::Hold: - set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); + set_mode(mode_hold, ModeReason::FENCE_BREACHED); break; case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) { diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 8381410a6ee6d8..b1c2a23f71419e 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -10,7 +10,7 @@ Mode::Mode() : channel_roll(rover.channel_roll), channel_pitch(rover.channel_pitch), channel_walking_height(rover.channel_walking_height), - attitude_control(rover.g2.attitude_control) + attitude_control(g2.attitude_control) { } void Mode::exit() @@ -44,10 +44,11 @@ bool Mode::enter() // initialisation common to all modes if (ret) { - set_reversed(false); + // init reversed flag + init_reversed_flag(); // clear sailboat tacking flags - rover.g2.sailboat.clear_tack(); + g2.sailboat.clear_tack(); } return ret; @@ -66,10 +67,10 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const } // apply RC skid steer mixing - switch ((enum pilot_steer_type_t)rover.g.pilot_steer_type.get()) + switch ((PilotSteerType)g.pilot_steer_type.get()) { - case PILOT_STEER_TYPE_DEFAULT: - case PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING: + case PilotSteerType::DEFAULT: + case PilotSteerType::DIR_REVERSED_WHEN_REVERSING: default: { // by default regular and skid-steering vehicles reverse their rotation direction when backing up throttle_out = rover.channel_throttle->get_control_in(); @@ -78,7 +79,7 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const break; } - case PILOT_STEER_TYPE_TWO_PADDLES: { + case PilotSteerType::TWO_PADDLES: { // convert the two radio_in values from skid steering values // left paddle from steering input channel, right paddle from throttle input channel // steering = left-paddle - right-paddle @@ -91,7 +92,7 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const break; } - case PILOT_STEER_TYPE_DIR_UNCHANGED_WHEN_REVERSING: { + case PilotSteerType::DIR_UNCHANGED_WHEN_REVERSING: { throttle_out = rover.channel_throttle->get_control_in(); steering_out = rover.channel_steer->get_control_in(); break; @@ -111,7 +112,7 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t // we proportionally reduce steering and throttle if (g2.motors.have_skid_steering()) { const float steer_normalised = constrain_float(steering_out / 4500.0f, -1.0f, 1.0f); - const float throttle_normalised = constrain_float(throttle_out / 100.0f, -1.0f, 1.0f); + const float throttle_normalised = constrain_float(throttle_out * 0.01f, -1.0f, 1.0f); const float saturation_value = fabsf(steer_normalised) + fabsf(throttle_normalised); if (saturation_value > 1.0f) { steering_out /= saturation_value; @@ -122,8 +123,8 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t // check for special case of input and output throttle being in opposite directions float throttle_out_limited = g2.motors.get_slew_limited_throttle(throttle_out, rover.G_Dt); if ((is_negative(throttle_out) != is_negative(throttle_out_limited)) && - ((g.pilot_steer_type == PILOT_STEER_TYPE_DEFAULT) || - (g.pilot_steer_type == PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING))) { + (g.pilot_steer_type == PilotSteerType::DEFAULT || + g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) { steering_out *= -1; } throttle_out = throttle_out_limited; @@ -138,8 +139,8 @@ void Mode::get_pilot_desired_steering_and_speed(float &steering_out, float &spee // check for special case of input and output throttle being in opposite directions float speed_out_limited = g2.attitude_control.get_desired_speed_accel_limited(speed_out, rover.G_Dt); if ((is_negative(speed_out) != is_negative(speed_out_limited)) && - ((g.pilot_steer_type == PILOT_STEER_TYPE_DEFAULT) || - (g.pilot_steer_type == PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING))) { + (g.pilot_steer_type == PilotSteerType::DEFAULT || + g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) { steering_out *= -1; } speed_out = speed_out_limited; @@ -166,7 +167,7 @@ void Mode::get_pilot_desired_heading_and_speed(float &heading_out, float &speed_ float desired_throttle = constrain_float(rover.channel_throttle->norm_input_dz(), -1.0f, 1.0f); // handle two paddle input - if ((enum pilot_steer_type_t)rover.g.pilot_steer_type.get() == PILOT_STEER_TYPE_TWO_PADDLES) { + if (g.pilot_steer_type == PilotSteerType::TWO_PADDLES) { const float left_paddle = desired_steering; const float right_paddle = desired_throttle; desired_steering = (left_paddle - right_paddle) * 0.5f; @@ -279,7 +280,7 @@ void Mode::handle_tack_request() { // autopilot modes handle tacking if (is_autopilot_mode()) { - rover.g2.sailboat.handle_tack_request_auto(); + g2.sailboat.handle_tack_request_auto(); } } @@ -304,9 +305,9 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled) // call throttle controller and convert output to -100 to +100 range float throttle_out = 0.0f; - if (rover.g2.sailboat.sail_enabled()) { + if (g2.sailboat.sail_enabled()) { // sailboats use special throttle and mainsail controller - rover.g2.sailboat.get_throttle_and_set_mainsail(target_speed, throttle_out); + g2.sailboat.get_throttle_and_set_mainsail(target_speed, throttle_out); } else { // call speed or stop controller if (is_zero(target_speed) && !rover.is_balancebot()) { @@ -530,7 +531,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::LOITER: ret = &mode_loiter; break; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED case Mode::Number::FOLLOW: ret = &mode_follow; break; @@ -556,7 +557,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::INITIALISING: ret = &mode_initializing; break; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED case Mode::Number::DOCK: ret = (Mode *)g2.mode_dock_ptr; break; diff --git a/Rover/mode.h b/Rover/mode.h index f166843ed0d231..6b7b579702ad01 100644 --- a/Rover/mode.h +++ b/Rover/mode.h @@ -19,7 +19,7 @@ class Mode LOITER = 5, FOLLOW = 6, SIMPLE = 7, -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED DOCK = 8, #endif CIRCLE = 9, @@ -124,6 +124,9 @@ class Mode // execute the mission in reverse (i.e. backing up) void set_reversed(bool value); + // init reversed flag for autopilot mode + virtual void init_reversed_flag() { if (is_autopilot_mode()) { set_reversed(false); } } + // handle tacking request (from auxiliary switch) in sailboats virtual void handle_tack_request(); @@ -277,16 +280,23 @@ class ModeAuto : public Mode bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4); void nav_script_time_done(uint16_t id); + // + void init_reversed_flag() override { + if (!mission.is_resume()) { + set_reversed(false); + } + } + AP_Mission mission{ FUNCTOR_BIND_MEMBER(&ModeAuto::start_command, bool, const AP_Mission::Mission_Command&), FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&), FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)}; - enum Mis_Done_Behave { - MIS_DONE_BEHAVE_HOLD = 0, - MIS_DONE_BEHAVE_LOITER = 1, - MIS_DONE_BEHAVE_ACRO = 2, - MIS_DONE_BEHAVE_MANUAL = 3 + enum class DoneBehaviour : uint8_t { + HOLD = 0, + LOITER = 1, + ACRO = 2, + MANUAL = 3, }; protected: @@ -447,6 +457,12 @@ class ModeCircle : public Mode // initialise mode bool _enter() override; + // Update position controller targets driving to the circle edge + void update_drive_to_radius(); + + // Update position controller targets while circling + void update_circling(); + // initialise target_yaw_rad using the vehicle's position and yaw // if there is no current position estimate target_yaw_rad is set to vehicle yaw void init_target_yaw_rad(); @@ -483,6 +499,7 @@ class ModeCircle : public Mode float angle_total_rad; // total angle in radians that vehicle has circled bool reached_edge; // true once vehicle has reached edge of circle float dist_to_edge_m; // distance to edge of circle in meters (equivalent to crosstrack error) + bool tracking_back; // true if the vehicle is trying to track back onto the circle }; class ModeGuided : public Mode @@ -792,7 +809,7 @@ class ModeInitializing : public Mode bool _enter() override { return false; }; }; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED class ModeFollow : public Mode { public: @@ -852,7 +869,7 @@ class ModeSimple : public Mode float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot }; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED class ModeDock : public Mode { public: diff --git a/Rover/mode_acro.cpp b/Rover/mode_acro.cpp index d59f208f0aafc5..1cad71e702b11f 100644 --- a/Rover/mode_acro.cpp +++ b/Rover/mode_acro.cpp @@ -28,12 +28,12 @@ void ModeAcro::update() // handle sailboats if (!is_zero(desired_steering)) { // steering input return control to user - rover.g2.sailboat.clear_tack(); + g2.sailboat.clear_tack(); } - if (rover.g2.sailboat.tacking()) { + if (g2.sailboat.tacking()) { // call heading controller during tacking - steering_out = attitude_control.get_steering_out_heading(rover.g2.sailboat.get_tack_heading_rad(), + steering_out = attitude_control.get_steering_out_heading(g2.sailboat.get_tack_heading_rad(), g2.wp_nav.get_pivot_rate(), g2.motors.limit.steer_left, g2.motors.limit.steer_right, @@ -60,5 +60,5 @@ bool ModeAcro::requires_velocity() const // sailboats in acro mode support user manually initiating tacking from transmitter void ModeAcro::handle_tack_request() { - rover.g2.sailboat.handle_tack_request_acro(); + g2.sailboat.handle_tack_request_acro(); } diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index dd99f363a15198..0e9b0c94235e2e 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -141,7 +141,7 @@ void ModeAuto::update() break; case SubMode::Circle: - rover.g2.mode_circle.update(); + g2.mode_circle.update(); break; } } @@ -173,7 +173,7 @@ float ModeAuto::wp_bearing() const case SubMode::NavScriptTime: return rover.mode_guided.wp_bearing(); case SubMode::Circle: - return rover.g2.mode_circle.wp_bearing(); + return g2.mode_circle.wp_bearing(); } // this line should never be reached @@ -197,7 +197,7 @@ float ModeAuto::nav_bearing() const case SubMode::NavScriptTime: return rover.mode_guided.nav_bearing(); case SubMode::Circle: - return rover.g2.mode_circle.nav_bearing(); + return g2.mode_circle.nav_bearing(); } // this line should never be reached @@ -221,7 +221,7 @@ float ModeAuto::crosstrack_error() const case SubMode::NavScriptTime: return rover.mode_guided.crosstrack_error(); case SubMode::Circle: - return rover.g2.mode_circle.crosstrack_error(); + return g2.mode_circle.crosstrack_error(); } // this line should never be reached @@ -245,7 +245,7 @@ float ModeAuto::get_desired_lat_accel() const case SubMode::NavScriptTime: return rover.mode_guided.get_desired_lat_accel(); case SubMode::Circle: - return rover.g2.mode_circle.get_desired_lat_accel(); + return g2.mode_circle.get_desired_lat_accel(); } // this line should never be reached @@ -270,7 +270,7 @@ float ModeAuto::get_distance_to_destination() const case SubMode::NavScriptTime: return rover.mode_guided.get_distance_to_destination(); case SubMode::Circle: - return rover.g2.mode_circle.get_distance_to_destination(); + return g2.mode_circle.get_distance_to_destination(); } // this line should never be reached @@ -299,7 +299,7 @@ bool ModeAuto::get_desired_location(Location& destination) const case SubMode::NavScriptTime: return rover.mode_guided.get_desired_location(destination); case SubMode::Circle: - return rover.g2.mode_circle.get_desired_location(destination); + return g2.mode_circle.get_desired_location(destination); } // we should never reach here but just in case @@ -341,7 +341,7 @@ bool ModeAuto::reached_destination() const case SubMode::NavScriptTime: return rover.mode_guided.reached_destination(); case SubMode::Circle: - return rover.g2.mode_circle.reached_destination(); + return g2.mode_circle.reached_destination(); } // we should never reach here but just in case, return true to allow missions to continue @@ -366,7 +366,7 @@ bool ModeAuto::set_desired_speed(float speed) case SubMode::NavScriptTime: return rover.mode_guided.set_desired_speed(speed); case SubMode::Circle: - return rover.g2.mode_circle.set_desired_speed(speed); + return g2.mode_circle.set_desired_speed(speed); } return false; } @@ -512,13 +512,6 @@ void ModeAuto::send_guided_position_target() /********************************************************************************/ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { -#if HAL_LOGGING_ENABLED - // log when new commands start - if (rover.should_log(MASK_LOG_CMD)) { - rover.logger.Write_Mission_Cmd(mission, cmd); - } -#endif - switch (cmd.id) { case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint return do_nav_wp(cmd, false); @@ -593,18 +586,6 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_set_reverse(cmd); break; - case MAV_CMD_DO_FENCE_ENABLE: -#if AP_FENCE_ENABLED - if (cmd.p1 == 0) { //disable - rover.fence.enable(false); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); - } else { //enable fence - rover.fence.enable(true); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); - } -#endif - break; - case MAV_CMD_DO_GUIDED_LIMITS: do_guided_limits(cmd); break; @@ -626,16 +607,25 @@ void ModeAuto::exit_mission() // send message gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete"); - if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && start_loiter()) { - return; - } - - if (g2.mis_done_behave == MIS_DONE_BEHAVE_ACRO && rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) { - return; - } - - if (g2.mis_done_behave == MIS_DONE_BEHAVE_MANUAL && rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) { - return; + switch ((DoneBehaviour)g2.mis_done_behave) { + case DoneBehaviour::HOLD: + // the default "start_stop" behaviour is used + break; + case DoneBehaviour::LOITER: + if (start_loiter()) { + return; + } + break; + case DoneBehaviour::ACRO: + if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) { + return; + } + break; + case DoneBehaviour::MANUAL: + if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) { + return; + } + break; } start_stop(); @@ -902,7 +892,7 @@ bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // if a location target was set, return true once vehicle is close if (guided_target.valid) { - if (rover.current_loc.get_distance(guided_target.loc) <= rover.g2.wp_nav.get_radius()) { + if (rover.current_loc.get_distance(guided_target.loc) <= g2.wp_nav.get_radius()) { return true; } } diff --git a/Rover/mode_circle.cpp b/Rover/mode_circle.cpp index 86ba7dbdae1193..c0a76862071950 100644 --- a/Rover/mode_circle.cpp +++ b/Rover/mode_circle.cpp @@ -70,7 +70,7 @@ bool ModeCircle::set_center(const Location& center_loc, float radius_m, bool dir return true; } -// initialize dock mode +// initialize circle mode from current position bool ModeCircle::_enter() { // capture starting point and yaw @@ -85,9 +85,15 @@ bool ModeCircle::_enter() target.yaw_rad = AP::ahrs().get_yaw(); target.speed = 0; + // record center as location (only used for reporting) + config.center_loc = rover.current_loc; + // check speed around circle does not lead to excessive lateral acceleration check_config_speed(); + // reset tracking_back + tracking_back = false; + // calculate speed, accel and jerk limits // otherwise the vehicle uses wp_nav default speed limit float atc_accel_max = MIN(g2.attitude_control.get_accel_max(), g2.attitude_control.get_decel_max()); @@ -144,27 +150,69 @@ void ModeCircle::update() return; } - // check if vehicle has reached edge of circle + // Update distance to destination and distance to edge const Vector2f center_to_veh = curr_pos - config.center_pos; - _distance_to_destination = center_to_veh.length(); - dist_to_edge_m = fabsf(_distance_to_destination - config.radius); + _distance_to_destination = (target.pos.tofloat() - curr_pos).length(); + dist_to_edge_m = fabsf(center_to_veh.length() - config.radius); + + // Update depending on stage if (!reached_edge) { - const float dist_thresh_m = MAX(rover.g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST); - reached_edge = dist_to_edge_m <= dist_thresh_m; + update_drive_to_radius(); + } else if (dist_to_edge_m > 2 * MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && !tracking_back) { + // if more than 2* turn_radius outside circle radius, slow vehicle by 20% + config.speed = 0.8 * config.speed; + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Circle: cannot keep up, slowing to %.1fm/s", config.speed); + tracking_back = true; + } else if (dist_to_edge_m < MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && tracking_back) { + // if within turn_radius, call the vehicle back on track + tracking_back = false; + } else { + update_circling(); } + g2.pos_control.update(rover.G_Dt); + + // get desired speed and turn rate from pos_control + const float desired_speed = g2.pos_control.get_desired_speed(); + const float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads(); + + // run steering and throttle controllers + calc_steering_from_turn_rate(desired_turn_rate); + calc_throttle(desired_speed, true); +} + +void ModeCircle::update_drive_to_radius() +{ + // check if vehicle has reached edge of circle + const float dist_thresh_m = MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST); + reached_edge |= dist_to_edge_m <= dist_thresh_m; + + // calculate target point's position, velocity and acceleration + target.pos = config.center_pos.topostype(); + target.pos.offset_bearing(degrees(target.yaw_rad), config.radius); + + g2.pos_control.input_pos_target(target.pos, rover.G_Dt); +} + +// Update position controller targets while circling +void ModeCircle::update_circling() +{ + // accelerate speed up to desired speed - const float speed_max = reached_edge ? config.speed : 0.0; const float speed_change_max = (g2.pos_control.get_accel_max() * 0.5 * rover.G_Dt); - const float accel_fb = constrain_float(speed_max - target.speed, -speed_change_max, speed_change_max); + const float accel_fb = constrain_float(config.speed - target.speed, -speed_change_max, speed_change_max); target.speed += accel_fb; - // calculate angular rate and update target angle - const float circumference = 2.0 * M_PI * config.radius; - const float angular_rate_rad = (target.speed / circumference) * M_2PI * (config.dir == Direction::CW ? 1.0 : -1.0); - const float angle_dt = angular_rate_rad * rover.G_Dt; - target.yaw_rad = wrap_PI(target.yaw_rad + angle_dt); - angle_total_rad += angle_dt; + // calculate angular rate and update target angle, if the vehicle is not trying to track back + if (!tracking_back) { + const float circumference = 2.0 * M_PI * config.radius; + const float angular_rate_rad = (target.speed / circumference) * M_2PI * (config.dir == Direction::CW ? 1.0 : -1.0); + const float angle_dt = angular_rate_rad * rover.G_Dt; + target.yaw_rad = wrap_PI(target.yaw_rad + angle_dt); + angle_total_rad += angle_dt; + } else { + init_target_yaw_rad(); + } // calculate target point's position, velocity and acceleration target.pos = config.center_pos.topostype(); @@ -179,15 +227,7 @@ void ModeCircle::update() target.accel.rotate(target.yaw_rad); g2.pos_control.set_pos_vel_accel_target(target.pos, target.vel, target.accel); - g2.pos_control.update(rover.G_Dt); - // get desired speed and turn rate from pos_control - const float desired_speed = g2.pos_control.get_desired_speed(); - const float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads(); - - // run steering and throttle controllers - calc_steering_from_turn_rate(desired_turn_rate); - calc_throttle(desired_speed, true); } // return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message) @@ -198,7 +238,7 @@ float ModeCircle::wp_bearing() const return 0; } // calc vector from circle center to vehicle - Vector2f veh_to_center = (config.center_pos - curr_pos_NE); + Vector2f veh_to_center = (target.pos.tofloat() - curr_pos_NE); if (veh_to_center.is_zero()) { return 0; } @@ -243,6 +283,7 @@ bool ModeCircle::set_desired_speed(float speed_ms) bool ModeCircle::get_desired_location(Location& destination) const { destination = config.center_loc; + destination.offset_bearing(degrees(target.yaw_rad), config.radius); return true; } @@ -266,8 +307,8 @@ void ModeCircle::check_config_speed() void ModeCircle::check_config_radius() { // ensure radius is at least as large as vehicle's turn radius - if (config.radius < rover.g2.turn_radius) { - config.radius = rover.g2.turn_radius; - gcs().send_text(MAV_SEVERITY_WARNING, "Circle: radius increased to TURN_RADIUS (%4.1f)", (double)rover.g2.turn_radius); + if (config.radius < g2.turn_radius) { + config.radius = g2.turn_radius; + gcs().send_text(MAV_SEVERITY_WARNING, "Circle: radius increased to TURN_RADIUS (%4.1f)", (double)g2.turn_radius); } } diff --git a/Rover/mode_dock.cpp b/Rover/mode_dock.cpp index 89f8d89af7361a..09d727fce0397c 100644 --- a/Rover/mode_dock.cpp +++ b/Rover/mode_dock.cpp @@ -1,6 +1,6 @@ #include "Rover.h" -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED const AP_Param::GroupInfo ModeDock::var_info[] = { // @Param: _SPEED diff --git a/Rover/mode_guided.cpp b/Rover/mode_guided.cpp index 96ab7e15651d46..338a734ff99eca 100644 --- a/Rover/mode_guided.cpp +++ b/Rover/mode_guided.cpp @@ -82,7 +82,7 @@ void ModeGuided::update() } if (have_attitude_target) { // run steering and throttle controllers - float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds / 100.0f), + float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f), g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt); @@ -443,5 +443,5 @@ bool ModeGuided::limit_breached() const // 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); + return ((g2.guided_options.get() & uint32_t(Options::SCurvesUsedForNavigation)) != 0); } diff --git a/Rover/mode_loiter.cpp b/Rover/mode_loiter.cpp index 918144c9fa444d..b208c595b14ddc 100644 --- a/Rover/mode_loiter.cpp +++ b/Rover/mode_loiter.cpp @@ -23,16 +23,16 @@ void ModeLoiter::update() // get distance (in meters) to destination _distance_to_destination = rover.current_loc.get_distance(_destination); - const float loiter_radius = rover.g2.sailboat.tack_enabled() ? g2.sailboat.get_loiter_radius() : g2.loit_radius; + const float loiter_radius = g2.sailboat.tack_enabled() ? g2.sailboat.get_loiter_radius() : g2.loit_radius; // if within loiter radius slew desired speed towards zero and use existing desired heading if (_distance_to_destination <= loiter_radius) { // sailboats should not stop unless motoring - const float desired_speed_within_radius = rover.g2.sailboat.tack_enabled() ? 0.1f : 0.0f; + const float desired_speed_within_radius = g2.sailboat.tack_enabled() ? 0.1f : 0.0f; _desired_speed = attitude_control.get_desired_speed_accel_limited(desired_speed_within_radius, rover.G_Dt); // if we have a sail but not trying to use it then point into the wind - if (!rover.g2.sailboat.tack_enabled() && rover.g2.sailboat.sail_enabled()) { + if (!g2.sailboat.tack_enabled() && g2.sailboat.sail_enabled()) { _desired_yaw_cd = degrees(g2.windvane.get_true_wind_direction_rad()) * 100.0f; } } else { diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index e896c5151fc878..8fe2ad75959d75 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -8,7 +8,7 @@ bool ModeRTL::_enter() } // initialise waypoint navigation library - g2.wp_nav.init(MAX(0, g2.rtl_speed)); + g2.wp_nav.init(MAX(0.0f, g2.rtl_speed)); // set target to the closest rally point or home #if HAL_RALLY_ENABLED diff --git a/Rover/precision_landing.cpp b/Rover/precision_landing.cpp index c62b499b6a3eca..3e6f1c105d5fde 100644 --- a/Rover/precision_landing.cpp +++ b/Rover/precision_landing.cpp @@ -8,7 +8,9 @@ void Rover::init_precland() { - rover.precland.init(400); + // scheduler table specifies 400Hz, but we can call it no faster + // than the scheduler loop rate: + rover.precland.init(MIN(400, scheduler.get_loop_rate_hz())); } void Rover::update_precland() diff --git a/Rover/radio.cpp b/Rover/radio.cpp index cf1f159689c957..9fdb5c0c980f62 100644 --- a/Rover/radio.cpp +++ b/Rover/radio.cpp @@ -6,9 +6,10 @@ void Rover::set_control_channels(void) { // check change on RCMAP - channel_steer = rc().channel(rcmap.roll()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_lateral = rc().channel(rcmap.yaw()-1); + // the library gaurantees that these are non-nullptr: + channel_steer = &rc().get_roll_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_lateral = &rc().get_yaw_channel(); // set rc channel ranges channel_steer->set_angle(SERVO_MAX); diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index 7fb957e06c6281..24b11dea09178a 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -275,9 +275,9 @@ void Sailboat::relax_sails() // calculate throttle and mainsail angle required to attain desired speed (in m/s) void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttle_out) { + throttle_out = 0.0f; if (!sail_enabled()) { relax_sails(); - throttle_out = 0.0f; return; } @@ -292,8 +292,6 @@ void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttl rover.g.speed_cruise, rover.g.throttle_cruise * 0.01f, rover.G_Dt); - } else { - throttle_out = 0.0f; } if (motor_state == UseMotor::USE_MOTOR_ALWAYS) { diff --git a/Rover/sensors.cpp b/Rover/sensors.cpp index aa9f7918912275..793fa4b726a25e 100644 --- a/Rover/sensors.cpp +++ b/Rover/sensors.cpp @@ -87,6 +87,7 @@ void Rover::update_wheel_encoder() #endif } +#if AP_RANGEFINDER_ENABLED // read the rangefinders void Rover::read_rangefinders(void) { @@ -95,3 +96,4 @@ void Rover::read_rangefinders(void) Log_Write_Depth(); #endif } +#endif diff --git a/Rover/system.cpp b/Rover/system.cpp index 7a687ad27bea73..ef8b77261bff50 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -1,10 +1,3 @@ -/***************************************************************************** -The init_ardupilot function processes everything we need for an in - air restart - We will determine later if we are actually on the ground and process a - ground start in that case. - -*****************************************************************************/ - #include "Rover.h" static void failsafe_check_static() @@ -25,7 +18,9 @@ void Rover::init_ardupilot() rpm_sensor.init(); #endif +#if AP_RSSI_ENABLED rssi.init(); +#endif g2.windvane.init(serial_manager); @@ -35,7 +30,7 @@ void Rover::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED osd.init(); #endif @@ -47,9 +42,11 @@ void Rover::init_ardupilot() airspeed.set_log_bit(MASK_LOG_IMU); #endif +#if AP_RANGEFINDER_ENABLED // initialise rangefinder rangefinder.set_log_rfnd_bit(MASK_LOG_RANGEFINDER); rangefinder.init(ROTATION_NONE); +#endif #if HAL_PROXIMITY_ENABLED // init proximity sensor @@ -73,7 +70,7 @@ void Rover::init_ardupilot() init_rc_in(); // sets up rc channels deadzone g2.motors.init(get_frame_type()); // init motors including setting servo out channels ranges - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); // init wheel encoders g2.wheel_encoder.init(); @@ -126,7 +123,24 @@ void Rover::init_ardupilot() g2.oa.init(); #endif - startup_ground(); + set_mode(mode_initializing, ModeReason::INITIALISED); + + startup_INS(); + +#if AP_MISSION_ENABLED + // initialise mission library + mode_auto.mission.init(); +#if HAL_LOGGING_ENABLED + mode_auto.mission.set_log_start_mission_item_bit(MASK_LOG_CMD); +#endif +#endif + + // initialise AP_Logger library +#if HAL_LOGGING_ENABLED + logger.setVehicle_Startup_Writer( + FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) + ); +#endif Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get()); if (initial_mode == nullptr) { @@ -143,37 +157,13 @@ void Rover::init_ardupilot() // boat should loiter after completing a mission to avoid drifting off if (is_boat()) { - rover.g2.mis_done_behave.set_default(ModeAuto::Mis_Done_Behave::MIS_DONE_BEHAVE_LOITER); + rover.g2.mis_done_behave.set_default(uint8_t(ModeAuto::DoneBehaviour::LOITER)); } // flag that initialisation has completed initialised = true; } -//********************************************************************************* -// This function does all the calibrations, etc. that we need during a ground start -//********************************************************************************* -void Rover::startup_ground(void) -{ - set_mode(mode_initializing, ModeReason::INITIALISED); - - // IMU ground start - //------------------------ - // - - startup_INS_ground(); - - // initialise mission library - mode_auto.mission.init(); - - // initialise AP_Logger library -#if HAL_LOGGING_ENABLED - logger.setVehicle_Startup_Writer( - FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) - ); -#endif -} - // update the ahrs flyforward setting which can allow // the vehicle's movements to be used to estimate heading void Rover::update_ahrs_flyforward() @@ -219,7 +209,7 @@ bool Rover::gcs_mode_enabled(const Mode::Number mode_num) const (uint8_t)Mode::Number::RTL, (uint8_t)Mode::Number::SMART_RTL, (uint8_t)Mode::Number::GUIDED, -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED (uint8_t)Mode::Number::DOCK #endif }; @@ -290,7 +280,7 @@ bool Rover::set_mode(Mode::Number new_mode, ModeReason reason) return rover.set_mode(*mode, reason); } -void Rover::startup_INS_ground(void) +void Rover::startup_INS(void) { gcs().send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle"); hal.scheduler->delay(100); diff --git a/Rover/version.h b/Rover/version.h index b0f269dc5c24e1..891bdcc935430c 100644 --- a/Rover/version.h +++ b/Rover/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduRover V4.6.0-dev" +#define THISFIRMWARE "ArduRover V4.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 6 +#define FW_MINOR 7 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/Rover/wscript b/Rover/wscript index af5233391fc835..29ad6ab6112e32 100644 --- a/Rover/wscript +++ b/Rover/wscript @@ -8,12 +8,9 @@ def build(bld): ap_vehicle=vehicle, ap_libraries=bld.ap_common_vehicle_libraries() + [ 'APM_Control', - 'AP_Arming', 'AP_Mount', 'AP_Navigation', 'AR_WPNav', - 'AP_RCMapper', - 'AP_Beacon', 'AP_AdvancedFailsafe', 'AP_WheelEncoder', 'AP_SmartRTL', diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index 79fdb759b03ac1..5c1efea998d3ea 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -74,7 +74,7 @@ int main(void) flash_init(); -#ifdef STM32H7 +#if defined(STM32H7) && CH_CFG_USE_HEAP check_ecc_errors(); #endif diff --git a/Tools/AP_Bootloader/bl_protocol.cpp b/Tools/AP_Bootloader/bl_protocol.cpp index 9b505664d6c9a5..a270abb81e0319 100644 --- a/Tools/AP_Bootloader/bl_protocol.cpp +++ b/Tools/AP_Bootloader/bl_protocol.cpp @@ -505,8 +505,16 @@ bootloader(unsigned timeout) led_off(LED_ACTIVITY); do { - /* if we have a timeout and the timer has expired, return now */ - if (timeout && !timer[TIMER_BL_WAIT]) { + /* if we have a timeout and the timer has expired and serial forward is not busy, return now */ +#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL) + bool ser_forward_active = update_otg2_serial_forward(); +#endif + if (timeout && !timer[TIMER_BL_WAIT] +#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL) + // do serial forward only when idle + && !ser_forward_active +#endif + ) { return; } diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index c353daa5a87116..325dd047df8d45 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -72,6 +72,11 @@ EXT_HW_RADIOLINK_MINI_PIX 3 # Do not allocate IDs in the range 1000 to 19999 except via a PR # against this file in https://github.com/ArduPilot/ardupilot/tree/master/Tools/AP_Bootloader/board_types.txt +# if you want to reserve a block of IDs, please limit that allocation +# to 10 IDs at a time. + +# please fill gaps rather than adding past ID #7109 + # values starting with AP_ are implemented in the ArduPilot bootloader # https://github.com/ArduPilot/ardupilot/tree/master/Tools/AP_Bootloader # the values come from the APJ_BOARD_ID in the hwdef files here: @@ -103,6 +108,8 @@ AP_HW_JDMINIF405 144 AP_HW_KAKUTEF7_MINI 145 AP_HW_H757I_EVAL 146 AP_HW_F4BY 20 # value due to previous release by vendor +AP_HW_MAZZYSTARDRONE 188 + AP_HW_VRBRAIN_V51 1151 AP_HW_VRBRAIN_V52 1152 AP_HW_VRBRAIN_V54 1154 @@ -111,7 +118,7 @@ AP_HW_VRUBRAIN_V51 1351 AP_HW_F103_PERIPH 1000 AP_HW_CUAV_GPS 1001 AP_HW_OMNIBUSF4 1002 -AP_HW_CUBEBLACK+ 1003 +AP_HW_CUBEBLACKPLUS 1003 AP_HW_F303_PERIPH 1004 AP_HW_ZUBAXGNSS 1005 AP_HW_NIGHTCRAWLER 1006 @@ -187,7 +194,7 @@ AP_HW_SKYSTARSH7HD 1075 AP_HW_PixSurveyA1 1076 AP_HW_AEROFOX_AIRSPEED 1077 AP_HW_ATOMRCF405 1078 -AP_HW_CUBEPILOT_CANMOD 1079 +AP_HW_CUBENODE 1079 AP_HW_AEROFOX_PMU 1080 AP_HW_JHEMCUGF16F405 1081 AP_HW_SPEEDYBEEF4V3 1082 @@ -200,7 +207,7 @@ AP_HW_HolybroCompass 1088 AP_HW_FOXEERH743_V1 1089 AP_HW_PixFlamingoL4R5_V1 1090 -AP_HW_Sierra-TrueNav Pro 1091 +AP_HW_Sierra-TrueNavPro 1091 AP_HW_Sierra-TrueNav 1092 AP_HW_Sierra-TrueNorth 1093 AP_HW_Sierra-TrueSpeed 1094 @@ -273,10 +280,35 @@ AP_HW_MicoAir405Mini 1161 AP_HW_BlitzH7Pro 1162 AP_HW_BlitzF7Mini 1163 AP_HW_BlitzF7 1164 +AP_HW_3DR-ASAUAV 1165 +AP_HW_MicoAir743 1166 +AP_HW_BlitzH7Wing 1168 +AP_HW_SDMODELH7V2 1167 +AP_HW_JHEMCUF405WING 1169 +AP_HW_MatekG474 1170 +AP_HW_PhenixH7_lite 1171 +AP_HW_PhenixH7_Pro 1172 +AP_HW_2RAWH743 1173 +AP_HW_X-MAV-AP-H743V2 1174 +AP_HW_BETAFPV_F4_2-3S_20A 1175 +AP_HW_MicoAir743AIOv1 1176 +AP_HW_CrazyF405 1177 +AP_HW_FlywooF405HD_AIOv2 1180 +AP_HW_FlywooH743Pro 1181 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 +AP_HW_CSKY-PMU 1212 + +AP_HW_MUPilot 1222 + +AP_HW_CBUnmanned-CM405-FC 1301 + +AP_HW_KHA_ETH 1315 + +AP_HW_FlysparkF4 1361 + AP_HW_CUBEORANGE_PERIPH 1400 AP_HW_CUBEBLACK_PERIPH 1401 AP_HW_PIXRACER_PERIPH 1402 @@ -291,8 +323,32 @@ AP_HW_PIXHAWK6X_PERIPH 1408 AP_HW_CUBERED_PERIPH 1409 AP_HW_RadiolinkPIX6 1410 +AP_HW_JHEMCU-H743HD 1411 + +AP_HW_LongbowF405 1422 + +AP_HW_MountainEagleH743 1444 + +AP_HW_StellarF4 1500 +AP_HW_GEPRCF745BTHD 1501 + +AP_HW_HGLRCF405V4 1524 + +AP_HW_F4BY_F427 1530 + +AP_HW_MFT-SEMA100 2000 + +AP_HW_AET-H743-Basic 2024 + AP_HW_SakuraRC-H743 2714 +# IDs 4000-4009 reserved for Karshak Drones +AP_HW_KRSHKF7_MINI 4000 + +# IDs 4200-4220 reserved for HAKRC +AP_HW_HAKRC_F405 4200 +AP_HW_HAKRC_F405Wing 4201 + # IDs 5000-5099 reserved for Carbonix # IDs 5100-5199 reserved for SYPAQ Systems # IDs 5200-5209 reserved for Airvolute @@ -302,6 +358,29 @@ AP_HW_AIRVOLUTE_DCS2 5200 AP_HW_AOCODA-RC-H743DUAL 5210 AP_HW_AOCODA-RC-F405V3 5211 +# IDs 5220-5239 reserved for UAV-DEV GmbH +AP_HW_UAV-DEV-HAT-H7 5220 +AP_HW_UAV-DEV-NucPilot-H7 5221 +AP_HW_UAV-DEV-M10S-L4 5222 +AP_HW_UAV-DEV-F9P-G4 5223 +AP_HW_UAV-DEV-UM982-G4 5224 +AP_HW_UAV-DEV-M20D-G4 5225 +AP_HW_UAV-DEV-Sensorboard-G4 5226 +AP_HW_UAV-DEV-PWM-G4 5227 +AP_HW_UAV-DEV-AUAV-H7 5228 +AP_HW_UAV-DEV-FC-H7 5229 + +# IDs 5240-5249 reserved for TM IT-Systemhaus +AP_HW_TM-SYS-BeastFC 5240 +AP_HW_TM-SYS-Sensornode 5241 +AP_HW_TM-SYS-OpenHDFPV 5242 +AP_HW_TM-SYS-VisualNAV 5243 +AP_HW_TM-SYS-Airspeed 5244 + +# IDs 5250-5269 reserved for Team Black Sheep +AP_HW_TBS_LUCID_H7 5250 +AP_HW_TBS_LUCID_PRO 5251 + #IDs 5301-5399 reserved for Sierra Aerospace AP_HW_Sierra-TrueNavPro-G4 5301 AP_HW_Sierra-TrueNavIC 5302 @@ -318,11 +397,45 @@ AP_HW_Holybro-PMU-F4 5401 AP_HW_Holybro-UM982-G4 5402 AP_HW_Holybro-UM960-H7 5403 AP_HW_Holybro-PERIPH-H7 5404 +AP_HW_Holybro-DroneCAN-Airspeed 5405 +AP_HW_Holybro-KakuteF4-Wing 5406 + +#IDs 5501-5599 reserved for MATEKSYS +AP_HW_MATEKH743SE 5501 + +#IDs 5600-5699 reserved for ZeroOne +AP_HW_ZeroOne_X6 5600 +AP_HW_ZeroOne_PMU 5601 +AP_HW_ZeroOne_GNSS 5602 + +#IDs 5700-5710 reserved for DroneBuild +AP_HW_DroneBuild_G1 5700 +AP_HW_DroneBuild_G2 5701 # IDs 6000-6099 reserved for SpektreWorks +# IDs 6100-6109 reserved for MFE +AP_HW_MFE_PDB_CAN 6100 +AP_HW_MFE_POS3_CAN 6101 +AP_HW_MFE_RTK_CAN 6102 +AP_HW_MFE_AirSpeed_CAN 6103 + # IDs 6600-6699 reserved for Eagle Eye Drones +# IDs 6900-6909 reserved for Easy Aerial + +# IDs 7000-7099 reserved for CUAV +AP_HW_CUAV-7-NANO 7000 + +# IDs 7100-7109 reserved for V-UAV +AP_HW_VUAV-V7pro 7100 + +# please fill gaps in the above ranges rather than adding past ID #7109 + + # OpenDroneID enabled boards. Use 10000 + the base board ID AP_HW_CubeOrange_ODID 10140 AP_HW_Pixhawk6_ODID 10053 + +# do not allocate board IDs above 10,000 for non-ODID boards. +# do not allocate board IDs above 19,999 in this file. diff --git a/Tools/AP_Bootloader/can.cpp b/Tools/AP_Bootloader/can.cpp index 0026ffc9c5bbc5..de1b37227672b4 100644 --- a/Tools/AP_Bootloader/can.cpp +++ b/Tools/AP_Bootloader/can.cpp @@ -50,7 +50,7 @@ static CANConfig cancfg = { // pipelining is not faster when using ChibiOS CAN driver #define FW_UPDATE_PIPELINE_LEN 1 #else -static ChibiOS::CANIface can_iface[HAL_NUM_CAN_IFACES]; +ChibiOS::CANIface can_iface[HAL_NUM_CAN_IFACES]; #endif #ifndef CAN_APP_VERSION_MAJOR @@ -139,7 +139,7 @@ static uint32_t get_random_range(uint16_t range) static void handle_get_node_info(CanardInstance* ins, CanardRxTransfer* transfer) { - uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; uavcan_protocol_GetNodeInfoResponse pkt {}; node_status.uptime_sec = AP_HAL::millis() / 1000U; @@ -429,7 +429,7 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout. node_id_allocation_unique_id_offset = msg.unique_id.len; send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS; - } else { + } else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over) // Allocation complete - copying the allocated node ID from the message canardSetLocalNodeID(ins, msg.node_id); } @@ -747,7 +747,7 @@ bool can_check_update(void) bool ret = false; #if HAL_RAM_RESERVE_START >= 256 struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START; - if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC) { + if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC && comms->my_node_id != 0) { can_set_node_id(comms->my_node_id); fw_update.node_id = comms->server_node_id; for (uint8_t i=0; i= 'A' && a <= 'F') return a - 'A' + 10; @@ -342,7 +342,7 @@ bool flash_from_sd() return false; } - verifier = new ABinVerifier{verify_abin_path}; + verifier = NEW_NOTHROW ABinVerifier{verify_abin_path}; if (!verifier->run()) { goto out; } @@ -354,7 +354,7 @@ bool flash_from_sd() return false; } - flasher = new ABinFlasher{flash_abin_path}; + flasher = NEW_NOTHROW ABinFlasher{flash_abin_path}; if (!flasher->run()) { goto out; } diff --git a/Tools/AP_Bootloader/network.cpp b/Tools/AP_Bootloader/network.cpp index 2a78b199a96047..1d7a312227b87c 100644 --- a/Tools/AP_Bootloader/network.cpp +++ b/Tools/AP_Bootloader/network.cpp @@ -8,6 +8,7 @@ #include #include +#include #include #include @@ -29,6 +30,7 @@ #include #include #include +#include #ifndef AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR #define AP_NETWORKING_BOOTLOADER_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46" @@ -59,6 +61,8 @@ #define MIN(a,b) ((a)<(b)?(a):(b)) +static AP_Networking_CAN mcast_server; + void BL_Network::link_up_cb(void *p) { auto *driver = (BL_Network *)p; @@ -67,6 +71,9 @@ void BL_Network::link_up_cb(void *p) #endif char ipstr[IP4_STR_LEN]; can_printf("IP %s", SocketAPM::inet_addr_to_str(ntohl(driver->thisif->ip_addr.addr), ipstr, sizeof(ipstr))); + + // start mcast CAN server + mcast_server.start((1U<send(header, strlen(header)); if (strncmp(headers, "POST / ", 7) == 0) { - const char *clen = "\r\nContent-Length:"; - const char *p = strstr(headers, clen); + const char *clen1 = "\r\nContent-Length:"; + const char *clen2 = "\r\ncontent-length:"; + const char *p = strstr(headers, clen1); + if (p == nullptr) { + p = strstr(headers, clen2); + } if (p != nullptr) { - p += strlen(clen); + p += strlen(clen1); const uint32_t content_length = atoi(p); handle_post(sock, content_length); delete headers; @@ -554,7 +565,7 @@ void BL_Network::net_request_trampoline(void *ctx) */ void BL_Network::web_server(void) { - auto *listen_socket = new SocketAPM(0); + auto *listen_socket = NEW_NOTHROW SocketAPM(0); listen_socket->bind("0.0.0.0", 80); listen_socket->listen(20); @@ -573,7 +584,7 @@ void BL_Network::web_server(void) continue; } // a new thread for each connection to allow for AJAX - auto *req = new req_context; + auto *req = NEW_NOTHROW req_context; req->driver = this; req->sock = sock; thread_create_alloc(THD_WORKING_AREA_SIZE(2048), @@ -601,7 +612,7 @@ void BL_Network::init() macInit(); - thisif = new netif; + thisif = NEW_NOTHROW netif; net_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(2048), "network", diff --git a/Tools/AP_Bootloader/support.cpp b/Tools/AP_Bootloader/support.cpp index 86d51d35f2a75e..cc720919bdec24 100644 --- a/Tools/AP_Bootloader/support.cpp +++ b/Tools/AP_Bootloader/support.cpp @@ -364,6 +364,17 @@ void thread_sleep_ms(uint32_t ms) } } +void thread_sleep_us(uint32_t us) +{ + while (us > 0) { + // don't sleep more than 65 at a time, to cope with 16 bit + // timer + const uint32_t dt = us > 6500? 6500: us; + chThdSleepMicroseconds(dt); + us -= dt; + } +} + // generate a pulse sequence forever, for debugging void led_pulses(uint8_t npulses) { @@ -445,7 +456,11 @@ void init_uarts(void) #if HAL_USE_SERIAL_USB == TRUE sduObjectInit(&SDU1); sduStart(&SDU1, &serusbcfg1); - +#if HAL_HAVE_DUAL_USB_CDC + sduObjectInit(&SDU2); + sduStart(&SDU2, &serusbcfg2); +#endif + usbDisconnectBus(serusbcfg1.usbp); thread_sleep_ms(1000); usbStart(serusbcfg1.usbp, &usbcfg); @@ -457,7 +472,11 @@ void init_uarts(void) for (const auto &uart : uarts) { #if HAL_USE_SERIAL_USB == TRUE - if (uart == (BaseChannel *)&SDU1) { + if (uart == (BaseChannel *)&SDU1 +#if HAL_HAVE_DUAL_USB_CDC + || uart == (BaseChannel *)&SDU2 +#endif + ) { continue; } #endif @@ -467,13 +486,52 @@ void init_uarts(void) } +#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL) +/* forward serial to OTG2 +Used for devices containing multiple devices in one +*/ +static SerialConfig forward_sercfg; +static uint32_t otg2_serial_deadline_ms; +bool update_otg2_serial_forward() +{ + // get baudrate set on SDU2 and set it on HAL_FORWARD_OTG2_SERIAL if changed + if (forward_sercfg.speed != BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE) { + forward_sercfg.speed = BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE; +#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP) && BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP + forward_sercfg.cr2 = USART_CR2_SWAP; +#endif + sdStart(&BOOTLOADER_FORWARD_OTG2_SERIAL, &forward_sercfg); + } + // check how many bytes are available to read from HAL_FORWARD_OTG2_SERIAL + uint8_t data[SERIAL_BUFFERS_SIZE]; // read upto SERIAL_BUFFERS_SIZE at a time + int n = chnReadTimeout(&SDU2, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE); + if (n > 0) { + // do a blocking write to HAL_FORWARD_OTG2_SERIAL + chnWriteTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, n, TIME_IMMEDIATE); + otg2_serial_deadline_ms = AP_HAL::millis() + 1000; + } + + n = chnReadTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE); + if (n > 0) { + // do a blocking write to SDU2 + chnWriteTimeout(&SDU2, data, n, TIME_IMMEDIATE); + } + + return (AP_HAL::millis() < otg2_serial_deadline_ms); +} +#endif + /* set baudrate on the current port */ void port_setbaud(uint32_t baudrate) { #if HAL_USE_SERIAL_USB == TRUE - if (uarts[last_uart] == (BaseChannel *)&SDU1) { + if (uarts[last_uart] == (BaseChannel *)&SDU1 +#if HAL_HAVE_DUAL_USB_CDC + || uarts[last_uart] == (BaseChannel *)&SDU2 +#endif + ) { // can't set baudrate on USB return; } @@ -486,32 +544,40 @@ void port_setbaud(uint32_t baudrate) } #endif // BOOTLOADER_DEV_LIST -#ifdef STM32H7 +#if defined(STM32H7) && CH_CFG_USE_HEAP /* check if flash has any ECC errors and if it does then erase all of flash */ +#define ECC_CHECK_CHUNK_SIZE (32*sizeof(uint32_t)) void check_ecc_errors(void) { __disable_fault_irq(); + // stm32_flash_corrupt(0x8043200); auto *dma = dmaStreamAlloc(STM32_DMA_STREAM_ID(1, 1), 0, nullptr, nullptr); - uint32_t buf[32]; + + uint32_t *buf = (uint32_t*)malloc_dma(ECC_CHECK_CHUNK_SIZE); + + if (buf == nullptr) { + // DMA'ble memory not available + return; + } uint32_t ofs = 0; while (ofs < BOARD_FLASH_SIZE*1024) { - if (FLASH->SR1 != 0) { + if (FLASH->SR1 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) { break; } #if BOARD_FLASH_SIZE > 1024 - if (FLASH->SR2 != 0) { + if (FLASH->SR2 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) { break; } #endif dmaStartMemCopy(dma, STM32_DMA_CR_PL(0) | STM32_DMA_CR_PSIZE_BYTE | STM32_DMA_CR_MSIZE_BYTE, - ofs+(uint8_t*)FLASH_BASE, buf, sizeof(buf)); + ofs+(uint8_t*)FLASH_BASE, buf, ECC_CHECK_CHUNK_SIZE); dmaWaitCompletion(dma); - ofs += sizeof(buf); + ofs += ECC_CHECK_CHUNK_SIZE; } dmaStreamFree(dma); @@ -525,5 +591,5 @@ void check_ecc_errors(void) } __enable_fault_irq(); } -#endif // STM32H7 +#endif // defined(STM32H7) && CH_CFG_USE_HEAP diff --git a/Tools/AP_Bootloader/support.h b/Tools/AP_Bootloader/support.h index 1eebcd22fe705f..e96137bf8dfae5 100644 --- a/Tools/AP_Bootloader/support.h +++ b/Tools/AP_Bootloader/support.h @@ -1,5 +1,7 @@ #pragma once +#include + #define LED_ACTIVITY 1 #define LED_BOOTLOADER 2 @@ -18,7 +20,9 @@ int16_t cin(unsigned timeout_ms); int cin_word(uint32_t *wp, unsigned timeout_ms); void cout(uint8_t *data, uint32_t len); void port_setbaud(uint32_t baudrate); - +#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL) +bool update_otg2_serial_forward(void); +#endif void flash_init(); uint32_t flash_func_read_word(uint32_t offset); @@ -46,10 +50,13 @@ void led_off(unsigned led); void led_toggle(unsigned led); void thread_sleep_ms(uint32_t ms); +void thread_sleep_us(uint32_t us); void custom_startup(void); +#if defined(STM32H7) && CH_CFG_USE_HEAP void check_ecc_errors(void); +#endif // printf to debug uart (or USB) extern "C" { diff --git a/Tools/AP_Bootloader/wscript b/Tools/AP_Bootloader/wscript index 19c29da5dfc9ea..172db176261234 100644 --- a/Tools/AP_Bootloader/wscript +++ b/Tools/AP_Bootloader/wscript @@ -21,6 +21,7 @@ def build(bld): 'AP_HAL', 'AP_Networking', 'AP_ROMFS', + 'AP_Common', ]) # build external libcanard library diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index f02037e5a2dc26..f9479d285a1eca 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -168,6 +168,15 @@ void AP_Periph_FW::init() baro.init(); #endif +#ifdef HAL_PERIPH_ENABLE_IMU + if (g.imu_sample_rate) { + imu.init(g.imu_sample_rate); + if (imu.get_accel_count() > 0 || imu.get_gyro_count() > 0) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Periph_FW::can_imu_update, void), "IMU_UPDATE", 16384, AP_HAL::Scheduler::PRIORITY_CAN, 0); + } + } +#endif + #ifdef HAL_PERIPH_ENABLE_BATTERY battery_lib.init(); #endif @@ -208,7 +217,7 @@ void AP_Periph_FW::init() #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && (HAL_USE_I2C == TRUE) const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01); if (pins_enabled) { ChibiOS::I2CBus::set_bus_to_floating(0); @@ -227,15 +236,20 @@ void AP_Periph_FW::init() #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - if (rangefinder.get_type(0) != RangeFinder::Type::NONE) { - if (g.rangefinder_port >= 0) { + bool have_rangefinder = false; + for (uint8_t i=0; i= 0)) { // init uart for serial rangefinders - auto *uart = hal.serial(g.rangefinder_port); + auto *uart = hal.serial(g.rangefinder_port[i]); if (uart != nullptr) { - uart->begin(g.rangefinder_baud); - serial_manager.set_protocol_and_baud(g.rangefinder_port, AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud); + uart->begin(g.rangefinder_baud[i]); + serial_manager.set_protocol_and_baud(g.rangefinder_port[i], AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud[i]); + have_rangefinder = true; } } + } + if (have_rangefinder) { + // Can only call rangefinder init once, subsequent inits are blocked rangefinder.init(ROTATION_NONE); } #endif @@ -263,7 +277,7 @@ void AP_Periph_FW::init() for (uint8_t i = 0; i < ESC_NUMBERS; i++) { const uint8_t port = g.esc_serial_port[i]; if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports - apd_esc_telem[i] = new ESC_APD_Telem (hal.serial(port), g.pole_count[i]); + apd_esc_telem[i] = NEW_NOTHROW ESC_APD_Telem (hal.serial(port), g.pole_count[i]); } } #endif @@ -419,7 +433,14 @@ void AP_Periph_FW::update() hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature()); #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - hal.serial(0)->printf("RNG %u %ucm\n", rangefinder.num_sensors(), rangefinder.distance_cm_orient(ROTATION_NONE)); + hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors()); + for (uint8_t i=0; iprintf("RNG %u %ucm\n", i, uint16_t(backend->distance()*100)); + } #endif hal.scheduler->delay(1); #endif @@ -596,7 +617,9 @@ void AP_Periph_FW::prepare_reboot() // delay to give the ACK a chance to get out, the LEDs to flash, // the IO board safety to be forced on, the parameters to flush, + hal.scheduler->expect_delay_ms(100); hal.scheduler->delay(40); + hal.scheduler->expect_delay_ms(0); } /* @@ -604,6 +627,7 @@ void AP_Periph_FW::prepare_reboot() */ void AP_Periph_FW::reboot(bool hold_in_bootloader) { + prepare_reboot(); hal.scheduler->reboot(hold_in_bootloader); } diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 95d32af7936fff..0cbf5f419e792d 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -6,12 +6,14 @@ #include #include #include +#include #include "SRV_Channel/SRV_Channel.h" #include #include #include #include #include +#include #include #include #include @@ -90,6 +92,10 @@ #endif #endif +#if defined(HAL_PERIPH_ENABLE_RPM_STREAM) && !defined(HAL_PERIPH_ENABLE_RPM) + #error "HAL_PERIPH_ENABLE_RPM_STREAM requires HAL_PERIPH_ENABLE_RPM" +#endif + #ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED #define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT) #endif @@ -168,7 +174,13 @@ class AP_Periph_FW { void send_relposheading_msg(); void can_baro_update(); void can_airspeed_update(); +#ifdef HAL_PERIPH_ENABLE_IMU + void can_imu_update(); +#endif + +#ifdef HAL_PERIPH_ENABLE_RANGEFINDER void can_rangefinder_update(); +#endif void can_battery_update(); void can_battery_send_cells(uint8_t instance); void can_proximity_update(); @@ -223,10 +235,19 @@ class AP_Periph_FW { AP_Baro baro; #endif +#ifdef HAL_PERIPH_ENABLE_IMU + AP_InertialSensor imu; +#endif + #ifdef HAL_PERIPH_ENABLE_RPM AP_RPM rpm_sensor; uint32_t rpm_last_update_ms; +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + void rpm_sensor_send(); + uint32_t rpm_last_send_ms; + uint8_t rpm_last_sent_index; #endif +#endif // HAL_PERIPH_ENABLE_RPM #ifdef HAL_PERIPH_ENABLE_BATTERY void handle_battery_failsafe(const char* type_str, const int8_t action) { } @@ -279,7 +300,8 @@ class AP_Periph_FW { #ifdef HAL_PERIPH_ENABLE_RANGEFINDER RangeFinder rangefinder; - uint32_t last_sample_ms; + uint32_t last_rangefinder_update_ms; + uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES]; #endif #ifdef HAL_PERIPH_ENABLE_PROXIMITY @@ -321,9 +343,15 @@ class AP_Periph_FW { #ifdef HAL_PERIPH_ENABLE_RC_OUT #if HAL_WITH_ESC_TELEM AP_ESC_Telem esc_telem; + uint8_t get_motor_number(const uint8_t esc_number) const; uint32_t last_esc_telem_update_ms; void esc_telem_update(); uint32_t esc_telem_update_period_ms; +#if AP_EXTENDED_ESC_TELEM_ENABLED + void esc_telem_extended_update(const uint32_t &now_ms); + uint32_t last_esc_telem_extended_update; + uint8_t last_esc_telem_extended_sent_id; +#endif #endif SRV_Channels servo_channels; @@ -451,7 +479,16 @@ class AP_Periph_FW { bool debug_option_is_set(const DebugOptions option) const { return (uint8_t(g.debug.get()) & (1U< 1 + // @Param: RNGFND2_BAUDRATE + // @DisplayName: Rangefinder serial baudrate + // @Description: Rangefinder 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 + GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT), + + // @Param: RNGFND2_PORT + // @DisplayName: Rangefinder Serial Port + // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + // @RebootRequired: True + GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1), +#endif // @Param: RNGFND_MAX_RATE // @DisplayName: Rangefinder max rate @@ -383,6 +407,15 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Path: ../libraries/SRV_Channel/SRV_Channels.cpp GOBJECT(servo_channels, "OUT", SRV_Channels), + // @Param: ESC_RATE + // @DisplayName: ESC Update Rate + // @Description: Rate in Hz that ESC PWM outputs (function is MotorN) will update at + // @Units: Hz + // @Range: 50 400 + // @Increment: 1 + // @User: Advanced + GSCALAR(esc_rate, "ESC_RATE", 400), // effective Copter and QuadPlane default after clamping + // @Param: ESC_PWM_TYPE // @DisplayName: Output PWM type // @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output @@ -661,6 +694,49 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0), #endif + // @Param: OPTIONS + // @DisplayName: AP Periph Options + // @Description: Bitmask of AP Periph Options + // @Bitmask: 0: Enable continuous sensor probe + // @User: Standard + GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS), + +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + // @Param: RPM_MSG_RATE + // @DisplayName: RPM sensor message rate + // @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn. + // @Units: Hz + // @Range: 0 200 + // @Increment: 1 + // @User: Standard + GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0), +#endif + +#if AP_EXTENDED_ESC_TELEM_ENABLED && HAL_WITH_ESC_TELEM + // @Param: ESC_EXT_TLM_RATE + // @DisplayName: ESC Extended telemetry message rate + // @Description: This is the rate at which extended ESC Telemetry will be sent across the CAN bus for each ESC + // @Units: Hz + // @Range: 0 50 + // @Increment: 1 + // @User: Advanced + GSCALAR(esc_extended_telem_rate, "ESC_EXT_TLM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT / 10), +#endif + + +#ifdef HAL_PERIPH_ENABLE_IMU + // @Param: IMU_SAMPLE_RATE + // @DisplayName: IMU Sample Rate + // @Description: IMU Sample Rate + // @Range: 0 1000 + // @User: Standard + GSCALAR(imu_sample_rate, "INS_SAMPLE_RATE", 0), + + // @Group: INS + // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp + GOBJECT(imu, "INS", AP_InertialSensor), +#endif + AP_VAREND }; diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 94ac49b39ac05c..c2df5d27f0d5ea 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -25,7 +25,7 @@ class Parameters { k_param_airspeed, k_param_rangefinder, k_param_flash_bootloader, - k_param_rangefinder_baud, + k_param_rangefinder_baud0, k_param_adsb_baudrate, k_param_hardpoint_id, k_param_hardpoint_rate, @@ -36,7 +36,7 @@ class Parameters { k_param_serial_number, k_param_adsb_port, k_param_servo_channels, - k_param_rangefinder_port, + k_param_rangefinder_port0, k_param_gps_port, k_param_msp_port, k_param_notify, @@ -91,6 +91,14 @@ class Parameters { k_param_serial_options, k_param_relay, k_param_temperature_msg_rate, + k_param_rangefinder_baud1, + k_param_rangefinder_port1, + k_param_options, + k_param_rpm_msg_rate, + k_param_esc_rate, + k_param_esc_extended_telem_rate, + k_param_imu_sample_rate, + k_param_imu, }; AP_Int16 format_version; @@ -119,8 +127,8 @@ class Parameters { #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - AP_Int32 rangefinder_baud; - AP_Int8 rangefinder_port; + AP_Int32 rangefinder_baud[RANGEFINDER_MAX_INSTANCES]; + AP_Int8 rangefinder_port[RANGEFINDER_MAX_INSTANCES]; AP_Int16 rangefinder_max_rate; #endif @@ -170,6 +178,7 @@ class Parameters { #endif #ifdef HAL_PERIPH_ENABLE_RC_OUT + AP_Int16 esc_rate; AP_Int8 esc_pwm_type; AP_Int16 esc_command_timeout_ms; #if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED @@ -177,6 +186,9 @@ class Parameters { #endif #if HAL_WITH_ESC_TELEM AP_Int32 esc_telem_rate; +#if AP_EXTENDED_ESC_TELEM_ENABLED + AP_Int16 esc_extended_telem_rate; +#endif #endif #endif @@ -201,6 +213,10 @@ class Parameters { AP_Int8 efi_port; #endif +#ifdef HAL_PERIPH_ENABLE_IMU + AP_Int16 imu_sample_rate; +#endif + #if HAL_PERIPH_CAN_MIRROR AP_Int8 can_mirror_ports; #endif // HAL_PERIPH_CAN_MIRROR @@ -209,6 +225,10 @@ class Parameters { AP_Int8 temperature_msg_rate; #endif +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + AP_Int16 rpm_msg_rate; +#endif + #if HAL_CANFD_SUPPORTED AP_Int8 can_fdmode; AP_Int8 can_fdbaudrate[HAL_NUM_CAN_IFACES]; @@ -216,6 +236,8 @@ class Parameters { static constexpr uint8_t can_fdmode = 0; #endif + AP_Int32 options; + AP_Int8 can_terminate[HAL_NUM_CAN_IFACES]; AP_Int8 node_stats; diff --git a/Tools/AP_Periph/Web/scripts/pppgw_webui.lua b/Tools/AP_Periph/Web/scripts/pppgw_webui.lua index 3390a89dc4bbdb..58cf3590bad51b 100644 --- a/Tools/AP_Periph/Web/scripts/pppgw_webui.lua +++ b/Tools/AP_Periph/Web/scripts/pppgw_webui.lua @@ -2,6 +2,11 @@ example script to test lua socket API --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil +---@diagnostic disable: redundant-parameter +---@diagnostic disable: undefined-field + PARAM_TABLE_KEY = 47 PARAM_TABLE_PREFIX = "WEB_" @@ -216,6 +221,7 @@ local DYNAMIC_PAGES = { IP Netmask Gateway + MCU Temperature ]] } @@ -933,6 +939,9 @@ local function Client(_sock, _idx) function self.remove() DEBUG(string.format("%u: removing client OFFSET=%u", idx, offset)) + if self.closed then + return + end sock:close() self.closed = true end diff --git a/Tools/AP_Periph/adsb.cpp b/Tools/AP_Periph/adsb.cpp index 1a1229826bee6e..917beffb91948f 100644 --- a/Tools/AP_Periph/adsb.cpp +++ b/Tools/AP_Periph/adsb.cpp @@ -138,7 +138,7 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg) pkt.vertical_velocity_valid = (msg.flags & 0x0080) != 0; pkt.baro_valid = (msg.flags & 0x0100) != 0; - uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE]; uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE, diff --git a/Tools/AP_Periph/airspeed.cpp b/Tools/AP_Periph/airspeed.cpp index 17a4da160731c5..71cc910c66acdf 100644 --- a/Tools/AP_Periph/airspeed.cpp +++ b/Tools/AP_Periph/airspeed.cpp @@ -21,7 +21,7 @@ void AP_Periph_FW::can_airspeed_update(void) return; } #if AP_PERIPH_PROBE_CONTINUOUS - if (!airspeed.healthy()) { + if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && !airspeed.healthy()) { uint32_t now = AP_HAL::millis(); static uint32_t last_probe_ms; if (now - last_probe_ms >= 1000) { @@ -72,7 +72,7 @@ void AP_Periph_FW::can_airspeed_update(void) } #endif - uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_MAX_SIZE]; uint16_t total_size = uavcan_equipment_air_data_RawAirData_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_SIGNATURE, diff --git a/Tools/AP_Periph/baro.cpp b/Tools/AP_Periph/baro.cpp index a1b1bc35bc1788..61c296cd137fd5 100644 --- a/Tools/AP_Periph/baro.cpp +++ b/Tools/AP_Periph/baro.cpp @@ -34,7 +34,7 @@ void AP_Periph_FW::can_baro_update(void) pkt.static_pressure = press; pkt.static_pressure_variance = 0; // should we make this a parameter? - uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_MAX_SIZE]; uint16_t total_size = uavcan_equipment_air_data_StaticPressure_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_SIGNATURE, @@ -49,7 +49,7 @@ void AP_Periph_FW::can_baro_update(void) pkt.static_temperature = C_TO_KELVIN(temp); pkt.static_temperature_variance = 0; // should we make this a parameter? - uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE]; uint16_t total_size = uavcan_equipment_air_data_StaticTemperature_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_SIGNATURE, diff --git a/Tools/AP_Periph/batt_balance.cpp b/Tools/AP_Periph/batt_balance.cpp index 86c7c7a11cd7c4..e7869e01b4f008 100644 --- a/Tools/AP_Periph/batt_balance.cpp +++ b/Tools/AP_Periph/batt_balance.cpp @@ -80,7 +80,7 @@ void AP_Periph_FW::batt_balance_update() // allocate cell sources if needed if (battery_balance.cells == nullptr) { - battery_balance.cells = new AP_HAL::AnalogSource*[ncell]; + battery_balance.cells = NEW_NOTHROW AP_HAL::AnalogSource*[ncell]; if (battery_balance.cells == nullptr) { return; } @@ -98,8 +98,8 @@ void AP_Periph_FW::batt_balance_update() // allocate space for the packet. This is a large // packet that won't fit on the stack, so dynamically allocate - auto *pkt = new ardupilot_equipment_power_BatteryInfoAux; - uint8_t *buffer = new uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE]; + auto *pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux; + uint8_t *buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE]; if (pkt == nullptr || buffer == nullptr) { delete pkt; delete [] buffer; diff --git a/Tools/AP_Periph/battery.cpp b/Tools/AP_Periph/battery.cpp index 8f07834d22e66c..942e5b2136d468 100644 --- a/Tools/AP_Periph/battery.cpp +++ b/Tools/AP_Periph/battery.cpp @@ -67,7 +67,7 @@ void AP_Periph_FW::can_battery_update(void) pkt.model_name.len = strnlen((char*)pkt.model_name.data, sizeof(pkt.model_name.data)); #endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME) - uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE]; const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE, @@ -90,8 +90,8 @@ void AP_Periph_FW::can_battery_send_cells(uint8_t instance) { // allocate space for the packet. This is a large // packet that won't fit on the stack, so dynamically allocate - auto* pkt = new ardupilot_equipment_power_BatteryInfoAux; - uint8_t* buffer = new uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE]; + auto* pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux; + uint8_t* buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE]; if (pkt == nullptr || buffer == nullptr) { delete pkt; delete [] buffer; diff --git a/Tools/AP_Periph/buzzer.cpp b/Tools/AP_Periph/buzzer.cpp index c5285e3612d375..a683f2e0b4e868 100644 --- a/Tools/AP_Periph/buzzer.cpp +++ b/Tools/AP_Periph/buzzer.cpp @@ -26,7 +26,8 @@ void AP_Periph_FW::handle_beep_command(CanardInstance* canard_instance, CanardRx if (!initialised) { initialised = true; hal.rcout->init(); - hal.util->toneAlarm_init(AP_Notify::Notify_Buzz_Builtin); + // just one buzzer type supported: + hal.util->toneAlarm_init(uint8_t(AP_Notify::BuzzerType::BUILTIN)); } buzzer_start_ms = AP_HAL::millis(); buzzer_len_ms = req.duration*1000; diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 80ae6fbc4fc9c2..55ceefc9d87c5b 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -125,10 +125,7 @@ HAL_GPIO_PIN_TERMCAN1 }; #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) -#ifndef HAL_CAN_DEFAULT_NODE_ID -#define HAL_CAN_DEFAULT_NODE_ID CANARD_BROADCAST_NODE_ID -#endif -uint8_t PreferredNodeID = HAL_CAN_DEFAULT_NODE_ID; +uint8_t user_set_node_id = HAL_CAN_DEFAULT_NODE_ID; #ifndef AP_PERIPH_PROBE_CONTINUOUS #define AP_PERIPH_PROBE_CONTINUOUS 0 @@ -185,7 +182,7 @@ static void readUniqueID(uint8_t* out_uid) void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance, CanardRxTransfer* transfer) { - uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; uavcan_protocol_GetNodeInfoResponse pkt {}; node_status.uptime_sec = AP_HAL::millis() / 1000U; @@ -324,7 +321,7 @@ void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRx pkt.name.len = strnlen((char *)pkt.name.data, sizeof(pkt.name.data)); } - uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE]; uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout()); canard_respond(canard_instance, @@ -373,7 +370,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C pkt.ok = true; - uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE]; uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout()); canard_respond(canard_instance, @@ -406,7 +403,7 @@ void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len); comms->my_node_id = canardGetLocalNodeID(canard_instance); - uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE]; uavcan_protocol_file_BeginFirmwareUpdateResponse reply {}; reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; @@ -472,7 +469,7 @@ void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, C 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 { + } else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over) // Allocation complete - copying the allocated node ID from the message canardSetLocalNodeID(canard_instance, msg.node_id); printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id); @@ -753,7 +750,7 @@ void AP_Periph_FW::can_safety_button_update(void) pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY; pkt.press_time = counter; - uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE]; uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout()); canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE, @@ -1058,6 +1055,7 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature, uint16_t payload_len, uint8_t iface_mask) { + WITH_SEMAPHORE(canard_broadcast_semaphore); const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID; if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { return false; @@ -1550,7 +1548,7 @@ bool AP_Periph_FW::can_do_dna() // Structure of the request is documented in the DSDL definition // See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1]; - allocation_request[0] = (uint8_t)(PreferredNodeID << 1U); + allocation_request[0] = 0; // we are only called if the user has not set an ID, so request any ID if (dronecan.node_id_allocation_unique_id_offset == 0) { allocation_request[0] |= 1; // First part of unique ID @@ -1590,7 +1588,7 @@ void AP_Periph_FW::can_start() node_status.uptime_sec = AP_HAL::millis() / 1000U; if (g.can_node >= 0 && g.can_node < 128) { - PreferredNodeID = g.can_node; + user_set_node_id = g.can_node; } #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) @@ -1622,15 +1620,15 @@ void AP_Periph_FW::can_start() for (uint8_t i=0; i (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE); + instances[i].mirror_queue = NEW_NOTHROW ObjectBuffer (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE); } #endif //HAL_PERIPH_CAN_MIRROR #if HAL_NUM_CAN_IFACES >= 2 @@ -1662,14 +1660,28 @@ void AP_Periph_FW::can_start() canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool), onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, this); - if (PreferredNodeID != CANARD_BROADCAST_NODE_ID) { - canardSetLocalNodeID(&dronecan.canard, PreferredNodeID); + if (user_set_node_id != CANARD_BROADCAST_NODE_ID) { + canardSetLocalNodeID(&dronecan.canard, user_set_node_id); } } #ifdef HAL_PERIPH_ENABLE_RC_OUT #if HAL_WITH_ESC_TELEM +// try to map the ESC number to a motor number. This is needed +// for when we have multiple CAN nodes, one for each ESC +uint8_t AP_Periph_FW::get_motor_number(const uint8_t esc_number) const +{ + const auto *channel = SRV_Channels::srv_channel(esc_number); + // try to map the ESC number to a motor number. This is needed + // for when we have multiple CAN nodes, one for each ESC + if (channel == nullptr) { + return esc_number; + } + const int8_t motor_num = channel->get_motor_num(); + return (motor_num == -1) ? esc_number : motor_num; +} + /* send ESC status packets based on AP_ESC_Telem */ @@ -1681,15 +1693,8 @@ void AP_Periph_FW::esc_telem_update() mask &= ~(1U<get_motor_num(); - pkt.esc_index = motor_num==-1? i:motor_num; - } + pkt.esc_index = get_motor_number(i); + if (!esc_telem.get_voltage(i, pkt.voltage)) { pkt.voltage = nan; } @@ -1708,10 +1713,17 @@ void AP_Periph_FW::esc_telem_update() if (esc_telem.get_raw_rpm(i, rpm)) { pkt.rpm = rpm; } - pkt.power_rating_pct = 0; + +#if AP_EXTENDED_ESC_TELEM_ENABLED + uint8_t power_rating_pct; + if (esc_telem.get_power_percentage(i, power_rating_pct)) { + pkt.power_rating_pct = power_rating_pct; + } +#endif + pkt.error_count = 0; - uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE]; uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, @@ -1722,6 +1734,73 @@ void AP_Periph_FW::esc_telem_update() } #endif // HAL_WITH_ESC_TELEM +#if AP_EXTENDED_ESC_TELEM_ENABLED +void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms) +{ + if (g.esc_extended_telem_rate <= 0) { + // Not configured to send + return; + } + + uint32_t mask = esc_telem.get_active_esc_mask(); + if (mask == 0) { + // No ESCs to report + return; + } + + // ESCs are sent in turn to minimise used bandwidth, to make the rate param match the status message we multiply + // the period such that the param gives the per-esc rate + const uint32_t update_period_ms = 1000 / constrain_int32(g.esc_extended_telem_rate.get() * __builtin_popcount(mask), 1, 1000); + if (now_ms - last_esc_telem_extended_update < update_period_ms) { + // Too soon! + return; + } + last_esc_telem_extended_update = now_ms; + + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + // Send each ESC in turn + const uint8_t index = (last_esc_telem_extended_sent_id + 1 + i) % ESC_TELEM_MAX_ESCS; + + if ((mask & (1U << index)) == 0) { + // Not enabled + continue; + } + + uavcan_equipment_esc_StatusExtended pkt {}; + + // Only send if we have data + bool have_data = false; + + int16_t motor_temp_cdeg; + if (esc_telem.get_motor_temperature(index, motor_temp_cdeg)) { + // Convert from centi-degrees to degrees + pkt.motor_temperature_degC = motor_temp_cdeg * 0.01; + have_data = true; + } + + have_data |= esc_telem.get_input_duty(index, pkt.input_pct); + have_data |= esc_telem.get_output_duty(index, pkt.output_pct); + have_data |= esc_telem.get_flags(index, pkt.status_flags); + + if (have_data) { + pkt.esc_index = get_motor_number(index); + + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE]; + const uint16_t total_size = uavcan_equipment_esc_StatusExtended_encode(&pkt, buffer, !canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE, + UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + + last_esc_telem_extended_sent_id = index; + break; + } +} +#endif + #ifdef HAL_PERIPH_ENABLE_ESC_APD void AP_Periph_FW::apd_esc_telem_update() { @@ -1744,7 +1823,7 @@ void AP_Periph_FW::apd_esc_telem_update() pkt.power_rating_pct = t.power_rating_pct; pkt.error_count = t.error_count; - uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE]; uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, @@ -1848,6 +1927,9 @@ void AP_Periph_FW::can_update() #endif #ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE temperature_sensor_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + rpm_sensor_send(); #endif } const uint32_t now_us = AP_HAL::micros(); @@ -1858,12 +1940,15 @@ void AP_Periph_FW::can_update() // allow for user enabling/disabling CANFD at runtime dronecan.canard.tao_disabled = g.can_fdmode == 1; #endif - - processTx(); - processRx(); + { + WITH_SEMAPHORE(canard_broadcast_semaphore); + processTx(); + processRx(); #if HAL_PERIPH_CAN_MIRROR - processMirror(); + processMirror(); #endif // HAL_PERIPH_CAN_MIRROR + + } } } @@ -1910,7 +1995,7 @@ void can_vprintf(uint8_t severity, const char *fmt, va_list ap) memcpy(pkt.text.data, &buffer_data[buffer_offset], pkt.text.len); buffer_offset += pkt.text.len; - uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {}; + uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE]; const uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer_packet, !periph.canfdout()); periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE, @@ -1922,7 +2007,7 @@ void can_vprintf(uint8_t severity, const char *fmt, va_list ap) #else uavcan_protocol_debug_LogMessage pkt {}; - uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE]; uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap); pkt.level.value = level; pkt.text.len = MIN(n, sizeof(pkt.text.data)); diff --git a/Tools/AP_Periph/compass.cpp b/Tools/AP_Periph/compass.cpp index da5d230776115a..06c0aae8bed121 100644 --- a/Tools/AP_Periph/compass.cpp +++ b/Tools/AP_Periph/compass.cpp @@ -20,6 +20,8 @@ #define AP_PERIPH_MAG_HIRES 0 #endif +extern const AP_HAL::HAL &hal; + /* update CAN magnetometer */ @@ -40,7 +42,7 @@ void AP_Periph_FW::can_mag_update(void) compass.read(); #if AP_PERIPH_PROBE_CONTINUOUS - if (compass.get_count() == 0) { + if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && (compass.get_count() == 0)) { static uint32_t last_probe_ms; uint32_t now = AP_HAL::millis(); if (now - last_probe_ms >= 1000) { @@ -68,7 +70,7 @@ void AP_Periph_FW::can_mag_update(void) pkt.magnetic_field_ga[i] = field_Ga[i]; } - uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_MAX_SIZE]; uint16_t total_size = uavcan_equipment_ahrs_MagneticFieldStrength_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_SIGNATURE, @@ -84,7 +86,7 @@ void AP_Periph_FW::can_mag_update(void) pkt.magnetic_field_ga[i] = field_Ga[i]; } - uint8_t buffer[DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_MAX_SIZE] {}; + uint8_t buffer[DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_MAX_SIZE]; uint16_t total_size = dronecan_sensors_magnetometer_MagneticFieldStrengthHiRes_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(DRONECAN_SENSORS_MAGNETOMETER_MAGNETICFIELDSTRENGTHHIRES_SIGNATURE, diff --git a/Tools/AP_Periph/efi.cpp b/Tools/AP_Periph/efi.cpp index d1bb114cf633d7..84d0eb3ffb752b 100644 --- a/Tools/AP_Periph/efi.cpp +++ b/Tools/AP_Periph/efi.cpp @@ -193,7 +193,7 @@ void AP_Periph_FW::can_efi_update(void) 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] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE]; const uint16_t total_size = uavcan_equipment_ice_reciprocating_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_SIGNATURE, diff --git a/Tools/AP_Periph/esc_apd_telem.cpp b/Tools/AP_Periph/esc_apd_telem.cpp index ed438d60f36c5d..e7173bdca9e83c 100644 --- a/Tools/AP_Periph/esc_apd_telem.cpp +++ b/Tools/AP_Periph/esc_apd_telem.cpp @@ -17,8 +17,9 @@ extern const AP_HAL::HAL& hal; #define TELEM_LEN 0x16 ESC_APD_Telem::ESC_APD_Telem (AP_HAL::UARTDriver *_uart, float num_poles) : - pole_count(num_poles), - uart(_uart) { + uart(_uart), + pole_count(num_poles) +{ uart->begin(115200); } diff --git a/Tools/AP_Periph/gps.cpp b/Tools/AP_Periph/gps.cpp index f185f709a07207..3eced2d6e19b9d 100644 --- a/Tools/AP_Periph/gps.cpp +++ b/Tools/AP_Periph/gps.cpp @@ -159,7 +159,7 @@ void AP_Periph_FW::can_gps_update(void) check_float16_range(pkt.covariance.data, pkt.covariance.len); - uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE]; uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE, @@ -177,7 +177,7 @@ void AP_Periph_FW::can_gps_update(void) aux.hdop = gps.get_hdop() * 0.01; aux.vdop = gps.get_vdop() * 0.01; - uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE]; uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_AUXILIARY_SIGNATURE, UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID, @@ -204,7 +204,7 @@ void AP_Periph_FW::can_gps_update(void) status.error_codes = error_codes; } - uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE]; const uint16_t total_size = ardupilot_gnss_Status_encode(&status, buffer, !canfdout()); canard_broadcast(ARDUPILOT_GNSS_STATUS_SIGNATURE, ARDUPILOT_GNSS_STATUS_ID, @@ -226,7 +226,7 @@ void AP_Periph_FW::can_gps_update(void) heading.heading_accuracy_valid = is_positive(yaw_acc_deg); heading.heading_rad = radians(yaw_deg); heading.heading_accuracy_rad = radians(yaw_acc_deg); - uint8_t buffer[ARDUPILOT_GNSS_HEADING_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_GNSS_HEADING_MAX_SIZE]; const uint16_t total_size = ardupilot_gnss_Heading_encode(&heading, buffer, !canfdout()); canard_broadcast(ARDUPILOT_GNSS_HEADING_SIGNATURE, ARDUPILOT_GNSS_HEADING_ID, @@ -271,7 +271,7 @@ void AP_Periph_FW::send_moving_baseline_msg() mbldata.data.len = n; memcpy(mbldata.data.data, data, n); - uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE]; const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout()); canard_broadcast(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, @@ -295,8 +295,8 @@ void AP_Periph_FW::send_relposheading_msg() { float relative_down_pos; float reported_heading_acc; uint32_t curr_timestamp = 0; - gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc); - if (last_relposheading_ms == curr_timestamp) { + if (!gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc) || + last_relposheading_ms == curr_timestamp) { return; } last_relposheading_ms = curr_timestamp; @@ -307,7 +307,7 @@ void AP_Periph_FW::send_relposheading_msg() { relpos.relative_down_pos_m = relative_down_pos; relpos.reported_heading_acc_deg = reported_heading_acc; relpos.reported_heading_acc_available = !is_zero(relpos.reported_heading_acc_deg); - uint8_t buffer[ARDUPILOT_GNSS_RELPOSHEADING_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_GNSS_RELPOSHEADING_MAX_SIZE]; const uint16_t total_size = ardupilot_gnss_RelPosHeading_encode(&relpos, buffer, !canfdout()); canard_broadcast(ARDUPILOT_GNSS_RELPOSHEADING_SIGNATURE, ARDUPILOT_GNSS_RELPOSHEADING_ID, diff --git a/Tools/AP_Periph/hardpoint.cpp b/Tools/AP_Periph/hardpoint.cpp index c60d64ca815553..59279825b266d6 100644 --- a/Tools/AP_Periph/hardpoint.cpp +++ b/Tools/AP_Periph/hardpoint.cpp @@ -53,7 +53,7 @@ void AP_Periph_FW::pwm_hardpoint_update() cmd.hardpoint_id = g.hardpoint_id; cmd.command = value; - uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE]; uint16_t total_size = uavcan_equipment_hardpoint_Command_encode(&cmd, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE, UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID, diff --git a/Tools/AP_Periph/hwing_esc.cpp b/Tools/AP_Periph/hwing_esc.cpp index a1e2d4a4721078..6ffb36f4eb5b82 100644 --- a/Tools/AP_Periph/hwing_esc.cpp +++ b/Tools/AP_Periph/hwing_esc.cpp @@ -164,7 +164,7 @@ void AP_Periph_FW::hwesc_telem_update() pkt.power_rating_pct = t.phase_current; pkt.error_count = t.error_count; - uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE]; uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, diff --git a/Tools/AP_Periph/imu.cpp b/Tools/AP_Periph/imu.cpp new file mode 100644 index 00000000000000..c0c5aaf40128d7 --- /dev/null +++ b/Tools/AP_Periph/imu.cpp @@ -0,0 +1,50 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_IMU +#include + +extern const AP_HAL::HAL &hal; + +/* + update CAN magnetometer + */ +void AP_Periph_FW::can_imu_update(void) +{ + while (true) { + // sleep for a bit to avoid flooding the CPU + hal.scheduler->delay_microseconds(100); + + imu.update(); + + if (!imu.healthy()) { + continue; + } + + uavcan_equipment_ahrs_RawIMU pkt {}; + + Vector3f tmp; + imu.get_delta_velocity(tmp, pkt.integration_interval); + pkt.accelerometer_integral[0] = tmp.x; + pkt.accelerometer_integral[1] = tmp.y; + pkt.accelerometer_integral[2] = tmp.z; + + imu.get_delta_angle(tmp, pkt.integration_interval); + pkt.rate_gyro_integral[0] = tmp.x; + pkt.rate_gyro_integral[1] = tmp.y; + pkt.rate_gyro_integral[2] = tmp.z; + + tmp = imu.get_accel(); + pkt.accelerometer_latest[0] = tmp.x; + pkt.accelerometer_latest[1] = tmp.y; + pkt.accelerometer_latest[2] = tmp.z; + + uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_RAWIMU_MAX_SIZE]; + uint16_t total_size = uavcan_equipment_ahrs_RawIMU_encode(&pkt, buffer, !canfdout()); + canard_broadcast(UAVCAN_EQUIPMENT_AHRS_RAWIMU_SIGNATURE, + UAVCAN_EQUIPMENT_AHRS_RAWIMU_ID, + CANARD_TRANSFER_PRIORITY_HIGH, + &buffer[0], + total_size); + } +} +#endif // HAL_PERIPH_ENABLE_IMU diff --git a/Tools/AP_Periph/proximity.cpp b/Tools/AP_Periph/proximity.cpp index 2c88d3fc0f98af..d0a3267e1d2422 100644 --- a/Tools/AP_Periph/proximity.cpp +++ b/Tools/AP_Periph/proximity.cpp @@ -60,7 +60,7 @@ void AP_Periph_FW::can_proximity_update() break; } - uint8_t buffer[ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_MAX_SIZE] {}; + uint8_t buffer[ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_MAX_SIZE]; uint16_t total_size = ardupilot_equipment_proximity_sensor_Proximity_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_SIGNATURE, diff --git a/Tools/AP_Periph/rangefinder.cpp b/Tools/AP_Periph/rangefinder.cpp index 43ad6d65e506ae..5ea1753ff9451b 100644 --- a/Tools/AP_Periph/rangefinder.cpp +++ b/Tools/AP_Periph/rangefinder.cpp @@ -12,6 +12,8 @@ #define AP_PERIPH_PROBE_CONTINUOUS 0 #endif +extern const AP_HAL::HAL &hal; + /* update CAN rangefinder */ @@ -21,7 +23,8 @@ void AP_Periph_FW::can_rangefinder_update(void) return; } #if AP_PERIPH_PROBE_CONTINUOUS - if (rangefinder.num_sensors() == 0) { + // We only allow continuous probing for rangefinders while vehicle is disarmed. Probing is currently inefficient and leads to longer loop times. + if ((rangefinder.num_sensors() == 0) && !hal.util->get_soft_armed() && option_is_set(PeriphOptions::PROBE_CONTINUOUS)) { uint32_t now = AP_HAL::millis(); static uint32_t last_probe_ms; if (now - last_probe_ms >= 1000) { @@ -31,67 +34,88 @@ void AP_Periph_FW::can_rangefinder_update(void) } #endif uint32_t now = AP_HAL::millis(); - static uint32_t last_update_ms; if (g.rangefinder_max_rate > 0 && - now - last_update_ms < uint32_t(1000/g.rangefinder_max_rate)) { + now - last_rangefinder_update_ms < uint32_t(1000/g.rangefinder_max_rate)) { // limit to max rate return; } - last_update_ms = now; + last_rangefinder_update_ms = now; + + // update all rangefinder instances rangefinder.update(); - RangeFinder::Status status = rangefinder.status_orient(ROTATION_NONE); - if (status <= RangeFinder::Status::NoData) { - // 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); - switch (status) { - case RangeFinder::Status::OutOfRangeLow: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE; - break; - case RangeFinder::Status::OutOfRangeHigh: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; - break; - case RangeFinder::Status::Good: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; - break; - default: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_UNDEFINED; - break; - } - switch (rangefinder.get_mav_distance_sensor_type_orient(ROTATION_NONE)) { - case MAV_DISTANCE_SENSOR_LASER: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; - break; - case MAV_DISTANCE_SENSOR_ULTRASOUND: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR; - break; - case MAV_DISTANCE_SENSOR_RADAR: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR; - break; - default: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_UNDEFINED; - break; - } - pkt.range = dist_cm * 0.01; + // cycle through each rangefinder instance to find one to send + // equipment.range_sensor only uses 3 CAN frames so we just send all available sensor measurements. + for (uint8_t i = 0; i <= rangefinder.num_sensors(); i++) { + + if (rangefinder.get_type(i) == RangeFinder::Type::NONE) { + continue; + } + + AP_RangeFinder_Backend *backend = rangefinder.get_backend(i); + if (backend == nullptr) { + continue; + } + + RangeFinder::Status status = backend->status(); + if (status <= RangeFinder::Status::NoData) { + // don't send any data for this instance + continue; + } + + const uint32_t sample_ms = backend->last_reading_ms(); + if (last_rangefinder_sample_ms[i] == sample_ms) { + // don't same the same reading again + continue; + } + last_rangefinder_sample_ms[i] = sample_ms; + + uavcan_equipment_range_sensor_Measurement pkt {}; + pkt.sensor_id = rangefinder.get_address(i); + + switch (status) { + case RangeFinder::Status::OutOfRangeLow: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE; + break; + case RangeFinder::Status::OutOfRangeHigh: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; + break; + case RangeFinder::Status::Good: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; + break; + default: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_UNDEFINED; + break; + } + + switch (backend->get_mav_distance_sensor_type()) { + case MAV_DISTANCE_SENSOR_LASER: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; + break; + case MAV_DISTANCE_SENSOR_ULTRASOUND: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR; + break; + case MAV_DISTANCE_SENSOR_RADAR: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR; + break; + default: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_UNDEFINED; + break; + } - uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer, !periph.canfdout()); + float dist_m = backend->distance(); + pkt.range = dist_m; - canard_broadcast(UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SIGNATURE, - UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); + uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE]; + 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, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + } } #endif // HAL_PERIPH_ENABLE_RANGEFINDER diff --git a/Tools/AP_Periph/rc_in.cpp b/Tools/AP_Periph/rc_in.cpp index 63a584d684b828..c4fd8dcbd6d7d8 100644 --- a/Tools/AP_Periph/rc_in.cpp +++ b/Tools/AP_Periph/rc_in.cpp @@ -165,7 +165,7 @@ void AP_Periph_FW::can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t n } // encode and send message: - uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE] {}; + uint8_t buffer[DRONECAN_SENSORS_RC_RCINPUT_MAX_SIZE]; uint16_t total_size = dronecan_sensors_rc_RCInput_encode(&pkt, buffer, !periph.canfdout()); diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index 93614c1352ad42..8feb3e0805ce8b 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -63,8 +63,15 @@ void AP_Periph_FW::rcout_init() // run this once and at 1Hz to configure aux and esc ranges rcout_init_1Hz(); +#if HAL_DSHOT_ENABLED + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); +#endif + + // run PWM ESCs at configured rate + hal.rcout->set_freq(esc_mask, g.esc_rate.get()); + // setup ESCs with the desired PWM type, allowing for DShot - SRV_Channels::init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get()); + AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get()); // run DShot at 1kHz hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400); @@ -76,7 +83,7 @@ void AP_Periph_FW::rcout_init() void AP_Periph_FW::rcout_init_1Hz() { // this runs at 1Hz to allow for run-time param changes - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); for (uint8_t i=0; i= esc_telem_update_period_ms) { last_esc_telem_update_ms = now_ms; esc_telem_update(); } +#if AP_EXTENDED_ESC_TELEM_ENABLED + esc_telem_extended_update(now_ms); +#endif #endif } diff --git a/Tools/AP_Periph/rpm.cpp b/Tools/AP_Periph/rpm.cpp new file mode 100644 index 00000000000000..b017fb04157e3e --- /dev/null +++ b/Tools/AP_Periph/rpm.cpp @@ -0,0 +1,55 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + +#include + +// Send rpm message occasionally +void AP_Periph_FW::rpm_sensor_send(void) +{ + if (g.rpm_msg_rate <= 0) { + return; + } + + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - rpm_last_send_ms < (1000U / g.rpm_msg_rate)) { + return; + } + rpm_last_send_ms = now_ms; + + { + const uint8_t num_sensors = rpm_sensor.num_sensors(); + for (uint8_t i = 0; i < num_sensors; i++) { + // Send each sensor in turn + const uint8_t index = (rpm_last_sent_index + 1 + i) % num_sensors; + + const int8_t sensor_id = rpm_sensor.get_dronecan_sensor_id(index); + if (sensor_id < 0) { + // disabled or not configured to send + continue; + } + + dronecan_sensors_rpm_RPM pkt {}; + pkt.sensor_id = sensor_id; + + // Get rpm and set health flag + if (!rpm_sensor.get_rpm(index, pkt.rpm)) { + pkt.flags |= DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY; + } + + uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE]; + const uint16_t total_size = dronecan_sensors_rpm_RPM_encode(&pkt, buffer, !canfdout()); + + canard_broadcast(DRONECAN_SENSORS_RPM_RPM_SIGNATURE, + DRONECAN_SENSORS_RPM_RPM_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + rpm_last_sent_index = index; + break; + } + } +} + +#endif // HAL_PERIPH_ENABLE_RPM_STREAM diff --git a/Tools/AP_Periph/serial_tunnel.cpp b/Tools/AP_Periph/serial_tunnel.cpp index cdba23b41c46d8..a4e13d9ab9a5f0 100644 --- a/Tools/AP_Periph/serial_tunnel.cpp +++ b/Tools/AP_Periph/serial_tunnel.cpp @@ -50,7 +50,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER if (uart_num == -1) { - uart_num = g.rangefinder_port; + uart_num = g.rangefinder_port[0]; } #endif #ifdef HAL_PERIPH_ENABLE_ADSB @@ -79,7 +79,7 @@ void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* canard_ins, CanardRxT return; } if (uart_monitor.buffer == nullptr) { - uart_monitor.buffer = new ByteBuffer(1024); + uart_monitor.buffer = NEW_NOTHROW ByteBuffer(1024); if (uart_monitor.buffer == nullptr) { return; } @@ -196,7 +196,7 @@ void AP_Periph_FW::send_serial_monitor_data() pkt.serial_id = uart_monitor.uart_num; memcpy(pkt.buffer.data, buf, n); - uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE]; const uint16_t total_size = uavcan_tunnel_Targetted_encode(&pkt, buffer, !canfdout()); debug("read %u", unsigned(n)); diff --git a/Tools/AP_Periph/temperature.cpp b/Tools/AP_Periph/temperature.cpp index 3377e2b63594e7..b7003b022d9efe 100644 --- a/Tools/AP_Periph/temperature.cpp +++ b/Tools/AP_Periph/temperature.cpp @@ -36,7 +36,7 @@ void AP_Periph_FW::temperature_sensor_update(void) // Use source ID from temperature lib pkt.device_id = temperature_sensor.get_source_id(index); - uint8_t buffer[UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_MAX_SIZE] {}; + uint8_t buffer[UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_MAX_SIZE]; const uint16_t total_size = uavcan_equipment_device_Temperature_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_DEVICE_TEMPERATURE_SIGNATURE, diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index 70d587bc961548..f07244c615f939 100644 --- a/Tools/AP_Periph/wscript +++ b/Tools/AP_Periph/wscript @@ -44,6 +44,7 @@ def build(bld): 'AP_FlashStorage', 'AP_RAMTRON', 'AP_GPS', + 'AP_GSOF', 'AP_Networking', 'AP_SerialManager', 'AP_RTC', @@ -82,7 +83,8 @@ def build(bld): 'AP_RobotisServo', 'AP_FETtecOneWire', 'GCS_MAVLink', - 'AP_Relay' + 'AP_Relay', + 'AP_MultiHeap', ] bld.ap_stlib( diff --git a/Tools/CodeStyle/astylerc b/Tools/CodeStyle/astylerc index 20bc80e4ec176b..75a467bc1dad1a 100644 --- a/Tools/CodeStyle/astylerc +++ b/Tools/CodeStyle/astylerc @@ -1,6 +1,6 @@ style=linux keep-one-line-statements -add-brackets +add-braces indent=spaces=4 indent-col1-comments min-conditional-indent=0 diff --git a/Tools/Frame_params/ModalAI/AutonomyDevKit.parm b/Tools/Frame_params/ModalAI/AutonomyDevKit.parm new file mode 100644 index 00000000000000..ad2982829b2c68 --- /dev/null +++ b/Tools/Frame_params/ModalAI/AutonomyDevKit.parm @@ -0,0 +1,95 @@ +# parameters for the autonomy dev kit +# https://www.modalai.com/products/px4-autonomy-developer-kit + +# flight modes +FLTMODE1 5 +FLTMODE4 2 +FLTMODE_CH 6 + +# motor ordering +SERVO1_FUNCTION 34 +SERVO2_FUNCTION 35 +SERVO3_FUNCTION 33 +SERVO4_FUNCTION 36 + +# enable PID logging +LOG_BITMASK 65535 + +# mag field varies quite a lot between batteries +ARMING_MAGTHRESH 200 + +# IMU orientation +AHRS_ORIENTATION 8 + +# compass orientation +COMPASS_ORIENT 8 + +# filtering +INS_GYRO_FILTER 40 +INS_HNTCH_ENABLE 1 +INS_HNTCH_FREQ 100 +INS_HNTCH_BW 50 +INS_HNTCH_HMNCS 7 +INS_HNTCH_REF 1 +INS_HNTCH_MODE 3 +INS_HNTCH_OPTS 2 + +# run IMU at 2kHz +INS_GYRO_RATE 1 + +# a bit more agressive loiter +PILOT_SPEED_UP 500 +LOIT_BRK_ACCEL 500 +LOIT_BRK_JERK 1000 +LOIT_BRK_DELAY 0.200000 + +# tuning from autotune +ATC_ACCEL_Y_MAX 46813.816406 +ATC_ACCEL_R_MAX 218565.890625 +ATC_ACCEL_P_MAX 220962 +ATC_ANG_RLL_P 15.120497 +ATC_ANG_PIT_P 15.393054 +ATC_ANG_YAW_P 7.636879 +ATC_RAT_RLL_P 0.038459 +ATC_RAT_RLL_I 0.038459 +ATC_RAT_RLL_D 0.000927 +ATC_RAT_PIT_P 0.043496 +ATC_RAT_PIT_I 0.043496 +ATC_RAT_PIT_D 0.000934 +ATC_RAT_YAW_P 0.376548 +ATC_RAT_YAW_I 0.037655 +ATC_RAT_YAW_FLTE 2.090602 + +# battery setup +BATT_LOW_VOLT 7 +BATT_OPTIONS 64 +BATT_VOLT_PIN 1 +BATT_CURR_PIN 2 +BATT_VOLT_MULT 1 +BATT_AMP_PERVLT 1 +# on the test board we have a current offset of -16.8A +# we need to check if this applies to all versions of this vehicle +BATT_AMP_OFFSET -16.8 + +# 2S battery range +MOT_BAT_VOLT_MAX 8.400000 +MOT_BAT_VOLT_MIN 6.600000 + +# quad-X +FRAME_CLASS 1 + +# tweak R/C inputs +RC1_MIN 1000 +RC1_MAX 2000 +RC1_DZ 40 +RC2_MIN 1000 +RC2_MAX 2000 +RC2_REVERSED 1 +RC3_MIN 1000 +RC3_MAX 2000 +RC4_MIN 1000 +RC4_MAX 2000 +RC4_DZ 40 + +# add arming on right switch +RC7_OPTION 153 diff --git a/Tools/Frame_params/ModalAI/D0013.parm b/Tools/Frame_params/ModalAI/D0013.parm new file mode 100644 index 00000000000000..1d3fcf65139cb0 --- /dev/null +++ b/Tools/Frame_params/ModalAI/D0013.parm @@ -0,0 +1,109 @@ +# parameters for the Stinger drone + +# flight modes +FLTMODE1 5 +FLTMODE4 2 +FLTMODE_CH 6 + +# enable PID logging +LOG_BITMASK 65535 + +# mag field varies quite a lot between batteries +ARMING_MAGTHRESH 200 + +# IMU orientation +# 4 = YAW 180 +AHRS_ORIENTATION 4 + +# Forced external compass +COMPASS_EXTERNAL 2 +# compass orientation +# 2 = YAW 90 +COMPASS_ORIENT 8 + +# filtering +INS_GYRO_FILTER 40 +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 40.0 +INS_HNTCH_BW 50.0 +INS_HNTCH_FM_RAT 1.0 +INS_HNTCH_FREQ 100.0 +INS_HNTCH_HMNCS 7 +INS_HNTCH_MODE 3 +INS_HNTCH_OPTS 2 +INS_HNTCH_REF 1.0 + +# run IMU at 2kHz +INS_GYRO_RATE 1 + +# a bit more agressive loiter +PILOT_SPEED_UP 500 +LOIT_BRK_ACCEL 500 +LOIT_BRK_JERK 1000 +LOIT_BRK_DELAY 0.200000 + +# Tune parameters from Quik Tune +ATC_ACCEL_Y_MAX 30000.0 +ATC_ACCEL_R_MAX 125000.0 +ATC_ACCEL_P_MAX 125000.0 +ATC_RAT_PIT_D 0.002856164472177625 +ATC_RAT_PIT_FLTD 40.0 +ATC_RAT_PIT_FLTT 40.0 +ATC_RAT_PIT_I 0.124929137527942657 +ATC_RAT_PIT_P 0.124929137527942657 +ATC_RAT_PIT_SMAX 50.0 +ATC_RAT_RLL_D 0.001519999350421131 +ATC_RAT_RLL_FLTD 40.0 +ATC_RAT_RLL_FLTT 40.0 +ATC_RAT_RLL_I 0.075611755251884460 +ATC_RAT_RLL_P 0.075611755251884460 +ATC_RAT_RLL_SMAX 50.0 +ATC_RAT_YAW_D 0.010000008158385754 +ATC_RAT_YAW_FLTD 40.0 +ATC_RAT_YAW_FLTE 2.0 +ATC_RAT_YAW_FLTT 40.0 +ATC_RAT_YAW_I 0.050000030547380447 +ATC_RAT_YAW_P 0.500000298023223877 +ATC_RAT_YAW_SMAX 50.0 + +# battery setup +BATT_LOW_VOLT 14.2 +BATT_OPTIONS 64 +BATT_VOLT_PIN 1 +BATT_CURR_PIN 2 +BATT_VOLT_MULT 1 +BATT_AMP_PERVLT 1 +BATT_AMP_OFFSET 0.0 + +# 4S battery range +MOT_BAT_VOLT_MAX 16.800000 +MOT_BAT_VOLT_MIN 13.200000 + +# Learned hover thrust +MOT_THST_EXPO 0.550000011920928955 +MOT_THST_HOVER 0.130549192428588867 + +# quad-X +FRAME_CLASS 1 + +# tweak R/C inputs +RC1_MIN 1000 +RC1_MAX 2000 +RC1_DZ 40 +RC2_MIN 1000 +RC2_MAX 2000 +RC2_REVERSED 1 +RC3_MIN 1000 +RC3_MAX 2000 +RC4_MIN 1000 +RC4_MAX 2000 +RC4_DZ 40 + +# add arming on right switch +RC7_OPTION 153 + +# Motor mappings +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 36 +SERVO3_FUNCTION 34 +SERVO4_FUNCTION 35 diff --git a/Tools/Frame_params/ModalAI/Starling2Max.parm b/Tools/Frame_params/ModalAI/Starling2Max.parm new file mode 100644 index 00000000000000..7e06a8e3bd4627 --- /dev/null +++ b/Tools/Frame_params/ModalAI/Starling2Max.parm @@ -0,0 +1,48 @@ +# Parameters for Starling 2 Max drone +# https://www.modalai.com/products/starling-2-max?variant=48172375310640 + +# IMU orientation is ROLL_180 +AHRS_ORIENT 8 + +# Mag orientation is ROLL_180 +COMPASS_ORIENT 8 + +# Pitch control is backwards? +RC2_REVERSED 1 + +# Left 3-pos switch is RC6 +FLTMODE_CH 6 + +# Flight mode channel mapping +FLTMODE1 0 +FLTMODE3 2 +FLTMODE6 5 + +# Motor mapping +SERVO1_FUNCTION 34 +SERVO2_FUNCTION 35 +SERVO3_FUNCTION 33 +SERVO4_FUNCTION 36 + +# Motor spin +MOT_SPIN_ARM 0.05 +MOT_SPIN_MIN 0.15 + +# Visual Inertial Odometry setup +VISO_TYPE 3 +EK3_SRC1_POSXY 6 +EK3_SRC1_VELXY 6 +EK3_SRC1_POSZ 6 +EK3_SRC1_VELZ 6 +EK3_SRC1_YAW 6 + +# To improve Mavlink connection disable forwarding from camera/viso +SERIAL2_OPTIONS 1024 + +# PID tuning +ATC_RAT_RLL_P 0.07 +ATC_RAT_RLL_I 0.07 +ATC_RAT_RLL_D 0.0015 +ATC_RAT_PIT_P 0.07 +ATC_RAT_PIT_I 0.07 +ATC_RAT_PIT_D 0.0015 \ No newline at end of file diff --git a/Tools/Frame_params/SPARKKit-rover.param b/Tools/Frame_params/SPARKKit-rover.param new file mode 100644 index 00000000000000..bb8cd8f1afdf9f --- /dev/null +++ b/Tools/Frame_params/SPARKKit-rover.param @@ -0,0 +1,57 @@ +#NOTE: Params for SPARTK Kit Rover V4.5.0 (and higher) +ACRO_TURN_RATE,90 +AHRS_ORIENTATION,14 +ATC_SPEED_I,0.7556667 +ATC_SPEED_P,0.7556667 +ATC_STR_ACC_MAX,160 +ATC_STR_RAT_D,0.002 +ATC_STR_RAT_FF,0.3316459 +ATC_STR_RAT_FLTD,2 +ATC_STR_RAT_FLTT,2 +ATC_STR_RAT_I,0.17 +ATC_STR_RAT_P,0.17 +ATC_TURN_MAX_G,0.15 +BATT_CURR_PIN,15 +BATT_VOLT_MULT,12.02 +BATT_VOLT_PIN,14 +CAN_P1_DRIVER,1 +COMPASS_USE2,0 +COMPASS_USE3,0 +CRUISE_SPEED,1.137718 +CRUISE_THROTTLE,85 +EK3_IMU_MASK,7 +FRAME_CLASS,1 +FRAME_TYPE,0 +FS_CRASH_CHECK,2 +FS_EKF_THRESH,0.6 +FS_GCS_TIMEOUT,2 +FS_THR_ENABLE,2 +GPS_POS1_X,-0.1 +GPS_POS1_Y,-0.08 +GPS_TYPE,9 +GUID_OPTIONS,64 +MANUAL_OPTIONS,1 +MANUAL_STR_EXPO,0.2 +MODE_CH,5 +MODE3,0 +MODE4,1 +MODE5,0 +MODE6,10 +MOT_THR_MIN,14 +NTF_LED_LEN,16 +NTF_LED_TYPES,123367 +PSC_VEL_D,0.02 +PSC_VEL_FF,1 +PSC_VEL_I,0.04 +PSC_VEL_P,0.2 +SERIAL1_BAUD,921 +SERVO1_MAX,1920 +SERVO1_MIN,1120 +SERVO1_TRIM,1538 +SERVO3_MAX,1920 +SERVO3_MIN,1120 +SERVO3_TRIM,1520 +SERVO9_FUNCTION,120 +WP_PIVOT_ANGLE,0 +WP_PIVOT_RATE,0 +WP_SPEED,1 diff --git a/Tools/Frame_params/hexsoon-edu650.param b/Tools/Frame_params/hexsoon-edu650.param index 330ffba32feed4..cd3e08251612fc 100644 --- a/Tools/Frame_params/hexsoon-edu650.param +++ b/Tools/Frame_params/hexsoon-edu650.param @@ -17,8 +17,6 @@ ATC_RAT_RLL_P,0.10 ATC_RAT_YAW_FLTD,10 ATC_RAT_YAW_FLTE,2 ATC_RAT_YAW_FLTT,10 -BATT_MONITOR,3 -BATT_VOLT_MULT,12.02 FRAME_CLASS,1 FRAME_TYPE,1 INS_GYRO_FILTER,40 diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index 18f2ad8269a9db..a475ba17f1bd86 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -184,3 +184,25 @@ FreeName Anchit maggie Abdullah Saleem +Hiroshi Kaneda +Abe Takuya +Masahiro Suzuki +Hideyuki Fujikawa +Ryoga Kamimura +HIROSHI Suto +Yasuhiro Setoguchi +Shinji Ichimura +masahiko Ito +Kei Kabutomori +Hiroaki Kawasaki +Kazuhide Juta +Ryoichi Shiohama +Masaki Shibuya +Aryan Roshan trying his first commit +Amr +Tsuyoshi Arakawa +Naveen Kumar Kilaparthi +Amr Attia +Alessandro Martini +Eren Mert YİĞİT +Prashant Powar diff --git a/Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin new file mode 100755 index 00000000000000..d9cad7f0ca76bf Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin new file mode 100755 index 00000000000000..2e181269c0e302 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_cube_highpolh.bin b/Tools/IO_Firmware/iofirmware_cube_highpolh.bin new file mode 100755 index 00000000000000..f23e2095b76294 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_cube_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_cube_lowpolh.bin b/Tools/IO_Firmware/iofirmware_cube_lowpolh.bin new file mode 100755 index 00000000000000..82aabcbe572886 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_cube_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 5934290788ad07..65c8298b29da34 100755 Binary files a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin and b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin index c65751281d15ac..c52a18b84b63bc 100755 Binary files a/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_highpolh.bin new file mode 100644 index 00000000000000..40cd87a955ba27 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin new file mode 100644 index 00000000000000..be59d5439a7c85 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin index adbf98f090cde5..c0be42428df236 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 fce01bb26c29e6..f4019759445184 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_f103_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin index 2ba418de0788fe..de8758ba4a1aaf 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin index 1a0426c5761b65..0a4d24564454a2 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_highpolh.bin index af9d068cd5ea57..b05367f7ac12f2 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin index 8db3cfaad172de..25bfa7c11a95a1 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_highpolh.bin b/Tools/IO_Firmware/iofirmware_highpolh.bin index 988375fa5d73c2..1e153bef3d1210 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 059048670ef3f5..dabf7c39dc1140 100755 Binary files a/Tools/IO_Firmware/iofirmware_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_lowpolh.bin differ diff --git a/Tools/LogAnalyzer/DataflashLog.py b/Tools/LogAnalyzer/DataflashLog.py deleted file mode 100644 index a96cca589cecd5..00000000000000 --- a/Tools/LogAnalyzer/DataflashLog.py +++ /dev/null @@ -1,820 +0,0 @@ -# -# Code to abstract the parsing of APM Dataflash log files, currently only used by the LogAnalyzer -# -# Initial code by Andrew Chapman (amchapman@gmail.com), 16th Jan 2014 -# - -# AP_FLAKE8_CLEAN - -from __future__ import print_function, division - -import bisect -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' - self.msgType = msgType - 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 - """ - try: - if valueType in "fcCeELd": - return float(value) - elif valueType in "bBhHiIMQq": - return int(value) - elif valueType in "nNZ": - return str(value) - except ValueError: - pass - return value - - def to_class(self): - members = dict( - NAME=self.name, - labels=self.labels[:], - ) - - fieldtypes = [i for i in self.types] - fieldlabels = self.labels[:] - - # 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)), - ) - 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]) - ) - - def init(a, *x): - if len(x) != len(a.labels): - raise ValueError("Invalid Length") - for (l, v) in zip(a.labels, x): - try: - setattr(a, l, v) - except Exception as e: - print("{} {} {} failed".format(a, l, v)) - print(e) - - members['__init__'] = init - - # finally, create the class - cls = type('Log__{:s}'.format(self.name), (object,), members) - return cls - - -class logheader(ctypes.LittleEndianStructure): - _fields_ = [ - ('head1', ctypes.c_uint8), - ('head2', ctypes.c_uint8), - ('msgid', ctypes.c_uint8), - ] - - def __repr__(self): - return "".format( - self=self - ) - - -class BinaryFormat(ctypes.LittleEndianStructure): - NAME = 'FMT' - MSG = 128 - SIZE = 0 - FIELD_FORMAT = { - 'a': ctypes.c_int16 * 32, - 'b': ctypes.c_int8, - 'B': ctypes.c_uint8, - 'h': ctypes.c_int16, - 'H': ctypes.c_uint16, - 'i': ctypes.c_int32, - 'I': ctypes.c_uint32, - 'f': ctypes.c_float, - 'd': ctypes.c_double, - '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, - 'L': ctypes.c_int32, - 'M': ctypes.c_uint8, - 'q': ctypes.c_int64, - 'Q': ctypes.c_uint64, - } - - FIELD_SCALE = { - 'c': 100, - 'C': 100, - 'e': 100, - 'E': 100, - } - - _packed_ = True - _fields_ = [ - ('head', logheader), - ('type', ctypes.c_uint8), - ('length', ctypes.c_uint8), - ('name', ctypes.c_char * 4), - ('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:]]), - ) - - def to_class(self): - labels = self.labels.decode(encoding="utf-8") if self.labels else "" - members = dict( - NAME=self.name.decode(encoding="utf-8"), - MSG=self.type, - SIZE=self.length, - labels=labels.split(","), - _pack_=True, - ) - - if isinstance(self.types[0], str): - fieldtypes = [i for i in self.types] - else: - fieldtypes = [chr(i) for i in self.types] - fieldlabels = members["labels"] - if self.labels and (len(fieldtypes) != len(fieldlabels)): - print("Broken FMT message for {} .. ignoring".format(self.name), file=sys.stderr) - return None - - 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(encoding="utf-8") - return ret - - p = property(get_message_attribute) - if scale is not None: - 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]) - ) - - # finally, create the class - 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) - 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''' - - # TODO: rethink data storage, but do more thorough regression testing before refactoring it - # TODO: store data as a scipy spline curve so we can more easily interpolate and sample the slope? - - def __init__(self): - # 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.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 < len(self.listData): - line = self.listData[index][0] - if line >= lineNumber: - return (self.listData[index][1], line) - index += 1 - 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] - if line <= lineNumber: - return (self.listData[index][1], line) - index -= 1 - 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) - """ - if lookForwards: - try: - return self.getNearestValueFwd(lineNumber) - except ValueError: - return self.getNearestValueBack(lineNumber) - else: - try: - return self.getNearestValueBack(lineNumber) - 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) - if prevValueLine == nextValueLine: - return prevValue - 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)) - 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 - - class LogIteratorSubValue: - '''syntactic sugar to allow access by LogIterator[lineLabel][dataLabel]''' - - 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 - currentLine = None - - def __init__(self, logdata, lineNumber=0): - self.logdata = logdata - self.currentLine = lineNumber - for lineLabel in self.logdata.formats: - 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 - if self.currentLine > self.logdata.lineCount: - return self - for lineLabel in self.iterators.keys(): - # 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, 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) - 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) - self.iterators[lineLabel] = (self.logdata.channels[lineLabel][dataLabel].getIndexOf(lineNumber), lineNumber) - - -class DataflashLogHelper: - '''helper functions for dealing with log data, put here to keep DataflashLog class as a simple parser and data store''' - - @staticmethod - def getTimeAtLine(logdata, lineNumber): - '''returns the nearest GPS timestamp in milliseconds after the given line number''' - 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 - timeLabel = None - for possible in "TimeMS", "Time", "TimeUS": - if possible in logdata.channels["GPS"]: - timeLabel = possible - break - if timeLabel is None: - raise Exception("Unable to get time label") - while lineNumber <= logdata.lineCount: - if lineNumber in logdata.channels["GPS"][timeLabel].dictData: - return logdata.channels["GPS"][timeLabel].dictData[lineNumber] - lineNumber = lineNumber + 1 - - sys.stderr.write("didn't find GPS data for " + str(lineNumber) + " - using maxtime\n") - return logdata.channels["GPS"][timeLabel].max() - - @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 - """ - # 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] - if chunk1Len == chunk2Len: - return 0 - elif chunk1Len > chunk2Len: - return -1 - else: - return 1 - - changes = [{"line": k, "modeName": v[0], "modeNum": v[1]} for k, v in sorted(logdata.modeChanges.items())] - chunks = [] - 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 - chunkTimeSeconds = ( - DataflashLogHelper.getTimeAtLine(logdata, endLine) - - DataflashLogHelper.getTimeAtLine(logdata, startLine) - + 1 - ) / 1000.0 - if chunkTimeSeconds > minLengthSeconds: - chunks.append((startLine, endLine)) - chunks.sort(key=lambda chunk: chunk[1] - chunk[0]) - return chunks - - @staticmethod - def isLogEmpty(logdata): - '''returns an human readable error string if the log is essentially empty, otherwise returns None''' - # 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 - if "CTUN" in logdata.channels: - try: - maxThrottle = logdata.channels["CTUN"]["ThrOut"].max() - 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 - throttleThreshold = 0.2 - if maxThrottle < throttleThreshold: - return "Throttle never above 20%" - return None - - -class DataflashLog(object): - """ - 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.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.durationSecs = 0 - self.lineCount = 0 - self.skippedLines = 0 - self.backpatch_these_modechanges = [] - self.frame = None - - if logfile: - self.read(logfile, format, ignoreBadlines) - - def getCopterType(self): - '''returns quad/hex/octo/tradheli if this is a copter log''' - if self.vehicleType != VehicleType.Copter: - return None - motLabels = [] - 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" - elif len(motLabels) == 4: - return "quad" - elif len(motLabels) == 6: - return "hex" - elif len(motLabels) == 8: - return "octo" - else: - return "" - - def num_motor_channels(self): - motor_channels_for_frame = { - "QUAD": 4, - "HEXA": 6, - "Y6": 6, - "OCTA": 8, - "OCTA_QUAD": 8, - "DECA": 10, - # "HELI": 1, - # "HELI_DUAL": 2, - "TRI": 3, - "SINGLE": 1, - "COAX": 2, - "TAILSITTER": 1, - "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]) - self.filename = logfile - if self.filename == '': - f = sys.stdin - else: - f = open(self.filename, 'rb') - - if format.lower() == 'bin': - head = df_header - elif format == 'log': - head = "" - elif format == 'auto': - if self.filename == '': - # assuming TXT format - head = "" - else: - head = f.read(4) - f.seek(0) - else: - raise ValueError("Unknown log format for {}: {}".format(self.filename, format)) - - if head == df_header: - numBytes, lineNumber = self.read_binary(f, ignoreBadlines) - pass - else: - numBytes, lineNumber = self.read_text(f, ignoreBadlines) - - # gather some general stats about the log - 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': - 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]) - if timeLabel == 'TimeUS': - firstTimeGPS /= 1000 - lastTimeGPS /= 1000 - self.durationSecs = (lastTimeGPS - firstTimeGPS) / 1000 - - # TODO: calculate logging rate based on timestamps - # ... - - msg_vehicle_to_vehicle_map = { - "ArduCopter": VehicleType.Copter, - "APM:Copter": VehicleType.Copter, - "ArduPlane": VehicleType.Plane, - "ArduRover": VehicleType.Rover, - } - - # takes the vehicle type supplied via "MSG" and sets vehicleType from - # the VehicleType enumeration - def set_vehicleType_from_MSG_vehicle(self, MSG_vehicle): - ret = self.msg_vehicle_to_vehicle_map.get(MSG_vehicle, None) - if ret is None: - raise ValueError("Unknown vehicle type (%s)" % (MSG_vehicle)) - self.vehicleType = ret - self.vehicleTypeString = VehicleTypeString[ret] - - 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', - } - try: - if hasattr(e, 'ThrCrs'): - self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ThrCrs) - else: - # assume it has ModeNum: - self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ModeNum) - except ValueError: - if hasattr(e, 'ThrCrs'): - self.modeChanges[lineNumber] = (e.Mode, e.ThrCrs) - else: - # some .log files have the name spelt out by name - # rather than number, contrary to the format - # string. Attempt to map that back to a number: - uppername = str(e.Mode).upper() - for num in modes: - if modes[num].upper() == uppername: - self.modeChanges[lineNumber] = (uppername, num) - return - # assume it has ModeNum: - print("Unknown mode=%u" % e.ModeNum) - self.modeChanges[lineNumber] = (e.Mode, "mode=%u" % e.ModeNum) - elif self.vehicleType in [VehicleType.Plane, VehicleType.Copter, VehicleType.Rover]: - self.modeChanges[lineNumber] = (e.Mode, e.ModeNum) - 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)) - ) - - def backPatchModeChanges(self): - for (lineNumber, e) in self.backpatch_these_modechanges: - self.handleModeChange(lineNumber, e) - - def set_frame(self, frame): - self.frame = 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 - self._formats[e.type] = cls - if cls.NAME not in self.formats: - self.formats[cls.NAME] = cls - elif e.NAME == "PARM": - self.parameters[e.Name] = e.Value - elif e.NAME == "MSG": - tokens = e.Message.split(' ') - if not self.frame: - if "Frame" in tokens[0]: - self.set_frame(tokens[1]) - if not self.vehicleType: - try: - self.set_vehicleType_from_MSG_vehicle(tokens[0]) - except ValueError: - return - self.backPatchModeChanges() - self.firmwareVersion = tokens[1] - if len(tokens) == 3: - self.firmwareHash = tokens[2][1:-1] - else: - self.messages[lineNumber] = e.Message - elif e.NAME == "MODE": - if self.vehicleType is None: - self.backpatch_these_modechanges.append((lineNumber, e)) - else: - self.handleModeChange(lineNumber, e) - # anything else must be the log data - else: - groupName = e.NAME - - # first time seeing this type of log line, create the channel storage - if groupName not in self.channels: - self.channels[groupName] = {} - for label in e.labels: - self.channels[groupName][label] = Channel() - - # store each token in its relevant channel - for label in e.labels: - value = getattr(e, label) - channel = self.channels[groupName][label] - channel.dictData[lineNumber] = value - channel.listData.append((lineNumber, value)) - - def read_text(self, f, ignoreBadlines): - 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: - 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" - ) - if len(tokens) == 1: - tokens2 = line.split(' ') - if line == "": - pass - 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: - # 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] - else: - errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename) - if ignoreBadlines: - print(errorMsg + " (skipping line)", file=sys.stderr) - self.skippedLines += 1 - else: - raise Exception("") - else: - if tokens[0] not in self.formats: - raise ValueError("Unknown Format {}".format(tokens[0])) - e = self.formats[tokens[0]](*tokens[1:]) - self.process(lineNumber, e) - 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) - - def read_binary(self, f, ignoreBadlines): - lineNumber = 0 - numBytes = 0 - for e in self._read_binary(f, ignoreBadlines): - lineNumber += 1 - if e is None: - continue - numBytes += e.SIZE - # print(e) - self.process(lineNumber, e) - return (numBytes, lineNumber) - - def _read_binary(self, f, ignoreBadlines): - 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 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, - ) - break - offset += 1 - continue - - if h.msgid in self._formats: - typ = self._formats[h.msgid] - if len(data) <= offset + typ.SIZE: - break - try: - e = typ.from_buffer(data, offset) - 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: - raise ValueError(str(h) + "unknown type") - yield e diff --git a/Tools/LogAnalyzer/LogAnalyzer.py b/Tools/LogAnalyzer/LogAnalyzer.py deleted file mode 100755 index 748cbe793b915f..00000000000000 --- a/Tools/LogAnalyzer/LogAnalyzer.py +++ /dev/null @@ -1,313 +0,0 @@ -#!/usr/bin/env python -# -# A module to analyze and identify any common problems which can be determined from log files -# -# 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 -# - CTUN.ThrOut on copter is 0-1000, on plane+rover it is 0-100 - -# TODO: add test for noisy baro values -# TODO: support loading binary log files (use Tridge's mavlogdump?) - -from __future__ import print_function - -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 - GOOD, FAIL, WARN, UNKNOWN, NA = range(5) - - status = None - 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 - """ - - def __init__(self): - self.name = "" - self.result = None # will be an instance of TestResult after being run - self.execTime = None - self.enable = True - - def run(self, logdata, verbose=False): - pass - - -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.logfile = 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') - - 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: - self.tests.extend(getTests(script)) - - # and here's an example of explicitly loading a Test class if you wanted to do that - # 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): - '''run all registered tests in a single call, gathering execution timing info''' - self.logdata = logdata - if 'GPS' not in self.logdata.channels and 'GPS2' in self.logdata.channels: - # *cough* - self.logdata.channels['GPS'] = self.logdata.channels['GPS2'] - - self.logfile = logdata.filename - for test in self.tests: - # run each test in turn, gathering timing info - if test.enable: - startTime = time.time() - test.run(self.logdata, verbose) # RUN THE TEST - endTime = time.time() - test.execTime = 1000 * (endTime - startTime) - - def outputPlainText(self, outputStats): - '''output test results in plain text''' - print('Dataflash log analysis report for file: ' + self.logfile) - print('Log size: %.2fmb (%d lines)' % (self.logdata.filesizeKB / 1024.0, self.logdata.lineCount)) - print('Log duration: %s' % str(datetime.timedelta(seconds=self.logdata.durationSecs)) + '\n') - - if self.logdata.vehicleType == VehicleType.Copter and self.logdata.getCopterType(): - print('Vehicle Type: %s (%s)' % (self.logdata.vehicleTypeString, self.logdata.getCopterType())) - else: - print('Vehicle Type: %s' % self.logdata.vehicleTypeString) - print('Firmware Version: %s (%s)' % (self.logdata.firmwareVersion, self.logdata.firmwareHash)) - print('Hardware: %s' % self.logdata.hardwareType) - print('Free RAM: %s' % self.logdata.freeRAM) - if self.logdata.skippedLines: - print("\nWARNING: %d malformed log lines skipped during read" % self.logdata.skippedLines) - print('\n') - - print("Test Results:") - for test in self.tests: - 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:] - execTime = "" - if outputStats: - execTime = " (%6.2fms)" % (test.execTime) - if test.result.status == TestResult.StatusType.GOOD: - print(" %20s: GOOD %-55s%s" % (test.name, statusMessageFirstLine, execTime)) - elif test.result.status == TestResult.StatusType.FAIL: - print(" %20s: FAIL %-55s%s [GRAPH]" % (test.name, statusMessageFirstLine, execTime)) - elif test.result.status == TestResult.StatusType.WARN: - print(" %20s: WARN %-55s%s [GRAPH]" % (test.name, statusMessageFirstLine, execTime)) - elif test.result.status == TestResult.StatusType.NA: - # skip any that aren't relevant for this vehicle/hardware/etc - continue - else: - print(" %20s: UNKNOWN %-55s%s" % (test.name, statusMessageFirstLine, execTime)) - # if statusMessageExtra: - for line in statusMessageExtra: - 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('\n') - - def outputXML(self, xmlFile): - '''output test results to an XML file''' - - # open the file for writing - xml = None - try: - if xmlFile == '-': - xml = sys.stdout - else: - xml = open(xmlFile, 'w') - 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(repr(self.logdata.lineCount)) + "\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.firmwareVersion) + "\n") - xml.write(" " + escape(self.logdata.firmwareHash) + "\n") - xml.write(" " + escape(self.logdata.hardwareType) + "\n") - xml.write(" " + escape(repr(self.logdata.freeRAM)) + "\n") - xml.write(" " + escape(repr(self.logdata.skippedLines)) + "\n") - xml.write("
\n") - - # output parameters - xml.write("\n") - for param, value in self.logdata.parameters.items(): - xml.write(" \n" % (param, escape(repr(value)))) - xml.write("\n") - - # output test results - xml.write("\n") - for test in self.tests: - if not test.enable: - continue - xml.write(" \n") - if test.result.status == TestResult.StatusType.GOOD: - xml.write(" " + escape(test.name) + "\n") - xml.write(" GOOD\n") - xml.write(" " + escape(test.result.statusMessage) + "\n") - elif test.result.status == TestResult.StatusType.FAIL: - xml.write(" " + escape(test.name) + "\n") - xml.write(" FAIL\n") - xml.write(" " + escape(test.result.statusMessage) + "\n") - xml.write(" (test data will be embedded here at some point)\n") - elif test.result.status == TestResult.StatusType.WARN: - xml.write(" " + escape(test.name) + "\n") - xml.write(" WARN\n") - xml.write(" " + escape(test.result.statusMessage) + "\n") - xml.write(" (test data will be embedded here at some point)\n") - elif test.result.status == TestResult.StatusType.NA: - xml.write(" " + escape(test.name) + "\n") - xml.write(" NA\n") - else: - xml.write(" " + escape(test.name) + "\n") - xml.write(" UNKNOWN\n") - xml.write(" " + escape(test.result.statusMessage) + "\n") - xml.write(" \n") - xml.write("\n") - - xml.write("
\n") - - xml.close() - - -def main(): - # 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('-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 - endTime = time.time() - if args.profile: - print("Log file read time: %.2f seconds" % (endTime - startTime)) - - # check for empty log if requested - if args.empty: - emptyErr = DataflashLog.DataflashLogHelper.isLogEmpty(logdata) - if emptyErr: - sys.stderr.write("Empty log file: %s, %s" % (logdata.filename, emptyErr)) - sys.exit(1) - - # 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)) - - # deal with output - if not args.quiet: - testSuite.outputPlainText(args.profile) - if args.xml: - testSuite.outputXML(args.xml) - if not args.quiet: - print("XML output written to file: %s\n" % args.xml) - - -if __name__ == "__main__": - main() diff --git a/Tools/LogAnalyzer/UnitTest.py b/Tools/LogAnalyzer/UnitTest.py deleted file mode 100755 index 4f94a2eeecfe30..00000000000000 --- a/Tools/LogAnalyzer/UnitTest.py +++ /dev/null @@ -1,404 +0,0 @@ -#!/usr/bin/env python -# -# -# Unit and regression tests for the LogAnalyzer code -# -# - -# AP_FLAKE8_CLEAN - -# TODO: implement more unit+regression tests - -from __future__ import print_function - -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, - '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 - - # 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 DataflashLog reading 2 - # ... - - # TODO: unit test the log test classes - # ... - - print("All unit/regression tests GOOD\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 deleted file mode 100644 index 00df6759302d0c..00000000000000 --- a/Tools/LogAnalyzer/VehicleType.py +++ /dev/null @@ -1,12 +0,0 @@ -# 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"} diff --git a/Tools/LogAnalyzer/example_output.xml b/Tools/LogAnalyzer/example_output.xml deleted file mode 100644 index fed131a0afbef6..00000000000000 --- a/Tools/LogAnalyzer/example_output.xml +++ /dev/null @@ -1,356 +0,0 @@ - - -
- examples/robert_lefebvre_octo_PM.log - 302.7548828125 - 4750 - 0:02:35 - ArduCopter - octo - V3.0.1 - 5c6503e2 - APM 2 - 1331 - 0 -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Brownout - GOOD - - - - Compass - GOOD - No MAG data, unable to test mag_field interference - - - - Dupe Log Data - GOOD - - - - Empty - GOOD - - - - Event/Failsafe - FAIL - ERR found: GPS - (test data will be embedded here at some point) - - - GPS - WARN - Min satellites: 6, Max HDop: 4.68 - (test data will be embedded here at some point) - - - Parameters - GOOD - - - - PM - FAIL - 14 slow loop lines found, max 18.56% on line 2983 - (test data will be embedded here at some point) - - - Pitch/Roll - GOOD - - - - Thrust - GOOD - - - - VCC - GOOD - - - - Vibration - UNKNOWN - No IMU log data - - -
diff --git a/Tools/LogAnalyzer/examples/mechanical_fail.log b/Tools/LogAnalyzer/examples/mechanical_fail.log deleted file mode 100644 index f0ba451d873367..00000000000000 --- a/Tools/LogAnalyzer/examples/mechanical_fail.log +++ /dev/null @@ -1,7777 +0,0 @@ -9 - -ArduCopter V3.1 (5c6503e2) -Free RAM: 1044 -APM 2 -FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format -FMT, 129, 23, PARM, Nf, Name,Value -FMT, 130, 45, GPS, BIHBcLLeeEefI, Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T -FMT, 131, 31, IMU, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 132, 67, MSG, Z, Message -FMT, 25, 25, ATUN, BBfffff, Axis,TuneStep,RateMin,RateMax,RPGain,RDGain,SPGain -FMT, 26, 9, ATDE, cf, Angle,Rate -FMT, 9, 19, CURR, hIhhhf, ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot -FMT, 11, 11, MOT, hhhh, Mot1,Mot2,Mot3,Mot4 -FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch -FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit -FMT, 4, 25, CTUN, hcefchhhh, ThrIn,SonAlt,BarAlt,WPAlt,DesSonAlt,AngBst,CRate,ThrOut,DCRate -FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 6, 19, PM, BBHHIhBHB, RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr -FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng -FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw -FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng -FMT, 3, 6, MODE, Mh, Mode,ThrCrs -FMT, 10, 3, STRT, , -FMT, 13, 4, EV, B, Id -FMT, 20, 6, D16, Bh, Id,Value -FMT, 21, 6, DU16, BH, Id,Value -FMT, 22, 8, D32, Bi, Id,Value -FMT, 23, 8, DU32, BI, Id,Value -FMT, 24, 8, DFLT, Bf, Id,Value -FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain -FMT, 18, 27, CAM, IHLLeccC, GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw -FMT, 19, 5, ERR, BB, Subsys,ECode -PARM, SYSID_SW_MREV, 120.0000 -PARM, SYSID_SW_TYPE, 10.00000 -PARM, SYSID_THISMAV, 1.000000 -PARM, SYSID_MYGCS, 253.0000 -PARM, SERIAL3_BAUD, 57.00000 -PARM, TELEM_DELAY, 0.000000 -PARM, RTL_ALT, 7000.000 -PARM, SONAR_ENABLE, 0.000000 -PARM, SONAR_TYPE, 0.000000 -PARM, SONAR_GAIN, 0.800000 -PARM, FS_BATT_ENABLE, 1.000000 -PARM, FS_BATT_VOLTAGE, 14.00000 -PARM, FS_BATT_MAH, 0.000000 -PARM, FS_GPS_ENABLE, 1.000000 -PARM, FS_GCS_ENABLE, 0.000000 -PARM, GPS_HDOP_GOOD, 200.0000 -PARM, MAG_ENABLE, 1.000000 -PARM, FLOW_ENABLE, 0.000000 -PARM, SUPER_SIMPLE, 0.000000 -PARM, RTL_ALT_FINAL, 0.000000 -PARM, RSSI_PIN, -1.000000 -PARM, WP_YAW_BEHAVIOR, 2.000000 -PARM, WP_TOTAL, 4.000000 -PARM, WP_INDEX, 0.000000 -PARM, CIRCLE_RADIUS, 10.00000 -PARM, CIRCLE_RATE, 20.00000 -PARM, RTL_LOIT_TIME, 5000.000 -PARM, LAND_SPEED, 50.00000 -PARM, PILOT_VELZ_MAX, 250.0000 -PARM, THR_MIN, 130.0000 -PARM, THR_MAX, 1000.000 -PARM, FS_THR_ENABLE, 1.000000 -PARM, FS_THR_VALUE, 975.0000 -PARM, TRIM_THROTTLE, 352.0000 -PARM, THR_MID, 380.0000 -PARM, FLTMODE1, 0.000000 -PARM, FLTMODE2, 5.000000 -PARM, FLTMODE3, 11.00000 -PARM, FLTMODE4, 0.000000 -PARM, FLTMODE5, 2.000000 -PARM, FLTMODE6, 6.000000 -PARM, SIMPLE, 0.000000 -PARM, LOG_BITMASK, 1854.000 -PARM, ESC, 0.000000 -PARM, TUNE, 0.000000 -PARM, TUNE_LOW, 65.00000 -PARM, TUNE_HIGH, 225.0000 -PARM, FRAME, 1.000000 -PARM, CH7_OPT, 17.00000 -PARM, CH8_OPT, 0.000000 -PARM, ARMING_CHECK, 1.000000 -PARM, ANGLE_MAX, 3500.000 -PARM, ANGLE_RATE_MAX, 18000.00 -PARM, RC1_MIN, 994.0000 -PARM, RC1_TRIM, 1507.000 -PARM, RC1_MAX, 2022.000 -PARM, RC1_REV, 1.000000 -PARM, RC1_DZ, 30.00000 -PARM, RC2_MIN, 991.0000 -PARM, RC2_TRIM, 1504.000 -PARM, RC2_MAX, 2022.000 -PARM, RC2_REV, 1.000000 -PARM, RC2_DZ, 30.00000 -PARM, RC3_MIN, 994.0000 -PARM, RC3_TRIM, 1000.000 -PARM, RC3_MAX, 2022.000 -PARM, RC3_REV, 1.000000 -PARM, RC3_DZ, 30.00000 -PARM, RC4_MIN, 1070.000 -PARM, RC4_TRIM, 1495.000 -PARM, RC4_MAX, 1938.000 -PARM, RC4_REV, 1.000000 -PARM, RC4_DZ, 10.00000 -PARM, RC5_MIN, 1175.000 -PARM, RC5_TRIM, 1178.000 -PARM, RC5_MAX, 1850.000 -PARM, RC5_REV, 1.000000 -PARM, RC5_DZ, 0.000000 -PARM, RC5_FUNCTION, 0.000000 -PARM, RC6_MIN, 991.0000 -PARM, RC6_TRIM, 1498.000 -PARM, RC6_MAX, 2022.000 -PARM, RC6_REV, 1.000000 -PARM, RC6_DZ, 0.000000 -PARM, RC6_FUNCTION, 0.000000 -PARM, RC7_MIN, 991.0000 -PARM, RC7_TRIM, 991.0000 -PARM, RC7_MAX, 994.0000 -PARM, RC7_REV, 1.000000 -PARM, RC7_DZ, 0.000000 -PARM, RC7_FUNCTION, 0.000000 -PARM, RC8_MIN, 1506.000 -PARM, RC8_TRIM, 1507.000 -PARM, RC8_MAX, 1507.000 -PARM, RC8_REV, 1.000000 -PARM, RC8_DZ, 0.000000 -PARM, RC8_FUNCTION, 0.000000 -PARM, RC10_MIN, 1100.000 -PARM, RC10_TRIM, 1500.000 -PARM, RC10_MAX, 1900.000 -PARM, RC10_REV, 1.000000 -PARM, RC10_DZ, 0.000000 -PARM, RC10_FUNCTION, 0.000000 -PARM, RC11_MIN, 1100.000 -PARM, RC11_TRIM, 1500.000 -PARM, RC11_MAX, 1900.000 -PARM, RC11_REV, 1.000000 -PARM, RC11_DZ, 0.000000 -PARM, RC11_FUNCTION, 0.000000 -PARM, RC_SPEED, 490.0000 -PARM, ACRO_RP_P, 4.500000 -PARM, ACRO_YAW_P, 3.000000 -PARM, ACRO_BAL_ROLL, 1.000000 -PARM, ACRO_BAL_PITCH, 1.000000 -PARM, ACRO_TRAINER, 2.000000 -PARM, LED_MODE, 9.000000 -PARM, RATE_RLL_P, 0.105000 -PARM, RATE_RLL_I, 0.105000 -PARM, RATE_RLL_D, 0.015000 -PARM, RATE_RLL_IMAX, 500.0000 -PARM, RATE_PIT_P, 0.075000 -PARM, RATE_PIT_I, 0.075000 -PARM, RATE_PIT_D, 0.013500 -PARM, RATE_PIT_IMAX, 500.0000 -PARM, RATE_YAW_P, 0.200000 -PARM, RATE_YAW_I, 0.020000 -PARM, RATE_YAW_D, 0.000000 -PARM, RATE_YAW_IMAX, 800.0000 -PARM, LOITER_LAT_P, 1.000000 -PARM, LOITER_LAT_I, 0.500000 -PARM, LOITER_LAT_D, 0.000000 -PARM, LOITER_LAT_IMAX, 400.0000 -PARM, LOITER_LON_P, 1.000000 -PARM, LOITER_LON_I, 0.500000 -PARM, LOITER_LON_D, 0.000000 -PARM, LOITER_LON_IMAX, 400.0000 -PARM, THR_RATE_P, 6.000000 -PARM, THR_RATE_I, 0.000000 -PARM, THR_RATE_D, 0.000000 -PARM, THR_RATE_IMAX, 300.0000 -PARM, THR_ACCEL_P, 0.750000 -PARM, THR_ACCEL_I, 1.500000 -PARM, THR_ACCEL_D, 0.000000 -PARM, THR_ACCEL_IMAX, 500.0000 -PARM, OF_RLL_P, 2.500000 -PARM, OF_RLL_I, 0.500000 -PARM, OF_RLL_D, 0.120000 -PARM, OF_RLL_IMAX, 100.0000 -PARM, OF_PIT_P, 2.500000 -PARM, OF_PIT_I, 0.500000 -PARM, OF_PIT_D, 0.120000 -PARM, OF_PIT_IMAX, 100.0000 -PARM, STB_RLL_P, 4.500000 -PARM, STB_RLL_I, 0.100000 -PARM, STB_RLL_IMAX, 800.0000 -PARM, STB_PIT_P, 4.500000 -PARM, STB_PIT_I, 0.100000 -PARM, STB_PIT_IMAX, 800.0000 -PARM, STB_YAW_P, 4.500000 -PARM, STB_YAW_I, 0.000000 -PARM, STB_YAW_IMAX, 800.0000 -PARM, THR_ALT_P, 1.000000 -PARM, THR_ALT_I, 0.000000 -PARM, THR_ALT_IMAX, 300.0000 -PARM, HLD_LAT_P, 1.000000 -PARM, HLD_LAT_I, 0.000000 -PARM, HLD_LAT_IMAX, 0.000000 -PARM, HLD_LON_P, 1.000000 -PARM, HLD_LON_I, 0.000000 -PARM, HLD_LON_IMAX, 0.000000 -PARM, CAM_TRIGG_TYPE, 0.000000 -PARM, CAM_DURATION, 10.00000 -PARM, CAM_SERVO_ON, 1300.000 -PARM, CAM_SERVO_OFF, 1100.000 -PARM, CAM_TRIGG_DIST, 0.000000 -PARM, RELAY_PIN, 13.00000 -PARM, COMPASS_OFS_X, -68.20219 -PARM, COMPASS_OFS_Y, 22.18370 -PARM, COMPASS_OFS_Z, 73.09023 -PARM, COMPASS_DEC, 0.361231 -PARM, COMPASS_LEARN, 0.000000 -PARM, COMPASS_USE, 1.000000 -PARM, COMPASS_AUTODEC, 1.000000 -PARM, COMPASS_MOTCT, 0.000000 -PARM, COMPASS_MOT_X, 0.000000 -PARM, COMPASS_MOT_Y, 0.000000 -PARM, COMPASS_MOT_Z, 0.000000 -PARM, COMPASS_ORIENT, 8.000000 -PARM, COMPASS_EXTERNAL, 1.000000 -PARM, INS_PRODUCT_ID, 88.00000 -PARM, INS_ACCSCAL_X, 0.996883 -PARM, INS_ACCSCAL_Y, 1.002162 -PARM, INS_ACCSCAL_Z, 0.987875 -PARM, INS_ACCOFFS_X, -0.064104 -PARM, INS_ACCOFFS_Y, 0.211506 -PARM, INS_ACCOFFS_Z, 1.198524 -PARM, INS_GYROFFS_X, -0.028185 -PARM, INS_GYROFFS_Y, 0.015048 -PARM, INS_GYROFFS_Z, 0.001241 -PARM, INS_MPU6K_FILTER, 0.000000 -PARM, INAV_TC_XY, 2.500000 -PARM, INAV_TC_Z, 5.000000 -PARM, WPNAV_SPEED, 500.0000 -PARM, WPNAV_RADIUS, 200.0000 -PARM, WPNAV_SPEED_UP, 250.0000 -PARM, WPNAV_SPEED_DN, 150.0000 -PARM, WPNAV_LOIT_SPEED, 500.0000 -PARM, WPNAV_ACCEL, 100.0000 -PARM, SR0_RAW_SENS, 2.000000 -PARM, SR0_EXT_STAT, 2.000000 -PARM, SR0_RC_CHAN, 2.000000 -PARM, SR0_RAW_CTRL, 2.000000 -PARM, SR0_POSITION, 2.000000 -PARM, SR0_EXTRA1, 2.000000 -PARM, SR0_EXTRA2, 2.000000 -PARM, SR0_EXTRA3, 2.000000 -PARM, SR0_PARAMS, 0.000000 -PARM, SR3_RAW_SENS, 2.000000 -PARM, SR3_EXT_STAT, 2.000000 -PARM, SR3_RC_CHAN, 2.000000 -PARM, SR3_RAW_CTRL, 2.000000 -PARM, SR3_POSITION, 2.000000 -PARM, SR3_EXTRA1, 2.000000 -PARM, SR3_EXTRA2, 2.000000 -PARM, SR3_EXTRA3, 2.000000 -PARM, SR3_PARAMS, 0.000000 -PARM, AHRS_GPS_GAIN, 1.000000 -PARM, AHRS_GPS_USE, 1.000000 -PARM, AHRS_YAW_P, 0.100000 -PARM, AHRS_RP_P, 0.100000 -PARM, AHRS_WIND_MAX, 0.000000 -PARM, AHRS_TRIM_X, 0.006394 -PARM, AHRS_TRIM_Y, 0.007151 -PARM, AHRS_TRIM_Z, 0.000000 -PARM, AHRS_ORIENTATION, 0.000000 -PARM, AHRS_COMP_BETA, 0.100000 -PARM, AHRS_GPS_MINSATS, 6.000000 -PARM, AHRS_GPS_DELAY, 2.000000 -PARM, MNT_MODE, 0.000000 -PARM, MNT_RETRACT_X, 0.000000 -PARM, MNT_RETRACT_Y, 0.000000 -PARM, MNT_RETRACT_Z, 0.000000 -PARM, MNT_NEUTRAL_X, 0.000000 -PARM, MNT_NEUTRAL_Y, 0.000000 -PARM, MNT_NEUTRAL_Z, 0.000000 -PARM, MNT_CONTROL_X, 0.000000 -PARM, MNT_CONTROL_Y, 0.000000 -PARM, MNT_CONTROL_Z, 0.000000 -PARM, MNT_STAB_ROLL, 0.000000 -PARM, MNT_STAB_TILT, 0.000000 -PARM, MNT_STAB_PAN, 0.000000 -PARM, MNT_RC_IN_ROLL, 0.000000 -PARM, MNT_ANGMIN_ROL, -4500.000 -PARM, MNT_ANGMAX_ROL, 4500.000 -PARM, MNT_RC_IN_TILT, 0.000000 -PARM, MNT_ANGMIN_TIL, -4500.000 -PARM, MNT_ANGMAX_TIL, 4500.000 -PARM, MNT_RC_IN_PAN, 0.000000 -PARM, MNT_ANGMIN_PAN, -4500.000 -PARM, MNT_ANGMAX_PAN, 4500.000 -PARM, MNT_JSTICK_SPD, 0.000000 -PARM, BATT_MONITOR, 4.000000 -PARM, BATT_VOLT_PIN, 13.00000 -PARM, BATT_CURR_PIN, 12.00000 -PARM, BATT_VOLT_MULT, 10.39689 -PARM, BATT_AMP_PERVOLT, 18.00180 -PARM, BATT_AMP_OFFSET, 0.000000 -PARM, BATT_CAPACITY, 4200.000 -PARM, GND_ABS_PRESS, 100422.4 -PARM, GND_TEMP, 24.71102 -PARM, GND_ALT_OFFSET, 0.000000 -PARM, SCHED_DEBUG, 0.000000 -PARM, FENCE_ENABLE, 1.000000 -PARM, FENCE_TYPE, 1.000000 -PARM, FENCE_ACTION, 0.000000 -PARM, FENCE_ALT_MAX, 100.0000 -PARM, FENCE_RADIUS, 150.0000 -PARM, FENCE_MARGIN, 2.000000 -PARM, GPSGLITCH_ENABLE, 1.000000 -PARM, GPSGLITCH_RADIUS, 200.0000 -PARM, GPSGLITCH_ACCEL, 1000.000 -PARM, MOT_TCRV_ENABLE, 1.000000 -PARM, MOT_TCRV_MIDPCT, 52.00000 -PARM, MOT_TCRV_MAXPCT, 93.00000 -PARM, MOT_SPIN_ARMED, 0.000000 -PARM, RCMAP_ROLL, 1.000000 -PARM, RCMAP_PITCH, 2.000000 -PARM, RCMAP_THROTTLE, 3.000000 -PARM, RCMAP_YAW, 4.000000 -MSG, ArduCopter V3.1 (5c6503e2) -MODE, STABILIZE, 352 -D32, 9, 35888 -CMD, 4, 0, 16, 0, 0, 0.00, -39.4950300, 176.7483511 -EV, 10 -GPS, 3, 109206800, 1774, 9, 2.42, -39.4950300, 176.7483511, 0.05, 46.82, 0.03, 202.77, 0.080000, 66937 -CTUN, 0, 0.00, -0.06, 0.000000, 0.00, 0, -2, 0, 0 -ATT, 0.00, -0.30, 0.00, -4.66, 0.00, 358.89, 358.89 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.10, 0.000000, 0.00, 0, -2, 0, 0 -ATT, 0.00, -0.39, 0.00, -4.71, 0.00, 358.90, 358.90 -MOT, 994, 994, 994, 994 -GPS, 3, 109214200, 1774, 9, 2.42, -39.4950310, 176.7483504, 0.04, 46.82, 0.06, 202.77, 0.140000, 67138 -CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -2, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.76, 0.00, 358.92, 358.92 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -2, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.75, 0.00, 358.93, 358.93 -MOT, 994, 994, 994, 994 -GPS, 3, 109214400, 1774, 9, 2.42, -39.4950310, 176.7483505, 0.04, 46.83, 0.04, 202.77, 0.120000, 67338 -CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -2, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.74, 0.10, 358.94, 358.94 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.75, 0.00, 358.95, 358.95 -MOT, 994, 994, 994, 994 -GPS, 3, 109214600, 1774, 9, 2.42, -39.4950310, 176.7483505, 0.03, 46.84, 0.04, 202.77, 0.090000, 67538 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 358.96, 358.96 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.03, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.76, 0.10, 358.97, 358.97 -MOT, 994, 994, 994, 994 -GPS, 3, 109214800, 1774, 9, 2.42, -39.4950310, 176.7483504, 0.02, 46.83, 0.03, 202.77, 0.120000, 67740 -CTUN, 0, 0.00, -0.08, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 0.20, 358.98, 358.98 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.04, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 0.10, 358.99, 358.99 -MOT, 994, 994, 994, 994 -DU32, 7, 270937 -CURR, 0, 0, 1691, 0, 4962, 0.000000 -GPS, 3, 109215000, 1774, 9, 2.42, -39.4950311, 176.7483504, 0.00, 46.83, 0.05, 202.77, 0.120000, 67940 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.77, 6.13, 359.00, 359.00 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.05, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 23.59, 359.01, 359.01 -MOT, 994, 994, 994, 994 -GPS, 3, 109215200, 1774, 9, 2.42, -39.4950311, 176.7483503, 0.00, 46.83, 0.02, 202.77, 0.110000, 68140 -CTUN, 0, 0.00, 0.03, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.76, 41.15, 359.02, 359.02 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.02, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 45.31, 359.02, 359.02 -MOT, 994, 994, 994, 994 -GPS, 3, 109215400, 1774, 9, 2.42, -39.4950311, 176.7483503, 0.00, 46.84, 0.03, 202.77, 0.099999, 68340 -CTUN, 0, 0.00, 0.04, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.04, 359.04 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.11, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.04, 359.04 -MOT, 994, 994, 994, 994 -GPS, 3, 109215600, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.01, 46.86, 0.01, 202.77, 0.080000, 68541 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 45.20, 359.05, 359.05 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.11, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.06, 359.06 -MOT, 994, 994, 994, 994 -GPS, 3, 109215800, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.01, 46.85, 0.03, 202.77, 0.130000, 68741 -CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.79, 45.31, 359.07, 359.07 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.07, 359.07 -MOT, 994, 994, 994, 994 -DU32, 7, 270937 -CURR, 0, 0, 1695, 0, 4962, 0.000000 -GPS, 3, 109216000, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.02, 46.87, 0.02, 202.77, 0.090000, 68941 -CTUN, 0, 0.00, 0.02, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.78, 45.20, 359.08, 359.08 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.07, 0.000000, 0.00, 0, -3, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.78, 45.31, 359.09, 359.09 -MOT, 994, 994, 994, 994 -GPS, 3, 109216200, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.03, 46.87, 0.05, 202.77, 0.110000, 69141 -CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.79, 32.73, 359.10, 359.10 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.10, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.78, 18.29, 359.11, 359.11 -MOT, 994, 994, 994, 994 -GPS, 3, 109216400, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.02, 46.89, 0.02, 202.77, 0.110000, 69341 -CTUN, 0, 0.00, -0.03, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.77, 6.75, 359.12, 359.12 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.06, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.78, 1.76, 359.13, 359.13 -MOT, 994, 994, 994, 994 -GPS, 3, 109216600, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.03, 46.89, 0.03, 202.77, 0.090000, 69541 -CTUN, 0, 0.00, 0.09, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.79, 0.00, 359.14, 359.14 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.79, 0.00, 359.14, 359.14 -MOT, 994, 994, 994, 994 -GPS, 3, 109216800, 1774, 9, 2.42, -39.4950310, 176.7483504, -0.03, 46.89, 0.05, 202.77, 0.110000, 69742 -CTUN, 0, 0.00, -0.04, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.50, 0.00, -4.78, 0.00, 359.15, 359.15 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.09, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.78, 0.00, 359.16, 359.16 -MOT, 994, 994, 994, 994 -DU32, 7, 270937 -CURR, 0, 0, 1686, 0, 4940, 0.000000 -GPS, 3, 109217000, 1774, 9, 2.42, -39.4950311, 176.7483504, -0.03, 46.89, 0.05, 202.77, 0.110000, 69942 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 0.00, 359.16, 359.16 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 0.10, 359.17, 359.17 -MOT, 994, 994, 994, 994 -GPS, 3, 109217200, 1774, 9, 2.42, -39.4950311, 176.7483505, -0.04, 46.89, 0.06, 202.77, 0.090000, 70143 -CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.77, 0.00, 359.18, 359.18 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, 0.02, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.76, 0.10, 359.19, 359.19 -MOT, 994, 994, 994, 994 -GPS, 3, 109217400, 1774, 9, 2.42, -39.4950312, 176.7483505, -0.04, 46.89, 0.05, 202.77, 0.130000, 70343 -CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.19, 359.19 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.02, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.20, 359.20 -MOT, 994, 994, 994, 994 -GPS, 3, 109217600, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.04, 46.89, 0.08, 202.77, 0.110000, 70543 -CTUN, 0, 0.00, -0.03, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.21, 359.21 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.07, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.75, 0.10, 359.22, 359.22 -MOT, 994, 994, 994, 994 -GPS, 3, 109217800, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.05, 46.90, 0.05, 202.77, 0.130000, 70744 -CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.49, 0.00, -4.75, 0.10, 359.22, 359.22 -MOT, 994, 994, 994, 994 -CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.76, 0.20, 359.23, 359.23 -MOT, 994, 994, 994, 994 -DU32, 7, 270937 -CURR, 0, 0, 1690, 0, 4962, 0.000000 -CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.48, 0.00, -4.77, 0.20, 359.23, 359.23 -MOT, 994, 994, 994, 994 -GPS, 3, 109218000, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.06, 46.90, 0.07, 202.77, 0.140000, 70963 -CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 -ATT, 0.00, -0.47, 0.00, -4.76, 0.10, 359.24, 359.24 -MOT, 994, 994, 994, 994 -EV, 15 -GPS, 3, 109218200, 1774, 9, 2.42, -39.4950313, 176.7483506, -0.07, 46.90, 0.08, 202.77, 0.160000, 71145 -CTUN, 135, 0.00, -0.10, 0.000000, 0.00, 0, -4, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.76, 0.10, 359.24, 359.24 -MOT, 1149, 1130, 1152, 1127 -CTUN, 137, 0.00, -0.04, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.46, 0.00, -4.76, 0.10, 359.25, 359.25 -MOT, 1163, 1130, 1162, 1127 -GPS, 3, 109218400, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.08, 46.89, 0.07, 202.77, 0.140000, 71345 -CTUN, 137, 0.00, -0.04, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.46, 0.00, -4.75, 0.10, 359.27, 359.27 -MOT, 1162, 1129, 1160, 1127 -CTUN, 135, 0.00, -0.07, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.73, 0.20, 359.28, 359.28 -MOT, 1166, 1140, 1171, 1127 -GPS, 3, 109218600, 1774, 9, 2.42, -39.4950313, 176.7483506, -0.09, 46.90, 0.05, 202.77, 0.099999, 71545 -CTUN, 135, 0.00, 0.00, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.71, 0.00, 359.31, 359.31 -MOT, 1156, 1127, 1160, 1127 -CTUN, 137, 0.00, -0.02, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.49, 0.00, -4.71, 0.10, 359.32, 359.32 -MOT, 1159, 1149, 1181, 1127 -GPS, 3, 109218800, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.09, 46.90, 0.06, 202.77, 0.140000, 71746 -CTUN, 135, 0.00, -0.04, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.48, 0.00, -4.71, 0.00, 359.33, 359.33 -MOT, 1169, 1129, 1167, 1127 -CTUN, 135, 0.00, -0.04, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.48, 0.00, -4.71, 0.00, 359.34, 359.34 -MOT, 1166, 1145, 1183, 1127 -DU32, 7, 270969 -CURR, 133, 1069, 1688, 340, 4962, 1.545313 -GPS, 3, 109219000, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.09, 46.90, 0.08, 202.77, 0.120000, 71946 -CTUN, 137, 0.00, -0.05, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.47, 0.00, -4.70, 0.00, 359.35, 359.35 -MOT, 1178, 1128, 1179, 1127 -CTUN, 137, 0.00, -0.12, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.47, 0.00, -4.68, 0.00, 359.36, 359.36 -MOT, 1175, 1143, 1192, 1127 -GPS, 3, 109219200, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.11, 46.90, 0.04, 202.77, 0.099999, 72146 -CTUN, 137, 0.00, -0.12, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.47, 0.00, -4.68, 0.10, 359.37, 359.37 -MOT, 1176, 1130, 1179, 1127 -CTUN, 135, 0.00, -0.08, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.69, 0.10, 359.38, 359.38 -MOT, 1198, 1127, 1185, 1140 -GPS, 3, 109219400, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.12, 46.91, 0.03, 202.77, 0.110000, 72347 -CTUN, 135, 0.00, -0.14, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.48, 0.00, -4.69, 0.10, 359.38, 359.38 -MOT, 1181, 1141, 1192, 1127 -CTUN, 135, 0.00, -0.09, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.68, 0.00, 359.40, 359.40 -MOT, 1176, 1151, 1200, 1127 -GPS, 3, 109219600, 1774, 9, 2.42, -39.4950314, 176.7483505, -0.13, 46.92, 0.04, 202.77, 0.099999, 72547 -CTUN, 135, 0.00, -0.05, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.46, 0.00, -4.68, 0.00, 359.41, 359.41 -MOT, 1181, 1127, 1179, 1129 -CTUN, 135, 0.00, -0.15, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.48, 0.00, -4.67, 0.00, 359.42, 359.42 -MOT, 1191, 1136, 1200, 1127 -GPS, 3, 109219800, 1774, 9, 2.42, -39.4950314, 176.7483505, -0.14, 46.91, 0.03, 202.77, 0.099999, 72747 -CTUN, 135, 0.00, -0.12, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.48, 0.00, -4.66, 0.00, 359.42, 359.42 -MOT, 1190, 1129, 1192, 1127 -CTUN, 135, 0.00, -0.12, 0.000000, 0.00, 0, -5, 133, 0 -ATT, 0.00, -0.47, 0.00, -4.65, 0.00, 359.43, 359.43 -MOT, 1187, 1147, 1207, 1127 -DU32, 7, 270969 -CURR, 134, 2401, 1674, 335, 4940, 2.455562 -GPS, 3, 109220000, 1774, 9, 2.42, -39.4950315, 176.7483504, -0.15, 46.90, 0.03, 202.77, 0.090000, 72948 -CTUN, 137, 0.00, -0.14, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.47, 0.00, -4.66, 0.00, 359.44, 359.44 -MOT, 1183, 1139, 1196, 1127 -CTUN, 137, 0.00, -0.10, 0.000000, 0.00, 0, -5, 134, 0 -ATT, 0.00, -0.47, 0.00, -4.65, 0.00, 359.45, 359.45 -MOT, 1199, 1149, 1221, 1127 -GPS, 3, 109220200, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.16, 46.90, 0.03, 202.77, 0.090000, 73148 -CTUN, 138, 0.00, 0.04, 0.000000, 0.00, 0, -6, 135, 0 -ATT, 0.00, -0.47, 0.00, -4.64, 0.00, 359.46, 359.46 -MOT, 1202, 1129, 1200, 1127 -CTUN, 137, 0.00, -0.13, 0.000000, 0.00, 0, -6, 134, 0 -ATT, 0.00, -0.48, 0.00, -4.62, 0.20, 359.47, 359.47 -MOT, 1198, 1129, 1196, 1127 -GPS, 3, 109220400, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.16, 46.91, 0.04, 202.77, 0.099999, 73348 -CTUN, 140, 0.00, -0.04, 0.000000, 0.00, 0, -6, 136, 0 -ATT, 0.00, -0.48, 0.00, -4.61, 0.10, 359.48, 359.48 -MOT, 1210, 1140, 1219, 1127 -CTUN, 141, 0.00, -0.04, 0.000000, 0.00, 0, -5, 137, 0 -ATT, 0.00, -0.48, 0.00, -4.59, 0.20, 359.49, 359.49 -MOT, 1200, 1143, 1213, 1127 -GPS, 3, 109220600, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.15, 46.91, 0.03, 202.77, 0.110000, 73549 -CTUN, 164, 0.00, -0.09, 0.000000, 0.00, 0, -6, 152, 0 -ATT, 0.00, -0.47, 0.00, -4.57, 0.10, 359.49, 359.49 -MOT, 1200, 1137, 1211, 1127 -CTUN, 166, 0.00, -0.24, 0.000000, 0.00, 0, -6, 154, 0 -ATT, 0.00, -0.47, 0.00, -4.58, 0.20, 359.50, 359.50 -MOT, 1208, 1138, 1211, 1127 -GPS, 3, 109220800, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.17, 46.91, 0.03, 202.77, 0.110000, 73749 -CTUN, 169, 0.00, 0.00, 0.000000, 0.00, 0, -6, 156, 0 -ATT, 0.00, -0.47, 0.00, -4.56, 0.10, 359.52, 359.52 -MOT, 1214, 1145, 1228, 1127 -CTUN, 177, 0.00, -0.02, 0.000000, 0.00, 0, -6, 161, 0 -ATT, 0.00, -0.48, 0.00, -4.54, 0.10, 359.52, 359.52 -MOT, 1217, 1152, 1238, 1127 -DU32, 7, 270969 -CURR, 167, 3831, 1683, 411, 4962, 3.494093 -PM, 0, 0, 1, 1000, 7381955, 0, 0, 0, 0 -GPS, 3, 109221000, 1774, 9, 2.42, -39.4950317, 176.7483504, -0.16, 46.91, 0.06, 202.77, 0.130000, 73949 -CTUN, 188, 0.00, -0.01, 0.000000, 0.00, 0, -6, 169, 0 -ATT, 0.00, -0.48, 0.00, -4.52, 0.10, 359.53, 359.53 -MOT, 1228, 1148, 1244, 1127 -CTUN, 201, 0.00, -0.15, 0.000000, 0.00, 0, -5, 177, 0 -ATT, 0.00, -0.48, 0.00, -4.51, 0.20, 359.54, 359.54 -MOT, 1221, 1146, 1236, 1127 -EV, 28 -GPS, 3, 109221200, 1774, 9, 2.42, -39.4950318, 176.7483503, -0.17, 46.91, 0.03, 202.77, 0.110000, 74149 -CTUN, 214, 0.00, 0.05, 0.000000, 0.00, 0, -5, 186, 0 -ATT, 0.00, -0.48, 0.00, -4.48, 0.10, 359.55, 359.54 -MOT, 1222, 1153, 1240, 1135 -EV, 16 -CTUN, 230, 0.00, -0.23, 0.000000, 0.00, 0, -4, 197, 0 -ATT, 0.00, -0.49, 0.00, -4.45, 0.10, 359.56, 359.54 -MOT, 1242, 1158, 1258, 1138 -GPS, 3, 109221400, 1774, 9, 2.42, -39.4950318, 176.7483503, -0.17, 46.92, 0.02, 202.77, 0.110000, 74350 -CTUN, 243, 0.00, -0.06, 0.000000, 0.00, 0, -4, 206, 0 -ATT, 0.00, -0.49, 0.00, -4.40, 0.10, 359.58, 359.54 -MOT, 1255, 1162, 1255, 1162 -CTUN, 259, 0.00, -0.08, 0.000000, 0.00, 0, -5, 217, 0 -ATT, 0.00, -0.50, 0.00, -4.34, 0.10, 359.59, 359.54 -MOT, 1254, 1189, 1280, 1162 -GPS, 3, 109221600, 1774, 9, 2.42, -39.4950319, 176.7483503, -0.17, 46.91, 0.03, 202.77, 0.099999, 74550 -CTUN, 263, 0.00, 0.00, 0.000000, 0.00, 0, -4, 219, 0 -ATT, 0.00, -0.52, 0.00, -4.25, 0.10, 359.60, 359.54 -MOT, 1261, 1186, 1275, 1172 -CTUN, 282, 0.00, 0.00, 0.000000, 0.00, 0, -4, 232, 0 -ATT, 0.00, -0.53, 0.00, -4.15, 0.10, 359.62, 359.54 -MOT, 1270, 1205, 1296, 1178 -GPS, 3, 109221800, 1774, 9, 2.42, -39.4950319, 176.7483503, -0.16, 46.92, 0.02, 202.77, 0.080000, 74750 -CTUN, 293, 0.00, 0.00, 0.000000, 0.00, 0, -4, 238, 0 -ATT, 0.00, -0.54, 0.00, -4.06, 0.10, 359.64, 359.54 -MOT, 1275, 1212, 1300, 1187 -CTUN, 295, 0.00, -0.18, 0.000000, 0.00, 0, -3, 241, 0 -ATT, 0.00, -0.55, 0.00, -4.06, 0.20, 359.65, 359.54 -MOT, 1294, 1199, 1292, 1201 -DU32, 7, 270713 -CURR, 246, 5903, 1642, 795, 4940, 5.161857 -GPS, 3, 109222000, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.16, 46.92, 0.03, 202.77, 0.090000, 74950 -CTUN, 306, 0.00, -0.28, 0.000000, 0.00, 0, -4, 248, 0 -ATT, 0.00, -0.55, 0.00, -3.94, 0.51, 359.67, 359.57 -MOT, 1308, 1205, 1299, 1205 -CTUN, 321, 0.00, -0.06, 0.000000, 0.00, 0, -4, 257, 0 -ATT, 0.00, -0.57, 0.00, -3.88, 0.72, 359.70, 359.75 -MOT, 1313, 1227, 1312, 1207 -GPS, 3, 109222200, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.17, 46.93, 0.03, 202.77, 0.099999, 75151 -CTUN, 321, 0.00, -0.10, 0.000000, 0.00, 0, -5, 259, 0 -ATT, 0.00, -0.56, 0.00, -3.79, 1.66, 359.72, 0.08 -MOT, 1304, 1254, 1307, 1201 -CTUN, 332, 0.00, -0.19, 0.000000, 0.00, 0, -5, 264, 0 -ATT, 0.00, -0.59, 0.00, -3.65, 1.97, 359.76, 0.60 -MOT, 1307, 1275, 1316, 1190 -GPS, 3, 109222400, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.18, 46.93, 0.04, 202.77, 0.110000, 75351 -CTUN, 337, 0.00, -0.17, 0.000000, 0.00, 0, -6, 269, 0 -ATT, 0.00, -0.63, 0.00, -3.58, 2.70, 359.80, 1.29 -MOT, 1335, 1276, 1302, 1195 -CTUN, 355, 0.00, -0.12, 0.000000, 0.00, 0, -5, 278, 0 -ATT, 0.00, -0.65, 0.00, -3.44, 2.70, 359.83, 2.06 -MOT, 1376, 1275, 1292, 1203 -GPS, 3, 109222600, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.18, 46.94, 0.04, 202.77, 0.110000, 75551 -CTUN, 366, 0.00, -0.18, 0.000000, 0.00, 0, -5, 289, 0 -ATT, 0.00, -0.70, 0.00, -3.30, 2.70, 359.88, 2.79 -MOT, 1393, 1298, 1303, 1202 -CTUN, 371, 0.00, -0.03, 0.000000, 0.00, 0, -4, 290, 0 -ATT, 0.00, -0.77, 0.00, -2.97, 4.57, 359.94, 4.05 -MOT, 1387, 1349, 1286, 1180 -GPS, 3, 109222800, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.19, 46.96, 0.02, 202.77, 0.090000, 75752 -CTUN, 387, 0.00, -0.12, 0.000000, 0.00, 0, -4, 303, 0 -ATT, 0.00, -0.85, 0.00, -2.54, 4.46, 0.01, 5.42 -MOT, 1397, 1389, 1298, 1172 -CTUN, 398, 0.00, -0.09, 0.000000, 0.00, 0, -4, 309, 0 -ATT, 0.00, -0.95, 0.00, -2.03, 4.88, 0.12, 6.77 -MOT, 1418, 1408, 1287, 1169 -DU32, 7, 270713 -CURR, 316, 8656, 1641, 1523, 4940, 8.217794 -GPS, 3, 109223000, 1774, 9, 2.42, -39.4950321, 176.7483503, -0.19, 46.97, 0.06, 202.77, 0.090000, 75952 -CTUN, 408, 0.00, -0.18, 0.000000, 0.00, 0, -3, 316, 0 -ATT, 0.00, -1.09, 0.00, -1.41, 5.50, 0.26, 8.26 -MOT, 1441, 1429, 1277, 1163 -CTUN, 429, 0.00, -0.17, 0.000000, 0.00, 0, -3, 332, 0 -ATT, 0.00, -1.10, 0.00, -0.32, 5.40, 0.44, 9.86 -MOT, 1485, 1454, 1243, 1199 -GPS, 3, 109223200, 1774, 9, 2.42, -39.4950321, 176.7483502, -0.19, 46.98, 0.04, 202.77, 0.099999, 76152 -CTUN, 442, 0.00, -0.43, 0.000000, 0.00, 0, 0, 339, 0 -ATT, 0.00, -1.04, 0.00, 1.68, 5.50, 0.82, 10.82 -MOT, 1477, 1477, 1227, 1231 -CTUN, 458, 0.00, -0.28, 0.000000, 0.00, 0, 3, 351, 0 -ATT, 0.00, -0.75, 0.00, 4.65, 5.71, 1.36, 11.36 -MOT, 1469, 1509, 1222, 1262 -GPS, 3, 109223400, 1774, 9, 2.42, -39.4950323, 176.7483502, -0.20, 47.00, 0.11, 202.77, 0.060000, 76353 -CTUN, 476, 0.00, -0.40, 0.000000, 0.00, 2, 7, 365, 0 -ATT, 0.00, -0.13, -0.50, 8.25, 6.02, 2.34, 12.34 -MOT, 1453, 1538, 1226, 1306 -CTUN, 476, 0.00, -0.29, 0.000000, 0.00, 4, 12, 367, 0 -ATT, 0.00, 0.47, -4.20, 11.64, 6.13, 3.80, 13.80 -MOT, 1489, 1489, 1257, 1299 -GPS, 3, 109223600, 1774, 9, 2.42, -39.4950327, 176.7483503, -0.19, 47.03, 0.23, 202.77, 0.000000, 76553 -CTUN, 476, 0.00, -0.15, 0.000000, 0.00, 5, 17, 368, 0 -ATT, 0.00, 0.75, -5.07, 12.38, 5.81, 6.07, 15.58 -MOT, 1430, 1505, 1336, 1267 -CTUN, 476, 0.00, 0.11, 0.000000, 0.00, 4, 17, 367, 0 -ATT, 0.00, 0.11, -5.93, 11.30, 4.46, 8.96, 17.13 -MOT, 1383, 1499, 1372, 1279 -GPS, 3, 109223800, 1774, 9, 2.42, -39.4950337, 176.7483505, -0.14, 47.07, 0.56, 179.17, -0.080000, 76753 -CTUN, 476, 0.00, 0.16, 0.000000, 0.00, 3, 19, 365, 0 -ATT, 0.00, -0.31, -6.15, 9.21, 2.39, 11.72, 18.03 -MOT, 1390, 1438, 1391, 1307 -CTUN, 476, 0.00, 0.31, 0.000000, 0.00, 1, 21, 364, 0 -ATT, 0.00, -0.33, -6.37, 6.23, 1.66, 14.06, 18.55 -MOT, 1364, 1440, 1413, 1303 -DU32, 7, 270713 -CURR, 363, 12184, 1622, 2053, 4897, 13.83383 -GPS, 3, 109224000, 1774, 9, 2.42, -39.4950352, 176.7483507, -0.05, 47.11, 0.81, 176.44, -0.110000, 76954 -CTUN, 476, 0.00, 0.17, 0.000000, 0.00, 0, 22, 363, 0 -ATT, 0.00, -0.61, -7.02, 3.43, 0.83, 15.98, 18.83 -MOT, 1356, 1423, 1399, 1338 -CTUN, 476, 0.00, 0.01, 0.000000, 0.00, 0, 22, 363, 0 -ATT, 0.00, -0.96, -7.45, 1.47, 0.10, 17.30, 18.83 -MOT, 1348, 1417, 1410, 1342 -GPS, 3, 109224200, 1774, 9, 2.42, -39.4950373, 176.7483507, 0.01, 47.16, 1.14, 177.70, -0.120000, 77153 -CTUN, 474, 0.00, 0.28, 0.000000, 0.00, 0, 20, 362, 0 -ATT, 0.00, -1.68, -9.20, -0.10, 0.10, 18.20, 18.83 -MOT, 1360, 1400, 1392, 1360 -CTUN, 474, 0.00, 0.19, 0.000000, 0.00, 0, 19, 362, 0 -ATT, 0.00, -1.81, -11.66, -2.54, 0.00, 18.80, 18.83 -MOT, 1367, 1392, 1396, 1358 -GPS, 3, 109224400, 1774, 9, 2.42, -39.4950396, 176.7483506, 0.07, 47.21, 1.28, 179.83, -0.170000, 77354 -CTUN, 474, 0.00, 0.14, 0.000000, 0.00, 0, 15, 362, 0 -ATT, 1.87, -1.93, -17.09, -5.55, 0.00, 19.22, 18.83 -MOT, 1362, 1394, 1385, 1371 -CTUN, 474, 0.00, 0.33, 0.000000, 0.00, 2, 11, 364, 0 -ATT, 2.38, -0.95, -19.05, -9.25, 0.10, 19.47, 18.83 -MOT, 1360, 1402, 1382, 1376 -GPS, 3, 109224600, 1774, 9, 2.42, -39.4950419, 176.7483504, 0.12, 47.23, 1.24, 182.10, -0.099999, 77554 -CTUN, 474, 0.00, 0.36, 0.000000, 0.00, 5, 7, 367, 0 -ATT, 1.72, 0.00, -19.49, -12.80, 0.20, 19.61, 18.83 -MOT, 1387, 1387, 1397, 1363 -CTUN, 476, 0.00, 0.39, 0.000000, 0.00, 7, 3, 369, 0 -ATT, 0.00, 0.40, -17.31, -15.07, 0.20, 19.68, 18.83 -MOT, 1431, 1347, 1422, 1342 -GPS, 3, 109224800, 1774, 9, 2.42, -39.4950437, 176.7483502, 0.16, 47.26, 1.06, 182.40, 0.000000, 77755 -CTUN, 513, 0.00, 0.60, 0.000000, 0.00, 10, 2, 406, 0 -ATT, 0.00, 0.31, -12.09, -15.19, 0.20, 19.74, 18.83 -MOT, 1385, 1472, 1403, 1441 -CTUN, 524, 0.00, 0.74, 0.000000, 0.00, 7, 7, 413, 0 -ATT, 0.00, 0.24, -10.57, -13.00, 0.10, 19.61, 18.83 -MOT, 1438, 1446, 1428, 1419 -DU32, 7, 270713 -CURR, 417, 15902, 1593, 2783, 4897, 19.21214 -GPS, 3, 109225000, 1774, 9, 2.42, -39.4950449, 176.7483505, 0.23, 47.26, 0.68, 179.00, 0.099999, 77955 -CTUN, 526, 0.00, 0.57, 0.000000, 0.00, 5, 23, 417, 0 -ATT, 0.00, -0.04, -11.37, -10.70, 0.00, 19.28, 18.83 -MOT, 1418, 1485, 1430, 1415 -CTUN, 524, 0.00, 0.39, 0.000000, 0.00, 3, 39, 412, 0 -ATT, 0.00, -0.23, -12.46, -9.43, 0.00, 18.86, 18.83 -MOT, 1404, 1499, 1420, 1403 -GPS, 3, 109225200, 1774, 9, 2.42, -39.4950454, 176.7483510, 0.34, 47.31, 0.36, 173.65, 0.010000, 78155 -CTUN, 524, 0.00, 0.42, 0.000000, 0.00, 3, 53, 412, 0 -ATT, 0.00, -0.81, -13.33, -8.64, 0.00, 18.51, 18.83 -MOT, 1425, 1476, 1415, 1411 -CTUN, 524, 0.00, 0.56, 0.000000, 0.00, 2, 69, 411, 0 -ATT, 0.00, -1.30, -13.18, -7.87, 0.00, 18.29, 18.83 -MOT, 1421, 1476, 1423, 1402 -GPS, 3, 109225400, 1774, 9, 2.42, -39.4950451, 176.7483520, 0.50, 47.44, 0.45, 118.53, -0.210000, 78355 -CTUN, 524, 0.00, 0.79, 0.000000, 0.00, 2, 87, 411, 0 -ATT, 0.00, -1.38, -13.18, -7.60, 0.00, 18.27, 18.83 -MOT, 1399, 1492, 1414, 1418 -CTUN, 526, 0.00, 0.67, 0.000000, 0.00, 2, 105, 414, 0 -ATT, 0.00, -1.24, -12.96, -7.22, 0.10, 18.34, 18.83 -MOT, 1428, 1470, 1398, 1440 -GPS, 3, 109225600, 1774, 9, 2.42, -39.4950444, 176.7483530, 0.75, 47.60, 0.52, 71.44, -0.440000, 78555 -CTUN, 524, 0.00, 0.90, 0.000000, 0.00, 2, 123, 411, 0 -ATT, 0.00, -1.08, -13.11, -7.11, 1.66, 18.40, 19.10 -MOT, 1422, 1488, 1414, 1399 -CTUN, 524, 0.00, 1.16, 0.000000, 0.00, 2, 141, 411, 0 -ATT, 0.00, -0.93, -13.40, -7.60, 3.22, 18.77, 19.85 -MOT, 1413, 1505, 1402, 1402 -GPS, 3, 109225800, 1774, 9, 2.42, -39.4950432, 176.7483540, 1.07, 47.84, 0.74, 48.24, -0.760000, 78756 -CTUN, 524, 0.00, 1.30, 0.000000, 0.00, 2, 159, 411, 0 -ATT, 0.00, -0.93, -13.98, -8.22, 2.70, 19.63, 20.77 -MOT, 1430, 1465, 1396, 1432 -CTUN, 524, 0.00, 1.40, 0.000000, 0.00, 3, 173, 412, 0 -ATT, 0.00, -0.74, -14.92, -8.89, 0.10, 20.61, 21.11 -MOT, 1392, 1470, 1429, 1437 -DU32, 7, 270713 -CURR, 402, 20022, 1589, 2437, 4940, 26.21315 -GPS, 3, 109226000, 1774, 9, 2.42, -39.4950418, 176.7483550, 1.47, 48.11, 0.86, 37.28, -1.030000, 78956 -CTUN, 516, 0.00, 1.59, 0.000000, 0.00, 3, 188, 402, 0 -ATT, 0.00, -0.47, -15.36, -9.77, 0.10, 21.26, 21.11 -MOT, 1413, 1434, 1409, 1430 -CTUN, 510, 0.00, 1.90, 0.000000, 0.00, 4, 195, 400, 0 -ATT, 0.00, -0.19, -15.36, -10.45, 0.10, 21.62, 21.11 -MOT, 1387, 1456, 1399, 1435 -GPS, 3, 109226200, 1774, 9, 2.42, -39.4950400, 176.7483562, 1.91, 48.43, 1.10, 32.72, -1.270000, 79156 -CTUN, 508, 0.00, 2.19, 0.000000, 0.00, 4, 198, 393, 0 -ATT, 0.00, 0.00, -15.36, -10.50, 0.00, 21.80, 21.11 -MOT, 1390, 1442, 1405, 1410 -CTUN, 509, 0.00, 2.33, 0.000000, 0.00, 4, 197, 395, 0 -ATT, 0.00, 0.45, -15.36, -10.52, 0.10, 21.79, 21.11 -MOT, 1382, 1460, 1381, 1432 -GPS, 3, 109226400, 1774, 9, 2.42, -39.4950380, 176.7483577, 2.36, 48.77, 1.26, 30.97, -1.420000, 79356 -CTUN, 497, 0.00, 2.47, 0.000000, 0.00, 4, 194, 381, 0 -ATT, 0.00, 0.93, -15.79, -10.36, 0.00, 21.68, 21.11 -MOT, 1379, 1438, 1373, 1402 -CTUN, 500, 0.00, 2.66, 0.000000, 0.00, 4, 190, 384, 0 -ATT, 0.00, 1.19, -15.57, -10.34, 0.00, 21.48, 21.11 -MOT, 1388, 1438, 1354, 1425 -GPS, 3, 109226600, 1774, 9, 2.42, -39.4950356, 176.7483592, 2.79, 49.14, 1.42, 29.03, -1.450000, 79557 -CTUN, 500, 0.00, 2.99, 0.000000, 0.00, 4, 186, 384, 0 -ATT, 0.00, 1.50, -15.14, -10.38, 0.10, 21.30, 21.11 -MOT, 1378, 1454, 1382, 1391 -CTUN, 500, 0.00, 3.26, 0.000000, 0.00, 4, 182, 384, 0 -ATT, 0.00, 1.30, -15.14, -10.37, 0.00, 21.20, 21.11 -MOT, 1371, 1457, 1352, 1425 -GPS, 3, 109226800, 1774, 9, 2.42, -39.4950329, 176.7483611, 3.21, 49.45, 1.67, 29.62, -1.390000, 79757 -CTUN, 500, 0.00, 3.42, 0.000000, 0.00, 4, 179, 384, 0 -ATT, 0.00, 1.18, -14.92, -10.56, 0.10, 21.12, 21.11 -MOT, 1370, 1464, 1373, 1398 -CTUN, 500, 0.00, 3.67, 0.000000, 0.00, 4, 176, 384, 0 -ATT, 0.00, 0.85, -14.70, -10.80, 0.00, 20.95, 21.11 -MOT, 1369, 1470, 1381, 1385 -DU32, 7, 270713 -CURR, 384, 23918, 1638, 2120, 4897, 32.12435 -GPS, 3, 109227000, 1774, 9, 2.42, -39.4950300, 176.7483634, 3.62, 49.75, 1.83, 31.55, -1.350000, 79958 -CTUN, 500, 0.00, 3.83, 0.000000, 0.00, 4, 174, 384, 0 -ATT, 0.00, 0.45, -14.63, -11.14, 0.10, 20.79, 21.11 -MOT, 1372, 1469, 1365, 1399 -CTUN, 503, 0.00, 3.89, 0.000000, 0.00, 4, 168, 384, 0 -ATT, 0.00, 0.13, -14.70, -11.26, 0.00, 20.62, 21.11 -MOT, 1365, 1477, 1365, 1397 -GPS, 3, 109227200, 1774, 9, 2.42, -39.4950269, 176.7483658, 4.00, 50.04, 2.00, 31.76, -1.300000, 80158 -CTUN, 500, 0.00, 4.25, 0.000000, 0.00, 4, 163, 384, 0 -ATT, 0.00, 0.06, -15.14, -11.37, 0.20, 20.55, 21.11 -MOT, 1381, 1461, 1369, 1394 -CTUN, 500, 0.00, 4.39, 0.000000, 0.00, 5, 160, 388, 0 -ATT, 0.00, -0.15, -15.36, -11.64, 0.00, 20.49, 21.11 -MOT, 1359, 1490, 1368, 1405 -GPS, 3, 109227400, 1774, 9, 2.42, -39.4950235, 176.7483682, 4.37, 50.31, 2.13, 30.68, -1.250000, 80358 -CTUN, 503, 0.00, 4.46, 0.000000, 0.00, 5, 158, 388, 0 -ATT, 0.00, -0.31, -14.92, -11.66, 0.00, 20.48, 21.11 -MOT, 1400, 1442, 1368, 1412 -CTUN, 503, 0.00, 4.79, 0.000000, 0.00, 5, 158, 385, 0 -ATT, 0.00, 0.04, -14.92, -11.49, 0.00, 20.48, 21.11 -MOT, 1389, 1454, 1361, 1405 -GPS, 3, 109227600, 1774, 9, 2.42, -39.4950198, 176.7483708, 4.74, 50.60, 2.27, 30.25, -1.230000, 80558 -CTUN, 500, 0.00, 4.93, 0.000000, 0.00, 5, 158, 385, 0 -ATT, 0.00, 0.21, -15.14, -11.76, 0.10, 20.41, 21.11 -MOT, 1372, 1473, 1355, 1410 -CTUN, 500, 0.00, 5.11, 0.000000, 0.00, 5, 156, 388, 0 -ATT, 0.00, 0.28, -15.28, -11.83, 0.10, 20.37, 21.11 -MOT, 1385, 1463, 1369, 1404 -GPS, 3, 109227800, 1774, 9, 2.42, -39.4950159, 176.7483734, 5.10, 50.89, 2.38, 29.46, -1.240000, 80759 -CTUN, 500, 0.00, 5.32, 0.000000, 0.00, 5, 156, 385, 0 -ATT, 0.00, 0.46, -16.15, -12.29, 0.00, 20.51, 21.11 -MOT, 1402, 1432, 1369, 1407 -CTUN, 503, 0.00, 5.40, 0.000000, 0.00, 6, 157, 389, 0 -ATT, 0.00, 0.46, -15.79, -12.76, 0.10, 20.62, 21.11 -MOT, 1356, 1489, 1376, 1405 -DU32, 7, 270713 -CURR, 386, 27772, 1632, 2005, 4876, 37.88295 -GPS, 3, 109228000, 1774, 9, 2.42, -39.4950118, 176.7483761, 5.46, 51.19, 2.51, 28.74, -1.250000, 80960 -CTUN, 500, 0.00, 5.62, 0.000000, 0.00, 6, 157, 386, 0 -ATT, 0.00, 0.21, -16.22, -12.96, 0.00, 20.73, 21.11 -MOT, 1334, 1496, 1344, 1439 -CTUN, 500, 0.00, 5.52, 0.000000, 0.00, 6, 158, 386, 0 -ATT, 0.00, 0.19, -16.44, -13.16, 0.10, 20.91, 21.11 -MOT, 1378, 1454, 1369, 1413 -GPS, 3, 109228200, 1774, 9, 2.42, -39.4950075, 176.7483790, 5.80, 51.46, 2.68, 28.42, -1.240000, 81159 -CTUN, 500, 0.00, 5.89, 0.000000, 0.00, 7, 159, 387, 0 -ATT, 0.00, 0.20, -16.44, -13.53, 0.00, 21.00, 21.11 -MOT, 1373, 1463, 1381, 1400 -CTUN, 500, 0.00, 5.98, 0.000000, 0.00, 7, 158, 387, 0 -ATT, 0.00, 0.49, -17.09, -14.01, 0.00, 21.04, 21.11 -MOT, 1393, 1441, 1368, 1416 -GPS, 3, 109228400, 1774, 9, 2.42, -39.4950029, 176.7483821, 6.15, 51.73, 2.84, 28.05, -1.260000, 81360 -CTUN, 500, 0.00, 6.09, 0.000000, 0.00, 7, 160, 387, 0 -ATT, 0.00, 0.49, -17.31, -14.25, 0.10, 21.04, 21.11 -MOT, 1370, 1464, 1357, 1427 -CTUN, 500, 0.00, 6.40, 0.000000, 0.00, 8, 164, 388, 0 -ATT, 0.00, 0.63, -17.53, -14.34, 0.00, 20.95, 21.11 -MOT, 1380, 1458, 1357, 1427 -GPS, 3, 109228600, 1774, 9, 2.42, -39.4949981, 176.7483851, 6.51, 52.03, 2.94, 27.33, -1.260000, 81560 -CTUN, 500, 0.00, 6.60, 0.000000, 0.00, 8, 168, 388, 0 -ATT, 0.00, 0.53, -17.74, -14.31, 0.10, 20.90, 21.11 -MOT, 1335, 1510, 1362, 1415 -CTUN, 500, 0.00, 6.98, 0.000000, 0.00, 7, 171, 387, 0 -ATT, 0.00, 0.33, -17.74, -14.12, 0.00, 20.89, 21.11 -MOT, 1377, 1463, 1369, 1409 -GPS, 3, 109228800, 1774, 9, 2.42, -39.4949930, 176.7483886, 6.89, 52.30, 3.15, 27.74, -1.280000, 81761 -CTUN, 500, 0.00, 7.05, 0.000000, 0.00, 8, 167, 388, 0 -ATT, 0.00, 0.40, -17.74, -14.67, 0.00, 20.87, 21.11 -MOT, 1372, 1466, 1355, 1429 -CTUN, 500, 0.00, 7.29, 0.000000, 0.00, 8, 167, 388, 0 -ATT, 0.00, 0.69, -17.31, -14.84, 0.10, 20.94, 21.11 -MOT, 1368, 1473, 1358, 1423 -DU32, 7, 270713 -CURR, 388, 31650, 1629, 2171, 4940, 43.74749 -GPS, 3, 109229000, 1774, 9, 2.42, -39.4949878, 176.7483920, 7.28, 52.59, 3.25, 27.40, -1.320000, 81961 -CTUN, 500, 0.00, 7.41, 0.000000, 0.00, 8, 168, 388, 0 -ATT, 0.00, 0.68, -17.53, -14.85, 0.00, 21.12, 21.11 -MOT, 1373, 1453, 1353, 1443 -CTUN, 500, 0.00, 7.54, 0.000000, 0.00, 8, 168, 388, 0 -ATT, 0.00, 0.77, -18.83, -14.96, 0.00, 21.21, 21.11 -MOT, 1382, 1450, 1380, 1410 -GPS, 3, 109229200, 1774, 9, 2.42, -39.4949823, 176.7483955, 7.66, 52.88, 3.35, 26.84, -1.320000, 82161 -CTUN, 500, 0.00, 7.68, 0.000000, 0.00, 9, 169, 389, 0 -ATT, 0.00, 0.76, -19.27, -15.77, 0.10, 21.32, 21.11 -MOT, 1360, 1472, 1353, 1441 -CTUN, 500, 0.00, 7.81, 0.000000, 0.00, 10, 167, 390, 0 -ATT, 0.00, 0.75, -18.83, -16.59, 0.00, 21.40, 21.11 -MOT, 1372, 1458, 1380, 1420 -GPS, 3, 109229400, 1774, 9, 2.42, -39.4949768, 176.7483993, 8.02, 53.14, 3.47, 27.21, -1.320000, 82361 -CTUN, 503, 0.00, 8.12, 0.000000, 0.00, 11, 168, 394, 0 -ATT, 0.00, 0.64, -19.05, -16.63, 0.10, 21.47, 21.11 -MOT, 1373, 1470, 1378, 1431 -CTUN, 500, 0.00, 8.17, 0.000000, 0.00, 11, 166, 391, 0 -ATT, 0.00, 0.63, -19.49, -17.05, 0.00, 21.46, 21.11 -MOT, 1392, 1444, 1365, 1433 -GPS, 3, 109229600, 1774, 9, 2.42, -39.4949709, 176.7484031, 8.38, 53.42, 3.62, 27.04, -1.300000, 82561 -CTUN, 500, 0.00, 8.30, 0.000000, 0.00, 12, 164, 392, 0 -ATT, 0.00, 0.24, -19.49, -17.67, 0.00, 21.38, 21.11 -MOT, 1333, 1516, 1370, 1420 -CTUN, 500, 0.00, 8.52, 0.000000, 0.00, 12, 164, 392, 0 -ATT, 0.00, -0.25, -19.70, -17.59, 0.00, 21.21, 21.11 -MOT, 1380, 1471, 1361, 1427 -GPS, 3, 109229800, 1774, 9, 2.42, -39.4949648, 176.7484073, 8.73, 53.68, 3.83, 27.39, -1.260000, 82762 -CTUN, 500, 0.00, 8.81, 0.000000, 0.00, 13, 166, 393, 0 -ATT, 0.00, -0.38, -19.70, -18.26, 0.00, 21.12, 21.11 -MOT, 1340, 1513, 1351, 1443 -CTUN, 500, 0.00, 8.87, 0.000000, 0.00, 13, 168, 393, 0 -ATT, 0.00, -0.33, -19.49, -18.28, 0.00, 21.19, 21.11 -MOT, 1369, 1474, 1375, 1430 -DU32, 7, 270713 -CURR, 393, 35555, 1616, 2255, 4897, 49.79305 -GPS, 3, 109230000, 1774, 9, 2.42, -39.4949583, 176.7484116, 9.09, 53.97, 4.03, 27.18, -1.280000, 82962 -CTUN, 500, 0.00, 9.06, 0.000000, 0.00, 13, 168, 393, 0 -ATT, 0.00, -0.44, -19.27, -18.36, 0.10, 21.22, 21.11 -MOT, 1392, 1451, 1371, 1434 -CTUN, 500, 0.00, 9.15, 0.000000, 0.00, 13, 169, 393, 0 -ATT, 0.00, -0.69, -19.27, -18.22, 0.00, 21.26, 21.11 -MOT, 1392, 1451, 1414, 1391 -GPS, 3, 109230200, 1774, 9, 2.42, -39.4949514, 176.7484159, 9.45, 54.27, 4.18, 26.57, -1.310000, 83163 -CTUN, 500, 0.00, 9.42, 0.000000, 0.00, 14, 167, 394, 0 -ATT, 0.00, -1.15, -19.70, -18.94, 0.00, 21.48, 21.11 -MOT, 1390, 1444, 1367, 1451 -CTUN, 500, 0.00, 9.47, 0.000000, 0.00, 14, 159, 394, 0 -ATT, 0.00, -0.93, -19.92, -19.17, 0.20, 21.57, 21.11 -MOT, 1364, 1472, 1378, 1437 -GPS, 3, 109230400, 1774, 9, 2.42, -39.4949441, 176.7484201, 9.79, 54.57, 4.37, 25.60, -1.300000, 83362 -CTUN, 500, 0.00, 9.57, 0.000000, 0.00, 14, 152, 394, 0 -ATT, 0.00, -0.65, -19.92, -19.13, 0.00, 21.57, 21.11 -MOT, 1388, 1453, 1379, 1432 -CTUN, 500, 0.00, 9.78, 0.000000, 0.00, 14, 147, 394, 0 -ATT, 0.00, -0.68, -20.14, -19.27, 0.00, 21.50, 21.11 -MOT, 1359, 1488, 1356, 1449 -GPS, 3, 109230600, 1774, 9, 2.42, -39.4949367, 176.7484245, 10.09, 54.81, 4.52, 25.13, -1.190000, 83563 -CTUN, 500, 0.00, 9.84, 0.000000, 0.00, 14, 144, 394, 0 -ATT, 0.00, -0.30, -20.57, -19.04, 0.00, 21.37, 21.11 -MOT, 1365, 1481, 1377, 1428 -CTUN, 500, 0.00, 10.12, 0.000000, 0.00, 14, 142, 394, 0 -ATT, 0.00, -0.11, -21.22, -19.20, 0.00, 21.37, 21.11 -MOT, 1359, 1485, 1369, 1438 -GPS, 3, 109230800, 1774, 9, 2.42, -39.4949289, 176.7484288, 10.37, 55.05, 4.64, 24.29, -1.090000, 83763 -CTUN, 500, 0.00, 10.25, 0.000000, 0.00, 14, 141, 394, 0 -ATT, 0.00, 0.00, -21.22, -19.30, 0.00, 21.46, 21.11 -MOT, 1367, 1472, 1367, 1446 -CTUN, 500, 0.00, 10.35, 0.000000, 0.00, 14, 142, 394, 0 -ATT, 0.00, -0.13, -21.00, -19.12, 0.00, 21.49, 21.11 -MOT, 1361, 1490, 1371, 1430 -DU32, 7, 270713 -CURR, 394, 39492, 1630, 2280, 4897, 55.94674 -PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 -GPS, 3, 109231000, 1774, 9, 2.42, -39.4949207, 176.7484331, 10.66, 55.29, 4.83, 23.32, -1.060000, 83963 -CTUN, 500, 0.00, 10.55, 0.000000, 0.00, 14, 143, 394, 0 -ATT, 0.00, -0.25, -21.22, -18.97, 0.00, 21.61, 21.11 -MOT, 1347, 1498, 1376, 1431 -CTUN, 500, 0.00, 10.54, 0.000000, 0.00, 14, 140, 394, 0 -ATT, 0.00, -0.15, -21.00, -19.21, 0.00, 21.75, 21.11 -MOT, 1333, 1501, 1347, 1471 -GPS, 3, 109231200, 1774, 9, 2.42, -39.4949126, 176.7484375, 10.94, 55.51, 4.93, 23.08, -1.070000, 84164 -CTUN, 500, 0.00, 10.71, 0.000000, 0.00, 14, 138, 394, 0 -ATT, 0.00, -0.05, -21.44, -18.87, 0.00, 21.85, 21.11 -MOT, 1370, 1471, 1395, 1416 -CTUN, 503, 0.00, 10.81, 0.000000, 0.00, 14, 134, 397, 0 -ATT, 0.00, -0.10, -22.53, -19.22, 0.00, 21.84, 21.11 -MOT, 1333, 1514, 1374, 1443 -GPS, 3, 109231400, 1774, 9, 2.42, -39.4949039, 176.7484419, 11.20, 55.75, 5.12, 22.36, -1.050000, 84364 -CTUN, 503, 0.00, 10.91, 0.000000, 0.00, 15, 130, 398, 0 -ATT, 0.00, 0.53, -22.75, -19.95, 0.00, 21.82, 21.11 -MOT, 1396, 1451, 1367, 1455 -CTUN, 503, 0.00, 10.95, 0.000000, 0.00, 17, 121, 400, 0 -ATT, 0.00, 0.15, -22.75, -20.70, 0.00, 21.77, 21.11 -MOT, 1398, 1457, 1378, 1443 -GPS, 3, 109231600, 1774, 9, 2.42, -39.4948950, 176.7484465, 11.43, 55.95, 5.27, 22.03, -0.940000, 84564 -CTUN, 503, 0.00, 11.09, 0.000000, 0.00, 17, 120, 400, 0 -ATT, 0.00, -0.72, -22.75, -20.62, 0.00, 21.66, 21.11 -MOT, 1336, 1513, 1397, 1431 -CTUN, 503, 0.00, 11.32, 0.000000, 0.00, 17, 120, 400, 0 -ATT, 0.00, -0.61, -22.75, -21.13, 0.00, 21.67, 21.11 -MOT, 1404, 1446, 1391, 1435 -GPS, 3, 109231800, 1774, 9, 2.42, -39.4948860, 176.7484510, 11.65, 56.14, 5.36, 21.41, -0.880000, 84765 -CTUN, 503, 0.00, 11.36, 0.000000, 0.00, 18, 114, 401, 0 -ATT, 0.00, -1.16, -22.75, -21.31, 0.00, 21.66, 21.11 -MOT, 1358, 1486, 1390, 1446 -CTUN, 500, 0.00, 11.41, 0.000000, 0.00, 18, 119, 401, 0 -ATT, 0.00, -0.82, -22.75, -21.34, 0.00, 21.71, 21.11 -MOT, 1392, 1459, 1437, 1393 -DU32, 7, 270713 -CURR, 399, 43471, 1591, 2336, 4918, 62.41039 -GPS, 3, 109232000, 1774, 9, 2.42, -39.4948765, 176.7484555, 11.87, 56.32, 5.59, 20.90, -0.850000, 84965 -CTUN, 503, 0.00, 11.66, 0.000000, 0.00, 20, 110, 403, 0 -ATT, 0.00, -1.34, -22.96, -22.52, 0.00, 21.74, 21.11 -MOT, 1384, 1471, 1379, 1455 -CTUN, 503, 0.00, 11.16, 0.000000, 0.00, 22, 96, 405, 0 -ATT, 0.00, -0.96, -22.96, -23.42, 0.00, 21.68, 21.11 -MOT, 1399, 1471, 1408, 1420 -GPS, 3, 109232200, 1774, 9, 2.42, -39.4948665, 176.7484599, 12.02, 56.52, 5.81, 19.69, -0.840000, 85165 -CTUN, 503, 0.00, 11.29, 0.000000, 0.00, 23, 83, 406, 0 -ATT, 0.00, -0.82, -22.75, -24.04, -0.21, 21.61, 21.08 -MOT, 1388, 1478, 1396, 1440 -CTUN, 503, 0.00, 11.23, 0.000000, 0.00, 26, 61, 409, 0 -ATT, 0.00, -0.47, -22.96, -25.41, -0.97, 21.57, 20.84 -MOT, 1397, 1466, 1423, 1428 -GPS, 3, 109232400, 1774, 9, 2.42, -39.4948561, 176.7484644, 12.07, 56.66, 6.05, 19.07, -0.670000, 85365 -CTUN, 503, 0.00, 11.39, 0.000000, 0.00, 27, 38, 410, 0 -ATT, 0.00, -0.43, -22.96, -25.74, -1.95, 21.14, 20.33 -MOT, 1416, 1460, 1427, 1416 -CTUN, 503, 0.00, 11.43, 0.000000, 0.00, 28, 17, 411, 0 -ATT, 0.00, -0.31, -22.96, -26.15, -1.95, 20.41, 19.73 -MOT, 1397, 1479, 1396, 1451 -GPS, 3, 109232600, 1774, 9, 2.42, -39.4948452, 176.7484690, 12.03, 56.71, 6.38, 18.69, -0.370000, 85566 -CTUN, 503, 0.00, 11.35, 0.000000, 0.00, 28, 0, 411, 0 -ATT, 0.00, -0.08, -22.96, -25.93, -1.95, 19.66, 19.13 -MOT, 1395, 1485, 1390, 1453 -CTUN, 503, 0.00, 11.42, 0.000000, 0.00, 27, -11, 410, 0 -ATT, 0.00, 0.14, -22.96, -25.33, -1.62, 18.97, 18.56 -MOT, 1411, 1465, 1421, 1421 -GPS, 3, 109232800, 1774, 9, 2.42, -39.4948337, 176.7484738, 11.93, 56.70, 6.68, 18.28, -0.050000, 85766 -CTUN, 503, 0.00, 11.47, 0.000000, 0.00, 25, -21, 408, 0 -ATT, 0.00, 0.01, -22.75, -24.67, 0.00, 18.39, 18.32 -MOT, 1391, 1506, 1382, 1431 -CTUN, 500, 0.00, 11.39, 0.000000, 0.00, 22, -26, 402, 0 -ATT, 0.00, 0.30, -22.96, -23.18, 0.00, 17.96, 18.32 -MOT, 1387, 1496, 1353, 1450 -DU32, 7, 270713 -CURR, 403, 47539, 1582, 2360, 4940, 69.01168 -GPS, 3, 109233000, 1774, 9, 2.42, -39.4948216, 176.7484787, 11.82, 56.64, 7.02, 17.79, 0.160000, 85966 -CTUN, 503, 0.00, 11.47, 0.000000, 0.00, 20, -26, 400, 0 -ATT, 0.00, 0.69, -22.96, -22.30, 0.00, 17.77, 18.32 -MOT, 1383, 1491, 1380, 1422 -CTUN, 503, 0.00, 11.65, 0.000000, 0.00, 19, -29, 402, 0 -ATT, 0.00, 0.65, -23.18, -21.56, 0.00, 17.86, 18.32 -MOT, 1407, 1468, 1353, 1458 -GPS, 3, 109233200, 1774, 9, 2.42, -39.4948091, 176.7484837, 11.73, 56.55, 7.30, 17.35, 0.300000, 86166 -CTUN, 503, 0.00, 11.75, 0.000000, 0.00, 17, -28, 400, 0 -ATT, 0.00, 0.78, -23.25, -20.81, 0.00, 18.01, 18.32 -MOT, 1385, 1474, 1365, 1452 -CTUN, 503, 0.00, 11.50, 0.000000, 0.00, 16, -24, 399, 0 -ATT, 0.00, 0.81, -23.18, -20.11, 0.00, 18.18, 18.32 -MOT, 1362, 1493, 1363, 1454 -GPS, 3, 109233400, 1774, 9, 2.42, -39.4947963, 176.7484887, 11.67, 56.46, 7.50, 17.12, 0.360000, 86367 -CTUN, 503, 0.00, 11.63, 0.000000, 0.00, 15, -19, 398, 0 -ATT, 0.00, 0.54, -23.18, -19.34, 0.00, 18.41, 18.32 -MOT, 1361, 1492, 1363, 1452 -CTUN, 505, 0.00, 11.36, 0.000000, 0.00, 14, -7, 400, 0 -ATT, 0.00, 0.28, -23.18, -18.62, 0.00, 18.64, 18.32 -MOT, 1333, 1522, 1360, 1461 -GPS, 3, 109233600, 1774, 9, 2.42, -39.4947831, 176.7484940, 11.63, 56.39, 7.66, 17.05, 0.320000, 86567 -CTUN, 505, 0.00, 11.07, 0.000000, 0.00, 12, 10, 398, 0 -ATT, 0.00, 0.00, -22.96, -17.88, 0.00, 18.87, 18.32 -MOT, 1359, 1481, 1369, 1463 -CTUN, 513, 0.00, 11.17, 0.000000, 0.00, 12, 27, 408, 0 -ATT, 0.00, -0.28, -22.96, -17.48, 0.00, 19.06, 18.32 -MOT, 1375, 1480, 1390, 1465 -GPS, 3, 109233800, 1774, 9, 2.42, -39.4947698, 176.7484992, 11.62, 56.36, 7.74, 16.96, 0.220000, 86767 -CTUN, 513, 0.00, 11.41, 0.000000, 0.00, 12, 39, 408, 0 -ATT, 0.00, -0.12, -23.40, -17.21, 0.00, 19.31, 18.32 -MOT, 1387, 1462, 1416, 1445 -CTUN, 510, 0.00, 11.59, 0.000000, 0.00, 12, 49, 404, 0 -ATT, 0.00, -0.23, -23.40, -17.59, 0.00, 19.42, 18.32 -MOT, 1348, 1499, 1362, 1484 -DU32, 7, 270713 -CURR, 404, 51559, 1595, 2465, 4918, 75.52970 -GPS, 3, 109234000, 1774, 9, 2.42, -39.4947562, 176.7485045, 11.70, 56.40, 7.86, 16.78, 0.010000, 86967 -CTUN, 510, 0.00, 11.41, 0.000000, 0.00, 12, 56, 404, 0 -ATT, 0.00, -0.25, -23.18, -17.44, 0.00, 19.50, 18.32 -MOT, 1371, 1476, 1385, 1461 -CTUN, 510, 0.00, 11.72, 0.000000, 0.00, 12, 63, 404, 0 -ATT, 0.00, -0.23, -23.40, -17.53, 0.00, 19.47, 18.32 -MOT, 1359, 1492, 1383, 1459 -GPS, 3, 109234200, 1774, 9, 2.42, -39.4947425, 176.7485097, 11.81, 56.48, 7.86, 16.71, -0.160000, 87168 -CTUN, 510, 0.00, 11.78, 0.000000, 0.00, 13, 69, 405, 0 -ATT, 0.00, -0.05, -23.18, -17.97, 0.00, 19.40, 18.32 -MOT, 1387, 1462, 1381, 1468 -CTUN, 510, 0.00, 11.70, 0.000000, 0.00, 13, 74, 405, 0 -ATT, 0.00, -0.36, -23.40, -18.01, 0.00, 19.33, 18.32 -MOT, 1384, 1464, 1384, 1464 -GPS, 3, 109234400, 1774, 9, 2.42, -39.4947287, 176.7485149, 11.96, 56.60, 7.92, 16.52, -0.360000, 87368 -CTUN, 510, 0.00, 11.98, 0.000000, 0.00, 14, 76, 406, 0 -ATT, 0.00, -0.32, -23.18, -18.33, 0.00, 19.26, 18.32 -MOT, 1370, 1481, 1392, 1455 -CTUN, 510, 0.00, 11.88, 0.000000, 0.00, 14, 75, 406, 0 -ATT, 0.00, -0.25, -23.25, -18.72, 0.00, 19.16, 18.32 -MOT, 1389, 1466, 1362, 1484 -GPS, 3, 109234600, 1774, 9, 2.42, -39.4947151, 176.7485200, 12.11, 56.71, 7.85, 16.34, -0.410000, 87568 -CTUN, 510, 0.00, 12.08, 0.000000, 0.00, 15, 71, 407, 0 -ATT, 0.00, -0.38, -23.18, -19.31, 0.00, 19.05, 18.32 -MOT, 1401, 1460, 1400, 1444 -CTUN, 513, 0.00, 11.95, 0.000000, 0.00, 17, 61, 413, 0 -ATT, 0.00, -0.07, -23.47, -19.99, 0.00, 18.86, 18.32 -MOT, 1383, 1495, 1390, 1459 -GPS, 3, 109234800, 1774, 9, 2.42, -39.4947013, 176.7485250, 12.24, 56.83, 7.86, 16.10, -0.440000, 87769 -CTUN, 510, 0.00, 12.17, 0.000000, 0.00, 18, 51, 410, 0 -ATT, 0.00, 0.14, -23.40, -20.78, 0.10, 18.81, 18.32 -MOT, 1405, 1473, 1403, 1454 -CTUN, 513, 0.00, 12.11, 0.000000, 0.00, 19, 40, 415, 0 -ATT, 0.00, 0.11, -23.40, -21.36, 0.00, 18.77, 18.32 -MOT, 1400, 1482, 1401, 1456 -DU32, 7, 270713 -CURR, 416, 55635, 1639, 2507, 4940, 82.22855 -GPS, 3, 109235000, 1774, 9, 2.42, -39.4946877, 176.7485299, 12.32, 56.92, 7.83, 15.85, -0.330000, 87969 -CTUN, 512, 0.00, 12.05, 0.000000, 0.00, 21, 29, 415, 0 -ATT, 0.00, -0.01, -23.40, -22.20, 0.20, 18.71, 18.32 -MOT, 1430, 1459, 1397, 1458 -CTUN, 514, 0.00, 12.22, 0.000000, 0.00, 22, 17, 419, 0 -ATT, 0.00, 0.25, -23.40, -22.63, 0.00, 18.62, 18.32 -MOT, 1414, 1479, 1402, 1461 -GPS, 3, 109235200, 1774, 9, 2.42, -39.4946738, 176.7485348, 12.34, 56.98, 7.90, 15.64, -0.180000, 88169 -CTUN, 513, 0.00, 12.28, 0.000000, 0.00, 23, 6, 419, 0 -ATT, 0.00, 0.41, -23.47, -23.20, 0.10, 18.68, 18.32 -MOT, 1398, 1495, 1398, 1465 -CTUN, 513, 0.00, 11.94, 0.000000, 0.00, 24, -7, 420, 0 -ATT, 0.00, 0.55, -23.25, -23.61, 0.20, 18.75, 18.32 -MOT, 1374, 1511, 1408, 1448 -GPS, 3, 109235400, 1774, 9, 2.42, -39.4946598, 176.7485396, 12.31, 56.98, 8.02, 14.91, -0.010000, 88370 -CTUN, 513, 0.00, 12.06, 0.000000, 0.00, 23, -13, 419, 0 -ATT, 0.00, 0.24, -23.18, -23.45, 0.00, 18.84, 18.32 -MOT, 1388, 1503, 1411, 1459 -CTUN, 513, 0.00, 12.08, 0.000000, 0.00, 23, -22, 419, 0 -ATT, 0.00, -0.12, -23.18, -23.35, 0.00, 18.89, 18.32 -MOT, 1415, 1468, 1398, 1459 -GPS, 3, 109235600, 1774, 9, 2.42, -39.4946457, 176.7485443, 12.24, 56.94, 8.08, 14.57, 0.170000, 88569 -CTUN, 513, 0.00, 11.98, 0.000000, 0.00, 23, -31, 419, 0 -ATT, 0.00, -0.09, -23.18, -23.34, 0.00, 18.82, 18.32 -MOT, 1385, 1501, 1417, 1453 -CTUN, 510, 0.00, 12.13, 0.000000, 0.00, 22, -37, 414, 0 -ATT, 0.00, -0.19, -23.18, -23.16, 0.10, 18.76, 18.32 -MOT, 1393, 1502, 1394, 1468 -GPS, 3, 109235800, 1774, 9, 2.42, -39.4946312, 176.7485491, 12.14, 56.87, 8.30, 14.48, 0.280000, 88770 -CTUN, 514, 0.00, 12.17, 0.000000, 0.00, 22, -39, 419, 0 -ATT, 0.00, -0.11, -23.18, -22.72, 0.00, 18.77, 18.32 -MOT, 1340, 1534, 1331, 1528 -CTUN, 510, 0.00, 11.97, 0.000000, 0.00, 18, -28, 410, 0 -ATT, 0.00, 0.19, -23.18, -21.09, 0.10, 18.82, 18.32 -MOT, 1407, 1480, 1425, 1428 -DU32, 7, 270713 -CURR, 409, 59817, 1603, 2834, 4962, 89.32329 -GPS, 3, 109236000, 1774, 9, 2.42, -39.4946165, 176.7485539, 12.07, 56.78, 8.43, 14.05, 0.410000, 88970 -CTUN, 513, 0.00, 11.88, 0.000000, 0.00, 17, -15, 413, 0 -ATT, 0.00, 0.10, -23.18, -20.18, 0.00, 18.79, 18.32 -MOT, 1394, 1474, 1365, 1481 -CTUN, 510, 0.00, 12.03, 0.000000, 0.00, 16, -10, 408, 0 -ATT, 0.00, 0.00, -23.18, -19.99, 0.20, 18.79, 18.32 -MOT, 1357, 1511, 1419, 1444 -GPS, 3, 109236200, 1774, 9, 2.42, -39.4946016, 176.7485588, 12.03, 56.70, 8.58, 14.27, 0.350000, 89171 -CTUN, 513, 0.00, 12.01, 0.000000, 0.00, 16, -11, 412, 0 -ATT, 0.00, -0.27, -22.96, -19.82, 0.00, 18.76, 18.32 -MOT, 1405, 1477, 1394, 1451 -CTUN, 513, 0.00, 12.11, 0.000000, 0.00, 17, -10, 413, 0 -ATT, 0.00, -0.25, -23.25, -19.96, 0.00, 18.70, 18.32 -MOT, 1364, 1520, 1382, 1464 -GPS, 3, 109236400, 1774, 9, 2.42, -39.4945866, 176.7485637, 12.00, 56.66, 8.64, 14.21, 0.220000, 89370 -CTUN, 513, 0.00, 11.90, 0.000000, 0.00, 17, -11, 413, 0 -ATT, 0.00, -0.21, -22.96, -20.24, 0.00, 18.66, 18.32 -MOT, 1399, 1477, 1393, 1462 -CTUN, 513, 0.00, 12.01, 0.000000, 0.00, 17, -12, 413, 0 -ATT, 0.00, -0.36, -22.96, -20.08, 0.00, 18.70, 18.32 -MOT, 1409, 1470, 1396, 1461 -GPS, 3, 109236600, 1774, 9, 2.42, -39.4945712, 176.7485685, 11.98, 56.64, 8.73, 13.75, 0.180000, 89571 -CTUN, 513, 0.00, 11.83, 0.000000, 0.00, 17, -8, 413, 0 -ATT, 0.00, -0.49, -22.96, -20.15, 0.10, 18.65, 18.32 -MOT, 1388, 1486, 1398, 1442 -CTUN, 513, 0.00, 11.90, 0.000000, 0.00, 17, -9, 413, 0 -ATT, 0.00, -0.39, -22.96, -20.09, 0.00, 18.66, 18.32 -MOT, 1394, 1482, 1411, 1444 -GPS, 3, 109236800, 1774, 9, 2.42, -39.4945561, 176.7485734, 11.94, 56.56, 8.72, 13.89, 0.260000, 89771 -CTUN, 513, 0.00, 11.64, 0.000000, 0.00, 17, -8, 413, 0 -ATT, 0.00, -0.34, -22.96, -20.24, 0.20, 18.77, 18.32 -MOT, 1355, 1525, 1383, 1468 -CTUN, 514, 0.00, 11.59, 0.000000, 0.00, 16, -2, 413, 0 -ATT, 0.00, -0.16, -22.75, -19.77, 0.00, 18.94, 18.32 -MOT, 1381, 1476, 1389, 1464 -DU32, 7, 270713 -CURR, 412, 63937, 1589, 2580, 4962, 96.24298 -GPS, 3, 109237000, 1774, 9, 2.42, -39.4945405, 176.7485782, 11.90, 56.54, 8.82, 13.43, 0.220000, 89972 -CTUN, 513, 0.00, 11.77, 0.000000, 0.00, 15, 4, 411, 0 -ATT, 0.00, -0.04, -22.96, -19.38, 0.00, 19.00, 18.32 -MOT, 1388, 1476, 1398, 1465 -CTUN, 513, 0.00, 11.73, 0.000000, 0.00, 15, 15, 411, 0 -ATT, 0.00, -0.06, -22.96, -18.94, 0.00, 18.99, 18.32 -MOT, 1371, 1499, 1373, 1480 -GPS, 3, 109237200, 1774, 9, 2.42, -39.4945248, 176.7485830, 11.91, 56.54, 8.94, 13.30, 0.140000, 90172 -CTUN, 513, 0.00, 11.85, 0.000000, 0.00, 15, 21, 411, 0 -ATT, 0.00, 0.12, -22.75, -18.96, 0.00, 18.94, 18.32 -MOT, 1361, 1519, 1369, 1474 -CTUN, 513, 0.00, 11.82, 0.000000, 0.00, 15, 26, 411, 0 -ATT, 0.00, -0.12, -22.75, -18.85, 0.00, 18.89, 18.32 -MOT, 1388, 1489, 1398, 1449 -GPS, 3, 109237400, 1774, 9, 2.42, -39.4945088, 176.7485879, 11.95, 56.56, 9.09, 13.55, 0.020000, 90372 -CTUN, 513, 0.00, 11.82, 0.000000, 0.00, 15, 28, 411, 0 -ATT, 0.00, 0.01, -22.75, -19.14, 0.00, 18.84, 18.32 -MOT, 1365, 1502, 1394, 1461 -CTUN, 513, 0.00, 11.92, 0.000000, 0.00, 15, 31, 411, 0 -ATT, 0.00, -0.13, -22.75, -18.91, 0.10, 18.88, 18.32 -MOT, 1384, 1481, 1396, 1461 -GPS, 3, 109237600, 1774, 9, 2.42, -39.4944927, 176.7485930, 12.00, 56.62, 9.18, 13.63, -0.110000, 90572 -CTUN, 513, 0.00, 11.85, 0.000000, 0.00, 15, 37, 411, 0 -ATT, 0.00, -0.02, -22.75, -18.91, 0.00, 18.84, 18.32 -MOT, 1361, 1513, 1391, 1458 -CTUN, 513, 0.00, 12.07, 0.000000, 0.00, 15, 44, 411, 0 -ATT, 0.00, 0.02, -22.53, -18.94, 0.00, 18.79, 18.32 -MOT, 1385, 1489, 1380, 1469 -GPS, 3, 109237800, 1774, 9, 2.42, -39.4944765, 176.7485980, 12.09, 56.68, 9.22, 13.51, -0.160000, 90773 -CTUN, 513, 0.00, 11.89, 0.000000, 0.00, 15, 49, 411, 0 -ATT, 0.00, -0.14, -22.75, -19.14, 0.00, 18.80, 18.32 -MOT, 1382, 1475, 1393, 1456 -CTUN, 513, 0.00, 11.98, 0.000000, 0.00, 15, 51, 411, 0 -ATT, 0.00, -0.05, -22.75, -19.29, 0.00, 18.86, 18.32 -MOT, 1365, 1511, 1392, 1459 -DU32, 7, 270713 -CURR, 411, 68048, 1597, 2425, 4897, 102.9687 -GPS, 3, 109238000, 1774, 9, 2.42, -39.4944600, 176.7486032, 12.18, 56.78, 9.36, 13.77, -0.270000, 90973 -CTUN, 513, 0.00, 12.13, 0.000000, 0.00, 16, 53, 412, 0 -ATT, 0.00, -0.01, -22.53, -19.50, 0.00, 18.87, 18.32 -MOT, 1405, 1466, 1402, 1449 -CTUN, 510, 0.00, 12.13, 0.000000, 0.00, 16, 52, 408, 0 -ATT, 0.00, 0.12, -22.75, -19.73, 0.10, 18.79, 18.32 -MOT, 1388, 1489, 1396, 1455 -GPS, 3, 109238200, 1774, 9, 2.42, -39.4944434, 176.7486085, 12.28, 56.88, 9.43, 13.86, -0.320000, 91173 -CTUN, 513, 0.00, 12.24, 0.000000, 0.00, 15, 55, 411, 0 -ATT, 0.00, -0.08, -22.75, -19.35, 0.00, 18.74, 18.32 -MOT, 1365, 1513, 1404, 1444 -CTUN, 513, 0.00, 12.52, 0.000000, 0.00, 15, 58, 411, 0 -ATT, 0.00, -0.05, -22.82, -19.12, 0.10, 18.65, 18.32 -MOT, 1359, 1521, 1355, 1488 -GPS, 3, 109238400, 1774, 9, 2.42, -39.4944268, 176.7486139, 12.41, 56.99, 9.47, 14.04, -0.370000, 91374 -CTUN, 513, 0.00, 12.74, 0.000000, 0.00, 15, 61, 411, 0 -ATT, 0.00, 0.02, -22.75, -18.97, 0.00, 18.59, 18.32 -MOT, 1419, 1453, 1416, 1435 -CTUN, 513, 0.00, 12.59, 0.000000, 0.00, 14, 68, 410, 0 -ATT, 0.00, 0.24, -22.75, -18.48, 0.10, 18.55, 18.32 -MOT, 1391, 1479, 1374, 1475 -GPS, 3, 109238600, 1774, 9, 2.42, -39.4944101, 176.7486192, 12.58, 57.13, 9.48, 13.84, -0.460000, 91574 -CTUN, 513, 0.00, 12.62, 0.000000, 0.00, 13, 75, 409, 0 -ATT, 0.00, 0.27, -22.75, -18.13, 0.00, 18.52, 18.32 -MOT, 1379, 1495, 1370, 1471 -CTUN, 513, 0.00, 12.72, 0.000000, 0.00, 13, 83, 409, 0 -ATT, 0.00, 0.20, -22.75, -17.95, 0.00, 18.48, 18.32 -MOT, 1382, 1494, 1381, 1457 -GPS, 3, 109238800, 1774, 9, 2.42, -39.4943935, 176.7486244, 12.76, 57.26, 9.44, 13.73, -0.500000, 91774 -CTUN, 513, 0.00, 13.07, 0.000000, 0.00, 14, 86, 410, 0 -ATT, 0.00, 0.22, -22.75, -18.31, 0.10, 18.56, 18.32 -MOT, 1384, 1481, 1403, 1450 -CTUN, 513, 0.00, 13.03, 0.000000, 0.00, 14, 83, 410, 0 -ATT, 0.00, 0.19, -22.75, -18.36, 0.00, 18.73, 18.32 -MOT, 1411, 1440, 1421, 1446 -DU32, 7, 270713 -CURR, 411, 72155, 1574, 2371, 4940, 109.8004 -GPS, 3, 109239000, 1774, 9, 2.42, -39.4943768, 176.7486297, 12.97, 57.43, 9.45, 13.90, -0.580000, 91974 -CTUN, 513, 0.00, 13.17, 0.000000, 0.00, 15, 75, 411, 0 -ATT, 0.00, -0.05, -22.75, -19.00, 0.00, 18.94, 18.32 -MOT, 1357, 1504, 1400, 1461 -CTUN, 513, 0.00, 13.05, 0.000000, 0.00, 16, 70, 412, 0 -ATT, 0.00, -0.07, -22.75, -19.46, 0.00, 19.00, 18.32 -MOT, 1402, 1468, 1373, 1480 -GPS, 3, 109239200, 1774, 9, 2.42, -39.4943603, 176.7486348, 13.14, 57.61, 9.38, 13.54, -0.660000, 92175 -CTUN, 513, 0.00, 13.13, 0.000000, 0.00, 15, 72, 411, 0 -ATT, 0.00, -0.02, -22.75, -19.19, 0.10, 19.00, 18.32 -MOT, 1391, 1471, 1368, 1494 -CTUN, 513, 0.00, 13.20, 0.000000, 0.00, 15, 77, 411, 0 -ATT, 0.00, 0.02, -22.75, -18.86, 0.00, 18.92, 18.32 -MOT, 1413, 1455, 1378, 1477 -GPS, 3, 109239400, 1774, 9, 2.42, -39.4943439, 176.7486399, 13.30, 57.75, 9.30, 13.72, -0.570000, 92375 -CTUN, 516, 0.00, 13.47, 0.000000, 0.00, 14, 86, 413, 0 -ATT, 0.00, 0.30, -22.75, -18.28, 0.10, 18.71, 18.32 -MOT, 1358, 1528, 1388, 1457 -CTUN, 518, 0.00, 13.50, 0.000000, 0.00, 14, 96, 416, 0 -ATT, 0.00, -0.05, -22.75, -18.04, 0.00, 18.48, 18.32 -MOT, 1385, 1512, 1383, 1463 -GPS, 3, 109239600, 1774, 9, 2.42, -39.4943275, 176.7486450, 13.52, 57.92, 9.29, 13.71, -0.630000, 92575 -CTUN, 518, 0.00, 13.62, 0.000000, 0.00, 13, 109, 415, 0 -ATT, 0.00, -0.22, -22.75, -17.46, 0.10, 18.42, 18.32 -MOT, 1401, 1485, 1392, 1461 -CTUN, 518, 0.00, 13.57, 0.000000, 0.00, 13, 123, 415, 0 -ATT, 0.00, -0.15, -22.75, -17.48, 0.20, 18.39, 18.32 -MOT, 1371, 1508, 1362, 1499 -GPS, 3, 109239800, 1774, 9, 2.42, -39.4943111, 176.7486502, 13.78, 58.12, 9.34, 13.75, -0.810000, 92775 -CTUN, 518, 0.00, 13.88, 0.000000, 0.00, 12, 132, 414, 0 -ATT, 0.00, -0.27, -22.75, -17.10, 0.10, 18.46, 18.32 -MOT, 1378, 1506, 1390, 1461 -CTUN, 518, 0.00, 14.11, 0.000000, 0.00, 13, 136, 415, 0 -ATT, 0.00, -0.35, -22.82, -17.40, 0.00, 18.45, 18.32 -MOT, 1381, 1508, 1376, 1475 -DU32, 7, 270713 -CURR, 419, 76290, 1595, 2482, 4962, 116.7737 -GPS, 3, 109240000, 1774, 9, 2.42, -39.4942946, 176.7486554, 14.08, 58.37, 9.38, 13.59, -1.020000, 92976 -CTUN, 526, 0.00, 14.09, 0.000000, 0.00, 13, 143, 425, 0 -ATT, 0.00, -0.55, -22.75, -17.16, 0.00, 18.47, 18.32 -MOT, 1390, 1516, 1399, 1477 -CTUN, 526, 0.00, 14.38, 0.000000, 0.00, 13, 157, 425, 0 -ATT, 0.00, -0.69, -22.96, -17.21, 0.00, 18.43, 18.32 -MOT, 1416, 1481, 1404, 1480 -GPS, 3, 109240200, 1774, 9, 2.42, -39.4942783, 176.7486605, 14.42, 58.65, 9.27, 13.86, -1.160000, 93176 -CTUN, 526, 0.00, 14.40, 0.000000, 0.00, 13, 173, 425, 0 -ATT, 0.00, -0.69, -22.75, -17.23, 0.10, 18.34, 18.32 -MOT, 1401, 1517, 1382, 1481 -CTUN, 526, 0.00, 14.73, 0.000000, 0.00, 13, 184, 425, 0 -ATT, 0.00, -0.49, -22.96, -17.47, 0.10, 18.23, 18.32 -MOT, 1403, 1513, 1374, 1492 -GPS, 3, 109240400, 1774, 9, 2.42, -39.4942620, 176.7486655, 14.82, 58.97, 9.25, 13.56, -1.370000, 93376 -CTUN, 526, 0.00, 14.70, 0.000000, 0.00, 14, 192, 426, 0 -ATT, 0.00, 0.02, -22.96, -17.82, 0.00, 18.14, 18.32 -MOT, 1396, 1516, 1411, 1463 -CTUN, 527, 0.00, 14.98, 0.000000, 0.00, 14, 200, 427, 0 -ATT, 0.00, -0.34, -23.03, -17.93, 0.00, 18.14, 18.32 -MOT, 1416, 1500, 1395, 1479 -GPS, 3, 109240600, 1774, 9, 2.42, -39.4942457, 176.7486703, 15.23, 59.35, 9.25, 13.04, -1.590000, 93576 -CTUN, 526, 0.00, 15.07, 0.000000, 0.00, 14, 211, 426, 0 -ATT, 0.00, -0.26, -22.96, -17.98, 0.10, 18.31, 18.32 -MOT, 1397, 1504, 1414, 1471 -CTUN, 526, 0.00, 15.47, 0.000000, 0.00, 14, 220, 426, 0 -ATT, 0.00, -0.32, -22.96, -18.16, 0.10, 18.40, 18.32 -MOT, 1380, 1528, 1397, 1481 -GPS, 3, 109240800, 1774, 9, 2.42, -39.4942293, 176.7486750, 15.69, 59.74, 9.27, 12.79, -1.750000, 93777 -CTUN, 526, 0.00, 15.49, 0.000000, 0.00, 15, 228, 427, 0 -ATT, 0.00, -0.32, -22.96, -18.56, 0.00, 18.49, 18.32 -MOT, 1445, 1460, 1405, 1479 -CTUN, 524, 0.00, 15.91, 0.000000, 0.00, 16, 226, 425, 0 -ATT, 0.00, -0.27, -22.75, -19.20, 0.00, 18.52, 18.32 -MOT, 1392, 1512, 1438, 1440 -DU32, 7, 270713 -CURR, 429, 80540, 1606, 2708, 4940, 124.2455 -PM, 0, 0, 0, 1000, 10322, 0, 0, 0, 0 -GPS, 3, 109241000, 1774, 9, 2.42, -39.4942128, 176.7486797, 16.16, 60.18, 9.30, 12.80, -1.940000, 93977 -CTUN, 526, 0.00, 16.18, 0.000000, 0.00, 17, 224, 429, 0 -ATT, 0.00, -0.18, -23.03, -19.78, 0.00, 18.35, 18.32 -MOT, 1418, 1504, 1399, 1481 -CTUN, 526, 0.00, 16.10, 0.000000, 0.00, 18, 219, 430, 0 -ATT, 0.00, 0.05, -23.18, -20.42, 0.00, 18.20, 18.32 -MOT, 1405, 1519, 1399, 1483 -GPS, 3, 109241200, 1774, 9, 2.42, -39.4941962, 176.7486844, 16.62, 60.65, 9.35, 12.47, -1.990000, 94177 -CTUN, 526, 0.00, 16.41, 0.000000, 0.00, 19, 216, 431, 0 -ATT, 0.00, -0.11, -23.62, -20.95, 0.10, 18.13, 18.32 -MOT, 1401, 1531, 1432, 1446 -CTUN, 526, 0.00, 16.73, 0.000000, 0.00, 21, 212, 433, 0 -ATT, 0.00, -0.27, -24.27, -21.58, 0.10, 18.04, 18.32 -MOT, 1450, 1490, 1417, 1463 -GPS, 3, 109241400, 1774, 9, 2.42, -39.4941797, 176.7486888, 17.06, 61.05, 9.32, 12.10, -1.970000, 94378 -CTUN, 526, 0.00, 16.96, 0.000000, 0.00, 22, 208, 434, 0 -ATT, 0.00, -0.42, -24.05, -21.97, 0.00, 18.03, 18.32 -MOT, 1421, 1516, 1407, 1480 -CTUN, 526, 0.00, 17.30, 0.000000, 0.00, 22, 206, 434, 0 -ATT, 0.00, -0.32, -23.83, -22.32, 0.10, 18.05, 18.32 -MOT, 1394, 1533, 1396, 1499 -GPS, 3, 109241600, 1774, 9, 2.42, -39.4941628, 176.7486933, 17.50, 61.49, 9.49, 11.70, -1.940000, 94578 -CTUN, 526, 0.00, 17.42, 0.000000, 0.00, 22, 209, 434, 0 -ATT, 0.00, -0.26, -23.62, -22.28, 0.10, 18.03, 18.32 -MOT, 1449, 1486, 1444, 1444 -CTUN, 526, 0.00, 17.60, 0.000000, 0.00, 24, 205, 436, 0 -ATT, 0.00, -0.33, -23.83, -22.91, 0.00, 17.88, 18.32 -MOT, 1451, 1495, 1404, 1482 -GPS, 3, 109241800, 1774, 9, 2.42, -39.4941457, 176.7486976, 17.93, 61.90, 9.60, 11.04, -1.920000, 94778 -CTUN, 526, 0.00, 17.76, 0.000000, 0.00, 25, 198, 437, 0 -ATT, 0.00, -0.14, -23.62, -23.39, 0.10, 17.75, 18.32 -MOT, 1411, 1538, 1422, 1462 -CTUN, 526, 0.00, 17.88, 0.000000, 0.00, 25, 194, 437, 0 -ATT, 0.00, -0.01, -23.62, -23.42, 0.00, 17.75, 18.32 -MOT, 1428, 1518, 1419, 1472 -DU32, 7, 270713 -CURR, 437, 84870, 1594, 2832, 4962, 131.9923 -GPS, 3, 109242000, 1774, 9, 2.42, -39.4941283, 176.7487018, 18.33, 62.32, 9.76, 10.69, -1.940000, 94980 -CTUN, 526, 0.00, 18.39, 0.000000, 0.00, 25, 189, 437, 0 -ATT, 0.00, 0.05, -23.40, -23.45, 0.10, 17.87, 18.32 -MOT, 1441, 1500, 1418, 1477 -CTUN, 526, 0.00, 18.43, 0.000000, 0.00, 24, 186, 436, 0 -ATT, 0.00, 0.21, -23.40, -23.14, 0.10, 17.96, 18.32 -MOT, 1398, 1537, 1432, 1463 -GPS, 3, 109242200, 1774, 9, 2.42, -39.4941107, 176.7487057, 18.73, 62.71, 9.84, 9.86, -1.840000, 95178 -CTUN, 526, 0.00, 18.69, 0.000000, 0.00, 25, 179, 437, 0 -ATT, 0.00, 0.08, -23.18, -23.38, 0.00, 18.03, 18.32 -MOT, 1440, 1497, 1443, 1456 -CTUN, 527, 0.00, 18.79, 0.000000, 0.00, 25, 167, 438, 0 -ATT, 0.00, 0.24, -23.18, -23.34, 0.10, 18.02, 18.32 -MOT, 1416, 1529, 1405, 1490 -GPS, 3, 109242400, 1774, 9, 2.42, -39.4940928, 176.7487094, 19.09, 63.10, 9.97, 9.24, -1.780000, 95379 -CTUN, 526, 0.00, 19.13, 0.000000, 0.00, 24, 162, 436, 0 -ATT, 0.00, 0.38, -23.18, -23.21, 0.10, 17.98, 18.32 -MOT, 1409, 1537, 1403, 1481 -CTUN, 526, 0.00, 19.25, 0.000000, 0.00, 22, 169, 434, 0 -ATT, 0.00, 0.19, -23.18, -22.22, 0.10, 17.99, 18.32 -MOT, 1417, 1522, 1383, 1501 -GPS, 3, 109242600, 1774, 9, 2.42, -39.4940749, 176.7487128, 19.45, 63.43, 10.03, 8.46, -1.650000, 95580 -CTUN, 526, 0.00, 19.51, 0.000000, 0.00, 20, 182, 432, 0 -ATT, 0.00, 0.38, -23.18, -21.17, 0.00, 18.01, 18.32 -MOT, 1403, 1528, 1415, 1470 -CTUN, 526, 0.00, 19.70, 0.000000, 0.00, 18, 192, 430, 0 -ATT, 0.00, 0.27, -23.18, -20.16, 0.00, 18.18, 18.32 -MOT, 1389, 1534, 1405, 1477 -GPS, 3, 109242800, 1774, 9, 2.42, -39.4940568, 176.7487161, 19.86, 63.76, 10.16, 8.16, -1.690000, 95780 -CTUN, 526, 0.00, 19.88, 0.000000, 0.00, 17, 196, 429, 0 -ATT, 0.00, 0.42, -23.18, -19.88, 0.20, 18.29, 18.32 -MOT, 1413, 1501, 1414, 1475 -CTUN, 526, 0.00, 20.02, 0.000000, 0.00, 17, 196, 429, 0 -ATT, 0.00, 0.46, -22.96, -19.72, 0.10, 18.33, 18.32 -MOT, 1419, 1499, 1420, 1464 -DU32, 7, 270713 -CURR, 429, 89211, 1588, 2721, 4940, 139.7294 -GPS, 3, 109243000, 1774, 9, 2.42, -39.4940384, 176.7487196, 20.28, 64.18, 10.25, 8.25, -1.840000, 95980 -CTUN, 526, 0.00, 20.26, 0.000000, 0.00, 17, 195, 429, 0 -ATT, 0.00, 0.59, -22.96, -19.85, 0.10, 18.37, 18.32 -MOT, 1408, 1506, 1405, 1483 -CTUN, 527, 0.00, 20.43, 0.000000, 0.00, 18, 191, 431, 0 -ATT, 0.00, 0.73, -23.03, -20.32, 0.10, 18.43, 18.32 -MOT, 1429, 1494, 1417, 1472 -GPS, 3, 109243200, 1774, 9, 2.42, -39.4940202, 176.7487230, 20.69, 64.59, 10.16, 8.31, -1.850000, 96181 -CTUN, 526, 0.00, 20.36, 0.000000, 0.00, 19, 185, 431, 0 -ATT, 0.00, 0.57, -23.25, -20.53, 0.00, 18.54, 18.32 -MOT, 1421, 1497, 1424, 1469 -CTUN, 526, 0.00, 20.63, 0.000000, 0.00, 20, 177, 432, 0 -ATT, 0.00, 0.61, -22.96, -20.96, 0.10, 18.57, 18.32 -MOT, 1392, 1532, 1392, 1499 -GPS, 3, 109243400, 1774, 9, 2.42, -39.4940021, 176.7487264, 21.04, 64.96, 10.12, 8.39, -1.780000, 96381 -CTUN, 526, 0.00, 20.81, 0.000000, 0.00, 20, 177, 432, 0 -ATT, 0.00, 0.48, -23.03, -20.98, 0.10, 18.53, 18.32 -MOT, 1398, 1524, 1408, 1485 -CTUN, 524, 0.00, 21.49, 0.000000, 0.00, 20, 173, 429, 0 -ATT, 0.00, 0.40, -22.96, -21.18, 0.10, 18.45, 18.32 -MOT, 1385, 1535, 1393, 1488 -GPS, 3, 109243600, 1774, 9, 2.42, -39.4939842, 176.7487298, 21.42, 65.30, 10.07, 8.24, -1.710000, 96581 -CTUN, 526, 0.00, 21.09, 0.000000, 0.00, 20, 169, 432, 0 -ATT, 0.00, 0.26, -22.96, -21.21, 0.00, 18.51, 18.32 -MOT, 1420, 1504, 1400, 1491 -CTUN, 524, 0.00, 21.59, 0.000000, 0.00, 19, 172, 428, 0 -ATT, 0.00, -0.10, -22.96, -20.87, 0.20, 18.66, 18.32 -MOT, 1400, 1503, 1408, 1483 -GPS, 3, 109243800, 1774, 9, 2.42, -39.4939663, 176.7487330, 21.77, 65.64, 10.01, 7.93, -1.650000, 96782 -CTUN, 526, 0.00, 21.94, 0.000000, 0.00, 19, 173, 431, 0 -ATT, 0.00, -0.27, -22.96, -20.75, 0.00, 18.76, 18.32 -MOT, 1425, 1491, 1415, 1480 -CTUN, 527, 0.00, 21.85, 0.000000, 0.00, 19, 166, 432, 0 -ATT, 0.00, 0.14, -22.96, -20.64, 0.00, 18.68, 18.32 -MOT, 1425, 1503, 1405, 1481 -DU32, 7, 270713 -CURR, 431, 93516, 1586, 2725, 4897, 147.3127 -GPS, 3, 109244000, 1774, 9, 2.42, -39.4939486, 176.7487359, 22.14, 65.97, 9.91, 7.42, -1.620000, 96982 -CTUN, 526, 0.00, 21.77, 0.000000, 0.00, 20, 163, 432, 0 -ATT, 0.00, 0.09, -23.18, -21.08, 0.00, 18.57, 18.32 -MOT, 1453, 1474, 1402, 1486 -CTUN, 526, 0.00, 21.98, 0.000000, 0.00, 20, 154, 432, 0 -ATT, 0.00, 0.20, -23.18, -21.46, 0.20, 18.42, 18.32 -MOT, 1398, 1533, 1445, 1437 -GPS, 3, 109244200, 1774, 9, 2.42, -39.4939310, 176.7487388, 22.44, 66.30, 9.86, 7.18, -1.560000, 97182 -CTUN, 526, 0.00, 22.10, 0.000000, 0.00, 21, 147, 433, 0 -ATT, 0.00, 0.13, -23.18, -21.93, 0.20, 18.33, 18.32 -MOT, 1429, 1500, 1413, 1478 -CTUN, 526, 0.00, 22.57, 0.000000, 0.00, 22, 142, 434, 0 -ATT, 0.00, -0.13, -23.18, -22.16, 0.00, 18.13, 18.32 -MOT, 1449, 1493, 1445, 1437 -GPS, 3, 109244400, 1774, 9, 2.42, -39.4939134, 176.7487416, 22.72, 66.61, 9.84, 6.79, -1.500000, 97383 -CTUN, 526, 0.00, 22.39, 0.000000, 0.00, 23, 131, 435, 0 -ATT, 0.00, -0.47, -23.40, -22.75, 0.00, 17.98, 18.32 -MOT, 1412, 1528, 1403, 1485 -CTUN, 526, 0.00, 22.80, 0.000000, 0.00, 23, 125, 435, 0 -ATT, 0.00, -0.54, -23.40, -22.36, 0.10, 17.99, 18.32 -MOT, 1382, 1552, 1419, 1468 -GPS, 3, 109244600, 1774, 9, 2.42, -39.4938956, 176.7487439, 22.97, 66.89, 9.91, 5.89, -1.390000, 97582 -CTUN, 524, 0.00, 23.26, 0.000000, 0.00, 22, 130, 431, 0 -ATT, 0.00, -0.71, -23.18, -22.12, 0.10, 18.03, 18.32 -MOT, 1414, 1513, 1425, 1459 -CTUN, 526, 0.00, 23.33, 0.000000, 0.00, 22, 132, 434, 0 -ATT, 0.00, -0.69, -23.18, -22.10, 0.00, 18.27, 18.32 -MOT, 1400, 1520, 1442, 1461 -GPS, 3, 109244800, 1774, 9, 2.42, -39.4938778, 176.7487460, 23.28, 67.13, 9.97, 5.01, -1.320000, 97783 -CTUN, 526, 0.00, 23.47, 0.000000, 0.00, 22, 129, 434, 0 -ATT, 0.00, -0.81, -23.18, -22.15, 0.00, 18.53, 18.32 -MOT, 1412, 1506, 1419, 1486 -CTUN, 524, 0.00, 23.58, 0.000000, 0.00, 20, 126, 429, 0 -ATT, 0.00, -0.48, -23.18, -21.40, 0.10, 18.62, 18.32 -MOT, 1420, 1502, 1442, 1438 -DU32, 7, 270713 -CURR, 435, 97842, 1613, 2793, 4876, 155.0120 -GPS, 3, 109245000, 1774, 9, 2.42, -39.4938601, 176.7487477, 23.57, 67.35, 9.94, 4.28, -1.280000, 97983 -CTUN, 526, 0.00, 23.72, 0.000000, 0.00, 25, 100, 437, 0 -ATT, 0.00, -0.25, -23.40, -23.80, 0.00, 18.41, 18.32 -MOT, 1390, 1545, 1391, 1506 -CTUN, 526, 0.00, 23.45, 0.000000, 0.00, 26, 76, 438, 0 -ATT, 0.00, 0.03, -23.62, -24.14, 0.00, 18.30, 18.32 -MOT, 1422, 1521, 1449, 1449 -GPS, 3, 109245200, 1774, 9, 2.42, -39.4938424, 176.7487493, 23.75, 67.60, 9.88, 3.92, -1.210000, 98183 -CTUN, 526, 0.00, 23.60, 0.000000, 0.00, 28, 60, 440, 0 -ATT, 0.00, 0.25, -23.62, -24.68, 0.20, 18.18, 18.32 -MOT, 1430, 1516, 1424, 1479 -CTUN, 526, 0.00, 23.57, 0.000000, 0.00, 27, 46, 439, 0 -ATT, 0.00, 0.41, -23.62, -24.46, 0.00, 18.20, 18.32 -MOT, 1469, 1473, 1421, 1482 -GPS, 3, 109245400, 1774, 9, 2.42, -39.4938251, 176.7487506, 23.84, 67.71, 9.72, 3.31, -0.850000, 98383 -CTUN, 526, 0.00, 23.50, 0.000000, 0.00, 27, 37, 439, 0 -ATT, 0.00, 0.84, -23.62, -24.16, 0.00, 18.30, 18.32 -MOT, 1411, 1530, 1431, 1473 -CTUN, 524, 0.00, 23.78, 0.000000, 0.00, 25, 30, 434, 0 -ATT, 0.00, 0.94, -23.83, -23.44, 0.10, 18.31, 18.32 -MOT, 1441, 1496, 1409, 1478 -GPS, 3, 109245600, 1774, 9, 2.42, -39.4938078, 176.7487515, 23.88, 67.80, 9.66, 2.50, -0.610000, 98584 -CTUN, 526, 0.00, 24.01, 0.000000, 0.00, 23, 36, 435, 0 -ATT, 0.00, 0.85, -24.05, -22.41, 0.10, 18.34, 18.32 -MOT, 1421, 1508, 1401, 1498 -CTUN, 524, 0.00, 23.77, 0.000000, 0.00, 20, 48, 429, 0 -ATT, 0.00, 0.28, -24.27, -21.20, 0.00, 18.51, 18.32 -MOT, 1419, 1486, 1404, 1493 -GPS, 3, 109245800, 1774, 9, 2.42, -39.4937906, 176.7487524, 23.98, 67.86, 9.62, 2.24, -0.490000, 98784 -CTUN, 526, 0.00, 23.80, 0.000000, 0.00, 19, 61, 431, 0 -ATT, 0.00, 0.08, -24.56, -20.61, 0.00, 18.58, 18.32 -MOT, 1388, 1528, 1400, 1495 -CTUN, 526, 0.00, 24.13, 0.000000, 0.00, 18, 72, 430, 0 -ATT, 0.00, -0.19, -24.49, -20.14, 0.20, 18.54, 18.32 -MOT, 1445, 1475, 1418, 1469 -DU32, 7, 270713 -CURR, 430, 102201, 1572, 2820, 5006, 162.7852 -GPS, 3, 109246000, 1774, 9, 2.42, -39.4937735, 176.7487534, 24.12, 67.95, 9.57, 2.59, -0.560000, 98984 -CTUN, 526, 0.00, 23.77, 0.000000, 0.00, 17, 78, 429, 0 -ATT, 0.00, -0.04, -24.27, -19.74, 0.10, 18.44, 18.32 -MOT, 1415, 1512, 1382, 1494 -CTUN, 526, 0.00, 23.85, 0.000000, 0.00, 17, 90, 429, 0 -ATT, 0.00, -0.12, -24.12, -19.61, 0.10, 18.10, 18.32 -MOT, 1429, 1509, 1379, 1486 -GPS, 3, 109246200, 1774, 9, 2.42, -39.4937564, 176.7487545, 24.26, 68.12, 9.56, 2.54, -0.700000, 99185 -CTUN, 526, 0.00, 24.11, 0.000000, 0.00, 17, 98, 429, 0 -ATT, 0.00, 0.30, -24.27, -19.59, 1.97, 17.99, 18.68 -MOT, 1444, 1508, 1413, 1438 -CTUN, 524, 0.00, 24.02, 0.000000, 0.00, 17, 103, 426, 0 -ATT, 0.00, 0.52, -24.49, -20.01, 3.53, 18.27, 19.44 -MOT, 1428, 1530, 1345, 1482 -GPS, 3, 109246400, 1774, 9, 2.42, -39.4937394, 176.7487557, 24.45, 68.29, 9.49, 3.12, -0.840000, 99385 -CTUN, 526, 0.00, 24.30, 0.000000, 0.00, 18, 106, 430, 0 -ATT, 0.00, 0.94, -24.27, -20.26, 2.70, 19.05, 20.28 -MOT, 1397, 1544, 1380, 1481 -CTUN, 526, 0.00, 24.45, 0.000000, 0.00, 18, 111, 430, 0 -ATT, 0.00, 1.09, -24.05, -20.09, 2.59, 19.82, 20.98 -MOT, 1443, 1500, 1399, 1464 -GPS, 3, 109246600, 1774, 9, 2.42, -39.4937224, 176.7487571, 24.67, 68.49, 9.46, 3.50, -0.900000, 99585 -CTUN, 526, 0.00, 24.55, 0.000000, 0.00, 18, 119, 430, 0 -ATT, 0.00, 1.21, -24.05, -19.94, 2.39, 20.54, 21.73 -MOT, 1422, 1519, 1403, 1462 -CTUN, 526, 0.00, 24.77, 0.000000, 0.00, 18, 123, 430, 0 -ATT, 0.00, 1.35, -24.05, -19.94, 0.41, 21.17, 22.12 -MOT, 1418, 1504, 1379, 1505 -GPS, 3, 109246800, 1774, 9, 2.42, -39.4937056, 176.7487587, 24.93, 68.71, 9.36, 4.34, -0.950000, 99786 -CTUN, 526, 0.00, 24.78, 0.000000, 0.00, 18, 127, 430, 0 -ATT, 0.00, 1.28, -24.05, -20.05, 0.41, 21.45, 22.20 -MOT, 1410, 1525, 1405, 1466 -CTUN, 526, 0.00, 24.97, 0.000000, 0.00, 18, 127, 430, 0 -ATT, 0.00, 1.50, -24.05, -20.12, 1.03, 21.58, 22.34 -MOT, 1398, 1543, 1398, 1463 -DU32, 7, 270713 -CURR, 430, 106496, 1587, 2709, 4962, 170.4330 -GPS, 3, 109247000, 1774, 9, 2.42, -39.4936890, 176.7487606, 25.19, 68.95, 9.24, 4.92, -1.000000, 99986 -CTUN, 527, 0.00, 24.82, 0.000000, 0.00, 18, 130, 431, 0 -ATT, 0.00, 1.43, -24.12, -20.07, 0.72, 21.79, 22.58 -MOT, 1430, 1510, 1387, 1485 -CTUN, 524, 0.00, 25.06, 0.000000, 0.00, 18, 133, 427, 0 -ATT, 0.00, 1.31, -24.05, -20.01, 0.72, 21.96, 22.78 -MOT, 1392, 1541, 1411, 1442 -GPS, 3, 109247200, 1774, 9, 2.42, -39.4936724, 176.7487630, 25.44, 69.22, 9.18, 6.22, -1.090000, 100186 -CTUN, 526, 0.00, 25.16, 0.000000, 0.00, 18, 130, 430, 0 -ATT, 0.00, 0.59, -23.83, -20.25, 0.83, 22.16, 22.98 -MOT, 1429, 1513, 1365, 1500 -CTUN, 526, 0.00, 25.36, 0.000000, 0.00, 17, 131, 429, 0 -ATT, 0.00, 0.84, -23.83, -19.83, 0.72, 22.45, 23.18 -MOT, 1414, 1525, 1389, 1475 -GPS, 3, 109247400, 1774, 9, 2.42, -39.4936561, 176.7487655, 25.69, 69.50, 9.06, 6.62, -1.160000, 100386 -CTUN, 526, 0.00, 25.44, 0.000000, 0.00, 17, 146, 429, 0 -ATT, 0.00, 0.75, -23.83, -19.52, 0.72, 22.58, 23.38 -MOT, 1388, 1546, 1379, 1484 -CTUN, 526, 0.00, 25.58, 0.000000, 0.00, 16, 163, 428, 0 -ATT, 0.00, 0.51, -23.83, -19.09, 0.72, 22.75, 23.58 -MOT, 1392, 1538, 1388, 1474 -GPS, 3, 109247600, 1774, 9, 2.42, -39.4936400, 176.7487684, 26.01, 69.75, 9.00, 7.81, -1.190000, 100587 -CTUN, 526, 0.00, 25.65, 0.000000, 0.00, 15, 179, 427, 0 -ATT, 0.00, 0.43, -23.83, -18.66, 0.51, 22.88, 23.77 -MOT, 1434, 1501, 1379, 1476 -CTUN, 526, 0.00, 25.80, 0.000000, 0.00, 15, 193, 427, 0 -ATT, 0.00, 0.40, -23.83, -18.38, 0.10, 23.00, 23.83 -MOT, 1409, 1520, 1394, 1468 -GPS, 3, 109247800, 1774, 9, 2.42, -39.4936239, 176.7487714, 26.37, 70.07, 9.04, 8.03, -1.420000, 100787 -CTUN, 526, 0.00, 26.03, 0.000000, 0.00, 15, 199, 427, 0 -ATT, 0.00, 0.37, -23.90, -18.62, 0.20, 22.99, 23.83 -MOT, 1360, 1563, 1373, 1484 -CTUN, 526, 0.00, 26.11, 0.000000, 0.00, 15, 203, 427, 0 -ATT, 0.00, 0.20, -23.83, -18.50, 0.20, 23.14, 23.83 -MOT, 1421, 1508, 1405, 1456 -DU32, 7, 270713 -CURR, 428, 110779, 1552, 2674, 4940, 177.9816 -GPS, 3, 109248000, 1774, 9, 2.42, -39.4936078, 176.7487747, 26.76, 70.45, 9.00, 8.89, -1.650000, 100988 -CTUN, 526, 0.00, 26.69, 0.000000, 0.00, 17, 196, 429, 0 -ATT, 0.00, 0.47, -23.83, -19.57, 0.10, 23.32, 23.83 -MOT, 1418, 1502, 1419, 1463 -CTUN, 537, 0.00, 26.69, 0.000000, 0.00, 19, 180, 444, 0 -ATT, 0.00, 0.22, -23.83, -20.51, 0.10, 23.55, 23.83 -MOT, 1451, 1505, 1440, 1470 -GPS, 3, 109248200, 1774, 9, 2.42, -39.4935917, 176.7487781, 27.13, 70.85, 8.96, 9.09, -1.770000, 101187 -CTUN, 537, 0.00, 26.86, 0.000000, 0.00, 22, 167, 447, 0 -ATT, 0.00, 0.13, -23.83, -21.73, 0.10, 23.73, 23.83 -MOT, 1413, 1540, 1442, 1480 -CTUN, 534, 0.00, 27.18, 0.000000, 0.00, 23, 159, 445, 0 -ATT, 0.00, -0.29, -24.27, -22.33, 0.10, 23.86, 23.83 -MOT, 1434, 1518, 1438, 1480 -GPS, 3, 109248400, 1774, 9, 2.42, -39.4935759, 176.7487814, 27.45, 71.18, 8.91, 9.35, -1.610000, 101388 -CTUN, 535, 0.00, 27.12, 0.000000, 0.00, 25, 146, 448, 0 -ATT, 0.00, -0.82, -24.12, -23.22, 0.10, 23.92, 23.83 -MOT, 1440, 1524, 1432, 1486 -CTUN, 534, 0.00, 27.33, 0.000000, 0.00, 26, 138, 448, 0 -ATT, 0.00, -1.02, -24.27, -23.65, 0.00, 23.94, 23.83 -MOT, 1428, 1532, 1445, 1477 -GPS, 3, 109248600, 1774, 9, 2.42, -39.4935599, 176.7487846, 27.72, 71.48, 8.92, 8.93, -1.450000, 101588 -CTUN, 534, 0.00, 27.44, 0.000000, 0.00, 27, 133, 449, 0 -ATT, 0.00, -1.22, -24.27, -24.12, 0.00, 23.92, 23.83 -MOT, 1423, 1540, 1450, 1471 -CTUN, 534, 0.00, 27.31, 0.000000, 0.00, 28, 127, 450, 0 -ATT, 0.00, -1.44, -24.27, -24.52, 0.00, 23.82, 23.83 -MOT, 1427, 1539, 1442, 1480 -GPS, 3, 109248800, 1774, 9, 2.42, -39.4935437, 176.7487878, 27.96, 71.76, 9.04, 8.50, -1.340000, 101788 -CTUN, 534, 0.00, 27.68, 0.000000, 0.00, 29, 120, 451, 0 -ATT, 0.00, -1.36, -24.05, -24.60, 0.00, 23.76, 23.83 -MOT, 1446, 1532, 1419, 1497 -CTUN, 534, 0.00, 28.32, 0.000000, 0.00, 29, 113, 451, 0 -ATT, 0.00, -1.02, -24.05, -24.55, 0.00, 23.63, 23.83 -MOT, 1462, 1517, 1419, 1497 -DU32, 7, 270713 -CURR, 452, 115236, 1549, 2955, 4897, 186.0750 -GPS, 3, 109249000, 1774, 9, 2.42, -39.4935274, 176.7487907, 28.20, 72.01, 9.17, 7.84, -1.250000, 101988 -CTUN, 534, 0.00, 28.38, 0.000000, 0.00, 28, 108, 450, 0 -ATT, 0.00, -0.64, -24.05, -24.44, 0.00, 23.53, 23.83 -MOT, 1435, 1537, 1421, 1495 -CTUN, 534, 0.00, 28.40, 0.000000, 0.00, 28, 103, 450, 0 -ATT, 0.00, -0.35, -23.83, -24.44, 0.10, 23.47, 23.83 -MOT, 1466, 1506, 1432, 1486 -GPS, 3, 109249200, 1774, 9, 2.42, -39.4935108, 176.7487937, 28.44, 72.25, 9.27, 7.85, -1.190000, 102189 -CTUN, 534, 0.00, 28.68, 0.000000, 0.00, 28, 98, 450, 0 -ATT, 0.00, -0.18, -23.62, -24.30, 0.00, 23.47, 23.83 -MOT, 1501, 1472, 1401, 1517 -CTUN, 534, 0.00, 28.79, 0.000000, 0.00, 27, 96, 449, 0 -ATT, 0.00, 0.15, -23.18, -23.90, 0.10, 23.45, 23.83 -MOT, 1436, 1532, 1412, 1506 -GPS, 3, 109249400, 1774, 9, 2.42, -39.4934941, 176.7487968, 28.67, 72.45, 9.37, 8.00, -1.060000, 102389 -CTUN, 537, 0.00, 28.49, 0.000000, 0.00, 26, 100, 451, 0 -ATT, 0.00, 0.36, -24.05, -23.33, 0.00, 23.50, 23.83 -MOT, 1464, 1509, 1409, 1514 -CTUN, 537, 0.00, 28.89, 0.000000, 0.00, 26, 101, 451, 0 -ATT, 0.00, 0.59, -24.34, -23.29, 0.00, 23.44, 23.83 -MOT, 1446, 1530, 1396, 1522 -GPS, 3, 109249600, 1774, 9, 2.42, -39.4934772, 176.7487999, 28.89, 72.65, 9.45, 8.15, -0.970000, 102589 -CTUN, 537, 0.00, 29.09, 0.000000, 0.00, 25, 99, 450, 0 -ATT, 0.00, 0.68, -24.27, -23.04, 0.10, 23.43, 23.83 -MOT, 1443, 1529, 1415, 1503 -CTUN, 535, 0.00, 29.02, 0.000000, 0.00, 24, 100, 447, 0 -ATT, 0.00, 0.89, -24.56, -22.54, 0.10, 23.40, 23.83 -MOT, 1422, 1546, 1384, 1521 -GPS, 3, 109249800, 1774, 9, 2.42, -39.4934604, 176.7488032, 29.12, 72.83, 9.43, 8.64, -0.940000, 102790 -CTUN, 534, 0.00, 29.33, 0.000000, 0.00, 22, 106, 444, 0 -ATT, 0.00, 0.73, -24.27, -21.79, 0.10, 23.25, 23.83 -MOT, 1425, 1546, 1419, 1470 -CTUN, 535, 0.00, 29.96, 0.000000, 0.00, 21, 111, 444, 0 -ATT, 0.00, 0.44, -24.27, -21.45, 0.00, 23.04, 23.83 -MOT, 1465, 1510, 1393, 1498 -DU32, 7, 270713 -CURR, 443, 119729, 1572, 2923, 4940, 194.3328 -GPS, 3, 109250000, 1774, 9, 2.42, -39.4934438, 176.7488068, 29.40, 73.03, 9.38, 9.42, -0.970000, 102990 -CTUN, 535, 0.00, 29.78, 0.000000, 0.00, 21, 110, 444, 0 -ATT, 0.00, 0.44, -24.05, -21.52, 0.00, 23.01, 23.83 -MOT, 1425, 1540, 1429, 1469 -CTUN, 535, 0.00, 29.68, 0.000000, 0.00, 22, 105, 445, 0 -ATT, 0.00, 0.33, -24.05, -21.76, 0.00, 23.02, 23.83 -MOT, 1464, 1506, 1392, 1508 -GPS, 3, 109250200, 1774, 9, 2.42, -39.4934273, 176.7488107, 29.66, 73.23, 9.29, 10.12, -0.980000, 103190 -CTUN, 534, 0.00, 29.71, 0.000000, 0.00, 22, 98, 444, 0 -ATT, 0.00, 0.68, -24.27, -21.89, 0.20, 23.15, 23.83 -MOT, 1423, 1533, 1439, 1469 -CTUN, 534, 0.00, 29.84, 0.000000, 0.00, 22, 94, 444, 0 -ATT, 0.00, 0.27, -24.71, -21.79, 0.10, 23.29, 23.83 -MOT, 1454, 1502, 1381, 1528 -GPS, 3, 109250400, 1774, 9, 2.43, -39.4934109, 176.7488145, 29.88, 73.41, 9.21, 10.36, -0.890000, 103390 -CTUN, 534, 0.00, 30.14, 0.000000, 0.00, 22, 100, 444, 0 -ATT, 0.00, 0.58, -24.27, -21.68, 0.10, 23.47, 23.83 -MOT, 1396, 1551, 1423, 1489 -CTUN, 534, 0.00, 30.07, 0.000000, 0.00, 21, 105, 443, 0 -ATT, 0.00, 0.56, -23.90, -21.43, 0.00, 23.46, 23.83 -MOT, 1429, 1528, 1417, 1489 -GPS, 3, 109250600, 1774, 9, 2.43, -39.4933947, 176.7488185, 30.12, 73.57, 9.15, 10.63, -0.820000, 103591 -CTUN, 535, 0.00, 30.10, 0.000000, 0.00, 20, 107, 443, 0 -ATT, 0.00, 0.49, -24.34, -20.76, 0.00, 23.61, 23.83 -MOT, 1392, 1551, 1375, 1535 -CTUN, 534, 0.00, 30.25, 0.000000, 0.00, 19, 115, 441, 0 -ATT, 0.00, 0.70, -24.27, -20.60, 0.10, 23.58, 23.83 -MOT, 1405, 1549, 1409, 1484 -GPS, 3, 109250800, 1774, 9, 2.43, -39.4933787, 176.7488227, 30.36, 73.77, 9.09, 11.45, -0.850000, 103791 -CTUN, 534, 0.00, 30.45, 0.000000, 0.00, 20, 114, 442, 0 -ATT, 0.00, 0.75, -24.71, -20.70, 0.10, 23.31, 23.83 -MOT, 1451, 1524, 1416, 1466 -CTUN, 534, 0.00, 30.97, 0.000000, 0.00, 21, 105, 443, 0 -ATT, 0.00, -0.14, -24.71, -21.54, 0.00, 23.15, 23.83 -MOT, 1450, 1519, 1414, 1479 -DU32, 7, 270713 -CURR, 444, 124162, 1567, 2787, 4876, 202.3738 -PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 -GPS, 3, 109251000, 1774, 9, 2.43, -39.4933628, 176.7488271, 30.62, 73.98, 8.96, 12.25, -0.920000, 103991 -CTUN, 534, 0.00, 30.64, 0.000000, 0.00, 23, 95, 445, 0 -ATT, 0.00, -0.14, -24.71, -22.33, 0.20, 23.18, 23.83 -MOT, 1424, 1541, 1431, 1471 -CTUN, 534, 0.00, 30.33, 0.000000, 0.00, 24, 85, 446, 0 -ATT, 0.00, -0.17, -24.71, -22.78, 0.00, 23.24, 23.83 -MOT, 1476, 1493, 1422, 1483 -GPS, 3, 109251200, 1774, 9, 2.43, -39.4933474, 176.7488315, 30.80, 74.17, 8.77, 12.53, -0.830000, 104192 -CTUN, 534, 0.00, 30.64, 0.000000, 0.00, 25, 76, 447, 0 -ATT, 0.00, 0.10, -24.78, -23.16, 0.20, 23.44, 23.83 -MOT, 1407, 1548, 1439, 1479 -CTUN, 534, 0.00, 30.62, 0.000000, 0.00, 25, 74, 447, 0 -ATT, 0.00, 0.18, -24.71, -23.03, 0.00, 23.79, 23.83 -MOT, 1408, 1542, 1412, 1513 -GPS, 3, 109251400, 1774, 9, 2.43, -39.4933320, 176.7488358, 30.93, 74.33, 8.69, 12.36, -0.700000, 104392 -CTUN, 534, 0.00, 30.56, 0.000000, 0.00, 25, 75, 447, 0 -ATT, 0.00, 0.34, -24.71, -22.95, 0.00, 24.08, 23.83 -MOT, 1430, 1520, 1412, 1517 -CTUN, 534, 0.00, 30.65, 0.000000, 0.00, 24, 70, 446, 0 -ATT, 0.00, 0.19, -24.49, -22.80, 0.00, 24.27, 23.83 -MOT, 1428, 1518, 1457, 1472 -GPS, 3, 109251600, 1774, 9, 2.43, -39.4933167, 176.7488403, 31.04, 74.46, 8.75, 12.74, -0.620000, 104592 -CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 26, 57, 448, 0 -ATT, 0.00, 0.63, -24.05, -23.37, 0.00, 24.27, 23.83 -MOT, 1411, 1545, 1416, 1506 -CTUN, 534, 0.00, 30.94, 0.000000, 0.00, 25, 50, 447, 0 -ATT, 0.00, 0.04, -24.27, -23.07, 0.00, 24.16, 23.83 -MOT, 1446, 1516, 1420, 1496 -GPS, 3, 109251800, 1774, 9, 2.43, -39.4933013, 176.7488448, 31.15, 74.57, 8.76, 12.59, -0.560000, 104793 -CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 25, 49, 447, 0 -ATT, 0.00, 0.40, -24.49, -23.00, 0.00, 24.08, 23.83 -MOT, 1409, 1545, 1403, 1517 -CTUN, 535, 0.00, 31.13, 0.000000, 0.00, 25, 46, 448, 0 -ATT, 0.00, 0.44, -24.56, -23.22, 0.00, 24.00, 23.83 -MOT, 1392, 1563, 1424, 1494 -DU32, 7, 270713 -CURR, 447, 128628, 1559, 2951, 4876, 210.5070 -GPS, 3, 109252000, 1774, 9, 2.43, -39.4932860, 176.7488494, 31.24, 74.66, 8.75, 13.15, -0.460000, 104993 -CTUN, 534, 0.00, 30.87, 0.000000, 0.00, 23, 51, 445, 0 -ATT, 0.00, 0.11, -24.92, -22.34, 0.00, 24.03, 23.83 -MOT, 1468, 1489, 1439, 1475 -CTUN, 534, 0.00, 31.25, 0.000000, 0.00, 23, 48, 445, 0 -ATT, 0.00, 0.52, -24.71, -22.18, 0.00, 23.92, 23.83 -MOT, 1372, 1575, 1396, 1514 -GPS, 3, 109252200, 1774, 9, 2.43, -39.4932706, 176.7488541, 31.32, 74.76, 8.77, 13.44, -0.420000, 105193 -CTUN, 534, 0.00, 31.03, 0.000000, 0.00, 21, 52, 443, 0 -ATT, 0.00, -0.01, -24.99, -21.07, 0.00, 23.83, 23.83 -MOT, 1444, 1516, 1390, 1512 -CTUN, 535, 0.00, 30.83, 0.000000, 0.00, 19, 69, 442, 0 -ATT, 0.00, 0.24, -24.99, -20.29, 0.10, 23.66, 23.83 -MOT, 1376, 1573, 1410, 1485 -GPS, 3, 109252400, 1774, 9, 2.43, -39.4932553, 176.7488593, 31.42, 74.84, 8.81, 14.51, -0.410000, 105393 -CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 18, 88, 440, 0 -ATT, 0.00, 0.42, -24.27, -19.80, 0.00, 23.60, 23.83 -MOT, 1384, 1559, 1391, 1506 -CTUN, 534, 0.00, 30.86, 0.000000, 0.00, 16, 110, 438, 0 -ATT, 0.00, 0.22, -24.34, -18.78, 0.20, 23.64, 23.83 -MOT, 1466, 1483, 1415, 1476 -GPS, 3, 109252600, 1774, 9, 2.43, -39.4932398, 176.7488648, 31.58, 75.00, 8.89, 15.29, -0.590000, 105594 -CTUN, 534, 0.00, 31.39, 0.000000, 0.00, 16, 129, 438, 0 -ATT, 0.00, 0.12, -24.71, -18.64, 0.00, 23.69, 23.83 -MOT, 1414, 1519, 1401, 1506 -CTUN, 534, 0.00, 31.43, 0.000000, 0.00, 15, 145, 437, 0 -ATT, 0.00, -0.03, -25.13, -18.49, 0.00, 23.93, 23.83 -MOT, 1428, 1510, 1419, 1480 -GPS, 3, 109252800, 1774, 9, 2.43, -39.4932243, 176.7488705, 31.85, 75.21, 8.94, 15.88, -0.900000, 105794 -CTUN, 537, 0.00, 31.48, 0.000000, 0.00, 16, 161, 441, 0 -ATT, 0.00, -0.21, -25.13, -18.79, 0.00, 23.93, 23.83 -MOT, 1435, 1515, 1412, 1492 -CTUN, 537, 0.00, 31.67, 0.000000, 0.00, 17, 173, 442, 0 -ATT, 0.00, -0.34, -25.13, -19.11, 0.10, 24.00, 23.83 -MOT, 1462, 1483, 1436, 1476 -DU32, 7, 270713 -CURR, 443, 133043, 1569, 2941, 4876, 218.5246 -GPS, 3, 109253000, 1774, 9, 2.43, -39.4932088, 176.7488763, 32.17, 75.49, 8.97, 16.10, -1.180000, 105994 -CTUN, 537, 0.00, 31.83, 0.000000, 0.00, 19, 171, 444, 0 -ATT, 0.00, -0.49, -25.13, -20.21, 0.10, 24.13, 23.83 -MOT, 1396, 1548, 1402, 1514 -CTUN, 537, 0.00, 32.17, 0.000000, 0.00, 20, 169, 445, 0 -ATT, 0.00, -0.26, -25.13, -20.98, 0.10, 24.12, 23.83 -MOT, 1404, 1548, 1452, 1460 -GPS, 3, 109253200, 1774, 9, 2.43, -39.4931932, 176.7488823, 32.50, 75.83, 8.99, 16.61, -1.370000, 106194 -CTUN, 537, 0.00, 32.30, 0.000000, 0.00, 21, 172, 446, 0 -ATT, 0.00, -0.44, -24.92, -21.17, 0.10, 23.98, 23.83 -MOT, 1436, 1524, 1441, 1473 -CTUN, 537, 0.00, 32.61, 0.000000, 0.00, 21, 179, 446, 0 -ATT, 0.00, -1.19, -24.92, -20.95, 0.00, 23.89, 23.83 -MOT, 1421, 1538, 1416, 1496 -GPS, 3, 109253400, 1774, 9, 2.43, -39.4931774, 176.7488884, 32.87, 76.19, 9.03, 16.91, -1.470000, 106395 -CTUN, 537, 0.00, 33.22, 0.000000, 0.00, 22, 182, 447, 0 -ATT, 0.00, -1.04, -24.99, -21.69, 0.20, 23.71, 23.83 -MOT, 1416, 1550, 1413, 1493 -CTUN, 537, 0.00, 32.91, 0.000000, 0.00, 23, 171, 448, 0 -ATT, 0.00, -0.73, -24.92, -22.34, 0.10, 23.70, 23.83 -MOT, 1501, 1470, 1452, 1460 -GPS, 3, 109253600, 1774, 9, 2.43, -39.4931615, 176.7488947, 33.25, 76.56, 9.11, 17.11, -1.570000, 106595 -CTUN, 542, 0.00, 33.28, 0.000000, 0.00, 27, 154, 459, 0 -ATT, 0.00, -0.59, -24.99, -23.48, 0.00, 23.68, 23.83 -MOT, 1454, 1537, 1452, 1483 -CTUN, 542, 0.00, 33.35, 0.000000, 0.00, 30, 136, 462, 0 -ATT, 0.00, -0.41, -24.92, -24.76, 0.00, 23.62, 23.83 -MOT, 1442, 1551, 1455, 1486 -GPS, 3, 109253800, 1774, 9, 2.43, -39.4931458, 176.7489006, 33.56, 76.90, 9.04, 16.33, -1.530000, 106796 -CTUN, 542, 0.00, 33.47, 0.000000, 0.00, 32, 123, 464, 0 -ATT, 0.00, -0.45, -24.71, -25.39, 0.00, 23.57, 23.83 -MOT, 1469, 1536, 1445, 1498 -CTUN, 542, 0.00, 33.38, 0.000000, 0.00, 33, 108, 465, 0 -ATT, 0.00, -0.60, -24.34, -26.02, 0.20, 23.61, 23.83 -MOT, 1498, 1506, 1492, 1462 -DU32, 7, 270713 -CURR, 467, 137556, 1528, 2975, 4876, 226.8026 -GPS, 3, 109254000, 1774, 9, 2.43, -39.4931300, 176.7489062, 33.77, 77.18, 9.03, 15.68, -1.300000, 106996 -CTUN, 539, 0.00, 33.95, 0.000000, 0.00, 34, 84, 462, 0 -ATT, 0.00, -0.80, -24.05, -26.38, 0.00, 23.47, 23.83 -MOT, 1474, 1532, 1445, 1490 -CTUN, 543, 0.00, 33.68, 0.000000, 0.00, 35, 65, 468, 0 -ATT, 0.00, -0.59, -24.05, -26.31, 0.00, 23.20, 23.83 -MOT, 1504, 1528, 1425, 1514 -GPS, 3, 109254200, 1774, 9, 2.43, -39.4931142, 176.7489117, 33.93, 77.40, 9.06, 14.94, -1.050000, 107196 -CTUN, 539, 0.00, 34.08, 0.000000, 0.00, 33, 56, 461, 0 -ATT, 0.00, -0.42, -24.05, -25.98, 0.10, 22.98, 23.83 -MOT, 1493, 1518, 1463, 1463 -CTUN, 543, 0.00, 34.06, 0.000000, 0.00, 33, 41, 466, 0 -ATT, 0.00, 0.17, -24.05, -25.56, 0.00, 22.83, 23.83 -MOT, 1477, 1546, 1397, 1536 -GPS, 3, 109254400, 1774, 9, 2.43, -39.4930982, 176.7489169, 34.04, 77.55, 9.13, 14.36, -0.760000, 107396 -CTUN, 540, 0.00, 33.96, 0.000000, 0.00, 29, 34, 458, 0 -ATT, 0.00, 1.02, -24.05, -24.52, 0.10, 22.86, 23.83 -MOT, 1468, 1530, 1471, 1456 -CTUN, 542, 0.00, 34.36, 0.000000, 0.00, 29, 25, 461, 0 -ATT, 0.00, 0.79, -24.05, -24.18, 0.00, 23.02, 23.83 -MOT, 1496, 1500, 1407, 1533 -GPS, 3, 109254600, 1774, 9, 2.43, -39.4930821, 176.7489222, 34.11, 77.63, 9.23, 14.03, -0.520000, 107596 -CTUN, 542, 0.00, 34.15, 0.000000, 0.00, 25, 29, 457, 0 -ATT, 0.00, 0.55, -24.12, -22.77, 0.20, 23.43, 23.83 -MOT, 1394, 1573, 1453, 1489 -CTUN, 539, 0.00, 34.88, 0.000000, 0.00, 21, 46, 449, 0 -ATT, 0.00, 0.45, -24.27, -21.18, 0.00, 23.78, 23.83 -MOT, 1407, 1543, 1421, 1512 -GPS, 3, 109254800, 1774, 9, 2.43, -39.4930660, 176.7489274, 34.24, 77.68, 9.26, 13.86, -0.400000, 107797 -CTUN, 539, 0.00, 34.39, 0.000000, 0.00, 19, 56, 447, 0 -ATT, 0.00, 0.38, -24.49, -20.15, 0.00, 23.98, 23.83 -MOT, 1444, 1514, 1373, 1543 -CTUN, 542, 0.00, 34.38, 0.000000, 0.00, 18, 70, 450, 0 -ATT, 0.00, 1.16, -24.49, -19.55, 0.00, 24.16, 23.83 -MOT, 1400, 1551, 1416, 1517 -DU32, 7, 270713 -CURR, 449, 142136, 1554, 2866, 4984, 235.1741 -GPS, 3, 109255000, 1774, 9, 2.43, -39.4930499, 176.7489325, 34.41, 77.78, 9.23, 13.73, -0.470000, 107997 -CTUN, 542, 0.00, 34.33, 0.000000, 0.00, 17, 91, 449, 0 -ATT, 0.00, 1.50, -24.71, -18.72, 0.00, 24.16, 23.83 -MOT, 1414, 1549, 1423, 1495 -CTUN, 540, 0.00, 34.52, 0.000000, 0.00, 15, 114, 444, 0 -ATT, 0.00, 0.73, -24.49, -17.99, 0.10, 24.02, 23.83 -MOT, 1417, 1543, 1403, 1498 -GPS, 3, 109255200, 1774, 9, 2.43, -39.4930336, 176.7489378, 34.64, 77.94, 9.31, 14.09, -0.630000, 108198 -CTUN, 539, 0.00, 34.66, 0.000000, 0.00, 15, 134, 443, 0 -ATT, 0.00, 0.29, -24.49, -17.82, 0.00, 23.90, 23.83 -MOT, 1373, 1576, 1414, 1485 -CTUN, 542, 0.00, 34.48, 0.000000, 0.00, 14, 157, 446, 0 -ATT, 0.00, 0.12, -24.49, -17.51, 0.00, 23.82, 23.83 -MOT, 1433, 1534, 1418, 1488 -GPS, 3, 109255400, 1774, 9, 2.43, -39.4930174, 176.7489433, 34.95, 78.16, 9.31, 14.45, -0.930000, 108397 -CTUN, 539, 0.00, 34.96, 0.000000, 0.00, 14, 178, 442, 0 -ATT, 0.00, -0.11, -24.71, -17.44, 0.00, 23.80, 23.83 -MOT, 1430, 1518, 1410, 1500 -CTUN, 539, 0.00, 35.11, 0.000000, 0.00, 15, 182, 443, 0 -ATT, 0.00, 0.00, -24.27, -18.35, 0.10, 23.78, 23.83 -MOT, 1352, 1584, 1404, 1505 -GPS, 3, 109255600, 1774, 9, 2.43, -39.4930010, 176.7489490, 35.33, 78.49, 9.32, 15.22, -1.240000, 108598 -CTUN, 540, 0.00, 35.31, 0.000000, 0.00, 13, 196, 442, 0 -ATT, 0.00, -0.76, -24.12, -17.17, 0.00, 24.27, 23.83 -MOT, 1492, 1437, 1432, 1497 -CTUN, 543, 0.00, 35.84, 0.000000, 0.00, 15, 201, 448, 0 -ATT, 0.00, -0.98, -24.27, -17.91, 0.00, 24.63, 23.83 -MOT, 1401, 1534, 1422, 1523 -GPS, 3, 109255800, 1774, 9, 2.43, -39.4929849, 176.7489544, 35.77, 78.86, 9.18, 14.86, -1.480000, 108798 -CTUN, 542, 0.00, 35.88, 0.000000, 0.00, 16, 196, 448, 0 -ATT, 0.00, -1.03, -24.49, -18.48, 0.00, 24.70, 23.83 -MOT, 1429, 1519, 1418, 1517 -CTUN, 539, 0.00, 36.00, 0.000000, 0.00, 18, 184, 446, 0 -ATT, 0.00, -1.13, -24.05, -19.78, 0.00, 24.70, 23.83 -MOT, 1437, 1506, 1465, 1465 -DU32, 7, 270713 -CURR, 447, 146589, 1583, 2876, 4940, 243.5272 -GPS, 3, 109256000, 1774, 9, 2.43, -39.4929692, 176.7489597, 36.18, 79.25, 8.94, 14.54, -1.580000, 108998 -CTUN, 539, 0.00, 36.11, 0.000000, 0.00, 20, 167, 448, 0 -ATT, 0.00, -0.67, -24.12, -20.55, 0.20, 24.67, 23.83 -MOT, 1394, 1558, 1466, 1456 -CTUN, 539, 0.00, 36.43, 0.000000, 0.00, 22, 155, 450, 0 -ATT, 0.00, -1.00, -24.05, -21.81, 0.00, 24.39, 23.83 -MOT, 1452, 1517, 1405, 1517 -GPS, 3, 109256200, 1774, 9, 2.43, -39.4929538, 176.7489644, 36.52, 79.61, 8.70, 13.52, -1.510000, 109199 -CTUN, 539, 0.00, 36.44, 0.000000, 0.00, 25, 138, 453, 0 -ATT, 0.00, -0.37, -23.62, -22.84, 0.00, 24.20, 23.83 -MOT, 1459, 1514, 1480, 1451 -CTUN, 542, 0.00, 36.43, 0.000000, 0.00, 26, 125, 458, 0 -ATT, 0.00, 0.00, -23.90, -23.07, 0.20, 24.29, 23.83 -MOT, 1420, 1546, 1414, 1537 -GPS, 3, 109256400, 1774, 9, 2.43, -39.4929387, 176.7489687, 36.78, 79.90, 8.50, 12.77, -1.290000, 109399 -CTUN, 539, 0.00, 36.75, 0.000000, 0.00, 25, 114, 453, 0 -ATT, 0.00, 0.49, -23.62, -23.12, 0.00, 24.32, 23.83 -MOT, 1449, 1518, 1446, 1491 -CTUN, 542, 0.00, 36.85, 0.000000, 0.00, 25, 106, 457, 0 -ATT, 0.00, 0.46, -23.83, -22.79, 0.00, 24.32, 23.83 -MOT, 1455, 1524, 1418, 1523 -GPS, 3, 109256600, 1774, 9, 2.43, -39.4929238, 176.7489731, 37.01, 80.13, 8.44, 12.84, -1.100000, 109599 -CTUN, 539, 0.00, 36.96, 0.000000, 0.00, 25, 108, 453, 0 -ATT, 0.00, 0.56, -24.05, -22.74, 0.10, 24.24, 23.83 -MOT, 1413, 1553, 1424, 1506 -CTUN, 539, 0.00, 37.33, 0.000000, 0.00, 24, 101, 452, 0 -ATT, 0.00, 0.82, -24.05, -22.60, 0.00, 24.28, 23.83 -MOT, 1408, 1549, 1446, 1491 -GPS, 3, 109256800, 1774, 9, 2.43, -39.4929091, 176.7489776, 37.24, 80.33, 8.41, 13.19, -1.010000, 109800 -CTUN, 542, 0.00, 37.40, 0.000000, 0.00, 23, 99, 455, 0 -ATT, 0.00, 0.37, -24.27, -21.92, 0.10, 24.39, 23.83 -MOT, 1423, 1543, 1388, 1548 -CTUN, 542, 0.00, 37.35, 0.000000, 0.00, 21, 112, 453, 0 -ATT, 0.00, 0.29, -24.05, -20.87, 0.10, 24.33, 23.83 -MOT, 1382, 1572, 1400, 1535 -DU32, 7, 270713 -CURR, 450, 151121, 1536, 3095, 4897, 251.8125 -GPS, 3, 109257000, 1774, 9, 2.43, -39.4928947, 176.7489820, 37.49, 80.50, 8.31, 13.04, -0.950000, 110000 -CTUN, 542, 0.00, 37.11, 0.000000, 0.00, 18, 136, 450, 0 -ATT, 0.00, 0.10, -23.83, -19.36, 0.00, 24.36, 23.83 -MOT, 1453, 1501, 1481, 1456 -CTUN, 542, 0.00, 37.54, 0.000000, 0.00, 16, 150, 448, 0 -ATT, 0.00, -0.16, -23.83, -18.58, 0.10, 24.37, 23.83 -MOT, 1431, 1525, 1405, 1521 -GPS, 3, 109257200, 1774, 9, 2.43, -39.4928805, 176.7489863, 37.78, 80.72, 8.17, 13.28, -1.060000, 110201 -CTUN, 542, 0.00, 37.71, 0.000000, 0.00, 16, 157, 448, 0 -ATT, 0.00, -0.30, -23.62, -18.48, 0.00, 24.33, 23.83 -MOT, 1422, 1532, 1418, 1509 -CTUN, 542, 0.00, 37.73, 0.000000, 0.00, 16, 162, 448, 0 -ATT, 0.00, -0.42, -24.12, -18.41, 0.20, 24.23, 23.83 -MOT, 1436, 1526, 1437, 1483 -GPS, 3, 109257400, 1774, 9, 2.43, -39.4928664, 176.7489905, 38.11, 81.02, 8.04, 13.08, -1.280000, 110401 -CTUN, 542, 0.00, 37.68, 0.000000, 0.00, 17, 165, 449, 0 -ATT, 0.00, -0.40, -24.05, -19.03, 0.00, 24.07, 23.83 -MOT, 1400, 1555, 1392, 1532 -CTUN, 539, 0.00, 38.18, 0.000000, 0.00, 18, 165, 446, 0 -ATT, 0.00, -0.30, -24.27, -19.61, 0.00, 23.97, 23.83 -MOT, 1418, 1541, 1413, 1499 -GPS, 3, 109257600, 1774, 9, 2.43, -39.4928525, 176.7489946, 38.43, 81.34, 7.88, 12.96, -1.390000, 110601 -CTUN, 539, 0.00, 38.10, 0.000000, 0.00, 18, 168, 446, 0 -ATT, 0.00, -0.01, -24.27, -19.77, 0.00, 23.89, 23.83 -MOT, 1424, 1537, 1412, 1498 -CTUN, 542, 0.00, 38.00, 0.000000, 0.00, 19, 169, 451, 0 -ATT, 0.00, 0.23, -24.71, -20.11, 0.00, 23.84, 23.83 -MOT, 1440, 1524, 1431, 1500 -GPS, 3, 109257800, 1774, 9, 2.43, -39.4928389, 176.7489986, 38.74, 81.64, 7.73, 12.86, -1.400000, 110801 -CTUN, 539, 0.00, 38.70, 0.000000, 0.00, 20, 165, 448, 0 -ATT, 0.00, 0.27, -24.78, -20.87, 0.00, 23.80, 23.83 -MOT, 1388, 1568, 1398, 1518 -CTUN, 542, 0.00, 38.91, 0.000000, 0.00, 22, 159, 454, 0 -ATT, 0.00, 0.32, -24.49, -21.41, 0.00, 23.73, 23.83 -MOT, 1429, 1539, 1444, 1493 -DU32, 7, 270713 -CURR, 450, 155609, 1554, 2967, 4940, 260.1063 -GPS, 3, 109258000, 1774, 9, 2.43, -39.4928254, 176.7490024, 39.08, 81.97, 7.64, 12.65, -1.450000, 111002 -CTUN, 539, 0.00, 38.86, 0.000000, 0.00, 23, 152, 451, 0 -ATT, 0.00, -0.06, -24.49, -22.12, 0.10, 23.85, 23.83 -MOT, 1466, 1500, 1457, 1472 -CTUN, 539, 0.00, 39.10, 0.000000, 0.00, 25, 139, 453, 0 -ATT, 0.00, 0.00, -24.56, -22.90, 0.00, 23.81, 23.83 -MOT, 1404, 1564, 1437, 1488 -GPS, 3, 109258200, 1774, 9, 2.43, -39.4928122, 176.7490063, 39.37, 82.26, 7.49, 12.75, -1.360000, 111202 -CTUN, 539, 0.00, 39.08, 0.000000, 0.00, 26, 128, 454, 0 -ATT, 0.00, 0.18, -24.56, -23.37, 0.20, 23.73, 23.83 -MOT, 1446, 1535, 1473, 1452 -CTUN, 542, 0.00, 39.69, 0.000000, 0.00, 28, 114, 460, 0 -ATT, 0.00, 0.10, -24.49, -24.10, 0.00, 23.69, 23.83 -MOT, 1427, 1557, 1433, 1509 -GPS, 3, 109258400, 1774, 9, 2.43, -39.4927993, 176.7490101, 39.61, 82.52, 7.38, 12.82, -1.240000, 111402 -CTUN, 539, 0.00, 39.34, 0.000000, 0.00, 29, 101, 457, 0 -ATT, 0.00, 0.09, -24.49, -24.54, 0.00, 23.72, 23.83 -MOT, 1448, 1532, 1449, 1491 -CTUN, 543, 0.00, 39.88, 0.000000, 0.00, 30, 88, 463, 0 -ATT, 0.00, 0.00, -24.49, -24.64, 0.10, 23.76, 23.83 -MOT, 1438, 1551, 1434, 1516 -GPS, 3, 109258600, 1774, 9, 2.43, -39.4927864, 176.7490139, 39.81, 82.72, 7.37, 12.71, -1.060000, 111602 -CTUN, 542, 0.00, 39.79, 0.000000, 0.00, 29, 86, 461, 0 -ATT, 0.00, -0.27, -24.71, -24.08, 0.00, 23.80, 23.83 -MOT, 1436, 1546, 1445, 1504 -CTUN, 543, 0.00, 40.35, 0.000000, 0.00, 28, 87, 461, 0 -ATT, 0.00, -0.58, -24.92, -23.78, 0.00, 23.88, 23.83 -MOT, 1419, 1558, 1462, 1490 -GPS, 3, 109258800, 1774, 9, 2.43, -39.4927735, 176.7490175, 40.02, 82.88, 7.31, 12.50, -0.870000, 111803 -CTUN, 542, 0.00, 39.76, 0.000000, 0.00, 27, 83, 459, 0 -ATT, 0.00, -0.93, -24.92, -23.70, 0.00, 23.95, 23.83 -MOT, 1460, 1525, 1439, 1504 -CTUN, 540, 0.00, 39.67, 0.000000, 0.00, 28, 75, 457, 0 -ATT, 0.00, -0.93, -25.13, -24.20, 0.10, 23.94, 23.83 -MOT, 1427, 1552, 1434, 1501 -DU32, 7, 270713 -CURR, 456, 160185, 1552, 3048, 4918, 268.5145 -GPS, 3, 109259000, 1774, 9, 2.43, -39.4927608, 176.7490210, 40.15, 83.01, 7.32, 12.12, -0.790000, 112003 -CTUN, 542, 0.00, 39.69, 0.000000, 0.00, 29, 65, 461, 0 -ATT, 0.00, -0.48, -24.92, -24.50, 0.20, 23.84, 23.83 -MOT, 1488, 1509, 1450, 1492 -CTUN, 539, 0.00, 39.70, 0.000000, 0.00, 31, 43, 459, 0 -ATT, 0.00, -0.12, -24.92, -25.23, 0.20, 23.83, 23.83 -MOT, 1439, 1549, 1465, 1470 -GPS, 3, 109259200, 1774, 9, 2.43, -39.4927479, 176.7490242, 40.20, 83.12, 7.34, 11.32, -0.670000, 112203 -CTUN, 542, 0.00, 40.02, 0.000000, 0.00, 33, 22, 465, 0 -ATT, 0.00, 0.18, -24.99, -25.68, 0.00, 23.77, 23.83 -MOT, 1478, 1532, 1448, 1500 -CTUN, 542, 0.00, 40.35, 0.000000, 0.00, 35, 2, 467, 0 -ATT, 0.00, 0.68, -24.92, -26.46, 0.00, 23.62, 23.83 -MOT, 1410, 1592, 1461, 1486 -GPS, 3, 109259400, 1774, 9, 2.43, -39.4927349, 176.7490273, 40.22, 83.21, 7.34, 10.86, -0.450000, 112403 -CTUN, 542, 0.00, 39.77, 0.000000, 0.00, 32, -2, 464, 0 -ATT, 0.00, -0.30, -24.71, -25.44, 0.00, 23.55, 23.83 -MOT, 1469, 1531, 1425, 1524 -CTUN, 542, 0.00, 40.08, 0.000000, 0.00, 26, 15, 458, 0 -ATT, 0.00, -1.42, -24.71, -23.06, 0.00, 23.62, 23.83 -MOT, 1423, 1548, 1464, 1483 -GPS, 3, 109259600, 1774, 9, 2.43, -39.4927221, 176.7490301, 40.21, 83.17, 7.31, 10.19, -0.099999, 112604 -CTUN, 539, 0.00, 40.00, 0.000000, 0.00, 22, 40, 450, 0 -ATT, 0.00, -1.87, -24.92, -21.58, 0.00, 23.68, 23.83 -MOT, 1411, 1546, 1420, 1509 -CTUN, 540, 0.00, 40.07, 0.000000, 0.00, 20, 55, 449, 0 -ATT, 0.00, -2.06, -24.71, -20.32, 0.10, 23.67, 23.83 -MOT, 1405, 1554, 1413, 1508 -GPS, 3, 109259800, 1774, 9, 2.43, -39.4927090, 176.7490326, 40.30, 83.18, 7.44, 9.17, -0.110000, 112804 -CTUN, 539, 0.00, 40.07, 0.000000, 0.00, 19, 69, 447, 0 -ATT, 0.00, -2.00, -24.92, -19.91, 0.00, 23.68, 23.83 -MOT, 1445, 1517, 1445, 1471 -CTUN, 539, 0.00, 39.76, 0.000000, 0.00, 19, 78, 447, 0 -ATT, 0.00, -1.72, -24.92, -20.25, 0.00, 23.63, 23.83 -MOT, 1421, 1537, 1407, 1512 -DU32, 7, 270713 -CURR, 447, 164742, 1580, 2990, 4940, 277.0022 -GPS, 3, 109260000, 1774, 9, 2.43, -39.4926954, 176.7490347, 40.42, 83.28, 7.60, 7.95, -0.380000, 113005 -CTUN, 542, 0.00, 40.27, 0.000000, 0.00, 20, 88, 452, 0 -ATT, 0.00, -1.26, -24.71, -20.36, 0.00, 23.60, 23.83 -MOT, 1422, 1547, 1442, 1482 -CTUN, 542, 0.00, 40.27, 0.000000, 0.00, 20, 95, 452, 0 -ATT, 0.00, -0.93, -24.05, -20.66, 0.00, 23.64, 23.83 -MOT, 1393, 1569, 1429, 1498 -GPS, 3, 109260200, 1774, 9, 2.43, -39.4926817, 176.7490362, 40.59, 83.44, 7.64, 6.49, -0.550000, 113205 -CTUN, 542, 0.00, 40.23, 0.000000, 0.00, 20, 97, 452, 0 -ATT, 0.00, -0.28, -23.83, -20.72, 0.20, 23.82, 23.83 -MOT, 1367, 1586, 1433, 1498 -CTUN, 542, 0.00, 40.64, 0.000000, 0.00, 19, 109, 451, 0 -ATT, 0.00, -0.01, -23.40, -20.01, 0.00, 24.07, 23.83 -MOT, 1431, 1529, 1430, 1505 -GPS, 3, 109260400, 1774, 9, 2.43, -39.4926680, 176.7490375, 40.80, 83.60, 7.61, 5.22, -0.650000, 113405 -CTUN, 542, 0.00, 40.60, 0.000000, 0.00, 18, 121, 450, 0 -ATT, 0.00, 0.34, -23.18, -19.29, 0.00, 24.16, 23.83 -MOT, 1440, 1520, 1430, 1501 -CTUN, 542, 0.00, 40.51, 0.000000, 0.00, 16, 130, 448, 0 -ATT, 0.00, 0.48, -22.75, -18.67, 0.00, 24.22, 23.83 -MOT, 1400, 1551, 1423, 1501 -GPS, 3, 109260600, 1774, 9, 2.43, -39.4926544, 176.7490384, 41.04, 83.80, 7.51, 4.14, -0.780000, 113605 -CTUN, 542, 0.00, 40.58, 0.000000, 0.00, 15, 142, 447, 0 -ATT, 0.00, 0.79, -22.53, -18.02, 0.00, 24.17, 23.83 -MOT, 1430, 1533, 1448, 1466 -CTUN, 542, 0.00, 40.94, 0.000000, 0.00, 14, 148, 446, 0 -ATT, 0.00, 0.96, -22.53, -17.53, 0.10, 24.09, 23.83 -MOT, 1417, 1545, 1419, 1489 -GPS, 3, 109260800, 1774, 9, 2.43, -39.4926413, 176.7490391, 41.32, 84.02, 7.29, 3.28, -0.940000, 113805 -CTUN, 542, 0.00, 40.95, 0.000000, 0.00, 14, 153, 446, 0 -ATT, 0.00, 0.87, -22.53, -17.66, 0.10, 23.88, 23.83 -MOT, 1424, 1541, 1378, 1528 -CTUN, 543, 0.00, 41.04, 0.000000, 0.00, 14, 158, 447, 0 -ATT, 0.00, 1.17, -22.75, -17.20, 0.10, 23.70, 23.83 -MOT, 1421, 1548, 1421, 1482 -DU32, 7, 270713 -CURR, 447, 169231, 1539, 2927, 4876, 285.3965 -PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 -GPS, 3, 109261000, 1774, 9, 2.43, -39.4926285, 176.7490398, 41.61, 84.31, 7.06, 2.80, -1.120000, 114006 -CTUN, 542, 0.00, 41.14, 0.000000, 0.00, 14, 164, 446, 0 -ATT, 0.00, 1.18, -22.96, -17.40, 0.00, 23.61, 23.83 -MOT, 1442, 1528, 1392, 1512 -CTUN, 543, 0.00, 41.37, 0.000000, 0.00, 14, 167, 447, 0 -ATT, 0.00, 1.02, -22.75, -17.60, 0.10, 23.66, 23.83 -MOT, 1421, 1540, 1412, 1502 -GPS, 3, 109261200, 1774, 9, 2.43, -39.4926161, 176.7490403, 41.92, 84.60, 6.84, 2.31, -1.210000, 114206 -CTUN, 542, 0.00, 41.35, 0.000000, 0.00, 15, 171, 447, 0 -ATT, 0.00, 0.93, -22.96, -17.77, 0.10, 23.69, 23.83 -MOT, 1428, 1538, 1413, 1497 -CTUN, 542, 0.00, 41.47, 0.000000, 0.00, 15, 175, 447, 0 -ATT, 0.14, 0.74, -22.96, -18.04, 0.10, 23.67, 23.83 -MOT, 1413, 1553, 1393, 1513 -GPS, 3, 109261400, 1774, 9, 2.43, -39.4926043, 176.7490409, 42.23, 84.88, 6.59, 2.18, -1.280000, 114406 -CTUN, 542, 0.00, 41.88, 0.000000, 0.00, 15, 178, 447, 0 -ATT, 0.21, 0.64, -23.18, -18.17, 0.10, 23.70, 23.83 -MOT, 1396, 1563, 1435, 1475 -CTUN, 542, 0.00, 41.68, 0.000000, 0.00, 16, 183, 448, 0 -ATT, 0.21, 0.50, -23.40, -18.41, 0.10, 23.64, 23.83 -MOT, 1434, 1538, 1419, 1489 -GPS, 3, 109261600, 1774, 9, 2.43, -39.4925927, 176.7490415, 42.56, 85.19, 6.40, 2.09, -1.380000, 114606 -CTUN, 542, 0.00, 41.81, 0.000000, 0.00, 16, 191, 448, 0 -ATT, 0.21, 0.66, -23.40, -18.69, 0.20, 23.63, 23.83 -MOT, 1432, 1540, 1425, 1482 -CTUN, 542, 0.00, 42.59, 0.000000, 0.00, 17, 196, 449, 0 -ATT, 0.86, 0.70, -24.05, -18.97, 0.10, 23.57, 23.83 -MOT, 1468, 1510, 1409, 1501 -GPS, 3, 109261800, 1774, 9, 2.43, -39.4925816, 176.7490420, 42.92, 85.49, 6.21, 2.01, -1.430000, 114807 -CTUN, 542, 0.00, 42.46, 0.000000, 0.00, 17, 200, 449, 0 -ATT, 1.29, 0.92, -24.34, -19.18, 0.10, 23.50, 23.83 -MOT, 1456, 1521, 1431, 1479 -CTUN, 539, 0.00, 42.60, 0.000000, 0.00, 18, 201, 446, 0 -ATT, 1.43, 0.89, -24.49, -19.80, 0.10, 23.53, 23.83 -MOT, 1441, 1521, 1436, 1476 -DU32, 7, 270713 -CURR, 448, 173710, 1569, 3056, 4897, 293.6468 -GPS, 3, 109262000, 1774, 9, 2.43, -39.4925706, 176.7490425, 43.29, 85.83, 6.08, 1.99, -1.530000, 115007 -CTUN, 539, 0.00, 42.93, 0.000000, 0.00, 21, 190, 449, 0 -ATT, 1.65, 1.21, -24.49, -21.09, 0.10, 23.56, 23.83 -MOT, 1464, 1509, 1428, 1486 -CTUN, 542, 0.00, 42.83, 0.000000, 0.00, 22, 179, 454, 0 -ATT, 2.16, 1.50, -24.71, -21.46, 0.10, 23.50, 23.83 -MOT, 1472, 1516, 1408, 1513 -GPS, 3, 109262200, 1774, 9, 2.43, -39.4925600, 176.7490430, 43.63, 86.18, 5.88, 2.15, -1.550000, 115207 -CTUN, 539, 0.00, 42.82, 0.000000, 0.00, 22, 178, 450, 0 -ATT, 2.30, 1.83, -24.92, -21.66, 0.20, 23.39, 23.83 -MOT, 1431, 1542, 1438, 1476 -CTUN, 539, 0.00, 43.32, 0.000000, 0.00, 23, 173, 451, 0 -ATT, 2.95, 2.56, -25.35, -22.11, 0.00, 23.39, 23.83 -MOT, 1422, 1550, 1425, 1491 -GPS, 3, 109262400, 1774, 9, 2.43, -39.4925496, 176.7490437, 43.92, 86.47, 5.76, 2.59, -1.430000, 115408 -CTUN, 542, 0.00, 43.43, 0.000000, 0.00, 26, 160, 458, 0 -ATT, 3.02, 2.96, -25.86, -23.18, 0.20, 23.32, 23.83 -MOT, 1464, 1529, 1433, 1498 -CTUN, 539, 0.00, 43.60, 0.000000, 0.00, 28, 145, 456, 0 -ATT, 3.67, 3.24, -25.79, -24.19, 0.00, 23.19, 23.83 -MOT, 1479, 1515, 1448, 1475 -GPS, 3, 109262600, 1774, 9, 2.43, -39.4925393, 176.7490446, 44.18, 86.77, 5.70, 3.32, -1.380000, 115608 -CTUN, 539, 0.00, 44.18, 0.000000, 0.00, 32, 127, 460, 0 -ATT, 3.89, 3.94, -25.79, -25.24, 0.10, 23.14, 23.83 -MOT, 1459, 1538, 1425, 1508 -CTUN, 543, 0.00, 43.76, 0.000000, 0.00, 34, 114, 467, 0 -ATT, 4.10, 4.32, -26.08, -25.84, 0.00, 23.08, 23.83 -MOT, 1526, 1497, 1443, 1500 -GPS, 3, 109262800, 1774, 9, 2.43, -39.4925289, 176.7490456, 44.41, 87.06, 5.70, 4.08, -1.220000, 115808 -CTUN, 542, 0.00, 43.94, 0.000000, 0.00, 37, 98, 469, 0 -ATT, 4.25, 4.46, -26.44, -26.89, 0.00, 22.88, 23.83 -MOT, 1430, 1579, 1433, 1519 -CTUN, 539, 0.00, 44.30, 0.000000, 0.00, 37, 87, 465, 0 -ATT, 4.97, 4.34, -26.66, -27.02, 0.10, 22.83, 23.83 -MOT, 1482, 1535, 1412, 1528 -DU32, 7, 270713 -CURR, 465, 178287, 1573, 3207, 4918, 302.1701 -GPS, 3, 109263000, 1774, 9, 2.43, -39.4925188, 176.7490470, 44.56, 87.25, 5.66, 5.27, -0.980000, 116008 -CTUN, 539, 0.00, 43.95, 0.000000, 0.00, 37, 82, 465, 0 -ATT, 5.40, 4.53, -26.73, -26.89, 0.20, 22.86, 23.83 -MOT, 1460, 1554, 1472, 1465 -CTUN, 542, 0.00, 44.06, 0.000000, 0.00, 36, 84, 468, 0 -ATT, 5.84, 4.81, -27.16, -26.34, 0.00, 22.99, 23.83 -MOT, 1505, 1518, 1463, 1484 -GPS, 3, 109263200, 1774, 9, 2.43, -39.4925087, 176.7490489, 44.67, 87.37, 5.68, 6.75, -0.740000, 116209 -CTUN, 542, 0.00, 44.08, 0.000000, 0.00, 38, 75, 470, 0 -ATT, 4.76, 4.96, -26.66, -26.95, 0.10, 23.04, 23.83 -MOT, 1418, 1583, 1408, 1549 -CTUN, 542, 0.00, 44.36, 0.000000, 0.00, 35, 73, 467, 0 -ATT, 4.54, 4.69, -26.22, -26.14, 0.00, 23.35, 23.83 -MOT, 1471, 1536, 1450, 1509 -GPS, 3, 109263400, 1774, 9, 2.43, -39.4924982, 176.7490512, 44.77, 87.55, 5.86, 8.33, -0.680000, 116409 -CTUN, 542, 0.00, 44.38, 0.000000, 0.00, 33, 75, 465, 0 -ATT, 4.76, 4.58, -26.00, -25.40, 0.10, 23.65, 23.83 -MOT, 1442, 1551, 1478, 1480 -CTUN, 539, 0.00, 44.37, 0.000000, 0.00, 33, 69, 461, 0 -ATT, 4.10, 4.66, -26.08, -25.45, 0.00, 23.93, 23.83 -MOT, 1419, 1558, 1442, 1510 -GPS, 3, 109263600, 1774, 9, 2.43, -39.4924877, 176.7490537, 44.88, 87.67, 5.95, 9.33, -0.630000, 116609 -CTUN, 539, 0.00, 44.81, 0.000000, 0.00, 32, 65, 460, 0 -ATT, 4.10, 4.44, -26.08, -25.44, 0.00, 24.16, 23.83 -MOT, 1443, 1536, 1454, 1498 -CTUN, 540, 0.00, 44.77, 0.000000, 0.00, 32, 59, 461, 0 -ATT, 3.46, 3.91, -26.44, -25.39, 0.00, 24.12, 23.83 -MOT, 1465, 1528, 1458, 1485 -GPS, 3, 109263800, 1774, 9, 2.43, -39.4924771, 176.7490567, 44.99, 87.79, 6.01, 10.61, -0.600000, 116810 -CTUN, 539, 0.00, 44.72, 0.000000, 0.00, 33, 50, 461, 0 -ATT, 3.46, 3.54, -26.95, -25.64, 0.00, 23.95, 23.83 -MOT, 1458, 1534, 1433, 1511 -CTUN, 542, 0.00, 44.56, 0.000000, 0.00, 34, 45, 466, 0 -ATT, 3.39, 3.32, -26.88, -26.12, 0.10, 23.80, 23.83 -MOT, 1457, 1550, 1448, 1502 -DU32, 7, 270713 -CURR, 462, 182930, 1542, 3131, 4897, 310.9405 -GPS, 3, 109264000, 1774, 9, 2.43, -39.4924666, 176.7490601, 45.05, 87.87, 6.02, 12.43, -0.490000, 117010 -CTUN, 540, 0.00, 45.02, 0.000000, 0.00, 34, 43, 463, 0 -ATT, 3.46, 3.32, -26.88, -26.18, 0.00, 23.68, 23.83 -MOT, 1466, 1534, 1432, 1512 -CTUN, 539, 0.00, 45.18, 0.000000, 0.00, 34, 38, 462, 0 -ATT, 3.46, 3.51, -26.88, -26.03, 0.00, 23.63, 23.83 -MOT, 1450, 1544, 1433, 1511 -GPS, 3, 109264200, 1774, 9, 2.43, -39.4924558, 176.7490635, 45.13, 87.98, 6.12, 13.32, -0.430000, 117210 -CTUN, 542, 0.00, 44.45, 0.000000, 0.00, 33, 40, 465, 0 -ATT, 3.46, 3.68, -26.29, -25.57, 0.00, 23.79, 23.83 -MOT, 1438, 1556, 1469, 1488 -CTUN, 542, 0.00, 44.72, 0.000000, 0.00, 32, 44, 464, 0 -ATT, 3.46, 3.38, -26.22, -25.26, 0.00, 23.98, 23.83 -MOT, 1461, 1528, 1451, 1510 -GPS, 3, 109264400, 1774, 9, 2.43, -39.4924451, 176.7490670, 45.16, 88.06, 6.12, 13.83, -0.310000, 117410 -CTUN, 542, 0.00, 44.69, 0.000000, 0.00, 31, 47, 463, 0 -ATT, 4.10, 3.39, -27.09, -24.59, 0.00, 24.14, 23.83 -MOT, 1424, 1560, 1423, 1528 -CTUN, 542, 0.00, 45.14, 0.000000, 0.00, 30, 50, 462, 0 -ATT, 4.54, 3.63, -27.82, -24.38, 0.00, 24.15, 23.83 -MOT, 1436, 1556, 1441, 1500 -GPS, 3, 109264600, 1774, 9, 2.43, -39.4924343, 176.7490708, 45.23, 88.16, 6.17, 14.59, -0.330000, 117611 -CTUN, 542, 0.00, 45.33, 0.000000, 0.00, 30, 54, 462, 0 -ATT, 4.32, 4.10, -27.53, -24.35, 0.00, 24.07, 23.83 -MOT, 1456, 1531, 1452, 1502 -CTUN, 542, 0.00, 44.76, 0.000000, 0.00, 29, 56, 461, 0 -ATT, 4.32, 4.08, -27.75, -24.10, 0.00, 24.12, 23.83 -MOT, 1439, 1549, 1448, 1496 -GPS, 3, 109264800, 1774, 9, 2.43, -39.4924237, 176.7490749, 45.33, 88.24, 6.18, 15.65, -0.380000, 117811 -CTUN, 542, 0.00, 44.95, 0.000000, 0.00, 30, 58, 462, 0 -ATT, 4.10, 4.07, -27.82, -24.33, 0.00, 24.03, 23.83 -MOT, 1468, 1533, 1433, 1506 -CTUN, 542, 0.00, 45.24, 0.000000, 0.00, 31, 54, 463, 0 -ATT, 4.32, 4.08, -27.82, -24.64, 0.00, 23.96, 23.83 -MOT, 1437, 1552, 1450, 1500 -DU32, 7, 270713 -CURR, 463, 187551, 1558, 3122, 4876, 319.6703 -GPS, 3, 109265000, 1774, 9, 2.43, -39.4924130, 176.7490793, 45.42, 88.38, 6.18, 16.76, -0.450000, 118011 -CTUN, 542, 0.00, 45.11, 0.000000, 0.00, 31, 53, 463, 0 -ATT, 4.32, 3.95, -27.53, -24.83, 0.00, 23.97, 23.83 -MOT, 1441, 1547, 1443, 1509 -CTUN, 542, 0.00, 44.96, 0.000000, 0.00, 33, 47, 465, 0 -ATT, 4.54, 3.97, -27.75, -25.49, 0.00, 24.05, 23.83 -MOT, 1453, 1543, 1459, 1499 -GPS, 3, 109265200, 1774, 9, 2.43, -39.4924024, 176.7490838, 45.48, 88.52, 6.16, 17.51, -0.470000, 118212 -CTUN, 542, 0.00, 45.25, 0.000000, 0.00, 35, 34, 467, 0 -ATT, 4.76, 4.05, -27.75, -26.20, 0.00, 24.10, 23.83 -MOT, 1488, 1517, 1453, 1510 -CTUN, 542, 0.00, 45.10, 0.000000, 0.00, 38, 19, 470, 0 -ATT, 4.76, 4.34, -27.82, -27.17, 0.00, 24.01, 23.83 -MOT, 1456, 1554, 1439, 1523 -GPS, 3, 109265400, 1774, 9, 2.43, -39.4923919, 176.7490885, 45.49, 88.59, 6.22, 18.21, -0.390000, 118411 -CTUN, 542, 0.00, 45.02, 0.000000, 0.00, 40, 8, 472, 0 -ATT, 4.97, 4.50, -27.82, -27.80, 0.00, 23.84, 23.83 -MOT, 1493, 1526, 1459, 1510 -CTUN, 543, 0.00, 45.10, 0.000000, 0.00, 41, -4, 474, 0 -ATT, 4.97, 4.75, -27.96, -27.99, 0.00, 23.69, 23.83 -MOT, 1444, 1574, 1442, 1522 -GPS, 3, 109265600, 1774, 9, 2.43, -39.4923812, 176.7490931, 45.44, 88.65, 6.21, 18.56, -0.180000, 118612 -CTUN, 542, 0.00, 44.96, 0.000000, 0.00, 40, -8, 472, 0 -ATT, 3.89, 4.70, -27.82, -27.77, 0.00, 23.77, 23.83 -MOT, 1494, 1521, 1455, 1518 -CTUN, 542, 0.00, 45.47, 0.000000, 0.00, 39, -10, 471, 0 -ATT, 3.24, 4.06, -27.75, -27.39, 0.00, 23.90, 23.83 -MOT, 1443, 1560, 1451, 1520 -GPS, 3, 109265800, 1774, 9, 2.43, -39.4923704, 176.7490979, 45.39, 88.67, 6.29, 18.84, 0.000000, 118812 -CTUN, 542, 0.00, 45.47, 0.000000, 0.00, 36, -10, 468, 0 -ATT, 3.24, 3.81, -27.75, -26.64, 0.00, 24.01, 23.83 -MOT, 1450, 1550, 1468, 1497 -CTUN, 542, 0.00, 45.51, 0.000000, 0.00, 35, -8, 467, 0 -ATT, 3.46, 3.81, -28.03, -26.35, 0.00, 24.06, 23.83 -MOT, 1474, 1528, 1460, 1504 -DU32, 7, 270713 -CURR, 468, 192237, 1576, 3266, 4984, 328.5627 -GPS, 3, 109266000, 1774, 9, 2.43, -39.4923594, 176.7491030, 45.38, 88.67, 6.48, 19.37, 0.070000, 119013 -CTUN, 542, 0.00, 45.19, 0.000000, 0.00, 35, -12, 467, 0 -ATT, 3.46, 3.69, -28.03, -26.41, 0.00, 23.94, 23.83 -MOT, 1440, 1563, 1443, 1511 -CTUN, 542, 0.00, 45.18, 0.000000, 0.00, 36, -12, 468, 0 -ATT, 3.46, 3.80, -27.96, -26.46, 0.00, 23.84, 23.83 -MOT, 1456, 1550, 1461, 1497 -GPS, 3, 109266200, 1774, 9, 2.43, -39.4923484, 176.7491084, 45.33, 88.67, 6.54, 20.06, 0.080000, 119213 -CTUN, 542, 0.00, 44.98, 0.000000, 0.00, 35, -16, 467, 0 -ATT, 3.39, 3.67, -27.75, -26.14, 0.10, 23.83, 23.83 -MOT, 1431, 1569, 1450, 1506 -CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 35, -22, 467, 0 -ATT, 3.24, 3.29, -27.82, -26.34, 0.00, 23.86, 23.83 -MOT, 1452, 1547, 1404, 1551 -GPS, 3, 109266400, 1774, 9, 2.43, -39.4923372, 176.7491139, 45.26, 88.66, 6.64, 20.45, 0.120000, 119413 -CTUN, 542, 0.00, 45.23, 0.000000, 0.00, 34, -22, 466, 0 -ATT, 3.17, 3.15, -27.75, -25.91, 0.00, 24.09, 23.83 -MOT, 1484, 1510, 1486, 1482 -CTUN, 542, 0.00, 44.89, 0.000000, 0.00, 34, -27, 466, 0 -ATT, 3.17, 2.86, -27.53, -26.15, 0.00, 24.14, 23.83 -MOT, 1442, 1550, 1444, 1520 -GPS, 3, 109266600, 1774, 9, 2.43, -39.4923258, 176.7491194, 45.19, 88.65, 6.75, 20.59, 0.150000, 119613 -CTUN, 542, 0.00, 44.98, 0.000000, 0.00, 35, -31, 467, 0 -ATT, 3.24, 2.92, -27.60, -26.45, 0.20, 24.20, 23.83 -MOT, 1458, 1541, 1462, 1502 -CTUN, 542, 0.00, 44.85, 0.000000, 0.00, 36, -35, 468, 0 -ATT, 2.95, 2.87, -27.31, -26.58, 0.00, 24.23, 23.83 -MOT, 1445, 1550, 1455, 1514 -GPS, 3, 109266800, 1774, 9, 2.43, -39.4923143, 176.7491251, 45.08, 88.62, 6.83, 20.76, 0.190000, 119814 -CTUN, 542, 0.00, 44.88, 0.000000, 0.00, 35, -37, 467, 0 -ATT, 2.73, 2.41, -27.09, -26.45, 0.00, 24.23, 23.83 -MOT, 1419, 1569, 1481, 1485 -CTUN, 542, 0.00, 44.89, 0.000000, 0.00, 34, -33, 466, 0 -ATT, 1.94, 1.76, -26.44, -26.11, 0.00, 24.20, 23.83 -MOT, 1440, 1551, 1438, 1526 -DU32, 7, 270713 -CURR, 465, 196908, 1558, 3250, 4897, 337.5396 -GPS, 3, 109267000, 1774, 9, 2.43, -39.4923025, 176.7491308, 44.98, 88.60, 6.95, 20.68, 0.240000, 120014 -CTUN, 542, 0.00, 45.07, 0.000000, 0.00, 32, -29, 464, 0 -ATT, 0.57, 1.43, -26.00, -25.48, 0.00, 24.24, 23.83 -MOT, 1413, 1564, 1474, 1489 -CTUN, 542, 0.00, 45.15, 0.000000, 0.00, 31, -26, 463, 0 -ATT, 0.14, 0.70, -25.79, -24.93, 0.00, 24.21, 23.83 -MOT, 1415, 1571, 1430, 1518 -GPS, 3, 109267200, 1774, 9, 2.43, -39.4922905, 176.7491363, 44.94, 88.58, 7.04, 20.31, 0.220000, 120234 -CTUN, 542, 0.00, 45.00, 0.000000, 0.00, 28, -10, 460, 0 -ATT, 0.00, 0.03, -25.35, -23.81, 0.20, 24.12, 23.83 -MOT, 1444, 1550, 1434, 1499 -CTUN, 542, 0.00, 45.07, 0.000000, 0.00, 26, 2, 458, 0 -ATT, 0.00, -0.21, -25.13, -22.89, 0.00, 24.11, 23.83 -MOT, 1419, 1551, 1461, 1486 -GPS, 3, 109267400, 1774, 9, 2.43, -39.4922782, 176.7491419, 44.95, 88.56, 7.20, 19.83, 0.170000, 120415 -CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 24, 20, 456, 0 -ATT, 0.00, -0.63, -25.13, -22.21, 0.10, 24.16, 23.83 -MOT, 1424, 1546, 1413, 1528 -CTUN, 542, 0.00, 45.02, 0.000000, 0.00, 22, 34, 454, 0 -ATT, 0.00, -0.70, -24.92, -21.57, 0.10, 24.05, 23.83 -MOT, 1453, 1532, 1449, 1474 -GPS, 3, 109267600, 1774, 9, 2.43, -39.4922656, 176.7491472, 45.03, 88.60, 7.31, 19.02, -0.010000, 120615 -CTUN, 542, 0.00, 45.34, 0.000000, 0.00, 22, 45, 454, 0 -ATT, 0.00, -0.64, -24.78, -21.39, 0.00, 23.89, 23.83 -MOT, 1421, 1551, 1439, 1490 -CTUN, 542, 0.00, 45.13, 0.000000, 0.00, 22, 52, 454, 0 -ATT, 0.00, -0.57, -24.71, -21.50, 0.10, 23.87, 23.83 -MOT, 1415, 1558, 1418, 1509 -GPS, 3, 109267800, 1774, 9, 2.43, -39.4922529, 176.7491522, 45.16, 88.71, 7.31, 18.07, -0.240000, 120815 -CTUN, 542, 0.00, 45.28, 0.000000, 0.00, 21, 60, 453, 0 -ATT, 0.00, -0.23, -24.71, -21.19, 0.00, 23.90, 23.83 -MOT, 1434, 1537, 1439, 1492 -CTUN, 542, 0.00, 45.26, 0.000000, 0.00, 21, 63, 453, 0 -ATT, 0.00, -0.11, -24.71, -21.07, 0.10, 23.98, 23.83 -MOT, 1432, 1533, 1438, 1499 -DU32, 7, 270713 -CURR, 453, 201483, 1547, 3050, 4918, 346.1808 -GPS, 3, 109268000, 1774, 9, 2.43, -39.4922400, 176.7491568, 45.31, 88.82, 7.33, 16.88, -0.350000, 121016 -CTUN, 542, 0.00, 45.51, 0.000000, 0.00, 21, 69, 453, 0 -ATT, 0.00, -0.07, -24.71, -20.84, 0.10, 24.00, 23.83 -MOT, 1417, 1550, 1439, 1492 -CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 21, 76, 453, 0 -ATT, 0.00, 0.02, -24.71, -20.89, 0.10, 24.04, 23.83 -MOT, 1397, 1567, 1420, 1509 -GPS, 3, 109268200, 1774, 9, 2.43, -39.4922272, 176.7491610, 45.46, 88.99, 7.25, 15.56, -0.470000, 121216 -CTUN, 542, 0.00, 45.17, 0.000000, 0.00, 21, 79, 453, 0 -ATT, 0.00, 0.00, -24.49, -20.91, 0.20, 24.06, 23.83 -MOT, 1452, 1521, 1445, 1485 -CTUN, 542, 0.00, 45.58, 0.000000, 0.00, 20, 86, 452, 0 -ATT, 0.00, 0.06, -24.12, -20.54, 0.10, 24.08, 23.83 -MOT, 1416, 1547, 1410, 1521 -GPS, 3, 109268400, 1774, 9, 2.43, -39.4922143, 176.7491650, 45.63, 89.16, 7.29, 14.67, -0.610000, 121416 -CTUN, 542, 0.00, 45.63, 0.000000, 0.00, 20, 94, 452, 0 -ATT, 0.00, 0.05, -24.05, -20.45, 0.10, 24.11, 23.83 -MOT, 1420, 1539, 1451, 1486 -CTUN, 542, 0.00, 45.70, 0.000000, 0.00, 20, 100, 452, 0 -ATT, 0.00, -0.04, -24.05, -20.55, 0.20, 24.13, 23.83 -MOT, 1461, 1505, 1421, 1512 -GPS, 3, 109268600, 1774, 9, 2.43, -39.4922013, 176.7491688, 45.84, 89.36, 7.31, 13.73, -0.730000, 121616 -CTUN, 542, 0.00, 45.77, 0.000000, 0.00, 21, 105, 453, 0 -ATT, 0.00, -0.11, -24.05, -20.86, 0.10, 24.16, 23.83 -MOT, 1454, 1515, 1428, 1508 -CTUN, 544, 0.00, 45.94, 0.000000, 0.00, 21, 106, 455, 0 -ATT, 0.00, 0.06, -23.83, -21.20, 0.10, 24.22, 23.83 -MOT, 1412, 1552, 1471, 1471 -GPS, 3, 109268800, 1774, 9, 2.43, -39.4921882, 176.7491721, 46.07, 89.59, 7.29, 12.63, -0.850000, 121817 -CTUN, 550, 0.00, 46.28, 0.000000, 0.00, 23, 106, 465, 0 -ATT, 0.00, 0.22, -23.83, -21.65, 0.20, 24.13, 23.83 -MOT, 1482, 1520, 1478, 1478 -CTUN, 552, 0.00, 46.05, 0.000000, 0.00, 24, 106, 468, 0 -ATT, 0.00, 0.29, -23.83, -21.70, 0.10, 24.13, 23.83 -MOT, 1434, 1558, 1417, 1548 -DU32, 7, 270713 -CURR, 467, 206034, 1595, 3357, 4918, 354.6142 -GPS, 3, 109269000, 1774, 9, 2.43, -39.4921752, 176.7491753, 46.30, 89.80, 7.30, 11.85, -0.880000, 122016 -CTUN, 553, 0.00, 46.13, 0.000000, 0.00, 23, 113, 468, 0 -ATT, 0.00, 0.21, -23.83, -21.57, 0.20, 24.13, 23.83 -MOT, 1413, 1581, 1441, 1521 -CTUN, 558, 0.00, 46.46, 0.000000, 0.00, 23, 114, 474, 0 -ATT, 0.00, 0.13, -23.83, -21.61, 0.10, 24.01, 23.83 -MOT, 1458, 1559, 1490, 1481 -GPS, 3, 109269200, 1774, 9, 2.43, -39.4921620, 176.7491780, 46.54, 90.05, 7.28, 10.46, -0.950000, 122217 -CTUN, 561, 0.00, 46.24, 0.000000, 0.00, 24, 117, 479, 0 -ATT, 0.00, -0.41, -23.90, -21.43, 0.20, 23.98, 23.83 -MOT, 1440, 1576, 1455, 1532 -CTUN, 561, 0.00, 46.74, 0.000000, 0.00, 24, 124, 479, 0 -ATT, 0.00, -0.51, -24.05, -21.43, 0.10, 23.99, 23.83 -MOT, 1443, 1570, 1444, 1543 -GPS, 3, 109269400, 1774, 9, 2.43, -39.4921488, 176.7491805, 46.79, 90.29, 7.37, 9.49, -1.020000, 122417 -CTUN, 561, 0.00, 47.16, 0.000000, 0.00, 23, 138, 478, 0 -ATT, 0.00, -0.34, -24.05, -20.96, 0.10, 24.01, 23.83 -MOT, 1441, 1572, 1494, 1494 -CTUN, 563, 0.00, 47.01, 0.000000, 0.00, 23, 147, 481, 0 -ATT, 0.00, -0.27, -24.27, -20.79, 0.20, 24.04, 23.83 -MOT, 1427, 1590, 1468, 1524 -GPS, 3, 109269600, 1774, 9, 2.43, -39.4921353, 176.7491829, 47.13, 90.56, 7.46, 8.68, -1.130000, 122618 -CTUN, 571, 0.00, 47.05, 0.000000, 0.00, 23, 159, 491, 0 -ATT, 0.00, -0.40, -24.27, -20.86, 0.10, 24.03, 23.83 -MOT, 1474, 1566, 1451, 1558 -CTUN, 571, 0.00, 46.79, 0.000000, 0.00, 22, 173, 490, 0 -ATT, 0.00, -0.39, -24.27, -20.29, 0.20, 23.98, 23.83 -MOT, 1463, 1574, 1494, 1519 -GPS, 3, 109269800, 1774, 9, 2.43, -39.4921219, 176.7491851, 47.47, 90.86, 7.47, 8.03, -1.310000, 122818 -CTUN, 571, 0.00, 47.46, 0.000000, 0.00, 22, 188, 490, 0 -ATT, 0.00, -0.08, -24.78, -20.45, 0.00, 24.06, 23.83 -MOT, 1465, 1569, 1494, 1523 -CTUN, 571, 0.00, 47.80, 0.000000, 0.00, 24, 186, 492, 0 -ATT, 0.00, 0.24, -24.49, -21.45, 0.10, 24.13, 23.83 -MOT, 1425, 1605, 1473, 1542 -DU32, 7, 270713 -CURR, 493, 210838, 1552, 3677, 4940, 364.2424 -GPS, 3, 109270000, 1774, 9, 2.43, -39.4921083, 176.7491870, 47.87, 91.22, 7.51, 7.19, -1.520000, 123018 -CTUN, 571, 0.00, 47.63, 0.000000, 0.00, 25, 185, 493, 0 -ATT, 0.00, -0.01, -24.49, -21.58, 0.00, 24.09, 23.83 -MOT, 1512, 1545, 1484, 1530 -CTUN, 571, 0.00, 48.25, 0.000000, 0.00, 26, 188, 494, 0 -ATT, 0.00, 0.20, -24.71, -21.94, 0.10, 23.86, 23.83 -MOT, 1458, 1593, 1462, 1544 -GPS, 3, 109270200, 1774, 9, 2.43, -39.4920949, 176.7491887, 48.27, 91.57, 7.45, 6.35, -1.640000, 123218 -CTUN, 571, 0.00, 48.51, 0.000000, 0.00, 26, 189, 494, 0 -ATT, 0.00, 0.46, -24.27, -22.18, 0.00, 23.69, 23.83 -MOT, 1474, 1584, 1478, 1528 -CTUN, 568, 0.00, 48.76, 0.000000, 0.00, 25, 196, 489, 0 -ATT, 0.00, 0.02, -23.83, -21.51, 0.00, 23.55, 23.83 -MOT, 1475, 1575, 1478, 1518 -GPS, 3, 109270400, 1774, 9, 2.43, -39.4920815, 176.7491902, 48.71, 91.95, 7.33, 5.71, -1.600000, 123419 -CTUN, 568, 0.00, 48.67, 0.000000, 0.00, 23, 209, 487, 0 -ATT, 0.00, 0.17, -24.12, -20.88, 0.20, 23.52, 23.83 -MOT, 1451, 1581, 1469, 1534 -CTUN, 568, 0.00, 48.70, 0.000000, 0.00, 22, 221, 486, 0 -ATT, 0.00, 0.07, -23.83, -20.12, 0.00, 23.68, 23.83 -MOT, 1475, 1559, 1446, 1551 -GPS, 3, 109270600, 1774, 9, 2.43, -39.4920682, 176.7491915, 49.17, 92.37, 7.30, 5.11, -1.710000, 123619 -CTUN, 568, 0.00, 49.59, 0.000000, 0.00, 19, 237, 483, 0 -ATT, 0.00, 0.26, -24.05, -19.21, 0.10, 23.82, 23.83 -MOT, 1480, 1550, 1471, 1528 -CTUN, 568, 0.00, 49.23, 0.000000, 0.00, 19, 254, 483, 0 -ATT, 0.00, 0.22, -24.05, -18.75, 0.00, 23.98, 23.83 -MOT, 1430, 1586, 1433, 1560 -GPS, 3, 109270800, 1774, 9, 2.43, -39.4920549, 176.7491926, 49.72, 92.84, 7.26, 4.48, -1.920000, 123820 -CTUN, 568, 0.00, 49.49, 0.000000, 0.00, 17, 269, 481, 0 -ATT, 0.00, 0.12, -24.49, -18.38, 0.00, 24.05, 23.83 -MOT, 1466, 1559, 1462, 1529 -CTUN, 569, 0.00, 50.03, 0.000000, 0.00, 18, 274, 483, 0 -ATT, 0.00, 0.38, -24.92, -18.69, 0.00, 24.11, 23.83 -MOT, 1470, 1556, 1474, 1526 -DU32, 7, 270713 -CURR, 484, 215710, 1495, 3305, 4897, 373.9483 -PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 -GPS, 3, 109271000, 1774, 9, 2.43, -39.4920420, 176.7491935, 50.29, 93.36, 7.13, 3.90, -2.240000, 124020 -CTUN, 568, 0.00, 50.38, 0.000000, 0.00, 19, 279, 483, 0 -ATT, 0.00, 0.48, -24.34, -19.46, 0.00, 24.08, 23.83 -MOT, 1505, 1530, 1486, 1512 -CTUN, 569, 0.00, 50.47, 0.000000, 0.00, 21, 279, 486, 0 -ATT, 0.00, 0.54, -24.92, -20.34, 0.00, 23.95, 23.83 -MOT, 1481, 1562, 1454, 1537 -GPS, 3, 109271200, 1774, 9, 2.43, -39.4920292, 176.7491943, 50.89, 93.90, 7.02, 3.38, -2.430000, 124220 -CTUN, 568, 0.00, 50.71, 0.000000, 0.00, 24, 271, 488, 0 -ATT, 0.00, 0.66, -26.95, -21.78, 0.00, 23.78, 23.83 -MOT, 1486, 1563, 1491, 1505 -CTUN, 569, 0.00, 50.72, 0.000000, 0.00, 29, 263, 494, 0 -ATT, 0.00, 0.60, -27.96, -23.57, 0.00, 23.60, 23.83 -MOT, 1501, 1563, 1481, 1525 -GPS, 3, 109271400, 1774, 9, 2.43, -39.4920167, 176.7491950, 51.42, 94.45, 6.87, 2.81, -2.480000, 124421 -CTUN, 569, 0.00, 51.08, 0.000000, 0.00, 34, 252, 499, 0 -ATT, 0.00, 0.28, -25.13, -25.35, 0.10, 23.38, 23.83 -MOT, 1553, 1528, 1548, 1459 -CTUN, 568, 0.00, 51.22, 0.000000, 0.00, 35, 248, 499, 0 -ATT, 0.00, 0.18, -21.22, -25.12, 0.00, 23.26, 23.83 -MOT, 1488, 1583, 1489, 1526 -GPS, 3, 109271600, 1774, 9, 2.43, -39.4920041, 176.7491956, 51.91, 94.94, 6.92, 2.55, -2.370000, 124621 -CTUN, 569, 0.00, 51.33, 0.000000, 0.00, 32, 246, 497, 0 -ATT, 0.00, -0.15, -21.00, -24.00, 0.20, 23.13, 23.83 -MOT, 1534, 1549, 1464, 1536 -CTUN, 568, 0.00, 51.82, 0.000000, 0.00, 28, 240, 492, 0 -ATT, 0.00, -0.06, -22.09, -22.74, 0.00, 23.10, 23.83 -MOT, 1472, 1586, 1485, 1513 -GPS, 3, 109271800, 1774, 9, 2.43, -39.4919916, 176.7491961, 52.37, 95.44, 6.91, 2.11, -2.320000, 124821 -CTUN, 569, 0.00, 52.34, 0.000000, 0.00, 26, 240, 491, 0 -ATT, 0.00, 0.04, -21.66, -21.79, 0.10, 23.00, 23.83 -MOT, 1520, 1548, 1472, 1522 -CTUN, 568, 0.00, 52.29, 0.000000, 0.00, 24, 247, 488, 0 -ATT, 0.00, -0.05, -22.53, -21.00, 0.00, 23.14, 23.83 -MOT, 1476, 1566, 1462, 1537 -DU32, 7, 270713 -CURR, 486, 220625, 1544, 3491, 4940, 383.6895 -GPS, 3, 109272000, 1774, 9, 2.43, -39.4919788, 176.7491965, 52.94, 95.89, 7.09, 1.77, -2.280000, 125041 -CTUN, 569, 0.00, 52.41, 0.000000, 0.00, 22, 258, 487, 0 -ATT, 0.00, 0.05, -22.53, -20.18, 0.00, 23.41, 23.83 -MOT, 1461, 1573, 1470, 1533 -CTUN, 568, 0.00, 53.04, 0.000000, 0.00, 20, 269, 484, 0 -ATT, 0.00, 0.16, -22.75, -19.60, 0.00, 23.54, 23.83 -MOT, 1499, 1541, 1463, 1530 -GPS, 3, 109272200, 1774, 9, 2.43, -39.4919661, 176.7491968, 53.42, 96.40, 6.98, 1.41, -2.340000, 125222 -CTUN, 568, 0.00, 53.34, 0.000000, 0.00, 20, 276, 484, 0 -ATT, 0.00, 0.31, -22.75, -19.53, 0.00, 23.58, 23.83 -MOT, 1477, 1564, 1453, 1533 -CTUN, 569, 0.00, 53.55, 0.000000, 0.00, 20, 276, 485, 0 -ATT, 0.00, 0.62, -22.75, -19.49, 0.00, 23.62, 23.83 -MOT, 1459, 1576, 1469, 1525 -GPS, 3, 109272400, 1774, 9, 2.43, -39.4919535, 176.7491972, 54.00, 96.94, 6.94, 1.35, -2.460000, 125422 -CTUN, 568, 0.00, 53.79, 0.000000, 0.00, 20, 275, 484, 0 -ATT, 0.00, 0.59, -22.75, -19.70, 0.10, 23.63, 23.83 -MOT, 1483, 1552, 1465, 1530 -CTUN, 568, 0.00, 53.99, 0.000000, 0.00, 21, 277, 485, 0 -ATT, 0.00, 0.53, -22.75, -19.96, 0.00, 23.66, 23.83 -MOT, 1472, 1569, 1469, 1521 -GPS, 3, 109272600, 1774, 9, 2.43, -39.4919414, 176.7491974, 54.57, 97.47, 6.73, 1.02, -2.520000, 125622 -CTUN, 569, 0.00, 54.04, 0.000000, 0.00, 22, 276, 487, 0 -ATT, 0.00, 0.56, -22.75, -20.39, 0.00, 23.61, 23.83 -MOT, 1473, 1575, 1478, 1512 -CTUN, 568, 0.00, 54.57, 0.000000, 0.00, 23, 269, 487, 0 -ATT, 0.00, 0.12, -22.75, -20.74, 0.00, 23.62, 23.83 -MOT, 1432, 1596, 1465, 1537 -GPS, 3, 109272800, 1774, 9, 2.43, -39.4919294, 176.7491975, 55.11, 98.01, 6.59, 0.68, -2.520000, 125822 -CTUN, 569, 0.00, 54.70, 0.000000, 0.00, 22, 272, 487, 0 -ATT, 0.00, -0.12, -22.75, -20.47, 0.10, 23.71, 23.83 -MOT, 1475, 1562, 1469, 1534 -CTUN, 569, 0.00, 55.02, 0.000000, 0.00, 21, 280, 486, 0 -ATT, 0.00, -0.17, -22.75, -19.98, 0.00, 23.70, 23.83 -MOT, 1489, 1551, 1446, 1548 -DU32, 7, 270713 -CURR, 486, 225480, 1570, 3487, 4876, 393.2772 -GPS, 3, 109273000, 1774, 9, 2.43, -39.4919178, 176.7491974, 55.66, 98.52, 6.41, 0.20, -2.480000, 126023 -CTUN, 568, 0.00, 55.13, 0.000000, 0.00, 20, 292, 484, 0 -ATT, 0.00, 0.08, -22.96, -19.78, 0.00, 23.67, 23.83 -MOT, 1479, 1557, 1458, 1534 -CTUN, 569, 0.00, 55.30, 0.000000, 0.00, 21, 294, 486, 0 -ATT, 0.00, 0.18, -23.40, -20.19, 0.00, 23.65, 23.83 -MOT, 1461, 1578, 1472, 1522 -GPS, 3, 109273200, 1774, 9, 2.43, -39.4919063, 176.7491973, 56.22, 99.07, 6.36, 359.91, -2.580000, 126223 -CTUN, 569, 0.00, 56.00, 0.000000, 0.00, 22, 289, 487, 0 -ATT, 0.00, 0.07, -24.27, -20.64, 0.00, 23.67, 23.83 -MOT, 1489, 1551, 1471, 1532 -CTUN, 568, 0.00, 56.04, 0.000000, 0.00, 24, 288, 488, 0 -ATT, 0.00, 0.11, -24.49, -21.33, 0.00, 23.72, 23.83 -MOT, 1509, 1539, 1480, 1524 -GPS, 3, 109273400, 1774, 9, 2.43, -39.4918948, 176.7491971, 56.80, 99.63, 6.36, 359.51, -2.700000, 126423 -CTUN, 568, 0.00, 56.46, 0.000000, 0.00, 26, 284, 490, 0 -ATT, 0.00, 0.28, -24.71, -22.38, 0.00, 23.74, 23.83 -MOT, 1472, 1574, 1465, 1537 -CTUN, 568, 0.00, 56.91, 0.000000, 0.00, 28, 274, 492, 0 -ATT, 0.00, 0.05, -24.92, -23.15, 0.00, 23.73, 23.83 -MOT, 1473, 1578, 1474, 1532 -GPS, 3, 109273600, 1774, 9, 2.43, -39.4918835, 176.7491967, 57.36, 100.20, 6.26, 359.03, -2.720000, 126623 -CTUN, 568, 0.00, 57.38, 0.000000, 0.00, 29, 267, 493, 0 -ATT, 0.00, -0.21, -24.92, -23.60, 0.20, 23.55, 23.83 -MOT, 1490, 1578, 1504, 1490 -CTUN, 568, 0.00, 57.26, 0.000000, 0.00, 31, 261, 495, 0 -ATT, 0.00, -0.39, -24.92, -23.92, 0.00, 23.39, 23.83 -MOT, 1486, 1578, 1468, 1537 -GPS, 3, 109273800, 1774, 9, 2.43, -39.4918724, 176.7491961, 57.91, 100.73, 6.19, 358.47, -2.610000, 126824 -CTUN, 568, 0.00, 57.63, 0.000000, 0.00, 32, 260, 496, 0 -ATT, 0.00, -0.13, -25.13, -24.26, 0.10, 23.28, 23.83 -MOT, 1465, 1597, 1442, 1556 -CTUN, 568, 0.00, 58.32, 0.000000, 0.00, 32, 257, 496, 0 -ATT, 0.00, 0.05, -25.13, -24.22, 0.20, 23.25, 23.83 -MOT, 1496, 1573, 1481, 1525 -DU32, 7, 270713 -CURR, 496, 230388, 1537, 3598, 4918, 403.0589 -GPS, 3, 109274000, 1774, 9, 2.43, -39.4918613, 176.7491953, 58.45, 101.24, 6.15, 357.74, -2.500000, 127024 -CTUN, 569, 0.00, 58.26, 0.000000, 0.00, 32, 251, 497, 0 -ATT, 0.00, 0.02, -25.13, -24.33, 0.00, 23.25, 23.83 -MOT, 1464, 1600, 1490, 1519 -CTUN, 569, 0.00, 58.45, 0.000000, 0.00, 33, 246, 498, 0 -ATT, 0.00, 0.02, -24.92, -24.70, 0.00, 23.19, 23.83 -MOT, 1461, 1602, 1474, 1537 -GPS, 3, 109274200, 1774, 9, 2.43, -39.4918501, 176.7491945, 58.96, 101.75, 6.18, 357.28, -2.430000, 127224 -CTUN, 569, 0.00, 58.65, 0.000000, 0.00, 32, 243, 497, 0 -ATT, 0.00, -0.08, -25.13, -24.32, 0.00, 23.26, 23.83 -MOT, 1479, 1583, 1475, 1537 -CTUN, 568, 0.00, 58.93, 0.000000, 0.00, 32, 249, 496, 0 -ATT, 0.00, 0.03, -25.79, -24.35, 0.00, 23.30, 23.83 -MOT, 1473, 1592, 1474, 1532 -GPS, 3, 109274400, 1774, 9, 2.43, -39.4918388, 176.7491937, 59.45, 102.24, 6.23, 357.08, -2.350000, 127425 -CTUN, 568, 0.00, 59.15, 0.000000, 0.00, 33, 245, 497, 0 -ATT, 0.00, 0.19, -25.79, -24.71, 0.20, 23.36, 23.83 -MOT, 1437, 1621, 1432, 1566 -CTUN, 569, 0.00, 58.98, 0.000000, 0.00, 33, 244, 498, 0 -ATT, 0.00, 0.29, -28.69, -24.81, 0.00, 23.23, 23.83 -MOT, 1486, 1591, 1504, 1498 -GPS, 3, 109274600, 1774, 9, 2.43, -39.4918275, 176.7491929, 59.92, 102.73, 6.27, 357.01, -2.330000, 127625 -CTUN, 568, 0.00, 59.77, 0.000000, 0.00, 37, 235, 501, 0 -ATT, 0.00, 0.40, -28.69, -26.14, 0.00, 23.08, 23.83 -MOT, 1470, 1607, 1482, 1532 -CTUN, 568, 0.00, 59.72, 0.000000, 0.00, 40, 225, 504, 0 -ATT, 0.00, 0.38, -28.03, -27.12, 0.00, 22.99, 23.83 -MOT, 1518, 1578, 1500, 1517 -GPS, 3, 109274800, 1774, 9, 2.43, -39.4918161, 176.7491922, 60.37, 103.18, 6.37, 357.08, -2.270000, 127825 -CTUN, 568, 0.00, 59.97, 0.000000, 0.00, 42, 212, 506, 0 -ATT, 0.00, 0.49, -28.03, -27.21, 0.00, 22.88, 23.83 -MOT, 1493, 1601, 1432, 1576 -CTUN, 569, 0.00, 59.81, 0.000000, 0.00, 40, 209, 505, 0 -ATT, 0.00, 0.92, -28.03, -26.89, 0.00, 22.77, 23.83 -MOT, 1469, 1616, 1512, 1510 -DU32, 7, 270713 -CURR, 504, 235382, 1516, 3698, 4962, 413.1130 -GPS, 3, 109275000, 1774, 9, 2.43, -39.4918045, 176.7491915, 60.76, 103.62, 6.41, 357.22, -2.140000, 128026 -CTUN, 568, 0.00, 60.23, 0.000000, 0.00, 40, 212, 504, 0 -ATT, 0.00, 0.97, -29.05, -26.92, 0.00, 22.63, 23.83 -MOT, 1531, 1572, 1469, 1539 -CTUN, 568, 0.00, 60.35, 0.000000, 0.00, 41, 211, 505, 0 -ATT, 0.00, 1.05, -28.91, -27.03, 0.00, 22.57, 23.83 -MOT, 1512, 1589, 1453, 1553 -GPS, 3, 109275200, 1774, 9, 2.43, -39.4917927, 176.7491912, 61.14, 104.01, 6.55, 357.96, -2.020000, 128226 -CTUN, 568, 0.00, 60.98, 0.000000, 0.00, 40, 212, 504, 0 -ATT, 0.00, 1.33, -28.62, -26.97, 0.00, 22.52, 23.83 -MOT, 1506, 1590, 1499, 1514 -CTUN, 569, 0.00, 60.88, 0.000000, 0.00, 40, 217, 505, 0 -ATT, 0.00, 1.26, -28.62, -26.84, 0.00, 22.57, 23.83 -MOT, 1514, 1584, 1496, 1521 -GPS, 3, 109275400, 1774, 9, 2.43, -39.4917807, 176.7491914, 61.57, 104.42, 6.68, 359.23, -2.030000, 128426 -CTUN, 568, 0.00, 61.15, 0.000000, 0.00, 41, 219, 505, 0 -ATT, 0.00, 1.00, -26.88, -27.02, 0.20, 22.64, 23.83 -MOT, 1495, 1597, 1444, 1564 -CTUN, 568, 0.00, 61.66, 0.000000, 0.00, 38, 220, 502, 0 -ATT, 0.00, 0.98, -25.57, -26.11, 0.00, 22.76, 23.83 -MOT, 1495, 1589, 1486, 1530 -GPS, 3, 109275600, 1774, 9, 2.43, -39.4917684, 176.7491919, 62.00, 104.84, 6.83, 0.70, -2.060000, 128626 -CTUN, 569, 0.00, 61.47, 0.000000, 0.00, 35, 221, 500, 0 -ATT, 0.86, 0.83, -25.13, -25.10, 0.10, 22.93, 23.83 -MOT, 1481, 1590, 1498, 1523 -CTUN, 569, 0.00, 62.01, 0.000000, 0.00, 32, 225, 497, 0 -ATT, 2.38, 0.80, -25.13, -24.00, 0.00, 23.07, 23.83 -MOT, 1505, 1568, 1441, 1559 -GPS, 3, 109275800, 1774, 9, 2.43, -39.4917559, 176.7491928, 62.44, 105.26, 6.94, 1.96, -2.060000, 128827 -CTUN, 569, 0.00, 61.77, 0.000000, 0.00, 30, 235, 495, 0 -ATT, 1.65, 1.51, -27.53, -23.32, 0.10, 23.24, 23.83 -MOT, 1443, 1610, 1474, 1533 -CTUN, 568, 0.00, 62.56, 0.000000, 0.00, 30, 240, 494, 0 -ATT, 2.38, 1.84, -28.40, -23.80, 0.10, 23.32, 23.83 -MOT, 1443, 1611, 1463, 1537 -GPS, 3, 109276000, 1774, 9, 2.43, -39.4917433, 176.7491939, 62.86, 105.70, 7.01, 2.91, -2.140000, 129007 -DU32, 7, 270713 -CURR, 496, 240398, 1538, 3602, 4940, 423.3008 -CTUN, 568, 0.00, 62.43, 0.000000, 0.00, 31, 247, 495, 0 -ATT, 3.02, 2.06, -28.84, -24.13, 0.00, 23.55, 23.83 -MOT, 1463, 1592, 1480, 1530 -CTUN, 569, 0.00, 62.49, 0.000000, 0.00, 33, 249, 498, 0 -ATT, 4.25, 2.54, -28.62, -24.59, 0.10, 23.70, 23.83 -MOT, 1484, 1579, 1505, 1514 -GPS, 3, 109276200, 1774, 9, 2.43, -39.4917306, 176.7491952, 63.38, 106.17, 7.05, 3.62, -2.210000, 129227 -CTUN, 568, 0.00, 63.33, 0.000000, 0.00, 35, 247, 499, 0 -ATT, 4.25, 3.27, -27.75, -25.08, 0.10, 23.76, 23.83 -MOT, 1506, 1565, 1505, 1514 -CTUN, 568, 0.00, 63.70, 0.000000, 0.00, 36, 243, 500, 0 -ATT, 4.32, 3.72, -27.16, -25.40, 0.00, 23.69, 23.83 -MOT, 1494, 1580, 1479, 1539 -GPS, 3, 109276400, 1774, 9, 2.43, -39.4917180, 176.7491967, 63.90, 106.65, 7.01, 4.57, -2.270000, 129428 -CTUN, 568, 0.00, 63.72, 0.000000, 0.00, 36, 237, 500, 0 -ATT, 4.54, 4.03, -26.22, -25.45, 0.00, 23.61, 23.83 -MOT, 1482, 1587, 1482, 1538 -CTUN, 568, 0.00, 64.07, 0.000000, 0.00, 35, 235, 499, 0 -ATT, 4.47, 4.19, -26.00, -24.94, 0.00, 23.55, 23.83 -MOT, 1485, 1585, 1492, 1523 -GPS, 3, 109276600, 1774, 9, 2.43, -39.4917053, 176.7491985, 64.40, 107.13, 7.02, 5.49, -2.250000, 129628 -CTUN, 568, 0.00, 64.23, 0.000000, 0.00, 34, 239, 498, 0 -ATT, 3.81, 4.28, -27.53, -24.45, 0.00, 23.62, 23.83 -MOT, 1480, 1589, 1468, 1540 -CTUN, 568, 0.00, 65.16, 0.000000, 0.00, 33, 241, 497, 0 -ATT, 3.89, 4.37, -28.62, -24.53, 0.00, 23.66, 23.83 -MOT, 1508, 1566, 1454, 1549 -GPS, 3, 109276800, 1774, 9, 2.43, -39.4916928, 176.7492006, 64.93, 107.60, 6.96, 6.42, -2.200000, 129828 -CTUN, 568, 0.00, 64.32, 0.000000, 0.00, 35, 240, 499, 0 -ATT, 4.32, 4.01, -28.91, -25.04, 0.00, 23.74, 23.83 -MOT, 1482, 1587, 1482, 1532 -CTUN, 568, 0.00, 64.82, 0.000000, 0.00, 36, 234, 500, 0 -ATT, 4.32, 4.05, -30.13, -25.58, 0.00, 23.76, 23.83 -MOT, 1528, 1550, 1499, 1526 -DU32, 7, 270713 -CURR, 503, 245383, 1568, 3634, 4897, 433.3951 -GPS, 3, 109277000, 1774, 9, 2.43, -39.4916806, 176.7492030, 65.38, 108.05, 6.84, 7.44, -2.210000, 130028 -CTUN, 568, 0.00, 65.42, 0.000000, 0.00, 40, 228, 504, 0 -ATT, 3.46, 4.07, -29.99, -26.71, 0.10, 23.80, 23.83 -MOT, 1517, 1565, 1460, 1564 -CTUN, 568, 0.00, 65.67, 0.000000, 0.00, 42, 220, 506, 0 -ATT, 2.95, 3.93, -30.21, -27.35, 0.00, 23.87, 23.83 -MOT, 1493, 1587, 1515, 1523 -GPS, 3, 109277200, 1774, 9, 2.43, -39.4916683, 176.7492055, 65.86, 108.51, 6.82, 8.35, -2.130000, 130229 -CTUN, 569, 0.00, 65.51, 0.000000, 0.00, 44, 209, 509, 0 -ATT, 2.80, 3.36, -29.78, -27.91, 0.00, 23.78, 23.83 -MOT, 1514, 1576, 1497, 1543 -CTUN, 568, 0.00, 66.07, 0.000000, 0.00, 45, 202, 509, 0 -ATT, 2.38, 3.04, -29.78, -28.27, 0.00, 23.74, 23.83 -MOT, 1510, 1581, 1486, 1550 -GPS, 3, 109277400, 1774, 9, 2.43, -39.4916562, 176.7492083, 66.28, 108.94, 6.75, 9.30, -2.050000, 130429 -CTUN, 568, 0.00, 66.48, 0.000000, 0.00, 46, 196, 510, 0 -ATT, 2.38, 2.74, -29.05, -28.46, 0.10, 23.78, 23.83 -MOT, 1501, 1592, 1495, 1541 -CTUN, 571, 0.00, 66.14, 0.000000, 0.00, 46, 187, 514, 0 -ATT, 2.30, 2.38, -28.84, -28.48, 0.00, 23.69, 23.83 -MOT, 1513, 1590, 1513, 1534 -GPS, 3, 109277600, 1774, 9, 2.43, -39.4916442, 176.7492114, 66.68, 109.32, 6.79, 10.15, -1.930000, 130629 -CTUN, 571, 0.00, 66.34, 0.000000, 0.00, 47, 172, 515, 0 -ATT, 2.16, 2.17, -29.12, -28.58, 0.10, 23.61, 23.83 -MOT, 1505, 1596, 1497, 1550 -CTUN, 571, 0.00, 66.74, 0.000000, 0.00, 46, 167, 514, 0 -ATT, 2.30, 1.96, -29.26, -28.48, 0.10, 23.56, 23.83 -MOT, 1514, 1591, 1506, 1537 -GPS, 3, 109277800, 1774, 9, 2.43, -39.4916323, 176.7492145, 67.01, 109.68, 6.72, 10.70, -1.780000, 130829 -CTUN, 569, 0.00, 66.98, 0.000000, 0.00, 46, 157, 511, 0 -ATT, 2.16, 1.83, -29.78, -28.64, 0.00, 23.46, 23.83 -MOT, 1514, 1584, 1499, 1540 -CTUN, 568, 0.00, 66.73, 0.000000, 0.00, 46, 151, 510, 0 -ATT, 2.09, 1.71, -29.92, -28.72, 0.00, 23.38, 23.83 -MOT, 1516, 1586, 1480, 1548 -DU32, 7, 270713 -CURR, 515, 250493, 1539, 3685, 4897, 443.7743 -GPS, 3, 109278000, 1774, 9, 2.43, -39.4916203, 176.7492177, 67.34, 109.99, 6.83, 11.08, -1.640000, 131050 -CTUN, 571, 0.00, 67.34, 0.000000, 0.00, 47, 145, 512, 0 -ATT, 2.09, 1.73, -29.99, -28.66, 0.10, 23.35, 23.83 -MOT, 1532, 1572, 1494, 1544 -CTUN, 568, 0.00, 66.91, 0.000000, 0.00, 47, 139, 511, 0 -ATT, 2.16, 1.88, -29.99, -28.98, 0.10, 23.33, 23.83 -MOT, 1516, 1586, 1484, 1548 -GPS, 3, 109278200, 1774, 10, 1.65, -39.4916081, 176.7492208, 67.59, 110.30, 6.84, 11.09, -1.520000, 131230 -CTUN, 571, 0.00, 66.96, 0.000000, 0.00, 49, 133, 517, 0 -ATT, 2.38, 1.75, -29.99, -29.17, 0.10, 23.34, 23.83 -MOT, 1509, 1601, 1501, 1545 -CTUN, 571, 0.00, 67.39, 0.000000, 0.00, 49, 121, 517, 0 -ATT, 2.38, 1.72, -30.21, -29.35, 0.10, 23.34, 23.83 -MOT, 1518, 1592, 1509, 1541 -GPS, 3, 109278400, 1774, 10, 1.65, -39.4915959, 176.7492240, 67.80, 110.58, 6.91, 11.16, -1.410000, 131431 -CTUN, 571, 0.00, 67.64, 0.000000, 0.00, 49, 116, 517, 0 -ATT, 2.38, 1.59, -29.99, -29.26, 0.10, 23.32, 23.83 -MOT, 1524, 1591, 1485, 1555 -CTUN, 571, 0.00, 67.56, 0.000000, 0.00, 49, 118, 517, 0 -ATT, 2.30, 1.74, -29.99, -29.17, 0.10, 23.25, 23.83 -MOT, 1525, 1593, 1493, 1546 -GPS, 3, 109278600, 1774, 10, 1.65, -39.4915835, 176.7492272, 68.02, 110.82, 7.02, 11.21, -1.260000, 131631 -CTUN, 571, 0.00, 67.51, 0.000000, 0.00, 48, 109, 516, 0 -ATT, 2.59, 1.96, -30.21, -29.00, 0.10, 23.19, 23.83 -MOT, 1509, 1605, 1495, 1543 -CTUN, 571, 0.00, 67.68, 0.000000, 0.00, 48, 109, 516, 0 -ATT, 2.52, 2.16, -30.13, -28.83, 0.10, 23.13, 23.83 -MOT, 1509, 1605, 1494, 1544 -GPS, 3, 109278800, 1774, 10, 1.65, -39.4915708, 176.7492304, 68.20, 111.03, 7.16, 10.98, -1.130000, 131831 -CTUN, 578, 0.00, 68.17, 0.000000, 0.00, 48, 110, 524, 0 -ATT, 2.38, 2.24, -30.21, -28.70, 0.10, 23.07, 23.83 -MOT, 1501, 1625, 1506, 1546 -CTUN, 576, 0.00, 68.09, 0.000000, 0.00, 47, 108, 521, 0 -ATT, 2.38, 2.38, -30.21, -28.48, 0.10, 23.09, 23.83 -MOT, 1528, 1598, 1501, 1546 -DU32, 7, 270713 -CURR, 522, 255675, 1534, 4125, 4918, 454.4429 -GPS, 3, 109279000, 1774, 10, 1.65, -39.4915578, 176.7492336, 68.41, 111.25, 7.33, 10.84, -1.090000, 132031 -CTUN, 576, 0.00, 67.93, 0.000000, 0.00, 47, 109, 523, 0 -ATT, 2.59, 2.40, -30.21, -28.40, 0.20, 23.12, 23.83 -MOT, 1485, 1636, 1498, 1550 -CTUN, 578, 0.00, 67.90, 0.000000, 0.00, 46, 113, 522, 0 -ATT, 2.52, 2.44, -30.21, -28.10, 0.00, 23.12, 23.83 -MOT, 1536, 1593, 1506, 1542 -GPS, 3, 109279200, 1774, 10, 1.65, -39.4915446, 176.7492368, 68.59, 111.47, 7.45, 10.70, -1.080000, 132232 -CTUN, 578, 0.00, 68.57, 0.000000, 0.00, 46, 109, 523, 0 -ATT, 2.80, 2.48, -30.13, -28.06, 0.00, 23.12, 23.83 -MOT, 1481, 1638, 1504, 1547 -CTUN, 578, 0.00, 68.30, 0.000000, 0.00, 46, 108, 522, 0 -ATT, 2.59, 2.48, -30.21, -28.06, 0.10, 23.12, 23.83 -MOT, 1532, 1592, 1513, 1542 -GPS, 3, 109279400, 1774, 10, 1.65, -39.4915309, 176.7492401, 68.80, 111.74, 7.61, 10.66, -1.070000, 132432 -CTUN, 579, 0.00, 68.95, 0.000000, 0.00, 46, 113, 523, 0 -ATT, 2.30, 2.51, -30.35, -27.83, 0.10, 23.20, 23.83 -MOT, 1532, 1593, 1514, 1543 -CTUN, 578, 0.00, 68.51, 0.000000, 0.00, 46, 111, 522, 0 -ATT, 2.38, 2.47, -30.21, -28.03, 0.10, 23.27, 23.83 -MOT, 1494, 1623, 1486, 1563 -GPS, 3, 109279600, 1774, 10, 1.65, -39.4915172, 176.7492435, 69.02, 111.95, 7.73, 10.69, -1.050000, 132632 -CTUN, 579, 0.00, 68.72, 0.000000, 0.00, 45, 107, 522, 0 -ATT, 2.38, 2.53, -30.43, -27.93, 0.10, 23.37, 23.83 -MOT, 1514, 1605, 1516, 1541 -CTUN, 576, 0.00, 68.61, 0.000000, 0.00, 46, 109, 523, 0 -ATT, 2.52, 2.56, -30.35, -28.01, 0.10, 23.40, 23.83 -MOT, 1528, 1592, 1506, 1554 -GPS, 3, 109279800, 1774, 10, 1.65, -39.4915034, 176.7492469, 69.21, 112.21, 7.78, 10.76, -1.070000, 132832 -CTUN, 578, 0.00, 68.65, 0.000000, 0.00, 46, 109, 522, 0 -ATT, 3.02, 2.47, -30.86, -27.98, 0.20, 23.43, 23.83 -MOT, 1522, 1599, 1501, 1553 -CTUN, 577, 0.00, 69.43, 0.000000, 0.00, 46, 107, 521, 0 -ATT, 2.95, 2.53, -30.86, -28.11, 0.10, 23.37, 23.83 -MOT, 1508, 1615, 1491, 1553 -DU32, 7, 270713 -CURR, 521, 260896, 1532, 3928, 4918, 465.4024 -GPS, 3, 109280000, 1774, 10, 1.65, -39.4914893, 176.7492503, 69.40, 112.44, 7.91, 10.72, -1.040000, 133033 -CTUN, 579, 0.00, 69.47, 0.000000, 0.00, 46, 107, 523, 0 -ATT, 2.95, 2.71, -30.79, -28.02, 0.00, 23.35, 23.83 -MOT, 1515, 1608, 1486, 1564 -CTUN, 579, 0.00, 69.75, 0.000000, 0.00, 45, 119, 519, 0 -ATT, 2.80, 2.92, -30.64, -27.72, 0.00, 23.42, 23.83 -MOT, 1528, 1585, 1509, 1547 -GPS, 3, 109280200, 1774, 10, 1.65, -39.4914752, 176.7492538, 69.66, 112.67, 7.95, 10.94, -1.040000, 133233 -CTUN, 578, 0.00, 69.60, 0.000000, 0.00, 45, 120, 521, 0 -ATT, 2.59, 2.83, -30.64, -27.69, 0.10, 23.66, 23.83 -MOT, 1505, 1604, 1489, 1568 -CTUN, 587, 0.00, 69.39, 0.000000, 0.00, 45, 120, 529, 0 -ATT, 2.59, 2.89, -30.64, -27.53, 0.10, 23.82, 23.83 -MOT, 1520, 1604, 1541, 1539 -GPS, 3, 109280400, 1774, 10, 1.65, -39.4914608, 176.7492571, 69.91, 112.91, 8.03, 10.39, -1.050000, 133433 -CTUN, 587, 0.00, 69.81, 0.000000, 0.00, 45, 120, 532, 0 -ATT, 2.59, 2.95, -30.64, -27.44, 0.10, 23.88, 23.83 -MOT, 1532, 1603, 1497, 1576 -CTUN, 590, 0.00, 69.77, 0.000000, 0.00, 46, 121, 537, 0 -ATT, 2.59, 3.00, -30.57, -27.34, 0.10, 23.81, 23.83 -MOT, 1522, 1625, 1513, 1570 -GPS, 3, 109280600, 1774, 10, 1.65, -39.4914464, 176.7492604, 70.14, 113.18, 8.06, 10.36, -1.110000, 133634 -CTUN, 587, 0.00, 69.97, 0.000000, 0.00, 44, 123, 531, 0 -ATT, 2.52, 2.99, -30.86, -27.14, 0.00, 23.96, 23.83 -MOT, 1537, 1592, 1511, 1569 -CTUN, 587, 0.00, 69.89, 0.000000, 0.00, 44, 121, 531, 0 -ATT, 2.80, 3.06, -31.08, -27.08, 0.00, 24.06, 23.83 -MOT, 1526, 1604, 1510, 1568 -GPS, 3, 109280800, 1774, 10, 1.65, -39.4914320, 176.7492637, 70.38, 113.41, 8.06, 10.22, -1.070000, 133834 -CTUN, 587, 0.00, 70.61, 0.000000, 0.00, 43, 128, 530, 0 -ATT, 3.02, 2.93, -31.29, -26.85, 0.10, 23.89, 23.83 -MOT, 1533, 1605, 1510, 1556 -CTUN, 586, 0.00, 70.82, 0.000000, 0.00, 44, 133, 530, 0 -ATT, 2.95, 3.17, -31.44, -27.06, 0.00, 23.85, 23.83 -MOT, 1502, 1623, 1505, 1568 -DU32, 7, 270713 -CURR, 530, 266175, 1478, 3968, 4897, 476.5942 -PM, 0, 0, 0, 1001, 10258, 0, 0, 0, 0 -GPS, 3, 109281000, 1774, 10, 1.65, -39.4914177, 176.7492671, 70.68, 113.67, 8.01, 10.40, -1.100000, 134034 -CTUN, 587, 0.00, 70.62, 0.000000, 0.00, 44, 137, 530, 0 -ATT, 2.80, 3.17, -31.29, -27.02, 0.00, 23.94, 23.83 -MOT, 1518, 1607, 1504, 1572 -CTUN, 587, 0.00, 70.80, 0.000000, 0.00, 43, 145, 529, 0 -ATT, 3.24, 3.14, -30.86, -26.93, 0.10, 24.14, 23.83 -MOT, 1532, 1592, 1504, 1572 -GPS, 3, 109281200, 1774, 10, 1.65, -39.4914036, 176.7492704, 70.98, 113.94, 7.94, 10.25, -1.160000, 134234 -CTUN, 586, 0.00, 71.02, 0.000000, 0.00, 43, 145, 529, 0 -ATT, 3.60, 3.29, -31.51, -26.91, 0.00, 24.23, 23.83 -MOT, 1506, 1616, 1522, 1555 -CTUN, 587, 0.00, 71.04, 0.000000, 0.00, 44, 148, 531, 0 -ATT, 4.54, 3.40, -30.86, -26.99, 0.00, 24.19, 23.83 -MOT, 1509, 1619, 1516, 1561 -GPS, 3, 109281400, 1774, 10, 1.65, -39.4913894, 176.7492737, 71.30, 114.22, 7.93, 10.38, -1.220000, 134435 -CTUN, 586, 0.00, 71.26, 0.000000, 0.00, 43, 158, 529, 0 -ATT, 4.32, 3.75, -30.64, -26.51, 0.00, 24.14, 23.83 -MOT, 1499, 1624, 1500, 1570 -CTUN, 586, 0.00, 71.39, 0.000000, 0.00, 41, 166, 527, 0 -ATT, 4.32, 3.83, -30.43, -26.12, 0.00, 24.17, 23.83 -MOT, 1501, 1617, 1511, 1560 -GPS, 3, 109281600, 1774, 10, 1.65, -39.4913753, 176.7492770, 71.64, 114.51, 7.90, 10.29, -1.290000, 134635 -CTUN, 587, 0.00, 71.51, 0.000000, 0.00, 40, 173, 527, 0 -ATT, 3.39, 3.89, -29.12, -25.70, 0.00, 24.27, 23.83 -MOT, 1513, 1606, 1499, 1571 -CTUN, 586, 0.00, 71.75, 0.000000, 0.00, 38, 179, 524, 0 -ATT, 4.54, 3.81, -29.78, -24.91, 0.00, 24.39, 23.83 -MOT, 1470, 1632, 1523, 1550 -GPS, 3, 109281800, 1774, 10, 1.65, -39.4913613, 176.7492803, 72.01, 114.84, 7.85, 10.40, -1.390000, 134835 -CTUN, 586, 0.00, 72.11, 0.000000, 0.00, 36, 193, 522, 0 -ATT, 4.97, 4.07, -29.99, -24.39, 0.00, 24.41, 23.83 -MOT, 1493, 1614, 1499, 1563 -CTUN, 587, 0.00, 71.98, 0.000000, 0.00, 34, 209, 520, 0 -ATT, 4.32, 4.30, -29.99, -24.05, 0.00, 24.50, 23.83 -MOT, 1505, 1599, 1460, 1592 -DU32, 7, 270713 -CURR, 521, 271450, 1519, 4004, 4918, 487.8539 -GPS, 3, 109282000, 1774, 10, 1.65, -39.4913474, 176.7492837, 72.44, 115.18, 7.78, 10.66, -1.500000, 135035 -CTUN, 586, 0.00, 72.32, 0.000000, 0.00, 33, 216, 519, 0 -ATT, 2.09, 4.13, -30.35, -23.48, 0.20, 24.70, 23.83 -MOT, 1468, 1619, 1522, 1550 -CTUN, 586, 0.00, 72.26, 0.000000, 0.00, 32, 236, 519, 0 -ATT, 1.65, 3.32, -30.35, -23.29, 0.00, 24.84, 23.83 -MOT, 1464, 1624, 1486, 1574 -GPS, 3, 109282200, 1774, 10, 1.65, -39.4913336, 176.7492873, 72.90, 115.60, 7.75, 11.14, -1.760000, 135236 -CTUN, 587, 0.00, 72.47, 0.000000, 0.00, 31, 251, 517, 0 -ATT, 3.24, 2.80, -30.57, -22.92, 0.00, 24.92, 23.83 -MOT, 1486, 1601, 1498, 1565 -CTUN, 586, 0.00, 73.13, 0.000000, 0.00, 30, 275, 517, 0 -ATT, 4.69, 2.92, -31.22, -22.72, 0.20, 24.88, 23.83 -MOT, 1469, 1628, 1502, 1549 -GPS, 3, 109282400, 1774, 10, 1.65, -39.4913198, 176.7492909, 73.44, 116.07, 7.73, 11.25, -2.010000, 135436 -CTUN, 587, 0.00, 73.15, 0.000000, 0.00, 30, 295, 517, 0 -ATT, 3.46, 3.82, -31.51, -22.70, 0.00, 24.74, 23.83 -MOT, 1459, 1633, 1511, 1544 -CTUN, 586, 0.00, 73.68, 0.000000, 0.00, 31, 313, 518, 0 -ATT, 0.79, 3.47, -31.95, -22.90, 0.00, 24.69, 23.83 -MOT, 1552, 1552, 1413, 1627 -GPS, 3, 109282600, 1774, 10, 1.65, -39.4913061, 176.7492946, 74.08, 116.63, 7.66, 12.06, -2.340000, 135637 -CTUN, 585, 0.00, 74.09, 0.000000, 0.00, 31, 327, 516, 0 -ATT, 1.72, 2.63, -31.51, -23.20, 0.00, 24.59, 23.83 -MOT, 1477, 1621, 1461, 1578 -CTUN, 587, 0.00, 73.84, 0.000000, 0.00, 31, 347, 517, 0 -ATT, 1.08, 2.75, -30.86, -23.23, 0.00, 24.53, 23.83 -MOT, 1499, 1596, 1519, 1544 -GPS, 3, 109282800, 1774, 10, 1.65, -39.4912924, 176.7492984, 74.78, 117.27, 7.65, 12.34, -2.700000, 135837 -CTUN, 586, 0.00, 74.32, 0.000000, 0.00, 32, 356, 518, 0 -ATT, 0.64, 2.40, -30.64, -23.38, 0.20, 24.49, 23.83 -MOT, 1493, 1602, 1489, 1569 -CTUN, 587, 0.00, 75.00, 0.000000, 0.00, 33, 367, 520, 0 -ATT, 0.57, 1.97, -31.08, -23.90, 0.00, 24.46, 23.83 -MOT, 1493, 1610, 1474, 1579 -DU32, 7, 270713 -CURR, 521, 276626, 1518, 3935, 4918, 498.9821 -GPS, 3, 109283000, 1774, 10, 1.65, -39.4912789, 176.7493023, 75.51, 117.96, 7.59, 12.67, -3.030000, 136037 -CTUN, 587, 0.00, 74.87, 0.000000, 0.00, 34, 372, 521, 0 -ATT, 0.57, 1.70, -31.51, -24.46, 0.00, 24.36, 23.83 -MOT, 1533, 1579, 1508, 1555 -CTUN, 586, 0.00, 75.40, 0.000000, 0.00, 39, 366, 525, 0 -ATT, 1.50, 1.52, -31.51, -26.01, 0.10, 24.15, 23.83 -MOT, 1493, 1622, 1476, 1583 -GPS, 3, 109283200, 1774, 10, 1.65, -39.4912655, 176.7493062, 76.24, 118.68, 7.53, 13.10, -3.230000, 136237 -CTUN, 586, 0.00, 76.00, 0.000000, 0.00, 43, 354, 530, 0 -ATT, 2.09, 1.54, -31.44, -27.31, 0.10, 23.95, 23.83 -MOT, 1533, 1604, 1534, 1537 -CTUN, 587, 0.00, 76.07, 0.000000, 0.00, 48, 339, 535, 0 -ATT, 1.94, 1.43, -31.51, -28.30, 0.00, 23.72, 23.83 -MOT, 1514, 1630, 1525, 1552 -GPS, 3, 109283400, 1774, 10, 1.65, -39.4912522, 176.7493102, 76.93, 119.40, 7.46, 13.48, -3.280000, 136437 -CTUN, 587, 0.00, 76.19, 0.000000, 0.00, 51, 326, 538, 0 -ATT, 1.87, 1.24, -31.73, -29.23, 0.00, 23.46, 23.83 -MOT, 1561, 1597, 1506, 1569 -CTUN, 587, 0.00, 76.92, 0.000000, 0.00, 54, 309, 541, 0 -ATT, 1.87, 1.22, -31.73, -29.97, 0.20, 23.28, 23.83 -MOT, 1509, 1651, 1541, 1544 -GPS, 3, 109283600, 1774, 10, 1.65, -39.4912389, 176.7493141, 77.53, 120.05, 7.45, 12.97, -3.070000, 136638 -CTUN, 587, 0.00, 76.92, 0.000000, 0.00, 57, 295, 544, 0 -ATT, 2.09, 1.10, -31.95, -30.66, 0.00, 23.08, 23.83 -MOT, 1532, 1636, 1522, 1566 -CTUN, 586, 0.00, 77.62, 0.000000, 0.00, 58, 285, 544, 0 -ATT, 2.09, 0.90, -31.88, -30.97, 0.00, 23.02, 23.83 -MOT, 1545, 1620, 1541, 1552 -GPS, 3, 109283800, 1774, 10, 1.65, -39.4912256, 176.7493179, 78.10, 120.65, 7.48, 12.37, -2.870000, 136838 -CTUN, 585, 0.00, 77.84, 0.000000, 0.00, 61, 272, 548, 0 -ATT, 2.38, 0.92, -32.16, -31.47, 0.10, 22.98, 23.83 -MOT, 1547, 1624, 1541, 1558 -CTUN, 586, 0.00, 77.69, 0.000000, 0.00, 62, 252, 548, 0 -ATT, 2.80, 1.04, -32.16, -31.86, 0.20, 22.83, 23.83 -MOT, 1549, 1628, 1521, 1572 -DU32, 7, 270713 -CURR, 548, 281980, 1508, 4144, 4962, 510.2630 -GPS, 3, 109284000, 1774, 10, 1.65, -39.4912121, 176.7493214, 78.65, 121.20, 7.56, 11.48, -2.660000, 137057 -CTUN, 586, 0.00, 78.51, 0.000000, 0.00, 63, 244, 549, 0 -ATT, 3.46, 1.37, -32.09, -31.86, 0.00, 22.90, 23.83 -MOT, 1541, 1630, 1541, 1562 -CTUN, 587, 0.00, 78.55, 0.000000, 0.00, 63, 229, 550, 0 -ATT, 4.54, 1.76, -32.60, -31.89, 0.10, 22.90, 23.83 -MOT, 1526, 1648, 1537, 1566 -GPS, 3, 109284200, 1774, 10, 1.65, -39.4911985, 176.7493248, 79.07, 121.71, 7.66, 10.91, -2.440000, 137239 -CTUN, 587, 0.00, 78.69, 0.000000, 0.00, 64, 213, 551, 0 -ATT, 6.05, 2.67, -33.04, -32.00, 0.10, 22.98, 23.83 -MOT, 1543, 1633, 1548, 1556 -CTUN, 587, 0.00, 79.24, 0.000000, 0.00, 66, 201, 553, 0 -ATT, 6.49, 4.00, -33.04, -32.36, 0.00, 22.89, 23.83 -MOT, 1540, 1645, 1535, 1568 -GPS, 3, 109284400, 1774, 10, 1.65, -39.4911846, 176.7493280, 79.48, 122.14, 7.80, 10.17, -2.210000, 137439 -CTUN, 587, 0.00, 79.68, 0.000000, 0.00, 67, 182, 554, 0 -ATT, 6.70, 4.86, -33.47, -32.41, 0.00, 22.80, 23.83 -MOT, 1554, 1633, 1542, 1562 -CTUN, 586, 0.00, 79.32, 0.000000, 0.00, 68, 173, 555, 0 -ATT, 6.92, 5.69, -33.47, -32.57, 0.10, 22.80, 23.83 -MOT, 1542, 1644, 1555, 1552 -GPS, 3, 109284600, 1774, 10, 1.65, -39.4911707, 176.7493311, 79.85, 122.52, 7.86, 9.60, -1.990000, 137639 -CTUN, 586, 0.00, 80.32, 0.000000, 0.00, 69, 157, 555, 0 -ATT, 7.35, 6.11, -33.47, -32.65, 0.00, 22.97, 23.83 -MOT, 1530, 1651, 1533, 1579 -CTUN, 587, 0.00, 80.09, 0.000000, 0.00, 68, 151, 555, 0 -ATT, 7.35, 6.37, -33.47, -32.34, 0.00, 23.17, 23.83 -MOT, 1558, 1627, 1521, 1587 -GPS, 3, 109284800, 1774, 10, 1.65, -39.4911566, 176.7493343, 80.20, 122.84, 7.95, 9.72, -1.750000, 137840 -CTUN, 586, 0.00, 79.99, 0.000000, 0.00, 66, 148, 552, 0 -ATT, 7.79, 7.10, -33.69, -31.83, 0.10, 23.34, 23.83 -MOT, 1524, 1651, 1560, 1548 -CTUN, 586, 0.00, 79.75, 0.000000, 0.00, 65, 146, 552, 0 -ATT, 8.00, 7.14, -33.69, -31.50, 0.20, 23.44, 23.83 -MOT, 1547, 1629, 1526, 1581 -DU32, 7, 270713 -CURR, 550, 287497, 1527, 4405, 4984, 521.9993 -GPS, 3, 109285000, 1774, 10, 1.65, -39.4911424, 176.7493376, 80.48, 123.15, 8.03, 10.10, -1.570000, 138040 -CTUN, 586, 0.00, 80.08, 0.000000, 0.00, 64, 152, 550, 0 -ATT, 8.43, 7.36, -33.47, -31.29, 0.00, 23.58, 23.83 -MOT, 1544, 1626, 1526, 1581 -CTUN, 587, 0.00, 80.83, 0.000000, 0.00, 63, 149, 549, 0 -ATT, 8.65, 7.87, -33.47, -30.93, 0.00, 23.73, 23.83 -MOT, 1546, 1619, 1541, 1569 -GPS, 3, 109285200, 1774, 10, 1.65, -39.4911281, 176.7493415, 80.77, 123.41, 8.17, 11.58, -1.490000, 138240 -CTUN, 587, 0.00, 80.71, 0.000000, 0.00, 62, 143, 549, 0 -ATT, 8.43, 8.24, -33.47, -30.81, 0.00, 23.78, 23.83 -MOT, 1547, 1628, 1534, 1565 -CTUN, 587, 0.00, 80.85, 0.000000, 0.00, 63, 137, 550, 0 -ATT, 8.22, 8.56, -33.25, -30.97, 0.00, 23.66, 23.83 -MOT, 1550, 1624, 1520, 1581 -GPS, 3, 109285400, 1774, 10, 1.65, -39.4911135, 176.7493457, 81.07, 123.71, 8.26, 12.33, -1.450000, 138441 -CTUN, 586, 0.00, 81.13, 0.000000, 0.00, 65, 132, 552, 0 -ATT, 8.43, 8.74, -33.04, -31.12, 0.00, 23.60, 23.83 -MOT, 1531, 1646, 1517, 1588 -CTUN, 587, 0.00, 81.12, 0.000000, 0.00, 64, 120, 551, 0 -ATT, 8.22, 8.71, -32.82, -30.96, 0.00, 23.69, 23.83 -MOT, 1537, 1631, 1539, 1573 -GPS, 3, 109285600, 1774, 10, 1.65, -39.4910990, 176.7493503, 81.34, 123.98, 8.28, 13.67, -1.320000, 138640 -CTUN, 586, 0.00, 81.25, 0.000000, 0.00, 63, 118, 550, 0 -ATT, 8.43, 8.70, -32.82, -30.80, 0.00, 23.80, 23.83 -MOT, 1532, 1638, 1528, 1579 -CTUN, 585, 0.00, 81.05, 0.000000, 0.00, 62, 119, 547, 0 -ATT, 8.65, 8.62, -32.75, -30.70, 0.00, 23.77, 23.83 -MOT, 1551, 1620, 1533, 1563 -GPS, 3, 109285800, 1774, 10, 1.65, -39.4910844, 176.7493551, 81.56, 124.21, 8.31, 14.39, -1.160000, 138842 -CTUN, 586, 0.00, 81.25, 0.000000, 0.00, 62, 110, 549, 0 -ATT, 8.87, 8.67, -32.75, -30.56, 0.10, 23.72, 23.83 -MOT, 1531, 1641, 1532, 1570 -CTUN, 587, 0.00, 81.29, 0.000000, 0.00, 61, 106, 547, 0 -ATT, 8.87, 8.63, -32.82, -30.38, 0.10, 23.79, 23.83 -MOT, 1517, 1649, 1520, 1578 -DU32, 7, 270713 -CURR, 546, 292989, 1484, 4226, 4940, 533.8241 -GPS, 3, 109286000, 1774, 10, 1.65, -39.4910700, 176.7493602, 81.76, 124.43, 8.32, 15.15, -1.090000, 139042 -CTUN, 584, 0.00, 81.90, 0.000000, 0.00, 60, 108, 544, 0 -ATT, 8.87, 8.68, -32.16, -30.14, 0.00, 23.95, 23.83 -MOT, 1525, 1633, 1529, 1570 -CTUN, 587, 0.00, 81.54, 0.000000, 0.00, 58, 109, 545, 0 -ATT, 8.87, 8.59, -32.16, -29.58, 0.00, 24.12, 23.83 -MOT, 1536, 1624, 1529, 1572 -GPS, 3, 109286200, 1774, 10, 1.65, -39.4910556, 176.7493656, 81.97, 124.64, 8.32, 15.98, -1.040000, 139242 -CTUN, 586, 0.00, 81.81, 0.000000, 0.00, 57, 108, 544, 0 -ATT, 8.65, 8.53, -32.38, -29.30, 0.00, 24.19, 23.83 -MOT, 1521, 1638, 1525, 1572 -CTUN, 586, 0.00, 81.88, 0.000000, 0.00, 56, 104, 542, 0 -ATT, 8.65, 8.54, -32.82, -29.20, 0.00, 24.15, 23.83 -MOT, 1526, 1628, 1519, 1575 -GPS, 3, 109286400, 1774, 10, 1.65, -39.4910411, 176.7493712, 82.17, 124.85, 8.35, 16.79, -1.010000, 139442 -CTUN, 586, 0.00, 82.18, 0.000000, 0.00, 55, 100, 541, 0 -ATT, 8.87, 8.23, -33.25, -29.05, 0.00, 24.15, 23.83 -MOT, 1522, 1635, 1528, 1562 -CTUN, 586, 0.00, 82.12, 0.000000, 0.00, 56, 97, 542, 0 -ATT, 8.43, 8.30, -33.47, -29.21, 0.00, 24.08, 23.83 -MOT, 1525, 1629, 1516, 1578 -GPS, 3, 109286600, 1774, 10, 1.65, -39.4910269, 176.7493772, 82.38, 125.05, 8.32, 17.71, -0.990000, 139642 -CTUN, 587, 0.00, 82.35, 0.000000, 0.00, 55, 104, 542, 0 -ATT, 8.43, 7.99, -33.69, -28.97, 0.00, 24.32, 23.83 -MOT, 1541, 1615, 1496, 1593 -CTUN, 586, 0.00, 82.32, 0.000000, 0.00, 55, 107, 542, 0 -ATT, 8.22, 7.94, -33.69, -29.08, 0.10, 24.48, 23.83 -MOT, 1525, 1628, 1541, 1556 -GPS, 3, 109286800, 1774, 10, 1.65, -39.4910127, 176.7493832, 82.60, 125.24, 8.27, 18.23, -0.920000, 139843 -CTUN, 587, 0.00, 81.80, 0.000000, 0.00, 55, 113, 542, 0 -ATT, 8.22, 7.85, -33.69, -29.05, 0.00, 24.58, 23.83 -MOT, 1541, 1610, 1526, 1573 -CTUN, 587, 0.00, 82.73, 0.000000, 0.00, 55, 110, 541, 0 -ATT, 8.22, 7.70, -33.69, -29.29, 0.00, 24.66, 23.83 -MOT, 1538, 1612, 1512, 1583 -DU32, 7, 270713 -CURR, 541, 298413, 1475, 4087, 4876, 545.4614 -GPS, 3, 109287000, 1774, 10, 1.65, -39.4909986, 176.7493893, 82.78, 125.44, 8.23, 18.62, -0.930000, 140043 -CTUN, 587, 0.00, 82.99, 0.000000, 0.00, 56, 110, 542, 0 -ATT, 8.22, 7.74, -33.69, -29.39, 0.00, 24.63, 23.83 -MOT, 1522, 1632, 1526, 1569 -CTUN, 584, 0.00, 82.54, 0.000000, 0.00, 56, 111, 543, 0 -ATT, 8.22, 7.70, -33.69, -29.56, 0.00, 24.59, 23.83 -MOT, 1531, 1623, 1531, 1570 -GPS, 3, 109287200, 1774, 10, 1.65, -39.4909847, 176.7493956, 83.01, 125.61, 8.21, 19.12, -0.910000, 140243 -CTUN, 586, 0.00, 82.88, 0.000000, 0.00, 56, 113, 542, 0 -ATT, 8.00, 7.61, -33.69, -29.40, 0.20, 24.65, 23.83 -MOT, 1508, 1638, 1522, 1578 -CTUN, 587, 0.00, 82.90, 0.000000, 0.00, 55, 118, 541, 0 -ATT, 8.00, 7.51, -33.69, -29.16, 0.00, 24.75, 23.83 -MOT, 1532, 1615, 1532, 1569 -GPS, 3, 109287400, 1774, 10, 1.65, -39.4909707, 176.7494020, 83.23, 125.83, 8.16, 19.61, -0.950000, 140443 -CTUN, 586, 0.00, 82.86, 0.000000, 0.00, 55, 119, 541, 0 -ATT, 8.00, 7.33, -33.47, -29.24, 0.00, 24.77, 23.83 -MOT, 1511, 1636, 1508, 1586 -CTUN, 586, 0.00, 83.14, 0.000000, 0.00, 55, 120, 542, 0 -ATT, 8.00, 7.28, -33.69, -29.15, 0.00, 24.66, 23.83 -MOT, 1537, 1617, 1528, 1570 -GPS, 3, 109287600, 1774, 10, 1.65, -39.4909567, 176.7494086, 83.46, 126.06, 8.23, 20.21, -1.030000, 140644 -CTUN, 587, 0.00, 83.29, 0.000000, 0.00, 55, 123, 542, 0 -ATT, 8.22, 7.38, -33.91, -29.09, 0.00, 24.61, 23.83 -MOT, 1537, 1617, 1515, 1580 -CTUN, 587, 0.00, 83.78, 0.000000, 0.00, 56, 124, 543, 0 -ATT, 8.00, 7.55, -33.83, -29.31, 0.00, 24.62, 23.83 -MOT, 1512, 1637, 1532, 1571 -GPS, 3, 109287800, 1774, 10, 1.65, -39.4909430, 176.7494154, 83.72, 126.27, 8.20, 20.77, -1.080000, 140844 -CTUN, 586, 0.00, 83.59, 0.000000, 0.00, 55, 127, 542, 0 -ATT, 7.79, 7.50, -33.91, -29.33, 0.00, 24.69, 23.83 -MOT, 1532, 1620, 1528, 1572 -CTUN, 587, 0.00, 84.02, 0.000000, 0.00, 56, 132, 543, 0 -ATT, 7.79, 7.44, -34.12, -29.34, 0.00, 24.64, 23.83 -MOT, 1516, 1637, 1515, 1582 -DU32, 7, 270713 -CURR, 541, 303831, 1502, 4242, 4897, 557.1648 -GPS, 3, 109288000, 1774, 10, 1.65, -39.4909291, 176.7494222, 84.01, 126.51, 8.22, 20.73, -1.130000, 141044 -CTUN, 587, 0.00, 83.28, 0.000000, 0.00, 56, 142, 542, 0 -ATT, 7.79, 7.57, -34.12, -29.49, 0.10, 24.62, 23.83 -MOT, 1528, 1625, 1541, 1556 -CTUN, 587, 0.00, 83.80, 0.000000, 0.00, 58, 139, 545, 0 -ATT, 7.79, 7.56, -34.12, -29.99, 0.00, 24.49, 23.83 -MOT, 1530, 1632, 1533, 1566 -GPS, 3, 109288200, 1774, 10, 1.65, -39.4909151, 176.7494292, 84.25, 126.77, 8.29, 21.35, -1.190000, 141245 -CTUN, 587, 0.00, 84.07, 0.000000, 0.00, 59, 139, 545, 0 -ATT, 7.79, 7.50, -34.12, -30.43, 0.10, 24.34, 23.83 -MOT, 1538, 1624, 1532, 1568 -CTUN, 587, 0.00, 83.77, 0.000000, 0.00, 61, 130, 548, 0 -ATT, 7.79, 7.32, -34.12, -30.60, 0.00, 24.30, 23.83 -MOT, 1537, 1627, 1544, 1564 -GPS, 3, 109288400, 1774, 10, 1.65, -39.4909010, 176.7494364, 84.48, 127.03, 8.38, 21.33, -1.220000, 141445 -CTUN, 587, 0.00, 84.40, 0.000000, 0.00, 62, 118, 549, 0 -ATT, 7.79, 7.43, -34.12, -30.91, 0.10, 24.27, 23.83 -MOT, 1518, 1642, 1518, 1592 -CTUN, 587, 0.00, 84.41, 0.000000, 0.00, 62, 115, 549, 0 -ATT, 7.79, 7.37, -34.34, -31.06, 0.00, 24.26, 23.83 -MOT, 1549, 1619, 1551, 1555 -GPS, 3, 109288600, 1774, 10, 1.65, -39.4908868, 176.7494436, 84.71, 127.28, 8.40, 21.41, -1.200000, 141645 -CTUN, 586, 0.00, 84.47, 0.000000, 0.00, 64, 111, 550, 0 -ATT, 7.79, 7.35, -34.34, -31.32, 0.00, 24.18, 23.83 -MOT, 1537, 1633, 1522, 1584 -CTUN, 587, 0.00, 84.51, 0.000000, 0.00, 64, 109, 551, 0 -ATT, 8.00, 7.52, -34.34, -31.45, 0.00, 24.15, 23.83 -MOT, 1537, 1633, 1544, 1567 -GPS, 3, 109288800, 1774, 10, 1.65, -39.4908725, 176.7494507, 84.91, 127.50, 8.49, 21.20, -1.120000, 141845 -CTUN, 587, 0.00, 84.56, 0.000000, 0.00, 65, 98, 552, 0 -ATT, 8.00, 7.55, -34.34, -31.55, 0.00, 24.15, 23.83 -MOT, 1548, 1622, 1524, 1589 -CTUN, 587, 0.00, 85.49, 0.000000, 0.00, 66, 88, 552, 0 -ATT, 8.00, 7.75, -34.34, -31.84, 0.10, 24.19, 23.83 -MOT, 1541, 1627, 1541, 1575 -DU32, 7, 270713 -CURR, 553, 309307, 1480, 4221, 4962, 569.0137 -GPS, 3, 109289000, 1774, 10, 1.65, -39.4908582, 176.7494580, 85.11, 127.71, 8.51, 21.31, -1.040000, 142046 -CTUN, 587, 0.00, 85.37, 0.000000, 0.00, 68, 84, 555, 0 -ATT, 7.79, 7.84, -34.34, -31.99, 0.00, 24.16, 23.83 -MOT, 1534, 1641, 1541, 1578 -CTUN, 587, 0.00, 84.39, 0.000000, 0.00, 67, 78, 554, 0 -ATT, 8.00, 7.53, -34.34, -31.95, 0.00, 24.23, 23.83 -MOT, 1547, 1623, 1537, 1584 -GPS, 3, 109289200, 1774, 10, 1.65, -39.4908437, 176.7494652, 85.27, 127.91, 8.58, 21.07, -0.940000, 142246 -CTUN, 586, 0.00, 86.09, 0.000000, 0.00, 68, 65, 554, 0 -ATT, 8.00, 7.46, -34.34, -32.23, 0.00, 24.15, 23.83 -MOT, 1521, 1651, 1547, 1570 -CTUN, 586, 0.00, 85.72, 0.000000, 0.00, 68, 62, 554, 0 -ATT, 8.00, 7.66, -34.34, -32.18, 0.00, 24.11, 23.83 -MOT, 1541, 1634, 1542, 1573 -GPS, 3, 109289400, 1774, 10, 1.65, -39.4908292, 176.7494725, 85.45, 128.05, 8.60, 21.15, -0.770000, 142446 -CTUN, 587, 0.00, 85.24, 0.000000, 0.00, 68, 56, 554, 0 -ATT, 8.00, 7.56, -34.34, -32.25, 0.00, 24.08, 23.83 -MOT, 1541, 1633, 1542, 1573 -CTUN, 585, 0.00, 85.85, 0.000000, 0.00, 69, 39, 554, 0 -ATT, 8.00, 7.72, -34.34, -32.55, 0.00, 23.91, 23.83 -MOT, 1525, 1654, 1544, 1567 -GPS, 3, 109289600, 1774, 10, 1.65, -39.4908149, 176.7494797, 85.56, 128.15, 8.58, 21.03, -0.610000, 142646 -CTUN, 586, 0.00, 85.77, 0.000000, 0.00, 71, 32, 557, 0 -ATT, 8.00, 7.84, -34.56, -32.96, 0.00, 23.94, 23.83 -MOT, 1556, 1620, 1553, 1571 -CTUN, 587, 0.00, 85.92, 0.000000, 0.00, 72, 13, 558, 0 -ATT, 8.00, 7.85, -34.56, -32.99, 0.00, 24.25, 23.83 -MOT, 1560, 1609, 1503, 1627 -GPS, 3, 109289800, 1774, 10, 1.65, -39.4908002, 176.7494868, 85.63, 128.23, 8.65, 20.47, -0.450000, 142847 -CTUN, 585, 0.00, 86.00, 0.000000, 0.00, 72, 8, 557, 0 -ATT, 7.79, 8.22, -34.56, -32.99, 0.00, 24.46, 23.83 -MOT, 1520, 1653, 1570, 1555 -CTUN, 587, 0.00, 85.25, 0.000000, 0.00, 72, 2, 559, 0 -ATT, 7.93, 7.74, -34.78, -32.80, 0.00, 24.49, 23.83 -MOT, 1560, 1620, 1517, 1608 -DU32, 7, 270713 -CURR, 555, 314863, 1488, 4347, 4897, 580.8494 -GPS, 3, 109290000, 1774, 10, 1.65, -39.4907856, 176.7494938, 85.65, 128.25, 8.66, 20.10, -0.250000, 143048 -CTUN, 584, 0.00, 85.80, 0.000000, 0.00, 70, -3, 554, 0 -ATT, 8.22, 7.98, -34.78, -32.75, 0.00, 24.38, 23.83 -MOT, 1514, 1658, 1564, 1552 -CTUN, 586, 0.00, 85.86, 0.000000, 0.00, 71, -12, 557, 0 -ATT, 8.22, 7.91, -34.78, -32.73, 0.00, 24.18, 23.83 -MOT, 1541, 1644, 1534, 1582 -GPS, 3, 109290200, 1774, 10, 1.65, -39.4907711, 176.7495011, 85.64, 128.26, 8.67, 21.24, -0.070000, 143247 -CTUN, 587, 0.00, 85.71, 0.000000, 0.00, 70, -11, 556, 0 -ATT, 8.22, 8.14, -35.00, -32.58, 0.00, 24.09, 23.83 -MOT, 1549, 1633, 1541, 1575 -CTUN, 586, 0.00, 85.83, 0.000000, 0.00, 71, -24, 557, 0 -ATT, 8.22, 8.21, -35.00, -32.69, 0.00, 23.95, 23.83 -MOT, 1546, 1636, 1531, 1588 -GPS, 3, 109290400, 1774, 10, 1.65, -39.4907563, 176.7495088, 85.62, 128.24, 8.84, 21.81, 0.050000, 143447 -CTUN, 584, 0.00, 85.49, 0.000000, 0.00, 71, -30, 558, 0 -ATT, 8.22, 7.94, -35.00, -32.85, 0.20, 23.89, 23.83 -MOT, 1544, 1641, 1547, 1572 -CTUN, 586, 0.00, 84.90, 0.000000, 0.00, 71, -34, 557, 0 -ATT, 8.22, 7.73, -35.00, -32.74, 0.00, 24.00, 23.83 -MOT, 1518, 1658, 1540, 1583 -GPS, 3, 109290600, 1774, 10, 1.65, -39.4907414, 176.7495169, 85.51, 128.19, 8.96, 22.60, 0.150000, 143648 -CTUN, 587, 0.00, 85.29, 0.000000, 0.00, 70, -34, 554, 0 -ATT, 8.00, 7.68, -35.00, -32.67, 0.00, 24.05, 23.83 -MOT, 1478, 1684, 1543, 1574 -CTUN, 587, 0.00, 85.75, 0.000000, 0.00, 67, -28, 554, 0 -ATT, 7.79, 7.72, -34.78, -32.05, 0.00, 24.23, 23.83 -MOT, 1601, 1571, 1484, 1625 -GPS, 3, 109290800, 1774, 10, 1.65, -39.4907264, 176.7495255, 85.44, 128.11, 9.12, 23.81, 0.260000, 143848 -CTUN, 586, 0.00, 85.68, 0.000000, 0.00, 68, -22, 555, 0 -ATT, 7.57, 8.33, -34.56, -31.88, 0.00, 24.40, 23.83 -MOT, 1556, 1610, 1516, 1609 -CTUN, 586, 0.00, 85.23, 0.000000, 0.00, 68, -35, 554, 0 -ATT, 7.79, 8.55, -35.00, -32.01, 0.20, 24.57, 23.83 -MOT, 1522, 1638, 1587, 1541 -DU32, 7, 270713 -CURR, 555, 320426, 1487, 4377, 4897, 592.9659 -PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 -GPS, 3, 109291000, 1774, 10, 1.65, -39.4907111, 176.7495343, 85.39, 128.06, 9.31, 24.01, 0.240000, 144049 -CTUN, 586, 0.00, 85.51, 0.000000, 0.00, 70, -44, 557, 0 -ATT, 7.57, 8.02, -35.00, -32.50, 0.00, 24.71, 23.83 -MOT, 1532, 1637, 1509, 1619 -CTUN, 586, 0.00, 86.29, 0.000000, 0.00, 69, -48, 555, 0 -ATT, 9.30, 8.44, -35.00, -32.45, 0.10, 25.08, 23.83 -MOT, 1554, 1603, 1557, 1580 -GPS, 3, 109291200, 1774, 10, 1.65, -39.4906956, 176.7495434, 85.32, 127.99, 9.50, 24.28, 0.280000, 144249 -CTUN, 587, 0.00, 86.31, 0.000000, 0.00, 74, -66, 561, 0 -ATT, 9.95, 9.36, -35.00, -33.20, 0.00, 25.40, 23.83 -MOT, 1538, 1620, 1541, 1614 -CTUN, 587, 0.00, 86.54, 0.000000, 0.00, 77, -83, 563, 0 -ATT, 10.39, 9.80, -35.00, -33.64, 0.10, 25.62, 23.83 -MOT, 1550, 1617, 1550, 1604 -GPS, 3, 109291400, 1774, 10, 1.65, -39.4906802, 176.7495527, 85.28, 127.87, 9.47, 24.63, 0.460000, 144449 -CTUN, 586, 0.00, 86.75, 0.000000, 0.00, 75, -98, 561, 0 -ATT, 10.17, 10.41, -35.00, -32.80, 0.00, 26.03, 23.83 -MOT, 1552, 1610, 1530, 1622 -CTUN, 587, 0.00, 86.73, 0.000000, 0.00, 70, -94, 556, 0 -ATT, 9.52, 10.30, -35.00, -31.64, 0.00, 26.31, 23.83 -MOT, 1555, 1603, 1475, 1652 -GPS, 3, 109291600, 1774, 10, 1.65, -39.4906651, 176.7495620, 85.24, 127.67, 9.33, 25.43, 0.810000, 144649 -CTUN, 587, 0.00, 86.41, 0.000000, 0.00, 61, -73, 547, 0 -ATT, 8.22, 9.46, -35.00, -29.49, 0.00, 26.70, 23.83 -MOT, 1492, 1641, 1427, 1679 -CTUN, 587, 0.00, 85.79, 0.000000, 0.00, 45, -14, 532, 0 -ATT, 6.92, 9.21, -35.00, -24.85, 0.00, 27.43, 23.83 -MOT, 1435, 1656, 1520, 1583 -GPS, 3, 109291800, 1774, 10, 1.65, -39.4906505, 176.7495719, 85.29, 127.48, 9.14, 27.44, 0.930000, 144850 -CTUN, 586, 0.00, 85.81, 0.000000, 0.00, 32, 66, 519, 0 -ATT, 6.92, 7.59, -35.00, -21.90, 0.00, 27.89, 23.83 -MOT, 1478, 1599, 1448, 1619 -CTUN, 586, 0.00, 85.24, 0.000000, 0.00, 26, 120, 512, 0 -ATT, 6.92, 6.72, -35.00, -20.04, 0.00, 28.10, 23.83 -MOT, 1435, 1621, 1518, 1553 -DU32, 7, 270713 -CURR, 510, 325904, 1519, 3821, 4918, 604.7382 -GPS, 3, 109292000, 1774, 10, 1.65, -39.4906362, 176.7495829, 85.55, 127.42, 9.29, 30.98, 0.430000, 145050 -CTUN, 587, 0.00, 85.04, 0.000000, 0.00, 23, 167, 510, 0 -ATT, 6.49, 5.54, -35.00, -19.39, 0.00, 27.96, 23.83 -MOT, 1451, 1604, 1480, 1581 -CTUN, 587, 0.00, 84.98, 0.000000, 0.00, 23, 196, 510, 0 -ATT, 6.49, 5.06, -35.00, -20.18, 0.00, 27.55, 23.83 -MOT, 1469, 1603, 1534, 1523 -GPS, 3, 109292200, 1774, 10, 1.65, -39.4906220, 176.7495949, 85.88, 127.66, 9.42, 33.88, -0.560000, 145250 -CTUN, 587, 0.00, 84.97, 0.000000, 0.00, 27, 206, 514, 0 -ATT, 6.27, 3.92, -35.00, -21.67, 0.00, 26.82, 23.83 -MOT, 1502, 1588, 1490, 1562 -CTUN, 586, 0.00, 85.04, 0.000000, 0.00, 32, 211, 519, 0 -ATT, 4.97, 3.98, -35.00, -23.72, 0.00, 26.05, 23.83 -MOT, 1474, 1625, 1494, 1560 -GPS, 3, 109292400, 1774, 10, 1.65, -39.4906081, 176.7496067, 86.22, 128.09, 9.12, 34.40, -1.280000, 145450 -CTUN, 587, 0.00, 85.48, 0.000000, 0.00, 38, 214, 525, 0 -ATT, 4.97, 3.70, -35.00, -25.36, 0.00, 25.45, 23.83 -MOT, 1502, 1615, 1504, 1560 -CTUN, 587, 0.00, 86.03, 0.000000, 0.00, 44, 205, 531, 0 -ATT, 5.62, 3.78, -35.00, -27.43, 0.00, 24.90, 23.83 -MOT, 1494, 1638, 1537, 1537 -GPS, 3, 109292600, 1774, 10, 1.65, -39.4905947, 176.7496183, 86.59, 128.48, 8.88, 34.51, -1.510000, 145651 -CTUN, 586, 0.00, 85.46, 0.000000, 0.00, 51, 198, 538, 0 -ATT, 7.57, 4.19, -35.00, -29.09, 0.00, 24.33, 23.83 -MOT, 1533, 1619, 1540, 1546 -CTUN, 587, 0.00, 85.84, 0.000000, 0.00, 57, 190, 544, 0 -ATT, 7.79, 5.20, -35.00, -30.26, 0.00, 23.94, 23.83 -MOT, 1506, 1652, 1530, 1564 -GPS, 3, 109292800, 1774, 10, 1.65, -39.4905815, 176.7496297, 86.89, 128.84, 8.74, 34.25, -1.510000, 145851 -CTUN, 587, 0.00, 86.04, 0.000000, 0.00, 60, 184, 547, 0 -ATT, 7.79, 5.86, -35.00, -30.82, 0.00, 23.96, 23.83 -MOT, 1545, 1615, 1526, 1581 -CTUN, 586, 0.00, 85.95, 0.000000, 0.00, 64, 175, 550, 0 -ATT, 7.79, 6.65, -35.00, -31.50, 0.00, 23.94, 23.83 -MOT, 1517, 1647, 1533, 1578 -DU32, 7, 270713 -CURR, 550, 331171, 1477, 4230, 4962, 616.0119 -GPS, 3, 109293000, 1774, 10, 1.65, -39.4905683, 176.7496408, 87.16, 129.17, 8.70, 33.36, -1.450000, 146051 -CTUN, 587, 0.00, 86.88, 0.000000, 0.00, 65, 171, 549, 0 -ATT, 8.00, 7.15, -35.00, -31.64, 0.00, 23.96, 23.83 -MOT, 1528, 1638, 1520, 1586 -CTUN, 586, 0.00, 86.66, 0.000000, 0.00, 63, 172, 549, 0 -ATT, 7.79, 7.16, -35.00, -31.11, 0.20, 24.07, 23.83 -MOT, 1547, 1618, 1546, 1563 -GPS, 3, 109293200, 1774, 10, 1.65, -39.4905545, 176.7496519, 87.47, 129.51, 8.91, 32.56, -1.450000, 146252 -CTUN, 587, 0.00, 87.09, 0.000000, 0.00, 63, 168, 547, 0 -ATT, 7.79, 7.27, -35.00, -31.23, 0.10, 24.12, 23.83 -MOT, 1551, 1610, 1502, 1598 -CTUN, 587, 0.00, 87.26, 0.000000, 0.00, 64, 169, 551, 0 -ATT, 7.79, 7.28, -35.00, -31.40, 0.00, 24.02, 23.83 -MOT, 1537, 1637, 1515, 1590 -GPS, 3, 109293400, 1774, 10, 1.65, -39.4905407, 176.7496632, 87.79, 129.82, 9.05, 32.62, -1.450000, 146452 -CTUN, 587, 0.00, 87.40, 0.000000, 0.00, 64, 173, 550, 0 -ATT, 8.00, 7.43, -35.00, -31.42, 0.00, 24.04, 23.83 -MOT, 1517, 1652, 1541, 1564 -CTUN, 586, 0.00, 87.93, 0.000000, 0.00, 63, 177, 549, 0 -ATT, 8.00, 7.41, -35.00, -30.98, 0.00, 24.19, 23.83 -MOT, 1511, 1647, 1499, 1607 -GPS, 3, 109293600, 1774, 10, 1.65, -39.4905265, 176.7496747, 88.13, 130.15, 9.29, 32.35, -1.490000, 146652 -CTUN, 587, 0.00, 87.67, 0.000000, 0.00, 57, 188, 544, 0 -ATT, 8.00, 7.56, -35.00, -29.53, 0.10, 24.30, 23.83 -MOT, 1541, 1624, 1578, 1512 -CTUN, 587, 0.00, 88.04, 0.000000, 0.00, 55, 208, 542, 0 -ATT, 8.00, 7.02, -35.00, -29.15, 0.00, 24.27, 23.83 -MOT, 1525, 1631, 1477, 1606 -GPS, 3, 109293800, 1774, 10, 1.65, -39.4905122, 176.7496863, 88.53, 130.47, 9.38, 32.09, -1.570000, 146853 -CTUN, 586, 0.00, 88.01, 0.000000, 0.00, 52, 230, 538, 0 -ATT, 8.00, 6.87, -35.00, -28.52, 0.10, 24.49, 23.83 -MOT, 1494, 1647, 1524, 1564 -CTUN, 587, 0.00, 88.36, 0.000000, 0.00, 52, 230, 539, 0 -ATT, 8.00, 6.87, -35.00, -28.73, 0.00, 24.48, 23.83 -MOT, 1537, 1609, 1506, 1585 -DU32, 7, 270713 -CURR, 540, 336640, 1493, 4220, 4876, 628.0048 -GPS, 3, 109294000, 1774, 10, 1.65, -39.4904974, 176.7496983, 88.97, 130.89, 9.64, 32.40, -1.820000, 147053 -CTUN, 587, 0.00, 87.86, 0.000000, 0.00, 55, 235, 542, 0 -ATT, 7.79, 6.60, -35.00, -29.34, 0.20, 24.59, 23.83 -MOT, 1534, 1611, 1496, 1603 -CTUN, 585, 0.00, 88.65, 0.000000, 0.00, 57, 230, 543, 0 -ATT, 8.00, 6.92, -35.00, -30.15, 0.10, 24.62, 23.83 -MOT, 1511, 1636, 1551, 1553 -GPS, 3, 109294200, 1774, 10, 1.65, -39.4904825, 176.7497103, 89.36, 131.34, 9.71, 32.28, -2.020000, 147253 -CTUN, 587, 0.00, 89.67, 0.000000, 0.00, 62, 215, 548, 0 -ATT, 7.79, 6.63, -35.00, -31.43, 0.00, 24.54, 23.83 -MOT, 1546, 1610, 1557, 1559 -CTUN, 587, 0.00, 89.84, 0.000000, 0.00, 67, 199, 554, 0 -ATT, 7.57, 6.63, -35.00, -32.14, 0.20, 24.50, 23.83 -MOT, 1534, 1633, 1553, 1571 -GPS, 3, 109294400, 1774, 10, 1.65, -39.4904677, 176.7497220, 89.82, 131.77, 9.64, 31.44, -2.040000, 147453 -CTUN, 586, 0.00, 89.40, 0.000000, 0.00, 69, 183, 555, 0 -ATT, 7.35, 6.65, -35.00, -32.61, 0.00, 24.38, 23.83 -MOT, 1513, 1657, 1529, 1592 -CTUN, 586, 0.00, 89.89, 0.000000, 0.00, 69, 178, 556, 0 -ATT, 6.70, 6.63, -35.00, -32.62, 0.10, 24.38, 23.83 -MOT, 1560, 1610, 1555, 1572 -GPS, 3, 109294600, 1774, 10, 1.65, -39.4904528, 176.7497332, 90.17, 132.17, 9.50, 30.37, -1.900000, 147653 -CTUN, 586, 0.00, 89.89, 0.000000, 0.00, 71, 168, 557, 0 -ATT, 6.49, 6.40, -35.00, -33.12, 0.00, 24.42, 23.83 -MOT, 1555, 1614, 1532, 1600 -CTUN, 586, 0.00, 89.77, 0.000000, 0.00, 73, 148, 559, 0 -ATT, 6.49, 6.32, -35.00, -33.66, 0.10, 24.34, 23.83 -MOT, 1557, 1615, 1546, 1589 -GPS, 3, 109294800, 1774, 10, 1.65, -39.4904378, 176.7497439, 90.46, 132.53, 9.48, 29.13, -1.750000, 147854 -CTUN, 585, 0.00, 90.01, 0.000000, 0.00, 76, 135, 561, 0 -ATT, 6.70, 6.41, -35.00, -34.09, 0.00, 24.35, 23.83 -MOT, 1537, 1643, 1554, 1580 -CTUN, 586, 0.00, 91.14, 0.000000, 0.00, 77, 122, 563, 0 -ATT, 6.27, 6.47, -35.00, -34.26, 0.00, 24.33, 23.83 -MOT, 1524, 1656, 1544, 1595 -DU32, 7, 270713 -CURR, 562, 342168, 1498, 4220, 4897, 639.7413 -GPS, 3, 109295000, 1774, 10, 1.65, -39.4904229, 176.7497544, 90.72, 132.84, 9.40, 28.66, -1.580000, 148054 -CTUN, 586, 0.00, 90.95, 0.000000, 0.00, 74, 107, 561, 0 -ATT, 6.49, 6.18, -35.00, -33.60, 0.10, 24.34, 23.83 -MOT, 1550, 1633, 1548, 1583 -CTUN, 587, 0.00, 91.12, 0.000000, 0.00, 72, 111, 559, 0 -ATT, 6.27, 6.60, -35.00, -33.18, 0.00, 24.27, 23.83 -MOT, 1555, 1623, 1531, 1598 -GPS, 3, 109295200, 1774, 10, 1.65, -39.4904080, 176.7497646, 90.98, 133.07, 9.38, 27.76, -1.330000, 148254 -CTUN, 587, 0.00, 90.30, 0.000000, 0.00, 70, 105, 557, 0 -ATT, 5.84, 6.70, -35.00, -32.62, 0.10, 24.34, 23.83 -MOT, 1556, 1617, 1531, 1596 -CTUN, 587, 0.00, 90.62, 0.000000, 0.00, 68, 103, 555, 0 -ATT, 5.40, 6.55, -35.00, -32.36, 0.10, 24.44, 23.83 -MOT, 1511, 1657, 1562, 1560 -GPS, 3, 109295400, 1774, 10, 1.65, -39.4903930, 176.7497748, 91.15, 133.27, 9.47, 27.38, -1.210000, 148455 -CTUN, 586, 0.00, 90.98, 0.000000, 0.00, 66, 105, 553, 0 -ATT, 5.40, 5.95, -35.00, -32.00, 0.00, 24.51, 23.83 -MOT, 1545, 1627, 1526, 1589 -CTUN, 587, 0.00, 90.92, 0.000000, 0.00, 63, 109, 550, 0 -ATT, 5.40, 5.75, -35.00, -31.30, 0.10, 24.48, 23.83 -MOT, 1532, 1631, 1532, 1583 -GPS, 3, 109295600, 1774, 10, 1.65, -39.4903776, 176.7497850, 91.35, 133.50, 9.59, 27.09, -1.180000, 148655 -CTUN, 587, 0.00, 90.75, 0.000000, 0.00, 61, 113, 548, 0 -ATT, 5.40, 5.62, -35.00, -30.90, 0.00, 24.41, 23.83 -MOT, 1535, 1628, 1514, 1591 -CTUN, 586, 0.00, 91.09, 0.000000, 0.00, 59, 113, 545, 0 -ATT, 5.62, 5.64, -35.00, -30.62, 0.00, 24.39, 23.83 -MOT, 1520, 1633, 1528, 1578 -GPS, 3, 109295800, 1774, 10, 1.65, -39.4903621, 176.7497952, 91.53, 133.73, 9.70, 26.89, -1.190000, 148855 -CTUN, 586, 0.00, 91.17, 0.000000, 0.00, 58, 115, 544, 0 -ATT, 5.62, 5.79, -35.00, -30.28, 0.20, 24.35, 23.83 -MOT, 1529, 1631, 1528, 1569 -CTUN, 587, 0.00, 91.69, 0.000000, 0.00, 58, 116, 545, 0 -ATT, 5.40, 5.74, -35.00, -30.24, 0.20, 24.39, 23.83 -MOT, 1476, 1665, 1532, 1578 -DU32, 7, 270713 -CURR, 544, 347690, 1484, 4202, 4940, 651.5557 -GPS, 3, 109296000, 1774, 10, 1.65, -39.4903463, 176.7498054, 91.79, 133.97, 9.83, 26.38, -1.240000, 149075 -CTUN, 587, 0.00, 91.80, 0.000000, 0.00, 57, 120, 544, 0 -ATT, 6.27, 5.60, -35.00, -30.26, 0.00, 24.47, 23.83 -MOT, 1532, 1622, 1545, 1560 -CTUN, 587, 0.00, 91.60, 0.000000, 0.00, 56, 116, 543, 0 -ATT, 6.27, 5.47, -35.00, -29.85, 0.00, 24.44, 23.83 -MOT, 1551, 1607, 1511, 1582 -GPS, 3, 109296200, 1774, 10, 1.65, -39.4903304, 176.7498155, 92.01, 134.24, 9.85, 26.26, -1.280000, 149256 -CTUN, 586, 0.00, 91.59, 0.000000, 0.00, 57, 119, 543, 0 -ATT, 6.27, 6.06, -35.00, -30.02, 0.00, 24.34, 23.83 -MOT, 1524, 1632, 1492, 1598 -CTUN, 586, 0.00, 91.84, 0.000000, 0.00, 57, 115, 543, 0 -ATT, 6.27, 6.51, -35.00, -30.13, 0.00, 24.27, 23.83 -MOT, 1545, 1614, 1514, 1579 -GPS, 3, 109296400, 1774, 10, 1.65, -39.4903144, 176.7498253, 92.22, 134.50, 9.82, 25.62, -1.290000, 149456 -CTUN, 587, 0.00, 92.21, 0.000000, 0.00, 60, 108, 546, 0 -ATT, 6.27, 6.64, -35.00, -30.65, 0.20, 24.19, 23.83 -MOT, 1521, 1641, 1549, 1552 -CTUN, 586, 0.00, 92.23, 0.000000, 0.00, 59, 102, 545, 0 -ATT, 6.70, 5.47, -35.00, -30.47, 0.00, 24.22, 23.83 -MOT, 1546, 1615, 1504, 1590 -GPS, 3, 109296600, 1774, 10, 1.65, -39.4902985, 176.7498352, 92.43, 134.76, 9.80, 25.70, -1.250000, 149656 -CTUN, 587, 0.00, 92.25, 0.000000, 0.00, 60, 106, 547, 0 -ATT, 6.49, 6.37, -35.00, -30.55, 0.00, 24.15, 23.83 -MOT, 1504, 1647, 1529, 1582 -CTUN, 587, 0.00, 92.50, 0.000000, 0.00, 56, 114, 543, 0 -ATT, 6.70, 6.21, -35.00, -29.70, 0.00, 24.39, 23.83 -MOT, 1571, 1581, 1520, 1581 -GPS, 3, 109296800, 1774, 10, 1.65, -39.4902827, 176.7498451, 92.66, 134.99, 9.72, 25.71, -1.120000, 149857 -CTUN, 586, 0.00, 92.58, 0.000000, 0.00, 57, 123, 543, 0 -ATT, 6.70, 6.49, -35.00, -29.83, 0.00, 24.36, 23.83 -MOT, 1504, 1647, 1473, 1613 -CTUN, 587, 0.00, 92.35, 0.000000, 0.00, 55, 135, 542, 0 -ATT, 6.49, 6.60, -35.00, -29.38, 0.00, 24.37, 23.83 -MOT, 1516, 1637, 1530, 1566 -DU32, 7, 270713 -CURR, 541, 353130, 1468, 4215, 4918, 663.2684 -GPS, 3, 109297000, 1774, 10, 1.65, -39.4902666, 176.7498551, 92.92, 135.24, 9.89, 25.79, -1.190000, 150057 -CTUN, 586, 0.00, 93.06, 0.000000, 0.00, 52, 150, 538, 0 -ATT, 6.49, 6.41, -35.00, -28.65, 0.20, 24.26, 23.83 -MOT, 1497, 1655, 1501, 1573 -CTUN, 586, 0.00, 93.13, 0.000000, 0.00, 50, 177, 536, 0 -ATT, 6.70, 6.07, -35.00, -28.17, 0.20, 24.19, 23.83 -MOT, 1522, 1627, 1512, 1566 -GPS, 3, 109297200, 1774, 10, 1.65, -39.4902503, 176.7498652, 93.28, 135.58, 9.95, 25.86, -1.390000, 150257 -CTUN, 586, 0.00, 93.49, 0.000000, 0.00, 49, 195, 535, 0 -ATT, 6.49, 6.23, -35.00, -27.80, 0.00, 24.37, 23.83 -MOT, 1494, 1639, 1529, 1555 -CTUN, 586, 0.00, 93.54, 0.000000, 0.00, 48, 209, 534, 0 -ATT, 6.70, 5.89, -35.00, -27.74, 0.00, 24.42, 23.83 -MOT, 1512, 1622, 1472, 1601 -GPS, 3, 109297400, 1774, 10, 1.65, -39.4902339, 176.7498754, 93.73, 135.96, 10.12, 25.78, -1.660000, 150457 -CTUN, 586, 0.00, 93.31, 0.000000, 0.00, 48, 222, 535, 0 -ATT, 6.49, 5.97, -35.00, -27.94, 0.10, 24.53, 23.83 -MOT, 1562, 1573, 1531, 1559 -CTUN, 587, 0.00, 94.35, 0.000000, 0.00, 53, 210, 540, 0 -ATT, 6.49, 6.27, -35.00, -28.89, 0.00, 24.61, 23.83 -MOT, 1484, 1651, 1515, 1582 -GPS, 3, 109297600, 1774, 10, 1.65, -39.4902172, 176.7498856, 94.18, 136.42, 10.15, 25.69, -1.940000, 150657 -CTUN, 587, 0.00, 94.35, 0.000000, 0.00, 53, 211, 540, 0 -ATT, 6.70, 6.70, -35.00, -29.10, 0.00, 24.68, 23.83 -MOT, 1509, 1636, 1537, 1559 -CTUN, 586, 0.00, 94.14, 0.000000, 0.00, 55, 210, 541, 0 -ATT, 6.70, 6.68, -35.00, -29.54, 0.00, 24.69, 23.83 -MOT, 1537, 1607, 1524, 1579 -GPS, 3, 109297800, 1774, 10, 1.65, -39.4902007, 176.7498958, 94.64, 136.89, 10.07, 25.93, -1.980000, 150858 -CTUN, 586, 0.00, 95.08, 0.000000, 0.00, 58, 210, 544, 0 -ATT, 6.70, 6.99, -35.00, -30.28, 0.00, 24.75, 23.83 -MOT, 1505, 1632, 1530, 1586 -CTUN, 586, 0.00, 94.72, 0.000000, 0.00, 59, 211, 545, 0 -ATT, 6.49, 6.86, -34.78, -30.34, 0.00, 24.94, 23.83 -MOT, 1532, 1613, 1534, 1582 -DU32, 7, 270713 -CURR, 547, 358519, 1477, 4201, 4897, 674.8842 -GPS, 3, 109298000, 1774, 10, 1.65, -39.4901845, 176.7499060, 95.11, 137.35, 9.95, 26.21, -2.000000, 151058 -CTUN, 586, 0.00, 95.09, 0.000000, 0.00, 61, 206, 547, 0 -ATT, 6.70, 6.76, -35.00, -30.89, 0.00, 24.97, 23.83 -MOT, 1526, 1625, 1541, 1574 -CTUN, 586, 0.00, 94.91, 0.000000, 0.00, 61, 203, 547, 0 -ATT, 6.49, 6.55, -35.00, -30.97, 0.00, 24.90, 23.83 -MOT, 1550, 1602, 1534, 1582 -GPS, 3, 109298200, 1774, 10, 1.65, -39.4901683, 176.7499162, 95.53, 137.80, 9.92, 26.35, -2.020000, 151258 -CTUN, 587, 0.00, 95.64, 0.000000, 0.00, 64, 196, 551, 0 -ATT, 6.49, 6.38, -35.00, -31.66, 0.00, 24.89, 23.83 -MOT, 1538, 1617, 1541, 1584 -CTUN, 587, 0.00, 95.77, 0.000000, 0.00, 67, 179, 554, 0 -ATT, 6.05, 5.97, -35.00, -32.54, 0.20, 24.61, 23.83 -MOT, 1562, 1611, 1518, 1597 -GPS, 3, 109298400, 1774, 10, 1.65, -39.4901521, 176.7499265, 95.92, 138.24, 9.94, 26.39, -2.020000, 151460 -CTUN, 586, 0.00, 96.53, 0.000000, 0.00, 68, 164, 554, 0 -ATT, 6.05, 5.83, -35.00, -32.66, 0.10, 24.42, 23.83 -MOT, 1559, 1613, 1555, 1564 -CTUN, 587, 0.00, 96.28, 0.000000, 0.00, 70, 159, 556, 0 -ATT, 5.19, 5.95, -35.00, -32.84, 0.00, 24.24, 23.83 -MOT, 1534, 1644, 1504, 1610 -GPS, 3, 109298600, 1774, 10, 1.65, -39.4901362, 176.7499365, 96.31, 138.61, 9.82, 26.02, -1.840000, 151660 -CTUN, 587, 0.00, 96.09, 0.000000, 0.00, 70, 157, 557, 0 -ATT, 4.76, 5.39, -35.00, -33.05, 0.00, 24.16, 23.83 -MOT, 1546, 1631, 1536, 1588 -CTUN, 586, 0.00, 96.98, 0.000000, 0.00, 69, 153, 555, 0 -ATT, 5.19, 5.13, -35.00, -32.95, 0.00, 24.14, 23.83 -MOT, 1546, 1628, 1557, 1564 -GPS, 3, 109298800, 1774, 10, 1.65, -39.4901201, 176.7499464, 96.65, 138.96, 9.89, 25.36, -1.710000, 151860 -CTUN, 586, 0.00, 96.27, 0.000000, 0.00, 70, 142, 556, 0 -ATT, 5.62, 5.20, -35.00, -33.03, 0.00, 24.10, 23.83 -MOT, 1547, 1623, 1526, 1601 -CTUN, 587, 0.00, 96.81, 0.000000, 0.00, 71, 127, 557, 0 -ATT, 5.84, 5.23, -35.00, -33.34, 0.00, 24.03, 23.83 -MOT, 1528, 1649, 1548, 1576 -DU32, 7, 270713 -CURR, 558, 364051, 1485, 4274, 4940, 686.6675 -GPS, 3, 109299000, 1774, 10, 1.65, -39.4901039, 176.7499562, 96.92, 139.29, 9.90, 25.02, -1.640000, 152060 -CTUN, 586, 0.00, 97.59, 0.000000, 0.00, 71, 121, 557, 0 -ATT, 6.05, 5.17, -35.00, -33.36, 0.00, 23.95, 23.83 -MOT, 1546, 1634, 1553, 1568 -CTUN, 586, 0.00, 97.13, 0.000000, 0.00, 72, 113, 558, 0 -ATT, 5.98, 5.22, -35.00, -33.44, 0.10, 23.92, 23.83 -MOT, 1550, 1629, 1550, 1574 -GPS, 3, 109299200, 1774, 10, 1.65, -39.4900878, 176.7499657, 97.21, 139.57, 9.84, 24.56, -1.460000, 152260 -CTUN, 587, 0.00, 97.79, 0.000000, 0.00, 72, 98, 559, 0 -ATT, 6.05, 5.29, -35.00, -33.40, 0.10, 23.80, 23.83 -MOT, 1548, 1640, 1521, 1596 -CTUN, 586, 0.00, 97.52, 0.000000, 0.00, 71, 96, 558, 0 -ATT, 6.05, 5.51, -35.00, -33.30, 0.00, 23.78, 23.83 -MOT, 1542, 1639, 1555, 1567 -GPS, 3, 109299400, 1774, 10, 1.65, -39.4900715, 176.7499749, 97.45, 139.81, 9.90, 23.61, -1.310000, 152461 -CTUN, 587, 0.00, 97.33, 0.000000, 0.00, 72, 76, 559, 0 -ATT, 6.05, 5.51, -35.00, -33.46, 0.00, 23.64, 23.83 -MOT, 1554, 1633, 1553, 1568 -CTUN, 586, 0.00, 98.06, 0.000000, 0.00, 73, 63, 559, 0 -ATT, 6.05, 5.61, -35.00, -33.69, 0.00, 23.67, 23.83 -MOT, 1526, 1653, 1548, 1579 -GPS, 3, 109299600, 1774, 10, 1.65, -39.4900553, 176.7499838, 97.61, 140.01, 9.83, 22.69, -1.150000, 152661 -CTUN, 586, 0.00, 97.76, 0.000000, 0.00, 73, 48, 560, 0 -ATT, 6.05, 5.50, -35.00, -33.42, 0.10, 23.77, 23.83 -MOT, 1564, 1618, 1536, 1593 -CTUN, 586, 0.00, 97.92, 0.000000, 0.00, 71, 47, 557, 0 -ATT, 6.27, 5.55, -35.00, -33.18, 0.10, 23.91, 23.83 -MOT, 1545, 1632, 1546, 1578 -GPS, 3, 109299800, 1774, 10, 1.65, -39.4900391, 176.7499923, 97.74, 140.17, 9.73, 22.00, -0.910000, 152862 -CTUN, 586, 0.00, 98.20, 0.000000, 0.00, 70, 42, 556, 0 -ATT, 6.27, 5.41, -35.00, -32.87, 0.20, 24.04, 23.83 -MOT, 1510, 1660, 1535, 1589 -CTUN, 586, 0.00, 98.04, 0.000000, 0.00, 66, 45, 552, 0 -ATT, 6.27, 5.55, -35.00, -31.94, 0.00, 24.31, 23.83 -MOT, 1524, 1638, 1537, 1584 -DU32, 7, 270713 -CURR, 556, 369629, 1471, 4241, 4940, 698.4905 -GPS, 3, 109300000, 1774, 10, 1.65, -39.4900229, 176.7500003, 97.88, 140.26, 9.70, 20.87, -0.710000, 153062 -CTUN, 590, 0.00, 97.56, 0.000000, 0.00, 63, 58, 554, 0 -ATT, 6.27, 5.51, -35.00, -31.13, 0.10, 24.59, 23.83 -MOT, 1550, 1617, 1533, 1591 -CTUN, 590, 0.00, 98.49, 0.000000, 0.00, 61, 59, 551, 0 -ATT, 6.27, 5.79, -35.00, -30.78, 0.20, 24.68, 23.83 -MOT, 1497, 1658, 1529, 1590 -GPS, 3, 109300200, 1774, 10, 1.65, -39.4900066, 176.7500084, 98.01, 140.37, 9.74, 20.73, -0.700000, 153262 -CTUN, 592, 0.00, 98.23, 0.000000, 0.00, 60, 55, 550, 0 -ATT, 6.27, 5.94, -35.00, -30.51, 0.20, 24.76, 23.83 -MOT, 1513, 1642, 1544, 1575 -CTUN, 598, 0.00, 97.99, 0.000000, 0.00, 60, 56, 561, 0 -ATT, 6.27, 6.12, -35.00, -30.07, 0.10, 24.81, 23.83 -MOT, 1534, 1641, 1532, 1607 -GPS, 3, 109300400, 1774, 10, 1.65, -39.4899902, 176.7500163, 98.15, 140.51, 9.74, 20.44, -0.720000, 153463 -CTUN, 605, 0.00, 98.52, 0.000000, 0.00, 60, 60, 570, 0 -ATT, 6.05, 6.21, -35.00, -29.77, 0.10, 24.78, 23.83 -MOT, 1570, 1624, 1530, 1619 -CTUN, 605, 0.00, 97.75, 0.000000, 0.00, 59, 74, 569, 0 -ATT, 6.27, 6.57, -35.00, -29.47, 0.00, 24.68, 23.83 -MOT, 1522, 1678, 1555, 1583 -GPS, 3, 109300600, 1774, 10, 1.65, -39.4899737, 176.7500242, 98.30, 140.65, 9.76, 20.23, -0.710000, 153662 -CTUN, 605, 0.00, 98.48, 0.000000, 0.00, 57, 83, 567, 0 -ATT, 6.27, 6.60, -35.00, -29.11, 0.10, 24.66, 23.83 -MOT, 1555, 1637, 1530, 1612 -CTUN, 605, 0.00, 98.99, 0.000000, 0.00, 57, 90, 567, 0 -ATT, 6.27, 6.56, -35.00, -28.94, 0.20, 24.67, 23.83 -MOT, 1533, 1658, 1544, 1598 -GPS, 3, 109300800, 1774, 10, 1.65, -39.4899574, 176.7500321, 98.52, 140.80, 9.70, 20.48, -0.800000, 153863 -CTUN, 605, 0.00, 98.34, 0.000000, 0.00, 56, 105, 566, 0 -ATT, 6.27, 6.55, -35.00, -28.95, 0.00, 24.75, 23.83 -MOT, 1533, 1651, 1560, 1586 -CTUN, 605, 0.00, 98.85, 0.000000, 0.00, 57, 103, 564, 0 -ATT, 6.27, 6.44, -35.00, -29.24, 0.00, 24.75, 23.83 -MOT, 1546, 1642, 1541, 1594 -DU32, 7, 270713 -CURR, 569, 375254, 1486, 4500, 4897, 710.8842 -PM, 0, 0, 0, 1000, 10201, 0, 0, 0, 0 -GPS, 3, 109301000, 1774, 10, 1.65, -39.4899410, 176.7500401, 98.75, 141.02, 9.75, 20.72, -0.930000, 154063 -CTUN, 605, 0.00, 99.03, 0.000000, 0.00, 58, 109, 568, 0 -ATT, 6.27, 6.30, -35.00, -29.39, 0.00, 24.88, 23.83 -MOT, 1544, 1644, 1552, 1596 -CTUN, 605, 0.00, 99.23, 0.000000, 0.00, 59, 105, 569, 0 -ATT, 6.27, 6.11, -35.00, -29.60, 0.00, 24.90, 23.83 -MOT, 1537, 1651, 1545, 1607 -GPS, 3, 109301200, 1774, 10, 1.65, -39.4899245, 176.7500481, 99.02, 141.26, 9.73, 20.51, -1.020000, 154263 -CTUN, 605, 0.00, 98.87, 0.000000, 0.00, 59, 112, 569, 0 -ATT, 6.27, 5.98, -35.00, -29.56, 0.20, 24.91, 23.83 -MOT, 1541, 1653, 1547, 1598 -CTUN, 605, 0.00, 99.39, 0.000000, 0.00, 59, 114, 569, 0 -ATT, 6.27, 5.89, -35.00, -29.55, 0.00, 24.89, 23.83 -MOT, 1547, 1642, 1556, 1594 -GPS, 3, 109301400, 1774, 10, 1.65, -39.4899081, 176.7500560, 99.27, 141.50, 9.65, 20.51, -1.060000, 154463 -CTUN, 605, 0.00, 99.20, 0.000000, 0.00, 58, 119, 568, 0 -ATT, 6.19, 5.88, -35.00, -29.47, 0.10, 24.90, 23.83 -MOT, 1544, 1646, 1546, 1601 -CTUN, 605, 0.00, 99.20, 0.000000, 0.00, 58, 128, 568, 0 -ATT, 6.27, 5.93, -35.00, -29.45, 0.10, 24.88, 23.83 -MOT, 1546, 1647, 1541, 1602 -GPS, 3, 109301600, 1774, 10, 1.65, -39.4898918, 176.7500637, 99.53, 141.78, 9.57, 20.46, -1.130000, 154664 -CTUN, 605, 0.00, 100.01, 0.000000, 0.00, 57, 132, 567, 0 -ATT, 6.27, 6.40, -35.00, -28.86, 0.00, 24.77, 23.83 -MOT, 1537, 1661, 1526, 1609 -CTUN, 605, 0.00, 99.55, 0.000000, 0.00, 55, 151, 565, 0 -ATT, 6.27, 6.41, -35.00, -28.58, 0.00, 24.70, 23.83 -MOT, 1555, 1633, 1530, 1609 -GPS, 3, 109301800, 1774, 10, 1.65, -39.4898755, 176.7500715, 99.86, 142.05, 9.59, 20.35, -1.210000, 154864 -CTUN, 605, 0.00, 100.11, 0.000000, 0.00, 54, 151, 564, 0 -ATT, 6.05, 6.77, -35.00, -28.44, 0.00, 24.61, 23.83 -MOT, 1551, 1640, 1549, 1583 -CTUN, 605, 0.00, 100.59, 0.000000, 0.00, 54, 161, 564, 0 -ATT, 6.27, 6.99, -35.00, -28.07, 0.00, 24.59, 23.83 -MOT, 1540, 1653, 1516, 1612 -DU32, 7, 270713 -CURR, 563, 380921, 1467, 4529, 4897, 723.4895 -GPS, 3, 109302000, 1774, 10, 1.65, -39.4898594, 176.7500793, 100.23, 142.39, 9.46, 20.69, -1.390000, 155065 -CTUN, 605, 0.00, 100.44, 0.000000, 0.00, 53, 177, 563, 0 -ATT, 6.27, 7.00, -35.00, -27.81, 0.10, 24.63, 23.83 -MOT, 1547, 1641, 1525, 1606 -ERR, 9, 1 -CTUN, 605, 0.00, 100.60, 0.000000, 0.00, 53, 182, 563, 0 -ATT, 6.49, 6.53, -35.00, -27.92, 0.00, 24.64, 23.83 -MOT, 1525, 1657, 1525, 1611 -GPS, 3, 109302200, 1774, 10, 1.65, -39.4898436, 176.7500872, 100.65, 142.73, 9.39, 21.39, -1.550000, 155264 -CTUN, 605, 0.00, 100.74, 0.000000, 0.00, 52, 202, 562, 0 -ATT, 6.49, 6.15, -35.00, -27.90, 0.00, 24.78, 23.83 -MOT, 1545, 1633, 1553, 1586 -CTUN, 605, 0.00, 101.14, 0.000000, 0.00, 51, 208, 561, 0 -ATT, 6.70, 5.61, -35.00, -27.66, 0.00, 25.02, 23.83 -MOT, 1552, 1621, 1528, 1613 -GPS, 3, 109302400, 1774, 10, 1.65, -39.4898280, 176.7500952, 101.12, 143.13, 9.32, 21.66, -1.760000, 155465 -CTUN, 605, 0.00, 101.16, 0.000000, 0.00, 51, 223, 561, 0 -ATT, 6.49, 5.65, -35.00, -27.84, 0.00, 25.08, 23.83 -MOT, 1528, 1649, 1550, 1587 -CTUN, 605, 0.00, 101.28, 0.000000, 0.00, 53, 232, 563, 0 -ATT, 6.49, 5.75, -35.00, -28.07, 0.00, 25.01, 23.83 -MOT, 1511, 1667, 1521, 1616 -GPS, 3, 109302600, 1774, 10, 1.65, -39.4898124, 176.7501031, 101.61, 143.60, 9.19, 21.74, -1.960000, 155665 -CTUN, 605, 0.00, 101.81, 0.000000, 0.00, 52, 237, 562, 0 -ATT, 6.49, 5.68, -35.00, -28.10, 0.00, 24.88, 23.83 -MOT, 1529, 1657, 1546, 1584 -CTUN, 605, 0.00, 101.81, 0.000000, 0.00, 53, 241, 563, 0 -ATT, 6.41, 5.29, -35.00, -28.35, 0.00, 24.77, 23.83 -MOT, 1550, 1635, 1524, 1610 -GPS, 3, 109302800, 1774, 10, 1.65, -39.4897970, 176.7501107, 102.13, 144.10, 9.07, 21.20, -2.100000, 155866 -CTUN, 605, 0.00, 102.30, 0.000000, 0.00, 54, 244, 564, 0 -ATT, 6.70, 6.07, -35.00, -28.52, 0.10, 24.69, 23.83 -MOT, 1539, 1647, 1562, 1575 -CTUN, 605, 0.00, 102.35, 0.000000, 0.00, 54, 245, 564, 0 -ATT, 6.41, 5.64, -35.00, -28.50, 0.10, 24.79, 23.83 -MOT, 1565, 1618, 1530, 1610 -DU32, 7, 270713 -CURR, 564, 386546, 1437, 4411, 4918, 735.9553 -GPS, 3, 109303000, 1774, 10, 1.65, -39.4897816, 176.7501182, 102.66, 144.60, 9.08, 20.98, -2.210000, 156066 -CTUN, 605, 0.00, 102.37, 0.000000, 0.00, 54, 248, 564, 0 -ATT, 6.49, 5.70, -35.00, -28.51, 0.10, 24.78, 23.83 -MOT, 1530, 1656, 1557, 1580 -CTUN, 605, 0.00, 103.30, 0.000000, 0.00, 56, 254, 566, 0 -ATT, 6.70, 5.99, -35.00, -28.96, 0.10, 24.70, 23.83 -MOT, 1525, 1664, 1528, 1612 -GPS, 3, 109303200, 1774, 10, 1.65, -39.4897662, 176.7501255, 103.19, 145.11, 9.01, 20.23, -2.290000, 156266 -CTUN, 605, 0.00, 103.28, 0.000000, 0.00, 56, 247, 566, 0 -ATT, 6.49, 5.58, -35.00, -28.98, 0.10, 24.69, 23.83 -MOT, 1541, 1648, 1530, 1610 -CTUN, 605, 0.00, 103.66, 0.000000, 0.00, 56, 257, 566, 0 -ATT, 6.49, 5.93, -35.00, -29.06, 0.10, 24.59, 23.83 -MOT, 1534, 1661, 1555, 1581 -GPS, 3, 109303400, 1774, 10, 1.65, -39.4897510, 176.7501327, 103.75, 145.63, 8.91, 20.35, -2.360000, 156466 -CTUN, 605, 0.00, 104.04, 0.000000, 0.00, 59, 254, 569, 0 -ATT, 6.70, 6.21, -35.00, -29.66, 0.20, 24.37, 23.83 -MOT, 1549, 1651, 1535, 1605 -CTUN, 605, 0.00, 103.82, 0.000000, 0.00, 61, 242, 571, 0 -ATT, 6.49, 6.32, -35.00, -30.06, 0.00, 24.23, 23.83 -MOT, 1572, 1631, 1555, 1588 -GPS, 3, 109303600, 1774, 10, 1.65, -39.4897360, 176.7501398, 104.29, 146.17, 8.83, 20.26, -2.450000, 156667 -CTUN, 605, 0.00, 104.80, 0.000000, 0.00, 63, 239, 573, 0 -ATT, 6.49, 6.17, -35.00, -30.66, 0.00, 24.10, 23.83 -MOT, 1547, 1659, 1537, 1614 -CTUN, 605, 0.00, 104.79, 0.000000, 0.00, 65, 226, 575, 0 -ATT, 6.70, 5.97, -35.00, -31.10, 0.00, 24.06, 23.83 -MOT, 1582, 1633, 1552, 1596 -GPS, 3, 109303800, 1774, 10, 1.65, -39.4897211, 176.7501467, 104.82, 146.68, 8.74, 20.03, -2.410000, 156867 -CTUN, 605, 0.00, 104.84, 0.000000, 0.00, 68, 215, 578, 0 -ATT, 6.70, 6.23, -35.00, -31.56, 0.00, 23.98, 23.83 -MOT, 1558, 1653, 1568, 1594 -CTUN, 605, 0.00, 104.65, 0.000000, 0.00, 70, 206, 580, 0 -ATT, 6.70, 6.15, -35.00, -31.95, 0.00, 23.92, 23.83 -MOT, 1557, 1664, 1557, 1601 -DU32, 7, 270713 -CURR, 580, 392248, 1482, 4564, 4897, 748.5086 -GPS, 3, 109304000, 1774, 10, 1.65, -39.4897063, 176.7501535, 105.25, 147.15, 8.68, 19.65, -2.260000, 157067 -CTUN, 605, 0.00, 104.73, 0.000000, 0.00, 71, 188, 581, 0 -ATT, 6.70, 6.13, -35.00, -32.19, 0.00, 23.86, 23.83 -MOT, 1564, 1661, 1567, 1592 -CTUN, 605, 0.00, 105.85, 0.000000, 0.00, 73, 181, 583, 0 -ATT, 6.70, 6.14, -35.00, -32.55, 0.00, 23.75, 23.83 -MOT, 1561, 1665, 1564, 1600 -GPS, 3, 109304200, 1774, 10, 1.65, -39.4896916, 176.7501600, 105.62, 147.57, 8.61, 18.91, -2.050000, 157267 -CTUN, 605, 0.00, 106.40, 0.000000, 0.00, 74, 171, 584, 0 -ATT, 6.70, 6.31, -35.00, -32.80, 0.00, 23.71, 23.83 -MOT, 1573, 1649, 1570, 1600 -CTUN, 605, 0.00, 106.31, 0.000000, 0.00, 74, 158, 584, 0 -ATT, 6.70, 6.24, -35.00, -32.73, 0.00, 23.76, 23.83 -MOT, 1559, 1665, 1573, 1596 -GPS, 3, 109304400, 1774, 10, 1.65, -39.4896769, 176.7501664, 106.04, 147.93, 8.58, 18.48, -1.860000, 157467 -CTUN, 605, 0.00, 106.11, 0.000000, 0.00, 73, 151, 583, 0 -ATT, 6.70, 6.22, -35.00, -32.51, 0.00, 23.84, 23.83 -MOT, 1554, 1672, 1559, 1605 -CTUN, 605, 0.00, 106.49, 0.000000, 0.00, 72, 151, 582, 0 -ATT, 6.70, 6.29, -35.00, -32.28, 0.00, 23.76, 23.83 -MOT, 1559, 1669, 1559, 1600 -GPS, 3, 109304600, 1774, 10, 1.65, -39.4896621, 176.7501725, 106.40, 148.26, 8.64, 17.80, -1.700000, 157668 -CTUN, 605, 0.00, 106.20, 0.000000, 0.00, 71, 153, 581, 0 -ATT, 6.70, 6.34, -35.00, -32.11, 0.00, 23.78, 23.83 -MOT, 1575, 1646, 1564, 1597 -CTUN, 605, 0.00, 106.26, 0.000000, 0.00, 71, 157, 581, 0 -ATT, 6.70, 6.42, -35.00, -31.99, 0.00, 23.84, 23.83 -MOT, 1564, 1655, 1556, 1607 -GPS, 3, 109304800, 1774, 10, 1.65, -39.4896471, 176.7501786, 106.70, 148.60, 8.70, 17.43, -1.650000, 157868 -CTUN, 605, 0.00, 106.80, 0.000000, 0.00, 69, 148, 579, 0 -ATT, 6.70, 6.43, -35.00, -31.63, 0.00, 23.94, 23.83 -MOT, 1546, 1672, 1571, 1587 -CTUN, 605, 0.00, 107.32, 0.000000, 0.00, 69, 145, 579, 0 -ATT, 0.00, 5.99, 0.00, -31.68, 0.00, 23.96, 23.83 -MOT, 1550, 1665, 1551, 1609 -MODE, RTL, 271 -ERR, 5, 1 -NTUN, 0.00, 1.94, 0.000000, 0.000000, 0.000000, 0.000000, 811.7078, 246.9585, 0.000000, 0.000000, 5.98, -31.63 -DU32, 7, 270713 -CURR, 578, 398064, 1493, 4659, 4918, 761.2452 -GPS, 3, 109305000, 1774, 10, 1.65, -39.4896320, 176.7501846, 107.04, 148.94, 8.76, 17.18, -1.640000, 158069 -CTUN, 0, 0.00, 107.63, 106.9908, 0.00, 77, 140, 646, 0 -ATT, 0.00, 5.96, 0.00, -31.48, 0.00, 23.80, 23.83 -MOT, 1845, 1369, 1950, 1231 -ERR, 5, 0 -NTUN, 625.49, 1.94, 1235.391, 375.9043, 476.6813, 145.0445, 813.9984, 235.1397, -337.0000, -99.00000, 2.34, 19.54 -CTUN, 605, 0.00, 106.94, 106.9908, 0.00, 124, 90, 796, 0 -ATT, 10.29, 3.61, -45.00, -35.85, 0.10, 20.72, 23.83 -MOT, 1809, 1872, 1938, 1546 -NTUN, 626.36, 1.94, 1151.688, 351.6025, 459.5132, 140.2863, 797.9639, 209.7603, -544.1852, -141.5525, 3.57, 29.62 -GPS, 3, 109305200, 1774, 10, 1.65, -39.4896170, 176.7501905, 107.29, 149.24, 8.74, 16.93, -1.590000, 158269 -CTUN, 605, 0.00, 106.79, 106.9908, 0.00, 186, 40, 945, 0 -ATT, 10.20, -3.55, -45.00, -39.79, 0.10, 18.85, 23.83 -MOT, 1656, 1950, 1918, 1370 -NTUN, 627.20, 1.94, 1068.617, 329.3184, 441.7150, 136.1244, 794.4001, 177.5082, -565.2200, -116.2072, 3.57, 30.25 -CTUN, 605, 0.00, 106.32, 106.9908, 0.00, 217, 5, 979, 0 -ATT, 10.57, -18.85, -45.00, -38.15, 0.20, 19.11, 23.83 -MOT, 1241, 1864, 1572, 1127 -NTUN, 628.04, 1.94, 986.3828, 309.9365, 423.2056, 132.9777, 799.1141, 127.5548, -608.0937, -75.46729, 5.72, 31.43 -GPS, 3, 109305400, 1774, 10, 1.65, -39.4896020, 176.7501956, 107.26, 149.42, 8.61, 14.54, -1.140000, 158469 -CTUN, 605, 0.00, 105.87, 106.9908, 0.00, 143, 7, 783, 0 -ATT, 10.57, -29.97, -45.00, -24.69, 0.20, 12.42, 22.42 -MOT, 1271, 1950, 1293, 1205 -NTUN, 628.87, 1.94, 904.1836, 294.8281, 403.5948, 131.6006, 808.8745, 50.89818, -665.1084, -5.770905, 8.66, 33.22 -CTUN, 605, 0.00, 105.89, 106.9908, 0.00, 76, 29, 563, 0 -ATT, 10.85, -34.63, -45.00, -1.94, 0.20, 358.06, 8.06 -MOT, 1471, 1950, 1276, 1503 -NTUN, 629.68, 1.94, 820.8320, 286.8574, 382.1828, 133.5620, 774.8207, -54.05908, -733.2821, 119.8125, 10.18, 35.00 -GPS, 3, 109305600, 1774, 10, 1.65, -39.4895875, 176.7501986, 107.16, 149.46, 8.19, 9.39, -0.540000, 158669 -CTUN, 605, 0.00, 106.26, 106.9908, 0.00, 92, 61, 434, 0 -ATT, 11.41, -43.35, -45.00, 22.73, 0.00, 336.87, 346.87 -MOT, 1239, 1897, 1235, 1231 -NTUN, 630.41, 1.94, 739.0469, 288.5508, 359.1792, 140.2366, 673.9511, -160.7752, -739.7587, 289.0852, 5.77, 35.00 -CTUN, 605, 0.00, 105.68, 106.9908, 0.00, 198, 59, 526, 0 -ATT, 11.41, -60.33, -45.00, 37.61, 0.00, 312.01, 322.01 -MOT, 1457, 1789, 1534, 1498 -NTUN, 631.00, 1.94, 665.0859, 303.2285, 335.7863, 153.0929, 528.2927, -232.6928, -675.9294, 481.5632, -1.75, 35.00 -GPS, 3, 109305800, 1774, 10, 1.65, -39.4895738, 176.7501986, 107.14, 149.57, 7.75, 6.05, -0.620000, 158870 -CTUN, 602, 0.00, 104.52, 106.9908, 0.00, 7, 23, 461, 0 -ATT, 10.57, -75.58, -45.00, 42.19, 0.00, 289.42, 299.42 -MOT, 1453, 1533, 1514, 1440 -NTUN, 631.42, 1.94, 604.1875, 327.0537, 313.9003, 169.9179, 340.0601, -276.2674, -534.8596, 625.2494, -8.19, 35.00 -CTUN, 603, 0.00, 103.79, 106.9908, 0.00, -147, -35, 569, 0 -ATT, 7.51, -78.57, -38.57, 42.27, 0.20, 277.52, 287.52 -MOT, 1569, 1658, 1705, 1492 -NTUN, 631.63, 1.94, 561.6563, 359.5801, 295.8232, 189.3901, 153.9193, -290.6631, -324.7706, 730.7223, -7.69, 35.00 -DU32, 7, 270713 -CURR, 792, 404695, 1483, 4564, 4834, 770.2328 -GPS, 3, 109306000, 1774, 10, 1.65, -39.4895630, 176.7501948, 106.78, 149.73, 6.42, 0.53, -0.740000, 159070 -CTUN, 605, 0.00, 103.12, 106.9899, 0.00, 0, -94, 1000, 0 -ATT, 0.00, -71.48, -27.29, 40.54, 0.10, 279.18, 286.65 -MOT, 1555, 1764, 1950, 1460 -NTUN, 631.63, 1.94, 536.4297, 394.8818, 282.6924, 208.0983, -58.25970, -292.0712, -88.00821, 772.2295, 0.24, 35.00 -CTUN, 605, 0.00, 106.12, 106.9882, 0.00, 0, -126, 1000, 0 -ATT, 0.00, -58.10, -24.22, 35.07, 0.00, 301.74, 291.74 -MOT, 1250, 1225, 1456, 1127 -NTUN, 631.38, 1.94, 533.4102, 433.6162, 277.0552, 225.2218, -224.5737, -356.2780, 210.6276, 816.2355, 19.07, 35.00 -GPS, 3, 109306200, 1774, 10, 1.65, -39.4895582, 176.7501897, 106.25, 149.82, 3.97, 348.77, -0.530000, 159270 -CTUN, 605, 0.00, 106.09, 106.9857, 0.00, 0, -137, 1000, 0 -ATT, 0.00, -48.32, -18.63, 14.08, 0.00, 338.68, 328.68 -MOT, 1381, 1158, 1818, 1127 -NTUN, 630.94, 1.94, 548.7383, 476.7510, 277.7562, 241.3182, -310.1249, -435.4615, 431.0131, 880.1295, 35.00, 13.22 -CTUN, 605, 0.00, 104.79, 106.9823, 0.00, 0, -152, 1000, 0 -ATT, 0.00, -50.72, -13.78, -9.34, 0.00, 14.05, 4.05 -MOT, 1304, 1448, 1950, 1525 -NTUN, 630.35, 1.94, 581.9023, 526.8828, 284.2108, 257.3384, -323.7206, -510.0528, 491.4966, 847.8391, 35.00, -24.24 -GPS, 3, 109306400, 1774, 10, 1.65, -39.4895599, 176.7501842, 105.86, 149.77, 2.58, 337.59, -0.120000, 159470 -CTUN, 605, 0.00, 104.49, 106.9780, 0.00, 0, -183, 1000, 0 -ATT, 0.00, -59.89, -11.08, -21.92, 0.00, 44.07, 34.07 -MOT, 1288, 1368, 1950, 1429 -NTUN, 629.71, 1.94, 618.9063, 584.3594, 291.0594, 274.8127, -288.1436, -566.4642, 469.5681, 860.1778, 26.60, -35.00 -CTUN, 605, 0.00, 105.09, 106.9729, 0.00, 0, -238, 1000, 0 -ATT, 0.00, -69.64, -7.36, -25.82, 0.10, 68.31, 58.31 -MOT, 1357, 1633, 1950, 1757 -NTUN, 629.04, 1.94, 660.0039, 645.2188, 298.7920, 292.0985, -222.1008, -606.6698, 440.8907, 875.2231, 5.06, -35.00 -GPS, 3, 109306600, 1774, 10, 1.65, -39.4895672, 176.7501787, 105.26, 149.52, 3.91, 248.20, 0.570000, 159671 -CTUN, 605, 0.00, 104.40, 106.9670, 0.00, 0, -291, 1000, 0 -ATT, 0.00, -75.51, -6.52, -25.48, 0.10, 85.05, 75.05 -MOT, 1417, 1333, 1950, 1494 -NTUN, 628.42, 1.94, 695.9180, 709.4805, 304.2365, 310.1657, -129.5809, -619.2767, 376.4690, 904.8044, -8.32, -35.00 -CTUN, 605, 0.00, 104.20, 106.9602, 0.00, -204, -354, 796, 0 -ATT, 0.00, -79.17, -2.32, -24.27, 0.10, 100.16, 90.16 -MOT, 1340, 1424, 1950, 1496 -NTUN, 627.85, 1.94, 725.6641, 773.0742, 307.6432, 327.7427, -56.93126, -609.9177, 317.2957, 927.2127, -18.69, -35.00 -GPS, 3, 109306800, 1774, 10, 1.65, -39.4895736, 176.7501698, 104.45, 149.32, 4.92, 234.60, 0.940000, 159871 -CTUN, 605, 0.00, 103.37, 106.9525, 0.00, -416, -429, 584, 0 -ATT, 0.00, -82.76, -0.93, -22.75, 0.20, 114.10, 104.10 -MOT, 1387, 1387, 1924, 1512 -NTUN, 627.38, 1.94, 746.6406, 835.2422, 308.3490, 344.9398, -6.010325, -585.3898, 265.3326, 943.3974, -26.43, -35.00 -CTUN, 605, 0.00, 103.33, 106.9441, 0.00, -582, -506, 418, 0 -ATT, 0.00, -85.49, -0.09, -21.49, 0.00, 128.14, 118.14 -MOT, 1226, 1221, 1770, 1350 -NTUN, 626.99, 1.94, 755.7734, 893.8633, 305.6556, 361.5030, 28.52817, -554.4348, 226.8805, 953.3757, -33.01, -35.00 -DU32, 7, 270713 -CURR, 358, 413577, 1521, 2393, 4855, 779.6537 -GPS, 3, 109307000, 1774, 10, 1.65, -39.4895754, 176.7501599, 103.32, 149.03, 4.51, 239.98, 1.310000, 160071 -CTUN, 605, 0.00, 103.39, 106.9347, 0.00, -618, -581, 382, 0 -ATT, 0.00, -84.61, 0.00, -21.52, 0.00, 139.35, 129.35 -MOT, 1399, 1391, 1514, 1548 -NTUN, 626.68, 1.94, 757.8672, 948.6914, 301.1791, 377.0134, 57.08358, -517.2155, 206.0006, 958.1042, -35.00, -28.66 -CTUN, 607, 0.00, 102.93, 106.9245, 0.00, -74, -645, 926, 0 -ATT, 0.00, -73.69, 0.00, -22.63, 0.10, 142.32, 132.32 -MOT, 1818, 1869, 1950, 1879 -NTUN, 626.48, 1.94, 746.1094, 996.9775, 292.9480, 391.4474, 90.83958, -440.2201, 171.7545, 964.8318, -35.00, -25.35 -GPS, 3, 109307200, 1774, 10, 1.65, -39.4895749, 176.7501501, 101.99, 148.43, 4.37, 251.64, 1.950000, 160272 -CTUN, 605, 0.00, 103.69, 106.9180, 0.00, 0, -661, 1000, 0 -ATT, 0.00, -54.33, 0.00, -22.08, 0.20, 140.34, 132.34 -MOT, 1733, 1172, 1201, 1950 -NTUN, 626.38, 1.93, 737.8672, 1041.070, 286.3396, 404.0018, 121.9568, -329.5644, 167.3953, 965.5976, -35.00, -25.28 -CTUN, 605, 0.00, 103.87, 106.9140, 0.00, 0, -623, 1000, 0 -ATT, 0.00, -17.94, 0.00, -11.57, 0.10, 136.40, 132.34 -MOT, 1215, 1187, 1127, 1410 -NTUN, 626.38, 1.93, 724.5234, 1072.183, 279.2793, 413.2902, 117.7836, -288.9771, 162.5869, 966.4189, -35.00, -28.26 -GPS, 3, 109307400, 1774, 10, 1.65, -39.4895710, 176.7501422, 100.86, 147.34, 4.23, 270.38, 3.020000, 160472 -CTUN, 603, 0.00, 101.47, 106.9105, 0.00, 0, -554, 1000, 0 -ATT, 0.00, 22.33, 0.00, 5.21, 0.00, 142.73, 132.73 -MOT, 1560, 1317, 1127, 1826 -NTUN, 626.41, 1.93, 709.4297, 1095.600, 271.7639, 419.6956, 79.96101, -329.7435, 178.4351, 963.6187, -35.00, -28.11 -CTUN, 605, 0.00, 99.43, 106.9060, 0.00, 0, -481, 1000, 0 -ATT, 0.00, 54.18, 0.00, 10.71, 0.10, 155.52, 145.52 -MOT, 1950, 1537, 1343, 1883 -NTUN, 626.43, 1.93, 689.0547, 1115.125, 262.8296, 425.3477, 29.64819, -460.4289, 189.0110, 961.6001, -35.00, -18.37 -GPS, 3, 109307600, 1774, 10, 1.65, -39.4895693, 176.7501394, 99.81, 145.84, 2.41, 280.24, 3.980000, 160672 -CTUN, 605, 0.00, 98.67, 106.9007, 0.00, 0, -489, 1000, 0 -ATT, 0.00, 78.36, 0.00, 7.95, 0.10, 163.50, 153.50 -MOT, 1950, 1288, 1470, 1732 -NTUN, 626.39, 1.93, 670.0117, 1142.883, 252.8727, 431.3414, -29.72285, -607.2896, 201.1700, 959.1302, -35.00, -7.41 -ERR, 9, 0 -CTUN, 605, 0.00, 98.99, 106.8946, 0.00, -870, -555, 130, 0 -ATT, 0.00, 91.47, 0.00, 3.49, 0.00, 156.90, 153.60 -MOT, 1401, 1127, 1319, 1197 -NTUN, 626.26, 1.93, 653.9766, 1178.352, 242.6334, 437.1830, -96.73808, -739.2455, 218.7059, 955.2841, -35.00, -4.93 -GPS, 3, 109307800, 1774, 10, 1.65, -39.4895675, 176.7501345, 98.56, 144.92, 2.56, 289.93, 3.940000, 160873 -CTUN, 608, 0.00, 99.61, 106.8876, 0.00, -870, -638, 130, 0 -ATT, 0.00, 89.13, 0.00, -0.44, 0.10, 140.66, 150.66 -MOT, 1408, 1234, 1385, 1127 -NTUN, 626.03, 1.93, 642.1602, 1225.878, 232.0130, 442.9108, -182.7007, -836.3657, 241.8324, 949.6931, -35.00, -15.65 -CTUN, 605, 0.00, 98.36, 106.8798, 0.00, -266, -719, 734, 0 -ATT, 0.00, 76.79, 0.00, -7.25, 0.00, 122.41, 132.41 -MOT, 1918, 1950, 1795, 1784 -NTUN, 625.70, 1.93, 636.7656, 1283.848, 222.1659, 447.9311, -292.3903, -909.1473, 284.9275, 937.6653, -35.00, -27.87 -DU32, 7, 270713 -CURR, 1000, 420534, 1561, 1209, 4616, 788.4255 -GPS, 3, 109308000, 1774, 10, 1.65, -39.4895668, 176.7501238, 97.16, 144.05, 4.22, 280.93, 3.990000, 161073 -CTUN, 605, 0.00, 96.31, 106.8711, 0.00, 0, -771, 1000, 0 -ATT, 0.00, 63.27, 0.00, -15.03, 0.00, 109.79, 119.79 -MOT, 1950, 1726, 1541, 1695 -NTUN, 625.21, 1.93, 639.2617, 1349.182, 214.0912, 451.8462, -451.8521, -958.2631, 348.0969, 916.0942, -35.00, -34.57 -CTUN, 605, 0.00, 96.28, 106.8615, 0.00, 0, -783, 1000, 0 -ATT, 0.00, 53.72, 0.00, -23.98, 0.20, 101.73, 111.73 -MOT, 1950, 1661, 1677, 1759 -NTUN, 624.53, 1.93, 655.6016, 1426.131, 208.8427, 454.2958, -626.0864, -965.0202, 434.5451, 878.3909, -32.12, -35.00 -GPS, 3, 109308200, 1774, 10, 1.65, -39.4895703, 176.7501095, 95.45, 142.50, 6.07, 265.26, 4.850000, 161273 -CTUN, 605, 0.00, 95.93, 106.8512, 0.00, 0, -771, 1000, 0 -ATT, 0.00, 47.13, 0.00, -32.29, 0.00, 95.11, 105.11 -MOT, 1950, 1734, 1761, 1775 -NTUN, 623.67, 1.93, 687.5273, 1506.539, 207.5861, 454.8715, -780.5817, -919.5109, 528.2693, 825.4282, -30.16, -35.00 -CTUN, 605, 0.00, 96.25, 106.8400, 0.00, 0, -740, 1000, 0 -ATT, 0.00, 40.28, 0.00, -36.26, 0.00, 91.46, 101.46 -MOT, 1950, 1659, 1611, 1797 -NTUN, 622.63, 1.93, 737.8516, 1587.854, 210.7045, 453.4353, -946.8992, -835.1133, 619.0580, 759.7152, -28.77, -35.00 -GPS, 3, 109308400, 1774, 10, 1.65, -39.4895771, 176.7500967, 93.96, 140.71, 6.59, 243.25, 5.700000, 161473 -CTUN, 605, 0.00, 95.83, 106.8279, 0.00, 0, -677, 1000, 0 -ATT, 0.00, 34.75, 0.00, -39.16, 0.00, 87.43, 97.43 -MOT, 1950, 1661, 1644, 1752 -NTUN, 621.45, 1.93, 802.8945, 1662.299, 217.4636, 450.2328, -1082.753, -724.8730, 698.9538, 686.9234, -29.36, -35.00 -CTUN, 605, 0.00, 95.55, 106.8150, 0.00, 0, -618, 1000, 0 -ATT, 0.00, 32.05, 0.00, -41.19, 0.00, 82.67, 92.67 -MOT, 1950, 1651, 1695, 1649 -NTUN, 620.15, 1.93, 885.1250, 1723.182, 228.4530, 444.7575, -1165.760, -598.9265, 761.4490, 616.9240, -28.86, -34.68 -GPS, 3, 109308600, 1774, 10, 1.65, -39.4895889, 176.7500861, 92.84, 139.21, 7.59, 219.65, 5.950000, 161674 -CTUN, 605, 0.00, 94.71, 106.8011, 0.00, 0, -584, 1000, 0 -ATT, 0.00, 30.55, 0.00, -42.98, 0.00, 76.55, 86.55 -MOT, 1950, 1616, 1586, 1665 -NTUN, 618.78, 1.93, 976.4297, 1770.481, 241.4652, 437.8293, -1237.568, -482.2914, 806.2280, 557.1323, -27.54, -35.00 -CTUN, 605, 0.00, 94.45, 106.7867, 0.00, 0, -549, 1000, 0 -ATT, 0.00, 30.84, 0.00, -44.32, 0.00, 69.10, 79.10 -MOT, 1950, 1634, 1601, 1631 -NTUN, 617.36, 1.93, 1078.125, 1798.336, 257.0941, 428.8386, -1292.612, -365.5301, 847.6306, 491.8560, -26.23, -35.00 -GPS, 3, 109308800, 1774, 10, 1.65, -39.4896040, 176.7500808, 91.87, 138.15, 8.44, 199.22, 5.710000, 161874 -CTUN, 605, 0.00, 93.88, 106.7711, 0.00, 0, -531, 1000, 0 -ATT, 0.00, 31.91, 0.00, -45.31, 0.00, 60.60, 70.60 -MOT, 1950, 1638, 1607, 1619 -NTUN, 615.92, 1.93, 1184.375, 1811.837, 273.5782, 418.5152, -1325.614, -244.3797, 877.8202, 435.6969, -23.83, -35.00 -CTUN, 605, 0.00, 93.55, 106.7548, 0.00, 0, -514, 1000, 0 -ATT, 0.00, 34.14, 0.00, -46.24, 0.00, 50.47, 60.47 -MOT, 1950, 1572, 1565, 1578 -NTUN, 614.51, 1.93, 1293.250, 1802.732, 291.4518, 406.2707, -1336.823, -127.0351, 906.3613, 372.7051, -20.95, -35.00 -DU32, 7, 270713 -CURR, 1000, 430534, 1387, 5844, 4876, 807.2175 -GPS, 3, 109309000, 1774, 10, 1.65, -39.4896207, 176.7500813, 91.01, 137.38, 9.17, 181.44, 5.260000, 162074 -CTUN, 605, 0.00, 93.30, 106.7376, 0.00, 0, -509, 1000, 0 -ATT, 0.00, 38.10, 0.00, -47.31, 0.00, 38.51, 48.51 -MOT, 1950, 1585, 1581, 1583 -NTUN, 613.14, 1.93, 1402.234, 1778.488, 309.5724, 392.6383, -1331.628, -15.43563, 927.5319, 316.3617, -16.63, -35.00 -CTUN, 605, 0.00, 93.89, 106.7196, 0.00, 0, -518, 1000, 0 -ATT, 0.00, 43.47, 0.00, -48.18, 0.00, 24.81, 34.81 -MOT, 1950, 1549, 1566, 1574 -NTUN, 611.86, 1.93, 1505.504, 1732.763, 327.9348, 377.4371, -1309.987, 90.43272, 944.7438, 260.4977, -10.79, -35.00 -GPS, 3, 109309200, 1774, 10, 1.65, -39.4896368, 176.7500860, 90.21, 136.70, 9.34, 168.53, 4.860000, 162274 -CTUN, 605, 0.00, 93.81, 106.7006, 0.00, 0, -538, 1000, 0 -ATT, 0.00, 49.58, 0.00, -48.22, 0.00, 9.72, 19.72 -MOT, 1950, 1615, 1605, 1617 -NTUN, 610.67, 1.93, 1603.777, 1673.038, 346.0032, 360.9457, -1267.905, 189.5441, 957.1492, 210.3930, -3.26, -35.00 -CTUN, 605, 0.00, 93.80, 106.6811, 0.00, 0, -564, 1000, 0 -ATT, 0.00, 57.22, 0.00, -47.55, 0.00, 352.41, 2.41 -MOT, 1950, 1557, 1624, 1558 -NTUN, 609.62, 1.93, 1689.992, 1596.900, 363.4211, 343.4023, -1210.072, 279.8782, 967.4070, 156.6004, 5.09, -35.00 -GPS, 3, 109309400, 1774, 10, 1.65, -39.4896509, 176.7500943, 89.46, 136.03, 8.94, 156.79, 4.590000, 162475 -CTUN, 605, 0.00, 93.00, 106.6604, 0.00, 0, -598, 1000, 0 -ATT, 0.00, 65.34, 0.00, -45.55, 0.00, 333.48, 343.48 -MOT, 1950, 1588, 1578, 1552 -NTUN, 608.70, 1.93, 1766.344, 1508.796, 380.1822, 324.7484, -1127.765, 356.6176, 973.7379, 110.6085, 15.29, -35.00 -CTUN, 605, 0.00, 92.45, 106.6392, 0.00, 0, -642, 1000, 0 -ATT, 0.00, 73.07, 0.00, -42.40, 0.00, 313.65, 323.65 -MOT, 1950, 1573, 1589, 1497 -NTUN, 607.97, 1.93, 1824.480, 1409.027, 395.7263, 305.6153, -1023.186, 411.7567, 977.6873, 67.28786, 24.83, -35.00 -GPS, 3, 109309600, 1774, 10, 1.65, -39.4896635, 176.7501055, 88.53, 135.19, 8.66, 147.34, 4.540000, 162675 -CTUN, 605, 0.00, 92.26, 106.6180, 0.00, -226, -693, 774, 0 -ATT, 0.00, 80.26, 0.00, -38.21, 0.00, 293.00, 303.00 -MOT, 1950, 1525, 1633, 1540 -NTUN, 607.40, 1.94, 1870.340, 1302.120, 410.3483, 285.6822, -892.8578, 442.7764, 979.6035, 27.87698, 32.93, -27.68 -CTUN, 605, 0.00, 92.23, 106.5969, 0.00, -608, -750, 392, 0 -ATT, 0.00, 86.42, 0.00, -31.95, 0.00, 272.14, 282.14 -MOT, 1558, 1135, 1443, 1258 -NTUN, 607.05, 1.94, 1894.629, 1190.492, 423.3603, 266.0189, -749.3270, 433.1040, 979.9940, 3.435690, 35.00, -12.03 -GPS, 3, 109309800, 1774, 10, 1.65, -39.4896719, 176.7501197, 87.42, 134.17, 7.82, 132.77, 4.720000, 162875 -CTUN, 605, 0.00, 91.33, 106.5757, 0.00, -593, -808, 407, 0 -ATT, 0.00, 83.72, 0.00, -26.12, 0.00, 254.44, 264.44 -MOT, 1461, 1293, 1730, 1537 -NTUN, 606.88, 1.94, 1902.102, 1078.564, 434.9417, 246.6286, -601.0383, 383.9391, 980.0000, 0.056778, 35.00, 7.25 -CTUN, 605, 0.00, 90.09, 106.5546, 0.00, 0, -849, 1000, 0 -ATT, 0.00, 70.75, 0.00, -19.53, 0.00, 243.04, 253.04 -MOT, 1521, 1536, 1950, 1504 -NTUN, 606.93, 1.94, 1884.027, 971.0889, 444.4364, 229.0770, -414.4949, 276.3171, 979.5334, 30.23489, 35.00, 21.96 -DU32, 7, 270713 -CURR, 1000, 439048, 1461, 4030, 4897, 819.2295 -GPS, 3, 109310000, 1774, 10, 1.65, -39.4896763, 176.7501331, 86.09, 132.94, 6.44, 118.10, 5.070000, 163076 -CTUN, 605, 0.00, 90.30, 106.5332, 0.00, 0, -817, 1000, 0 -ATT, 0.00, 45.90, 0.00, -18.63, 0.00, 231.19, 241.19 -MOT, 1262, 1349, 1608, 1127 -NTUN, 607.17, 1.94, 1845.895, 871.6846, 452.1232, 213.5056, -297.8584, 137.5289, 971.3177, 130.1608, 35.00, 32.56 -CTUN, 605, 0.00, 87.98, 106.5121, 0.00, 0, -728, 1000, 0 -ATT, 0.00, 16.58, 0.00, -23.51, 0.00, 219.50, 229.50 -MOT, 1746, 1752, 1950, 1319 -NTUN, 607.54, 1.94, 1782.055, 791.4746, 456.9581, 202.9515, -276.7377, 24.07106, 939.9755, 277.2110, 23.98, 35.00 -GPS, 3, 109310200, 1774, 10, 1.65, -39.4896742, 176.7501411, 84.90, 131.82, 3.90, 110.38, 5.240000, 163276 -CTUN, 605, 0.00, 85.42, 106.4909, 0.00, 0, -622, 1000, 0 -ATT, 0.00, 0.41, 0.00, -36.29, 0.00, 213.36, 223.36 -MOT, 1950, 1542, 1866, 1241 -NTUN, 607.92, 1.94, 1709.406, 724.8564, 460.3244, 195.1959, -341.9768, -69.13911, 904.0232, 378.3414, 11.01, 35.00 -CTUN, 605, 0.00, 84.64, 106.4697, 0.00, 0, -555, 1000, 0 -ATT, 0.00, -4.20, 0.00, -56.06, 0.00, 213.49, 222.36 -MOT, 1950, 1429, 1724, 1432 -NTUN, 608.27, 1.94, 1629.340, 679.0381, 461.5237, 192.3430, -444.7347, -147.1507, 869.9585, 451.1898, 3.42, 35.00 -GPS, 3, 109310400, 1774, 10, 1.65, -39.4896677, 176.7501417, 83.75, 130.59, 3.04, 55.12, 5.470000, 163476 -CTUN, 605, 0.00, 83.32, 106.4486, 0.00, 0, -539, 1000, 0 -ATT, 0.00, 3.95, 0.00, -71.79, 0.00, 212.72, 222.36 -MOT, 1950, 1573, 1683, 1616 -NTUN, 608.51, 1.94, 1555.582, 644.0059, 461.9752, 191.2562, -565.5382, -247.5177, 856.0806, 476.9970, 2.21, 35.00 -CTUN, 605, 0.00, 82.25, 106.4274, 0.00, -143, -575, 857, 0 -ATT, 0.00, 35.61, 0.00, -77.92, 0.00, 191.60, 201.60 -MOT, 1950, 1201, 1490, 1922 -NTUN, 608.64, 1.94, 1485.770, 631.9170, 460.1136, 195.6923, -668.8723, -366.3332, 826.5912, 526.4476, -1.73, 35.00 -GPS, 3, 109310600, 1774, 10, 1.65, -39.4896633, 176.7501375, 82.48, 129.51, 3.00, 26.92, 5.390000, 163676 -CTUN, 603, 0.00, 83.34, 106.4063, 0.00, -104, -639, 896, 0 -ATT, 0.00, 65.22, 0.00, -75.94, 0.00, 169.05, 179.05 -MOT, 1398, 1362, 1585, 1950 -NTUN, 608.63, 1.94, 1425.313, 634.7881, 456.7491, 203.4213, -734.4034, -489.1974, 799.2764, 567.0601, -7.63, 35.00 -CTUN, 605, 0.00, 83.85, 106.3851, 0.00, 0, -690, 1000, 0 -ATT, 0.00, 46.78, 0.00, -64.99, 0.00, 193.42, 183.42 -MOT, 1242, 1165, 1127, 1740 -NTUN, 608.48, 1.94, 1375.316, 660.3027, 450.7422, 216.4057, -777.3533, -618.1238, 756.4160, 623.0849, -11.52, 35.00 -GPS, 3, 109310800, 1774, 10, 1.65, -39.4896620, 176.7501314, 81.17, 128.19, 2.84, 3.17, 5.560000, 163876 -CTUN, 605, 0.00, 83.17, 106.3637, 0.00, 0, -702, 1000, 0 -ATT, 0.00, 29.83, 0.00, -35.55, 0.00, 218.00, 208.00 -MOT, 1384, 1537, 1391, 1950 -NTUN, 608.24, 1.94, 1330.965, 701.5156, 442.3210, 233.1355, -765.3212, -705.0020, 715.1798, 670.0133, -9.03, 35.00 -CTUN, 605, 0.00, 81.95, 106.3426, 0.00, 0, -698, 1000, 0 -ATT, 0.00, 26.94, 0.00, 0.47, 0.00, 230.69, 220.69 -MOT, 1456, 1605, 1573, 1950 -NTUN, 607.93, 1.94, 1294.566, 758.9854, 431.3342, 252.8849, -703.9335, -750.1877, 672.3566, 712.9774, -1.48, 35.00 -DU32, 7, 270713 -CURR, 1000, 448843, 1453, 2867, 4918, 830.6562 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -GPS, 3, 109311000, 1774, 10, 1.65, -39.4896658, 176.7501195, 79.89, 126.74, 4.48, 287.18, 5.870000, 164077 -CTUN, 605, 0.00, 82.14, 106.3214, 0.00, 0, -682, 1000, 0 -ATT, 0.00, 26.42, 0.00, 35.08, 0.00, 241.34, 231.34 -MOT, 1515, 1950, 1456, 1812 -NTUN, 607.65, 1.94, 1255.785, 824.0361, 418.0351, 274.3113, -622.4413, -737.4474, 630.1533, 750.5377, 6.08, 35.00 -CTUN, 605, 0.00, 82.21, 106.3003, 0.00, 0, -697, 1000, 0 -ATT, 0.00, 20.98, 0.00, 64.36, 0.00, 246.67, 236.87 -MOT, 1342, 1950, 1403, 1166 -NTUN, 607.39, 1.94, 1216.176, 895.3906, 402.6447, 296.4409, -533.7360, -674.2542, 593.5552, 779.8027, 7.89, 35.00 -GPS, 3, 109311200, 1774, 10, 1.65, -39.4896711, 176.7500995, 78.69, 125.44, 7.52, 255.84, 6.010000, 164277 -CTUN, 605, 0.00, 81.75, 106.2791, 0.00, -24, -728, 976, 0 -ATT, 0.00, -21.52, 0.00, 75.89, 0.00, 220.14, 230.14 -MOT, 1441, 1950, 1706, 1253 -NTUN, 607.22, 1.94, 1169.469, 963.7676, 385.8557, 317.9865, -466.3108, -592.7849, 569.4946, 797.5436, 1.26, 35.00 -CTUN, 605, 0.00, 81.48, 106.2580, 0.00, 0, -778, 1000, 0 -ATT, 0.00, -55.70, 0.00, 69.05, 0.00, 200.50, 210.16 -MOT, 1643, 1605, 1950, 1565 -NTUN, 607.09, 1.94, 1118.109, 1031.055, 367.5731, 338.9543, -421.4198, -494.7960, 552.7898, 809.2115, -8.46, 35.00 -GPS, 3, 109311400, 1774, 10, 1.65, -39.4896740, 176.7500796, 77.44, 124.37, 8.46, 259.08, 5.920000, 164477 -CTUN, 605, 0.00, 80.55, 106.2368, 0.00, 0, -811, 1000, 0 -ATT, 0.00, -50.69, 0.00, 54.61, 0.00, 218.26, 210.16 -MOT, 1395, 1445, 1748, 1127 -NTUN, 607.03, 1.93, 1061.949, 1090.884, 348.7701, 358.2728, -415.6103, -378.2093, 555.5469, 807.3213, -12.06, 35.00 -CTUN, 605, 0.00, 78.83, 106.2154, 0.00, 0, -825, 1000, 0 -ATT, 0.00, -44.42, 0.00, 31.61, 0.00, 241.23, 231.23 -MOT, 1590, 1587, 1851, 1127 -NTUN, 607.01, 1.93, 1001.320, 1139.513, 330.0443, 375.5938, -453.1321, -276.1216, 582.6448, 787.9880, -2.68, 35.00 -GPS, 3, 109311600, 1774, 9, 2.43, -39.4896736, 176.7500601, 76.02, 123.39, 8.41, 268.09, 5.780000, 164677 -CTUN, 602, 0.00, 77.66, 106.1943, 0.00, 0, -800, 1000, 0 -ATT, 0.00, -45.63, 0.00, 10.16, 0.00, 262.46, 252.46 -MOT, 1739, 1668, 1950, 1206 -NTUN, 606.98, 1.93, 942.5625, 1177.617, 312.4422, 390.3586, -544.3233, -210.9509, 629.4567, 751.1219, 19.23, 35.00 -CTUN, 605, 0.00, 77.61, 106.1731, 0.00, 0, -742, 1000, 0 -ATT, 0.00, -49.22, 0.00, -3.08, 0.00, 283.43, 273.43 -MOT, 1862, 1775, 1950, 1498 -NTUN, 606.90, 1.93, 887.9961, 1205.226, 296.5854, 402.5383, -659.9333, -234.5763, 681.9404, 703.8162, 35.00, 34.24 -GPS, 3, 109311800, 1774, 9, 2.43, -39.4896723, 176.7500419, 74.64, 122.63, 7.83, 271.41, 5.430000, 164878 -CTUN, 605, 0.00, 79.02, 106.1520, 0.00, 0, -686, 1000, 0 -ATT, 0.00, -52.93, 0.00, -8.56, 0.00, 304.13, 294.13 -MOT, 1427, 1644, 1950, 1363 -NTUN, 606.69, 1.93, 843.4688, 1231.235, 282.5803, 412.4905, -778.5619, -330.3637, 710.7822, 674.6768, 35.00, 18.76 -CTUN, 605, 0.00, 77.34, 106.1308, 0.00, 0, -645, 1000, 0 -ATT, 0.00, -57.02, 0.00, -10.19, 0.00, 325.27, 315.27 -MOT, 1606, 1326, 1950, 1677 -NTUN, 606.36, 1.93, 810.7656, 1263.882, 269.9711, 420.8511, -833.0995, -437.2181, 714.6117, 670.6191, 35.00, -1.34 -DU32, 7, 270713 -CURR, 1000, 458843, 1453, 4798, 4876, 842.8516 -GPS, 3, 109312000, 1774, 10, 1.65, -39.4896707, 176.7500251, 73.67, 122.50, 6.94, 268.68, 4.560000, 165078 -CTUN, 605, 0.00, 75.98, 106.1096, 0.00, 0, -642, 1000, 0 -ATT, 0.00, -53.08, 0.00, -11.13, 0.00, 343.07, 333.07 -MOT, 1466, 1450, 1946, 1950 -NTUN, 605.95, 1.93, 786.6641, 1306.694, 257.8857, 428.3631, -838.8315, -531.6833, 697.0085, 688.8970, 35.00, -19.35 -CTUN, 605, 0.00, 76.13, 106.0885, 0.00, 0, -639, 1000, 0 -ATT, 0.00, -38.05, 0.00, -11.96, 0.00, 354.45, 344.45 -MOT, 1318, 1343, 1633, 1950 -NTUN, 605.51, 1.93, 766.1250, 1362.041, 245.1250, 435.7909, -816.2412, -604.8326, 666.1210, 718.8066, 35.00, -28.08 -GPS, 3, 109312200, 1774, 10, 1.65, -39.4896711, 176.7500076, 72.62, 122.93, 6.98, 264.08, 3.390000, 165279 -CTUN, 605, 0.00, 75.26, 106.0671, 0.00, 0, -625, 1000, 0 -ATT, 0.00, -13.01, 0.00, -9.41, 0.00, 358.06, 348.06 -MOT, 1142, 1262, 1178, 1950 -NTUN, 605.06, 1.93, 743.8320, 1425.857, 231.2601, 443.3044, -791.2646, -631.1121, 635.2730, 746.2092, 35.00, -31.48 -CTUN, 605, 0.00, 75.17, 106.0462, 0.00, 0, -609, 1000, 0 -ATT, 0.00, 20.49, 0.00, 2.09, 0.00, 359.04, 349.04 -MOT, 1573, 1402, 1127, 1806 -NTUN, 604.61, 1.93, 721.6445, 1500.656, 216.6899, 450.6057, -768.2755, -615.0052, 614.7167, 763.2322, 35.00, -31.17 -GPS, 3, 109312400, 1774, 10, 1.65, -39.4896769, 176.7499949, 71.64, 121.44, 6.51, 257.75, 4.050000, 165479 -CTUN, 605, 0.00, 75.10, 106.0248, 0.00, 0, -618, 1000, 0 -ATT, 0.00, 52.31, 0.00, 12.12, 0.00, 3.38, 353.38 -MOT, 1807, 1416, 1127, 1591 -NTUN, 604.17, 1.93, 696.7266, 1576.664, 202.0967, 457.3367, -758.2792, -553.6387, 612.1394, 765.3007, 35.00, -32.34 -CTUN, 605, 0.00, 74.13, 106.0037, 0.00, 0, -656, 1000, 0 -ATT, 0.00, 76.02, 0.00, 13.79, 0.00, 3.64, 355.01 -MOT, 1950, 1384, 1296, 1315 -NTUN, 603.74, 1.93, 673.8086, 1648.731, 189.1547, 462.8396, -743.1379, -476.3700, 627.7534, 752.5462, 34.54, -35.00 -GPS, 3, 109312600, 1774, 10, 1.65, -39.4896827, 176.7499783, 70.64, 120.10, 7.70, 253.32, 4.450000, 165680 -CTUN, 605, 0.00, 73.00, 105.9825, 0.00, -348, -713, 652, 0 -ATT, 0.00, 80.47, 0.00, 11.49, 0.00, 354.37, 355.01 -MOT, 1950, 1567, 1443, 1302 -NTUN, 603.34, 1.93, 650.3672, 1713.130, 177.4605, 467.4482, -717.2687, -393.5936, 644.9492, 737.8621, 35.00, -33.20 -CTUN, 603, 0.00, 72.86, 105.9613, 0.00, -110, -777, 890, 0 -ATT, 0.00, 75.78, 0.00, 6.11, 0.00, 340.49, 350.49 -MOT, 1950, 1590, 1345, 1371 -NTUN, 602.99, 1.93, 624.6563, 1769.155, 166.4689, 471.4744, -671.6952, -314.4693, 657.0335, 727.1224, 35.00, -26.32 -GPS, 3, 109312800, 1774, 10, 1.65, -39.4896876, 176.7499596, 69.33, 117.33, 8.91, 267.03, 6.020000, 165880 -CTUN, 602, 0.00, 72.79, 105.9402, 0.00, 0, -831, 1000, 0 -ATT, 0.00, 69.91, 0.00, -3.08, 0.00, 326.59, 336.59 -MOT, 1950, 1506, 1672, 1562 -NTUN, 602.72, 1.93, 595.0430, 1816.809, 155.6261, 475.1637, -598.9000, -241.9769, 660.4778, 723.9952, 35.00, -15.48 -CTUN, 605, 0.00, 72.62, 105.9190, 0.00, 0, -865, 1000, 0 -ATT, 0.00, 66.39, 0.00, -13.04, 0.00, 312.28, 322.28 -MOT, 1906, 1638, 1950, 1812 -NTUN, 602.55, 1.93, 558.7539, 1855.866, 144.1458, 478.7713, -483.5654, -175.4013, 647.9259, 735.2496, 35.00, -0.57 -DU32, 7, 270713 -CURR, 1000, 468317, 1383, 6036, 4855, 852.1169 -GPS, 3, 109313000, 1774, 10, 1.65, -39.4896916, 176.7499407, 67.93, 115.96, 8.49, 259.32, 6.120000, 166080 -CTUN, 605, 0.00, 72.77, 105.8977, 0.00, 0, -872, 1000, 0 -ATT, 0.00, 59.04, 0.00, -23.23, 0.00, 296.11, 306.11 -MOT, 1225, 1147, 1520, 1127 -NTUN, 602.51, 1.93, 512.0898, 1887.287, 130.9339, 482.5518, -347.1010, -163.9697, 606.5880, 769.7084, 35.00, 16.16 -CTUN, 605, 0.00, 72.46, 105.8765, 0.00, 0, -865, 1000, 0 -ATT, 0.00, 45.00, 0.00, -36.80, 0.00, 278.81, 288.81 -MOT, 1336, 1427, 1950, 1469 -NTUN, 602.61, 1.93, 452.0703, 1914.758, 114.8903, 486.6212, -213.4912, -209.1951, 513.0965, 834.9443, 32.77, 33.78 -GPS, 3, 109313200, 1774, 10, 1.65, -39.4896968, 176.7499274, 66.66, 114.67, 6.75, 249.86, 6.200000, 166281 -CTUN, 605, 0.00, 70.36, 105.8553, 0.00, 0, -843, 1000, 0 -ATT, 0.00, 26.57, 0.00, -48.73, 0.00, 271.57, 281.57 -MOT, 1318, 1350, 1950, 1159 -NTUN, 602.82, 1.93, 378.5000, 1944.392, 95.53792, 490.7877, -111.7616, -315.1477, 383.0670, 902.0309, 18.50, 35.00 -CTUN, 605, 0.00, 69.22, 105.8342, 0.00, 0, -839, 1000, 0 -ATT, 0.00, 4.41, 0.00, -60.76, 0.00, 274.02, 280.88 -MOT, 1615, 1571, 1950, 1466 -NTUN, 603.09, 1.92, 294.5039, 1980.272, 73.55052, 494.5608, -46.79864, -457.0046, 256.7998, 945.7557, 9.07, 35.00 -GPS, 3, 109313400, 1774, 10, 1.65, -39.4897006, 176.7499218, 65.30, 113.27, 3.72, 247.96, 6.340000, 166481 -CTUN, 605, 0.00, 68.16, 105.8130, 0.00, 0, -849, 1000, 0 -ATT, 0.00, -20.23, 0.00, -69.57, 0.00, 290.99, 280.99 -MOT, 1841, 1624, 1950, 1509 -NTUN, 603.39, 1.92, 202.9414, 2028.521, 49.77356, 497.5164, -9.904141, -634.7659, 167.9452, 965.5021, 8.42, 35.00 -CTUN, 605, 0.00, 65.90, 105.7919, 0.00, 0, -880, 1000, 0 -ATT, 0.00, -58.28, 0.00, -72.63, 0.00, 325.61, 315.61 -MOT, 1437, 1950, 1616, 1321 -NTUN, 603.67, 1.92, 107.9844, 2088.087, 25.82274, 499.3327, -2.786196, -832.8705, 117.6979, 972.9066, 11.51, 35.00 -GPS, 3, 109313600, 1774, 10, 1.65, -39.4896986, 176.7499143, 63.71, 112.40, 3.40, 247.96, 6.030000, 166681 -CTUN, 605, 0.00, 65.82, 105.7707, 0.00, 0, -921, 1000, 0 -ATT, 0.00, -63.35, 0.00, -64.38, 0.00, 322.08, 320.93 -MOT, 1127, 1474, 1215, 1148 -NTUN, 603.91, 1.92, 11.57422, 2165.568, 2.672290, 499.9929, -25.88333, -1011.334, 95.63342, 975.3226, 17.82, 21.86 -CTUN, 605, 0.00, 65.16, 105.7493, 0.00, 0, -939, 1000, 0 -ATT, 0.00, -46.29, 0.00, -43.05, 0.00, 290.50, 300.50 -MOT, 1237, 1950, 1229, 1298 -NTUN, 604.11, 1.92, -85.27734, 2262.265, -18.83440, 499.6451, -74.46530, -1122.122, 101.2559, 974.7550, 20.57, 35.00 -GPS, 3, 109313800, 1774, 10, 1.65, -39.4896948, 176.7499005, 61.97, 111.52, 5.94, 287.51, 5.750000, 166881 -CTUN, 605, 0.00, 64.30, 105.7282, 0.00, 0, -933, 1000, 0 -ATT, 0.00, -39.60, 0.00, -10.08, 0.00, 266.54, 276.54 -MOT, 1634, 1950, 1500, 1525 -NTUN, 604.21, 1.92, -177.9492, 2372.841, -37.39208, 498.5999, -138.1259, -1155.972, 126.5079, 971.8002, 12.91, 35.00 -CTUN, 605, 0.00, 62.61, 105.7070, 0.00, 0, -907, 1000, 0 -ATT, 0.00, -43.62, 0.00, 21.97, 0.00, 246.53, 256.53 -MOT, 1237, 1950, 1522, 1514 -NTUN, 604.24, 1.92, -262.7969, 2493.957, -52.39663, 497.2470, -199.2726, -1109.896, 165.1311, 965.9874, -3.54, 35.00 -DU32, 7, 270713 -CURR, 1000, 478317, 1423, 3614, 4940, 861.0620 -GPS, 3, 109314000, 1774, 10, 1.65, -39.4896937, 176.7498824, 60.25, 109.33, 8.26, 285.70, 6.580000, 167082 -CTUN, 605, 0.00, 62.24, 105.6859, 0.00, 0, -909, 1000, 0 -ATT, 0.00, -57.78, 0.00, 41.48, 0.00, 224.69, 234.69 -MOT, 1572, 1950, 1904, 1706 -NTUN, 604.19, 1.92, -340.5195, 2613.760, -64.59393, 495.8101, -224.6234, -999.6001, 204.2917, 958.4701, -17.37, 35.00 -CTUN, 605, 0.00, 63.41, 105.6647, 0.00, 0, -950, 1000, 0 -ATT, 0.00, -72.97, 0.00, 52.48, 0.00, 201.39, 211.39 -MOT, 1414, 1564, 1950, 1756 -NTUN, 604.09, 1.92, -406.8984, 2726.511, -73.80157, 494.5233, -223.7670, -886.4194, 235.3489, 951.3206, -24.81, 35.00 -GPS, 3, 109314200, 1774, 10, 1.65, -39.4896932, 176.7498514, 58.56, 108.76, 12.24, 272.06, 5.890000, 167282 -CTUN, 605, 0.00, 63.08, 105.6436, 0.00, 0, -992, 1000, 0 -ATT, 0.00, -66.92, 0.00, 59.24, 0.00, 198.74, 205.86 -MOT, 1235, 1359, 1950, 1685 -NTUN, 603.98, 1.91, -470.6445, 2828.002, -82.08255, 493.2164, -210.5075, -769.7216, 248.9199, 947.8602, -25.45, 26.99 -CTUN, 603, 0.00, 62.47, 105.6224, 0.00, 0, -1029, 1000, 0 -ATT, 0.00, -40.65, 0.00, 58.60, 0.00, 217.78, 207.78 -MOT, 1397, 1328, 1950, 1754 -NTUN, 603.86, 1.91, -528.5977, 2921.806, -89.01240, 492.0130, -183.8832, -674.7067, 259.8592, 944.9197, -20.17, 34.01 -GPS, 3, 109314400, 1774, 9, 1.68, -39.4897001, 176.7498359, 56.93, 107.33, 8.32, 250.19, 6.060000, 167482 -CTUN, 605, 0.00, 61.32, 105.6010, 0.00, 0, -1046, 1000, 0 -ATT, 0.00, -16.93, 0.00, 47.69, 0.00, 236.34, 226.34 -MOT, 1634, 1458, 1950, 1815 -NTUN, 603.75, 1.91, -587.6953, 3006.146, -95.93289, 490.7106, -154.2102, -585.5060, 253.4210, 946.6666, -14.86, 35.00 -CTUN, 605, 0.00, 59.68, 105.5799, 0.00, 0, -1010, 1000, 0 -ATT, 0.00, -9.03, 0.00, 27.89, 0.00, 247.61, 237.61 -MOT, 1410, 1128, 1771, 1127 -NTUN, 603.63, 1.91, -638.0977, 3067.631, -101.8254, 489.5218, -137.2714, -510.2572, 254.0032, 946.5106, -9.44, 35.00 -GPS, 3, 109314600, 1774, 9, 1.68, -39.4897084, 176.7498265, 55.25, 105.73, 6.34, 233.39, 6.400000, 167682 -CTUN, 605, 0.00, 58.96, 105.5587, 0.00, 0, -933, 1000, 0 -ATT, 0.00, -15.28, 0.00, 1.06, 0.00, 258.04, 248.04 -MOT, 1441, 1451, 1917, 1127 -NTUN, 603.50, 1.91, -687.9063, 3117.163, -107.7492, 488.2521, -157.9182, -476.4375, 255.5554, 946.0927, -2.59, 35.00 -CTUN, 605, 0.00, 57.75, 105.5376, 0.00, 0, -844, 1000, 0 -ATT, 0.00, -27.62, 0.00, -15.39, 0.00, 271.57, 261.57 -MOT, 1378, 1587, 1950, 1161 -NTUN, 603.31, 1.91, -729.4063, 3147.284, -112.8867, 487.0899, -211.5943, -505.4050, 278.3556, 939.6373, 10.32, 35.00 -GPS, 3, 109314800, 1774, 10, 1.65, -39.4897172, 176.7498222, 53.81, 104.08, 4.91, 213.51, 6.680000, 167883 -CTUN, 605, 0.00, 56.52, 105.5164, 0.00, 0, -772, 1000, 0 -ATT, 0.00, -39.29, 0.00, -25.08, 0.00, 290.99, 280.99 -MOT, 1667, 1633, 1950, 1456 -NTUN, 603.04, 1.91, -764.7227, 3173.921, -117.1182, 486.0898, -276.8117, -580.7421, 309.5137, 929.8394, 24.41, 35.00 -CTUN, 603, 0.00, 55.59, 105.4953, 0.00, 0, -733, 1000, 0 -ATT, 0.00, -51.23, 0.00, -27.83, 0.00, 313.29, 303.29 -MOT, 1622, 1668, 1950, 1393 -NTUN, 602.67, 1.91, -787.5508, 3195.681, -119.6415, 485.4749, -329.3771, -681.7704, 339.6435, 919.2618, 35.00, 31.40 -DU32, 7, 270713 -CURR, 1000, 488317, 1404, 5819, 4940, 871.8691 -GPS, 3, 109315000, 1774, 10, 1.65, -39.4897267, 176.7498229, 52.53, 102.38, 4.49, 188.60, 6.840000, 168083 -CTUN, 605, 0.00, 56.27, 105.4739, 0.00, 0, -734, 1000, 0 -ATT, 0.00, -61.25, 0.00, -22.66, 0.00, 333.85, 323.85 -MOT, 1689, 1743, 1950, 1664 -NTUN, 602.20, 1.91, -803.1836, 3223.962, -120.8702, 485.1705, -364.4174, -797.0923, 350.0180, 915.3619, 35.00, 14.33 -CTUN, 605, 0.00, 56.44, 105.4529, 0.00, 0, -739, 1000, 0 -ATT, 0.00, -63.67, 0.00, -13.66, 0.00, 350.91, 340.91 -MOT, 1199, 1532, 1950, 1577 -NTUN, 601.64, 1.91, -807.2891, 3254.962, -120.3623, 485.2968, -382.0041, -922.4053, 351.5960, 914.7569, 35.00, -3.50 -GPS, 3, 109315200, 1774, 10, 1.65, -39.4897369, 176.7498195, 51.40, 101.30, 5.62, 195.72, 6.480000, 168283 -CTUN, 605, 0.00, 55.61, 105.4316, 0.00, 0, -746, 1000, 0 -ATT, 0.00, -58.13, 0.00, -2.59, 0.10, 0.60, 350.60 -MOT, 1369, 1354, 1496, 1950 -NTUN, 601.01, 1.91, -808.2148, 3296.178, -119.0716, 485.6150, -394.2592, -1021.971, 340.1804, 919.0632, 35.00, -16.74 -CTUN, 605, 0.00, 54.11, 105.4104, 0.00, 0, -732, 1000, 0 -ATT, 0.00, -35.25, 0.00, 11.25, 0.00, 3.62, 353.62 -MOT, 1251, 1266, 1290, 1950 -NTUN, 600.31, 1.91, -801.4766, 3347.944, -116.4077, 486.2605, -413.2569, -1079.439, 336.0268, 920.5900, 35.00, -20.76 -GPS, 3, 109315400, 1774, 10, 1.65, -39.4897484, 176.7498113, 50.29, 100.20, 7.03, 209.92, 6.200000, 168483 -CTUN, 605, 0.00, 53.52, 105.3893, 0.00, 0, -722, 1000, 0 -ATT, 0.00, 0.63, 0.00, 19.88, 0.00, 10.90, 0.90 -MOT, 1552, 1199, 1557, 1950 -NTUN, 599.55, 1.91, -791.4531, 3407.524, -113.1219, 487.0353, -449.6306, -1077.428, 343.4716, 917.8384, 35.00, -24.67 -CTUN, 605, 0.00, 53.03, 105.3681, 0.00, 0, -711, 1000, 0 -ATT, 0.00, 38.28, 0.00, 14.85, 0.00, 18.14, 8.14 -MOT, 1775, 1349, 1559, 1950 -NTUN, 598.72, 1.91, -774.2852, 3472.167, -108.8258, 488.0132, -497.3428, -1025.481, 364.1419, 909.8356, 35.00, -30.96 -GPS, 3, 109315600, 1774, 10, 1.65, -39.4897603, 176.7497979, 49.15, 99.16, 8.55, 222.10, 5.920000, 168684 -CTUN, 605, 0.00, 53.88, 105.3469, 0.00, 0, -716, 1000, 0 -ATT, 0.00, 62.23, 0.00, 6.41, 0.00, 27.85, 17.85 -MOT, 1676, 1655, 1458, 1950 -NTUN, 597.84, 1.91, -751.6563, 3534.305, -104.0110, 489.0621, -561.7349, -941.2330, 402.0710, 893.7220, 34.52, -35.00 -CTUN, 605, 0.00, 52.26, 105.3258, 0.00, 0, -738, 1000, 0 -ATT, 0.00, 66.10, 0.00, -4.45, 0.20, 43.26, 33.26 -MOT, 1531, 1950, 1917, 1908 -NTUN, 596.90, 1.91, -721.1758, 3591.646, -98.43160, 490.2155, -634.7596, -842.0714, 446.2993, 872.4774, 24.78, -35.00 -GPS, 3, 109315800, 1774, 9, 1.67, -39.4897725, 176.7497828, 48.08, 98.06, 9.25, 224.63, 5.780000, 168884 -CTUN, 605, 0.00, 53.36, 105.3044, 0.00, 0, -731, 1000, 0 -ATT, 0.00, 44.44, 0.00, -8.44, 0.00, 63.90, 53.90 -MOT, 1127, 1888, 1631, 1921 -NTUN, 595.90, 1.91, -684.1641, 3640.231, -92.35560, 491.3965, -703.5776, -775.3124, 497.4088, 844.3841, 6.55, -35.00 -CTUN, 605, 0.00, 53.07, 105.2833, 0.00, 0, -698, 1000, 0 -ATT, 0.00, 16.88, 0.00, 7.47, 0.00, 86.38, 76.38 -MOT, 1127, 1745, 1520, 1857 -NTUN, 594.85, 1.91, -638.5625, 3679.796, -85.48840, 492.6375, -749.6603, -774.3523, 536.8378, 819.8812, -17.67, -35.00 -DU32, 7, 270713 -CURR, 1000, 498317, 1395, 5134, 4876, 883.6629 -GPS, 3, 109316000, 1774, 9, 1.67, -39.4897881, 176.7497707, 47.19, 96.93, 9.72, 215.27, 5.640000, 169084 -CTUN, 605, 0.00, 50.69, 105.2621, 0.00, 0, -627, 1000, 0 -ATT, 0.00, -4.13, 0.00, 30.73, 0.00, 100.13, 90.13 -MOT, 1167, 1931, 1884, 1950 -NTUN, 593.74, 1.91, -587.2344, 3716.201, -78.04169, 493.8719, -738.5366, -817.5733, 551.8777, 809.8340, -30.57, -35.00 -CTUN, 605, 0.00, 50.27, 105.2409, 0.00, 0, -616, 1000, 0 -ATT, 0.00, -25.72, 0.00, 52.73, 0.00, 104.24, 94.38 -MOT, 1127, 1734, 1889, 1600 -NTUN, 592.64, 1.91, -531.0781, 3750.084, -70.10928, 495.0603, -679.9373, -868.9425, 536.9702, 819.7945, -28.33, -34.36 -GPS, 3, 109316200, 1774, 9, 1.67, -39.4898048, 176.7497611, 46.31, 96.12, 10.10, 207.59, 5.210000, 169285 -CTUN, 605, 0.00, 50.28, 105.2198, 0.00, 0, -644, 1000, 0 -ATT, 0.00, -52.22, 0.00, 65.93, 0.10, 101.14, 94.38 -MOT, 1127, 1442, 1716, 1264 -NTUN, 591.58, 1.91, -478.3555, 3787.827, -62.64620, 496.0599, -599.8033, -889.8303, 506.2943, 839.0864, -18.88, -35.00 -CTUN, 605, 0.00, 50.48, 105.1986, 0.00, 0, -691, 1000, 0 -ATT, 0.00, -57.02, 0.00, 68.46, 0.10, 112.21, 102.21 -MOT, 1445, 1326, 1950, 1547 -NTUN, 590.59, 1.91, -430.9570, 3824.496, -55.98735, 496.8555, -502.7559, -900.1999, 472.1385, 858.7697, -13.85, -35.00 -GPS, 3, 109316400, 1774, 10, 1.65, -39.4898201, 176.7497497, 45.35, 95.32, 9.89, 210.31, 5.000000, 169485 -CTUN, 605, 0.00, 49.13, 105.1775, 0.00, 0, -723, 1000, 0 -ATT, 0.00, -31.17, 0.00, 53.68, 0.00, 147.22, 137.22 -MOT, 1589, 1156, 1950, 1642 -NTUN, 589.71, 1.91, -392.4063, 3861.666, -50.54759, 497.4384, -409.1667, -879.8073, 432.9793, 879.1638, -21.96, -21.52 -CTUN, 605, 0.00, 47.92, 105.1563, 0.00, 0, -728, 1000, 0 -ATT, 0.00, -22.22, 0.00, 21.44, 0.00, 166.43, 156.43 -MOT, 1586, 1127, 1862, 1342 -NTUN, 588.94, 1.90, -365.9844, 3899.146, -46.72598, 497.8119, -344.7780, -828.0176, 397.1253, 895.9305, -35.00, 3.11 -GPS, 3, 109316600, 1774, 10, 1.65, -39.4898329, 176.7497365, 44.24, 94.25, 9.16, 218.20, 5.170000, 169685 -CTUN, 605, 0.00, 46.96, 105.1349, 0.00, 0, -701, 1000, 0 -ATT, 0.00, -29.75, 0.00, -16.05, 0.00, 179.94, 169.94 -MOT, 1688, 1456, 1840, 1127 -NTUN, 588.26, 1.90, -348.4688, 3933.309, -44.12433, 498.0493, -348.9094, -754.9597, 379.3677, 903.5930, -35.00, 14.95 -CTUN, 605, 0.00, 47.12, 105.1138, 0.00, 0, -707, 1000, 0 -ATT, 0.00, -57.09, 0.00, -42.40, 0.00, 206.67, 196.67 -MOT, 1331, 1849, 1589, 1127 -NTUN, 587.62, 1.90, -339.3477, 3963.896, -42.64882, 498.1778, -397.3857, -680.9581, 396.8342, 896.0595, -34.74, 29.78 -GPS, 3, 109316800, 1774, 10, 1.65, -39.4898420, 176.7497237, 43.09, 93.02, 7.63, 226.59, 5.440000, 169885 -CTUN, 605, 0.00, 47.34, 105.0926, 0.00, -484, -750, 516, 0 -ATT, 0.00, -87.29, 0.00, -43.80, 0.10, 232.78, 222.78 -MOT, 1353, 1587, 1127, 1301 -NTUN, 586.97, 1.90, -328.3359, 3987.716, -41.02958, 498.3137, -478.2703, -594.6638, 440.7399, 875.2990, -14.34, 35.00 -CTUN, 605, 0.00, 46.22, 105.0715, 0.00, -806, -798, 194, 0 -ATT, 0.00, -86.92, 0.00, -37.51, 0.00, 232.15, 225.73 -MOT, 1310, 1671, 1127, 1282 -NTUN, 586.32, 1.90, -317.4609, 4003.764, -39.52127, 498.4356, -553.8174, -507.5789, 497.1852, 844.5158, -2.87, 35.00 -GPS, 3, 109317000, 1774, 9, 1.67, -39.4898493, 176.7497129, 42.01, 91.88, 6.39, 229.72, 5.510000, 170066 -DU32, 7, 270713 -CURR, 718, 508165, 1517, 1571, 4962, 894.5137 -CTUN, 603, 0.00, 45.37, 105.0503, 0.00, 0, -850, 1000, 0 -ATT, 0.00, -71.18, 0.00, -27.38, 0.20, 217.50, 225.73 -MOT, 1471, 1950, 1316, 1381 -NTUN, 585.63, 1.90, -300.2578, 4011.029, -37.32458, 498.6049, -621.2233, -408.4954, 553.1685, 808.9528, -8.58, 35.00 -CTUN, 605, 0.00, 44.89, 105.0292, 0.00, 0, -874, 1000, 0 -ATT, 0.00, -55.77, 0.00, -9.68, 0.00, 201.56, 211.56 -MOT, 1746, 1950, 1430, 1676 -NTUN, 584.92, 1.90, -280.2734, 4006.371, -34.89319, 498.7810, -660.2535, -289.0837, 608.8859, 767.8918, -19.57, 35.00 -GPS, 3, 109317200, 1774, 10, 1.65, -39.4898573, 176.7497040, 40.46, 90.69, 5.92, 224.56, 5.590000, 170285 -CTUN, 605, 0.00, 43.00, 105.0078, 0.00, 0, -857, 1000, 0 -ATT, 0.00, -48.16, 0.00, 15.49, 0.00, 186.46, 196.46 -MOT, 1502, 1950, 1589, 1812 -NTUN, 584.21, 1.90, -255.3281, 3990.449, -31.92711, 498.9796, -650.1251, -138.5498, 661.5543, 723.0118, -28.95, 35.00 -CTUN, 605, 0.00, 42.64, 104.9866, 0.00, 0, -834, 1000, 0 -ATT, 0.00, -50.06, 0.00, 42.80, 0.00, 169.36, 179.36 -MOT, 1219, 1369, 1353, 1950 -NTUN, 583.55, 1.90, -228.8906, 3959.973, -28.85237, 499.1668, -561.3519, -19.34876, 701.3600, 684.4663, -31.94, 34.96 -GPS, 3, 109317400, 1774, 10, 1.65, -39.4898688, 176.7496989, 39.00, 89.29, 6.09, 208.24, 5.850000, 170486 -CTUN, 605, 0.00, 43.53, 104.9655, 0.00, 0, -846, 1000, 0 -ATT, 0.00, -51.26, 0.00, 66.16, 0.00, 150.13, 160.13 -MOT, 1288, 1443, 1578, 1950 -NTUN, 582.99, 1.91, -208.5508, 3915.988, -26.59044, 499.2924, -445.7025, 45.90363, 704.6873, 681.0402, -27.18, 23.20 -CTUN, 605, 0.00, 42.66, 104.9445, 0.00, -230, -879, 770, 0 -ATT, 0.00, -29.81, 0.00, 81.30, 0.00, 151.30, 154.93 -MOT, 1429, 1222, 1424, 1950 -NTUN, 582.55, 1.91, -195.8594, 3862.616, -25.32067, 499.3585, -301.6018, 68.31187, 675.5894, 709.9147, -14.51, 8.41 -GPS, 3, 109317600, 1774, 10, 1.65, -39.4898794, 176.7496994, 37.64, 87.85, 5.38, 186.65, 6.090000, 170686 -CTUN, 602, 0.00, 42.02, 104.9232, 0.00, -400, -927, 600, 0 -ATT, 0.00, 53.27, 0.00, 80.05, 0.00, 214.56, 204.56 -MOT, 1950, 1460, 1525, 1659 -NTUN, 582.27, 1.91, -197.0469, 3804.762, -25.86012, 499.3308, -159.5049, 44.14635, 599.1960, 775.4767, -4.15, 35.00 -CTUN, 605, 0.00, 40.49, 104.9020, 0.00, 0, -971, 1000, 0 -ATT, 0.00, 51.87, 0.00, 67.07, 0.00, 199.87, 205.78 -MOT, 1636, 1127, 1280, 1336 -NTUN, 582.14, 1.91, -214.0938, 3745.626, -28.53260, 499.1852, -13.87545, -34.70837, 471.7656, 858.9745, -7.26, 35.00 -GPS, 3, 109317800, 1774, 10, 1.65, -39.4898862, 176.7497014, 36.08, 86.56, 3.95, 181.95, 6.250000, 170886 -CTUN, 603, 0.00, 38.98, 104.8951, 0.00, 0, -978, 1000, 0 -ATT, 0.00, 38.66, 0.00, 43.48, 0.00, 178.02, 188.02 -MOT, 1950, 1492, 1813, 1544 -NTUN, 582.17, 1.91, -213.9609, 3700.147, -28.86427, 499.1662, 102.9985, -134.6166, 340.2846, 919.0247, -26.33, 24.81 -CTUN, 605, 0.00, 37.49, 104.8919, 0.00, 0, -939, 1000, 0 -ATT, 0.00, 28.70, 0.00, 15.82, 0.00, 165.22, 175.22 -MOT, 1915, 1583, 1950, 1525 -NTUN, 582.32, 1.91, -225.4570, 3668.210, -30.67332, 499.0583, 152.5185, -222.9875, 200.1464, 959.3442, -35.00, 2.76 -GPS, 3, 109318000, 1774, 10, 1.65, -39.4898892, 176.7497034, 34.39, 85.03, 2.05, 176.26, 6.600000, 171086 -DU32, 7, 270713 -CURR, 1000, 517665, 1423, 3441, 4855, 904.8021 -CTUN, 605, 0.00, 36.15, 104.8899, 0.00, 0, -864, 1000, 0 -ATT, 0.00, 16.35, 0.00, -14.67, 0.00, 158.94, 168.94 -MOT, 1851, 1466, 1950, 1618 -NTUN, 582.52, 1.91, -243.6797, 3647.422, -33.33007, 498.8879, 126.4590, -260.0151, 144.4410, 969.2971, -35.00, -10.13 -CTUN, 605, 0.00, 34.92, 104.8870, 0.00, 0, -812, 1000, 0 -ATT, 0.00, 0.90, 0.00, -43.24, 0.00, 161.59, 168.62 -MOT, 1775, 1195, 1950, 1414 -NTUN, 582.73, 1.91, -270.8086, 3637.662, -37.12017, 498.6202, 54.34202, -237.1867, 153.6583, 967.8787, -35.00, -11.82 -GPS, 3, 109318200, 1774, 10, 1.65, -39.4898868, 176.7497042, 32.82, 83.15, 0.94, 125.83, 7.120000, 171287 -CTUN, 605, 0.00, 34.67, 104.8833, 0.00, 0, -810, 1000, 0 -ATT, 0.00, -29.17, 0.00, -63.70, 0.00, 183.24, 173.24 -MOT, 1592, 1697, 1950, 1580 -NTUN, 582.88, 1.91, -295.9844, 3628.951, -40.64602, 498.3452, -39.73892, -175.2156, 216.5663, 955.7715, -29.38, 1.37 -CTUN, 603, 0.00, 34.15, 104.8788, 0.00, 0, -840, 1000, 0 -ATT, 0.00, -71.96, 0.00, -63.22, 0.10, 218.48, 208.48 -MOT, 1485, 1950, 1571, 1545 -NTUN, 582.98, 1.91, -320.2461, 3621.730, -44.03992, 498.0567, -155.1628, -85.28500, 313.3511, 928.5532, -16.96, 33.65 -GPS, 3, 109318400, 1774, 10, 1.65, -39.4898841, 176.7497026, 31.26, 81.51, 1.91, 359.83, 7.260000, 171487 -CTUN, 605, 0.00, 33.52, 104.8734, 0.00, -222, -876, 778, 0 -ATT, 0.00, -78.13, 0.00, -51.67, 0.00, 218.88, 212.89 -MOT, 1471, 1950, 1570, 1431 -NTUN, 582.98, 1.91, -336.8594, 3607.447, -46.48720, 497.8342, -257.3848, 24.19129, 439.8322, 875.7554, -10.56, 35.00 -CTUN, 605, 0.00, 32.98, 104.8671, 0.00, 0, -899, 1000, 0 -ATT, 0.00, -69.72, 0.00, -36.59, 0.10, 203.46, 212.89 -MOT, 1595, 1950, 1518, 1610 -NTUN, 582.90, 1.91, -343.8203, 3586.680, -47.71146, 497.7184, -330.9182, 131.2106, 567.1309, 799.2261, -15.37, 35.00 -GPS, 3, 109318600, 1774, 10, 1.65, -39.4898832, 176.7497012, 29.63, 79.76, 1.35, 348.29, 7.500000, 171687 -CTUN, 605, 0.00, 34.57, 104.8600, 0.00, 0, -899, 1000, 0 -ATT, 0.00, -58.71, 0.00, -15.95, 0.00, 188.09, 198.09 -MOT, 1736, 1950, 1606, 1725 -NTUN, 582.75, 1.91, -344.0703, 3555.748, -48.15734, 497.6754, -364.1504, 266.6606, 666.7737, 718.2010, -25.05, 35.00 -CTUN, 605, 0.00, 33.79, 104.8521, 0.00, 0, -846, 1000, 0 -ATT, 0.00, -53.95, 0.00, 10.23, 0.10, 173.89, 183.89 -MOT, 1464, 1950, 1594, 1814 -NTUN, 582.58, 1.91, -336.6211, 3512.274, -47.70208, 497.7193, -324.5786, 410.2761, 725.5526, 604.4388, -31.09, 35.00 -GPS, 3, 109318800, 1774, 10, 1.65, -39.4898869, 176.7497020, 28.33, 78.07, 1.22, 275.60, 7.670000, 171888 -CTUN, 605, 0.00, 33.14, 104.8432, 0.00, 0, -820, 1000, 0 -ATT, 0.00, -57.91, 0.00, 39.62, 0.00, 155.69, 165.69 -MOT, 1127, 1505, 1377, 1905 -NTUN, 582.46, 1.91, -330.7813, 3453.834, -47.66798, 497.7226, -220.5487, 493.2523, 662.3376, 469.0323, -29.70, 28.36 -CTUN, 605, 0.00, 32.13, 104.8336, 0.00, 0, -835, 1000, 0 -ATT, 0.00, -70.96, 0.00, 66.57, 0.20, 122.57, 132.57 -MOT, 1352, 1293, 1646, 1950 -NTUN, 582.42, 1.91, -329.0781, 3382.540, -48.41506, 497.6505, -94.65003, 521.6314, 538.5292, 391.2786, -20.94, 10.66 -GPS, 3, 109319000, 1774, 10, 1.65, -39.4898919, 176.7497083, 27.10, 76.30, 2.97, 136.94, 7.840000, 172088 -DU32, 7, 270713 -CURR, 130, 526569, 1442, 3923, 4940, 917.0999 -CTUN, 605, 0.00, 30.61, 104.8296, 0.00, -870, -886, 130, 0 -ATT, 0.00, -124.41, 0.00, 77.45, 0.00, 41.91, 51.91 -MOT, 1298, 1127, 1310, 1309 -NTUN, 582.50, 1.91, -325.1836, 3309.187, -48.89795, 497.6032, 29.95437, 489.2549, 413.1711, 377.5279, -6.19, -20.73 -CTUN, 605, 0.00, 28.56, 104.8296, 0.00, -870, -970, 130, 0 -ATT, 0.00, -156.17, 0.00, 69.94, 0.20, 336.75, 346.75 -MOT, 1270, 1127, 1312, 1335 -NTUN, 582.68, 1.91, -323.0078, 3236.811, -49.64940, 497.5288, 107.3899, 415.2329, 288.4855, 417.2560, 6.43, -16.93 -GPS, 3, 109319200, 1774, 10, 1.65, -39.4898939, 176.7497179, 25.44, 74.55, 3.80, 107.48, 7.980000, 172288 -CTUN, 605, 0.00, 28.41, 104.8296, 0.00, -870, -1076, 130, 0 -ATT, 0.00, -152.71, 0.00, 64.34, 0.10, 306.18, 316.18 -MOT, 1246, 1127, 1321, 1351 -NTUN, 582.93, 1.91, -330.1250, 3169.952, -51.79088, 497.3105, 130.2088, 315.1689, 197.5852, 499.8165, 11.68, 10.15 -CTUN, 605, 0.00, 26.93, 104.8296, 0.00, -870, -1184, 130, 0 -ATT, 0.00, -143.37, 0.00, 64.05, 0.00, 285.85, 295.85 -MOT, 1189, 1127, 1407, 1321 -NTUN, 583.20, 1.91, -346.3438, 3112.051, -55.30414, 496.9320, 105.0052, 223.1819, 158.8674, 597.2155, 10.22, 25.76 -GPS, 3, 109319400, 1774, 9, 1.69, -39.4898906, 176.7497254, 23.54, 73.12, 3.50, 69.99, 7.880000, 172469 -CTUN, 603, 0.00, 25.45, 104.8296, 0.00, -870, -1285, 130, 0 -ATT, 0.00, -134.80, 0.00, 68.73, 0.00, 272.62, 282.62 -MOT, 1196, 1127, 1409, 1313 -NTUN, 583.48, 1.91, -363.0430, 3063.878, -58.83408, 496.5265, 47.20593, 146.1634, 180.0501, 684.9847, 6.67, 33.58 -CTUN, 605, 0.00, 24.75, 104.8287, 0.00, -870, -1369, 130, 0 -ATT, 0.00, -123.07, 0.00, 75.90, 0.00, 267.98, 277.98 -MOT, 1185, 1127, 1396, 1337 -NTUN, 583.72, 1.91, -387.3164, 3031.032, -63.37650, 495.9671, -31.08433, 89.92115, 221.5758, 756.4064, 3.74, 35.00 -GPS, 3, 109319600, 1774, 9, 1.69, -39.4898887, 176.7497350, 20.99, 71.82, 4.06, 73.14, 7.690000, 172669 -CTUN, 603, 0.00, 23.27, 104.8270, 0.00, -870, -1444, 130, 0 -ATT, 0.00, -103.68, 0.00, 82.87, 0.10, 273.91, 277.95 -MOT, 1127, 1202, 1391, 1324 -NTUN, 583.86, 1.91, -406.4375, 3004.272, -67.03259, 495.4863, -122.1843, 49.74189, 306.4391, 811.1913, 3.09, 35.00 -CTUN, 605, 0.00, 21.79, 104.8245, 0.00, -681, -1500, 319, 0 -ATT, 0.00, -20.31, 0.00, 86.49, 0.00, 345.36, 335.36 -MOT, 1127, 1384, 1287, 1653 -NTUN, 583.90, 1.91, -418.7969, 2987.503, -69.41275, 495.1584, -216.8283, 36.10131, 412.1984, 845.7218, 3.00, 32.66 -GPS, 3, 109319800, 1774, 9, 1.69, -39.4898841, 176.7497436, 17.85, 69.48, 4.24, 56.43, 8.420000, 172889 -CTUN, 605, 0.00, 20.55, 104.8211, 0.00, -86, -1536, 914, 0 -ATT, 0.00, 19.25, 0.00, 72.34, 0.00, 13.11, 3.71 -MOT, 1950, 1725, 1860, 1742 -NTUN, 583.84, 1.91, -423.7852, 2972.631, -70.56766, 494.9951, -319.7787, 44.03148, 513.2307, 834.8619, 5.90, -34.64 -CTUN, 602, 0.00, 18.71, 104.8169, 0.00, 0, -1511, 1000, 0 -ATT, 0.00, 17.52, 0.00, 43.04, 0.00, 5.96, 3.71 -MOT, 1749, 1547, 1950, 1330 -NTUN, 583.66, 1.91, -420.6367, 2959.340, -70.36213, 495.0244, -442.3090, 87.97829, 605.9703, 770.1948, 18.51, -35.00 -GPS, 3, 109320000, 1774, 9, 1.69, -39.4898802, 176.7497476, 14.94, 66.81, 3.08, 40.35, 9.290000, 173089 -DU32, 7, 270713 -CURR, 1000, 530330, 1411, 5401, 4940, 923.9536 -CTUN, 602, 0.00, 12.01, 104.8118, 0.00, 0, -1370, 1000, 0 -ATT, 0.00, 3.98, 0.00, 19.65, 0.00, 12.77, 3.71 -MOT, 1127, 1127, 1127, 1127 -NTUN, 583.40, 1.91, -407.1758, 2943.127, -68.52136, 495.2826, -217.9949, 130.4473, 698.4833, 687.4017, 30.89, -35.00 -CTUN, 602, 0.00, 16.29, 104.8058, 0.00, 0, -1099, 1000, 0 -ATT, 0.00, 27.53, 0.00, 41.08, 0.00, 32.75, 22.75 -MOT, 1557, 1950, 1237, 1706 -NTUN, 583.32, 1.91, -395.9023, 2922.984, -67.10950, 495.4758, -269.3336, 54.61310, 554.1663, 808.2697, 21.32, -35.00 -GPS, 3, 109320200, 1774, 10, 1.65, -39.4898799, 176.7497487, 12.39, 62.55, 1.34, 40.35, 11.25000, 173289 -CTUN, 603, 0.00, 13.09, 104.7990, 0.00, 0, -1222, 1000, 0 -ATT, 0.00, 56.87, 0.00, 69.99, 0.00, 67.22, 57.22 -MOT, 1679, 1820, 1127, 1846 -NTUN, 583.21, 1.91, -402.2344, 2908.717, -68.49114, 495.2867, -287.6187, 45.52937, 565.9678, 800.0502, 8.15, -35.00 -CTUN, 578, 0.00, 14.35, 104.7914, 0.00, -870, -1346, 130, 0 -ATT, 0.00, 156.63, 0.00, 46.04, 0.00, 184.67, 174.67 -MOT, 1127, 1544, 1130, 1239 -NTUN, 583.07, 1.91, -404.6875, 2895.879, -69.20055, 495.1881, -265.8089, 33.26227, 575.4553, 793.2537, -18.20, 5.31 -GPS, 3, 109320400, 1774, 10, 1.65, -39.4898699, 176.7497426, 9.81, 60.61, 4.97, 332.53, 10.88000, 173490 -CTUN, 578, 0.00, 14.08, 104.7829, 0.00, -870, -1480, 130, 0 -ATT, 0.00, 149.77, 0.00, -9.02, 0.00, 220.06, 210.06 -MOT, 1278, 1278, 1127, 1361 -NTUN, 583.01, 1.91, -408.4961, 2884.354, -70.11276, 495.0598, -193.7366, 50.85666, 545.6195, 814.0635, -27.99, 35.00 -CTUN, 576, 0.00, 13.74, 104.7736, 0.00, -870, -1531, 130, 0 -ATT, 0.00, 128.29, 0.00, -38.60, 0.10, 257.41, 247.41 -MOT, 1336, 1127, 1291, 1291 -NTUN, 583.11, 1.91, -433.0000, 2878.462, -74.37697, 494.4371, -134.0334, 52.91002, 465.3579, 815.7729, 2.34, 35.00 -GPS, 3, 109320600, 1774, 8, 1.71, -39.4898611, 176.7497365, 7.45, 58.98, 5.57, 327.83, 10.30000, 173671 -CTUN, 571, 0.00, 13.44, 104.7633, 0.00, -870, -1314, 130, 0 -ATT, 0.00, 107.77, 0.00, -27.55, 0.00, 264.84, 254.84 -MOT, 1127, 1293, 1196, 1428 -NTUN, 583.33, 1.91, -467.5547, 2870.396, -80.38484, 493.4960, -150.9770, 91.86915, 396.5161, 818.6819, 14.44, 35.00 -CTUN, 516, 0.00, 13.21, 104.7523, 0.00, -870, -1411, 130, 0 -ATT, 0.00, 89.02, 0.00, -11.54, 0.00, 279.99, 269.99 -MOT, 1370, 1298, 1127, 1343 -NTUN, 583.61, 1.91, -522.3203, 2868.453, -89.57277, 491.9113, -108.6711, 131.2928, 367.1207, 759.1534, 19.66, 35.00 -GPS, 3, 109320800, 1774, 8, 1.71, -39.4898528, 176.7497325, 5.04, 57.83, 5.13, 327.83, 9.530000, 173891 -CTUN, 513, 0.00, 13.44, 104.7405, 0.00, -236, -1411, 764, 0 -ATT, 0.00, 74.86, 0.00, 10.78, 0.00, 286.88, 277.84 -MOT, 1876, 1735, 1946, 1127 -NTUN, 583.97, 1.91, -580.3281, 2861.337, -99.38505, 490.0230, -44.62383, 86.11898, 301.8772, 736.1172, 26.90, 32.36 -CTUN, 432, 0.00, 13.31, 104.7328, 0.00, 0, -1353, 1000, 0 -ATT, 0.00, 59.63, 0.00, 18.71, 0.41, 281.12, 277.90 -MOT, 1645, 1253, 1439, 1950 -NTUN, 584.42, 1.91, -639.1797, 2860.326, -109.0425, 487.9649, 87.15263, 70.60261, 215.4250, 786.4186, 20.37, 35.00 -PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 -GPS, 3, 109321000, 1774, 9, 1.67, -39.4898373, 176.7497253, 3.11, 57.51, 7.34, 339.61, 8.290000, 174091 -DU32, 7, 270713 -CURR, 1000, 535491, 1450, 4023, 4897, 933.4984 -CTUN, 346, 0.00, 13.38, 104.7305, 0.00, 0, -1329, 1000, 0 -ATT, 0.00, 63.36, 0.00, 19.05, 0.10, 281.53, 277.92 -MOT, 1662, 1153, 1437, 1950 -NTUN, 585.06, 1.91, -697.1680, 2866.962, -118.1436, 485.8416, 181.4631, 95.10277, 62.98926, 785.7671, 11.68, 35.00 -CTUN, 361, 0.00, 13.35, 104.7305, 0.00, 0, -1320, 1000, 0 -ATT, 0.00, 74.62, 0.00, 18.27, 5.50, 282.69, 278.77 -MOT, 1658, 1127, 1441, 1946 -NTUN, 585.86, 1.91, -773.5469, 2876.895, -129.8300, 482.8501, 252.5412, 110.8882, -73.86363, 755.0845, 4.72, 35.00 -GPS, 3, 109321200, 1774, 9, 1.67, -39.4898250, 176.7497155, 1.52, 57.56, 7.69, 335.81, 7.080000, 174291 -CTUN, 393, 0.00, 13.39, 104.7305, 0.00, -638, -1315, 362, 0 -ATT, 0.00, 89.11, 0.00, 16.41, 0.00, 283.46, 279.63 -MOT, 1303, 1127, 1220, 1508 -NTUN, 586.74, 1.91, -860.4023, 2886.216, -142.8418, 479.1620, 326.0185, 115.1317, -188.8293, 728.4844, -0.99, 35.00 -CTUN, 393, 0.00, 13.40, 104.7305, 0.00, -870, -1325, 130, 0 -ATT, 0.00, 107.02, 0.00, 12.89, 0.00, 283.20, 279.63 -MOT, 1288, 1127, 1206, 1423 -NTUN, 587.72, 1.91, -958.1953, 2900.364, -156.8474, 474.7619, 393.6312, 122.5968, -316.4713, 714.5547, -7.73, 35.00 -GPS, 3, 109321400, 1774, 9, 1.67, -39.4898185, 176.7497104, 0.12, 57.75, 5.62, 336.57, 5.980000, 174491 -CTUN, 393, 0.00, 13.46, 104.7305, 0.00, -870, -1339, 130, 0 -ATT, 0.00, 129.17, 0.00, 12.32, 0.00, 281.79, 279.63 -MOT, 1307, 1127, 1178, 1433 -NTUN, 588.74, 1.91, -1064.195, 2915.609, -171.4368, 469.6908, 452.5079, 123.2390, -430.4493, 694.7907, -15.16, 35.00 -CTUN, 389, 0.00, 13.31, 104.7305, 0.00, -870, -1368, 130, 0 -ATT, 0.00, 157.18, 0.00, 14.65, 0.00, 281.10, 279.63 -MOT, 1351, 1127, 1149, 1418 -NTUN, 589.78, 1.91, -1171.824, 2931.477, -185.5907, 464.2802, 480.2729, 117.1170, -528.5390, 685.8939, -20.60, 35.00 -GPS, 3, 109321600, 1774, 9, 1.67, -39.4898096, 176.7497037, -1.19, 58.71, 5.60, 337.09, 4.490000, 174692 -CTUN, 272, 0.00, 13.20, 104.7305, 0.00, -870, -1339, 130, 0 -ATT, 0.00, -175.09, 0.00, 17.35, 0.20, 281.91, 279.63 -MOT, 1197, 1396, 1324, 1127 -NTUN, 590.81, 1.91, -1282.043, 2948.089, -199.3977, 458.5200, 478.9667, 131.3042, -590.0704, 680.3981, -23.82, 35.00 -CTUN, 218, 0.00, 13.14, 104.7305, 0.00, -870, -1227, 130, 0 -ATT, 0.00, -177.48, 0.00, 20.37, 0.00, 282.11, 279.63 -MOT, 1127, 1429, 1288, 1200 -NTUN, 591.80, 1.91, -1388.422, 2965.782, -211.9930, 452.8344, 494.3753, 136.9094, -625.9529, 661.1439, -24.34, 35.00 -GPS, 3, 109321800, 1774, 8, 1.72, -39.4898085, 176.7497053, -2.08, 58.53, 2.39, 337.09, 3.990000, 174872 -CTUN, 219, 0.00, 13.21, 104.7305, 0.00, -870, -1239, 130, 0 -ATT, 0.00, 177.23, 0.00, 18.82, 0.00, 281.76, 279.63 -MOT, 1127, 1392, 1239, 1220 -NTUN, 592.72, 1.91, -1494.129, 2982.850, -223.9310, 447.0513, 541.4648, 123.1711, -688.3793, 653.1698, -27.42, 35.00 -CTUN, 217, 0.00, 13.21, 104.7305, 0.00, -870, -1218, 130, 0 -ATT, 0.00, 178.30, 0.00, 18.35, 0.00, 281.17, 279.63 -MOT, 1127, 1409, 1332, 1177 -NTUN, 593.62, 1.91, -1585.648, 2995.039, -233.9484, 441.8916, 577.6542, 129.8140, -740.9146, 641.4404, -30.09, 35.00 -GPS, 3, 109322000, 1774, 8, 1.72, -39.4898098, 176.7497048, -2.88, 58.51, 0.47, 337.09, 3.470000, 175072 -DU32, 7, 270713 -CURR, 130, 538154, 1541, 1946, 4897, 940.1125 -CTUN, 183, 0.00, 13.21, 104.7305, 0.00, -870, -1193, 130, 0 -ATT, 0.00, 178.06, 0.00, 18.67, 0.00, 280.93, 279.63 -MOT, 1127, 1385, 1307, 1226 -NTUN, 594.43, 1.91, -1681.465, 3007.260, -244.0143, 436.4138, 599.8972, 132.0768, -779.6234, 593.7906, -32.11, 35.00 -CTUN, 0, 0.00, 13.21, 104.7305, 0.00, -870, -1174, 130, 0 -ATT, 0.00, 177.62, 0.00, 18.58, -0.32, 280.91, 279.58 -MOT, 1127, 1415, 1313, 1189 -NTUN, 595.18, 1.91, -1758.500, 3016.493, -251.8157, 431.9593, 625.1893, 135.8845, -793.5139, 575.0963, -33.06, 35.00 -GPS, 3, 109322200, 1774, 8, 1.72, -39.4898109, 176.7497047, -3.49, 58.49, 0.27, 337.09, 3.010000, 175273 -CTUN, 0, 0.00, 13.24, 104.7305, 0.00, -870, -1153, 130, 0 -ATT, 0.00, 177.56, 0.00, 18.55, 0.00, 280.58, 279.58 -MOT, 1127, 1401, 1320, 1195 -NTUN, 595.86, 1.91, -1838.070, 3025.386, -259.6159, 427.3168, 640.0800, 141.0834, -818.3968, 539.0980, -34.31, 34.80 -CTUN, 0, 0.00, 13.19, 104.7305, 0.00, -870, -1130, 130, 0 -ATT, 0.00, 177.48, 0.00, 18.47, 0.00, 280.63, 279.58 -MOT, 1127, 1393, 1330, 1195 -NTUN, 596.49, 1.91, -1902.324, 3031.579, -265.7613, 423.5221, 657.5590, 145.8543, -830.9405, 519.5554, -34.88, 34.16 -GPS, 3, 109322400, 1774, 8, 1.72, -39.4898118, 176.7497048, -3.95, 58.50, 0.45, 337.09, 2.630000, 175473 -CTUN, 0, 0.00, 13.19, 104.7305, 0.00, -870, -1108, 130, 0 -ATT, 0.00, 177.44, 0.00, 18.47, -3.25, 280.47, 279.36 -MOT, 1127, 1397, 1318, 1202 -NTUN, 597.05, 1.91, -1968.113, 3037.303, -271.8982, 419.6086, 668.7850, 150.6082, -848.7465, 489.9279, -35.00, 33.04 -CTUN, 0, 0.00, 13.07, 104.7305, 0.00, -870, -1085, 130, 0 -ATT, 0.00, 177.35, 0.00, 18.59, -28.73, 280.29, 276.31 -MOT, 1183, 1472, 1262, 1127 -NTUN, 597.57, 1.91, -2021.555, 3040.794, -276.8151, 416.3813, 679.1684, 155.3190, -858.4435, 472.7311, -35.00, 32.24 -GPS, 3, 109322600, 1774, 8, 1.72, -39.4898126, 176.7497049, -4.26, 58.56, 0.52, 337.09, 2.270000, 175673 -CTUN, 0, 0.00, 13.14, 104.7305, 0.00, -870, -1064, 130, 0 -ATT, 0.00, 177.26, 0.00, 18.49, -45.10, 279.72, 269.72 -MOT, 1243, 1434, 1240, 1127 -NTUN, 598.04, 1.91, -2076.004, 3043.749, -281.7352, 413.0681, 684.3371, 160.6293, -871.5123, 448.1811, -35.00, 31.19 -CTUN, 0, 0.00, 13.27, 104.7305, 0.00, -870, -1039, 130, 0 -ATT, 0.00, 177.16, 0.00, 18.49, -45.10, 279.54, 269.54 -MOT, 1251, 1429, 1237, 1127 -NTUN, 598.46, 1.91, -2119.199, 3044.838, -285.6277, 410.3862, 689.5823, 165.5170, -878.7162, 433.8868, -35.00, 30.51 -GPS, 3, 109322800, 1774, 8, 1.72, -39.4898135, 176.7497050, -4.45, 58.58, 0.49, 337.09, 1.980000, 175893 -CTUN, 0, 0.00, 13.16, 104.7305, 0.00, -870, -1016, 130, 0 -ATT, 0.00, 177.30, 0.00, 18.49, -45.00, 279.53, 269.53 -MOT, 1238, 1460, 1218, 1127 -NTUN, 598.86, 1.91, -2162.938, 3045.476, -289.5188, 407.6504, 693.5057, 169.4538, -888.1757, 414.1785, -35.00, 29.46 -CTUN, 0, 0.00, 13.22, 104.7305, 0.00, -870, -992, 130, 0 -ATT, 0.00, 177.10, 0.00, 18.43, -45.10, 279.21, 269.21 -MOT, 1251, 1432, 1235, 1127 -NTUN, 599.20, 1.91, -2199.230, 3044.573, -292.7778, 405.3161, 694.2765, 175.4252, -894.5173, 400.2984, -35.00, 28.81 -GPS, 3, 109323000, 1774, 8, 1.72, -39.4898144, 176.7497054, -4.50, 58.63, 0.52, 337.09, 1.720000, 176074 -DU32, 7, 270713 -CURR, 130, 539454, 1467, 3743, 4962, 948.4289 -CTUN, 0, 0.00, 13.15, 104.7305, 0.00, -870, -968, 130, 0 -ATT, 0.00, 177.02, 0.00, 18.27, -45.10, 279.03, 269.03 -MOT, 1253, 1423, 1241, 1127 -NTUN, 599.48, 1.91, -2233.727, 3042.855, -295.8798, 403.0572, 691.2303, 181.1217, -901.3269, 384.7205, -35.00, 28.13 -CTUN, 0, 0.00, 13.08, 104.7305, 0.00, -870, -944, 130, 0 -ATT, 0.00, 176.97, 0.00, 18.44, -45.00, 278.96, 268.96 -MOT, 1241, 1459, 1216, 1127 -NTUN, 599.73, 1.91, -2258.535, 3040.441, -298.1553, 401.3769, 689.3187, 184.6811, -901.6480, 383.9673, -35.00, 27.88 -GPS, 3, 109323200, 1774, 8, 1.72, -39.4898154, 176.7497055, -4.45, 58.54, 0.44, 337.09, 1.570000, 176274 -CTUN, 0, 0.00, 13.05, 104.7305, 0.00, -870, -921, 130, 0 -ATT, 0.00, 177.03, 0.00, 18.28, -45.00, 278.74, 268.74 -MOT, 1243, 1432, 1242, 1127 -NTUN, 599.93, 1.91, -2283.066, 3037.455, -300.4188, 399.6855, 682.6840, 190.4137, -902.5809, 381.7693, -35.00, 27.74 -CTUN, 0, 0.00, 13.20, 104.7305, 0.00, -870, -896, 130, 0 -ATT, 0.00, 176.87, 0.00, 18.07, -45.10, 278.25, 268.25 -MOT, 1258, 1411, 1249, 1127 -NTUN, 600.10, 1.91, -2300.137, 3034.012, -302.0659, 398.4422, 675.0828, 194.3174, -901.9727, 383.2039, -35.00, 27.71 -GPS, 3, 109323400, 1774, 8, 1.72, -39.4898165, 176.7497057, -4.31, 58.44, 0.44, 337.09, 1.450000, 176474 -CTUN, 0, 0.00, 13.05, 104.7305, 0.00, -870, -871, 130, 0 -ATT, 0.00, 176.92, 0.00, 17.98, -45.10, 277.92, 267.92 -MOT, 1243, 1440, 1233, 1127 -NTUN, 600.24, 1.91, -2316.523, 3030.189, -303.6688, 397.2220, 668.1585, 198.6399, -902.7764, 381.3068, -35.00, 27.14 -CTUN, 0, 0.00, 13.12, 104.7305, 0.00, -870, -847, 130, 0 -ATT, 0.00, 176.98, 0.00, 18.05, -45.00, 277.89, 267.89 -MOT, 1260, 1431, 1227, 1127 -NTUN, 600.34, 1.91, -2326.363, 3026.005, -304.7456, 396.3964, 658.2323, 204.1594, -901.9138, 383.3424, -35.00, 26.93 -GPS, 3, 109323600, 1774, 8, 1.73, -39.4898172, 176.7497061, -4.09, 58.49, 0.41, 337.09, 1.250000, 176675 -CTUN, 0, 0.00, 13.02, 104.7305, 0.00, -870, -823, 130, 0 -ATT, 0.00, 177.08, 0.00, 18.01, -45.10, 278.09, 268.09 -MOT, 1254, 1418, 1244, 1127 -NTUN, 600.41, 1.91, -2335.398, 3021.181, -305.7934, 395.5887, 647.0358, 208.6652, -902.3506, 382.3133, -35.00, 27.30 -CTUN, 0, 0.00, 13.03, 104.7305, 0.00, -870, -800, 130, 0 -ATT, 0.00, 177.15, 0.00, 18.04, -45.00, 278.24, 268.24 -MOT, 1238, 1433, 1247, 1127 -NTUN, 600.45, 1.91, -2339.551, 3016.187, -306.4500, 395.0803, 635.9725, 211.0752, -901.3200, 384.7365, -35.00, 27.35 -GPS, 3, 109323800, 1774, 8, 1.73, -39.4898178, 176.7497061, -3.77, 58.52, 0.28, 337.09, 1.100000, 176894 -CTUN, 0, 0.00, 12.92, 104.7305, 0.00, -870, -775, 130, 0 -ATT, 0.00, 177.19, 0.00, 17.93, -45.00, 278.16, 268.16 -MOT, 1248, 1442, 1227, 1127 -NTUN, 600.48, 1.91, -2342.578, 3010.786, -307.0402, 394.6218, 627.2982, 214.5074, -900.8243, 385.8958, -35.00, 27.49 -CTUN, 0, 0.00, 12.95, 104.7305, 0.00, -870, -750, 130, 0 -ATT, 0.00, 177.42, 0.00, 17.97, -45.00, 278.43, 268.43 -MOT, 1250, 1431, 1236, 1127 -NTUN, 600.49, 1.91, -2343.605, 3005.352, -307.4695, 394.2873, 614.8159, 218.1698, -900.0731, 387.6447, -35.00, 27.57 -GPS, 3, 109324000, 1774, 8, 1.73, -39.4898187, 176.7497066, -3.45, 58.48, 0.31, 337.09, 1.010000, 177076 -DU32, 7, 270713 -CURR, 130, 540754, 1444, 3474, 5006, 959.8994 -ERR, 12, 1 -EV, 11 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -PM, 0, 0, 1, 1000, 113914, 0, 0, 0, 0 -DU32, 7, 270425 -MODE, STABILIZE, 271 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, RTL, 271 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, RTL, 271 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, STABILIZE, 271 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 -DU32, 7, 270425 -MODE, STABILIZE, 271 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, RTL, 271 -DU32, 7, 270425 -DU32, 7, 270425 -MODE, STABILIZE, 271 -DU32, 7, 270425 -DU32, 7, 270425 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -DU32, 7, 270425 -DU32, 7, 270425 -DU32, 7, 270425 -EV, 18 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10260, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10317, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10206, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10305, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10257, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10287, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10235, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10207, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10219, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10327, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10258, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10318, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10218, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10274, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10307, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10233, 2, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10285, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 1, 1000, 26884, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10231, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 5, 1000, 11978, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 46, 1000, 18406, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 28, 1000, 24550, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10261, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10290, 5, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10247, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10247, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10210, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10295, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10212, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10240, 5, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10268, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10278, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10299, 4, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10296, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10224, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10273, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10273, 1, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10264, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10318, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 25, 1000, 15546, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 67, 1000, 24342, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -PARM, SYSID_MYGCS, 253.0000 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 6, 1000, 25107, 4, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10321, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10285, 3, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10243, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10208, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10263, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10223, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10264, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10245, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10232, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10228, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10321, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10207, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10281, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10199, 0, 0, 0, 0 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10237, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10300, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10224, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10203, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10307, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -MODE, RTL, 271 -DU32, 7, 270937 -MODE, STABILIZE, 271 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10250, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10215, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10266, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10215, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10305, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10227, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10322, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10306, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10289, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10218, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10299, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10242, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10300, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10223, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10268, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10232, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10242, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10313, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10228, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10275, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10196, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10319, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10308, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10238, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10275, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10188, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10299, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10306, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10238, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10219, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10268, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10216, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10267, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10255, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10264, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10307, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10267, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10296, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10313, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10198, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10296, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10237, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10262, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10303, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10277, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10217, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10227, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10301, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10284, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10280, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10247, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10257, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 -DU32, 7, 270937 diff --git a/Tools/LogAnalyzer/examples/nan.log b/Tools/LogAnalyzer/examples/nan.log deleted file mode 100644 index e93cb4328c6838..00000000000000 --- a/Tools/LogAnalyzer/examples/nan.log +++ /dev/null @@ -1,2740 +0,0 @@ -ArduCopter V3.1 - -FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format -FMT, 129, 23, PARM, Nf, Name,Value -FMT, 130, 45, GPS, BIHBcLLeeEefI, Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T -FMT, 131, 31, IMU, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 135, 31, IMU2, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 132, 67, MSG, Z, Message -FMT, 133, 23, RCIN, Ihhhhhhhh, TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8 -FMT, 134, 23, RCOU, Ihhhhhhhh, TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8 -FMT, 25, 25, ATUN, BBfffff, Axis,TuneStep,RateMin,RateMax,RPGain,RDGain,SPGain -FMT, 26, 9, ATDE, cf, Angle,Rate -FMT, 9, 23, CURR, IhIhhhf, TimeMS,ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot -FMT, 12, 20, OF, hhBccee, Dx,Dy,SQual,X,Y,Roll,Pitch -FMT, 5, 47, NTUN, Iffffffffff, TimeMS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY -FMT, 4, 33, CTUN, Ihhhffecchh, TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt -FMT, 15, 25, MAG, Ihhhhhhhhh, TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 27, 25, MAG2, Ihhhhhhhhh, TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 6, 19, PM, BBHHIhBHB, RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr -FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng -FMT, 1, 19, ATT, IccccCC, TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw -FMT, 3, 6, MODE, Mh, Mode,ThrCrs -FMT, 10, 3, STRT, , -FMT, 13, 4, EV, B, Id -FMT, 20, 6, D16, Bh, Id,Value -FMT, 21, 6, DU16, BH, Id,Value -FMT, 22, 8, D32, Bi, Id,Value -FMT, 23, 8, DU32, BI, Id,Value -FMT, 24, 8, DFLT, Bf, Id,Value -FMT, 18, 27, CAM, IHLLeccC, GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw -FMT, 19, 5, ERR, BB, Subsys,ECode -PARM, SYSID_SW_MREV, 120 -PARM, SYSID_SW_TYPE, 10 -PARM, SYSID_THISMAV, 1 -PARM, SYSID_MYGCS, 255 -PARM, SERIAL1_BAUD, 57 -PARM, SERIAL2_BAUD, 57 -PARM, TELEM_DELAY, 0 -PARM, RTL_ALT, 1500 -PARM, SONAR_ENABLE, 0 -PARM, SONAR_TYPE, 0 -PARM, SONAR_GAIN, 0.8 -PARM, FS_BATT_ENABLE, 2 -PARM, FS_BATT_VOLTAGE, 14.5 -PARM, FS_BATT_MAH, 0 -PARM, FS_GPS_ENABLE, 2 -PARM, FS_GCS_ENABLE, 1 -PARM, GPS_HDOP_GOOD, 200 -PARM, MAG_ENABLE, 1 -PARM, FLOW_ENABLE, 0 -PARM, SUPER_SIMPLE, 0 -PARM, RTL_ALT_FINAL, 0 -PARM, RSSI_PIN, -1 -PARM, RSSI_RANGE, 5 -PARM, WP_YAW_BEHAVIOR, 2 -PARM, WP_TOTAL, 1 -PARM, WP_INDEX, 0 -PARM, CIRCLE_RADIUS, 10 -PARM, CIRCLE_RATE, 20 -PARM, RTL_LOIT_TIME, 5000 -PARM, LAND_SPEED, 50 -PARM, PILOT_VELZ_MAX, 250 -PARM, THR_MIN, 190 -PARM, THR_MAX, 1000 -PARM, FS_THR_ENABLE, 1 -PARM, FS_THR_VALUE, 975 -PARM, TRIM_THROTTLE, 424 -PARM, THR_MID, 500 -PARM, FLTMODE1, 0 -PARM, FLTMODE2, 11 -PARM, FLTMODE3, 2 -PARM, FLTMODE4, 9 -PARM, FLTMODE5, 5 -PARM, FLTMODE6, 7 -PARM, SIMPLE, 0 -PARM, LOG_BITMASK, -22530 -PARM, ESC, 0 -PARM, TUNE, 0 -PARM, TUNE_LOW, 0 -PARM, TUNE_HIGH, 1000 -PARM, FRAME, 1 -PARM, CH7_OPT, 4 -PARM, CH8_OPT, 17 -PARM, ARMING_CHECK, 1 -PARM, ANGLE_MAX, 4500 -PARM, ANGLE_RATE_MAX, 18000 -PARM, RC1_MIN, 990 -PARM, RC1_TRIM, 1509 -PARM, RC1_MAX, 2016 -PARM, RC1_REV, 1 -PARM, RC1_DZ, 30 -PARM, RC2_MIN, 993 -PARM, RC2_TRIM, 1509 -PARM, RC2_MAX, 2016 -PARM, RC2_REV, 1 -PARM, RC2_DZ, 30 -PARM, RC3_MIN, 1022 -PARM, RC3_TRIM, 1500 -PARM, RC3_MAX, 1997 -PARM, RC3_REV, 1 -PARM, RC3_DZ, 30 -PARM, RC4_MIN, 992 -PARM, RC4_TRIM, 1497 -PARM, RC4_MAX, 2017 -PARM, RC4_REV, 1 -PARM, RC4_DZ, 40 -PARM, RC5_MIN, 992 -PARM, RC5_TRIM, 1500 -PARM, RC5_MAX, 2017 -PARM, RC5_REV, 1 -PARM, RC5_DZ, 0 -PARM, RC5_FUNCTION, 0 -PARM, RC6_MIN, 992 -PARM, RC6_TRIM, 1500 -PARM, RC6_MAX, 2017 -PARM, RC6_REV, 1 -PARM, RC6_DZ, 0 -PARM, RC6_FUNCTION, 0 -PARM, RC7_MIN, 992 -PARM, RC7_TRIM, 1500 -PARM, RC7_MAX, 2017 -PARM, RC7_REV, 1 -PARM, RC7_DZ, 0 -PARM, RC7_FUNCTION, 0 -PARM, RC8_MIN, 991 -PARM, RC8_TRIM, 1500 -PARM, RC8_MAX, 2017 -PARM, RC8_REV, 1 -PARM, RC8_DZ, 0 -PARM, RC8_FUNCTION, 0 -PARM, RC9_MIN, 1100 -PARM, RC9_TRIM, 1500 -PARM, RC9_MAX, 1900 -PARM, RC9_REV, 1 -PARM, RC9_DZ, 0 -PARM, RC9_FUNCTION, 0 -PARM, RC10_MIN, 1100 -PARM, RC10_TRIM, 1500 -PARM, RC10_MAX, 1900 -PARM, RC10_REV, 1 -PARM, RC10_DZ, 0 -PARM, RC10_FUNCTION, 0 -PARM, RC11_MIN, 1100 -PARM, RC11_TRIM, 1500 -PARM, RC11_MAX, 1900 -PARM, RC11_REV, 1 -PARM, RC11_DZ, 0 -PARM, RC11_FUNCTION, 0 -PARM, RC12_MIN, 1100 -PARM, RC12_TRIM, 1500 -PARM, RC12_MAX, 1900 -PARM, RC12_REV, 1 -PARM, RC12_DZ, 0 -PARM, RC12_FUNCTION, 0 -PARM, RC_SPEED, 490 -PARM, ACRO_RP_P, 4.5 -PARM, ACRO_YAW_P, 4.5 -PARM, ACRO_BAL_ROLL, 1 -PARM, ACRO_BAL_PITCH, 1 -PARM, ACRO_TRAINER, 2 -PARM, RATE_RLL_P, 0.17 -PARM, RATE_RLL_I, 0.17 -PARM, RATE_RLL_D, 0.0125 -PARM, RATE_RLL_IMAX, 500 -PARM, RATE_PIT_P, 0.21 -PARM, RATE_PIT_I, 0.21 -PARM, RATE_PIT_D, 0.015 -PARM, RATE_PIT_IMAX, 500 -PARM, RATE_YAW_P, 0.2 -PARM, RATE_YAW_I, 0.02 -PARM, RATE_YAW_D, 0 -PARM, RATE_YAW_IMAX, 800 -PARM, LOITER_LAT_P, 1 -PARM, LOITER_LAT_I, 0.5 -PARM, LOITER_LAT_D, 0 -PARM, LOITER_LAT_IMAX, 400 -PARM, LOITER_LON_P, 1 -PARM, LOITER_LON_I, 0.5 -PARM, LOITER_LON_D, 0 -PARM, LOITER_LON_IMAX, 400 -PARM, THR_RATE_P, 3.4 -PARM, THR_RATE_I, 0 -PARM, THR_RATE_D, 0 -PARM, THR_RATE_IMAX, 300 -PARM, THR_ACCEL_P, 0.75 -PARM, THR_ACCEL_I, 1.5 -PARM, THR_ACCEL_D, 0 -PARM, THR_ACCEL_IMAX, 500 -PARM, OF_RLL_P, 2.5 -PARM, OF_RLL_I, 0.5 -PARM, OF_RLL_D, 0.12 -PARM, OF_RLL_IMAX, 100 -PARM, OF_PIT_P, 2.5 -PARM, OF_PIT_I, 0.5 -PARM, OF_PIT_D, 0.12 -PARM, OF_PIT_IMAX, 100 -PARM, STB_RLL_P, 7.59375 -PARM, STB_RLL_I, 0 -PARM, STB_RLL_IMAX, 0 -PARM, STB_PIT_P, 7.59375 -PARM, STB_PIT_I, 0 -PARM, STB_PIT_IMAX, 0 -PARM, STB_YAW_P, 4.5 -PARM, STB_YAW_I, 0 -PARM, STB_YAW_IMAX, 0 -PARM, THR_ALT_P, 1.25 -PARM, THR_ALT_I, 0 -PARM, THR_ALT_IMAX, 300 -PARM, HLD_LAT_P, 1 -PARM, HLD_LAT_I, 0 -PARM, HLD_LAT_IMAX, 0 -PARM, HLD_LON_P, 1 -PARM, HLD_LON_I, 0 -PARM, HLD_LON_IMAX, 0 -PARM, CAM_TRIGG_TYPE, 0 -PARM, CAM_DURATION, 10 -PARM, CAM_SERVO_ON, 1300 -PARM, CAM_SERVO_OFF, 1100 -PARM, CAM_TRIGG_DIST, 0 -PARM, RELAY_PIN, 54 -PARM, RELAY_PIN2, -1 -PARM, RELAY_PIN3, -1 -PARM, RELAY_PIN4, -1 -PARM, COMPASS_OFS_X, -86.91773 -PARM, COMPASS_OFS_Y, 10.53659 -PARM, COMPASS_OFS_Z, 139.6827 -PARM, COMPASS_DEC, 0 -PARM, COMPASS_LEARN, 0 -PARM, COMPASS_USE, 1 -PARM, COMPASS_AUTODEC, 1 -PARM, COMPASS_MOTCT, 1 -PARM, COMPASS_MOT_X, NaN -PARM, COMPASS_MOT_Y, NaN -PARM, COMPASS_MOT_Z, NaN -PARM, COMPASS_ORIENT, 0 -PARM, COMPASS_EXTERNAL, 1 -PARM, COMPASS_OFS2_X, 0 -PARM, COMPASS_OFS2_Y, 0 -PARM, COMPASS_OFS2_Z, 0 -PARM, COMPASS_MOT2_X, 0 -PARM, COMPASS_MOT2_Y, 0 -PARM, COMPASS_MOT2_Z, 0 -PARM, INS_PRODUCT_ID, 5 -PARM, INS_ACCSCAL_X, 1.007623 -PARM, INS_ACCSCAL_Y, 1.004452 -PARM, INS_ACCSCAL_Z, 0.9874112 -PARM, INS_ACCOFFS_X, -0.1485449 -PARM, INS_ACCOFFS_Y, -0.2596635 -PARM, INS_ACCOFFS_Z, -0.4252791 -PARM, INS_GYROFFS_X, -0.02919539 -PARM, INS_GYROFFS_Y, 0.04272092 -PARM, INS_GYROFFS_Z, -0.002589351 -PARM, INS_MPU6K_FILTER, 0 -PARM, INS_ACC2SCAL_X, 1.029834 -PARM, INS_ACC2SCAL_Y, 1.005518 -PARM, INS_ACC2SCAL_Z, 0.9937073 -PARM, INS_ACC2OFFS_X, 1.241575 -PARM, INS_ACC2OFFS_Y, 1.355125 -PARM, INS_ACC2OFFS_Z, 1.51342 -PARM, INS_GYR2OFFS_X, 0.0258936 -PARM, INS_GYR2OFFS_Y, 0.01227257 -PARM, INS_GYR2OFFS_Z, -0.003733256 -PARM, INAV_TC_XY, 2.5 -PARM, INAV_TC_Z, 6 -PARM, WPNAV_SPEED, 300 -PARM, WPNAV_RADIUS, 200 -PARM, WPNAV_SPEED_UP, 250 -PARM, WPNAV_SPEED_DN, 100 -PARM, WPNAV_LOIT_SPEED, 500 -PARM, WPNAV_ACCEL, 100 -PARM, SR0_RAW_SENS, 0 -PARM, SR0_EXT_STAT, 0 -PARM, SR0_RC_CHAN, 0 -PARM, SR0_RAW_CTRL, 0 -PARM, SR0_POSITION, 0 -PARM, SR0_EXTRA1, 0 -PARM, SR0_EXTRA2, 0 -PARM, SR0_EXTRA3, 0 -PARM, SR0_PARAMS, 0 -PARM, SR1_RAW_SENS, 2 -PARM, SR1_EXT_STAT, 2 -PARM, SR1_RC_CHAN, 2 -PARM, SR1_RAW_CTRL, 0 -PARM, SR1_POSITION, 3 -PARM, SR1_EXTRA1, 10 -PARM, SR1_EXTRA2, 10 -PARM, SR1_EXTRA3, 2 -PARM, SR1_PARAMS, 10 -PARM, SR2_RAW_SENS, 0 -PARM, SR2_EXT_STAT, 0 -PARM, SR2_RC_CHAN, 0 -PARM, SR2_RAW_CTRL, 0 -PARM, SR2_POSITION, 0 -PARM, SR2_EXTRA1, 0 -PARM, SR2_EXTRA2, 0 -PARM, SR2_EXTRA3, 0 -PARM, SR2_PARAMS, 0 -PARM, AHRS_GPS_GAIN, 1 -PARM, AHRS_GPS_USE, 1 -PARM, AHRS_YAW_P, 0.1 -PARM, AHRS_RP_P, 0.1 -PARM, AHRS_WIND_MAX, 0 -PARM, AHRS_TRIM_X, -0.03818516 -PARM, AHRS_TRIM_Y, 0.0007720405 -PARM, AHRS_TRIM_Z, 0 -PARM, AHRS_ORIENTATION, 0 -PARM, AHRS_COMP_BETA, 0.1 -PARM, AHRS_GPS_MINSATS, 6 -PARM, AHRS_GPS_DELAY, 1 -PARM, MNT_MODE, 0 -PARM, MNT_RETRACT_X, 0 -PARM, MNT_RETRACT_Y, 0 -PARM, MNT_RETRACT_Z, 0 -PARM, MNT_NEUTRAL_X, 0 -PARM, MNT_NEUTRAL_Y, 0 -PARM, MNT_NEUTRAL_Z, 0 -PARM, MNT_CONTROL_X, 0 -PARM, MNT_CONTROL_Y, 0 -PARM, MNT_CONTROL_Z, 0 -PARM, MNT_STAB_ROLL, 0 -PARM, MNT_STAB_TILT, 0 -PARM, MNT_STAB_PAN, 0 -PARM, MNT_RC_IN_ROLL, 0 -PARM, MNT_ANGMIN_ROL, -4500 -PARM, MNT_ANGMAX_ROL, 4500 -PARM, MNT_RC_IN_TILT, 0 -PARM, MNT_ANGMIN_TIL, -4500 -PARM, MNT_ANGMAX_TIL, 4500 -PARM, MNT_RC_IN_PAN, 0 -PARM, MNT_ANGMIN_PAN, -4500 -PARM, MNT_ANGMAX_PAN, 4500 -PARM, MNT_JSTICK_SPD, 0 -PARM, BATT_MONITOR, 4 -PARM, BATT_VOLT_PIN, 2 -PARM, BATT_CURR_PIN, 3 -PARM, BATT_VOLT_MULT, 10.39345 -PARM, BATT_AMP_PERVOLT, 18.0018 -PARM, BATT_AMP_OFFSET, 0 -PARM, BATT_CAPACITY, 8000 -PARM, BRD_PWM_COUNT, 4 -PARM, GND_ABS_PRESS, 101322.9 -PARM, GND_TEMP, 38.6347 -PARM, GND_ALT_OFFSET, 0 -PARM, SCHED_DEBUG, 0 -PARM, FENCE_ENABLE, 0 -PARM, FENCE_TYPE, 3 -PARM, FENCE_ACTION, 1 -PARM, FENCE_ALT_MAX, 100 -PARM, FENCE_RADIUS, 150 -PARM, FENCE_MARGIN, 2 -PARM, GPSGLITCH_ENABLE, 1 -PARM, GPSGLITCH_RADIUS, 200 -PARM, GPSGLITCH_ACCEL, 1000 -PARM, MOT_TCRV_ENABLE, 1 -PARM, MOT_TCRV_MIDPCT, 52 -PARM, MOT_TCRV_MAXPCT, 93 -PARM, MOT_SPIN_ARMED, 100 -PARM, RCMAP_ROLL, 1 -PARM, RCMAP_PITCH, 2 -PARM, RCMAP_THROTTLE, 3 -PARM, RCMAP_YAW, 4 -MSG, ArduCopter V3.1.1 (681dafcf) -MSG, PX4: bf42b124 NuttX: a6686464 -MSG, PX4v2 26002600 0A473234 33353231 -MODE, Stabilize, 424 -D32, 9, 18954 -CMD, 1, 0, 16, 0, 0, 0.00, 14.110576, 100.6192012 -EV, 10 -CTUN, 95890, 0, 0, 0, 0, -0.07, -0.13, 0.00, 0.00, 0, 0 -DU32, 7, 262745 -CURR, 95891, 0, 0, 1532, 53, 5302, 11.98451 -ATT, 95891, 0.00, -0.25, 0.00, 0.26, 189.54, 189.54 -RCIN, 95891, 1503, 1504, 1027, 1511, 992, 992, 993, 991 -RCOU, 95892, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 95892, 0.0003300551, 3.118068E-05, 0.0001806917, 0.04847138, 0.4273195, -9.78664 -IMU2, 95892, 0.002608102, 0.000912793, -0.001082554, 0.01101041, 0.5059863, -9.731324 -GPS, 3, 56674000, 1777, 12, 1.32, 14.1105766, 100.6191906, -0.06, -2.50, 2.48, 287.33, -1.2, 95901 -IMU, 95910, -0.0009821467, 0.0001306534, 0.000565017, 0.0440198, 0.4103907, -9.796521 -IMU2, 95910, -0.0007523485, 0.001337406, 0.003994141, 0.06996822, 0.5036547, -9.86237 -GPS, 3, 56674600, 1777, 12, 1.32, 14.1105772, 100.619181, -0.06, -0.64, 2.24, 285.51, -1.32, 95922 -IMU, 95930, -0.000161415, -6.018579E-05, -0.0009395918, 0.04602193, 0.4273452, -9.776276 -IMU2, 95930, 0.004217926, 0.004194447, 0.002743313, 0.0233587, 0.5833725, -9.837802 -IMU, 95950, -6.760471E-05, -7.643178E-05, -0.001094451, 0.04254892, 0.4280649, -9.788452 -IMU2, 95950, -0.001128796, 0.000945677, -0.003048411, 0.03911483, 0.5818061, -9.765361 -IMU, 95972, 0.0002469253, 0.000534825, 0.002132082, 0.02599005, 0.4356834, -9.82601 -IMU2, 95972, 0.003803164, 0.0007087337, 0.003556, -0.01116824, 0.542949, -9.840604 -MAG, 95980, -424, 68, 62, -86, 10, 139, 0, 0, 0 -MAG2, 95980, -282, -19, 236, 0, 0, 0, 0, 0, 0 -CTUN, 95990, 0, 0, 0, 0, -0.06, -0.16, 0.00, 0.00, 0, 0 -ATT, 95991, 0.00, -0.36, 0.00, 0.17, 189.55, 189.55 -RCIN, 95991, 1503, 1504, 1026, 1511, 992, 992, 992, 992 -RCOU, 95991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 95991, -0.0008315947, -0.0006118864, 0.005963499, 0.07896003, 0.4259605, -9.77841 -IMU2, 95991, 0.004842978, -0.005481538, 0.00072484, 0.04396272, 0.5337764, -9.792355 -IMU, 96010, 0.001237309, -0.0001293421, -0.00771925, 0.0662415, 0.3264562, -9.784401 -IMU2, 96010, 0.001461238, -0.0009936234, -0.01617744, -0.06194246, 0.4550481, -9.752249 -IMU, 96030, -0.002142342, 0.001001354, -0.008340571, 0.05505657, 0.4283919, -9.779114 -IMU2, 96030, -0.01055922, -0.004093088, -0.007808299, 0.03303206, 0.538103, -9.692242 -GPS, 3, 56674600, 1777, 12, 1.32, 14.1105816, 100.6191549, -0.06, 2.17, 1.46, 282.10, -0.83, 96040 -ERR, 11, 2 -IMU, 96050, -0.004749874, 0.0003456436, 0.01313075, 0.002824038, 0.5241867, -9.799286 -IMU2, 96050, -0.004449332, -0.002830722, 0.01737293, 0.009243131, 0.6920582, -9.899565 -IMU, 96072, 0.002289375, -0.001058813, 0.01578502, -0.07158111, 0.3150902, -9.819265 -IMU2, 96072, 0.00346932, 0.00190183, 0.01440532, -0.07286, 0.4307256, -9.8231 -MAG, 96080, -421, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96080, -282, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 96090, 0, 0, 0, 0, -0.07, -0.05, 0.00, 0.00, 0, 0 -ATT, 96090, 0.00, -0.72, 0.00, 0.03, 189.56, 189.56 -RCIN, 96090, 1503, 1504, 1028, 1510, 992, 992, 993, 992 -RCOU, 96090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96090, 0.007769374, 0.0009308942, -0.009168896, 0.0798659, 0.2679565, -9.804682 -IMU2, 96090, 4.541129E-05, 0.006001366, -0.01480796, -0.006455779, 0.3996272, -9.673789 -IMU, 96110, 0.004985156, -0.0009177215, -0.03779056, 0.04090804, 0.3486167, -9.743791 -IMU2, 96110, 0.00167701, -0.004181587, -0.03855282, -0.05323422, 0.5076005, -9.704834 -IMU, 96130, -0.005907046, 0.003225658, -0.01630748, 0.1314111, 0.7609013, -9.784241 -IMU2, 96130, 0.001601823, -0.001916378, -0.01041552, 0.1980277, 0.8447663, -9.880936 -IMU, 96150, -0.003933067, -0.004371688, 0.04936252, 0.0616512, 0.7023131, -9.787696 -IMU2, 96150, -0.002243515, -0.01160467, 0.06378991, 0.05199289, 0.8151442, -9.879122 -IMU, 96171, -0.005486319, -0.002939925, 0.03323961, 0.02296093, 0.06476419, -9.768613 -IMU2, 96171, -0.01082261, -0.001405461, 0.02306527, -0.01437461, 0.2381511, -9.749377 -MAG, 96180, -422, 68, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96180, -281, -24, 236, 0, 0, 0, 0, 0, 0 -CTUN, 96190, 0, 0, 0, 0, -0.07, -0.18, 0.00, 0.00, 0, 0 -ATT, 96190, 0.00, -1.14, 0.00, -0.07, 189.56, 189.56 -RCIN, 96190, 1504, 1504, 1027, 1512, 992, 993, 992, 992 -RCOU, 96191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96191, -0.01289027, 0.0009174868, -0.03333784, 0.1448201, 0.335862, -9.83723 -IMU2, 96191, -0.020836, -0.00825828, -0.02822849, 0.0853008, 0.5176723, -9.858112 -IMU, 96210, 0.007586712, -0.004972283, -0.0214536, -0.07948971, 0.2940454, -9.785866 -IMU2, 96210, 0.0001347847, -0.01232551, -0.01955692, -0.0005649328, 0.3652067, -9.555433 -IMU, 96231, 0.0061219, -0.006054558, -0.02386739, 0.1147051, 0.4197633, -9.767506 -IMU2, 96231, 0.003793795, -0.004731293, -0.02264143, 0.06776845, 0.5277125, -9.896957 -GPS, 3, 56676400, 1777, 9, 2.54, 14.1105813, 100.6191541, -0.07, 2.17, 1.46, 281.11, -0.66, 96240 -IMU, 96250, 0.006261809, -0.003656689, -0.01636885, 0.1411799, 0.4571569, -9.818777 -IMU2, 96250, 0.009787668, 8.29529E-06, -0.01610763, 0.1387742, 0.5273286, -9.693589 -IMU, 96271, 0.003390335, -0.007922072, 0.03235325, 0.1007699, 0.7760391, -9.726461 -IMU2, 96271, 0.008752227, -0.009106061, 0.04324618, 0.1649549, 0.8947295, -9.715615 -MAG, 96280, -423, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96280, -280, -22, 232, 0, 0, 0, 0, 0, 0 -CTUN, 96290, 0, 0, 0, 0, -0.07, 0.01, 0.00, 0.00, 0, 0 -ATT, 96291, 0.00, -1.39, 0.00, -0.17, 189.57, 189.57 -RCIN, 96291, 1504, 1504, 1026, 1510, 993, 992, 992, 992 -RCOU, 96291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96291, 0.00184443, -0.00319149, 0.05981512, -0.02441043, 0.3726792, -9.862672 -IMU2, 96291, -0.003412087, 0.0002293773, 0.06990407, -0.01329339, 0.5231104, -9.854074 -IMU, 96310, -0.009164764, 0.003327772, 0.01653023, -0.1067433, 0.1251355, -9.812826 -IMU2, 96310, -0.01669094, -0.001387345, 0.005929334, -0.1572839, 0.3345186, -9.855619 -IMU, 96331, -0.007992258, 0.005826924, -0.04646493, -0.10435, 0.3003148, -9.850533 -IMU2, 96331, -0.006297782, 0.01708363, -0.04402058, -0.1613911, 0.4906119, -9.742288 -IMU, 96350, 0.005633032, 0.00809212, -0.05222034, 0.05510949, 0.5099123, -9.872605 -IMU2, 96350, -0.001783293, 0.001858925, -0.04580709, 0.06330812, 0.6171741, -9.973408 -IMU, 96370, 0.007728094, 0.003459003, -0.001291914, 0.1262896, 0.5893066, -9.722572 -IMU2, 96370, 0.01139433, -0.006147399, 0.003298348, 0.1331872, 0.6886414, -9.659645 -MAG, 96380, -426, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 96380, -281, -21, 231, 0, 0, 0, 0, 0, 0 -CTUN, 96390, 0, 0, 0, 0, -0.07, 0.06, 0.00, 0.00, 0, 0 -ATT, 96391, 0.00, -1.40, 0.00, -0.16, 189.53, 189.53 -RCIN, 96391, 1504, 1503, 1027, 1510, 992, 993, 992, 992 -RCOU, 96391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96391, 0.003124423, -0.001252662, 0.04680479, 0.1801493, 0.4459013, -9.648439 -IMU2, 96391, -0.001555834, -0.01265137, 0.05117305, 0.1558603, 0.576853, -9.729488 -IMU, 96410, -0.002451932, 0.001770478, 0.04096214, 0.1554697, 0.2874705, -9.845304 -IMU2, 96410, -0.004111458, -0.01276694, 0.03968393, 0.1207542, 0.4296156, -9.72986 -IMU, 96431, -0.005783794, -0.001000792, -0.007511574, 0.08667986, 0.2805515, -9.778788 -IMU2, 96431, -0.00710074, -0.006929952, -0.02034733, 0.04881191, 0.392285, -9.707546 -GPS, 3, 56676600, 1777, 10, 2.42, 14.1105827, 100.6191504, -0.06, 2.21, 1.63, 285.46, -0.59, 96440 -IMU, 96450, -0.00469132, -0.001085028, -0.04455892, 0.04469742, 0.3999687, -9.770671 -IMU2, 96450, -0.002124147, 0.0003309026, -0.03989979, 0.02828145, 0.5773031, -9.654748 -IMU, 96471, 4.305877E-05, 0.001276877, -0.02883464, -0.02104209, 0.4989496, -9.818288 -IMU2, 96471, -0.01156176, -0.004186703, -0.0187913, 0.05143702, 0.6197199, -9.802992 -MAG, 96480, -424, 71, 59, -86, 10, 139, 0, 0, 0 -MAG2, 96480, -283, -18, 230, 0, 0, 0, 0, 0, 0 -CTUN, 96490, 0, 0, 0, 0, -0.06, -0.04, 0.00, 0.00, 0, 0 -ATT, 96490, 0.00, -1.38, 0.00, -0.14, 189.51, 189.51 -RCIN, 96490, 1503, 1504, 1027, 1510, 992, 992, 993, 992 -RCOU, 96490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96490, 0.007110998, -0.001394346, 0.01447614, -0.01856062, 0.5148976, -9.847913 -IMU2, 96490, 0.002182217, -0.003439816, 0.02349494, 0.04366529, 0.5981519, -9.932091 -IMU, 96510, 0.004182154, 0.001298204, 0.03766149, 0.01300329, 0.3850732, -9.804632 -IMU2, 96510, 0.00342395, 0.00279507, 0.03842603, -0.03860104, 0.4967276, -9.787738 -IMU, 96530, -0.004580261, 0.004862219, 0.01624249, 0.01177673, 0.3273551, -9.778834 -IMU2, 96530, -0.0007247049, 0.006628461, 0.01071892, 0.01032925, 0.4922744, -9.903612 -IMU, 96551, -0.001931647, 0.001766726, -0.02053646, 0.08351476, 0.4228689, -9.83811 -IMU2, 96551, 0.005289588, 0.003567355, -0.02488003, 0.07885301, 0.5689861, -9.785088 -IMU, 96570, -0.001845622, 0.0009451881, -0.02944209, 0.09105749, 0.5013096, -9.750097 -IMU2, 96570, -0.003928712, 0.001887301, -0.02788237, 0.1175249, 0.6173378, -9.609287 -MAG, 96580, -424, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96580, -283, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 96590, 0, 0, 0, 0, -0.06, -0.02, 0.00, 0.00, 0, 0 -ATT, 96591, 0.00, -1.33, 0.00, -0.05, 189.52, 189.52 -RCIN, 96591, 1503, 1504, 1027, 1510, 992, 993, 992, 992 -RCOU, 96591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96591, 0.003489064, -0.002257146, -0.005040305, 0.03069181, 0.4968213, -9.741073 -IMU2, 96591, -0.002782485, -0.002130993, 0.0008914412, 0.0460701, 0.6382558, -9.79085 -IMU, 96610, 0.007351881, -0.005673118, 0.01970799, 0.01988347, 0.3840539, -9.822873 -IMU2, 96610, 0.008527316, -0.004034685, 0.02134662, 0.0173986, 0.4790342, -10.07603 -IMU, 96630, -0.005581187, 0.001584783, 0.01943239, -0.01936373, 0.2502993, -9.846452 -IMU2, 96630, -0.009639965, 3.179908E-05, 0.01830522, -0.006766796, 0.3807832, -9.856627 -GPS, 3, 56676800, 1777, 10, 2.42, 14.1105834, 100.6191477, -0.06, 2.26, 1.56, 286.82, -0.53, 96640 -ERR, 11, 0 -IMU, 96650, -0.00603793, 0.00242161, -0.004842357, 0.01011831, 0.3771327, -9.779447 -IMU2, 96650, -0.002360184, -0.002923981, -0.005364096, 0.02027547, 0.5534456, -9.682236 -IMU, 96671, 0.0007730182, -5.09806E-05, -0.02025016, 0.08237778, 0.502821, -9.806449 -IMU2, 96671, -0.005199725, 0.003919491, -0.02124717, 0.05896807, 0.634107, -9.7395 -MAG, 96680, -422, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96680, -283, -18, 232, 0, 0, 0, 0, 0, 0 -CTUN, 96690, 0, 0, 0, 0, -0.06, -0.04, 0.00, 0.00, 0, 0 -ATT, 96690, 0.00, -1.30, 0.00, -0.01, 189.54, 189.54 -RCIN, 96690, 1503, 1504, 1026, 1511, 992, 992, 993, 991 -RCOU, 96691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96691, -0.00283567, 0.0026704, -0.006482869, 0.06044631, 0.5414412, -9.819135 -IMU2, 96691, -0.0001043342, 0.006862428, -0.001563504, 0.08333135, 0.6781532, -9.861589 -IMU, 96711, 0.01281849, -0.002039239, 0.01127663, 0.02032249, 0.4730232, -9.799807 -IMU2, 96711, 0.01142905, -0.002204303, 0.01590621, -0.04196882, 0.6395452, -9.816566 -IMU, 96730, 0.004726948, -0.002400883, 0.01041272, 0.01585931, 0.2335253, -9.764712 -IMU2, 96730, 0.003847498, 0.005314058, 0.01530278, 0.03279018, 0.3529367, -9.809809 -IMU, 96750, -0.01049428, 0.00689552, -0.002321461, 0.01237142, 0.3043614, -9.841002 -IMU2, 96750, -0.01364218, 0.001881326, -0.006212948, 0.01688194, 0.4530391, -9.871028 -IMU, 96771, -0.000380123, -0.002584144, -0.01232199, 0.07212281, 0.5097458, -9.743884 -IMU2, 96771, 0.01055465, -0.006842465, -0.01154366, 0.04865885, 0.6619164, -9.745512 -MAG, 96780, -423, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 96780, -283, -18, 234, 0, 0, 0, 0, 0, 0 -CTUN, 96790, 0, 0, 0, 0, -0.06, -0.01, 0.00, 0.00, 0, 0 -ATT, 96791, 0.00, -1.31, 0.00, -0.02, 189.55, 189.55 -RCIN, 96791, 1503, 1504, 1027, 1510, 992, 993, 992, 992 -RCOU, 96791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96791, -0.006575434, -0.003057133, -0.001626128, 0.08151996, 0.5136057, -9.824515 -IMU2, 96791, -0.009259552, -0.00375748, -0.003873657, -0.01021016, 0.6287439, -9.835629 -IMU, 96811, 0.00851687, 0.002490103, 0.01162791, 0.01664646, 0.5284026, -9.800533 -IMU2, 96811, 0.014163, -0.005624748, 0.01098242, 0.002051115, 0.6369412, -9.881124 -IMU, 96831, 0.01361982, -0.008717723, 0.004543159, -0.01405549, 0.2441867, -9.745026 -IMU2, 96831, 0.003805976, -0.005299035, 0.004648587, -0.1117901, 0.3737836, -9.664142 -GPS, 3, 56677000, 1777, 10, 2.42, 14.1105848, 100.6191447, -0.06, 2.15, 1.51, 288.96, -0.43, 96840 -IMU, 96850, -0.00913352, 0.008686036, -0.009359822, 0.02095838, 0.261115, -9.85012 -IMU2, 96850, -0.003713844, 0.01206475, -0.008668013, 0.03029907, 0.5042971, -9.791725 -IMU, 96870, -0.003417337, 0.003946174, -0.01091209, 0.0942038, 0.4717318, -9.724969 -IMU2, 96870, -0.001928607, -0.001475671, -0.007469022, 0.07926536, 0.6013764, -9.681035 -MAG, 96880, -423, 70, 59, -86, 10, 139, 0, 0, 0 -MAG2, 96880, -283, -17, 232, 0, 0, 0, 0, 0, 0 -CTUN, 96890, 0, 0, 0, 0, -0.06, -0.12, 0.00, 0.00, 0, 0 -DU32, 7, 262745 -CURR, 96890, 0, 0, 1531, 120, 5318, 12.41699 -ATT, 96891, 0.00, -1.31, 0.00, -0.01, 189.55, 189.55 -RCIN, 96891, 1503, 1503, 1027, 1510, 992, 993, 992, 992 -RCOU, 96891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96891, -0.008873323, -0.005979486, 0.006683235, 0.08344984, 0.5214467, -9.813636 -IMU2, 96891, -0.01383435, -0.004266547, 0.007532064, 0.1247317, 0.6811022, -9.791861 -IMU, 96910, 0.001903782, 0.00794046, 0.01632601, 0.002865285, 0.4668978, -9.830123 -IMU2, 96910, 0.001961466, 0.01384632, 0.0150997, 0.04291117, 0.6259702, -9.835535 -IMU, 96930, 0.01085529, -0.007577851, 0.001834584, 0.01159953, 0.2558644, -9.698481 -IMU2, 96930, 0.01087382, -0.01287242, 0.0009491602, -0.04448676, 0.3618015, -9.656192 -IMU, 96950, 0.005496226, 0.004956611, -0.01756132, 0.05717558, 0.2953855, -9.909133 -IMU2, 96950, 0.01257629, 0.01335729, -0.02116182, 0.004493713, 0.4812754, -9.97098 -IMU, 96970, -0.002357488, 0.004031543, -0.01329077, 0.109788, 0.4416046, -9.733743 -IMU2, 96970, -0.004913947, -0.002073715, -0.01493309, 0.08643305, 0.5986942, -9.778146 -MAG, 96980, -423, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 96980, -284, -18, 232, 0, 0, 0, 0, 0, 0 -CTUN, 96990, 0, 0, 0, 0, -0.06, 0.00, 0.00, 0.00, 0, 0 -ATT, 96990, 0.00, -1.32, 0.00, 0.00, 189.55, 189.55 -RCIN, 96990, 1502, 1504, 1027, 1510, 992, 993, 992, 992 -RCOU, 96991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 96991, -0.005797585, -0.01025219, 0.011181, 0.09797283, 0.6031722, -9.76777 -IMU2, 96991, -0.001103269, -0.01408836, 0.01849141, 0.1292152, 0.7495397, -9.853018 -IMU, 97010, -0.002762543, 0.003402948, 0.02171988, -0.003901362, 0.447396, -9.80054 -IMU2, 97010, 0.005727947, 0.004937749, 0.01570049, -0.009031057, 0.5919315, -9.747257 -IMU, 97031, -0.0002244562, -0.00148657, -0.0002959378, -0.05523814, 0.3133928, -9.816769 -IMU2, 97031, 0.001866937, -0.006835631, -0.006386385, -0.09397733, 0.4556978, -9.856174 -GPS, 3, 56677200, 1777, 10, 2.42, 14.110586, 100.6191426, -0.06, 1.88, 1.36, 289.61, -0.25, 97040 -IMU, 97050, -0.001316743, 0.002542656, -0.02076989, -0.005216494, 0.2735472, -9.873631 -IMU2, 97050, -0.007731609, 0.007134184, -0.02052278, 0.0165056, 0.4068105, -9.848598 -IMU, 97070, -0.0005618427, 0.001651831, -0.009784732, 0.09875646, 0.4929613, -9.760497 -IMU2, 97070, -0.00213279, 0.006941773, -0.005915055, 0.04419398, 0.575222, -9.88875 -MAG, 97081, -423, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97081, -283, -18, 232, 0, 0, 0, 0, 0, 0 -CTUN, 97090, 0, 0, 0, 0, -0.06, -0.19, 0.00, 0.00, 0, 0 -ATT, 97090, 0.00, -1.34, 0.00, 0.00, 189.56, 189.56 -RCIN, 97090, 1504, 1503, 1027, 1510, 993, 992, 992, 992 -RCOU, 97090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97090, 0.000621194, -0.003442965, 0.01464875, 0.05560463, 0.4875905, -9.800257 -IMU2, 97090, -0.001954636, -0.005002085, 0.01602529, 0.05635154, 0.6530517, -9.800668 -IMU, 97110, 0.005375147, -0.001447719, 0.01522672, 0.05506899, 0.3949506, -9.796881 -IMU2, 97110, 0.007292539, 0.007138453, 0.008088192, 0.02346647, 0.5226569, -9.835768 -IMU, 97130, -0.003421882, 0.006133106, -0.006819135, 0.03473414, 0.2560315, -9.795057 -IMU2, 97130, -0.01121635, 0.006290272, -0.006281287, 0.0530951, 0.432249, -9.725469 -IMU, 97150, -0.005152488, 2.7854E-05, -0.01590687, 0.09208527, 0.424143, -9.8036 -IMU2, 97150, -0.007455876, 0.009383619, -0.0185683, 0.1235149, 0.6226897, -9.745408 -IMU, 97170, 0.002436915, -0.002757296, -0.001423704, 0.05323859, 0.4550555, -9.808599 -IMU2, 97170, -0.00740795, 0.00149233, 0.003579131, -0.003332615, 0.6043037, -9.6862 -MAG, 97180, -424, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97180, -284, -20, 232, 0, 0, 0, 0, 0, 0 -CTUN, 97191, 0, 0, 0, 0, -0.06, -0.17, 0.00, 0.00, 0, 0 -ATT, 97191, 0.00, -1.37, 0.00, -0.01, 189.57, 189.57 -RCIN, 97191, 1504, 1503, 1027, 1510, 992, 993, 992, 992 -RCOU, 97191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97191, 0.004844621, -0.00209732, 0.01070679, -0.0001567602, 0.372945, -9.750602 -IMU2, 97191, 0.01416297, -0.001784779, 0.01289474, 0.007372856, 0.4840229, -9.700284 -IMU, 97210, 0.009540262, -0.003041979, 0.0009253937, 0.02809577, 0.2781599, -9.876833 -IMU2, 97210, 0.006674841, -0.004652936, -0.005046376, 0.02273655, 0.4008609, -9.778224 -IMU, 97231, -0.002742128, 0.003083974, -0.007732253, 0.1061789, 0.3178559, -9.699114 -IMU2, 97231, -0.004405793, 0.004041474, -0.007479691, 0.09997356, 0.4649265, -9.69242 -GPS, 3, 56677400, 1777, 10, 2.42, 14.1105872, 100.6191404, -0.07, 1.69, 1.27, 290.28, -0.12, 97240 -IMU, 97251, -0.006188916, -0.003119715, 8.542067E-05, 0.1165342, 0.4936258, -9.778388 -IMU2, 97251, 0.002224725, -0.006394583, -0.001199187, 0.1013162, 0.6235121, -9.676967 -IMU, 97270, 0.002062622, -0.001618996, 0.009207827, -0.001459494, 0.4371014, -9.819072 -IMU2, 97270, 0.002825228, -0.003099986, 0.0131735, -0.07969761, 0.5806754, -9.782886 -MAG, 97280, -421, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97280, -283, -19, 231, 0, 0, 0, 0, 0, 0 -CTUN, 97290, 0, 0, 0, 0, -0.07, -0.13, 0.00, 0.00, 0, 0 -ATT, 97290, 0.00, -1.40, 0.00, -0.03, 189.58, 189.58 -RCIN, 97290, 1503, 1504, 1027, 1511, 992, 992, 992, 992 -RCOU, 97290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97290, 0.001310268, 0.003470749, 0.0002358386, -0.006742835, 0.3258371, -9.773828 -IMU2, 97290, -0.003163798, -0.001680681, 0.0004444635, 0.05048823, 0.4200022, -9.722442 -IMU, 97310, 0.001239339, 0.002315793, -0.007981434, -0.003645644, 0.3446205, -9.853656 -IMU2, 97310, 0.002827797, 0.005124945, -0.004546103, 0.01924253, 0.4704539, -9.892382 -IMU, 97331, 0.003264913, -0.001010448, 0.002182462, 0.07923, 0.4527652, -9.758833 -IMU2, 97331, 0.007653739, 0.004429961, 0.007361482, 0.09655547, 0.5620528, -9.692983 -IMU, 97351, 0.003899293, -0.001514897, 0.01170143, 0.000472635, 0.4712112, -9.850106 -IMU2, 97351, 0.006435141, -0.001224757, 0.01446478, -0.06303561, 0.6111718, -9.880411 -IMU, 97370, 0.00715098, -0.0008460172, 0.0002020206, -0.005860507, 0.3327039, -9.801154 -IMU2, 97370, -0.003510525, 0.0002365345, -0.002387254, 0.01302636, 0.5026151, -9.716815 -MAG, 97380, -424, 71, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97380, -282, -19, 232, 0, 0, 0, 0, 0, 0 -CTUN, 97390, 0, 0, 0, 0, -0.07, -0.14, 0.00, 0.00, 0, 0 -ATT, 97390, 0.00, -1.42, 0.00, -0.03, 189.57, 189.57 -RCIN, 97390, 1503, 1504, 1027, 1510, 992, 993, 992, 992 -RCOU, 97391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97391, -0.002294945, 0.003057972, -0.01433028, 0.0317574, 0.3739161, -9.859117 -IMU2, 97391, -0.00418726, 0.00753279, -0.01576317, -0.02319002, 0.5338123, -9.892717 -IMU, 97411, -0.003039667, -0.0005792864, -0.003993779, 0.09414549, 0.517381, -9.707568 -IMU2, 97411, 0.0009250008, 0.006912384, -0.0006239698, 0.1014752, 0.6648191, -9.780729 -IMU, 97430, 0.0006349459, -0.004926875, 0.01298706, -0.0005097687, 0.5046299, -9.821255 -IMU2, 97430, 0.002703723, -0.006587907, 0.007492538, 0.003484249, 0.6625379, -9.847482 -GPS, 3, 56677600, 1777, 10, 2.42, 14.110589, 100.6191367, -0.08, 1.64, 1.30, 292.70, -0.09999999, 97440 -IMU, 97450, 0.005011598, 0.002750151, 0.009345217, 0.03325059, 0.3238256, -9.746146 -IMU2, 97450, 0.003336117, -0.001370902, -0.00179154, -0.05502188, 0.4576173, -9.835378 -IMU, 97471, -0.006962212, 0.002609845, -0.009344577, 0.05755249, 0.3489938, -9.820162 -IMU2, 97471, 0.0005834084, 0.005543303, -0.01423227, 0.006945848, 0.4552295, -9.908424 -MAG, 97480, -423, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 97480, -283, -17, 230, 0, 0, 0, 0, 0, 0 -CTUN, 97490, 0, 0, 0, 0, -0.08, -0.10, 0.00, 0.00, 0, 0 -ATT, 97490, 0.00, -1.44, 0.00, -0.01, 189.57, 189.57 -RCIN, 97490, 1503, 1504, 1026, 1511, 992, 992, 993, 991 -RCOU, 97490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97490, -0.0003847461, 0.001866657, -0.006814853, 0.1149021, 0.4504839, -9.78954 -IMU2, 97490, -0.00833806, -0.008050945, -0.005501085, 0.1365086, 0.5351946, -9.838549 -IMU, 97510, -0.0006100107, -0.003071867, 0.008294147, 0.01884735, 0.518268, -9.805443 -IMU2, 97510, -0.001794038, -0.002207079, 0.00908378, 0.02654123, 0.615652, -9.868294 -IMU, 97530, 0.005034808, 0.0005367547, 0.006660076, 0.01240261, 0.3308756, -9.802133 -IMU2, 97530, -0.0007880107, -0.005950221, 0.007490913, -0.0004794598, 0.4790008, -9.764924 -IMU, 97550, 4.993379E-05, 0.001631759, -0.005515889, 0.001551464, 0.3100188, -9.822131 -IMU2, 97550, 0.0002679154, 0.009166986, -0.008247595, 0.007954597, 0.4588802, -9.848437 -IMU, 97570, -0.001097329, 0.001543723, -0.003427681, 0.1195249, 0.4349164, -9.778702 -IMU2, 97570, 5.022436E-05, 0.0007460024, -0.003577277, 0.1821182, 0.5214647, -9.722858 -MAG, 97580, -424, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 97580, -283, -18, 233, 0, 0, 0, 0, 0, 0 -CTUN, 97590, 0, 0, 0, 0, -0.08, -0.07, 0.00, 0.00, 0, 0 -ATT, 97590, 0.00, -1.42, 0.00, 0.00, 189.59, 189.59 -RCIN, 97590, 1503, 1504, 1027, 1510, 992, 993, 992, 992 -RCOU, 97591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97591, 0.002549829, -0.005013272, 0.006112355, -0.0317505, 0.4290596, -9.81116 -IMU2, 97591, -0.005090278, 0.001935044, 0.001076899, -0.04445004, 0.5732718, -9.971998 -IMU, 97610, 0.005793825, 0.001855414, 0.001932908, 0.04469506, 0.2760678, -9.788642 -IMU2, 97610, 0.001412252, 0.005781041, -0.006028542, 0.03358793, 0.4306233, -9.67426 -IMU, 97631, 0.0002875775, 0.0008822605, -0.010772, -0.00319317, 0.3328316, -9.811236 -IMU2, 97631, -0.002299828, -0.0005227029, -0.007375253, 0.0004868507, 0.5007907, -9.736079 -GPS, 3, 56677800, 1777, 10, 2.42, 14.1105902, 100.6191342, -0.08, 1.64, 1.21, 295.10, -0.09999999, 97640 -IMU, 97650, -0.001097286, 0.001042038, -0.001341458, 0.1576501, 0.4570506, -9.758335 -IMU2, 97650, -0.003352387, -0.003354807, 0.002213051, 0.1560448, 0.5745126, -9.608218 -IMU, 97670, 0.00893461, -0.004390884, 0.01106527, -0.0292992, 0.4447888, -9.817816 -IMU2, 97670, 0.005899452, -0.002264823, 0.01050602, -0.09437013, 0.5346063, -9.735309 -MAG, 97680, -423, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97680, -283, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 97690, 0, 0, 0, 0, -0.08, -0.02, 0.00, 0.00, 0, 0 -ATT, 97690, 0.00, -1.43, 0.00, 0.02, 189.60, 189.60 -RCIN, 97690, 1503, 1504, 1026, 1511, 992, 992, 993, 991 -RCOU, 97691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97691, -0.001151724, 0.002814606, 0.001308166, 0.02615201, 0.2170453, -9.753443 -IMU2, 97691, -0.01074466, 0.001336033, -0.003856678, -0.0706284, 0.3597704, -9.68965 -IMU, 97710, -0.0009797476, 0.003878176, -0.01176087, 0.03324014, 0.346395, -9.82534 -IMU2, 97710, -0.01067719, 0.004306322, -0.01477076, 0.05228841, 0.5055866, -9.803888 -IMU, 97730, -0.003432868, 0.001033325, -0.001830435, 0.1203382, 0.4504208, -9.691119 -IMU2, 97730, -0.001859862, -0.004950619, -0.003085414, 0.1365914, 0.6247461, -9.669067 -IMU, 97750, 0.004894497, -0.002872646, 0.009271335, -0.05194965, 0.4584474, -9.91913 -IMU2, 97750, 0.006089196, 0.004356882, 0.01164783, -0.01224244, 0.6005051, -9.76209 -IMU, 97770, 0.0006659348, 0.003399979, 0.001380683, 0.04735705, 0.1631286, -9.733449 -IMU2, 97770, -0.003891846, -0.0008728933, -0.001348861, 0.02537739, 0.3488026, -9.679719 -MAG, 97780, -425, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97780, -283, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 97790, 0, 0, 0, 0, -0.08, -0.16, 0.00, 0.00, 0, 0 -ATT, 97790, 0.00, -1.45, 0.00, 0.03, 189.59, 189.59 -RCIN, 97790, 1503, 1504, 1026, 1510, 993, 992, 992, 992 -RCOU, 97791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97791, -0.001558537, 0.002029266, -0.01009224, 0.04538866, 0.3972062, -9.835378 -IMU2, 97791, -0.004288021, 0.01157895, -0.009274508, 0.09959435, 0.4939836, -9.8006 -IMU, 97810, -0.0026638, -0.002828479, -0.002132925, 0.1740034, 0.494275, -9.737828 -IMU2, 97810, 0.004643403, -0.006856284, 0.004542, 0.1468287, 0.6510121, -9.75069 -IMU, 97831, 0.004134746, -0.0003689751, 0.006204894, 0.02104741, 0.438797, -9.753789 -IMU2, 97831, 0.004082344, 0.001221947, 0.003773074, 0.03503978, 0.5444001, -9.638026 -GPS, 3, 56678000, 1777, 10, 2.42, 14.1105911, 100.619133, -0.08, 1.47, 1.12, 296.35, 0.03, 97840 -IMU, 97851, -0.0001340937, 0.0009457618, -0.002018677, 0.07796916, 0.3087648, -9.774381 -IMU2, 97851, 0.004240923, 0.000763108, 0.003108321, 0.0271498, 0.4251028, -9.731868 -IMU, 97870, -0.002352988, 0.005717576, -0.005571901, 0.06958007, 0.4166403, -9.828822 -IMU2, 97870, -0.008354152, 0.002414542, -0.002817529, 0.09432685, 0.5291157, -9.718664 -MAG, 97880, -423, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97880, -284, -17, 234, 0, 0, 0, 0, 0, 0 -CTUN, 97890, 0, 0, 0, 0, -0.08, -0.12, 0.00, 0.00, 0, 0 -DU32, 7, 262745 -CURR, 97890, 0, 0, 1533, 125, 5314, 12.77009 -ATT, 97891, 0.00, -1.47, 0.00, 0.03, 189.59, 189.59 -RCIN, 97891, 1503, 1504, 1028, 1510, 992, 992, 993, 992 -RCOU, 97891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97891, 9.826943E-05, -0.003694281, 0.005492737, 0.04900135, 0.5006176, -9.713171 -IMU2, 97891, 0.005135294, -0.003078458, 0.006473778, 0.05448079, 0.6498724, -9.870632 -IMU, 97910, 0.0043619, 0.0008941963, 0.005724513, -0.05553606, 0.3400166, -9.897219 -IMU2, 97910, 0.005698457, 0.005716341, -0.0003059199, -0.02150023, 0.472647, -9.869509 -IMU, 97930, 0.0004250482, 0.004484188, -0.006378135, 0.05563002, 0.3392111, -9.763164 -IMU2, 97930, 0.004094038, 0.0003996696, -0.006434865, -0.01959252, 0.5062276, -9.841893 -IMU, 97950, -0.003294567, -0.0001568273, -0.005211705, 0.08409099, 0.446012, -9.807865 -IMU2, 97950, -0.004335817, 0.005336693, -0.004062325, 0.1070225, 0.5612853, -9.785153 -IMU, 97970, 0.005020164, -0.003789365, 0.006167757, 0.0193703, 0.5570077, -9.756973 -IMU2, 97970, 0.005293019, -0.005423331, 0.001828918, 0.04552805, 0.6917776, -9.833418 -MAG, 97980, -424, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 97980, -283, -19, 232, 0, 0, 0, 0, 0, 0 -CTUN, 97990, 0, 0, 0, 0, -0.09, -0.13, 0.00, 0.00, 0, 0 -ATT, 97990, 0.00, -1.49, 0.00, 0.02, 189.60, 189.60 -RCIN, 97990, 1503, 1504, 1026, 1281, 993, 992, 992, 992 -RCOU, 97991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 97991, -0.005169937, -4.1686E-05, 0.004627439, -0.007010043, 0.2469673, -9.832038 -IMU2, 97991, 0.001501188, 0.004630838, 0.002296589, -0.05134881, 0.3726332, -9.686134 -IMU, 98010, -0.0002658907, 0.001670387, -0.005762041, 0.03429979, 0.4027213, -9.773249 -IMU2, 98010, -0.001969842, 0.005263042, -0.01244388, -0.04133427, 0.5049963, -9.752761 -IMU, 98031, -0.008464532, -0.001926221, -0.001075867, 0.1254611, 0.3859717, -9.690482 -IMU2, 98031, -0.006351205, -0.006579322, -0.0003892379, 0.1234138, 0.5666953, -9.658089 -GPS, 3, 56678200, 1777, 10, 2.42, 14.1105918, 100.6191313, -0.09, 1.35, 1.09, 293.58, 0.11, 98040 -IMU, 98050, 0.008776873, -0.002713218, 0.004409526, 0.001072451, 0.4896904, -9.804979 -IMU2, 98050, 0.007019531, -0.001569867, -0.0009901514, 0.02672386, 0.6448292, -9.754304 -IMU, 98070, -0.005849229, -0.0001298897, 0.0006194948, 0.03807498, 0.1748219, -9.789237 -IMU2, 98070, -0.01602691, -0.004835353, 0.0009577104, 0.01072443, 0.3336051, -9.86799 -MAG, 98080, -424, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 98080, -283, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98090, 0, 0, 0, 0, -0.09, -0.10, 0.00, 0.00, 0, 0 -ATT, 98090, 0.00, -1.49, 0.00, 0.00, 189.60, 189.60 -RCIN, 98090, 1504, 1503, 1027, 1044, 992, 993, 992, 992 -RCOU, 98091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98091, 0.001565598, 0.005342871, -0.007151244, 0.1169423, 0.5009068, -9.767206 -IMU2, 98091, -0.007975621, 0.002619634, 0.0005456356, 0.2225059, 0.6692783, -9.69457 -IMU, 98110, -0.007611969, -0.003176518, 0.005847425, 0.07707417, 0.4257923, -9.839363 -IMU2, 98110, -0.005156804, 0.001654006, 0.001567233, 0.03355777, 0.5202017, -9.827044 -IMU, 98130, 0.009248482, 0.0009321123, 0.004086928, 0.08276188, 0.497504, -9.777888 -IMU2, 98130, 0.00192374, -0.00643188, 0.002601457, 0.09300566, 0.6419121, -9.835669 -IMU, 98151, -0.005255213, 0.003228169, -0.003603097, 0.02949044, 0.1573078, -9.772739 -IMU2, 98151, -0.0105793, 0.006987888, -0.00217722, 0.01239812, 0.335458, -9.791435 -IMU, 98170, -0.001694603, 0.001212735, -0.004200726, 0.1304229, 0.5451467, -9.848415 -IMU2, 98170, -0.01252353, -0.001796251, 0.004350878, 0.1367394, 0.7295421, -9.866675 -MAG, 98180, -423, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 98180, -284, -20, 234, 0, 0, 0, 0, 0, 0 -CTUN, 98190, 0, 0, 0, 0, -0.09, -0.07, 0.00, 0.00, 0, 0 -ATT, 98190, 0.00, -1.48, 0.00, -0.04, 189.61, 189.61 -RCIN, 98190, 1504, 1503, 1026, 1003, 992, 993, 992, 992 -RCOU, 98191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98191, -0.000129018, -0.004799105, 0.006598519, 0.008324862, 0.3962408, -9.716734 -IMU2, 98191, 0.0001864582, -0.00576856, 0.01030604, -0.05223238, 0.521175, -9.729334 -IMU, 98210, 0.0006794464, -0.001170829, 0.001895011, 0.03518954, 0.443383, -9.837824 -IMU2, 98210, 0.001710491, 0.000952499, 0.001897829, 0.01525891, 0.5494621, -9.895976 -IMU, 98231, -0.003421972, 0.00284351, -0.004675084, 0.07583797, 0.3502201, -9.799784 -IMU2, 98231, -0.004082175, -0.0005494356, -0.002909932, 0.05363679, 0.4924558, -9.846443 -GPS, 3, 56678400, 1777, 9, 3.00, 14.1105913, 100.6191318, -0.09, 1.41, 0.80, 292.68, 0.14, 98240 -IMU, 98250, -0.002702119, -0.002949052, 0.002108626, 0.05854396, 0.6114032, -9.781138 -IMU2, 98250, -0.001528535, -0.006018687, 0.006537124, 0.1496087, 0.6663715, -9.833223 -IMU, 98270, 0.003698302, 0.0001285449, 0.003982902, -0.01689459, 0.4150078, -9.839013 -IMU2, 98270, 0.0043662, -0.005267701, 0.007755219, -0.0420593, 0.5351284, -9.826518 -MAG, 98280, -422, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 98280, -284, -18, 232, 0, 0, 0, 0, 0, 0 -CTUN, 98290, 0, 0, 0, 0, -0.09, -0.14, 0.00, 0.00, 0, 0 -ATT, 98290, 0.00, -1.50, 0.00, -0.07, 189.61, 189.61 -RCIN, 98290, 1503, 1504, 1023, 1003, 993, 992, 992, 992 -RCOU, 98290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98290, 0.001498666, 0.002198484, -0.002567244, -0.04172061, 0.2792139, -9.821782 -IMU2, 98290, 0.00269793, 0.00356118, -0.005807584, -0.06304216, 0.4615057, -9.841345 -IMU, 98311, -0.001321146, 0.003613278, -0.004348463, 0.06087108, 0.386266, -9.790531 -IMU2, 98311, -0.008618753, -0.004704624, 0.0005165704, 0.03313303, 0.5375099, -9.760395 -IMU, 98330, 0.0005324688, -0.003480393, 0.006569872, 0.06157019, 0.4984163, -9.806369 -IMU2, 98330, 0.002642032, 0.00235508, 0.006660666, 0.001069784, 0.6005646, -9.669304 -IMU, 98351, 0.0009583849, 0.0007315315, 0.002034906, -0.01318029, 0.4549608, -9.780295 -IMU2, 98351, 0.000926625, -0.006057595, -0.0009988691, 0.007840276, 0.5879949, -9.919662 -IMU, 98371, 0.004462028, 0.002038509, -0.00534701, 0.02655404, 0.2934862, -9.855229 -IMU2, 98371, 0.009255052, 0.006964754, -0.007323939, 0.0322938, 0.4415052, -9.803576 -MAG, 98380, -424, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 98380, -283, -16, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98390, 0, 0, 0, 0, -0.09, -0.16, 0.00, 0.00, 0, 0 -ATT, 98391, 0.00, -1.59, 0.00, -0.08, 189.61, 189.61 -RCIN, 98391, 1503, 1504, 1024, 1006, 992, 992, 993, 991 -RCOU, 98391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98391, -0.002659248, -9.551644E-05, -0.000418385, 0.08946524, 0.5286142, -9.815563 -IMU2, 98391, -0.002487443, 0.003188985, 0.005063556, 0.07135403, 0.652898, -9.848013 -IMU, 98410, 0.01069168, -0.002801582, 0.006449934, -0.02010725, 0.3805334, -9.83953 -IMU2, 98410, -0.003670726, -0.003639284, 0.007559927, 0.01599205, 0.4484026, -9.766366 -IMU, 98430, 0.003727602, 0.0003967732, -0.0006588215, -0.07260045, 0.3092303, -9.911707 -IMU2, 98430, 0.009061996, 0.004149732, 0.001199823, -0.02618289, 0.4375365, -9.972965 -GPS, 3, 56678600, 1777, 9, 3.00, 14.110591, 100.6191327, -0.10, 1.32, 0.57, 292.68, 0.26, 98440 -IMU, 98450, 0.002848597, 0.004366424, -0.005718641, 0.05932051, 0.3652175, -9.754871 -IMU2, 98450, 0.004823815, 0.0003444646, -0.004801664, 0.1062446, 0.5183991, -9.767824 -IMU, 98471, 0.001735769, -0.002094358, 0.006442961, -0.009065077, 0.5138138, -9.94927 -IMU2, 98471, -0.004830856, 0.001154425, 0.01253589, -0.003134727, 0.5889211, -9.875297 -MAG, 98480, -421, 69, 59, -86, 10, 139, 0, 0, 0 -MAG2, 98480, -284, -17, 231, 0, 0, 0, 0, 0, 0 -CTUN, 98490, 0, 0, 0, 0, -0.09999999, -0.16, 0.00, 0.00, 0, 0 -ATT, 98490, 0.00, -1.65, 0.00, -0.10, 189.62, 189.62 -RCIN, 98490, 1503, 1504, 1025, 1006, 992, 993, 992, 992 -RCOU, 98490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98490, 0.005099775, 0.0005872473, 0.002321768, -0.02135764, 0.387024, -9.772491 -IMU2, 98490, -0.001528254, 0.0032959, -0.000680306, -0.07382464, 0.5497603, -9.898603 -IMU, 98510, -0.002068968, 0.007889211, -0.007955107, 0.0136925, 0.2457245, -9.77809 -IMU2, 98510, -0.007545594, -0.0001933742, -0.009778205, -0.0571779, 0.423431, -9.837021 -IMU, 98530, -0.003875406, 0.0003802776, -0.002088644, 0.1135934, 0.4887854, -9.8039 -IMU2, 98530, -0.007558947, 0.002343928, 0.005045754, 0.1592776, 0.5994635, -9.806319 -IMU, 98550, 0.007457329, -0.003447719, 0.008088847, -0.05115497, 0.3810063, -9.775395 -IMU2, 98550, 0.009486437, -0.003062183, 0.005662934, -0.05839872, 0.5050179, -9.665888 -IMU, 98570, 3.58317E-05, 0.001588415, -0.002373678, 0.03252706, 0.2850364, -9.820687 -IMU2, 98570, -0.004047142, 0.006558787, -0.005600941, 0.02335703, 0.3676244, -9.788292 -MAG, 98581, -423, 69, 62, -86, 10, 139, 0, 0, 0 -MAG2, 98581, -285, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98590, 0, 0, 0, 0, -0.09999999, 0.01, 0.00, 0.00, 0, 0 -ATT, 98590, 0.00, -1.72, 0.00, -0.10, 189.62, 189.62 -RCIN, 98590, 1503, 1504, 1024, 1003, 992, 993, 992, 992 -RCOU, 98591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98591, 0.002575768, 0.004448663, -0.009999055, 0.1109966, 0.3935014, -9.805577 -IMU2, 98591, -0.00393091, 0.008701056, -0.008900761, 0.05778933, 0.5623397, -9.801163 -IMU, 98610, -0.007215342, -0.005424995, 0.004161853, 0.07699253, 0.4826076, -9.703601 -IMU2, 98610, -0.001220733, -0.005097787, 0.009152496, 0.08190703, 0.5921642, -9.736135 -IMU, 98631, 0.003259933, 0.0003828481, 0.003745798, 0.05865859, 0.4274116, -9.786655 -IMU2, 98631, -0.01047845, -0.004165061, 0.005258253, 0.06729245, 0.5683655, -9.800692 -GPS, 3, 56678800, 1777, 8, 3.37, 14.1105902, 100.6191353, -0.10, 1.14, 0.23, 292.68, 0.38, 98640 -IMU, 98650, -0.006993888, 0.004220389, -0.007033245, 0.03440108, 0.2156069, -9.789529 -IMU2, 98650, -0.007589892, 0.003558857, 0.0007115137, 0.04389226, 0.3968465, -9.749367 -IMU, 98670, -0.000170324, -0.0003647432, -0.004691194, 0.1596621, 0.5953149, -9.708954 -IMU2, 98670, 0.00476547, -0.002851892, -0.002739787, 0.1489856, 0.7286621, -9.848536 -MAG, 98680, -422, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 98680, -283, -19, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98690, 0, 0, 0, 0, -0.09999999, -0.09, 0.00, 0.00, 0, 0 -ATT, 98690, 0.00, -1.80, 0.00, -0.12, 189.63, 189.63 -RCIN, 98690, 1503, 1504, 1024, 1003, 992, 992, 993, 992 -RCOU, 98690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98691, -0.001817832, -0.003095299, 0.008584191, 0.01609273, 0.4027892, -9.746135 -IMU2, 98691, 0.00152183, -0.004984742, 0.01058388, -0.01479959, 0.5345668, -9.797546 -IMU, 98710, 0.006103059, -0.002675425, -0.001362793, 0.0136856, 0.3936787, -9.874266 -IMU2, 98710, 0.001792315, -0.003703851, -0.001783147, -0.02109921, 0.5450466, -9.838737 -IMU, 98730, -0.003539084, 0.005766902, -0.00828944, 0.12118, 0.3111885, -9.756535 -IMU2, 98730, -0.004109202, 0.005145432, -0.006943872, 0.1363628, 0.454107, -9.837322 -IMU, 98750, 0.0009071101, -0.002404489, 0.004507435, 0.06548233, 0.5786526, -9.764311 -IMU2, 98750, -0.00105322, -0.00449586, 0.008678193, 0.1369514, 0.6727189, -9.69173 -IMU, 98770, 0.002088234, -0.003598034, 0.006678463, -0.02201818, 0.3807703, -9.781886 -IMU2, 98770, 0.003281809, 0.001547304, 0.006555176, 0.03887296, 0.5121708, -9.883424 -MAG, 98780, -425, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 98780, -282, -20, 235, 0, 0, 0, 0, 0, 0 -CTUN, 98790, 0, 0, 0, 0, -0.09999999, -0.05, 0.00, 0.00, 0, 0 -ATT, 98790, 0.00, -1.88, 0.00, -0.14, 189.63, 189.63 -RCIN, 98790, 1503, 1504, 1024, 1003, 993, 992, 992, 992 -RCOU, 98791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98791, 0.003212649, 0.001554459, -0.005202568, -0.01202901, 0.3032285, -9.920295 -IMU2, 98791, 0.006184489, 0.004034344, -0.003155883, 0.03103495, 0.4298388, -9.896387 -IMU, 98810, -0.001849549, 0.001688175, -0.005514435, 0.1173348, 0.4975675, -9.803239 -IMU2, 98810, 0.007602178, -0.005415097, -0.0005522496, 0.1114187, 0.6195393, -9.823197 -IMU, 98831, 0.004957691, -0.002996415, 0.007559051, -0.01948197, 0.4632936, -9.826325 -IMU2, 98831, -0.001064543, -0.001518926, 0.008896465, -0.01603591, 0.6119761, -9.778654 -GPS, 3, 56679000, 1777, 8, 3.37, 14.1105902, 100.6191362, -0.10, 1.10, 0.22, 292.68, 0.38, 98840 -IMU, 98850, 0.003355078, 0.0008944981, -0.0002920718, -0.001666978, 0.3854052, -9.805753 -IMU2, 98850, 0.001225188, 0.006893665, -0.004743301, -0.03003109, 0.4376318, -9.829454 -IMU, 98870, -0.001395177, 0.006928638, -0.00680601, 0.09513403, 0.4021101, -9.784886 -IMU2, 98870, -0.008799881, -0.0012119, -0.004736784, 0.1408952, 0.5779223, -9.82667 -MAG, 98880, -422, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 98880, -284, -20, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98891, 0, 0, 0, 0, -0.09999999, -0.13, 0.00, 0.00, 0, 0 -DU32, 7, 262745 -CURR, 98891, 0, 0, 1531, 122, 5260, 13.11946 -ATT, 98891, 0.00, -1.95, 0.00, -0.13, 189.63, 189.63 -RCIN, 98891, 1503, 1504, 1022, 1004, 992, 993, 992, 992 -RCOU, 98891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98891, 0.0007582176, 0.0001759119, 0.003919898, 0.02192493, 0.5130094, -9.76209 -IMU2, 98891, -0.000594914, 0.008633265, 0.00673581, 0.04596877, 0.6458086, -9.684059 -IMU, 98910, 0.008555369, -0.003624283, 0.005532173, -0.07440092, 0.3651247, -9.71688 -IMU2, 98910, 0.004359283, 8.412264E-05, 0.001945632, -0.08466554, 0.4475285, -9.739316 -IMU, 98930, 0.003967337, 0.002802987, -0.007482421, 0.03499746, 0.2843157, -10.0172 -IMU2, 98930, 0.0004496295, 0.006429445, -0.0004790453, 0.01989686, 0.3761941, -10.10451 -IMU, 98951, 0.001468845, 0.002409298, -0.004812721, 0.1132853, 0.4341441, -9.826841 -IMU2, 98951, -0.001936281, -0.0006111367, 0.0003934959, 0.1348132, 0.5237405, -9.805401 -IMU, 98970, 0.004622953, -0.003839754, 0.007918321, 0.008715019, 0.4004187, -9.792552 -IMU2, 98970, -0.002587534, -0.008253757, 0.006423726, 0.006460071, 0.5152876, -9.666934 -MAG, 98980, -425, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 98980, -284, -20, 233, 0, 0, 0, 0, 0, 0 -CTUN, 98990, 0, 0, 0, 0, -0.09999999, -0.14, 0.00, 0.00, 0, 0 -ATT, 98990, 0.00, -1.96, 0.00, -0.11, 189.64, 189.64 -RCIN, 98990, 1503, 1504, 1022, 1006, 992, 992, 993, 992 -RCOU, 98991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 98991, 0.002823375, 0.0009379461, -0.0003324675, 0.04949731, 0.2957243, -9.828997 -IMU2, 98991, -0.007878782, -0.01041816, -0.003543898, 0.06666327, 0.4401557, -9.965231 -IMU, 99010, -0.006845014, 0.006336071, -0.008650813, 0.05625542, 0.3940163, -9.694487 -IMU2, 99010, -0.005324772, 0.009291263, -0.01197883, 0.127128, 0.5852046, -9.573356 -IMU, 99030, -0.001254851, -0.0006983727, 0.003339535, 0.09279501, 0.4992839, -9.690196 -IMU2, 99030, -8.613989E-05, -0.009954861, 0.006634166, 0.09012067, 0.6637303, -9.572134 -GPS, 3, 56679200, 1777, 8, 3.37, 14.11059, 100.6191367, -0.10, 1.13, 0.13, 292.68, 0.33, 99040 -IMU, 99050, 0.00239954, 0.002071165, 0.004800655, 0.01347069, 0.4450917, -9.723887 -IMU2, 99050, 0.006555837, 0.004404078, 0.001593554, 0.02377582, 0.5637532, -9.856186 -IMU, 99070, -0.005351776, 0.001515422, -0.006585394, 0.04992659, 0.2803554, -9.817282 -IMU2, 99070, -0.01850455, 0.004487485, -0.006050464, 0.04005718, 0.4433428, -9.800771 -MAG, 99080, -422, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 99080, -285, -17, 232, 0, 0, 0, 0, 0, 0 -CTUN, 99090, 0, 0, 0, 0, -0.09999999, -0.13, 0.00, 0.00, 0, -1 -ATT, 99090, 0.00, -1.97, 0.00, -0.09, 189.63, 189.63 -RCIN, 99090, 1504, 1504, 1024, 1005, 992, 993, 992, 992 -RCOU, 99090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99090, -9.63416E-05, 0.001650926, -0.001701466, 0.1449208, 0.5528419, -9.797822 -IMU2, 99090, -0.0007034466, -0.004500308, -0.0004629428, 0.1909832, 0.6554512, -9.875119 -IMU, 99110, -0.003362255, -0.003182635, 0.004640077, -0.01777269, 0.4647787, -9.752684 -IMU2, 99110, -0.001863925, -0.008811933, 0.007886627, -0.02990258, 0.5519321, -9.754408 -IMU, 99130, 0.008702792, -0.004961878, -0.002121484, 0.07431321, 0.4226093, -9.719002 -IMU2, 99130, 0.01051491, -0.003723478, -0.002769382, -0.006594419, 0.602603, -9.880643 -IMU, 99150, -0.008680465, 0.005963326, -0.00741408, 0.1217211, 0.4742988, -9.75943 -IMU2, 99150, -0.004978947, 0.003169613, -0.00334933, 0.08567309, 0.6034844, -9.861211 -IMU, 99170, 0.008458879, -0.004114769, 0.005343198, 0.06649118, 0.6219597, -9.743776 -IMU2, 99170, 0.001857642, 0.0003725942, 0.001148826, 0.06172609, 0.7318524, -9.631248 -MAG, 99180, -425, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 99180, -283, -21, 235, 0, 0, 0, 0, 0, 0 -CTUN, 99190, 0, 0, 0, 0, -0.09999999, -0.05, 0.00, 0.00, 0, -1 -ATT, 99190, 0.00, -1.95, 0.00, -0.13, 189.64, 189.64 -RCIN, 99190, 1504, 1504, 1024, 1005, 992, 993, 992, 992 -RCOU, 99191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99191, 0.004000498, 0.002428934, 0.006749073, 0.006349742, 0.3556841, -9.832576 -IMU2, 99191, 0.006587151, 0.006650776, 0.006869392, -0.03409779, 0.4536133, -9.862153 -IMU, 99210, -0.0006846357, 0.001479968, -0.006764578, 0.005293265, 0.3401144, -9.939724 -IMU2, 99210, -0.004778543, 0.009303821, -0.005281714, 0.02388203, 0.4510192, -9.887829 -IMU, 99230, -0.0001845267, 0.004595507, 0.002333866, 0.09780604, 0.3910793, -9.820708 -IMU2, 99230, -0.004554002, 0.002061065, 0.003048686, 0.1771108, 0.5121578, -9.749632 -GPS, 3, 56679400, 1777, 8, 3.37, 14.1105893, 100.6191368, -0.10, 1.35, 0.22, 292.68, 0.23, 99240 -IMU, 99250, 0.003334476, -0.002892923, 0.006888689, -0.04541834, 0.4142087, -9.853859 -IMU2, 99250, 0.006754529, 0.002836974, 0.007903526, -0.1248087, 0.5100216, -9.758055 -IMU, 99270, -0.002024414, 0.00222344, -0.004603053, 0.1152605, 0.2584174, -9.71493 -IMU2, 99270, 0.000666447, 0.005235098, -0.00819709, 0.05513453, 0.4329317, -9.850081 -MAG, 99280, -423, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 99280, -284, -18, 232, 0, 0, 0, 0, 0, 0 -CTUN, 99290, 0, 0, 0, 0, -0.09999999, -0.07, 0.00, 0.00, 0, -1 -ATT, 99291, 0.00, -1.94, 0.00, -0.15, 189.64, 189.64 -RCIN, 99291, 1504, 1504, 1022, 1004, 992, 992, 993, 991 -RCOU, 99291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99291, -0.00616104, 0.003190868, -0.006966989, 0.1198601, 0.4387134, -9.789811 -IMU2, 99291, -0.01131736, -0.005576464, -0.00400815, 0.09095323, 0.5647514, -9.761732 -IMU, 99310, -0.002023088, -0.006048124, 0.006691954, 0.03491504, 0.548535, -9.733667 -IMU2, 99310, -0.005772928, -0.0004382208, 0.008152848, 0.003557682, 0.738906, -9.874132 -IMU, 99330, 0.0006284714, -0.002380557, 0.004656637, -0.03526613, 0.4108614, -9.705063 -IMU2, 99330, 0.003549691, -0.00106922, 0.003264705, -0.03345346, 0.4484293, -9.725747 -IMU, 99351, -0.0001216698, 0.002766773, -0.00804774, 0.07161422, 0.3951331, -9.928395 -IMU2, 99351, -0.008667359, 0.002216541, -0.01340568, 0.06987011, 0.4696201, -9.785876 -IMU, 99370, 0.002014238, -0.001743726, 0.002884142, 0.05659837, 0.509932, -9.889293 -IMU2, 99370, -0.00238096, -0.002869389, 0.007103669, 0.08131909, 0.6008441, -9.804075 -MAG, 99380, -423, 70, 60, -86, 10, 139, 0, 0, 0 -MAG2, 99380, -283, -18, 234, 0, 0, 0, 0, 0, 0 -CTUN, 99390, 0, 0, 0, 0, -0.09999999, -0.09, 0.00, 0.00, 0, -1 -ATT, 99390, 0.00, -1.89, 0.00, -0.19, 189.65, 189.65 -RCIN, 99390, 1504, 1503, 1023, 1004, 992, 992, 992, 992 -RCOU, 99391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99391, 0.006387927, -0.003203865, 0.007428739, -0.05592209, 0.3668689, -9.842304 -IMU2, 99391, 0.006173033, 0.002230071, 0.005166642, -0.09166062, 0.5030746, -9.756334 -IMU, 99410, 0.001028491, 0.004782587, -0.005775472, 0.09308281, 0.2042275, -9.762752 -IMU2, 99410, -0.0171168, -0.0007693358, -0.005663381, 0.04905069, 0.3782403, -9.725251 -GPS, 3, 56679600, 1777, 8, 3.37, 14.1105893, 100.619136, -0.10, 1.56, 0.41, 292.68, 0.11, 99420 -IMU, 99431, -0.005422266, 0.003357582, -0.006210052, 0.1065648, 0.4782923, -9.768845 -IMU2, 99431, 0.003290473, 0.004525709, -0.003927783, 0.1540159, 0.5929251, -9.748516 -IMU, 99450, -0.001470299, -0.0041622, 0.008440807, 0.02421536, 0.5269005, -9.705994 -IMU2, 99450, -0.005181009, -0.007793733, 0.004222427, 0.04359853, 0.7305058, -9.752207 -IMU, 99470, 0.001747627, 0.003297098, 0.0009806172, 0.02155599, 0.3972293, -9.679233 -IMU2, 99470, -0.002813082, 0.002037444, 0.001394284, 0.01877952, 0.530737, -9.680684 -MAG, 99480, -422, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 99480, -283, -18, 233, 0, 0, 0, 0, 0, 0 -CTUN, 99490, 0, 0, 0, 0, -0.09999999, -0.17, 0.00, 0.00, 0, -1 -ATT, 99491, 0.00, -1.83, 0.00, -0.17, 189.65, 189.65 -RCIN, 99491, 1503, 1504, 1023, 1004, 992, 992, 992, 992 -RCOU, 99491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99491, -0.00441931, 0.003812339, -0.009922523, 0.1324047, 0.4726726, -9.883744 -IMU2, 99491, -0.005819742, 0.003838863, -0.01030077, 0.1051399, 0.6077168, -9.939369 -IMU, 99510, -6.365217E-05, -0.001647104, 0.006653844, 0.07757685, 0.5219742, -9.817894 -IMU2, 99510, -0.0006923862, 0.006329656, 0.01809245, 0.03778064, 0.6186568, -9.89406 -IMU, 99530, 0.002837893, -0.003954969, 0.008733028, -0.03101945, 0.3577663, -9.843947 -IMU2, 99530, -0.000763271, -0.0002740342, 0.01183747, -0.005691648, 0.4702122, -9.879848 -IMU, 99551, 0.000872096, 0.002573244, -0.00753727, 0.03641149, 0.2435728, -9.814958 -IMU2, 99551, -0.01110152, 0.008656163, -0.009641311, 0.02866268, 0.3756604, -9.795425 -IMU, 99570, -0.008176604, 0.001290023, -0.006067516, 0.09295821, 0.4886034, -9.82099 -IMU2, 99570, -0.009433638, 0.0007967371, -0.0034083, 0.04880893, 0.6444218, -9.876154 -MAG, 99580, -425, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 99580, -284, -17, 232, 0, 0, 0, 0, 0, 0 -CTUN, 99590, 0, 0, 0, 0, -0.11, -0.01, 0.00, 0.00, 0, -1 -ATT, 99590, 0.00, -1.77, 0.00, -0.14, 189.65, 189.65 -RCIN, 99590, 1503, 1504, 1022, 1004, 992, 992, 993, 992 -RCOU, 99591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99591, 0.003168399, -0.004843976, 0.008466155, 0.01869392, 0.5293859, -9.752801 -IMU2, 99591, 0.005017541, -0.002162352, 0.01414546, -0.02080655, 0.6476079, -9.834265 -IMU, 99610, 0.0001141354, 0.004440002, 0.0004820309, 0.009893522, 0.3145996, -9.72324 -IMU2, 99610, -0.0005776305, -0.0001652017, 0.0005070129, -0.1067028, 0.4913424, -9.82855 -IMU, 99631, -0.003119072, 0.002124682, -0.0102851, 0.1361986, 0.4123305, -9.868114 -IMU2, 99631, -0.01539892, 0.001215139, -0.003903178, 0.1176684, 0.4873869, -9.863784 -GPS, 3, 56679800, 1777, 9, 3.00, 14.1105892, 100.6191364, -0.11, 1.64, 0.30, 292.68, 0.07, 99640 -IMU, 99650, -0.00233846, -0.002318311, 0.007296436, 0.09842473, 0.5289965, -9.809088 -IMU2, 99650, 0.001682475, -0.004710078, 0.009854767, 0.1127322, 0.6454133, -9.855017 -IMU, 99670, -0.008441763, -0.002659906, 0.005821141, -0.05424561, 0.3463888, -9.720198 -IMU2, 99670, -0.01587264, -0.002017448, 0.004615176, -0.1561198, 0.4485623, -9.776019 -MAG, 99680, -422, 69, 60, -86, 10, 139, 0, 0, 0 -MAG2, 99680, -284, -19, 234, 0, 0, 0, 0, 0, 0 -CTUN, 99690, 0, 0, 0, 0, -0.09999999, -0.14, 0.00, 0.00, 0, -1 -ATT, 99691, 0.00, -1.74, 0.00, -0.11, 189.66, 189.66 -RCIN, 99691, 1503, 1505, 1024, 1004, 992, 992, 993, 991 -RCOU, 99691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99691, 0.00179467, 0.002258666, -0.009354093, 0.09085455, 0.4275376, -9.791979 -IMU2, 99691, -0.001348823, 0.003790719, -0.007056342, 0.07966256, 0.5707374, -9.697812 -IMU, 99710, -0.005579459, -0.0008292794, -0.003887746, 0.1134638, 0.5248096, -9.824264 -IMU2, 99710, 0.004267879, -0.003230988, 0.0006194916, 0.1034172, 0.5978465, -9.954821 -IMU, 99730, 0.01045288, -0.003393847, 0.009647575, 0.007037565, 0.4848244, -9.744705 -IMU2, 99730, 0.01200656, -0.008731111, 0.007320829, -0.03635609, 0.585927, -9.881698 -IMU, 99750, -0.001895698, 0.003722027, -0.0001289467, -0.009118274, 0.2144258, -9.795908 -IMU2, 99750, -0.005636141, 0.005268741, -0.0003013974, 0.0694288, 0.3961399, -9.856679 -IMU, 99770, -0.001690483, -6.371737E-05, -0.00922798, 0.1200482, 0.4617835, -9.925169 -IMU2, 99770, -0.01616947, 0.004782059, -0.008872852, 0.1471076, 0.6174694, -9.917435 -MAG, 99780, -424, 69, 61, -86, 10, 139, 0, 0, 0 -MAG2, 99780, -283, -19, 232, 0, 0, 0, 0, 0, 0 -CTUN, 99790, 0, 0, 0, 0, -0.11, -0.13, 0.00, 0.00, 0, -1 -ATT, 99790, 0.00, -1.75, 0.00, -0.10, 189.66, 189.66 -RCIN, 99790, 1503, 1504, 1023, 1003, 993, 992, 992, 992 -RCOU, 99791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99791, 0.003766743, -0.0002668276, 0.007942175, 0.009943008, 0.4435855, -9.776484 -IMU2, 99791, 0.001921723, 0.001875058, 0.006849817, -0.005600452, 0.6176859, -9.845956 -IMU, 99810, 0.0003019832, -0.0005800314, 0.002922729, 0.003569886, 0.3038493, -9.820212 -IMU2, 99810, -0.0003082417, 0.00746589, 0.00229156, -0.05661106, 0.4247375, -9.682405 -IMU, 99830, -0.0009104125, 0.005249828, -0.01111909, 0.1301367, 0.3306299, -9.82153 -IMU2, 99830, -0.01039157, 0.003175567, -0.009199141, 0.1532388, 0.4823462, -9.648136 -GPS, 3, 56680000, 1777, 8, 3.37, 14.110589, 100.6191381, -0.11, 1.46, 0.16, 292.68, 0.14, 99840 -IMU, 99851, -0.004400702, -0.0004771277, 0.000275715, 0.05180195, 0.5493466, -9.747105 -IMU2, 99851, -0.01143571, -0.002298098, 0.005300025, 0.09222412, 0.6376193, -9.723732 -IMU, 99870, 0.004721332, -0.003769275, 0.007575646, 0.007873833, 0.4054738, -9.636546 -IMU2, 99870, -0.002089746, -0.003688134, 0.005603625, 0.00451684, 0.5259866, -9.722897 -MAG, 99880, -422, 69, 59, -86, 10, 139, 0, 0, 0 -MAG2, 99880, -283, -19, 232, 0, 0, 0, 0, 0, 0 -PM, 0, 0, 3, 1000, 2639992, 13, 0, 0, 0 -CTUN, 99890, 0, 0, 0, 0, -0.11, -0.06, 0.00, 0.00, 0, -1 -DU32, 7, 262745 -CURR, 99890, 0, 0, 1531, 131, 5312, 13.46396 -ATT, 99890, 0.00, -1.78, 0.00, -0.09, 189.66, 189.66 -RCIN, 99890, 1503, 1504, 1024, 1003, 992, 993, 992, 992 -RCOU, 99891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99891, -0.0005407128, 0.003793683, -0.002825154, 0.03863762, 0.2778402, -9.841671 -IMU2, 99891, -0.006304637, 0.006648956, -0.004171841, -0.0234915, 0.3857838, -9.839526 -IMU, 99910, 0.0002839435, -0.002021179, -0.006154333, 0.09924071, 0.5365158, -9.872346 -IMU2, 99910, 0.003066916, -0.009222001, -0.001923052, 0.09085429, 0.6834072, -10.01367 -IMU, 99930, 0.007834025, -0.003490023, 0.005090807, -0.02450722, 0.4386109, -9.845732 -IMU2, 99930, 0.007838678, -0.001788601, 0.005286873, -0.004460216, 0.5447507, -9.83433 -IMU, 99950, 0.001026822, -0.0005732216, 0.002049084, 0.003953397, 0.3253032, -9.814947 -IMU2, 99950, 0.004390106, -0.007286205, 0.002884285, -0.09962094, 0.4725175, -9.824824 -IMU, 99970, -0.002591895, 0.002240054, -0.007594511, 0.1233448, 0.4110432, -9.723927 -IMU2, 99970, 0.000235064, 0.0006810445, -0.005234629, 0.091645, 0.5498232, -9.807002 -MAG, 99980, -424, 70, 61, -86, 10, 139, 0, 0, 0 -MAG2, 99980, -283, -16, 233, 0, 0, 0, 0, 0, 0 -CTUN, 99990, 0, 0, 0, 0, -0.11, 0.04, 0.00, 0.00, 0, -1 -ATT, 99991, 0.00, -1.83, 0.00, -0.09, 189.66, 189.66 -RCIN, 99991, 1504, 1504, 1024, 1003, 992, 993, 992, 992 -RCOU, 99991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 99991, -0.003177317, -0.001608491, 0.004347101, 0.06286513, 0.5661558, -9.785329 -IMU2, 99991, 0.002658952, 0.004805965, 0.01127636, 0.07239521, 0.6427889, -9.924076 -IMU, 100011, 0.004194031, 0.0001429953, 0.008531148, -0.03088214, 0.3830802, -9.740406 -IMU2, 100011, 0.005808551, 0.000232514, 0.01173777, -0.03003883, 0.4686028, -9.711623 -IMU, 100031, -0.001291392, 0.001761734, -0.005953279, 0.04458472, 0.2759756, -9.80163 -IMU2, 100031, -0.0111605, -0.001515143, -0.003058071, 0.01783001, 0.4304096, -9.782933 -GPS, 3, 56680200, 1777, 8, 3.37, 14.1105886, 100.619139, -0.11, 1.27, 0.17, 292.68, 0.24, 100040 -IMU, 100051, 0.0008018445, -0.001653515, -0.002376257, 0.1042004, 0.4663773, -9.866737 -IMU2, 100051, -0.006505627, -0.00800875, -4.771538E-05, 0.03904605, 0.6094342, -9.765942 -IMU, 100070, 0.007641856, 0.001171038, 0.005972357, -0.0214964, 0.3209479, -9.815849 -IMU2, 100070, -0.001995906, 0.004768234, 0.007815219, -0.09871674, 0.4980431, -9.76078 -MAG, 100080, -423, 68, 60, -86, 10, 139, 0, 0, 0 -MAG2, 100080, -283, -16, 232, 0, 0, 0, 0, 0, 0 -EV, 11 -D32, 9, 18251 -CMD, 1, 0, 16, 0, 0, 0.00, 14.1105685, 100.6192319 -EV, 10 -CTUN, 115391, 0, 0, 0, 0, 0.68, -0.09, 0.00, 0.00, 0, -1 -ATT, 115391, 0.00, 0.09, 0.00, 0.57, 182.49, 182.49 -RCIN, 115391, 1503, 1504, 1015, 2011, 992, 992, 993, 991 -RCOU, 115391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115391, 0.02690804, -0.01455218, -0.05497147, 0.1667195, 0.3931115, -9.793042 -IMU2, 115391, 0.0263056, -0.02078444, -0.05019797, 0.1527848, 0.5016375, -9.800529 -IMU, 115410, 0.03036566, -0.01380969, -0.04499388, 0.1692534, 0.3570677, -9.624863 -IMU2, 115410, 0.03022759, -0.01939039, -0.0475689, 0.1592191, 0.477726, -9.68758 -IMU, 115431, 0.04194621, -0.01591257, -0.03196166, 0.1949993, 0.3057886, -9.636971 -IMU2, 115431, 0.0370039, -0.02730206, -0.03320817, 0.2038536, 0.4546751, -9.562141 -GPS, 3, 56695600, 1777, 10, 1.44, 14.1105676, 100.6192312, 0.66, -1.39, 1.36, 292.68, 0.26, 115440 -IMU, 115450, 0.05943602, -0.02002659, -0.01912385, 0.2339035, 0.3040345, -9.75034 -IMU2, 115450, 0.05916355, -0.02423742, -0.01961913, 0.1897056, 0.4871972, -9.740042 -IMU, 115471, 0.06709114, -0.03165295, -0.0105688, 0.1594438, 0.2799598, -9.724665 -IMU2, 115471, 0.06145966, -0.03705858, -0.01170277, 0.1605941, 0.3937998, -9.680115 -MAG, 115480, -413, 17, 64, -86, 10, 139, 0, 0, 0 -MAG2, 115480, -273, -67, 241, 0, 0, 0, 0, 0, 0 -CTUN, 115490, 0, 0, 0, 0, 0.64, 0.19, 0.00, 0.00, 0, -3 -ATT, 115490, 0.00, 0.38, 0.00, 0.45, 182.35, 182.35 -RCIN, 115490, 1503, 1504, 1015, 2010, 993, 992, 992, 992 -RCOU, 115490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115490, 0.06334537, -0.04203882, -0.006845377, 0.2279209, 0.2027942, -9.75786 -IMU2, 115490, 0.0528127, -0.05422081, -0.01066912, 0.2024636, 0.3245736, -9.760239 -IMU, 115510, 0.04725132, -0.04965584, -0.002633009, 0.2179027, 0.1950002, -9.759245 -IMU2, 115510, 0.0271508, -0.06321153, -0.006081348, 0.2232369, 0.3267967, -9.765306 -IMU, 115530, 0.02960253, -0.06450482, 0.002986668, 0.1930816, 0.2478441, -9.829196 -IMU2, 115530, 0.02461168, -0.0672119, 0.003414482, 0.2287951, 0.4212712, -9.738664 -IMU, 115550, 0.02062048, -0.08677064, 0.01599443, 0.08001745, 0.3870621, -9.900935 -IMU2, 115550, 0.01509798, -0.09373377, 0.01518229, 0.0853107, 0.5500257, -9.893063 -IMU, 115570, 0.02021939, -0.1084567, 0.02616423, -0.05692558, 0.3291879, -9.821019 -IMU2, 115570, 0.02077651, -0.1136564, 0.02239345, -0.1879882, 0.5167003, -9.846665 -MAG, 115580, -414, 15, 65, -86, 10, 139, 0, 0, 0 -MAG2, 115580, -273, -71, 245, 0, 0, 0, 0, 0, 0 -CTUN, 115590, 0, 0, 0, 0, 0.61, 0.06, 0.00, 0.00, 0, -3 -ATT, 115591, 0.00, 0.59, 0.00, 0.02, 182.44, 182.44 -RCIN, 115591, 1503, 1504, 1015, 2011, 992, 992, 993, 992 -RCOU, 115591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115591, 0.007736364, -0.1157989, 0.02784019, 0.09935526, 0.3002955, -9.868073 -IMU2, 115591, 0.002810054, -0.1405549, 0.02340015, -0.01728225, 0.4487035, -9.812546 -IMU, 115611, 0.004328081, -0.1133414, 0.02233808, 0.209344, 0.2492395, -9.91753 -IMU2, 115611, 0.009767517, -0.1181583, 0.01433307, 0.2131573, 0.3339938, -9.919143 -IMU, 115631, 0.01127743, -0.1030415, 0.01553266, 0.03159006, 0.235072, -10.02503 -IMU2, 115631, 0.004213776, -0.1081834, 0.01061667, 0.05504012, 0.3186265, -9.944636 -GPS, 3, 56695800, 1777, 10, 1.44, 14.1105676, 100.6192309, 0.60, -1.24, 1.35, 292.68, 0.14, 115640 -IMU, 115651, 0.01335111, -0.1034502, 0.0003944493, -0.06040041, 0.2295935, -9.880753 -IMU2, 115651, 0.008094121, -0.1117278, -0.008961888, -0.06342459, 0.3385991, -9.872526 -IMU, 115671, 0.007724741, -0.1071697, -0.01731027, 0.02564165, 0.1759006, -9.867425 -IMU2, 115671, 0.0001417696, -0.1145198, -0.02363271, -0.01923287, 0.3253454, -9.903049 -MAG, 115680, -410, 17, 67, -86, 10, 139, 0, 0, 0 -MAG2, 115680, -270, -67, 243, 0, 0, 0, 0, 0, 0 -CTUN, 115690, 0, 0, 0, 0, 0.58, 0.09, 0.00, 0.00, 0, -2 -ATT, 115690, 0.00, 0.68, 0.00, -0.55, 182.48, 182.48 -RCIN, 115690, 1502, 1504, 1016, 2009, 992, 993, 992, 992 -RCOU, 115690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115690, 0.01224511, -0.1116434, -0.01063881, -0.01657945, 0.3684975, -9.790956 -IMU2, 115690, 0.01125038, -0.123853, -0.008393773, 0.005031228, 0.5344663, -9.72822 -IMU, 115710, 0.02943747, -0.1137598, -0.001305062, -0.175747, 0.341751, -9.827951 -IMU2, 115710, 0.02614116, -0.1287145, 0.002503884, -0.176473, 0.5046936, -9.785298 -IMU, 115730, 0.04014501, -0.1147434, 0.006589631, -0.220872, 0.3451048, -9.885088 -IMU2, 115730, 0.04297461, -0.1216449, 7.071579E-05, -0.2533998, 0.4610878, -9.859377 -IMU, 115750, 0.04954944, -0.1114918, 0.01517949, -0.1241176, 0.3355871, -9.848474 -IMU2, 115750, 0.05198195, -0.1187758, 0.01404706, -0.09447527, 0.5077688, -9.897835 -IMU, 115771, 0.05865136, -0.1066497, 0.02732355, -0.1169869, 0.2567283, -9.810445 -IMU2, 115771, 0.05865894, -0.118271, 0.0238355, -0.1107857, 0.4245034, -9.744092 -MAG, 115780, -410, 18, 71, -86, 10, 139, 0, 0, 0 -MAG2, 115780, -269, -68, 246, 0, 0, 0, 0, 0, 0 -CTUN, 115790, 0, 0, 0, 0, 0.55, 0.04, 0.00, 0.00, 0, -2 -ATT, 115790, 0.00, 0.95, 0.00, -1.12, 182.59, 182.59 -RCIN, 115790, 1502, 1504, 1019, 1994, 992, 993, 992, 992 -RCOU, 115791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115791, 0.06840818, -0.09893979, 0.03922037, -0.1503436, 0.2416834, -9.806296 -IMU2, 115791, 0.06574005, -0.1068758, 0.03740536, -0.1333612, 0.3761913, -9.756814 -IMU, 115811, 0.05998819, -0.09042607, 0.04710741, -0.279656, 0.2519215, -9.762287 -IMU2, 115811, 0.05353534, -0.09683144, 0.03842175, -0.2949936, 0.3443083, -9.801629 -IMU, 115831, 0.03325316, -0.08750983, 0.0500738, -0.3641734, 0.3094987, -9.750574 -IMU2, 115831, 0.02541475, -0.09674378, 0.04691467, -0.3452589, 0.4979928, -9.816926 -GPS, 3, 56696000, 1777, 10, 1.44, 14.1105669, 100.6192302, 0.54, -1.15, 1.31, 292.68, 0.01, 115840 -IMU, 115850, 0.006272806, -0.08138268, 0.05133354, -0.3082497, 0.3037277, -9.809681 -IMU2, 115850, -0.003047243, -0.08192144, 0.05039652, -0.3815953, 0.4626906, -9.8357 -IMU, 115870, 0.003532192, -0.06328905, 0.05630835, -0.1640976, 0.2143421, -9.817572 -IMU2, 115870, -0.01086139, -0.0641753, 0.05727068, -0.1473631, 0.3718152, -9.841953 -MAG, 115880, -408, 19, 75, -86, 10, 139, 0, 0, 0 -MAG2, 115880, -270, -63, 251, 0, 0, 0, 0, 0, 0 -CTUN, 115890, 0, 0, 0, 0, 0.53, -0.10, 0.00, 0.00, 0, -3 -DU32, 7, 262745 -CURR, 115890, 0, 0, 1534, 173, 5296, 15.94009 -ATT, 115890, 0.00, 1.10, 0.00, -1.53, 182.91, 182.91 -RCIN, 115890, 1503, 1504, 1022, 1907, 993, 992, 992, 992 -RCOU, 115891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115891, 0.02411056, -0.05073525, 0.06618109, -0.1768657, 0.2144334, -9.821573 -IMU2, 115891, 0.01329903, -0.0609922, 0.07018863, -0.1831052, 0.2935958, -9.81319 -IMU, 115910, 0.04401014, -0.04548221, 0.07053198, -0.2657516, 0.2454923, -9.750841 -IMU2, 115910, 0.02802921, -0.05312811, 0.07535889, -0.2884775, 0.3604183, -9.785096 -IMU, 115930, 0.04686096, -0.04403868, 0.0750584, -0.2843723, 0.2100314, -9.680636 -IMU2, 115930, 0.03847486, -0.04548398, 0.07979912, -0.3182583, 0.3320683, -9.658493 -IMU, 115950, 0.04323879, -0.05125578, 0.07301318, -0.2730866, 0.1395936, -9.57781 -IMU2, 115950, 0.0378068, -0.04290136, 0.07902635, -0.2760785, 0.2660916, -9.495477 -IMU, 115970, 0.03547266, -0.06484267, 0.06696816, -0.2291156, 0.1231432, -9.718628 -IMU2, 115970, 0.02701087, -0.06923495, 0.06674493, -0.2553955, 0.2396895, -9.82921 -MAG, 115980, -408, 23, 78, -86, 10, 139, 0, 0, 0 -MAG2, 115980, -267, -62, 255, 0, 0, 0, 0, 0, 0 -CTUN, 115990, 0, 0, 0, 0, 0.49, 0.00, 0.00, 0.00, 0, -4 -ATT, 115991, 0.00, 1.29, 0.00, -1.87, 183.31, 183.31 -RCIN, 115991, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 115991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 115991, 0.03033623, -0.07973009, 0.06093697, -0.2854325, 0.1691675, -9.704501 -IMU2, 115991, 0.02538193, -0.08330084, 0.05508354, -0.345376, 0.2649649, -9.775978 -IMU, 116010, 0.0241315, -0.09326053, 0.05583867, -0.3040803, 0.2318722, -9.88312 -IMU2, 116010, 0.0240815, -0.1113079, 0.04872046, -0.2887886, 0.4071159, -9.81708 -IMU, 116030, 0.02397696, -0.1050379, 0.05262403, -0.2971615, 0.2014783, -9.759925 -IMU2, 116030, 0.01949208, -0.1140253, 0.04300368, -0.3258197, 0.3747357, -9.834929 -IMU, 116051, 0.03092356, -0.1047011, 0.04560102, -0.354841, 0.09736912, -9.630186 -IMU2, 116051, 0.03123454, -0.1081335, 0.03589176, -0.3486666, 0.1904304, -9.667379 -GPS, 3, 56696200, 1777, 10, 1.44, 14.1105671, 100.6192292, 0.47, -1.41, 1.20, 292.68, 0.07, 116060 -IMU, 116070, 0.03384493, -0.09150905, 0.03409164, -0.2884087, 0.02216963, -9.711663 -IMU2, 116070, 0.02617063, -0.09080698, 0.02550149, -0.2916924, 0.1636964, -9.734908 -MAG, 116080, -406, 25, 79, -86, 10, 139, 0, 0, 0 -MAG2, 116080, -267, -59, 257, 0, 0, 0, 0, 0, 0 -CTUN, 116090, 0, 0, 0, 0, 0.46, -0.12, 0.00, 0.00, 0, -5 -ATT, 116090, 0.00, 1.43, 0.00, -2.42, 183.58, 183.58 -RCIN, 116090, 1503, 1504, 1023, 1512, 992, 993, 992, 992 -RCOU, 116091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116091, 0.03505609, -0.0771466, 0.02277755, -0.332266, 0.03265695, -9.828631 -IMU2, 116091, 0.0299151, -0.08061966, 0.01332434, -0.4229044, 0.2131151, -9.750269 -IMU, 116111, 0.0360851, -0.07552053, 0.01191106, -0.4048513, 0.1529027, -9.80523 -IMU2, 116111, 0.02406125, -0.08251381, 0.009330388, -0.3920845, 0.2629697, -9.709765 -IMU, 116130, 0.03850688, -0.09012641, 0.00431654, -0.4914058, 0.2293433, -9.714173 -IMU2, 116130, 0.03655974, -0.09598343, -0.00129008, -0.5076028, 0.3106682, -9.712324 -IMU, 116150, 0.04217252, -0.1000528, -0.004469417, -0.5546361, 0.1178601, -9.66655 -IMU2, 116150, 0.03966861, -0.09987855, -0.01094393, -0.6123786, 0.2993754, -9.77423 -IMU, 116171, 0.04223485, -0.1012614, -0.01593897, -0.5597661, 0.07629171, -9.819757 -IMU2, 116171, 0.04195588, -0.1072763, -0.02371536, -0.5474951, 0.2281997, -9.80346 -MAG, 116180, -406, 28, 83, -86, 10, 139, 0, 0, 0 -MAG2, 116180, -267, -58, 260, 0, 0, 0, 0, 0, 0 -CTUN, 116190, 0, 0, 0, 0, 0.42, 0.09, 0.00, 0.00, 0, -6 -ATT, 116191, 0.00, 1.63, 0.00, -2.88, 183.56, 183.56 -RCIN, 116191, 1503, 1504, 1024, 1512, 993, 992, 992, 992 -RCOU, 116191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116191, 0.04628224, -0.09756964, -0.03011232, -0.5976271, 0.07910591, -9.872504 -IMU2, 116191, 0.046953, -0.1098479, -0.02669201, -0.6470818, 0.2212896, -9.823536 -IMU, 116210, 0.04842381, -0.08451848, -0.04143876, -0.6104528, 0.02729033, -9.860401 -IMU2, 116210, 0.04333009, -0.08978164, -0.04500625, -0.6017625, 0.2101228, -9.83567 -IMU, 116230, 0.05971505, -0.0668439, -0.04794986, -0.6046584, 0.08492178, -9.711192 -IMU2, 116230, 0.05429805, -0.06939015, -0.04589346, -0.6693056, 0.191914, -9.740698 -GPS, 3, 56696400, 1777, 10, 1.44, 14.1105681, 100.6192302, 0.41, -1.46, 0.88, 292.68, 0, 116240 -IMU, 116251, 0.06395472, -0.0471021, -0.0552394, -0.7058128, 0.0850641, -9.778576 -IMU2, 116251, 0.05617969, -0.05316672, -0.05896766, -0.7467968, 0.2244179, -9.740659 -IMU, 116270, 0.05631832, -0.03044459, -0.06372896, -0.6750425, 0.01044628, -9.805564 -IMU2, 116270, 0.03769498, -0.03604573, -0.06429363, -0.6864195, 0.1665852, -9.747357 -MAG, 116281, -402, 27, 86, -86, 10, 139, 0, 0, 0 -MAG2, 116281, -266, -57, 263, 0, 0, 0, 0, 0, 0 -CTUN, 116290, 0, 0, 0, 0, 0.4, -0.12, 0.00, 0.00, 0, -6 -ATT, 116290, 0.00, 1.90, 0.00, -3.11, 183.26, 183.26 -RCIN, 116290, 1503, 1504, 1024, 1512, 993, 993, 992, 992 -RCOU, 116290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116290, 0.06712219, -0.0201014, -0.07138287, -0.6187585, -0.01975518, -9.940761 -IMU2, 116290, 0.06383781, -0.01735736, -0.06912898, -0.6780776, 0.1351814, -9.968992 -IMU, 116310, 0.07592814, -0.01195259, -0.07489975, -0.6655945, 0.02573255, -9.821389 -IMU2, 116310, 0.07260013, -0.02075817, -0.07114484, -0.6845127, 0.164807, -9.958166 -IMU, 116330, 0.07914601, -0.005651806, -0.07397985, -0.726751, 0.1554224, -9.868339 -IMU2, 116330, 0.08203789, -0.005736005, -0.06980728, -0.774883, 0.342967, -9.911212 -IMU, 116350, 0.08502454, 0.001789898, -0.06952904, -0.7714886, 0.03164326, -9.858279 -IMU2, 116350, 0.09484642, -0.003370704, -0.06518656, -0.7723172, 0.164103, -9.853385 -IMU, 116371, 0.07856411, 0.01526326, -0.06937611, -0.8605814, -0.1235069, -9.870687 -IMU2, 116371, 0.06614043, 0.01216324, -0.06469724, -0.8309932, 0.03072, -9.778282 -MAG, 116380, -404, 25, 87, -86, 10, 139, 0, 0, 0 -MAG2, 116380, -265, -59, 264, 0, 0, 0, 0, 0, 0 -CTUN, 116390, 0, 0, 0, 0, 0.37, -0.09, 0.00, 0.00, 0, -6 -ATT, 116390, 0.00, 2.25, 0.00, -3.01, 182.86, 182.86 -RCIN, 116390, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116391, 0.08701456, 0.02162955, -0.06933358, -0.8819101, -0.1355979, -9.767688 -IMU2, 116391, 0.09146942, 0.01703206, -0.06624062, -0.8551226, -0.02709711, -9.648767 -IMU, 116410, 0.06948835, 0.04204944, -0.06833901, -0.9332362, -0.09635898, -9.917822 -IMU2, 116410, 0.06776123, 0.04445623, -0.06465599, -1.010648, 0.1072036, -9.829921 -IMU, 116430, 0.04979735, 0.07218318, -0.07517684, -0.852758, -0.2370566, -10.01067 -IMU2, 116430, 0.03605238, 0.07879896, -0.07444216, -0.9203621, -0.06701124, -10.06 -IMU, 116451, 0.02246658, 0.111619, -0.08984154, -0.7516978, -0.4509764, -9.950024 -IMU2, 116451, 0.01396038, 0.1058795, -0.08207822, -0.8249428, -0.3212789, -9.953943 -GPS, 3, 56696600, 1777, 10, 1.44, 14.1105687, 100.6192319, 0.34, -1.29, 0.63, 292.68, -0.16, 116460 -IMU, 116470, -0.004609438, 0.125141, -0.102388, -0.5422509, -0.3510333, -9.80039 -IMU2, 116470, -0.004893348, 0.1192378, -0.09682731, -0.5417066, -0.2195796, -9.76455 -MAG, 116480, -405, 23, 86, -86, 10, 139, 0, 0, 0 -MAG2, 116480, -265, -59, 262, 0, 0, 0, 0, 0, 0 -CTUN, 116490, 0, 0, 0, 0, 0.34, 0.01, 0.00, 0.00, 0, -5 -ATT, 116490, 0.00, 2.33, 0.00, -2.43, 182.39, 182.39 -RCIN, 116490, 1503, 1504, 1023, 1513, 992, 992, 992, 992 -RCOU, 116490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116490, -0.01347781, 0.1091938, -0.103817, -0.4665349, -0.20182, -9.69292 -IMU2, 116490, -0.01047758, 0.1032592, -0.09711953, -0.443479, -0.07663119, -9.576138 -IMU, 116511, -0.03403082, 0.08333059, -0.09744696, -0.5780783, -0.1298074, -9.685418 -IMU2, 116511, -0.03307624, 0.0801027, -0.09453752, -0.539325, -0.02440369, -9.69243 -IMU, 116530, -0.06599847, 0.05914425, -0.09542148, -0.5157356, -0.2195051, -9.881344 -IMU2, 116530, -0.0770462, 0.05061404, -0.08600509, -0.541532, -0.03935122, -9.894301 -IMU, 116550, -0.08870151, 0.03116141, -0.09328078, -0.4235162, -0.2096688, -9.836433 -IMU2, 116550, -0.0833391, 0.02725226, -0.08574948, -0.4593824, 0.03064024, -9.788182 -IMU, 116570, -0.096164, -0.002040818, -0.08568002, -0.3119761, -0.08562025, -9.68532 -IMU2, 116570, -0.1092465, -0.00266319, -0.0791999, -0.4396606, 0.06865704, -9.658781 -MAG, 116580, -406, 18, 83, -86, 10, 139, 0, 0, 0 -MAG2, 116580, -268, -65, 260, 0, 0, 0, 0, 0, 0 -CTUN, 116590, 0, 0, 0, 0, 0.31, -0.05, 0.00, 0.00, 0, -6 -ATT, 116590, 0.00, 1.84, 0.00, -2.21, 181.88, 181.88 -RCIN, 116590, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116591, -0.1071032, -0.01345348, -0.06861033, -0.4059207, -0.05883446, -9.669391 -IMU2, 116591, -0.107173, -0.01366816, -0.06707998, -0.3595338, 0.04959154, -9.666223 -IMU, 116610, -0.1090406, -0.02747566, -0.05475406, -0.5654252, 0.05509323, -9.788559 -IMU2, 116610, -0.1055493, -0.02663721, -0.04579759, -0.5877437, 0.244916, -9.749816 -IMU, 116630, -0.08234814, -0.04455535, -0.03988758, -0.6378797, -0.03695497, -9.815259 -IMU2, 116630, -0.08135263, -0.0463939, -0.03822169, -0.5386238, 0.09451222, -9.892529 -GPS, 3, 56696800, 1777, 10, 1.44, 14.1105702, 100.619232, 0.30, -0.96, 0.84, 292.68, -0.36, 116640 -IMU, 116651, -0.0563247, -0.04454555, -0.02305163, -0.3440128, -0.06335875, -10.10552 -IMU2, 116651, -0.06422588, -0.04504533, -0.02280359, -0.3435614, 0.09004176, -10.19637 -IMU, 116671, -0.05030577, -0.006285828, -0.006163771, -0.3445104, -0.04347193, -10.26189 -IMU2, 116671, -0.0525053, -0.003709464, -0.004537581, -0.359704, 0.06175077, -10.27447 -MAG, 116681, -406, 15, 83, -86, 10, 139, 0, 0, 0 -MAG2, 116681, -268, -68, 261, 0, 0, 0, 0, 0, 0 -CTUN, 116690, 0, 0, 0, 0, 0.29, -0.04, 0.00, 0.00, 0, -5 -ATT, 116691, 0.00, 1.38, 0.00, -2.32, 181.74, 181.74 -RCIN, 116691, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116691, -0.06117756, 0.03668883, 0.00650034, -0.543448, 0.05305412, -10.0393 -IMU2, 116691, -0.05320524, 0.04066825, 0.01006226, -0.602885, 0.1776534, -9.960754 -IMU, 116711, -0.07262829, 0.05894051, 0.01284601, -0.650125, -0.02592421, -9.915814 -IMU2, 116711, -0.07299113, 0.06282394, 0.01980509, -0.6274688, 0.07450056, -9.960472 -IMU, 116730, -0.08518613, 0.06469356, 0.01800328, -0.4571621, 0.007672787, -9.832757 -IMU2, 116730, -0.08960433, 0.06537877, 0.02128005, -0.5070043, 0.1863035, -9.765821 -IMU, 116750, -0.08223957, 0.06947086, 0.03526187, -0.4377394, 0.0788614, -9.744729 -IMU2, 116750, -0.07678399, 0.06875437, 0.0427129, -0.3820567, 0.2184068, -9.710426 -IMU, 116771, -0.07207753, 0.08875547, 0.05145389, -0.3542717, 0.0396266, -9.872977 -IMU2, 116771, -0.07523662, 0.08718221, 0.05650371, -0.3334617, 0.1924216, -9.919302 -MAG, 116780, -406, 14, 82, -86, 10, 139, 0, 0, 0 -MAG2, 116780, -267, -71, 260, 0, 0, 0, 0, 0, 0 -CTUN, 116790, 0, 0, 0, 0, 0.27, -0.14, 0.00, 0.00, 0, -5 -ATT, 116791, 0.00, 0.97, 0.00, -1.84, 181.92, 181.92 -RCIN, 116791, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116791, -0.05802776, 0.1044076, 0.0564643, -0.4995188, -0.01239198, -9.912688 -IMU2, 116791, -0.06068019, 0.09948125, 0.07097063, -0.5626667, 0.1505718, -9.934712 -IMU, 116810, -0.05366028, 0.1030445, 0.05985322, -0.4364357, 0.1881879, -9.651985 -IMU2, 116810, -0.04626532, 0.09169893, 0.06812935, -0.4710171, 0.3187633, -9.596663 -IMU, 116830, -0.04946787, 0.0934643, 0.07676983, -0.3772928, 0.2839409, -9.707454 -IMU2, 116830, -0.0469239, 0.09125239, 0.09106331, -0.436758, 0.471529, -9.751163 -IMU, 116850, -0.04281236, 0.09430249, 0.09509605, -0.2947295, 0.2449124, -9.871351 -IMU2, 116850, -0.03837687, 0.09159642, 0.110699, -0.3152012, 0.3713228, -9.90888 -GPS, 3, 56697000, 1777, 10, 1.44, 14.1105716, 100.6192317, 0.24, -0.56, 1.00, 292.68, -0.51, 116860 -IMU, 116871, -0.0342041, 0.0916924, 0.1041852, -0.4121078, 0.2139892, -9.864397 -IMU2, 116871, -0.03937078, 0.09378269, 0.1134256, -0.4448359, 0.4157795, -9.82269 -MAG, 116880, -408, 15, 80, -86, 10, 139, 0, 0, 0 -MAG2, 116880, -269, -68, 255, 0, 0, 0, 0, 0, 0 -CTUN, 116890, 0, 0, 0, 0, 0.24, -0.16, 0.00, 0.00, 0, -5 -DU32, 7, 262745 -CURR, 116890, 0, 0, 1524, 131, 5302, 16.29026 -ATT, 116890, 0.00, 0.74, 0.00, -1.25, 182.41, 182.41 -RCIN, 116890, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116891, -0.02695091, 0.07611218, 0.1091999, -0.3406712, 0.2446236, -9.643405 -IMU2, 116891, -0.03016887, 0.06929269, 0.1203969, -0.3627322, 0.3883885, -9.61189 -IMU, 116910, -0.01434217, 0.05738731, 0.1194864, -0.3266249, 0.2652216, -9.729502 -IMU2, 116910, -0.0133842, 0.06569894, 0.1272651, -0.3535087, 0.4329015, -9.715868 -IMU, 116930, -0.01309804, 0.0707515, 0.1227214, -0.2762843, 0.1588566, -9.750234 -IMU2, 116930, -0.01543277, 0.07907437, 0.1304825, -0.3183284, 0.3178951, -9.795519 -IMU, 116950, -0.01640927, 0.1042213, 0.1144351, -0.3016173, 0.03998028, -9.931955 -IMU2, 116950, -0.02493755, 0.1063093, 0.1262649, -0.2358489, 0.2238026, -9.861126 -IMU, 116971, -0.02545351, 0.1188257, 0.1025549, -0.1878571, 0.1575403, -9.743476 -IMU2, 116971, -0.02618165, 0.1146114, 0.112643, -0.2094291, 0.3490102, -9.736527 -MAG, 116980, -408, 19, 76, -86, 10, 139, 0, 0, 0 -MAG2, 116980, -269, -64, 254, 0, 0, 0, 0, 0, 0 -CTUN, 116990, 0, 0, 0, 0, 0.21, -0.04, 0.00, 0.00, 0, -6 -ATT, 116990, 0.00, 0.66, 0.00, -0.70, 183.04, 183.04 -RCIN, 116990, 1503, 1504, 1024, 1512, 992, 993, 992, 992 -RCOU, 116991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 116991, -0.02093845, 0.1110106, 0.1006892, -0.1417458, 0.1167948, -9.753437 -IMU2, 116991, -0.02919092, 0.1062185, 0.1100556, -0.1229028, 0.2822288, -9.79158 -IMU, 117010, -0.0257157, 0.1029518, 0.09176763, -0.06620391, 0.1070635, -9.665768 -IMU2, 117010, -0.02339575, 0.1083495, 0.1058979, -0.06645977, 0.2372344, -9.722922 -IMU, 117030, -0.03550876, 0.09912993, 0.07546505, -0.1225603, -0.04738632, -9.780321 -IMU2, 117030, -0.03614217, 0.1049322, 0.08065376, -0.1870347, 0.104303, -9.80204 -IMU, 117050, -0.06081738, 0.09330483, 0.05491823, -0.1062876, 0.09384881, -9.775389 -IMU2, 117050, -0.06459036, 0.08321033, 0.05372472, -0.1441851, 0.2619226, -9.753411 -GPS, 3, 56697200, 1777, 10, 1.44, 14.1105714, 100.619232, 0.20, -0.15, 0.93, 292.68, -0.55, 117060 -IMU, 117071, -0.07585202, 0.07928058, 0.04290515, -0.2037199, 0.2513373, -9.72442 -IMU2, 117071, -0.07456967, 0.07071021, 0.04139363, -0.2397164, 0.3643205, -9.754216 -MAG, 117081, -408, 23, 73, -86, 10, 139, 0, 0, 0 -MAG2, 117081, -271, -62, 250, 0, 0, 0, 0, 0, 0 -CTUN, 117090, 0, 0, 0, 0, 0.19, -0.13, 0.00, 0.00, 0, -7 -ATT, 117090, 0.00, 0.40, 0.00, -0.18, 183.38, 183.38 -RCIN, 117090, 1503, 1504, 1025, 1513, 992, 992, 993, 991 -RCOU, 117090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117090, -0.08245774, 0.06120326, 0.03091223, -0.07824671, 0.2154339, -9.732973 -IMU2, 117090, -0.077682, 0.05447542, 0.03007675, -0.07493126, 0.3640894, -9.8044 -IMU, 117110, -0.06949358, 0.03955791, 0.01619016, -0.001769438, 0.1013711, -9.759501 -IMU2, 117110, -0.06495633, 0.04055288, 0.01607258, -0.1285, 0.2579626, -9.801716 -IMU, 117130, -0.05243329, 0.008609209, 0.0062338, 0.02395079, 0.2446147, -9.723518 -IMU2, 117130, -0.05096428, 0.004686844, 0.005570011, -0.06389534, 0.3904901, -9.760997 -IMU, 117150, -0.03837316, -0.01392576, 0.003893062, -0.03728826, 0.4036737, -9.846715 -IMU2, 117150, -0.03966792, -0.01422605, 0.006073729, -0.1541001, 0.528348, -9.810584 -IMU, 117171, -0.04176461, -0.01626013, -0.003576415, -0.04082234, 0.3147911, -9.901887 -IMU2, 117171, -0.04732361, -0.01337431, -0.007055567, -0.06004298, 0.3945162, -9.906599 -MAG, 117180, -410, 23, 71, -86, 10, 139, 0, 0, 0 -MAG2, 117180, -271, -61, 249, 0, 0, 0, 0, 0, 0 -CTUN, 117190, 0, 0, 0, 0, 0.17, -0.24, 0.00, 0.00, 0, -7 -ATT, 117190, 0.00, 0.13, 0.00, -0.23, 183.40, 183.40 -RCIN, 117190, 1503, 1504, 1024, 1511, 993, 992, 992, 992 -RCOU, 117191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117191, -0.04444544, -0.01436562, -0.0182518, -0.008383885, 0.2632056, -9.895354 -IMU2, 117191, -0.04230009, -0.01239261, -0.02424458, -0.003419638, 0.374398, -9.926292 -IMU, 117211, -0.03847518, -0.02567658, -0.02942085, 0.02129512, 0.41841, -9.815163 -IMU2, 117211, -0.04607527, -0.02564985, -0.03219263, -0.02982008, 0.5480752, -9.776895 -IMU, 117231, -0.02501072, -0.03528861, -0.03424976, -0.08809042, 0.4505571, -9.760715 -IMU2, 117231, -0.03685334, -0.03513128, -0.03703337, -0.1049894, 0.5490811, -9.800944 -IMU, 117251, -0.02263357, -0.02767121, -0.0468214, -0.1422769, 0.329169, -9.805989 -IMU2, 117251, -0.02929503, -0.0247331, -0.04455423, -0.1879686, 0.47364, -9.897201 -GPS, 3, 56697400, 1777, 10, 1.44, 14.1105721, 100.6192328, 0.14, 0.14, 0.99, 292.68, -0.52, 117260 -IMU, 117271, -0.02356184, -0.005963281, -0.06032375, -0.02368349, 0.224813, -9.884753 -IMU2, 117271, -0.01645371, 0.00118289, -0.06123804, -0.04820538, 0.4171413, -9.909933 -MAG, 117280, -409, 22, 72, -86, 10, 139, 0, 0, 0 -MAG2, 117280, -272, -61, 248, 0, 0, 0, 0, 0, 0 -CTUN, 117290, 0, 0, 0, 0, 0.14, -0.10, 0.00, 0.00, 0, -7 -ATT, 117290, 0.00, 0.00, 0.00, -0.39, 183.15, 183.15 -RCIN, 117290, 1503, 1504, 1025, 1512, 992, 992, 993, 992 -RCOU, 117290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117291, -0.02493996, 0.01365298, -0.06464987, -0.04588169, 0.361598, -9.82 -IMU2, 117291, -0.02128894, 0.01799068, -0.0635044, -0.0570991, 0.5218568, -9.854136 -IMU, 117311, -0.03093101, 0.02795317, -0.06750774, -0.1423792, 0.3492673, -9.68103 -IMU2, 117311, -0.03875658, 0.02796199, -0.05711748, -0.1500553, 0.510486, -9.79527 -IMU, 117330, -0.03742039, 0.03270713, -0.07609621, -0.1582019, 0.2427923, -9.636387 -IMU2, 117330, -0.04349362, 0.03353019, -0.07234497, -0.1628351, 0.2957759, -9.622797 -IMU, 117350, -0.04010361, 0.02393949, -0.07363725, 0.00632365, 0.3051108, -9.549396 -IMU2, 117350, -0.03779893, 0.02018358, -0.06983713, 0.01528013, 0.4368175, -9.497549 -IMU, 117371, -0.02779602, 0.001423478, -0.06422334, -0.04362363, 0.4100886, -9.611665 -IMU2, 117371, -0.02470981, -0.002311596, -0.05916747, -0.07266819, 0.5682677, -9.693636 -MAG, 117380, -410, 20, 72, -86, 10, 139, 0, 0, 0 -MAG2, 117380, -270, -64, 251, 0, 0, 0, 0, 0, 0 -CTUN, 117390, 0, 0, 0, 0, 0.12, -0.01, 0.00, 0.00, 0, -9 -ATT, 117390, 0.00, -0.20, 0.00, -0.28, 182.77, 182.77 -RCIN, 117390, 1503, 1504, 1025, 1512, 993, 992, 992, 992 -RCOU, 117391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117391, -0.03044801, -0.0205385, -0.05664979, -0.09295537, 0.3488954, -9.631238 -IMU2, 117391, -0.03100515, -0.03516607, -0.05334138, -0.06521249, 0.4654833, -9.675624 -IMU, 117410, -0.03626223, -0.03761911, -0.05869341, -0.08681607, 0.2718317, -9.708946 -IMU2, 117410, -0.05260962, -0.03969115, -0.05505452, -0.1258281, 0.4046412, -9.733184 -IMU, 117430, -0.03935701, -0.05270894, -0.05333196, 0.07218814, 0.4169963, -9.787305 -IMU2, 117430, -0.04046997, -0.0552492, -0.05286962, 0.04627514, 0.5390579, -9.819648 -IMU, 117450, -0.02746166, -0.06376126, -0.04058257, 0.01716058, 0.523329, -9.936768 -IMU2, 117450, -0.03743423, -0.07036601, -0.03703359, 0.0183121, 0.6564106, -9.951926 -GPS, 3, 56697600, 1777, 10, 1.44, 14.110574, 100.6192315, 0.10, 0.14, 1.22, 292.68, -0.46, 117460 -IMU, 117470, -0.02058432, -0.07049303, -0.03385177, 0.02512094, 0.4312539, -9.94559 -IMU2, 117470, -0.03156573, -0.07735404, -0.03446482, 0.01284862, 0.6263483, -9.903705 -MAG, 117481, -408, 18, 73, -86, 10, 139, 0, 0, 0 -MAG2, 117481, -271, -66, 248, 0, 0, 0, 0, 0, 0 -CTUN, 117490, 0, 0, 0, 0, 0.09999999, -0.05, 0.00, 0.00, 0, -9 -ATT, 117490, 0.00, -0.38, 0.00, -0.58, 182.53, 182.53 -RCIN, 117490, 1503, 1504, 1025, 1512, 993, 992, 992, 992 -RCOU, 117491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117491, -0.02264452, -0.07839122, -0.03142375, 0.05089399, 0.5229556, -9.960092 -IMU2, 117491, -0.02769973, -0.07745758, -0.03152798, 0.04543781, 0.7115234, -9.954218 -IMU, 117510, -0.02210565, -0.09269018, -0.02164523, 0.1214809, 0.6793487, -9.778975 -IMU2, 117510, -0.02390922, -0.1015965, -0.01652577, 0.1481426, 0.8103355, -9.887909 -IMU, 117530, 0.0005943254, -0.1003717, -0.00683379, -0.009554386, 0.6045391, -9.820844 -IMU2, 117530, -0.001240583, -0.1024401, -0.0048008, 0.04152524, 0.6877049, -9.811231 -IMU, 117550, 0.01056843, -0.1073745, -0.002467008, -0.06604236, 0.533691, -9.798155 -IMU2, 117550, 0.02238047, -0.1106995, -0.002622208, -0.05014098, 0.6802157, -9.833942 -IMU, 117570, 0.02856555, -0.1178884, 0.000299623, -0.1483808, 0.5149733, -9.672022 -IMU2, 117570, 0.02410585, -0.1273649, 0.0001236429, -0.1095437, 0.5863967, -9.59309 -MAG, 117580, -409, 14, 75, -86, 10, 139, 0, 0, 0 -MAG2, 117580, -270, -68, 250, 0, 0, 0, 0, 0, 0 -CTUN, 117590, 0, 0, 0, 0, 0.08, 0.00, 0.00, 0.00, 0, -9 -ATT, 117591, 0.00, -0.29, 0.00, -1.14, 182.52, 182.52 -RCIN, 117591, 1503, 1504, 1025, 1511, 993, 992, 992, 992 -RCOU, 117591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117591, 0.03967092, -0.1279338, 0.007591167, -0.2090134, 0.585847, -9.669685 -IMU2, 117591, 0.04701026, -0.1345015, 0.008049215, -0.1731597, 0.755468, -9.678996 -IMU, 117610, 0.05001412, -0.1235296, 0.01072866, -0.3784581, 0.4415379, -9.742291 -IMU2, 117610, 0.05751882, -0.1300466, 0.004772284, -0.3945971, 0.5641981, -9.74796 -IMU, 117631, 0.047542, -0.1210654, 0.00910164, -0.3647814, 0.3532028, -9.814203 -IMU2, 117631, 0.05479926, -0.1242523, 0.007867985, -0.364907, 0.5060414, -9.871842 -IMU, 117650, 0.04520031, -0.112832, 0.01363218, -0.4109563, 0.4183363, -9.727365 -IMU2, 117650, 0.04264569, -0.1233033, 0.009399571, -0.3815548, 0.6098298, -9.794961 -GPS, 3, 56697800, 1777, 10, 1.44, 14.1105752, 100.619231, 0.07, 0.36, 1.23, 292.68, -0.47, 117660 -IMU, 117671, 0.04848558, -0.1018538, 0.01825734, -0.46978, 0.4374076, -9.763465 -IMU2, 117671, 0.05266003, -0.1111677, 0.01386907, -0.488475, 0.5722555, -9.805814 -MAG, 117680, -407, 15, 80, -86, 10, 139, 0, 0, 0 -MAG2, 117680, -270, -67, 254, 0, 0, 0, 0, 0, 0 -CTUN, 117690, 0, 0, 0, 0, 0.07, -0.01, 0.00, 0.00, 0, -9 -ATT, 117690, 0.00, 0.00, 0.00, -1.72, 182.63, 182.63 -RCIN, 117690, 1502, 1504, 1026, 1512, 992, 993, 992, 992 -RCOU, 117691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117691, 0.04586201, -0.07763086, 0.01461237, -0.4116467, 0.2163721, -9.684008 -IMU2, 117691, 0.03854356, -0.08418664, 0.005680665, -0.4002373, 0.3369629, -9.619946 -IMU, 117710, 0.03949074, -0.06054238, 0.01092196, -0.3927801, 0.2073742, -9.691479 -IMU2, 117710, 0.02685307, -0.06264491, 0.01239502, -0.3974991, 0.3229737, -9.693765 -IMU, 117730, 0.03868091, -0.045282, 0.01027444, -0.3842472, 0.2334592, -9.65008 -IMU2, 117730, 0.02322498, -0.04372466, 0.00137263, -0.4190927, 0.3774804, -9.71194 -IMU, 117750, 0.03173429, -0.03400413, 0.00252969, -0.5062115, 0.1769472, -9.75001 -IMU2, 117750, 0.0262577, -0.03171613, -0.004278515, -0.5575434, 0.2892452, -9.760246 -IMU, 117771, 0.007650571, -0.03141832, -0.01141114, -0.5056998, 0.1443598, -9.6745 -IMU2, 117771, -0.008236153, -0.03804246, -0.01047271, -0.5124002, 0.3361536, -9.655693 -MAG, 117780, -406, 17, 83, -86, 10, 139, 0, 0, 0 -MAG2, 117780, -268, -66, 258, 0, 0, 0, 0, 0, 0 -CTUN, 117790, 0, 0, 0, 0, 0.05, -0.05, 0.00, 0.00, 0, -10 -ATT, 117791, 0.00, 0.14, 0.00, -1.98, 182.64, 182.64 -RCIN, 117791, 1504, 1504, 1025, 1511, 993, 992, 992, 992 -RCOU, 117791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117791, -0.01221393, -0.03778698, -0.01663449, -0.4687413, 0.2763363, -9.791633 -IMU2, 117791, -0.02947382, -0.0414579, -0.01532654, -0.5138789, 0.4580209, -9.885198 -IMU, 117810, -0.01315474, -0.04368081, -0.01454571, -0.470436, 0.3120265, -9.782681 -IMU2, 117810, -0.03155909, -0.04482481, -0.01540106, -0.4072, 0.535846, -9.864117 -IMU, 117830, -0.01323279, -0.03846147, -0.02052666, -0.4370447, 0.1749167, -9.918552 -IMU2, 117830, -0.02826628, -0.04916193, -0.01930139, -0.4267719, 0.3077537, -9.989121 -GPS, 3, 56698000, 1777, 10, 1.44, 14.1105766, 100.6192317, 0.04, 0.35, 1.02, 292.68, -0.49, 117840 -IMU, 117851, -0.01688864, -0.03492314, -0.02422944, -0.3787388, 0.2633567, -9.904424 -IMU2, 117851, -0.03070118, -0.03826906, -0.02547097, -0.4119968, 0.3679384, -9.884615 -IMU, 117870, -0.0181188, -0.03744674, -0.02062927, -0.408254, 0.4526689, -9.879974 -IMU2, 117870, -0.02681179, -0.04290065, -0.01912717, -0.3733532, 0.6299162, -9.895722 -MAG, 117881, -404, 16, 84, -86, 10, 139, 0, 0, 0 -MAG2, 117881, -267, -67, 257, 0, 0, 0, 0, 0, 0 -CTUN, 117890, 0, 0, 0, 0, 0.04, -0.02, 0.00, 0.00, 0, -10 -DU32, 7, 262745 -CURR, 117890, 0, 0, 1529, 125, 5283, 16.63677 -ATT, 117890, 0.00, 0.03, 0.00, -2.22, 182.54, 182.54 -RCIN, 117890, 1503, 1504, 1025, 1513, 992, 992, 993, 991 -RCOU, 117891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117891, -0.00198541, -0.04696069, -0.02134884, -0.4546933, 0.4107634, -9.970998 -IMU2, 117891, -0.008964859, -0.05198474, -0.02126155, -0.4793274, 0.5370034, -9.94678 -IMU, 117910, 0.01644112, -0.06291922, -0.02543474, -0.4072914, 0.3759084, -10.02783 -IMU2, 117910, 0.003205253, -0.07745913, -0.02978421, -0.4183356, 0.5083942, -10.01198 -IMU, 117930, 0.03485631, -0.08317554, -0.02136862, -0.4055308, 0.5004877, -9.824969 -IMU2, 117930, 0.0359715, -0.0883541, -0.02344617, -0.3511005, 0.6502844, -9.770474 -IMU, 117950, 0.05839092, -0.09442969, -0.01345934, -0.5162552, 0.4379844, -9.704681 -IMU2, 117950, 0.05191392, -0.09621216, -0.01771206, -0.5698719, 0.5550861, -9.720756 -IMU, 117970, 0.07779472, -0.08760075, -0.0182718, -0.4988881, 0.2153152, -9.770504 -IMU2, 117970, 0.06740378, -0.09010039, -0.02631683, -0.4710855, 0.3321123, -9.790085 -MAG, 117980, -405, 15, 85, -86, 10, 139, 0, 0, 0 -MAG2, 117980, -267, -67, 262, 0, 0, 0, 0, 0, 0 -CTUN, 117990, 0, 0, 0, 0, 0.02, -0.12, 0.00, 0.00, 0, -9 -ATT, 117990, 0.00, 0.21, 0.00, -2.69, 182.45, 182.45 -RCIN, 117990, 1504, 1503, 1026, 1512, 992, 992, 993, 992 -RCOU, 117991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 117991, 0.07959608, -0.07818529, -0.01962547, -0.4159826, 0.1504221, -9.750491 -IMU2, 117991, 0.07255781, -0.08838247, -0.01598399, -0.47736, 0.3374972, -9.72333 -IMU, 118010, 0.07570416, -0.0715895, -0.01627858, -0.5234317, 0.2663339, -9.64144 -IMU2, 118010, 0.07298603, -0.07462509, -0.00972244, -0.4342809, 0.4371922, -9.80619 -IMU, 118030, 0.06303816, -0.06882063, -0.02059203, -0.6988841, 0.1661585, -9.750016 -IMU2, 118030, 0.05212268, -0.06248822, -0.02210246, -0.6362548, 0.2811788, -9.759702 -IMU, 118051, 0.03998006, -0.06103485, -0.03383057, -0.6444452, 0.05762066, -9.681142 -IMU2, 118051, 0.02844827, -0.06112605, -0.03700707, -0.6972815, 0.1852878, -9.656788 -GPS, 3, 56698200, 1777, 10, 1.44, 14.1105771, 100.6192307, 0.01, 0.21, 0.89, 292.68, -0.35, 118060 -IMU, 118070, 0.0107778, -0.05803759, -0.03727339, -0.683156, 0.1760196, -9.593516 -IMU2, 118070, -0.001947517, -0.06248464, -0.03589718, -0.5892595, 0.3182831, -9.65955 -MAG, 118081, -404, 14, 89, -86, 10, 139, 0, 0, 0 -MAG2, 118081, -265, -66, 265, 0, 0, 0, 0, 0, 0 -CTUN, 118090, 0, 0, 0, 0, 0, -0.12, 0.00, 0.00, 0, -10 -ATT, 118090, 0.00, 0.37, 0.00, -3.08, 182.30, 182.30 -RCIN, 118090, 1503, 1504, 1026, 1512, 992, 992, 993, 992 -RCOU, 118090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 118090, -0.008140625, -0.05352993, -0.03453452, -0.6930082, 0.2116694, -9.743829 -IMU2, 118090, -0.02078513, -0.0622712, -0.02913642, -0.7286759, 0.2949578, -9.781599 -IMU, 118110, -0.01787397, -0.0403234, -0.04151883, -0.6947161, 0.1053011, -9.792717 -IMU2, 118110, -0.02562324, -0.04258044, -0.04324329, -0.692003, 0.3020397, -9.78549 -IMU, 118130, -0.03297688, -0.03247427, -0.04391371, -0.6527497, 0.2123973, -9.666496 -IMU2, 118130, -0.02668674, -0.03210483, -0.04181741, -0.6733007, 0.4007797, -9.560126 -IMU, 118150, -0.03436286, -0.03481855, -0.03272477, -0.6411967, 0.3477221, -9.748982 -IMU2, 118150, -0.04331817, -0.04794471, -0.02870226, -0.5939569, 0.4822071, -9.712712 -IMU, 118170, -0.01094867, -0.03481741, -0.02647128, -0.6715757, 0.2202929, -9.765799 -IMU2, 118170, -0.01394664, -0.02625813, -0.02486631, -0.6222938, 0.3378042, -9.722919 -MAG, 118180, -405, 14, 91, -86, 10, 139, 0, 0, 0 -MAG2, 118180, -264, -69, 269, 0, 0, 0, 0, 0, 0 -CTUN, 118190, 0, 0, 0, 0, 0, -0.16, 0.00, 0.00, 0, -11 -ATT, 118190, 0.00, 0.30, 0.00, -3.38, 182.11, 182.11 -RCIN, 118190, 1503, 1504, 1027, 1511, 993, 992, 992, 992 -RCOU, 118191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 118191, 0.003716871, -0.03268297, -0.02796047, -0.6004952, 0.2113713, -9.81896 -IMU2, 118191, 5.036592E-06, -0.03514703, -0.02870652, -0.5969143, 0.3307809, -9.821586 -IMU, 118210, 0.008461589, -0.03716719, -0.01971598, -0.5956843, 0.3183894, -9.775168 -IMU2, 118210, -0.006623622, -0.03890967, -0.01966814, -0.6171578, 0.4990432, -9.704137 -EV, 15 -IMU, 118230, 0.01886911, -0.05077928, -0.007437171, -0.6537081, 0.4040784, -9.829169 -IMU2, 118230, 0.002570774, -0.06382611, -0.008247514, -0.601205, 0.54002, -9.748709 -IMU, 118251, 0.02364587, -0.06147926, -0.01107863, -0.456117, 0.2462089, -9.762282 -IMU2, 118251, 0.01439221, -0.07334606, -0.01400589, -0.4638785, 0.4025568, -9.775249 -GPS, 3, 56698400, 1777, 10, 1.44, 14.1105797, 100.6192266, -0.02, 0.23, 1.55, 301.04, -0.29, 118260 -IMU, 118270, 0.02705537, -0.05935871, -0.008481384, -0.7008579, 0.388254, -10.06721 -IMU2, 118270, 0.02494279, -0.05595931, 0.0001205998, -0.6507919, 0.530412, -10.10859 -MAG, 118281, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118281, -256, -71, 247, 0, 0, 0, 0, 0, 0 -CTUN, 118290, 202, 0, 202, 0, -0.02, -0.07, 0.00, 0.00, 0, -10 -ATT, 118290, 0.00, 0.48, 0.00, -3.71, 182.07, 182.07 -RCIN, 118290, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 118291, 1322, 1210, 1303, 1233, 0, 0, 0, 0 -IMU, 118291, 0.03398599, -0.0386472, 0.006943359, -0.9528567, 0.4785241, -10.10479 -IMU2, 118291, 0.03318095, -0.02718784, 0.005025792, -0.9880323, 0.5976744, -10.19705 -IMU, 118311, 0.02729038, 0.006937377, -0.001249405, -1.037256, -0.02327266, -10.14934 -IMU2, 118311, 0.01048926, 0.01411848, -0.00555661, -1.069976, 0.1264081, -10.11006 -IMU, 118330, 0.02314684, 0.04430267, -0.002464815, -0.9947029, 0.08204147, -10.05811 -IMU2, 118330, 0.002607271, 0.04887997, -0.002185052, -1.009635, 0.2365041, -9.905854 -IMU, 118350, 0.007798841, 0.1003018, -0.001262228, -1.320865, -0.06320614, -10.12138 -IMU2, 118350, 0.004571576, 0.1092757, -0.003223399, -1.311403, -0.04328823, -10.16308 -IMU, 118371, -0.07218486, 0.1349631, -0.002145908, -1.067099, 0.2797121, -10.17071 -IMU2, 118371, -0.06537825, 0.1392305, 0.005519991, -1.105784, 0.3730093, -10.07955 -MAG, 118380, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118380, -253, -83, 239, 0, 0, 0, 0, 0, 0 -CTUN, 118390, 202, 0, 202, 0, -0.04, -0.09, 0.00, 0.00, 0, -7 -ATT, 118390, 0.00, 2.56, 0.00, -3.30, 182.07, 182.07 -RCIN, 118390, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 118391, 1286, 1210, 1253, 1255, 0, 0, 0, 0 -IMU, 118391, -0.06540987, 0.1539248, 0.009939826, -1.323405, -0.1232645, -10.1784 -IMU2, 118391, -0.07200199, 0.1463101, 0.01582218, -1.338412, 0.04360986, -10.18717 -IMU, 118410, -0.08688523, 0.1671252, 0.002364935, -0.9637141, 0.1839392, -9.979731 -IMU2, 118410, -0.08284947, 0.1567003, 0.002584099, -0.9244465, 0.3137364, -9.990106 -IMU, 118430, -0.07334684, 0.166354, 0.0207173, -1.042493, -0.186229, -9.77547 -IMU2, 118430, -0.07948069, 0.1687077, 0.01946603, -1.088215, -0.02250695, -9.80652 -IMU, 118451, -0.1112062, 0.1825927, 0.01916965, -0.69665, -0.05407271, -9.966374 -IMU2, 118451, -0.1113861, 0.1823214, 0.02459777, -0.7259262, 0.08736801, -9.960247 -GPS, 3, 56698600, 1777, 10, 1.44, 14.1105819, 100.6192227, -0.04, 0.08, 1.82, 303.96, -0.19, 118460 -IMU, 118470, -0.1606875, 0.172448, 0.03606346, -0.832628, 0.1257562, -10.07914 -IMU2, 118470, -0.1492862, 0.1799493, 0.0456781, -0.8319222, 0.1656041, -10.21806 -MAG, 118481, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118481, -260, -75, 250, 0, 0, 0, 0, 0, 0 -CTUN, 118490, 202, 0, 202, 0, -0.05, 0.04, 0.00, 0.00, 0, -5 -ATT, 118490, 0.00, 4.11, 0.00, -2.47, 182.25, 182.25 -RCIN, 118490, 1503, 1504, 1066, 1512, 992, 992, 993, 992 -RCOU, 118490, 1264, 1210, 1263, 1244, 0, 0, 0, 0 -IMU, 118490, -0.2169756, 0.1628079, 0.04685889, -0.3957147, 0.3873013, -9.897372 -IMU2, 118490, -0.2113275, 0.1525738, 0.05111823, -0.3154706, 0.5622334, -9.969704 -IMU, 118511, -0.2160548, 0.1278497, 0.0747397, -0.4559729, 0.0384578, -9.795688 -IMU2, 118511, -0.2188382, 0.1271609, 0.08474448, -0.4893156, 0.1701447, -9.888566 -IMU, 118530, -0.2197219, 0.09475452, 0.07198795, -0.06205222, -0.05085391, -9.847742 -IMU2, 118530, -0.2489389, 0.0848822, 0.0740412, 0.01311004, 0.2881244, -9.63337 -IMU, 118550, -0.2167003, 0.05589218, 0.0927169, -0.2547595, 0.4496791, -9.927505 -IMU2, 118550, -0.2176674, 0.05380568, 0.1050791, -0.2951083, 0.5525925, -10.06411 -IMU, 118571, -0.2642899, 0.01049513, 0.08917286, 0.1398289, 0.8098478, -10.08505 -IMU2, 118571, -0.2600517, 0.01113816, 0.09854006, 0.2053413, 0.9813327, -10.15137 -MAG, 118580, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118580, -260, -77, 243, 0, 0, 0, 0, 0, 0 -CTUN, 118590, 201, 0, 200, 0, -0.05, 0.03, 0.00, 0.00, 0, -4 -ATT, 118590, 0.00, 5.10, 0.00, -2.28, 182.75, 182.75 -RCIN, 118590, 1503, 1504, 1065, 1512, 992, 993, 992, 992 -RCOU, 118591, 1387, 1210, 1354, 1318, 0, 0, 0, 0 -IMU, 118591, -0.2357778, -0.03303306, 0.1300951, -0.2158858, 0.2542732, -9.829878 -IMU2, 118591, -0.2484834, -0.03488629, 0.1267154, -0.2171656, 0.3884978, -9.76165 -IMU, 118610, -0.2231407, -0.07716035, 0.1322046, -0.128782, 1.210932, -9.473305 -IMU2, 118610, -0.1923283, -0.07325159, 0.1453949, -0.08474064, 1.351868, -9.688465 -IMU, 118630, -0.1713338, -0.08998117, 0.1576418, -0.198891, 0.03678915, -9.519857 -IMU2, 118630, -0.2018903, -0.09083791, 0.1583914, -0.2492086, 0.2430803, -9.334386 -GPS, 3, 56698800, 1777, 11, 1.42, 14.1105826, 100.6192238, -0.05, 0.08, 1.46, 307.17, -0.08, 118640 -IMU, 118650, -0.158422, -0.09425621, 0.1898917, -0.3883126, 0.7198675, -9.730177 -IMU2, 118650, -0.1404104, -0.09092158, 0.1889785, -0.4885961, 0.6944104, -9.855974 -IMU, 118670, -0.2125846, -0.08701536, 0.1672168, -0.4449133, 0.1348209, -9.611242 -IMU2, 118670, -0.2549534, -0.07500808, 0.1714222, -0.3838622, 0.4038284, -9.510722 -MAG, 118680, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118680, -254, -79, 227, 0, 0, 0, 0, 0, 0 -CTUN, 118690, 202, 0, 202, 0, -0.05, 0.00, 0.00, 0.00, 0, -7 -ATT, 118690, 0.00, 6.18, 0.00, -2.84, 183.58, 183.58 -RCIN, 118690, 1504, 1503, 1066, 1513, 992, 992, 993, 991 -RCOU, 118690, 1383, 1210, 1364, 1334, 0, 0, 0, 0 -IMU, 118690, -0.2432955, -0.0680257, 0.1800602, -0.6423501, 0.2828821, -9.393067 -IMU2, 118690, -0.2628097, -0.05607123, 0.1841595, -0.7851152, 0.3760201, -9.254789 -IMU, 118710, -0.3010362, -0.0368824, 0.1607615, -0.4721855, 1.077112, -9.80226 -IMU2, 118710, -0.3024865, -0.0298221, 0.1679728, -0.3631174, 1.212047, -9.809614 -IMU, 118730, -0.3094987, -0.008985523, 0.1460229, -0.8741884, -0.2433835, -9.72007 -IMU2, 118730, -0.3534991, 0.01315164, 0.1449538, -0.8111903, 0.09964883, -9.613585 -IMU, 118750, -0.3043254, 0.03254157, 0.1636724, -0.8171836, 0.3990003, -9.482764 -IMU2, 118750, -0.3107746, 0.0405957, 0.1637839, -0.9382721, 0.294089, -9.55846 -IMU, 118770, -0.4165696, 0.06815883, 0.1400517, -0.8184342, 1.396707, -9.794366 -IMU2, 118770, -0.4122462, 0.09614363, 0.1603351, -0.6126067, 1.553741, -9.723526 -MAG, 118780, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118780, -260, -72, 245, 0, 0, 0, 0, 0, 0 -CTUN, 118790, 202, 0, 202, 0, -0.06, -0.13, 0.00, 0.00, 0, -9 -ATT, 118790, 0.00, 6.51, 0.00, -2.79, 184.35, 184.35 -RCIN, 118790, 1503, 1504, 1066, 1513, 992, 992, 992, 992 -RCOU, 118791, 1279, 1210, 1301, 1268, 0, 0, 0, 0 -IMU, 118791, -0.4682251, 0.1047058, 0.1251846, -0.5601153, 0.3953825, -9.172825 -IMU2, 118791, -0.4728242, 0.1023096, 0.1368871, -0.6918441, 0.5611329, -9.230287 -IMU, 118810, -0.4286012, 0.1097233, 0.1295279, -0.7129802, 1.11857, -9.955308 -IMU2, 118810, -0.4427958, 0.1214808, 0.1293952, -0.6852532, 1.169596, -9.880804 -IMU, 118831, -0.4510812, 0.1124856, 0.1180552, -0.4538409, 1.929393, -9.807808 -IMU2, 118831, -0.4238749, 0.1223344, 0.1328439, -0.3136856, 2.134554, -9.917916 -GPS, 3, 56699000, 1777, 11, 1.42, 14.1105829, 100.6192236, -0.06, 0.10, 1.10, 307.17, -0.11, 118840 -IMU, 118851, -0.4180443, 0.101213, 0.1165914, -0.531862, 0.3838805, -9.795286 -IMU2, 118851, -0.434184, 0.1103285, 0.1288452, -0.6046762, 0.6913913, -9.968926 -IMU, 118870, -0.3715342, 0.1103421, 0.1311039, -0.07613908, 1.594135, -9.623027 -IMU2, 118870, -0.379968, 0.1227036, 0.1418901, 0.06686687, 1.494065, -9.500364 -MAG, 118881, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118881, -262, -69, 247, 0, 0, 0, 0, 0, 0 -CTUN, 118890, 202, 0, 202, 0, -0.07, 0.03, 0.00, 0.00, 0, -11 -DU32, 7, 262777 -CURR, 118890, 202, 1412, 1526, 604, 5307, 18.26205 -ATT, 118891, 0.00, 6.46, 0.00, -2.39, 185.03, 185.03 -RCIN, 118891, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 118891, 1364, 1210, 1334, 1324, 0, 0, 0, 0 -IMU, 118891, -0.4099984, 0.08547246, 0.1319816, 0.1754799, 2.480813, -9.57228 -IMU2, 118891, -0.3643107, 0.09202133, 0.1529924, 0.1482137, 2.665481, -9.83928 -IMU, 118910, -0.4074506, 0.08994018, 0.122778, 0.1743392, 1.240438, -9.883668 -IMU2, 118910, -0.4255405, 0.08958031, 0.1370942, 0.3605186, 1.487356, -9.620042 -IMU, 118930, -0.3263507, 0.05107959, 0.1475869, 0.239891, 1.408366, -9.73796 -IMU2, 118930, -0.3511946, 0.05590354, 0.141542, 0.05821002, 1.358021, -9.729156 -IMU, 118950, -0.4024594, 0.02636492, 0.1481558, 0.2461585, 2.644836, -9.93103 -IMU2, 118950, -0.375345, 0.0392293, 0.1531206, 0.3570023, 2.812225, -10.05665 -IMU, 118970, -0.4563733, -0.04435765, 0.1390601, 0.3407898, 1.391072, -9.498364 -IMU2, 118970, -0.4958405, -0.04772064, 0.1464201, 0.2626339, 1.62189, -9.479417 -MAG, 118980, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 118980, -261, -71, 240, 0, 0, 0, 0, 0, 0 -CTUN, 118990, 202, 0, 202, 0, -0.08, 0.03, 0.00, 0.00, 0, -15 -ATT, 118990, 0.00, 6.53, 0.00, -2.48, 185.75, 185.75 -RCIN, 118990, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 118991, 1463, 1210, 1416, 1346, 0, 0, 0, 0 -IMU, 118991, -0.4276682, -0.1029291, 0.1437516, 0.2884077, 1.868155, -9.183166 -IMU2, 118991, -0.435733, -0.1074487, 0.1425554, 0.2843395, 1.857334, -9.188185 -IMU, 119010, -0.4403501, -0.1660073, 0.1117482, 0.2509333, 3.115346, -9.374969 -IMU2, 119010, -0.3949756, -0.187895, 0.123071, 0.2070202, 3.270288, -9.435873 -IMU, 119030, -0.3979405, -0.1971139, 0.08154722, -0.3097227, 1.824151, -9.589874 -IMU2, 119030, -0.4181914, -0.1943986, 0.08353786, -0.2098451, 2.095149, -9.336564 -IMU, 119050, -0.2766182, -0.2125002, 0.09570478, -0.3020373, 1.84631, -9.457026 -IMU2, 119050, -0.2985046, -0.2122837, 0.08832627, -0.4705554, 1.833985, -9.417267 -EV, 28 -GPS, 3, 56699200, 1777, 11, 1.42, 14.1105836, 100.6192221, -0.09, 0.07, 1.11, 307.17, -0.04, 119060 -IMU, 119071, -0.2520892, -0.1889026, 0.0978979, -0.5420339, 3.16864, -9.846885 -IMU2, 119071, -0.2235125, -0.1881595, 0.09912903, -0.4108674, 3.052377, -9.740399 -MAG, 119080, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119080, -256, -76, 234, 0, 0, 0, 0, 0, 0 -CTUN, 119090, 202, 0, 202, 0, -0.09, -0.17, 0.00, 0.00, 0, -21 -ATT, 119090, 0.00, 6.98, 0.00, -3.56, 186.03, 186.16 -RCIN, 119090, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119090, 1478, 1210, 1407, 1356, 0, 0, 0, 0 -IMU, 119090, -0.2897203, -0.1702886, 0.08978014, -0.9169019, 3.094676, -9.770012 -IMU2, 119090, -0.2663072, -0.1484475, 0.09454093, -0.9747418, 3.445683, -10.04036 -IMU, 119110, -0.2407556, -0.09021489, 0.0764164, -0.7475848, 2.013383, -9.117608 -IMU2, 119110, -0.2633222, -0.08853097, 0.07397582, -0.6981844, 2.17765, -9.226692 -IMU, 119130, -0.1653782, -0.01356022, 0.07096943, -0.8722744, 2.000268, -9.314461 -IMU2, 119130, -0.1876131, -0.001407674, 0.06442894, -0.9897802, 2.006256, -9.09088 -IMU, 119150, -0.1574522, 0.04735005, 0.05587002, -1.032238, 2.857754, -9.34001 -IMU2, 119150, -0.1455583, 0.04654883, 0.06560416, -0.9484904, 2.792143, -9.258422 -IMU, 119170, -0.2454779, 0.06279606, 0.03926987, -1.340649, 3.05815, -9.725466 -IMU2, 119170, -0.2240837, 0.07971562, 0.05379732, -1.203271, 3.369605, -9.917611 -MAG, 119180, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119180, -256, -76, 244, 0, 0, 0, 0, 0, 0 -CTUN, 119190, 202, 0, 202, 0, -0.12, 0.00, 0.00, 0.00, 0, -27 -ATT, 119190, 0.00, 8.08, 0.00, -3.52, 186.03, 186.44 -RCIN, 119190, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119191, 1444, 1210, 1338, 1383, 0, 0, 0, 0 -IMU, 119191, -0.2343841, 0.08676866, 0.03686884, -0.9089888, 1.768498, -8.97308 -IMU2, 119191, -0.2676366, 0.08839311, 0.03568914, -0.894895, 2.295817, -9.033433 -IMU, 119210, -0.1959882, 0.1161867, 0.04809744, -0.8975713, 2.005819, -9.11454 -IMU2, 119210, -0.2016709, 0.1243288, 0.05773201, -0.8023547, 2.073873, -9.065223 -IMU, 119230, -0.1927397, 0.1202815, 0.0603223, -0.7953458, 2.809923, -9.382029 -IMU2, 119230, -0.1820576, 0.1222801, 0.07960672, -0.6893929, 2.832889, -9.289086 -GPS, 3, 56699400, 1777, 11, 1.42, 14.110584, 100.6192204, -0.14, 0.10, 1.03, 307.17, -0.04, 119240 -IMU, 119250, -0.2315916, 0.1320013, 0.06094199, -0.6484291, 2.820742, -9.766487 -IMU2, 119250, -0.22977, 0.1319776, 0.08434717, -0.4600974, 3.092257, -9.918737 -IMU, 119270, -0.2315625, 0.1506424, 0.06869174, -0.3655645, 2.028634, -9.597137 -IMU2, 119270, -0.2557053, 0.147191, 0.08508576, -0.2272575, 2.215578, -9.424739 -MAG, 119280, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119281, -259, -74, 245, 0, 0, 0, 0, 0, 0 -CTUN, 119290, 202, 0, 202, 0, -0.15, -0.12, 0.00, 0.00, 0, -35 -ATT, 119290, 0.00, 9.08, 0.00, -2.96, 186.03, 186.87 -RCIN, 119290, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119290, 1489, 1210, 1337, 1459, 0, 0, 0, 0 -IMU, 119291, -0.2019687, 0.1426211, 0.08179177, -0.4320335, 2.242506, -9.706777 -IMU2, 119291, -0.2062442, 0.1468407, 0.08286227, -0.3587084, 2.257863, -9.693668 -IMU, 119310, -0.2281521, 0.1079045, 0.08194569, -0.128037, 3.206855, -9.572418 -IMU2, 119310, -0.2132929, 0.1100349, 0.09545151, -0.04688466, 3.280793, -9.730561 -IMU, 119330, -0.262158, 0.0777685, 0.07718788, 0.3672464, 2.853306, -9.697316 -IMU2, 119330, -0.2780896, 0.07652034, 0.08214945, 0.3469414, 3.203526, -9.737006 -IMU, 119350, -0.1996458, 0.07094192, 0.08863204, 0.7932507, 2.21679, -9.323524 -IMU2, 119350, -0.2375949, 0.05557616, 0.09174942, 0.7514626, 2.405096, -9.186548 -IMU, 119370, -0.1532346, 0.0419616, 0.09332203, 0.5418528, 2.921175, -9.243025 -IMU2, 119370, -0.1463836, 0.05057464, 0.09483131, 0.5636595, 2.749245, -9.329206 -MAG, 119380, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119380, -261, -74, 242, 0, 0, 0, 0, 0, 0 -CTUN, 119391, 202, 0, 202, 0, -0.19, 0.02, 0.00, 0.00, 0, -44 -ATT, 119391, 0.00, 10.20, 0.00, -2.77, 186.03, 187.31 -RCIN, 119391, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119392, 1499, 1210, 1361, 1426, 0, 0, 0, 0 -IMU, 119392, -0.1670006, -0.01950363, 0.0451951, 0.3546614, 3.280995, -9.122807 -IMU2, 119392, -0.1511238, -0.02333594, 0.04799, 0.4395977, 3.57053, -9.242687 -IMU, 119411, -0.1380568, -0.09719022, -0.001216226, 0.4124074, 2.183599, -8.625597 -IMU2, 119411, -0.1543782, -0.1165249, -0.01441146, 0.3871284, 2.471555, -8.613132 -IMU, 119430, -0.03429425, -0.1753741, -0.03422541, 0.1536917, 2.084798, -8.666061 -IMU2, 119430, -0.04048555, -0.1843706, -0.05341269, 0.1308124, 2.105969, -8.549107 -GPS, 3, 56699600, 1777, 11, 1.42, 14.1105866, 100.6192165, -0.21, -0.28, 1.17, 307.17, 0.08, 119440 -IMU, 119451, -0.009923989, -0.2366466, -0.07622971, 0.1215331, 3.146125, -8.862097 -IMU2, 119451, 0.02531778, -0.2431809, -0.08283079, 0.09173191, 3.176734, -9.023492 -IMU, 119470, -0.03421821, -0.2795731, -0.1340466, -0.02660677, 2.804479, -8.499823 -IMU2, 119470, -0.02939915, -0.2816647, -0.1446151, -0.1858906, 3.134392, -8.545085 -MAG, 119480, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119480, -259, -76, 239, 0, 0, 0, 0, 0, 0 -CTUN, 119490, 202, 0, 202, 0, -0.23, 0.00, 0.00, 0.00, 0, -60 -ATT, 119490, 0.00, 12.11, 0.00, -3.80, 186.03, 186.69 -RCIN, 119490, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119490, 1537, 1210, 1343, 1405, 0, 0, 0, 0 -IMU, 119490, -0.002463268, -0.2648776, -0.1680748, -0.06470348, 2.105048, -8.715077 -IMU2, 119490, -0.0142162, -0.2726793, -0.1812559, -0.2025534, 2.158141, -8.733257 -IMU, 119510, 0.006114645, -0.2224153, -0.1811519, -0.08423011, 3.226242, -8.967216 -IMU2, 119510, 0.02889549, -0.227476, -0.1917707, -0.1145141, 3.109101, -9.049902 -IMU, 119530, -0.05675416, -0.1705665, -0.2046513, -0.3788742, 3.419989, -9.303217 -IMU2, 119530, -0.03744776, -0.1666489, -0.2052555, -0.3121302, 3.593485, -9.630672 -IMU, 119550, -0.0601842, -0.09742042, -0.2119114, -0.5828596, 1.975758, -9.08941 -IMU2, 119550, -0.07685566, -0.09654772, -0.2148437, -0.6119055, 2.224029, -9.170494 -IMU, 119571, -0.0335785, -0.02184608, -0.2032692, -0.9963188, 2.287694, -9.31612 -IMU2, 119571, -0.04423216, -0.01395833, -0.2023423, -0.9639723, 2.260546, -9.29189 -MAG, 119580, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119580, -255, -83, 246, 0, 0, 0, 0, 0, 0 -CTUN, 119591, 202, 0, 202, 0, -0.29, 0.03, 0.00, 0.00, 0, -73 -ATT, 119591, 0.00, 14.13, 0.00, -4.09, 186.03, 185.53 -RCIN, 119591, 1504, 1504, 1066, 1511, 992, 993, 992, 992 -RCOU, 119591, 1548, 1210, 1276, 1457, 0, 0, 0, 0 -IMU, 119591, -0.0845401, 0.04177494, -0.1961038, -0.9870998, 3.151103, -9.436042 -IMU2, 119591, -0.06783731, 0.04428921, -0.184929, -0.9064037, 3.195209, -9.533559 -IMU, 119610, -0.1343863, 0.09063478, -0.1793662, -0.9030228, 2.478764, -9.356245 -IMU2, 119610, -0.1449468, 0.09406084, -0.1672562, -0.9828818, 2.772914, -9.396649 -IMU, 119630, -0.1162961, 0.1458064, -0.1315888, -0.7949084, 2.203629, -9.370528 -IMU2, 119630, -0.1105725, 0.1468993, -0.1253329, -0.8105406, 2.252659, -9.288188 -GPS, 3, 56699800, 1777, 11, 1.42, 14.1105885, 100.619215, -0.33, -0.62, 0.94, 307.17, 0.14, 119640 -IMU, 119650, -0.1713091, 0.1603958, -0.09907939, -0.7095855, 3.153898, -9.378579 -IMU2, 119650, -0.1509508, 0.1595969, -0.08897945, -0.7315977, 3.242734, -9.345186 -IMU, 119670, -0.27791, 0.1542275, -0.08514893, -0.8693259, 2.504196, -9.578992 -IMU2, 119670, -0.297209, 0.1626731, -0.07656703, -0.7756819, 3.056719, -9.716364 -MAG, 119680, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119680, -255, -91, 246, 0, 0, 0, 0, 0, 0 -CTUN, 119690, 202, 0, 202, 0, -0.36, 0.04, 0.00, 0.00, 0, -83 -ATT, 119690, 0.00, 15.22, 0.00, -3.25, 186.03, 185.17 -RCIN, 119690, 1503, 1504, 1066, 1511, 992, 993, 992, 992 -RCOU, 119690, 1532, 1210, 1288, 1465, 0, 0, 0, 0 -IMU, 119691, -0.2676858, 0.1624656, -0.03008487, -0.7565838, 2.17811, -9.52882 -IMU2, 119691, -0.2931348, 0.1548958, -0.02060319, -0.6985639, 2.301318, -9.449127 -IMU, 119710, -0.2793009, 0.1480428, 0.01742723, -0.4937752, 3.30352, -9.86775 -IMU2, 119710, -0.276462, 0.147003, 0.04271581, -0.3550129, 3.349786, -9.684479 -IMU, 119730, -0.3307035, 0.1094409, 0.04397395, -0.4867455, 2.789915, -9.814205 -IMU2, 119730, -0.3749399, 0.1152852, 0.06653135, -0.2824887, 3.260788, -9.591096 -IMU, 119750, -0.256574, 0.07201942, 0.09413126, -0.3108466, 2.334052, -9.57257 -IMU2, 119750, -0.2960475, 0.06475979, 0.1070908, -0.2266498, 2.41239, -9.453025 -IMU, 119770, -0.251307, 0.01413244, 0.1408956, 0.06267601, 3.774523, -9.303348 -IMU2, 119770, -0.240624, 0.002920764, 0.1608023, 0.1307601, 3.737036, -9.264937 -MAG, 119780, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119780, -259, -93, 246, 0, 0, 0, 0, 0, 0 -CTUN, 119790, 202, 0, 201, 0, -0.43, 0.09, 0.00, 0.00, 0, -96 -ATT, 119790, 0.00, 15.87, 0.00, -3.10, 186.03, 185.72 -RCIN, 119790, 1504, 1503, 1066, 1513, 992, 992, 993, 991 -RCOU, 119791, 1502, 1210, 1355, 1429, 0, 0, 0, 0 -IMU, 119791, -0.309848, -0.05330262, 0.1501404, -0.09818852, 3.174734, -9.300912 -IMU2, 119791, -0.3305766, -0.06032126, 0.1567205, -0.08447087, 3.552945, -9.356819 -IMU, 119810, -0.2618478, -0.09284739, 0.1696511, -0.09549439, 2.97256, -9.155827 -IMU2, 119810, -0.2699142, -0.1018425, 0.1630897, -0.1282798, 3.087567, -9.135202 -IMU, 119830, -0.2782252, -0.1071113, 0.1683292, 0.4278515, 4.590294, -9.458721 -IMU2, 119830, -0.2600386, -0.1145023, 0.1709101, 0.5715438, 4.631788, -9.445458 -GPS, 3, 56700000, 1777, 11, 1.42, 14.11059, 100.619212, -0.48, -0.78, 0.98, 307.17, 0.18, 119840 -IMU, 119850, -0.3229777, -0.1261341, 0.1349486, 0.1678581, 3.676726, -9.421895 -IMU2, 119850, -0.3426124, -0.1182779, 0.1401896, 0.249154, 4.163916, -9.386766 -IMU, 119870, -0.2395494, -0.1431008, 0.1201035, -0.3843271, 3.133654, -8.951303 -IMU2, 119870, -0.2585889, -0.1380615, 0.1140879, -0.3859382, 3.277136, -8.882263 -MAG, 119880, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119880, -259, -90, 246, 0, 0, 0, 0, 0, 0 -PM, 16, 16, 5, 1000, 10698, 10, 0, 0, 0 -CTUN, 119890, 202, 0, 202, 0, -0.52, -0.04, 0.00, 0.00, 0, -115 -DU32, 7, 262265 -CURR, 119890, 202, 3431, 1528, 707, 5267, 20.55008 -ATT, 119890, 0.00, 16.62, 0.00, -4.01, 186.03, 186.19 -RCIN, 119890, 1503, 1504, 1066, 1512, 993, 992, 992, 992 -RCOU, 119891, 1508, 1210, 1344, 1435, 0, 0, 0, 0 -IMU, 119891, -0.1810892, -0.1774186, 0.07979792, -0.1536832, 4.49776, -8.99227 -IMU2, 119891, -0.1647751, -0.1809488, 0.07601518, -0.1640042, 4.563289, -8.899393 -IMU, 119910, -0.1611137, -0.2189192, 0.02563305, -0.226642, 3.678396, -9.065203 -IMU2, 119910, -0.1813801, -0.2249118, 0.0164459, -0.2572886, 4.08982, -9.075308 -IMU, 119930, -0.04692656, -0.2442994, -0.01298489, -0.4857887, 3.062824, -8.607371 -IMU2, 119930, -0.06902619, -0.2471138, -0.03343199, -0.6609592, 3.180787, -8.577071 -IMU, 119950, -0.01307065, -0.2592671, -0.06439098, -0.1260458, 4.224293, -8.628184 -IMU2, 119950, 0.00491358, -0.2686563, -0.07764178, -0.2134312, 4.244638, -8.743273 -IMU, 119971, -0.04116452, -0.2626238, -0.1350489, -0.3303271, 3.645131, -8.706758 -IMU2, 119971, -0.03993414, -0.2569734, -0.1504531, -0.3618603, 4.031707, -8.865118 -MAG, 119980, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 119980, -257, -93, 251, 0, 0, 0, 0, 0, 0 -CTUN, 119990, 202, 0, 202, 0, -0.63, -0.04, 0.00, 0.00, 0, -141 -ATT, 119991, 0.00, 18.62, 0.00, -5.17, 186.03, 185.50 -RCIN, 119991, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 119991, 1534, 1210, 1319, 1430, 0, 0, 0, 0 -IMU, 119991, 0.008764882, -0.225984, -0.1692296, -0.3143525, 3.38761, -8.767689 -IMU2, 119991, -0.0001407228, -0.2331486, -0.1845192, -0.4170032, 3.435771, -8.722379 -IMU, 120011, 0.01063902, -0.1809574, -0.2036481, -0.4163826, 4.613874, -8.78567 -IMU2, 120011, 0.02963783, -0.1908092, -0.2120717, -0.3894365, 4.58532, -8.78884 -IMU, 120030, -0.02776724, -0.1480426, -0.2558784, -1.015053, 3.810076, -9.063055 -IMU2, 120030, -0.03445064, -0.1452911, -0.2569553, -0.9447073, 4.247834, -9.135535 -IMU, 120050, 0.03668275, -0.09218018, -0.2706695, -1.430536, 3.166366, -9.218024 -IMU2, 120050, 0.02381117, -0.09211299, -0.2727316, -1.411404, 3.342912, -9.091483 -IMU, 120070, 0.05707563, -0.03915593, -0.2749674, -1.309967, 4.220933, -9.538876 -IMU2, 120070, 0.07746215, -0.03556827, -0.2684767, -1.263387, 4.234675, -9.54988 -MAG, 120081, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120081, -253, -102, 258, 0, 0, 0, 0, 0, 0 -CTUN, 120090, 201, 0, 201, 0, -0.76, -0.10, 0.00, 0.00, 0, -165 -ATT, 120090, 0.00, 21.09, 0.00, -5.24, 186.03, 184.05 -RCIN, 120090, 1503, 1504, 1065, 1513, 992, 992, 993, 991 -RCOU, 120090, 1553, 1210, 1273, 1454, 0, 0, 0, 0 -IMU, 120090, 0.00264637, 0.008891478, -0.2828599, -1.60996, 3.689288, -9.594251 -IMU2, 120090, -0.01160094, 0.0207611, -0.2705281, -1.575302, 4.162926, -9.581481 -GPS, 3, 56700200, 1777, 11, 1.42, 14.1105891, 100.6192145, -0.79, -0.84, 0.49, 307.17, 0.13, 120101 -IMU, 120110, 0.04883865, 0.07833122, -0.2560704, -1.791067, 2.836312, -9.376728 -IMU2, 120110, 0.02721054, 0.08470003, -0.2486287, -1.820895, 3.027126, -9.407296 -IMU, 120130, 0.04215055, 0.1342326, -0.221415, -1.459522, 4.069212, -9.34154 -IMU2, 120130, 0.06934749, 0.1285722, -0.2052436, -1.350196, 4.159807, -9.465903 -IMU, 120150, -0.03761741, 0.1585873, -0.1980998, -1.253591, 3.678154, -9.474014 -IMU2, 120150, -0.04133844, 0.1620792, -0.187447, -1.229594, 4.070811, -9.533333 -IMU, 120170, -0.01798484, 0.1679712, -0.1345442, -1.310941, 3.256077, -9.454223 -IMU2, 120170, -0.02834449, 0.1571481, -0.1282914, -1.286139, 3.415406, -9.353833 -MAG, 120180, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120180, -252, -109, 256, 0, 0, 0, 0, 0, 0 -CTUN, 120190, 202, 1, 203, 0, -0.92, -0.02, 0.00, 0.00, 0, -188 -ATT, 120191, 0.00, 23.02, 0.00, -4.33, 186.03, 183.46 -RCIN, 120191, 1503, 1504, 1066, 1511, 992, 993, 992, 992 -RCOU, 120191, 1540, 1210, 1270, 1477, 0, 0, 0, 0 -IMU, 120191, -0.03629004, 0.1600097, -0.07471896, -0.9863584, 4.400149, -9.621876 -IMU2, 120191, -0.0186455, 0.1548074, -0.055677, -0.816074, 4.532917, -9.694745 -IMU, 120210, -0.07015243, 0.1442474, -0.02736456, -1.149039, 3.370494, -9.616851 -IMU2, 120210, -0.07997636, 0.1448228, -0.01364862, -0.9478832, 3.785423, -9.541195 -IMU, 120230, -0.02784111, 0.1421565, 0.06008138, -1.212528, 3.252415, -9.459556 -IMU2, 120230, -0.05224872, 0.1360761, 0.08107372, -1.074138, 3.381291, -9.458743 -GPS, 3, 56700400, 1777, 11, 1.42, 14.1105883, 100.6192166, -1.01, -0.94, 0.56, 307.17, 0.09999999, 120240 -IMU, 120250, -0.08358483, 0.1132378, 0.09841555, -0.9359732, 4.489856, -9.184659 -IMU2, 120250, -0.06966282, 0.1038307, 0.1255426, -0.8020713, 4.606156, -9.278159 -IMU, 120270, -0.1085968, 0.05564114, 0.1285644, -1.058752, 3.224495, -8.966753 -IMU2, 120270, -0.1150049, 0.05215879, 0.1458475, -0.9293433, 3.430553, -8.920606 -MAG, 120280, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120280, -255, -110, 253, 0, 0, 0, 0, 0, 0 -CTUN, 120290, 202, 1, 203, 0, -1.08, -0.17, 0.00, 0.00, 0, -213 -ATT, 120290, 0.00, 24.63, 0.00, -4.10, 186.03, 184.07 -RCIN, 120290, 1502, 1504, 1066, 1512, 992, 992, 993, 992 -RCOU, 120291, 1514, 1210, 1311, 1466, 0, 0, 0, 0 -IMU, 120291, -0.07948279, 0.01511034, 0.1837469, -0.7818945, 3.666495, -9.001183 -IMU2, 120291, -0.08306594, 0.01891066, 0.1955691, -0.7393214, 3.714378, -9.009679 -IMU, 120310, -0.1400929, 0.01049034, 0.2001879, -0.2400384, 4.071182, -9.029075 -IMU2, 120310, -0.1338892, 0.01967314, 0.2090776, -0.1631869, 4.290131, -8.986259 -IMU, 120331, -0.1400924, -0.00803943, 0.2186282, -0.5546045, 2.994734, -8.709513 -IMU2, 120331, -0.1542384, -0.004181007, 0.2136604, -0.6179429, 3.164016, -8.770059 -IMU, 120350, -0.1511251, -0.05189028, 0.2188569, -0.3223435, 4.021602, -8.413712 -IMU2, 120350, -0.1289314, -0.0533254, 0.2203176, -0.3246886, 4.10219, -8.502306 -IMU, 120371, -0.2242486, -0.08379275, 0.1841487, -0.3020754, 3.61889, -8.651039 -IMU2, 120371, -0.2326652, -0.08462757, 0.1847103, -0.3159428, 3.766922, -8.724155 -MAG, 120380, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120380, -256, -105, 255, 0, 0, 0, 0, 0, 0 -CTUN, 120390, 202, 1, 202, 0, -1.28, 0.03, 0.00, 0.00, 0, -243 -ATT, 120391, 0.00, 25.86, 0.00, -4.76, 186.03, 184.91 -RCIN, 120391, 1503, 1504, 1066, 1512, 993, 992, 992, 992 -RCOU, 120391, 1500, 1210, 1327, 1460, 0, 0, 0, 0 -IMU, 120391, -0.2050032, -0.08137253, 0.181933, -0.658293, 3.02603, -8.67794 -IMU2, 120391, -0.2269951, -0.07722692, 0.1745803, -0.6228746, 3.049584, -8.514411 -IMU, 120410, -0.2477178, -0.0786123, 0.1617779, -0.3651096, 4.617543, -8.744476 -IMU2, 120410, -0.2369459, -0.06726968, 0.1700048, -0.28408, 4.739725, -8.89129 -IMU, 120430, -0.2583203, -0.09091468, 0.1219736, -0.4515053, 3.693974, -8.72478 -IMU2, 120430, -0.2711259, -0.09212637, 0.1175094, -0.4419867, 3.894647, -8.596397 -GPS, 3, 56700600, 1777, 11, 1.42, 14.1105873, 100.6192198, -1.40, -1.06, 0.55, 307.17, 0.13, 120440 -IMU, 120450, -0.1856419, -0.1124511, 0.1190489, -0.662884, 3.67978, -8.547593 -IMU2, 120450, -0.1852227, -0.1138457, 0.1160886, -0.7782387, 3.65681, -8.630177 -IMU, 120470, -0.2159294, -0.1309669, 0.08541235, -0.3396387, 4.704413, -8.56782 -IMU2, 120470, -0.2007868, -0.132875, 0.09280712, -0.3013633, 4.865501, -8.669574 -MAG, 120480, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120480, -255, -101, 254, 0, 0, 0, 0, 0, 0 -CTUN, 120490, 202, 1, 203, 0, -1.49, 0.00, 0.00, 0.00, 0, -277 -ATT, 120490, 0.00, 26.75, 0.00, -5.54, 186.03, 185.19 -RCIN, 120490, 1504, 1503, 1066, 1513, 992, 992, 992, 992 -RCOU, 120490, 1506, 1210, 1336, 1448, 0, 0, 0, 0 -IMU, 120490, -0.1958238, -0.1397841, 0.06616323, -0.4888904, 3.634124, -8.659774 -IMU2, 120490, -0.2039824, -0.1501866, 0.06267537, -0.5615456, 3.823666, -8.49879 -IMU, 120510, -0.1392998, -0.1539488, 0.0669613, -0.5478984, 4.326402, -8.466464 -IMU2, 120510, -0.1282317, -0.1544241, 0.08251498, -0.6358982, 4.172328, -8.728794 -IMU, 120531, -0.179516, -0.1592735, 0.02192155, -0.3822479, 4.505899, -8.559166 -IMU2, 120531, -0.1760775, -0.1641461, 0.01635162, -0.3289761, 4.675927, -8.563434 -IMU, 120551, -0.1467402, -0.1484636, 0.007575302, -0.6428237, 3.498518, -8.408602 -IMU2, 120551, -0.1677873, -0.1504812, -0.002730266, -0.7018514, 3.673701, -8.372497 -IMU, 120570, -0.1150082, -0.123465, -0.0002418046, -0.4301849, 4.974116, -8.280162 -IMU2, 120570, -0.09318224, -0.1375531, -0.005984461, -0.530892, 4.863956, -8.371728 -MAG, 120580, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120580, -254, -103, 258, 0, 0, 0, 0, 0, 0 -CTUN, 120590, 202, 1, 203, 0, -1.73, -0.05, 0.00, 0.00, 0, -314 -ATT, 120591, 0.00, 28.17, 0.00, -6.24, 186.03, 184.89 -RCIN, 120591, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 120591, 1511, 1210, 1330, 1450, 0, 0, 0, 0 -IMU, 120591, -0.1522306, -0.1105769, -0.02674682, -0.3513995, 4.645787, -8.370109 -IMU2, 120591, -0.1552896, -0.1156445, -0.02514063, -0.244302, 4.790354, -8.540518 -IMU, 120611, -0.07469395, -0.09481477, -0.01620686, -0.7532021, 3.823262, -8.290855 -IMU2, 120611, -0.08458686, -0.09693925, -0.0229682, -0.6873872, 3.971209, -8.218175 -IMU, 120630, -0.05523664, -0.07587194, -0.007360855, -0.5226733, 5.276298, -8.468231 -IMU2, 120630, -0.03351334, -0.09095007, -0.0009331577, -0.5421332, 5.356634, -8.393656 -GPS, 3, 56700800, 1777, 11, 1.42, 14.110586, 100.6192235, -1.89, -1.08, 0.50, 307.17, 0.16, 120640 -IMU, 120650, -0.06005632, -0.07253049, -0.01840349, -0.9409075, 4.517164, -8.564435 -IMU2, 120650, -0.06631479, -0.07281784, -0.02024278, -0.8160656, 4.682307, -8.578921 -IMU, 120670, 0.03601542, -0.05740895, -0.0004074296, -1.172153, 3.859403, -8.391577 -IMU2, 120670, 0.011661, -0.06543845, -0.004070258, -1.148768, 3.852854, -8.312376 -MAG, 120680, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120680, -252, -105, 261, 0, 0, 0, 0, 0, 0 -CTUN, 120690, 202, 1, 203, 0, -2, -0.05, 0.00, 0.00, 0, -355 -ATT, 120690, 0.00, 30.06, 0.00, -6.55, 186.03, 184.67 -RCIN, 120690, 1503, 1504, 1066, 1512, 993, 992, 992, 992 -RCOU, 120690, 1507, 1210, 1318, 1464, 0, 0, 0, 0 -IMU, 120690, 0.04352294, -0.03508602, -0.003899687, -0.8247541, 5.129296, -8.799298 -IMU2, 120690, 0.06454044, -0.03046341, 0.0105845, -0.7768169, 5.165844, -8.834615 -IMU, 120710, 0.05016782, -0.006394614, -0.01414193, -0.909673, 4.219837, -8.915563 -IMU2, 120710, 0.03773317, -0.005778329, -0.01657644, -0.7791767, 4.383328, -8.911386 -IMU, 120730, 0.1162831, 0.004717834, 0.003729383, -1.122679, 4.127629, -8.569141 -IMU2, 120730, 0.0963426, -0.004687196, 0.000501195, -1.129446, 4.001588, -8.571844 -IMU, 120750, 0.05392028, 0.01144795, -0.009630378, -0.7502182, 5.204134, -8.842341 -IMU2, 120750, 0.0790815, 0.01129436, -0.001196662, -0.6146979, 5.310268, -9.086137 -IMU, 120770, 0.04672949, 0.02392055, -0.009602903, -0.7817262, 3.881374, -8.909164 -IMU2, 120770, 0.04275466, 0.01904727, -0.009878084, -0.6940305, 4.090192, -8.949183 -MAG, 120781, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120781, -252, -104, 265, 0, 0, 0, 0, 0, 0 -CTUN, 120790, 202, 2, 204, 0, -2.3, 0.04, 0.00, 0.00, 0, -396 -ATT, 120790, 0.00, 32.60, 0.00, -6.52, 186.03, 184.67 -RCIN, 120790, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 120791, 1502, 1210, 1317, 1470, 0, 0, 0, 0 -IMU, 120791, 0.09625018, 0.03110724, 0.01264956, -0.813466, 4.094265, -8.614484 -IMU2, 120791, 0.107445, 0.02149213, 0.01561313, -0.7347077, 3.957186, -8.513485 -IMU, 120810, 0.02789874, 0.02026873, -0.01118165, -0.7917362, 4.583382, -8.558179 -IMU2, 120810, 0.02187407, 0.02131719, -0.002462045, -0.6278892, 4.824897, -8.452066 -IMU, 120831, 0.02714905, 0.001381006, -0.02245378, -1.089135, 3.282952, -8.764796 -IMU2, 120831, -0.01480896, -0.003730035, -0.01362548, -0.8763048, 3.517162, -8.586386 -GPS, 3, 56701000, 1777, 11, 1.42, 14.110587, 100.6192253, -2.49, -1.03, 0.61, 307.17, 0.18, 120840 -IMU, 120851, 0.04112938, -0.004395351, -0.01837472, -1.021015, 4.414034, -8.709385 -IMU2, 120851, 0.02956226, -0.0150526, -0.005633889, -0.9110088, 4.36473, -8.657833 -IMU, 120870, -0.0301019, -0.01122152, -0.03835133, -1.025007, 4.426511, -8.775629 -IMU2, 120870, -0.03447049, -0.02099494, -0.01862781, -0.8586466, 4.751499, -8.710862 -MAG, 120880, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120880, -251, -103, 263, 0, 0, 0, 0, 0, 0 -CTUN, 120890, 202, 2, 204, 0, -2.63, 0.01, 0.00, 0.00, 0, -440 -DU32, 7, 262265 -CURR, 120890, 204, 5459, 1521, 767, 5270, 22.76009 -ATT, 120890, 0.00, 34.70, 0.00, -6.47, 186.03, 184.60 -RCIN, 120890, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 120891, 1502, 1210, 1327, 1461, 0, 0, 0, 0 -IMU, 120891, -0.01993599, -0.005415577, -0.02964217, -1.208, 3.398966, -8.826233 -IMU2, 120891, -0.0442575, -0.01001954, -0.01935334, -1.060681, 3.615629, -8.735451 -IMU, 120910, -0.02222229, 0.005014859, -0.01144625, -0.8359064, 4.980513, -9.012038 -IMU2, 120910, 0.004071865, -0.006046285, 0.006452505, -0.773952, 4.951796, -8.879604 -IMU, 120930, -0.08437372, 0.00587333, -0.01434649, -0.7481355, 4.48802, -9.081948 -IMU2, 120930, -0.08638871, 0.006769668, -0.007620472, -0.4896742, 4.958152, -9.086847 -IMU, 120950, -0.03134686, 0.01459933, 0.01751138, -1.028443, 3.523896, -8.951644 -IMU2, 120950, -0.04718155, 0.01441193, 0.0125677, -1.056074, 3.677862, -8.768542 -IMU, 120970, -0.03464547, 0.03327233, 0.04258281, -0.7913195, 4.904829, -8.982535 -IMU2, 120970, -0.01054906, 0.03419065, 0.05568652, -0.6318526, 4.944257, -8.886909 -MAG, 120980, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 120980, -252, -104, 263, 0, 0, 0, 0, 0, 0 -CTUN, 120990, 202, 3, 205, 0, -2.99, -0.02, 0.00, 0.00, 0, -485 -ATT, 120990, 0.00, 36.62, 0.00, -6.51, 186.03, 184.70 -RCIN, 120990, 1504, 1504, 1066, 1511, 992, 992, 993, 991 -RCOU, 120990, 1492, 1210, 1335, 1467, 0, 0, 0, 0 -IMU, 120990, -0.09453438, 0.03189777, 0.04710437, -0.8940896, 4.181313, -8.762299 -IMU2, 120990, -0.09803132, 0.02723353, 0.06091758, -0.6732643, 4.533216, -8.488169 -IMU, 121011, -0.06677175, 0.004854813, 0.08044598, -1.138585, 3.678983, -8.626837 -IMU2, 121011, -0.08194481, 0.00385017, 0.08744998, -1.071772, 3.80297, -8.584677 -IMU, 121030, -0.08701244, -0.01620614, 0.1013685, -0.8789546, 5.274945, -8.920201 -IMU2, 121030, -0.05373201, -0.01567894, 0.1166039, -0.6890328, 5.359389, -9.019489 -GPS, 3, 56701200, 1777, 11, 1.42, 14.1105869, 100.6192278, -3.22, -1.62, 0.31, 307.17, 0.4, 121040 -IMU, 121050, -0.09395212, -0.03394219, 0.1188123, -0.9277081, 4.359721, -8.993962 -IMU2, 121050, -0.1012535, -0.03464136, 0.1189477, -0.6394328, 4.825586, -8.908348 -IMU, 121071, -0.0136856, -0.03446486, 0.1670294, -0.9777868, 3.705139, -8.862671 -IMU2, 121071, -0.02099846, -0.03348131, 0.1561199, -1.017565, 3.832489, -8.642534 -MAG, 121080, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121080, -252, -103, 264, 0, 0, 0, 0, 0, 0 -CTUN, 121090, 202, 3, 205, 0, -3.38, 0.02, 0.00, 0.00, 0, -535 -ATT, 121090, 0.00, 38.22, 0.00, -7.08, 186.03, 185.17 -RCIN, 121090, 1503, 1504, 1066, 1510, 992, 993, 992, 992 -RCOU, 121091, 1477, 1210, 1347, 1470, 0, 0, 0, 0 -IMU, 121091, -0.05034822, -0.01953719, 0.1842046, -0.7499338, 5.104294, -9.055102 -IMU2, 121091, -0.01709401, -0.0121954, 0.1861634, -0.7011517, 5.239663, -9.118958 -IMU, 121110, -0.05976089, -0.002193406, 0.1802549, -0.8572232, 3.9787, -9.04588 -IMU2, 121110, -0.06748331, 0.0003022552, 0.1818627, -0.6699559, 4.444904, -9.159129 -IMU, 121130, 0.01801393, 0.0103279, 0.204475, -0.7500021, 3.72418, -8.935925 -IMU2, 121130, -0.001761513, 0.0184516, 0.1981543, -0.7524317, 3.699351, -8.842566 -IMU, 121151, -0.005898511, 0.007891577, 0.1947194, -0.6386346, 5.035808, -9.06135 -IMU2, 121151, 0.004354987, 0.01419768, 0.2038402, -0.4675694, 5.127364, -9.07618 -IMU, 121171, 0.0002183411, -0.01132716, 0.1659451, -0.7320893, 3.849106, -8.874701 -IMU2, 121171, -0.01285041, 0.007946525, 0.1646595, -0.5137414, 4.243353, -8.899722 -MAG, 121181, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121181, -253, -96, 265, 0, 0, 0, 0, 0, 0 -CTUN, 121190, 202, 3, 205, 0, -3.81, -0.09, 0.00, 0.00, 0, -588 -ATT, 121191, 0.00, 40.36, 0.00, -7.73, 186.03, 185.87 -RCIN, 121191, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 121191, 1478, 1210, 1347, 1469, 0, 0, 0, 0 -IMU, 121191, 0.092843, -0.03836537, 0.1610482, -0.6940202, 3.577932, -8.461497 -IMU2, 121191, 0.05429162, -0.03619827, 0.1553775, -0.6963459, 3.659739, -8.334767 -IMU, 121211, 0.06433752, -0.05266759, 0.1343393, -0.6084524, 5.149919, -8.673501 -IMU2, 121211, 0.09288288, -0.05164889, 0.1313345, -0.5080026, 5.179996, -8.874175 -IMU, 121230, 0.03791776, -0.05651593, 0.1058608, -0.5486184, 4.095959, -8.641464 -IMU2, 121230, 0.05110674, -0.0655244, 0.09527659, -0.4817779, 4.393464, -8.71265 -IMU, 121250, 0.09993546, -0.06153922, 0.09631094, -0.6709407, 3.353414, -8.26742 -IMU2, 121250, 0.09993496, -0.08427088, 0.07034772, -0.7777561, 3.474303, -8.320883 -GPS, 3, 56701400, 1777, 11, 1.42, 14.1105871, 100.6192289, -4.18, -1.76, 0.36, 307.17, 0.34, 121260 -IMU, 121270, 0.05859296, -0.05591209, 0.07309763, -0.7539316, 4.972761, -8.780079 -IMU2, 121270, 0.112511, -0.05399441, 0.06364261, -0.8079808, 4.945212, -9.07073 -MAG, 121280, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121280, -252, -90, 266, 0, 0, 0, 0, 0, 0 -CTUN, 121290, 202, 4, 206, 0, -4.27, 0.07, 0.00, 0.00, 0, -643 -ATT, 121290, 0.00, 42.77, 0.00, -8.26, 186.03, 186.02 -RCIN, 121290, 1503, 1504, 1066, 1511, 992, 993, 992, 992 -RCOU, 121291, 1469, 1210, 1357, 1467, 0, 0, 0, 0 -IMU, 121291, 0.01557366, -0.04349631, 0.03791127, -0.7796109, 4.425594, -8.901202 -IMU2, 121291, 0.002420507, -0.04010615, 0.03880623, -0.8042766, 4.805861, -8.904198 -IMU, 121310, 0.06451328, -0.005356286, 0.02903064, -0.8195554, 3.289773, -8.910854 -IMU2, 121310, 0.01479118, -0.01035682, 0.02570121, -0.745097, 3.478039, -8.730888 -IMU, 121330, 0.06417819, 0.03242825, 0.01252929, -0.726554, 4.36922, -9.017963 -IMU2, 121330, 0.05437393, 0.02619384, 0.02608481, -0.5429319, 4.367787, -8.798293 -IMU, 121351, -0.007522447, 0.0194338, -0.02716725, -0.6282805, 4.223436, -9.052505 -IMU2, 121351, -0.02760227, 0.01404008, -0.01095423, -0.5431106, 4.657491, -9.098605 -IMU, 121370, 0.00320599, 0.004876509, -0.03629232, -0.6270906, 3.472856, -8.903803 -IMU2, 121370, -0.04171788, -0.003047879, -0.02380037, -0.5739061, 3.632432, -8.730343 -MAG, 121380, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121380, -252, -88, 267, 0, 0, 0, 0, 0, 0 -CTUN, 121390, 202, 5, 207, 0, -4.77, -0.05, 0.00, 0.00, 0, -699 -ATT, 121390, 0.00, 45.10, 0.00, -8.21, 186.03, 185.99 -RCIN, 121391, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 121391, 1482, 1210, 1343, 1474, 0, 0, 0, 0 -IMU, 121391, 0.05880703, -0.01399893, -0.02942168, -0.4256033, 4.403307, -8.881502 -IMU2, 121391, 0.06849801, -0.03415, -0.02425819, -0.4892337, 4.223818, -8.873462 -IMU, 121410, 0.02562213, -0.07226893, -0.0410886, -0.4832932, 4.721781, -8.905303 -IMU2, 121410, 0.05810253, -0.08875823, -0.0400392, -0.4314137, 4.950359, -9.077115 -IMU, 121431, 0.06229687, -0.1324318, -0.04782156, -0.7991918, 3.440922, -8.741462 -IMU2, 121431, 0.06276852, -0.1461021, -0.06989937, -0.7439914, 3.720688, -8.723503 -GPS, 3, 56701600, 1777, 11, 1.42, 14.1105883, 100.6192289, -5.09, -1.84, 0.59, 307.17, 0.29, 121440 -IMU, 121451, 0.1490798, -0.1488709, -0.02702012, -0.5463187, 3.656263, -8.86001 -IMU2, 121451, 0.1484945, -0.1676642, -0.04668427, -0.5820877, 3.594651, -8.696804 -IMU, 121470, 0.1029804, -0.1246823, -0.0218427, -0.8332478, 4.741274, -9.364621 -IMU2, 121470, 0.114587, -0.1153868, -0.02902022, -0.7028095, 4.966683, -9.538031 -MAG, 121480, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121480, -251, -87, 266, 0, 0, 0, 0, 0, 0 -CTUN, 121490, 202, 6, 208, 0, -5.31, -0.05, 0.00, 0.00, 0, -758 -ATT, 121490, 0.00, 47.67, 0.00, -8.56, 186.03, 185.45 -RCIN, 121490, 1503, 1503, 1066, 1513, 992, 992, 993, 991 -RCOU, 121491, 1471, 1210, 1352, 1476, 0, 0, 0, 0 -IMU, 121491, 0.08115792, -0.07544769, -0.02822907, -0.9405177, 3.522126, -9.118261 -IMU2, 121491, 0.05419412, -0.07383133, -0.03218193, -0.8618495, 3.812317, -9.060167 -IMU, 121510, 0.1071171, -0.0386049, -0.02729775, -1.113194, 3.082066, -8.704291 -IMU2, 121510, 0.06770831, -0.03622537, -0.03478293, -1.091223, 3.12791, -8.528998 -IMU, 121530, 0.03567977, -0.01413561, -0.04531235, -1.443278, 4.552725, -8.982687 -IMU2, 121530, 0.05047039, 0.004182013, -0.03699343, -1.219386, 4.434219, -8.908154 -IMU, 121551, -0.04013235, -0.008773118, -0.07095362, -1.417964, 4.135907, -8.921514 -IMU2, 121551, -0.03453601, -0.00483096, -0.06854832, -1.276125, 4.35161, -8.969693 -IMU, 121570, -0.02967146, 0.009787638, -0.07290786, -1.370914, 3.309372, -8.690102 -IMU2, 121570, -0.05832895, 0.01062669, -0.06710832, -1.443031, 3.517159, -8.736757 -MAG, 121580, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121580, -250, -89, 271, 0, 0, 0, 0, 0, 0 -CTUN, 121590, 202, 6, 208, 0, -5.88, -0.10, 0.00, 0.00, 0, -820 -ATT, 121590, 0.00, 49.86, 0.00, -8.37, 186.03, 185.21 -RCIN, 121590, 1502, 1504, 1066, 1511, 992, 992, 992, 992 -RCOU, 121591, 1476, 1210, 1344, 1480, 0, 0, 0, 0 -IMU, 121591, -0.02757347, 0.0294423, -0.05909792, -1.096243, 4.440397, -8.679952 -IMU2, 121591, -0.00758215, 0.02412762, -0.06140231, -1.194004, 4.283955, -8.797016 -IMU, 121610, -0.09429762, 0.02681702, -0.06500387, -0.9874955, 4.754856, -8.733531 -IMU2, 121610, -0.06344227, 0.03087211, -0.04871991, -0.9020672, 4.939888, -8.996187 -IMU, 121631, -0.06606159, 0.02281857, -0.05465011, -1.079661, 3.327945, -8.583425 -IMU2, 121631, -0.08174419, 0.02244494, -0.05815076, -1.024986, 3.642867, -8.545488 -GPS, 3, 56701800, 1777, 11, 1.42, 14.1105878, 100.6192291, -6.25, -1.91, 0.60, 307.17, 0.24, 121640 -IMU, 121650, 0.01839513, 0.04204721, -0.02600512, -0.8462582, 3.601285, -8.641203 -IMU2, 121650, 0.01056895, 0.03521256, -0.02125915, -0.818854, 3.522696, -8.515017 -IMU, 121670, -0.03077001, 0.04736035, -0.02026004, -0.8456353, 4.641572, -9.148903 -IMU2, 121670, -0.02169579, 0.04633673, -0.003743624, -0.7486019, 4.781212, -9.114589 -MAG, 121680, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121680, -250, -91, 269, 0, 0, 0, 0, 0, 0 -CTUN, 121691, 202, 7, 209, 0, -6.5, -0.18, 0.00, 0.00, 0, -886 -ATT, 121691, 0.00, 51.70, 0.00, -8.14, 186.03, 185.17 -RCIN, 121691, 1502, 1504, 1066, 1510, 993, 992, 992, 992 -RCOU, 121691, 1470, 1210, 1358, 1474, 0, 0, 0, 0 -IMU, 121691, -0.07771251, 0.02968548, -0.02552048, -0.9043388, 3.779049, -8.955983 -IMU2, 121691, -0.09878742, 0.02695509, -0.009888405, -0.8761836, 4.086289, -8.845907 -IMU, 121710, -0.04189956, 0.005784884, -0.01106724, -0.7332675, 3.393383, -8.894102 -IMU2, 121710, -0.07817391, -0.006448158, -0.008062616, -0.6905575, 3.511649, -8.696216 -IMU, 121730, -0.0694017, -0.008493971, 0.005024078, -0.6506609, 4.78154, -9.152309 -IMU2, 121730, -0.06553825, -0.00347028, 0.008249216, -0.5448796, 4.852739, -9.028002 -IMU, 121751, -0.1175686, -0.03369805, 0.003058682, -0.7489314, 4.58316, -8.992105 -IMU2, 121751, -0.1176298, -0.04075162, 0.007223267, -0.5977722, 4.8961, -9.000126 -IMU, 121770, -0.07591401, -0.04934625, 0.02716188, -0.7722326, 3.533018, -8.607226 -IMU2, 121770, -0.1071531, -0.06876695, 0.0221575, -0.860487, 3.656599, -8.439167 -MAG, 121780, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121780, -250, -94, 268, 0, 0, 0, 0, 0, 0 -CTUN, 121790, 202, 8, 210, 0, -7.17, -0.02, 0.00, 0.00, 0, -956 -ATT, 121791, 0.00, 53.44, 0.00, -8.36, 186.03, 185.09 -RCIN, 121791, 1503, 1504, 1066, 1512, 993, 992, 992, 992 -RCOU, 121791, 1470, 1210, 1351, 1482, 0, 0, 0, 0 -IMU, 121791, -0.03569657, -0.04489939, 0.05315671, -0.683062, 4.60328, -8.839444 -IMU2, 121791, -0.01835087, -0.04410724, 0.0441317, -0.6592641, 4.600685, -8.794902 -IMU, 121812, -0.07915784, -0.05676742, 0.06521766, -0.7726045, 4.934319, -8.867061 -IMU2, 121812, -0.04549133, -0.05653759, 0.07307494, -0.6716157, 5.091639, -9.045763 -IMU, 121831, -0.05515839, -0.06218924, 0.06923807, -0.9756868, 3.531135, -8.607537 -IMU2, 121831, -0.07555605, -0.06555842, 0.06400412, -0.9615206, 3.891864, -8.677152 -GPS, 3, 56702000, 1777, 11, 1.42, 14.1105896, 100.6192277, -7.58, -2.24, 0.82, 307.17, 0.24, 121840 -IMU, 121851, 0.006148344, -0.05729671, 0.0793859, -0.915248, 3.608906, -8.406041 -IMU2, 121851, -0.0005983412, -0.06132001, 0.07801384, -0.9604326, 3.680307, -8.41481 -IMU, 121870, -0.0618696, -0.06896931, 0.06652715, -1.122185, 5.028658, -8.672603 -IMU2, 121870, -0.04224561, -0.06700486, 0.07326326, -1.135934, 5.076663, -8.667712 -MAG, 121880, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121880, -250, -92, 268, 0, 0, 0, 0, 0, 0 -CTUN, 121890, 202, 9, 211, 0, -7.87, -0.12, 0.00, 0.00, 0, -1029 -DU32, 7, 262265 -CURR, 121890, 211, 7533, 1520, 774, 5302, 24.88764 -ATT, 121891, 0.00, 55.20, 0.00, -8.83, 186.03, 185.02 -RCIN, 121891, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 121891, 1462, 1210, 1376, 1468, 0, 0, 0, 0 -IMU, 121891, -0.1195827, -0.08707174, 0.03897982, -1.245167, 4.473973, -8.750121 -IMU2, 121891, -0.1439454, -0.08654119, 0.05002877, -1.177456, 4.853792, -8.627576 -IMU, 121910, -0.06410708, -0.08155634, 0.03075948, -1.139516, 3.579407, -8.531755 -IMU2, 121910, -0.1025887, -0.07856144, 0.03022817, -1.043504, 3.709215, -8.446067 -IMU, 121930, -0.03685226, -0.046023, 0.02959816, -0.8666834, 4.709036, -8.900711 -IMU2, 121930, -0.03619458, -0.03355253, 0.03726036, -0.8113269, 4.741639, -8.918921 -IMU, 121950, -0.078436, -0.008894347, 0.01606823, -0.7706576, 4.957667, -9.027401 -IMU2, 121950, -0.05813078, -0.01296031, 0.0265865, -0.6881355, 5.186544, -9.147945 -IMU, 121970, -0.06828813, 0.009187583, 0.008056007, -0.8269079, 3.767218, -8.743578 -IMU2, 121970, -0.08200929, -0.002716393, -0.001969085, -0.8630761, 3.989529, -8.738843 -MAG, 121981, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 121981, -249, -92, 272, 0, 0, 0, 0, 0, 0 -CTUN, 121990, 202, 10, 212, 0, -8.61, -0.07, 0.00, 0.00, 0, -1106 -ATT, 121991, 0.00, 57.13, 0.00, -9.02, 186.03, 184.97 -RCIN, 121991, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 121991, 1465, 1210, 1354, 1488, 0, 0, 0, 0 -IMU, 121991, 0.002302695, 0.01571424, 0.01841389, -0.7213976, 3.691874, -8.681678 -IMU2, 121991, 0.002069702, 0.004493001, 0.01233434, -0.6994061, 3.749587, -8.580477 -IMU, 122011, -0.032697, -0.009847734, 0.02024528, -0.7591546, 4.843484, -8.790403 -IMU2, 122011, -0.02739179, -0.00990784, 0.02112232, -0.7023755, 4.838625, -8.968547 -IMU, 122030, -0.05690586, -0.04435914, 0.01023224, -1.061548, 4.289976, -8.732267 -IMU2, 122030, -0.07565731, -0.03678148, 0.009381384, -0.9615335, 4.477002, -8.613004 -GPS, 3, 56702200, 1777, 11, 1.42, 14.1105889, 100.6192284, -9.08, -2.51, 0.73, 307.17, 0.25, 122040 -IMU, 122051, 0.003881304, -0.06727058, 0.01481948, -1.075461, 3.462028, -8.566529 -IMU2, 122051, -0.04820433, -0.06953205, 0.01000093, -0.9898486, 3.607263, -8.333688 -IMU, 122070, 0.04770567, -0.05176987, 0.02199043, -1.188159, 4.52277, -8.909946 -IMU2, 122070, 0.04646444, -0.04358186, 0.02178239, -1.025572, 4.390664, -8.911444 -MAG, 122080, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122080, -249, -91, 272, 0, 0, 0, 0, 0, 0 -CTUN, 122090, 202, 11, 213, 0, -9.4, -0.01, 0.00, 0.00, 0, -1185 -ATT, 122091, 0.00, 59.07, 0.00, -9.26, 186.03, 184.78 -RCIN, 122091, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 122091, 1463, 1210, 1361, 1488, 0, 0, 0, 0 -IMU, 122091, 0.008684168, -0.03444017, 0.01463366, -1.160435, 5.125741, -8.858491 -IMU2, 122091, 0.04037465, -0.02676931, 0.0118823, -1.081223, 5.248929, -8.895741 -IMU, 122110, -0.0118789, -0.005109809, -0.0004186679, -1.036672, 4.143998, -8.652293 -IMU2, 122110, -0.03123979, -0.00184042, 0.003106214, -1.059628, 4.430539, -8.752041 -IMU, 122130, 0.04423196, 0.03479919, 0.005300786, -0.9004015, 3.708893, -8.392819 -IMU2, 122130, 0.03209332, 0.02489637, 0.001017715, -0.9064125, 3.836483, -8.134818 -IMU, 122150, 0.01112618, 0.03823759, -0.000853264, -0.8765823, 5.147348, -8.710326 -IMU2, 122150, 0.02583698, 0.02285937, 0.001029715, -0.7987676, 5.313918, -8.726312 -IMU, 122170, -0.06274395, 0.02002138, -0.01225873, -1.054749, 4.885548, -8.851444 -IMU2, 122170, -0.05165192, 0.008100666, -0.007937828, -0.9554255, 5.094442, -9.001105 -MAG, 122180, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122180, -249, -92, 276, 0, 0, 0, 0, 0, 0 -CTUN, 122190, 202, 11, 213, 0, -10.24, -0.01, 0.00, 0.00, 0, -1266 -ATT, 122190, 0.00, 61.23, 0.00, -9.21, 186.03, 184.81 -RCIN, 122190, 1503, 1504, 1066, 1511, 992, 993, 992, 992 -RCOU, 122191, 1460, 1210, 1368, 1483, 0, 0, 0, 0 -IMU, 122191, -0.03335413, -0.006273054, -0.01395409, -0.9514481, 3.449074, -8.394053 -IMU2, 122191, -0.06320534, -0.01489603, -0.02269921, -1.043381, 3.720319, -8.285451 -IMU, 122210, 0.007123085, -0.007436022, -0.004063399, -1.167343, 3.788215, -8.70122 -IMU2, 122210, 0.008492772, -0.01309894, -0.006927872, -1.172566, 3.858126, -8.676165 -IMU, 122231, -0.02977273, -0.01040551, -0.009850758, -1.1488, 4.953833, -9.023399 -IMU2, 122231, -0.01668128, -0.003763104, -0.00811041, -1.078081, 5.047722, -9.04293 -GPS, 3, 56702400, 1777, 11, 1.42, 14.1105891, 100.6192297, -10.76, -2.63, 0.48, 307.17, 0.18, 122240 -IMU, 122251, -0.05438031, -0.01711147, -0.02221768, -1.308094, 4.33621, -9.043341 -IMU2, 122251, -0.07204317, -0.01281004, -0.0203111, -1.283326, 4.681406, -9.039665 -IMU, 122270, 0.02242573, -0.01196945, -0.01283783, -1.142088, 3.63048, -8.583914 -IMU2, 122270, -0.01180387, -0.01737062, -0.01285181, -1.009188, 3.762892, -8.387712 -MAG, 122280, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122280, -249, -90, 275, 0, 0, 0, 0, 0, 0 -CTUN, 122290, 202, 9, 211, 0, -11.12, 0.06, 0.00, 0.00, 0, -1350 -ATT, 122291, 0.00, 63.12, 0.00, -9.24, 186.03, 184.75 -RCIN, 122291, 1503, 1504, 1066, 1512, 992, 992, 993, 992 -RCOU, 122291, 1461, 1210, 1354, 1493, 0, 0, 0, 0 -IMU, 122291, 0.03622176, -0.006102286, 0.001780076, -1.153394, 4.755993, -8.890806 -IMU2, 122291, 0.05048987, -0.00429396, 0.000281834, -1.107693, 4.829413, -8.898783 -IMU, 122310, -0.03138454, 0.01024403, 0.00281307, -0.9730268, 5.28271, -8.90858 -IMU2, 122310, -0.007045921, 0.009053642, 0.0006874755, -0.962357, 5.411571, -9.112842 -IMU, 122330, -0.04658844, 0.02031222, 0.008476142, -0.9500186, 4.177492, -8.716382 -IMU2, 122330, -0.06623707, 0.01624957, 0.00215173, -0.9130601, 4.326265, -8.791666 -IMU, 122350, 0.02190925, 0.04098757, 0.02101608, -0.7856493, 3.928062, -8.694594 -IMU2, 122350, 0.0177686, 0.03405596, 0.01627801, -0.7156587, 4.019731, -8.621119 -IMU, 122370, 0.01408637, 0.02990638, 0.01983906, -0.7626853, 4.889226, -8.908115 -IMU2, 122370, 0.02323013, 0.02303928, 0.02519725, -0.65425, 5.042627, -8.974091 -MAG, 122380, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122380, -250, -93, 275, 0, 0, 0, 0, 0, 0 -CTUN, 122390, 201, 7, 208, 0, -12.05, -0.13, 0.00, 0.00, 0, -1437 -ATT, 122391, 0.00, 65.32, 0.00, -9.23, 186.03, 184.85 -RCIN, 122391, 1502, 1504, 1065, 1512, 992, 993, 992, 992 -RCOU, 122391, 1447, 1210, 1367, 1485, 0, 0, 0, 0 -IMU, 122391, -0.01856238, 0.01155375, 0.007352598, -1.078748, 4.385458, -8.920555 -IMU2, 122391, -0.02345277, 0.01205162, 0.009039434, -0.9615821, 4.55481, -8.981088 -IMU, 122411, 0.02631622, -0.00988289, 0.008902208, -0.9994018, 3.242879, -8.599323 -IMU2, 122411, -0.01811987, -0.01513148, 0.01482785, -0.9375136, 3.423377, -8.382448 -IMU, 122431, 0.05263358, -0.0171361, 0.01633298, -1.193131, 4.200058, -8.936512 -IMU2, 122431, 0.04649306, -0.02062378, 0.01986467, -1.131315, 4.079874, -8.855522 -GPS, 3, 56702600, 1777, 11, 1.42, 14.1105903, 100.6192298, -12.63, -2.77, 0.63, 307.17, 0.17, 122440 -IMU, 122451, 0.0140443, -0.02990134, 0.004550496, -0.9364103, 4.809994, -8.906095 -IMU2, 122451, 0.01753106, -0.03320815, 0.01385125, -0.8055423, 4.925331, -8.899138 -IMU, 122470, -0.004773146, -0.02913674, -0.006013922, -0.8678269, 3.999219, -8.889067 -IMU2, 122470, -0.02778263, -0.02496766, -0.01545118, -0.8308361, 4.192219, -8.786569 -MAG, 122480, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122480, -249, -90, 274, 0, 0, 0, 0, 0, 0 -CTUN, 122490, 201, 5, 206, 0, -13.03, 0.06, 0.00, 0.00, 0, -1527 -ATT, 122491, 0.00, 67.38, 0.00, -9.36, 186.03, 184.81 -RCIN, 122491, 1503, 1504, 1065, 1511, 992, 993, 992, 992 -RCOU, 122491, 1451, 1210, 1350, 1494, 0, 0, 0, 0 -IMU, 122491, 0.06861667, -0.004471242, 0.008337259, -0.7006652, 3.717836, -8.38571 -IMU2, 122491, 0.06342209, -0.001022255, -0.002619893, -0.7901291, 3.811511, -8.145758 -IMU, 122510, 0.04312638, 0.0005741902, 0.0179146, -0.7160525, 5.168837, -8.605449 -IMU2, 122510, 0.06373466, -0.006553112, 0.0250224, -0.7511097, 5.274057, -8.670987 -IMU, 122530, -0.01540888, -0.004825659, 0.002204723, -0.806651, 5.053179, -8.675108 -IMU2, 122530, -0.005093042, -0.007481806, 0.003005533, -0.597367, 5.274435, -8.689487 -IMU, 122551, 0.02013652, -0.02100117, -0.002069383, -0.7128795, 3.550096, -8.490668 -IMU2, 122551, -0.01253255, -0.02716918, -0.008947864, -0.6949553, 3.860195, -8.341972 -IMU, 122571, 0.07636531, -0.007831536, 0.006632429, -0.9587609, 4.190867, -8.878709 -IMU2, 122571, 0.07930057, -0.008341465, 0.004310671, -0.8769429, 4.280209, -8.890991 -MAG, 122580, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122580, -249, -90, 276, 0, 0, 0, 0, 0, 0 -CTUN, 122590, 202, 4, 206, 0, -14.05, 0.00, 0.00, 0.00, 0, -1621 -ATT, 122590, 0.00, 69.79, 0.00, -9.41, 186.03, 184.70 -RCIN, 122590, 1503, 1504, 1066, 1512, 992, 992, 993, 991 -RCOU, 122591, 1446, 1210, 1357, 1492, 0, 0, 0, 0 -IMU, 122591, 0.04495281, -0.02540707, -0.002348981, -0.9964892, 4.840359, -8.991516 -IMU2, 122591, 0.04751647, -0.02183984, 0.002378118, -0.9003638, 4.997673, -9.064214 -IMU, 122610, 0.02525352, -0.03766789, -0.02012208, -1.167211, 4.119825, -9.052484 -IMU2, 122610, -0.007243382, -0.03379039, -0.02374217, -1.067716, 4.457182, -8.945318 -IMU, 122630, 0.1114313, -0.02686167, -0.02046297, -0.8889951, 3.291665, -8.514625 -IMU2, 122630, 0.0849297, -0.02732699, -0.03086705, -0.869517, 3.407592, -8.2761 -GPS, 3, 56702800, 1777, 11, 1.42, 14.1105914, 100.6192285, -14.69, -2.93, 0.81, 307.17, 0.19, 122640 -IMU, 122650, 0.1145958, -0.02323749, -0.02105515, -1.141542, 4.44119, -8.681067 -IMU2, 122650, 0.127644, -0.01699994, -0.02556098, -1.030947, 4.481464, -8.789151 -IMU, 122670, 0.03517856, -0.0238872, -0.0288299, -1.046345, 4.968502, -8.407017 -IMU2, 122670, 0.05933151, -0.01876437, -0.02977771, -1.03531, 5.06221, -8.689642 -MAG, 122681, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122681, -249, -89, 275, 0, 0, 0, 0, 0, 0 -CTUN, 122690, 202, 2, 204, 0, -15.13, -0.04, 0.00, 0.00, 0, -1716 -ATT, 122690, 0.00, 72.06, 0.00, -9.40, 186.03, 184.54 -RCIN, 122690, 1503, 1504, 1066, 1512, 992, 993, 992, 992 -RCOU, 122690, 1443, 1210, 1363, 1485, 0, 0, 0, 0 -IMU, 122690, 0.0182506, -0.02854822, -0.02927819, -0.8890297, 3.755622, -8.324371 -IMU2, 122690, 0.004633091, -0.03717333, -0.03719326, -0.8840256, 3.898454, -8.318209 -IMU, 122710, 0.06055415, -0.01846198, -0.01486684, -1.003161, 4.097819, -8.528645 -IMU2, 122710, 0.06757861, -0.02333758, -0.01925209, -0.9234318, 4.116952, -8.428158 -IMU, 122730, 0.02730548, -0.02525217, -0.01828047, -0.9285709, 4.971291, -8.773566 -IMU2, 122730, 0.05491648, -0.02577643, -0.01903021, -0.8362849, 4.997852, -8.799834 -IMU, 122750, -0.0157297, -0.04595441, -0.02119506, -1.166816, 3.87536, -9.001847 -IMU2, 122750, -0.03096906, -0.043933, -0.0303205, -1.137803, 4.31802, -9.101017 -IMU, 122770, 0.05157507, -0.03840284, -0.004578917, -1.124917, 3.490322, -8.855597 -IMU2, 122770, 0.008811887, -0.03453828, -0.00965735, -1.047438, 3.456508, -8.781701 -MAG, 122780, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122780, -248, -90, 277, 0, 0, 0, 0, 0, 0 -CTUN, 122791, 201, 0, 200, 0, -16.25, 0.08, 0.00, 0.00, 0, -1814 -ATT, 122791, 0.00, 74.49, 0.00, -9.40, 186.03, 184.30 -RCIN, 122791, 1503, 1504, 1065, 1512, 992, 992, 993, 992 -RCOU, 122791, 1440, 1210, 1351, 1495, 0, 0, 0, 0 -IMU, 122791, 0.04668631, -0.01971505, 0.0117337, -1.083549, 4.885886, -9.28522 -IMU2, 122791, 0.03990805, -0.02191106, 0.02344361, -1.181573, 4.499229, -9.117123 -IMU, 122810, -0.005991513, -0.02654248, 0.0005402497, -1.162072, 4.657893, -8.969583 -IMU2, 122810, 0.004218087, -0.0246352, 0.008486184, -1.042369, 4.872105, -8.906899 -IMU, 122830, -0.002959201, -0.03814752, 0.009658227, -0.9295572, 3.391807, -8.428908 -IMU2, 122830, -0.03321973, -0.05327644, 0.007764227, -0.9369167, 3.699824, -8.500721 -GPS, 3, 56703000, 1777, 11, 1.42, 14.1105915, 100.6192281, -16.94, -2.97, 0.74, 307.17, 0.15, 122840 -IMU, 122851, 0.04205284, -0.04130592, 0.02063645, -1.024873, 4.143146, -8.745243 -IMU2, 122851, 0.02894138, -0.04289242, 0.0229667, -0.9539324, 4.064108, -8.557685 -IMU, 122871, 0.02165997, -0.05586403, 0.01523274, -0.9718668, 4.861984, -8.856992 -IMU2, 122871, 0.03319605, -0.05907867, 0.01774855, -0.861238, 5.052306, -8.872653 -MAG, 122880, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122880, -248, -89, 277, 0, 0, 0, 0, 0, 0 -CTUN, 122890, 201, -2, 199, 0, -17.42, -0.16, 0.00, 0.00, 0, -1914 -DU32, 7, 262265 -CURR, 122890, 199, 9605, 1516, 720, 5322, 26.96793 -ATT, 122890, 0.00, 76.57, 0.00, -9.54, 186.03, 184.09 -RCIN, 122890, 1503, 1503, 1065, 1512, 993, 992, 992, 992 -RCOU, 122891, 1432, 1210, 1365, 1484, 0, 0, 0, 0 -IMU, 122891, -0.007804217, -0.05675782, 0.005777831, -1.1746, 3.877182, -8.864441 -IMU2, 122891, -0.02123788, -0.06336053, 0.007091075, -1.095763, 4.398545, -8.705472 -IMU, 122910, 0.05119922, -0.0334957, 0.01321835, -1.060874, 3.111233, -8.731457 -IMU2, 122910, 0.02617498, -0.04357101, 0.005456061, -1.087821, 3.203025, -8.434931 -IMU, 122930, 0.03337347, -0.03098672, 0.02182439, -1.253675, 4.511073, -9.01137 -IMU2, 122930, 0.02944102, -0.0465575, 0.02412766, -1.272482, 4.524562, -9.087445 -IMU, 122950, -0.04635703, -0.04162553, 0.01389792, -1.362108, 4.85456, -9.083702 -IMU2, 122950, -0.03388542, -0.04018033, 0.0196671, -1.263258, 5.10949, -9.24315 -IMU, 122970, -0.0459366, -0.03881286, 0.02733227, -0.91834, 3.459977, -8.580665 -IMU2, 122970, -0.07276607, -0.0497546, 0.01617003, -1.132074, 3.751625, -8.666393 -MAG, 122980, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 122980, -247, -87, 282, 0, 0, 0, 0, 0, 0 -CTUN, 122990, 201, -3, 198, 0, -18.65, -0.14, 0.00, 0.00, 0, -2016 -ATT, 122991, 0.00, 78.73, 0.00, -9.70, 186.03, 183.92 -RCIN, 122991, 1504, 1503, 1065, 1512, 992, 993, 992, 992 -RCOU, 122991, 1431, 1210, 1352, 1498, 0, 0, 0, 0 -IMU, 122991, -0.006361092, -0.007757459, 0.04190663, -0.8575115, 3.887897, -8.736903 -IMU2, 122991, -0.007283093, -0.005497419, 0.04190893, -0.8789358, 3.802011, -8.658555 -IMU, 123011, -0.03761484, 0.001422234, 0.03066221, -0.7555878, 4.52242, -8.84866 -IMU2, 123011, -0.03014749, 0.009491289, 0.04264164, -0.565872, 4.678783, -8.802482 -IMU, 123030, -0.0804902, -0.003337141, 0.01283955, -0.9383581, 3.837611, -9.047167 -IMU2, 123030, -0.1015471, -0.002662386, 0.02054749, -0.8180293, 4.280423, -8.977139 -GPS, 3, 56703200, 1777, 10, 1.99, 14.1105928, 100.6192256, -19.41, -3.09, 0.79, 307.17, 0.02, 123040 -IMU, 123051, -0.00925337, -0.01879727, 0.01002658, -1.034958, 3.221633, -8.65417 -IMU2, 123051, -0.05385352, -0.03260186, 0.01489383, -0.8560534, 3.316065, -8.373421 -IMU, 123070, 0.007581545, -0.06083293, 0.011324, -1.310547, 4.530807, -8.807231 -IMU2, 123070, -0.01088518, -0.06687832, 0.01253115, -1.255787, 4.396515, -8.751355 -MAG, 123080, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 123080, -247, -85, 281, 0, 0, 0, 0, 0, 0 -CTUN, 123090, 200, -4, 196, 0, -19.93, -0.07, 0.00, 0.00, 0, -2120 -ATT, 123090, 0.00, 80.52, 0.00, -9.86, 186.03, 183.75 -RCIN, 123090, 1503, 1504, 1064, 1512, 993, 992, 992, 992 -RCOU, 123090, 1432, 1210, 1366, 1480, 0, 0, 0, 0 -IMU, 123090, -0.05633277, -0.09600684, -0.002741202, -1.433153, 4.885421, -8.749609 -IMU2, 123090, -0.03208958, -0.09311152, 0.002115879, -1.256032, 5.091901, -8.991921 -IMU, 123110, -0.05784208, -0.1028306, 0.008563498, -1.126471, 3.881011, -8.431804 -IMU2, 123110, -0.06950248, -0.1186887, -0.003204012, -1.269523, 4.147892, -8.543129 -IMU, 123130, -0.007441917, -0.07037114, 0.02949282, -1.075972, 4.275474, -8.727318 -IMU2, 123130, 0.008265711, -0.06806241, 0.02028815, -1.029, 4.310304, -8.553785 -IMU, 123151, -0.0177033, -0.05709484, 0.03276781, -0.9953036, 4.9616, -8.70571 -IMU2, 123151, 0.0006425064, -0.06607085, 0.03188055, -0.9018078, 5.174588, -8.853257 -IMU, 123171, -0.05604141, -0.04039257, 0.02268425, -1.034639, 4.129023, -8.852354 -IMU2, 123171, -0.07004133, -0.04579435, 0.02509725, -0.9386121, 4.524492, -8.857354 -MAG, 123180, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 123180, -246, -88, 285, 0, 0, 0, 0, 0, 0 -CTUN, 123190, 196, -4, 192, 0, -21.25, -0.10, 0.00, 0.00, 0, -2228 -ATT, 123191, 0.00, 82.69, 0.00, -10.03, 186.03, 183.42 -RCIN, 123191, 1503, 1504, 1059, 1513, 992, 992, 993, 991 -RCOU, 123191, 1422, 1210, 1352, 1496, 0, 0, 0, 0 -IMU, 123191, 0.01603493, -0.01456985, 0.02618672, -1.036602, 3.026481, -8.615407 -IMU2, 123191, -0.01018874, -0.02282895, 0.02382831, -0.9618877, 3.121562, -8.264887 -IMU, 123210, 0.04186422, -0.01402949, 0.02184305, -1.403003, 4.40767, -8.990783 -IMU2, 123210, 0.02457519, -0.01076302, 0.02780118, -1.301492, 4.164771, -8.988515 -IMU, 123231, -0.007427176, -0.02538719, 0.005722054, -1.356934, 5.035402, -8.767863 -IMU2, 123231, 0.03727297, -0.02793521, 0.01518698, -1.369517, 5.012219, -8.98542 -IMU, 123250, -0.02329571, -0.04034476, -0.003374385, -1.12658, 3.892623, -8.387579 -IMU2, 123250, -0.04134599, -0.04840412, -0.01062868, -1.27392, 4.201605, -8.411218 -GPS, 3, 56703400, 1777, 10, 1.99, 14.1105939, 100.6192217, -22.34, -3.28, 1.10, 307.17, -0.05, 123261 -IMU, 123270, 0.02410541, -0.03318143, 0.002393056, -1.077008, 3.952428, -8.335003 -IMU2, 123270, 0.03607264, -0.03319681, -0.00251738, -1.014629, 3.88343, -8.161181 -MAG, 123280, 0, 0, 0, -86, 10, 139, 0, 0, 0 -MAG2, 123280, -245, -88, 288, 0, 0, 0, 0, 0, 0 -CTUN, 123290, 192, -2, 190, 0, -22.63, 0.03, 0.00, 0.00, 0, -2338 -ATT, 123290, 0.00, 84.78, 0.00, -10.10, 186.03, 183.25 -RCIN, 123290, 1503, 1504, 1055, 1512, 992, 993, 992, 992 -RCOU, 123291, 1422, 1210, 1354, 1489, 0, 0, 0, 0 -IMU, 123291, -0.004204655, -0.03553256, 0.002285741, -0.9683303, 4.985352, -8.741308 -IMU2, 123291, 0.01387082, -0.04162084, 0.003848672, -0.934172, 5.080159, -8.852489 -IMU, 123310, -0.05011934, -0.02450115, -0.006815219, -1.167364, 4.529291, -9.161108 -IMU2, 123310, -0.05317152, -0.01543067, -0.01260214, -1.018244, 4.98447, -9.10153 -IMU, 123330, 0.01233228, -0.01790007, 0.007976498, -1.262405, 3.584874, -8.746932 -IMU2, 123330, -0.03461868, -0.02196648, 0.00218105, -1.192196, 3.702729, -8.605768 -IMU, 123351, 0.03216823, -0.01323537, 0.02116856, -1.408839, 4.620263, -8.955957 -IMU2, 123351, 0.04534578, -0.008687048, 0.02165538, -1.38984, 4.628468, -9.112564 -IMU, 123370, -0.006822811, -0.02134612, 0.03136308, -1.161258, 5.343009, -8.82267 -IMU2, 123370, 0.002882307, -0.02342615, 0.04492819, -1.121574, 5.594732, -8.972331 -MAG, 123380, -389, 0, 120, -86, 10, 139, 0, 0, 0 -MAG2, 123380, -248, -85, 293, 0, 0, 0, 0, 0, 0 -CTUN, 123390, 0, 0, 0, 0, -24.05, 0.01, 0.00, 0.00, 0, -2452 -ATT, 123390, 0.00, 87.08, 0.00, -10.19, 183.11, 183.11 -RCIN, 123390, 1503, 1504, 1029, 1512, 993, 992, 992, 992 -RCOU, 123391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123391, 0.06364304, -0.02998074, 0.04327789, -1.078878, 3.936439, -8.502667 -IMU2, 123391, 0.02994697, -0.03528893, 0.0402716, -1.030933, 4.524731, -8.490604 -IMU, 123410, 0.1740303, -0.01399591, 0.05601315, -1.144966, 4.121819, -8.575219 -IMU2, 123410, 0.1721802, -0.01560627, 0.0592695, -1.066844, 4.092791, -8.54703 -IMU, 123431, 0.2091615, 0.005030133, 0.04947862, -1.206944, 5.246109, -8.892337 -IMU2, 123431, 0.2109154, 0.005344914, 0.05290591, -1.040338, 5.229698, -8.850446 -GPS, 3, 56703600, 1777, 10, 1.99, 14.1105938, 100.6192191, -24.92, -3.57, 1.12, 307.17, -0.06, 123440 -IMU, 123450, 0.2402408, 0.006070867, 0.02618402, -1.333677, 4.377191, -8.577825 -IMU2, 123450, 0.2374859, 0.008448107, 0.01672656, -1.263673, 4.738169, -8.855966 -IMU, 123470, 0.3261618, 0.05189636, 0.03595006, -1.237825, 4.434056, -8.452693 -IMU2, 123470, 0.3241948, 0.04329581, 0.01910707, -1.267649, 4.501615, -8.286452 -MAG, 123480, -386, 4, 121, -86, 10, 139, 0, 0, 0 -MAG2, 123480, -251, -78, 300, 0, 0, 0, 0, 0, 0 -CTUN, 123490, 0, 0, 0, 0, -25.52, 0.06, 0.00, 0.00, 0, -2567 -ATT, 123491, 0.00, 88.16, 0.00, -10.44, 183.23, 183.23 -RCIN, 123491, 1503, 1504, 1025, 1512, 993, 992, 992, 992 -RCOU, 123491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123491, 0.3141815, 0.057494, 0.02147848, -1.165875, 5.481636, -8.371037 -IMU2, 123491, 0.3496366, 0.04604575, 0.01336089, -1.27862, 5.621341, -8.719451 -IMU, 123510, 0.2994435, 0.09047022, -0.004001251, -1.055723, 3.980027, -8.846885 -IMU2, 123510, 0.2601603, 0.09827958, -0.01865278, -0.8655055, 4.524077, -8.862925 -IMU, 123530, 0.4126796, 0.09492038, 0.005398965, -1.074023, 3.98321, -8.364786 -IMU2, 123530, 0.4136848, 0.08696859, -0.008606298, -1.172132, 3.993513, -8.453793 -IMU, 123551, 0.4051137, 0.1332554, -0.03710408, -0.6812722, 4.670036, -8.760718 -IMU2, 123551, 0.4269657, 0.1267618, -0.03439674, -0.4568813, 4.686737, -8.610561 -IMU, 123570, 0.4215851, 0.09739988, -0.07591829, -1.010088, 3.276149, -8.845945 -IMU2, 123570, 0.3767421, 0.08279899, -0.0791134, -1.104948, 3.731874, -8.888198 -MAG, 123580, -389, 8, 120, -86, 10, 139, 0, 0, 0 -MAG2, 123580, -252, -72, 298, 0, 0, 0, 0, 0, 0 -CTUN, 123590, 0, 0, 0, 0, -27.04, -0.09, 0.00, 0.00, 0, -2681 -ATT, 123591, 0.00, 89.83, 0.00, -10.25, 183.79, 183.79 -RCIN, 123591, 1503, 1504, 1025, 1511, 993, 992, 992, 992 -RCOU, 123591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123591, 0.5042669, 0.06847307, -0.1039283, -1.164707, 4.365116, -8.962437 -IMU2, 123591, 0.5241218, 0.05400496, -0.1229258, -1.100339, 4.325109, -9.034883 -IMU, 123611, 0.4254343, 0.003325313, -0.1488243, -0.9980092, 4.561246, -9.376345 -IMU2, 123611, 0.4197843, -0.01285127, -0.1527239, -0.9976134, 4.814602, -9.504983 -IMU, 123630, 0.4619878, -0.05176982, -0.1619964, -1.017899, 3.049832, -8.859125 -IMU2, 123630, 0.4475812, -0.08639494, -0.172916, -1.172056, 3.179707, -8.767544 -GPS, 3, 56703800, 1777, 10, 1.99, 14.1105934, 100.6192181, -27.97, -3.76, 0.96, 307.17, -0.07, 123640 -IMU, 123650, 0.5051523, -0.08687326, -0.1909184, -1.003504, 3.458323, -9.278653 -IMU2, 123650, 0.5071556, -0.09606574, -0.2023271, -0.9360711, 3.524735, -9.306278 -IMU, 123670, 0.5013497, -0.07022492, -0.2346525, -1.307083, 2.57237, -8.97613 -IMU2, 123670, 0.4701032, -0.08594255, -0.235279, -1.209136, 2.716988, -8.800669 -MAG, 123680, -390, 14, 119, -86, 10, 139, 0, 0, 0 -MAG2, 123680, -252, -68, 296, 0, 0, 0, 0, 0, 0 -CTUN, 123690, 0, 0, 0, 0, -28.61, -0.17, 0.00, 0.00, 0, -2790 -ATT, 123690, 0.00, 92.01, 0.00, -9.26, 183.54, 183.54 -RCIN, 123690, 1503, 1504, 1025, 1512, 992, 993, 992, 992 -RCOU, 123690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123690, 0.4489642, -0.04485573, -0.2332839, -1.651662, 3.190909, -9.793008 -IMU2, 123690, 0.4295168, -0.04002207, -0.2401926, -1.733123, 3.407183, -9.776469 -IMU, 123710, 0.3637629, 0.02169627, -0.2422724, -1.193628, 3.140423, -9.334496 -IMU2, 123710, 0.3667182, 0.01352428, -0.2361846, -1.131999, 3.433488, -9.388017 -IMU, 123730, 0.3914517, 0.03084301, -0.2153358, -1.62751, 2.532774, -9.055321 -IMU2, 123730, 0.3825119, 0.03018438, -0.2117138, -1.74586, 2.583606, -9.08246 -IMU, 123750, 0.3430227, 0.05968434, -0.231509, -1.218585, 2.809718, -9.588828 -IMU2, 123750, 0.3392984, 0.04860977, -0.2146413, -1.142422, 2.89634, -9.541632 -IMU, 123770, 0.3200338, 0.08979329, -0.2152766, -1.864401, 2.358871, -9.86891 -IMU2, 123770, 0.3100983, 0.09051335, -0.212791, -1.864153, 2.496719, -9.69369 -MAG, 123780, -389, 13, 119, -86, 10, 139, 0, 0, 0 -MAG2, 123780, -253, -69, 298, 0, 0, 0, 0, 0, 0 -CTUN, 123790, 0, 0, 0, 0, -30.21, -0.22, 0.00, 0.00, 0, -2891 -ATT, 123791, 0.00, 93.44, 0.00, -8.07, 183.94, 183.94 -RCIN, 123791, 1504, 1503, 1026, 1512, 992, 993, 992, 992 -RCOU, 123791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123791, 0.2545149, 0.1088862, -0.1988601, -1.75923, 3.038763, -9.624741 -IMU2, 123791, 0.2604816, 0.103239, -0.1905349, -1.727675, 3.250914, -9.708367 -IMU, 123811, 0.2531273, 0.1417051, -0.1693949, -1.836405, 1.869325, -9.742012 -IMU2, 123811, 0.2308969, 0.1316001, -0.1643212, -1.822122, 2.134659, -9.479888 -IMU, 123830, 0.2553932, 0.1724485, -0.1363845, -1.478089, 2.452891, -9.529084 -IMU2, 123830, 0.2528834, 0.1615262, -0.1208059, -1.4253, 2.544604, -9.507276 -GPS, 3, 56704000, 1777, 10, 1.99, 14.1105921, 100.6192181, -31.19, -3.81, 0.83, 307.17, -0.13, 123840 -IMU, 123851, 0.2541674, 0.2064775, -0.1301521, -1.63655, 1.96719, -9.497205 -IMU2, 123851, 0.2528173, 0.1962845, -0.123991, -1.488159, 2.069249, -9.393333 -IMU, 123870, 0.2407233, 0.2296336, -0.08382627, -1.856719, 2.486893, -9.557608 -IMU2, 123870, 0.2521844, 0.2271065, -0.07768974, -1.866193, 2.51859, -9.706574 -MAG, 123880, -390, 12, 116, -86, 10, 139, 0, 0, 0 -MAG2, 123880, -254, -70, 294, 0, 0, 0, 0, 0, 0 -CTUN, 123890, 0, 0, 0, 0, -31.85, -0.10, 0.00, 0.00, 0, -2989 -DU32, 7, 262233 -CURR, 123890, 0, 10381, 1534, 120, 5306, 28.0594 -ATT, 123891, 0.00, 94.15, 0.00, -7.47, 185.13, 185.13 -RCIN, 123891, 1504, 1503, 1026, 1512, 992, 993, 992, 992 -RCOU, 123891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123891, 0.2020765, 0.2561394, -0.07781245, -1.764841, 1.619954, -9.576117 -IMU2, 123891, 0.1848075, 0.2552181, -0.07447792, -1.818112, 1.875732, -9.38927 -IMU, 123910, 0.187288, 0.2805591, -0.06115693, -1.148018, 2.31106, -9.739393 -IMU2, 123910, 0.1735553, 0.2735142, -0.0539551, -1.108592, 2.448464, -9.703372 -IMU, 123930, 0.1577166, 0.2954369, -0.0731931, -0.9464693, 2.431584, -9.972739 -IMU2, 123930, 0.1559664, 0.2843863, -0.06917759, -0.8396049, 2.616656, -9.84715 -IMU, 123951, 0.1835432, 0.271976, -0.07022163, -1.025819, 2.705842, -9.451896 -IMU2, 123951, 0.191771, 0.259645, -0.06806202, -0.9860085, 2.871177, -9.48293 -IMU, 123970, 0.1963143, 0.2401258, -0.08654428, -0.6226766, 2.128463, -9.469437 -IMU2, 123970, 0.1839154, 0.2270137, -0.08114198, -0.5798436, 2.362175, -9.477533 -MAG, 123980, -395, 12, 107, -86, 10, 139, 0, 0, 0 -MAG2, 123980, -258, -70, 286, 0, 0, 0, 0, 0, 0 -CTUN, 123990, 0, 0, 0, 0, -33.51, -0.09, 0.00, 0.00, 0, -3089 -ATT, 123990, 0.00, 94.55, 0.00, -7.19, 186.67, 186.67 -RCIN, 123990, 1503, 1504, 1025, 1513, 992, 992, 993, 991 -RCOU, 123991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 123991, 0.2312638, 0.2121029, -0.06917498, -0.5005175, 2.288168, -9.343316 -IMU2, 123991, 0.2240795, 0.1947113, -0.06226697, -0.4316813, 2.322988, -9.320822 -IMU, 124011, 0.1846781, 0.1770429, -0.07047808, -0.5521708, 2.136196, -9.560685 -IMU2, 124011, 0.1706323, 0.164768, -0.06881078, -0.5332843, 2.353472, -9.592219 -IMU, 124030, 0.1684805, 0.1263078, -0.04467219, -0.5874451, 2.215943, -9.251404 -IMU2, 124030, 0.1418551, 0.1108554, -0.04003113, -0.5281093, 2.355119, -8.99485 -IMU, 124050, 0.1232673, 0.06938791, -0.04998618, -0.5019091, 1.982788, -9.101209 -IMU2, 124050, 0.1099561, 0.06361604, -0.05488431, -0.4679245, 2.167844, -8.931154 -GPS, 3, 56704200, 1777, 11, 1.93, 14.1105941, 100.6192145, -34.84, -3.78, 0.82, 307.17, -0.14, 124060 -IMU, 124070, 0.1164952, 0.02572945, -0.03793108, -0.3957313, 2.368861, -9.301864 -IMU2, 124070, 0.1191392, 0.01624389, -0.03606318, -0.3006602, 2.488201, -9.191626 -MAG, 124080, -398, 11, 100, -86, 10, 139, 0, 0, 0 -MAG2, 124080, -261, -69, 277, 0, 0, 0, 0, 0, 0 -CTUN, 124090, 0, 0, 0, 0, -35.18, -0.06, 0.00, 0.00, 0, -3186 -ATT, 124090, 0.00, 94.78, 0.00, -7.03, 187.23, 187.23 -RCIN, 124090, 1503, 1504, 1026, 1513, 992, 992, 993, 991 -RCOU, 124090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124090, 0.08194517, 0.001446284, -0.0414243, -0.4422066, 1.950729, -9.422966 -IMU2, 124090, 0.07292243, -0.005895636, -0.04684228, -0.3518168, 2.137739, -9.399728 -IMU, 124110, 0.08088872, -0.02280226, -0.02706699, -0.3405564, 2.106317, -9.137671 -IMU2, 124110, 0.06533508, -0.03298128, -0.03185851, -0.3781151, 2.295452, -9.013756 -IMU, 124130, 0.05848244, -0.02949471, -0.03016867, -0.519916, 1.740112, -9.125987 -IMU2, 124130, 0.03551417, -0.03183499, -0.0366917, -0.5028955, 1.966394, -9.045195 -IMU, 124151, 0.01931011, -0.03968489, -0.02180996, -0.4312168, 2.333354, -9.017573 -IMU2, 124151, 0.01297318, -0.04606147, -0.02572882, -0.3508986, 2.450732, -8.978358 -IMU, 124170, 0.006101049, -0.0493395, -0.01714298, -0.5370484, 1.974408, -9.185822 -IMU2, 124170, -0.01048513, -0.05832528, -0.01934336, -0.4830287, 2.094759, -9.205865 -MAG, 124180, -400, 11, 99, -86, 10, 139, 0, 0, 0 -MAG2, 124180, -261, -70, 278, 0, 0, 0, 0, 0, 0 -CTUN, 124190, 0, 0, 0, 0, -36.88, -0.12, 0.00, 0.00, 0, -3280 -ATT, 124190, 0.00, 94.45, 0.00, -6.98, 187.14, 187.14 -RCIN, 124190, 1503, 1504, 1026, 1511, 992, 993, 992, 992 -RCOU, 124191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124191, -0.02000491, -0.05800029, -0.02753144, -0.3908171, 2.366986, -9.202068 -IMU2, 124191, -0.02490067, -0.06619585, -0.02164066, -0.2890516, 2.542569, -9.225578 -IMU, 124210, 0.005525088, -0.09088598, -0.03242238, -0.8693347, 2.208242, -9.092064 -IMU2, 124210, -0.002164714, -0.1086551, -0.03384673, -0.8304337, 2.281619, -9.066588 -IMU, 124230, 0.001884185, -0.1129146, -0.053835, -0.6062762, 2.388783, -9.316062 -IMU2, 124230, 0.008807406, -0.1294104, -0.0533888, -0.5037677, 2.604157, -9.187049 -IMU, 124250, 0.03398881, -0.1176285, -0.05030797, -0.8403156, 2.500767, -9.5103 -IMU2, 124250, 0.04366843, -0.1260757, -0.05568121, -0.8282583, 2.65324, -9.47875 -GPS, 3, 56704400, 1777, 11, 1.93, 14.1105971, 100.6192086, -38.24, -3.50, 1.07, 307.17, -0.29, 124260 -IMU, 124270, 0.04368337, -0.09668414, -0.06499241, -0.8654817, 2.243617, -9.447104 -IMU2, 124270, 0.04647755, -0.1037214, -0.06790011, -0.7623934, 2.387722, -9.509799 -MAG, 124280, -399, 11, 102, -86, 10, 139, 0, 0, 0 -MAG2, 124280, -261, -72, 282, 0, 0, 0, 0, 0, 0 -CTUN, 124290, 0, 0, 0, 0, -38.59, -0.10, 0.00, 0.00, 0, -3375 -ATT, 124290, 0.00, 94.12, 0.00, -6.75, 186.71, 186.71 -RCIN, 124290, 1503, 1504, 1025, 1512, 992, 992, 993, 992 -RCOU, 124291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124291, 0.09185395, -0.09474425, -0.06803698, -0.8632323, 2.390431, -9.498599 -IMU2, 124291, 0.09722879, -0.09642725, -0.06355726, -0.8255169, 2.512276, -9.529674 -IMU, 124310, 0.1173991, -0.06810227, -0.0809015, -0.894812, 2.08762, -9.849269 -IMU2, 124310, 0.1071118, -0.06456398, -0.08954906, -0.8963284, 2.250588, -9.801407 -IMU, 124330, 0.1240045, -0.04616319, -0.07697618, -0.9267061, 2.353178, -9.771173 -IMU2, 124330, 0.1141889, -0.05165381, -0.06974868, -0.9544163, 2.505482, -9.674075 -IMU, 124351, 0.1280078, -0.02964891, -0.07041806, -1.16522, 1.803393, -9.64481 -IMU2, 124351, 0.1148764, -0.02949188, -0.07473294, -1.240636, 1.969518, -9.652501 -IMU, 124370, 0.09174532, -0.01302591, -0.08168343, -0.9550468, 2.240875, -9.602235 -IMU2, 124370, 0.08627485, -0.01652953, -0.08355505, -0.8981864, 2.393281, -9.674908 -MAG, 124380, -396, 8, 104, -86, 10, 139, 0, 0, 0 -MAG2, 124380, -259, -73, 283, 0, 0, 0, 0, 0, 0 -CTUN, 124390, 0, 0, 0, 0, -40.32, 0.04, 0.00, 0.00, 0, -3466 -ATT, 124391, 0.00, 94.23, 0.00, -6.41, 186.65, 186.65 -RCIN, 124391, 1503, 1503, 1027, 1512, 992, 993, 992, 992 -RCOU, 124391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124391, 0.09649843, -0.01088369, -0.06781178, -1.234856, 2.193789, -9.792949 -IMU2, 124391, 0.0804094, -0.01155972, -0.07128785, -1.231646, 2.416811, -9.794872 -IMU, 124411, 0.07561171, -0.01090524, -0.08405469, -1.114588, 2.055108, -9.680913 -IMU2, 124411, 0.07247816, -0.01345743, -0.08466018, -1.049053, 2.329827, -9.691153 -IMU, 124430, 0.08555172, -0.02326359, -0.07869528, -1.180771, 2.202373, -9.478332 -IMU2, 124430, 0.08239006, -0.03241345, -0.06999188, -1.16448, 2.379428, -9.587965 -IMU, 124450, 0.1081422, -0.01977007, -0.08856471, -1.101415, 1.637083, -9.623309 -IMU2, 124450, 0.09018642, -0.02615882, -0.0874775, -1.163057, 1.810842, -9.416042 -GPS, 3, 56704600, 1777, 11, 1.93, 14.1106013, 100.6192023, -41.69, -3.40, 1.32, 301.95, -0.34, 124460 -IMU, 124471, 0.1256467, -0.002243135, -0.09649307, -0.8326613, 1.988664, -9.551085 -IMU2, 124471, 0.1228123, -0.006931346, -0.09718277, -0.7597195, 2.109104, -9.485934 -MAG, 124480, -395, 7, 106, -86, 10, 139, 0, 0, 0 -MAG2, 124480, -259, -75, 283, 0, 0, 0, 0, 0, 0 -CTUN, 124490, 0, 0, 0, 0, -42.05, -0.10, 0.00, 0.00, 0, -3555 -ATT, 124491, 0.00, 94.21, 0.00, -6.02, 186.77, 186.77 -RCIN, 124491, 1504, 1504, 1026, 1512, 992, 993, 992, 992 -RCOU, 124491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124491, 0.0893598, 0.03123143, -0.08758125, -1.111266, 2.094621, -9.578073 -IMU2, 124491, 0.09145891, 0.03296746, -0.0914868, -1.181849, 2.27178, -9.594206 -IMU, 124510, 0.04625759, 0.04971865, -0.1016859, -1.171736, 2.054543, -9.592256 -IMU2, 124510, 0.03549256, 0.05074297, -0.09665325, -0.9962416, 2.326583, -9.410513 -IMU, 124530, 0.05076827, 0.03210916, -0.09609598, -1.202663, 1.885532, -9.445352 -IMU2, 124530, 0.05627268, 0.02978033, -0.09364604, -1.16764, 2.049491, -9.483685 -IMU, 124550, 0.0423492, 0.02130653, -0.1137941, -1.231923, 1.450665, -9.663721 -IMU2, 124550, 0.03336445, 0.02281481, -0.1077358, -1.217395, 1.629329, -9.5606 -IMU, 124571, 0.0505509, 0.00143487, -0.1136297, -1.104598, 1.89024, -9.751956 -IMU2, 124571, 0.04520645, 0.005562892, -0.1054757, -0.9931323, 1.956106, -9.75007 -MAG, 124580, -397, 6, 105, -86, 10, 139, 0, 0, 0 -MAG2, 124580, -259, -77, 282, 0, 0, 0, 0, 0, 0 -CTUN, 124590, 0, 0, 0, 0, -43.79, -0.07, 0.00, 0.00, 0, -3640 -ATT, 124590, 0.00, 93.90, 0.00, -5.50, 187.07, 187.07 -RCIN, 124590, 1503, 1504, 1028, 1512, 992, 992, 993, 991 -RCOU, 124591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124591, 0.02003906, 0.002252333, -0.1025613, -1.138172, 1.994426, -9.491632 -IMU2, 124591, 0.01629454, -0.002532266, -0.1028935, -1.198382, 1.999054, -9.603089 -IMU, 124610, -0.01995115, 0.02199834, -0.1022358, -1.083593, 2.131942, -9.784894 -IMU2, 124610, -0.02307802, 0.02507462, -0.0962203, -1.035597, 2.29945, -9.763394 -IMU, 124631, -0.01030297, 0.015783, -0.07428963, -1.013337, 2.131745, -9.587505 -IMU2, 124631, 0.007745199, 0.009914607, -0.0711467, -1.020848, 2.304499, -9.720113 -GPS, 3, 56704800, 1777, 11, 1.93, 14.1106054, 100.6191971, -44.83, -3.46, 1.52, 299.31, -0.25, 124640 -IMU, 124650, -0.007751884, 0.02998463, -0.05907281, -0.9216791, 1.634356, -9.581984 -IMU2, 124650, -0.01584147, 0.03053621, -0.05781154, -0.9214046, 1.832451, -9.431826 -IMU, 124670, 0.0225361, 0.02442025, -0.03213274, -0.9617287, 1.860353, -9.438607 -IMU2, 124670, 0.03577067, 0.02323061, -0.0346, -0.9289138, 2.037978, -9.455422 -MAG, 124680, -396, 2, 104, -86, 10, 139, 0, 0, 0 -MAG2, 124680, -260, -79, 281, 0, 0, 0, 0, 0, 0 -CTUN, 124690, 0, 0, 0, 0, -45.53, -0.12, 0.00, 0.00, 0, -3724 -ATT, 124690, 0.00, 93.33, 0.00, -5.24, 187.33, 187.33 -RCIN, 124690, 1504, 1503, 1027, 1512, 992, 993, 992, 992 -RCOU, 124690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124690, 0.0149405, 0.02243665, -0.01046106, -1.07217, 1.989259, -9.456819 -IMU2, 124690, 0.01635196, 0.01389376, -0.008008203, -1.060534, 2.137538, -9.517042 -IMU, 124710, 0.007816399, 0.02748489, -0.004448027, -1.082046, 2.021998, -9.839367 -IMU2, 124710, 9.734184E-05, 0.02186666, -0.002175001, -0.9540278, 2.210244, -9.86739 -IMU, 124730, 0.004298193, 0.004668612, 0.01649442, -1.007012, 2.211344, -9.478398 -IMU2, 124730, -0.001832716, 0.000838032, 0.0234437, -1.011993, 2.400176, -9.554301 -IMU, 124750, 0.02776469, -0.005127028, 0.01602066, -0.9398284, 1.840197, -9.475532 -IMU2, 124750, 0.02211187, -0.000316754, 0.01286514, -0.8962525, 1.975238, -9.470582 -IMU, 124770, 0.02740668, -0.01912059, 0.02053174, -0.7278113, 2.116418, -9.459224 -IMU2, 124770, 0.02481192, -0.02776858, 0.02212732, -0.7364732, 2.254546, -9.528422 -MAG, 124780, -397, 0, 104, -86, 10, 139, 0, 0, 0 -MAG2, 124780, -260, -81, 283, 0, 0, 0, 0, 0, 0 -CTUN, 124790, 0, 0, 0, 0, -47.28, -0.14, 0.00, 0.00, 0, -3806 -ATT, 124790, 0.00, 92.89, 0.00, -5.40, 187.40, 187.40 -RCIN, 124790, 1503, 1504, 1027, 1512, 993, 992, 992, 992 -RCOU, 124791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124791, 0.0487286, -0.01742719, 0.03287468, -0.8730031, 2.02239, -9.649979 -IMU2, 124791, 0.0349171, -0.02113408, 0.02794369, -0.8627433, 2.185906, -9.563244 -IMU, 124810, 0.0279521, -0.00856081, 0.02173873, -0.9829618, 1.73559, -9.583595 -IMU2, 124810, 0.01512483, -0.007310117, 0.01848742, -0.9987487, 1.832819, -9.56201 -IMU, 124831, 0.01745647, -0.01103165, 0.02240632, -0.827952, 1.86999, -9.335504 -IMU2, 124831, 0.0006063785, -0.01467996, 0.02596214, -0.7435614, 2.06074, -9.247547 -IMU, 124851, 0.002428398, -0.02547261, 0.02450678, -0.9420162, 1.902169, -9.395121 -IMU2, 124851, -0.0004332159, -0.02847452, 0.02366173, -0.9586194, 2.041965, -9.357335 -GPS, 3, 56705000, 1777, 11, 1.93, 14.1106075, 100.6191941, -48.68, -3.63, 1.09, 299.31, -0.2, 124860 -IMU, 124870, -0.02700602, -0.03944201, 0.01776271, -0.838176, 2.011589, -9.480691 -IMU2, 124870, -0.04413154, -0.05579888, 0.01881386, -0.7863791, 2.204834, -9.421756 -MAG, 124880, -396, 2, 104, -86, 10, 139, 0, 0, 0 -MAG2, 124880, -260, -79, 282, 0, 0, 0, 0, 0, 0 -CTUN, 124890, 0, 0, 0, 0, -49.03, -0.04, 0.00, 0.00, 0, -3885 -DU32, 7, 262233 -CURR, 124890, 0, 10381, 1534, 119, 5322, 28.37431 -ATT, 124890, 0.00, 92.36, 0.00, -5.60, 187.31, 187.31 -RCIN, 124890, 1503, 1504, 1025, 1512, 993, 992, 992, 992 -RCOU, 124890, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124891, -0.02463084, -0.06007795, 0.0237191, -0.8428139, 2.070539, -9.563538 -IMU2, 124891, -0.03399976, -0.06463611, 0.0270499, -0.8133802, 2.211137, -9.596053 -IMU, 124911, 0.0008453857, -0.07006857, 0.02000163, -0.9772233, 1.734522, -9.610729 -IMU2, 124911, -0.01083499, -0.06992552, 0.0159936, -0.9184668, 1.850401, -9.522287 -IMU, 124930, -0.002723617, -0.07012093, 0.01547557, -0.810798, 1.90576, -9.493063 -IMU2, 124930, -0.02193773, -0.06800429, 0.01502165, -0.7992427, 2.046172, -9.403396 -IMU, 124950, -0.008125661, -0.06980061, 0.02361983, -0.9612436, 2.135863, -9.405401 -IMU2, 124950, -0.01467818, -0.06859745, 0.02541402, -0.9540974, 2.274982, -9.346336 -IMU, 124970, -0.004705684, -0.06988017, 0.01490572, -0.9916476, 1.754364, -9.484797 -IMU2, 124970, -0.02183456, -0.07398292, 0.01398337, -0.9655432, 1.908887, -9.355413 -MAG, 124980, -396, 2, 107, -86, 10, 139, 0, 0, 0 -MAG2, 124980, -259, -79, 284, 0, 0, 0, 0, 0, 0 -CTUN, 124990, 0, 0, 0, 0, -50.77, -0.02, 0.00, 0.00, 0, -3962 -ATT, 124990, 0.00, 91.85, 0.00, -5.75, 186.87, 186.87 -RCIN, 124990, 1503, 1504, 1025, 1512, 992, 993, 993, 991 -RCOU, 124991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 124991, 0.001874039, -0.08447629, 0.01035666, -0.8313837, 1.963343, -9.466019 -IMU2, 124991, -0.002731096, -0.09590247, 0.008036528, -0.8377132, 2.126632, -9.393163 -IMU, 125010, 0.03378954, -0.0996695, 0.01251912, -1.022064, 2.013015, -9.375756 -IMU2, 125010, 0.03392633, -0.1009059, 0.008968482, -1.04624, 2.118252, -9.423483 -IMU, 125030, 0.01774545, -0.09685299, -0.0006423562, -1.041248, 1.804299, -9.614242 -IMU2, 125030, 0.004895043, -0.08949298, -0.006776583, -0.9382653, 2.018618, -9.667237 -GPS, 3, 56705200, 1777, 11, 1.93, 14.1106101, 100.6191903, -51.81, -3.80, 0.83, 299.31, -0.2, 125040 -IMU, 125051, 0.005174682, -0.09164371, -0.003570753, -1.160871, 1.980867, -9.570785 -IMU2, 125051, 0.006224982, -0.09607442, -0.0006875731, -1.084518, 2.121501, -9.560266 -IMU, 125070, 0.01452384, -0.09119785, -0.008284106, -1.367939, 1.871935, -9.449196 -IMU2, 125070, 0.006238118, -0.09348057, -0.01085889, -1.359161, 1.983339, -9.721893 -MAG, 125081, -394, 4, 109, -86, 10, 139, 0, 0, 0 -MAG2, 125081, -258, -77, 287, 0, 0, 0, 0, 0, 0 -CTUN, 125090, 0, 0, 0, 0, -52.51, 0.01, 0.00, 0.00, 0, -4036 -ATT, 125091, 0.00, 91.46, 0.00, -5.80, 186.33, 186.33 -RCIN, 125091, 1502, 1504, 1026, 1512, 992, 992, 993, 992 -RCOU, 125091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 125091, 0.001813952, -0.08160252, -0.02488823, -1.0631, 1.832028, -9.340932 -IMU2, 125091, 0.0003004409, -0.08590154, -0.02375755, -1.03525, 2.025598, -9.314232 -IMU, 125110, 0.021246, -0.07175104, -0.02264027, -1.088385, 1.91841, -9.587788 -IMU2, 125110, 0.01098786, -0.07197793, -0.02518291, -1.073721, 2.02288, -9.67365 -IMU, 125130, 0.03463234, -0.04636079, -0.03060802, -1.221084, 1.79547, -9.778042 -IMU2, 125130, 0.03065075, -0.04599746, -0.03258538, -1.2475, 1.931882, -9.695873 -IMU, 125150, 0.01041876, -0.02491471, -0.04600776, -1.082186, 1.837803, -9.57405 -IMU2, 125150, -0.002467625, -0.02576911, -0.04537375, -1.099948, 1.947269, -9.438146 -IMU, 125171, 0.001126511, -0.01347687, -0.04751267, -1.198769, 1.877713, -9.40558 -IMU2, 125171, -0.003162172, -0.01422749, -0.05048951, -1.153666, 2.014159, -9.331002 -MAG, 125180, -394, 2, 112, -86, 10, 139, 0, 0, 0 -MAG2, 125180, -256, -80, 289, 0, 0, 0, 0, 0, 0 -CTUN, 125190, 0, 0, 0, 0, -54.23, 0.00, 0.00, 0.00, 0, -4107 -ATT, 125191, 0.00, 91.02, 0.00, -5.64, 186.16, 186.16 -RCIN, 125191, 1503, 1504, 1025, 1513, 992, 992, 993, 991 -RCOU, 125191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 -IMU, 125191, -0.001921276, -0.01156685, -0.06012962, -1.350242, 1.79443, -9.578811 -IMU2, 125191, -0.003243731, -0.01071055, -0.05637529, -1.302584, 1.907837, -9.582116 -IMU, 125210, -0.01965771, -0.01934712, -0.07203884, -1.055922, 1.947788, -9.649301 -IMU2, 125210, -0.01838078, -0.02487617, -0.07532278, -1.015742, 2.09629, -9.687523 -IMU, 125230, -0.003269086, -0.02289573, -0.06722176, -1.107607, 2.013193, -9.496122 -IMU2, 125230, -0.003808955, -0.02938985, -0.05879949, -1.139975, 2.113212, -9.425806 -IMU, 125250, 0.01602939, -0.03228795, -0.06954374, -1.409379, 1.827114, -9.650491 -IMU2, 125250, 0.009164467, -0.04113919, -0.06790464, -1.360331, 1.930157, -9.634181 -GPS, 3, 56705400, 1777, 11, 1.93, 14.1106147, 100.619185, -55.59, -4.00, 0.98, 299.31, -0.18, 125260 -IMU, 125270, 0.0211044, -0.04707771, -0.07547536, -1.24588, 2.0423, -9.504646 -IMU2, 125270, 0.01970118, -0.05647173, -0.07288989, -1.291565, 2.193253, -9.443418 -MAG, 125280, -394, 0, 112, -86, 10, 139, 0, 0, 0 -MAG2, 125280, -257, -80, 290, 0, 0, 0, 0, 0, 0 -CTUN, 125290, 0, 0, 0, 0, -55.94, -0.02, 0.00, 0.00, 0, -4176 -ERR, 12, 1 -EV, 11 diff --git a/Tools/LogAnalyzer/examples/robert_lefebvre_octo_PM.log b/Tools/LogAnalyzer/examples/robert_lefebvre_octo_PM.log deleted file mode 100644 index cd25fc3c41a60f..00000000000000 --- a/Tools/LogAnalyzer/examples/robert_lefebvre_octo_PM.log +++ /dev/null @@ -1,4750 +0,0 @@ -1 - -ArduCopter V3.0.1 (5c6503e2) -Free RAM: 1331 -APM 2 -FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format -FMT, 129, 23, PARM, Nf, Name,Value -FMT, 130, 35, GPS, BIBcLLeeEe, Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs -FMT, 131, 27, IMU, ffffff, GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 132, 67, MSG, Z, Message -FMT, 9, 19, CURR, hIhhhf, Thr,ThrInt,Volt,Curr,Vcc,CurrTot -FMT, 11, 19, MOT, hhhhhhhh, Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,Mot7,Mot8 -FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch -FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit -FMT, 4, 25, CTUN, hcefhhhhh, ThrIn,SonAlt,BarAlt,WPAlt,NavThr,AngBst,CRate,ThrOut,DCRate -FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 6, 17, PM, BBBHHIhB, RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr -FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng -FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw -FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng -FMT, 3, 6, MODE, Mh, Mode,ThrCrs -FMT, 10, 3, STRT, , -FMT, 13, 4, EV, B, Id -FMT, 20, 6, D16, Bh, Id,Value -FMT, 21, 6, DU16, BH, Id,Value -FMT, 22, 8, D32, Bi, Id,Value -FMT, 23, 8, DU32, BI, Id,Value -FMT, 24, 8, DFLT, Bf, Id,Value -FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain -FMT, 16, 15, DMP, ccccCC, DCMRoll,DMPRoll,DCMPtch,DMPPtch,DCMYaw,DMPYaw -FMT, 18, 25, CAM, ILLeccC, GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw -FMT, 19, 5, ERR, BB, Subsys,ECode -PARM, SYSID_SW_MREV, 120.000000 -PARM, SYSID_SW_TYPE, 10.000000 -PARM, SYSID_THISMAV, 1.000000 -PARM, SYSID_MYGCS, 255.000000 -PARM, SERIAL3_BAUD, 57.000000 -PARM, TELEM_DELAY, 0.000000 -PARM, RTL_ALT, 1000.000000 -PARM, SONAR_ENABLE, 0.000000 -PARM, SONAR_TYPE, 0.000000 -PARM, SONAR_GAIN, 0.200000 -PARM, BATT_MONITOR, 4.000000 -PARM, FS_BATT_ENABLE, 0.000000 -PARM, FS_GPS_ENABLE, 1.000000 -PARM, FS_GCS_ENABLE, 0.000000 -PARM, VOLT_DIVIDER, 10.000000 -PARM, AMP_PER_VOLT, 18.002001 -PARM, BATT_CAPACITY, 1760.000000 -PARM, MAG_ENABLE, 1.000000 -PARM, FLOW_ENABLE, 0.000000 -PARM, LOW_VOLT, 10.500000 -PARM, SUPER_SIMPLE, 0.000000 -PARM, RTL_ALT_FINAL, 0.000000 -PARM, BATT_VOLT_PIN, 13.000000 -PARM, BATT_CURR_PIN, 12.000000 -PARM, RSSI_PIN, -1.000000 -PARM, THR_ACC_ENABLE, 1.000000 -PARM, WP_YAW_BEHAVIOR, 2.000000 -PARM, WP_TOTAL, 14.000000 -PARM, WP_INDEX, 0.000000 -PARM, CIRCLE_RADIUS, 10.000000 -PARM, CIRCLE_RATE, 5.000000 -PARM, RTL_LOIT_TIME, 5000.000000 -PARM, LAND_SPEED, 50.000000 -PARM, PILOT_VELZ_MAX, 250.000000 -PARM, THR_MIN, 130.000000 -PARM, THR_MAX, 1000.000000 -PARM, FS_THR_ENABLE, 0.000000 -PARM, FS_THR_VALUE, 975.000000 -PARM, TRIM_THROTTLE, 260.000000 -PARM, THR_MID, 300.000000 -PARM, FLTMODE1, 1.000000 -PARM, FLTMODE2, 6.000000 -PARM, FLTMODE3, 0.000000 -PARM, FLTMODE4, 5.000000 -PARM, FLTMODE5, 0.000000 -PARM, FLTMODE6, 2.000000 -PARM, SIMPLE, 0.000000 -PARM, LOG_BITMASK, 830.000000 -PARM, TOY_RATE, 1.000000 -PARM, ESC, 0.000000 -PARM, TUNE, 0.000000 -PARM, TUNE_LOW, 0.000000 -PARM, TUNE_HIGH, 10000.000000 -PARM, FRAME, 1.000000 -PARM, CH7_OPT, 9.000000 -PARM, CH8_OPT, 0.000000 -PARM, ARMING_CHECK, 1.000000 -PARM, RC1_MIN, 1111.000000 -PARM, RC1_TRIM, 1524.000000 -PARM, RC1_MAX, 1936.000000 -PARM, RC1_REV, 1.000000 -PARM, RC1_DZ, 30.000000 -PARM, RC2_MIN, 1110.000000 -PARM, RC2_TRIM, 1521.000000 -PARM, RC2_MAX, 1929.000000 -PARM, RC2_REV, 1.000000 -PARM, RC2_DZ, 30.000000 -PARM, RC3_MIN, 1113.000000 -PARM, RC3_TRIM, 1476.000000 -PARM, RC3_MAX, 1930.000000 -PARM, RC3_REV, 1.000000 -PARM, RC3_DZ, 30.000000 -PARM, RC4_MIN, 1115.000000 -PARM, RC4_TRIM, 1524.000000 -PARM, RC4_MAX, 1942.000000 -PARM, RC4_REV, 1.000000 -PARM, RC4_DZ, 40.000000 -PARM, RC5_MIN, 1151.000000 -PARM, RC5_TRIM, 1676.000000 -PARM, RC5_MAX, 1829.000000 -PARM, RC5_REV, 1.000000 -PARM, RC5_DZ, 0.000000 -PARM, RC5_FUNCTION, 0.000000 -PARM, RC6_MIN, 971.000000 -PARM, RC6_TRIM, 1473.000000 -PARM, RC6_MAX, 2078.000000 -PARM, RC6_REV, 1.000000 -PARM, RC6_DZ, 0.000000 -PARM, RC6_FUNCTION, 0.000000 -PARM, RC7_MIN, 969.000000 -PARM, RC7_TRIM, 970.000000 -PARM, RC7_MAX, 1884.000000 -PARM, RC7_REV, 1.000000 -PARM, RC7_DZ, 0.000000 -PARM, RC7_FUNCTION, 0.000000 -PARM, RC8_MIN, 968.000000 -PARM, RC8_TRIM, 970.000000 -PARM, RC8_MAX, 1856.000000 -PARM, RC8_REV, 1.000000 -PARM, RC8_DZ, 0.000000 -PARM, RC8_FUNCTION, 0.000000 -PARM, RC10_MIN, 1100.000000 -PARM, RC10_TRIM, 1500.000000 -PARM, RC10_MAX, 1900.000000 -PARM, RC10_REV, 1.000000 -PARM, RC10_DZ, 0.000000 -PARM, RC10_FUNCTION, 0.000000 -PARM, RC11_MIN, 1100.000000 -PARM, RC11_TRIM, 1500.000000 -PARM, RC11_MAX, 1900.000000 -PARM, RC11_REV, 1.000000 -PARM, RC11_DZ, 0.000000 -PARM, RC11_FUNCTION, 7.000000 -PARM, RC_SPEED, 490.000000 -PARM, ACRO_P, 4.500000 -PARM, AXIS_ENABLE, 1.000000 -PARM, ACRO_BAL_ROLL, 200.000000 -PARM, ACRO_BAL_PITCH, 200.000000 -PARM, ACRO_TRAINER, 1.000000 -PARM, LED_MODE, 9.000000 -PARM, RATE_RLL_P, 0.070000 -PARM, RATE_RLL_I, 1.000000 -PARM, RATE_RLL_D, 0.006000 -PARM, RATE_RLL_IMAX, 4500.000000 -PARM, RATE_PIT_P, 0.070000 -PARM, RATE_PIT_I, 1.000000 -PARM, RATE_PIT_D, 0.006000 -PARM, RATE_PIT_IMAX, 4500.000000 -PARM, RATE_YAW_P, 0.200000 -PARM, RATE_YAW_I, 0.020000 -PARM, RATE_YAW_D, 0.000000 -PARM, RATE_YAW_IMAX, 800.000000 -PARM, LOITER_LAT_P, 1.000000 -PARM, LOITER_LAT_I, 0.500000 -PARM, LOITER_LAT_D, 0.000000 -PARM, LOITER_LAT_IMAX, 400.000000 -PARM, LOITER_LON_P, 1.000000 -PARM, LOITER_LON_I, 0.500000 -PARM, LOITER_LON_D, 0.000000 -PARM, LOITER_LON_IMAX, 400.000000 -PARM, THR_RATE_P, 6.000000 -PARM, THR_RATE_I, 0.000000 -PARM, THR_RATE_D, 0.000000 -PARM, THR_RATE_IMAX, 300.000000 -PARM, THR_ACCEL_P, 1.200000 -PARM, THR_ACCEL_I, 0.500000 -PARM, THR_ACCEL_D, 0.000000 -PARM, THR_ACCEL_IMAX, 5000.000000 -PARM, OF_RLL_P, 2.500000 -PARM, OF_RLL_I, 0.500000 -PARM, OF_RLL_D, 0.120000 -PARM, OF_RLL_IMAX, 100.000000 -PARM, OF_PIT_P, 2.500000 -PARM, OF_PIT_I, 0.500000 -PARM, OF_PIT_D, 0.120000 -PARM, OF_PIT_IMAX, 100.000000 -PARM, STB_RLL_P, 3.500000 -PARM, STB_RLL_I, 0.000000 -PARM, STB_RLL_IMAX, 800.000000 -PARM, STB_PIT_P, 3.500000 -PARM, STB_PIT_I, 0.000000 -PARM, STB_PIT_IMAX, 800.000000 -PARM, STB_YAW_P, 3.000000 -PARM, STB_YAW_I, 0.000000 -PARM, STB_YAW_IMAX, 800.000000 -PARM, THR_ALT_P, 1.000000 -PARM, THR_ALT_I, 0.000000 -PARM, THR_ALT_IMAX, 300.000000 -PARM, HLD_LAT_P, 1.000000 -PARM, HLD_LAT_I, 0.000000 -PARM, HLD_LAT_IMAX, 3000.000000 -PARM, HLD_LON_P, 1.000000 -PARM, HLD_LON_I, 0.000000 -PARM, HLD_LON_IMAX, 3000.000000 -PARM, CAM_TRIGG_TYPE, 1.000000 -PARM, CAM_DURATION, 10.000000 -PARM, CAM_SERVO_ON, 1300.000000 -PARM, CAM_SERVO_OFF, 1100.000000 -PARM, COMPASS_OFS_X, -20.490345 -PARM, COMPASS_OFS_Y, 46.709824 -PARM, COMPASS_OFS_Z, -5.120774 -PARM, COMPASS_DEC, 0.000000 -PARM, COMPASS_LEARN, 0.000000 -PARM, COMPASS_USE, 1.000000 -PARM, COMPASS_AUTODEC, 1.000000 -PARM, COMPASS_MOTCT, 0.000000 -PARM, COMPASS_MOT_X, 0.000000 -PARM, COMPASS_MOT_Y, 0.000000 -PARM, COMPASS_MOT_Z, 0.000000 -PARM, COMPASS_ORIENT, 0.000000 -PARM, INS_PRODUCT_ID, 88.000000 -PARM, INS_ACCSCAL_X, 0.992788 -PARM, INS_ACCSCAL_Y, 1.001470 -PARM, INS_ACCSCAL_Z, 0.976210 -PARM, INS_ACCOFFS_X, -0.019376 -PARM, INS_ACCOFFS_Y, 0.362242 -PARM, INS_ACCOFFS_Z, 1.370947 -PARM, INS_GYROFFS_X, -0.001698 -PARM, INS_GYROFFS_Y, 0.581989 -PARM, INS_GYROFFS_Z, 0.015170 -PARM, INS_MPU6K_FILTER, 20.000000 -PARM, INAV_TC_XY, 2.500000 -PARM, INAV_TC_Z, 8.000000 -PARM, WPNAV_SPEED, 1000.000000 -PARM, WPNAV_RADIUS, 100.000000 -PARM, WPNAV_SPEED_UP, 250.000000 -PARM, WPNAV_SPEED_DN, 150.000000 -PARM, WPNAV_LOIT_SPEED, 1000.000000 -PARM, WPNAV_ACCEL, 200.000000 -PARM, SR0_RAW_SENS, 2.000000 -PARM, SR0_EXT_STAT, 2.000000 -PARM, SR0_RC_CHAN, 2.000000 -PARM, SR0_RAW_CTRL, 0.000000 -PARM, SR0_POSITION, 3.000000 -PARM, SR0_EXTRA1, 10.000000 -PARM, SR0_EXTRA2, 10.000000 -PARM, SR0_EXTRA3, 2.000000 -PARM, SR0_PARAMS, 50.000000 -PARM, SR3_RAW_SENS, 0.000000 -PARM, SR3_EXT_STAT, 0.000000 -PARM, SR3_RC_CHAN, 0.000000 -PARM, SR3_RAW_CTRL, 0.000000 -PARM, SR3_POSITION, 0.000000 -PARM, SR3_EXTRA1, 0.000000 -PARM, SR3_EXTRA2, 0.000000 -PARM, SR3_EXTRA3, 0.000000 -PARM, SR3_PARAMS, 0.000000 -PARM, AHRS_GPS_GAIN, 1.000000 -PARM, AHRS_GPS_USE, 1.000000 -PARM, AHRS_YAW_P, 0.100000 -PARM, AHRS_RP_P, 0.100000 -PARM, AHRS_WIND_MAX, 0.000000 -PARM, AHRS_TRIM_X, 0.003997 -PARM, AHRS_TRIM_Y, 0.021683 -PARM, AHRS_TRIM_Z, 0.000000 -PARM, AHRS_ORIENTATION, 0.000000 -PARM, AHRS_COMP_BETA, 0.100000 -PARM, AHRS_GPS_MINSATS, 6.000000 -PARM, MNT_MODE, 3.000000 -PARM, MNT_RETRACT_X, 0.000000 -PARM, MNT_RETRACT_Y, 0.000000 -PARM, MNT_RETRACT_Z, 0.000000 -PARM, MNT_NEUTRAL_X, 0.000000 -PARM, MNT_NEUTRAL_Y, 0.000000 -PARM, MNT_NEUTRAL_Z, 0.000000 -PARM, MNT_CONTROL_X, 0.000000 -PARM, MNT_CONTROL_Y, 0.000000 -PARM, MNT_CONTROL_Z, 0.000000 -PARM, MNT_STAB_ROLL, 0.000000 -PARM, MNT_STAB_TILT, 0.000000 -PARM, MNT_STAB_PAN, 0.000000 -PARM, MNT_RC_IN_ROLL, 0.000000 -PARM, MNT_ANGMIN_ROL, -4500.000000 -PARM, MNT_ANGMAX_ROL, 4500.000000 -PARM, MNT_RC_IN_TILT, 8.000000 -PARM, MNT_ANGMIN_TIL, -4500.000000 -PARM, MNT_ANGMAX_TIL, 4500.000000 -PARM, MNT_RC_IN_PAN, 0.000000 -PARM, MNT_ANGMIN_PAN, -4500.000000 -PARM, MNT_ANGMAX_PAN, 4500.000000 -PARM, MNT_JSTICK_SPD, 0.000000 -PARM, GND_ABS_PRESS, 101566.970000 -PARM, GND_TEMP, 21.610104 -PARM, SCHED_DEBUG, 0.000000 -PARM, FENCE_ENABLE, 0.000000 -PARM, FENCE_TYPE, 3.000000 -PARM, FENCE_ACTION, 1.000000 -PARM, FENCE_ALT_MAX, 30.000000 -PARM, FENCE_RADIUS, 30.000000 -PARM, MOT_TCRV_ENABLE, 1.000000 -PARM, MOT_TCRV_MIDPCT, 52.000000 -PARM, MOT_TCRV_MAXPCT, 93.000000 -D32, 9, 11122 -EV, 10 -ERR, 7, 1 -CTUN, 0, 0.00, -0.01, 0.000000, 0, 0, 34, 0, 0 -DU32, 7, 133308 -CURR, 0, 0, 1499, 2, 4940, 0.439707 -ATT, 0.00, 0.47, 0.00, -8.53, 0.00, 111.24, 111.24 -CTUN, 0, 0.00, -0.07, 0.000000, 0, 0, 34, 0, 0 -ATT, 0.00, 0.47, 0.00, -8.54, 0.00, 111.26, 111.26 -CTUN, 132, 0.00, -0.08, 0.000000, 0, 0, 35, 0, 0 -EV, 15 -ATT, 0.00, 0.47, 0.00, -8.54, 0.00, 111.27, 111.27 -CTUN, 152, 0.00, -0.02, 0.000000, 0, 0, 35, 140, 0 -ATT, 0.00, 0.51, 0.00, -8.51, 0.00, 111.25, 111.27 -CTUN, 152, 0.00, -0.05, 0.000000, 0, 0, 36, 140, 0 -ATT, 0.00, 0.50, 0.00, -8.46, 0.00, 111.09, 111.27 -CTUN, 152, 0.00, 0.02, 0.000000, 0, 0, 37, 139, 0 -ATT, 0.00, 0.56, 0.00, -7.94, 0.00, 110.96, 111.27 -CTUN, 0, 0.00, 0.11, 0.000000, 0, 0, 39, 0, 0 -ATT, 0.00, 0.61, 0.00, -6.40, 0.00, 110.69, 110.69 -CTUN, 0, 0.00, -0.03, 0.000000, 0, 0, 38, 0, 0 -ATT, 0.00, 0.60, 0.00, -5.49, 0.00, 110.53, 110.53 -CTUN, 0, 0.00, -0.13, 0.000000, 0, 0, 36, 0, 0 -ATT, 0.00, 0.63, 0.00, -6.82, 0.00, 110.55, 110.55 -CTUN, 0, 0.00, 0.00, 0.000000, 0, 0, 38, 0, 0 -ATT, 0.00, 0.63, 0.00, -6.82, 0.00, 110.58, 110.58 -CTUN, 0, 0.00, -0.05, 0.000000, 0, 0, 38, 0, 0 -DU32, 7, 133308 -CURR, 0, 555, 1511, 2, 4984, 1.664896 -ATT, 0.00, 0.62, 0.00, -7.02, 0.00, 110.59, 110.59 -CTUN, 0, 0.00, 0.03, 0.000000, 0, 0, 38, 0, 0 -ATT, 0.00, 0.62, 0.00, -7.09, 0.00, 110.62, 110.62 -CTUN, 0, 0.00, -0.06, 0.000000, 0, 0, 39, 0, 0 -ATT, 0.00, 0.62, 0.00, -7.16, 0.00, 110.65, 110.65 -CTUN, 0, 0.00, -0.07, 0.000000, 0, 0, 39, 0, 0 -ATT, 0.00, 0.61, 0.00, -7.27, 0.00, 110.67, 110.67 -CTUN, 0, 0.00, 0.00, 0.000000, 0, 0, 40, 0, 0 -ATT, 0.00, 0.61, 0.00, -7.32, 0.00, 110.68, 110.68 -CTUN, 0, 0.00, -0.06, 0.000000, 0, 0, 40, 0, 0 -ATT, 0.00, 0.60, 0.00, -7.37, 0.00, 110.69, 110.69 -CTUN, 0, 0.00, -0.05, 0.000000, 0, 0, 40, 0, 0 -ATT, 0.00, 0.61, 0.00, -7.41, 0.00, 110.73, 110.73 -EV, 15 -CTUN, 145, 0.00, 0.01, 0.000000, 0, 0, 40, 135, 0 -ATT, 0.00, 0.59, -0.11, -7.45, 0.00, 110.74, 110.71 -CTUN, 187, 0.00, 0.02, 0.000000, 0, 0, 40, 153, 0 -ATT, 0.00, 0.58, -0.59, -7.43, 0.00, 110.71, 110.71 -CTUN, 204, 0.00, -0.16, 0.000000, 0, 0, 41, 163, 0 -ATT, 0.00, 0.57, -0.47, -7.11, 0.00, 110.59, 110.71 -CTUN, 202, 0.00, -0.08, 0.000000, 0, 0, 41, 163, 0 -DU32, 7, 133372 -CURR, 202, 1169, 1461, 907, 4940, 2.320214 -ATT, 0.00, 0.55, -0.47, -6.39, 0.00, 110.45, 110.71 -CTUN, 202, 0.00, -0.01, 0.000000, 0, 0, 42, 163, 0 -ATT, 0.00, 0.39, -0.35, -4.09, 0.00, 110.23, 110.71 -CTUN, 206, 0.00, 0.30, 0.000000, 0, 0, 45, 164, 0 -ATT, 0.00, 0.08, -0.23, -2.21, 0.00, 110.15, 110.71 -CTUN, 218, 0.00, -0.22, 0.000000, 0, 0, 44, 169, 0 -CTUN, 228, 0.00, -0.53, 0.000000, 0, 0, 41, 174, 0 -ATT, 0.00, 0.07, -1.53, -1.56, 0.00, 110.07, 110.71 -CTUN, 228, 0.00, -0.39, 0.000000, 0, 0, 41, 174, 0 -ATT, 0.00, 0.04, -4.01, -1.63, 0.00, 109.98, 110.71 -CTUN, 230, 0.00, -0.41, 0.000000, 0, 0, 41, 175, 0 -ATT, 0.00, 0.11, -5.43, -1.96, 0.00, 109.91, 110.71 -CTUN, 251, 0.00, -0.41, 0.000000, 0, 0, 39, 184, 0 -ATT, 0.00, 0.20, -5.66, -2.55, 0.00, 109.88, 110.71 -CTUN, 264, 0.00, -0.29, 0.000000, 0, 0, 40, 191, 0 -ATT, 0.00, 0.19, -6.61, -3.16, 0.00, 109.83, 110.71 -CTUN, 282, 0.00, -0.55, 0.000000, 0, 0, 39, 199, 0 -ATT, 0.00, 0.20, -6.96, -3.93, 0.00, 109.83, 110.71 -CTUN, 299, 0.00, -0.70, 0.000000, 0, 0, 40, 207, 0 -ATT, 0.82, 0.22, -7.32, -4.46, 0.00, 109.71, 110.71 -CTUN, 317, 0.00, -0.53, 0.000000, 0, 0, 40, 214, 0 -ATT, 2.47, 0.15, -7.32, -4.95, 0.00, 109.66, 110.71 -CTUN, 331, 0.00, -1.12, 0.000000, 0, 0, 39, 222, 0 -ATT, 2.94, 0.46, -7.08, -5.77, 0.00, 109.60, 110.71 -DU32, 7, 133372 -CURR, 332, 3217, 1466, 895, 5028, 4.198554 -CTUN, 335, 0.00, -0.78, 0.000000, 0, 0, 39, 223, 0 -ATT, 3.18, 0.94, -5.43, -6.59, 0.00, 109.53, 110.71 -CTUN, 341, 0.00, -0.76, 0.000000, 0, 0, 39, 225, 0 -ATT, 3.18, 1.60, -2.24, -6.66, 0.00, 109.59, 110.71 -CTUN, 347, 0.00, -0.74, 0.000000, 0, 0, 39, 228, 0 -ATT, 2.70, 2.17, -0.11, -5.39, 0.00, 109.71, 110.71 -CTUN, 348, 0.00, -0.83, 0.000000, 0, 0, 40, 230, 0 -ATT, 1.41, 2.33, 0.00, -4.05, 0.00, 109.81, 110.71 -CTUN, 354, 0.00, -0.90, 0.000000, 0, 0, 40, 231, 0 -ATT, 1.41, 2.13, 0.00, -2.71, 0.00, 109.89, 110.71 -CTUN, 355, 0.00, -0.89, 0.000000, 0, 0, 39, 232, 0 -ATT, 1.29, 1.87, 0.00, -1.60, 0.00, 109.91, 110.71 -CTUN, 357, 0.00, -0.88, 0.000000, 0, 0, 38, 234, 0 -ATT, 1.76, 1.97, 0.00, -0.92, 0.00, 109.77, 110.71 -CTUN, 359, 0.00, -0.46, 0.000000, 0, 0, 38, 235, 0 -ATT, 1.76, 1.81, 0.00, -0.38, 0.00, 109.85, 110.71 -CTUN, 362, 0.00, -0.42, 0.000000, 0, 0, 36, 236, 0 -EV, 16 -ATT, 2.23, 2.08, 0.00, -0.50, 0.00, 109.74, 110.71 -CTUN, 367, 0.00, -0.68, 0.000000, 0, 0, 36, 238, 0 -ATT, 2.23, 1.90, 0.00, -0.51, 0.00, 109.74, 110.71 -CTUN, 370, 0.00, -1.55, 0.000000, 0, 0, 36, 239, 0 -DU32, 7, 166140 -CURR, 372, 5530, 1452, 937, 4918, 6.691252 -ATT, 2.12, 1.84, 0.00, -0.29, 0.00, 109.62, 110.71 -CTUN, 375, 0.00, -1.14, 0.000000, 0, 0, 36, 242, 0 -CTUN, 375, 0.00, -0.54, 0.000000, 0, 0, 34, 242, 0 -ATT, 2.23, 2.20, 0.00, 0.13, 0.00, 109.49, 110.71 -CTUN, 382, 0.00, -1.17, 0.000000, 0, 0, 34, 244, 0 -ATT, 2.23, 2.41, -0.11, 0.02, 0.00, 109.46, 110.71 -CTUN, 390, 0.00, -1.11, 0.000000, 0, 0, 35, 249, 0 -ATT, 2.23, 2.68, -0.23, 0.16, 0.00, 109.50, 110.71 -CTUN, 390, 0.00, -1.47, 0.000000, 0, 0, 35, 249, 0 -ATT, 1.88, 2.64, -0.59, 0.53, 0.00, 109.61, 110.71 -CTUN, 396, 0.00, -0.99, 0.000000, 0, 0, 34, 250, 0 -ATT, 1.29, 2.29, -1.29, 0.81, 0.00, 109.91, 110.71 -CTUN, 399, 0.00, -1.48, 0.000000, 0, 0, 32, 253, 0 -ATT, 1.06, 1.93, -1.18, -0.23, 0.00, 110.14, 110.71 -CTUN, 401, 0.00, -1.23, 0.000000, 0, 0, 31, 254, 0 -ATT, 1.53, 1.30, -1.29, -1.03, 0.00, 110.27, 110.71 -CTUN, 406, 0.00, -1.41, 0.000000, 0, 0, 32, 254, 0 -ATT, 2.23, 2.06, -1.41, -1.82, 0.00, 110.19, 110.71 -CTUN, 408, 0.00, -0.85, 0.000000, 0, 0, 31, 257, 0 -DU32, 7, 166140 -CURR, 412, 8016, 1436, 1217, 4813, 9.848795 -ATT, 2.35, 1.93, -1.18, -1.60, 0.00, 110.30, 110.71 -CTUN, 417, 0.00, -1.49, 0.000000, 0, 0, 32, 261, 0 -ATT, 2.70, 1.20, -1.18, -0.44, 0.00, 110.67, 110.71 -CTUN, 422, 0.00, -1.20, 0.000000, 0, 0, 39, 263, 0 -ATT, 2.94, 1.41, -1.18, -0.02, 0.00, 110.91, 110.71 -CTUN, 426, 0.00, -1.52, 0.000000, 0, 0, 41, 265, 0 -ATT, 2.94, 3.24, -1.18, -2.26, 0.00, 110.89, 110.71 -CTUN, 426, 0.00, -0.99, 0.000000, 0, 0, 43, 266, 0 -ATT, 3.18, 3.03, -1.06, -1.58, 0.00, 111.02, 110.71 -CTUN, 424, 0.00, -0.79, 0.000000, 0, 0, 42, 265, 0 -ATT, 3.41, 2.85, -0.47, -1.15, 0.00, 111.00, 110.71 -CTUN, 422, 0.00, -0.48, 0.000000, 0, 0, 41, 264, 0 -ATT, 3.18, 3.11, -0.23, -0.90, 0.00, 110.83, 110.71 -CTUN, 424, 0.00, 0.23, 0.000000, 0, 0, 40, 264, 0 -ATT, 2.94, 2.48, 0.00, 0.03, 0.00, 110.74, 110.71 -CTUN, 424, 0.00, 0.29, 0.000000, 0, 0, 39, 264, 0 -ATT, 2.70, 2.07, 0.00, -0.32, 0.00, 110.80, 110.71 -CTUN, 424, 0.00, 0.23, 0.000000, 0, 0, 37, 264, 0 -ATT, 0.00, 2.81, 0.00, -0.43, 0.00, 110.59, 110.71 -DU32, 7, 166140 -CURR, 424, 10390, 1433, 1325, 4984, 13.239457 -CTUN, 424, 0.00, 0.18, 0.000000, 0, 0, 34, 265, 0 -ATT, 0.00, 1.05, 0.00, 0.12, 0.00, 110.78, 110.71 -CTUN, 439, 0.00, 0.39, 0.000000, 0, 0, 33, 271, 0 -ATT, 0.00, 0.83, 0.00, -0.21, 0.00, 110.66, 110.71 -CTUN, 446, 0.00, 0.56, 0.000000, 0, 0, 33, 273, 0 -ATT, 0.00, 0.26, -0.23, 0.02, 0.00, 110.56, 110.71 -CTUN, 453, 0.00, 0.32, 0.000000, 0, 0, 37, 278, 0 -ATT, 0.00, 0.45, -2.71, -0.80, 0.00, 110.43, 110.71 -CTUN, 462, 0.00, 0.34, 0.000000, 0, 0, 42, 282, 0 -ATT, 0.00, 0.12, -5.07, -2.41, 0.00, 110.24, 110.71 -CTUN, 466, 0.00, 0.21, 0.000000, 0, 0, 49, 284, 0 -ATT, 0.00, -0.91, -6.14, -1.87, 0.00, 110.36, 110.71 -CTUN, 464, 0.00, 0.27, 0.000000, 0, 0, 59, 283, 0 -CTUN, 463, 0.00, 0.34, 0.000000, 0, 0, 69, 283, 0 -ATT, 0.00, 0.78, -6.14, -4.54, 0.00, 110.25, 110.71 -CTUN, 462, 0.00, 0.20, 0.000000, 0, 0, 76, 282, 0 -ATT, -0.23, -0.80, -2.59, -5.61, 0.00, 110.36, 110.71 -CTUN, 461, 0.00, 0.30, 0.000000, 0, 0, 81, 283, 0 -ATT, -17.15, -0.83, -1.18, -1.88, 0.00, 109.75, 110.71 -DU32, 7, 166140 -CURR, 462, 12891, 1409, 1864, 4962, 17.240412 -CTUN, 461, 0.00, 0.32, 0.000000, 0, 0, 90, 282, 0 -ATT, -24.08, -10.18, 0.00, -1.84, 0.00, 110.13, 110.71 -CTUN, 461, 0.00, 0.40, 0.000000, 0, 4, 100, 286, 0 -ATT, -24.08, -15.30, 0.00, -1.85, 0.00, 110.44, 110.71 -CTUN, 461, 0.00, 0.45, 0.000000, 0, 5, 104, 287, 0 -ATT, -6.22, -16.72, 0.00, -0.40, 0.00, 110.45, 110.71 -CTUN, 463, 0.00, 0.42, 0.000000, 0, 6, 110, 288, 0 -ATT, 0.00, -9.53, 0.00, 0.12, 0.00, 110.34, 110.71 -CTUN, 461, 0.00, 0.54, 0.000000, 0, 1, 115, 283, 0 -PM, 0, 0, 0, 3, 1001, 6017636, 16, 0 -ATT, 0.00, -5.25, 0.00, -0.81, 0.00, 110.42, 110.71 -CTUN, 463, 0.00, 0.58, 0.000000, 0, 0, 122, 283, 0 -ATT, 0.00, -4.25, 0.00, -0.45, 0.00, 110.56, 110.71 -CTUN, 461, 0.00, 0.71, 0.000000, 0, 0, 127, 282, 0 -ATT, 2.94, -3.43, 0.00, -0.23, 0.00, 110.76, 110.71 -CTUN, 460, 0.00, 0.87, 0.000000, 0, 0, 129, 282, 0 -ATT, 8.48, -0.47, 0.00, 0.02, 0.00, 110.78, 110.71 -CTUN, 450, 0.00, 0.84, 0.000000, 0, 0, 130, 277, 0 -ATT, 13.54, 3.35, -0.70, 0.01, 0.00, 110.85, 110.71 -CTUN, 450, 0.00, 0.95, 0.000000, 0, 0, 129, 277, 0 -ATT, 20.37, 7.75, -2.71, -0.55, 0.00, 110.80, 110.71 -CTUN, 451, 0.00, 0.94, 0.000000, 0, 1, 127, 278, 0 -DU32, 7, 166140 -CURR, 450, 15715, 1424, 1514, 4876, 21.988916 -CTUN, 450, 0.00, 1.12, 0.000000, 0, 2, 124, 279, 0 -ATT, 25.44, 13.02, -5.31, -2.02, 0.00, 110.75, 110.71 -CTUN, 450, 0.00, 1.11, 0.000000, 0, 5, 120, 282, 0 -ATT, 22.50, 17.16, -8.26, -3.62, 0.00, 110.67, 110.71 -CTUN, 449, 0.00, 1.24, 0.000000, 0, 7, 117, 284, 0 -ATT, 15.19, 17.68, -9.33, -5.29, 0.00, 110.58, 110.71 -CTUN, 450, 0.00, 1.33, 0.000000, 0, 7, 113, 284, 0 -ATT, 11.19, 15.05, -8.62, -6.71, 0.00, 110.79, 110.71 -CTUN, 450, 0.00, 1.79, 0.000000, 0, 5, 111, 282, 0 -ATT, 2.94, 12.67, -5.43, -6.90, 0.00, 110.94, 110.71 -CTUN, 450, 0.00, 2.78, 0.000000, 0, 4, 110, 281, 0 -ATT, 2.23, 7.81, -4.48, -5.47, 0.00, 111.18, 110.71 -CTUN, 441, 0.00, 2.34, 0.000000, 0, 1, 110, 273, 0 -ATT, 5.89, 6.51, -4.37, -4.84, 0.00, 111.17, 110.71 -CTUN, 435, 0.00, 2.01, 0.000000, 0, 1, 109, 272, 0 -ATT, 5.77, 7.11, -5.19, -4.59, 0.00, 111.08, 110.71 -CTUN, 432, 0.00, 1.84, 0.000000, 0, 1, 105, 269, 0 -ATT, 0.94, 6.34, -4.13, -5.01, 0.00, 111.04, 110.71 -CTUN, 426, 0.00, 1.95, 0.000000, 0, 1, 99, 267, 0 -DU32, 7, 166140 -CURR, 422, 18219, 1417, 1365, 4876, 25.827288 -ATT, 0.00, 3.41, 0.00, -4.05, 0.00, 111.08, 110.71 -CTUN, 424, 0.00, 2.02, 0.000000, 0, 0, 93, 265, 0 -ATT, 0.00, 2.00, 0.00, -1.73, 0.00, 111.17, 110.71 -CTUN, 422, 0.00, 2.11, 0.000000, 0, 0, 88, 264, 0 -CTUN, 424, 0.00, 2.09, 0.000000, 0, 0, 82, 265, 0 -ATT, 0.00, 1.65, 0.00, -1.43, 0.00, 111.10, 110.71 -CTUN, 424, 0.00, 2.24, 0.000000, 0, 0, 76, 265, 0 -ATT, 0.00, 1.42, 0.00, -1.11, 0.00, 111.06, 110.71 -CTUN, 424, 0.00, 2.40, 0.000000, 0, 0, 69, 265, 0 -ATT, 0.00, 0.67, 15.47, -0.43, 0.00, 111.10, 110.71 -CTUN, 424, 0.00, 2.45, 0.000000, 0, 0, 66, 265, 0 -ATT, 0.00, 0.18, 21.42, 8.61, 0.00, 110.95, 110.71 -CTUN, 422, 0.00, 2.20, 0.000000, 0, 2, 61, 266, 0 -ATT, 0.00, 0.17, 7.38, 13.85, 0.00, 110.94, 110.71 -CTUN, 424, 0.00, 2.02, 0.000000, 0, 3, 60, 268, 0 -ATT, 0.00, 0.30, 0.00, 7.37, 0.00, 111.09, 110.71 -CTUN, 422, 0.00, 2.40, 0.000000, 0, 0, 56, 265, 0 -ATT, 0.00, 0.55, 0.00, 1.72, 0.00, 111.24, 110.71 -CTUN, 424, 0.00, 2.56, 0.000000, 0, 0, 50, 265, 0 -DU32, 7, 166140 -CURR, 424, 20871, 1422, 1301, 4897, 29.804852 -ATT, 0.00, 0.14, 0.00, 3.42, 0.00, 111.33, 110.71 -CTUN, 424, 0.00, 2.38, 0.000000, 0, 0, 46, 264, 0 -ATT, 0.00, 0.06, 0.00, 3.05, 0.00, 111.37, 110.71 -CTUN, 422, 0.00, 2.43, 0.000000, 0, 0, 41, 264, 0 -ATT, 0.00, 0.18, 0.00, 1.48, 0.00, 111.37, 110.71 -CTUN, 426, 0.00, 2.46, 0.000000, 0, 0, 34, 266, 0 -ATT, 0.00, 0.22, 0.00, 0.39, 0.00, 111.39, 110.71 -CTUN, 424, 0.00, 2.50, 0.000000, 0, 0, 28, 265, 0 -ATT, 0.00, 0.06, -8.03, 0.18, 0.00, 111.45, 110.71 -CTUN, 424, 0.00, 2.50, 0.000000, 0, 0, 22, 265, 0 -ATT, 0.00, -0.25, -11.33, -4.26, 0.00, 111.47, 110.71 -CTUN, 424, 0.00, 2.56, 0.000000, 0, 0, 18, 266, 0 -ATT, 0.00, 0.19, -14.76, -7.05, 0.00, 111.39, 110.71 -CTUN, 424, 0.00, 2.49, 0.000000, 0, 0, 12, 265, 0 -ATT, 0.00, 0.15, -14.17, -8.98, 0.00, 111.40, 110.71 -CTUN, 425, 0.00, 2.31, 0.000000, 0, 1, 8, 266, 0 -GPS, 3, 594438201, 6, 4.68, 44.0290459, -77.7367640, 3.13, 91.56, 0.00, 0.00 -ERR, 7, 0 -ATT, 0.00, 0.00, -8.26, -9.91, 0.00, 111.34, 110.71 -CTUN, 425, 0.00, 2.31, 0.000000, 0, 2, 2, 268, 0 -DU32, 7, 426236 -CURR, 425, 23258, 1433, 1398, 5006, 33.194981 -ATT, 0.00, 0.24, -4.01, -7.97, 0.00, 111.22, 110.71 -CTUN, 425, 0.00, 2.22, 0.000000, 0, 1, -2, 266, 0 -GPS, 3, 594438600, 6, 4.68, 44.0290437, -77.7367702, 3.06, 92.11, 0.75, 268.40 -CTUN, 425, 0.00, 2.25, 0.000000, 0, 0, -4, 265, 0 -ATT, 0.00, 0.14, -0.23, -5.55, 0.00, 111.13, 110.71 -CTUN, 426, 0.00, 2.25, 0.000000, 0, 0, -8, 266, 0 -ATT, -1.52, 0.17, -0.94, -3.24, 0.00, 111.04, 110.71 -GPS, 3, 594438800, 6, 4.68, 44.0290442, -77.7367750, 2.99, 92.42, 0.75, 268.40 -CTUN, 425, 0.00, 2.29, 0.000000, 0, 0, -10, 266, 0 -ATT, -5.75, -0.60, -1.41, -3.20, 0.00, 110.91, 110.71 -CTUN, 426, 0.00, 2.30, 0.000000, 0, 0, -12, 266, 0 -ATT, -6.69, -3.30, -1.41, -2.69, 0.00, 110.99, 110.71 -GPS, 3, 594439000, 6, 4.68, 44.0290416, -77.7367772, 2.92, 92.61, 0.64, 246.49 -CTUN, 426, 0.00, 2.41, 0.000000, 0, 0, -15, 266, 0 -ATT, -7.16, -4.21, -1.29, -1.94, 0.00, 110.81, 110.71 -CTUN, 426, 0.00, 2.47, 0.000000, 0, 0, -16, 265, 0 -ATT, -3.17, -5.12, -1.18, -1.67, 0.00, 110.86, 110.71 -GPS, 3, 594439200, 6, 4.68, 44.0290390, -77.7367770, 2.84, 92.73, 0.59, 216.35 -CTUN, 428, 0.00, 2.52, 0.000000, 0, 0, -20, 266, 0 -ATT, -0.11, -3.76, -0.47, -1.77, 0.00, 110.93, 110.71 -CTUN, 427, 0.00, 2.11, 0.000000, 0, 0, -22, 266, 0 -GPS, 3, 594439400, 6, 4.68, 44.0290393, -77.7367784, 2.76, 92.81, 0.25, 216.35 -ATT, 0.00, -1.85, -1.06, -1.17, -0.36, 110.78, 110.54 -CTUN, 426, 0.00, 1.93, 0.000000, 0, 0, -24, 266, 0 -ATT, 0.00, -1.79, -0.70, -1.32, -0.60, 110.63, 110.26 -CTUN, 426, 0.00, 1.86, 0.000000, 0, 0, -26, 266, 0 -GPS, 3, 594439600, 6, 4.68, 44.0290392, -77.7367791, 2.68, 92.79, 0.24, 216.35 -DU32, 7, 426236 -CURR, 428, 25916, 1420, 1354, 5006, 37.017731 -CTUN, 428, 0.00, 1.75, 0.000000, 0, 0, -28, 266, 0 -ATT, 0.00, -1.10, 0.00, -0.80, -1.21, 110.13, 109.70 -CTUN, 426, 0.00, 1.59, 0.000000, 0, 0, -30, 266, 0 -ATT, 0.00, -0.65, 0.00, -0.51, -1.34, 109.50, 109.02 -GPS, 3, 594439800, 6, 4.68, 44.0290397, -77.7367793, 2.53, 92.70, 0.04, 216.35 -CTUN, 427, 0.00, 1.81, 0.000000, 0, 0, -31, 266, 0 -ATT, 0.00, -0.47, 0.00, -0.18, -1.58, 108.77, 108.19 -CTUN, 426, 0.00, 2.07, 0.000000, 0, 0, -32, 266, 0 -ATT, 2.47, -0.20, 0.00, -0.19, -1.82, 108.03, 107.35 -GPS, 3, 594440000, 6, 4.68, 44.0290402, -77.7367792, 2.42, 92.59, 0.05, 216.35 -CTUN, 428, 0.00, 1.74, 0.000000, 0, 0, -34, 266, 0 -ATT, 4.12, 1.69, -0.94, -0.34, -1.70, 106.92, 106.35 -CTUN, 442, 0.00, 1.38, 0.000000, 0, 0, -36, 271, 0 -GPS, 3, 594440200, 6, 4.68, 44.0290411, -77.7367796, 2.30, 92.59, 0.12, 216.35 -ATT, 3.76, 2.51, -2.00, -0.79, 0.00, 106.10, 105.89 -CTUN, 457, 0.00, 1.22, 0.000000, 0, 0, -37, 280, 0 -ATT, 3.06, 2.88, -3.77, -1.70, 0.00, 105.98, 105.89 -CTUN, 457, 0.00, 1.20, 0.000000, 0, 0, -33, 280, 0 -GPS, 3, 594440400, 6, 4.68, 44.0290421, -77.7367802, 2.18, 92.64, 0.12, 216.35 -EV, 25 -CMD, 14, 0, 16, 0, 0, 0.00, 44.0290421, -77.7367802 -ATT, 0.35, 1.68, -2.71, -2.28, 0.00, 105.90, 105.89 -CTUN, 457, 0.00, 1.19, 0.000000, 0, 0, -22, 279, 0 -GPS, 3, 594440600, 6, 4.68, 44.0290427, -77.7367803, 2.03, 92.66, 0.04, 216.35 -ATT, 0.00, 1.11, -2.59, -2.65, 0.00, 105.95, 105.89 -CTUN, 455, 0.00, 1.11, 0.000000, 0, 0, -16, 280, 0 -ATT, 0.11, 1.24, -2.59, -2.88, 0.00, 105.82, 105.89 -CTUN, 455, 0.00, 1.05, 0.000000, 0, 0, -11, 279, 0 -GPS, 3, 594440800, 6, 4.68, 44.0290432, -77.7367802, 1.94, 92.63, 0.04, 216.35 -CTUN, 455, 0.00, 0.91, 0.000000, 0, 0, -5, 279, 0 -ATT, 0.00, 0.72, -2.59, -2.74, 0.00, 105.82, 105.89 -DU32, 7, 426237 -CURR, 456, 28648, 1406, 1609, 5051, 41.103027 -CTUN, 455, 0.00, 0.84, 0.000000, 0, 0, -1, 279, 0 -ATT, 0.00, 0.33, -2.24, -2.45, 0.00, 105.79, 105.89 -GPS, 3, 594441000, 6, 4.68, 44.0290440, -77.7367808, 1.87, 92.73, 0.04, 216.35 -CTUN, 455, 0.00, 0.79, 0.000000, 0, 0, 0, 279, 0 -ATT, 0.00, 0.28, 0.00, -2.07, 0.00, 105.80, 105.89 -CTUN, 455, 0.00, 0.71, 0.000000, 0, 0, 6, 279, 0 -ATT, 0.00, 0.25, 0.00, -1.04, 0.00, 105.88, 105.89 -GPS, 3, 594441200, 6, 4.68, 44.0290445, -77.7367809, 1.79, 92.82, 0.13, 216.35 -CTUN, 455, 0.00, 0.85, 0.000000, 0, 0, 10, 279, 0 -ATT, 0.00, 0.23, 0.00, -1.13, 0.00, 105.94, 105.89 -CTUN, 453, 0.00, 0.84, 0.000000, 0, 0, 14, 279, 0 -GPS, 3, 594441400, 6, 4.68, 44.0290452, -77.7367811, 1.75, 92.93, 0.13, 216.35 -ATT, 0.00, 0.13, 0.00, -0.76, 0.00, 105.97, 105.89 -CTUN, 453, 0.00, 0.76, 0.000000, 0, 0, 19, 278, 0 -ATT, 0.00, 0.09, 0.00, -0.62, 0.00, 105.98, 105.89 -CTUN, 453, 0.00, 0.75, 0.000000, 0, 0, 22, 278, 0 -GPS, 3, 594441600, 6, 4.68, 44.0290458, -77.7367811, 1.72, 93.06, 0.09, 216.35 -ATT, 0.00, 0.08, 0.00, -0.17, 0.00, 106.02, 105.89 -CTUN, 455, 0.00, 0.75, 0.000000, 0, 0, 25, 278, 0 -ATT, 0.00, 0.05, 0.00, -0.15, 0.00, 105.99, 105.89 -CTUN, 455, 0.00, 0.65, 0.000000, 0, 0, 28, 279, 0 -GPS, 3, 594441800, 6, 4.68, 44.0290463, -77.7367814, 1.70, 93.25, 0.04, 216.35 -CTUN, 455, 0.00, 0.66, 0.000000, 0, 0, 31, 279, 0 -ATT, 0.00, 0.00, 0.00, -0.34, 0.00, 106.01, 105.89 -MODE, ALT_HOLD, 269 -CTUN, 455, 0.00, 0.70, 2.010000, 0, 0, 33, 263, 0 -ATT, 0.00, -0.03, 0.00, -0.19, 0.00, 106.01, 105.89 -GPS, 3, 594442000, 6, 4.68, 44.0290473, -77.7367820, 1.68, 93.48, 0.11, 216.35 -CTUN, 455, 0.00, 0.68, 2.010000, 0, 0, 32, 279, 0 -DU32, 7, 426229 -CURR, 455, 31717, 1426, 1287, 4940, 45.729107 -ATT, 0.00, 0.20, 0.00, -0.02, 0.00, 106.04, 105.89 -CTUN, 455, 0.00, 0.75, 2.010000, 0, 0, 32, 265, 0 -ATT, 0.00, 0.07, 0.00, -0.33, 0.00, 106.01, 105.89 -GPS, 3, 594442200, 6, 4.68, 44.0290483, -77.7367826, 1.68, 93.68, 0.15, 216.35 -CTUN, 455, 0.00, 0.77, 2.010000, 0, 0, 31, 288, 0 -ATT, 0.00, 0.06, 0.00, 0.27, 0.00, 106.00, 105.89 -CTUN, 455, 0.00, 0.78, 2.010000, 0, 0, 32, 270, 0 -GPS, 3, 594442400, 6, 4.67, 44.0290496, -77.7367831, 1.67, 93.83, 0.15, 216.35 -ATT, 0.00, -0.02, 0.00, -0.25, 0.00, 106.00, 105.89 -CTUN, 477, 0.00, 0.77, 2.010000, 0, 0, 32, 278, 0 -ATT, 0.35, 0.00, 0.00, -0.02, 0.00, 105.95, 105.89 -GPS, 3, 594442600, 6, 4.67, 44.0290507, -77.7367833, 1.67, 93.93, 0.24, 216.35 -CTUN, 567, 0.00, 0.85, 2.010000, 0, 0, 32, 277, 0 -ATT, 1.64, 0.00, -1.29, -0.20, 0.00, 105.95, 105.89 -CTUN, 669, 0.00, 0.83, 2.020846, 0, 0, 33, 270, 43 -ATT, 2.00, 0.67, -2.36, -0.80, 0.00, 105.93, 105.89 -GPS, 3, 594442800, 6, 4.67, 44.0290516, -77.7367836, 1.67, 93.95, 0.37, 308.78 -CTUN, 792, 0.00, 0.87, 2.043615, 0, 0, 33, 291, 62 -ATT, 2.35, 1.60, -4.25, -1.51, 0.00, 105.98, 105.89 -CTUN, 846, 0.00, 0.92, 2.293856, 0, 0, 43, 316, 153 -GPS, 3, 594443000, 6, 4.67, 44.0290521, -77.7367834, 1.68, 93.84, 0.37, 308.78 -ATT, 2.35, 1.73, -6.61, -4.78, 0.00, 105.86, 105.89 -CTUN, 915, 0.00, 0.92, 2.473670, 0, 0, 66, 356, 182 -ATT, 2.23, 2.02, -7.08, -4.53, 0.00, 105.69, 105.89 -GPS, 3, 594443200, 6, 4.67, 44.0290528, -77.7367837, 1.75, 93.89, 0.29, 327.48 -CTUN, 961, 0.00, 1.00, 2.655006, 0, 1, 85, 282, 207 -ATT, 1.64, 1.98, -7.32, -6.19, 0.00, 105.51, 105.89 -CTUN, 978, 0.00, 1.03, 3.067259, 0, 0, 129, 318, 236 -ATT, 0.94, 1.76, -6.61, -5.39, 0.00, 105.32, 105.89 -GPS, 3, 594443400, 6, 4.67, 44.0290534, -77.7367843, 1.93, 94.06, 0.27, 330.28 -CTUN, 997, 0.00, 1.17, 3.162795, 0, 1, 142, 275, 240 -ATT, 0.58, 1.45, -6.02, -6.84, 0.00, 105.13, 105.89 -ATT, 0.11, 1.26, -5.31, -4.97, 0.00, 105.08, 105.89 -GPS, 3, 594443600, 6, 4.67, 44.0290537, -77.7367845, 2.19, 94.34, 0.27, 330.28 -CTUN, 996, 0.00, 1.55, 3.683455, 0, 0, 159, 311, 247 -ATT, 0.00, 0.99, -4.13, -4.05, 0.00, 105.10, 105.89 -CTUN, 996, 0.00, 1.63, 4.054469, 0, 0, 164, 326, 247 -GPS, 3, 594443800, 6, 4.67, 44.0290535, -77.7367844, 2.49, 94.67, 0.12, 330.28 -ATT, 0.00, 0.34, -1.88, -5.61, 0.00, 105.10, 105.89 -CTUN, 996, 0.00, 1.87, 4.227804, 0, 0, 177, 297, 247 -ATT, 0.00, 0.51, -1.29, -3.03, 0.00, 105.04, 105.89 -CTUN, 996, 0.00, 2.10, 4.548795, 0, 0, 193, 313, 247 -GPS, 3, 594444000, 6, 4.67, 44.0290537, -77.7367842, 2.76, 95.05, 0.26, 66.77 -CTUN, 996, 0.00, 2.18, 4.822787, 0, 0, 211, 302, 247 -ATT, 0.00, 0.47, -0.59, -2.13, 0.00, 105.07, 105.89 -CTUN, 996, 0.00, 2.37, 4.993937, 0, 0, 213, 274, 246 -ATT, 0.00, 0.20, -1.29, -1.58, 0.00, 105.04, 105.89 -GPS, 3, 594444200, 6, 4.67, 44.0290535, -77.7367833, 3.02, 95.41, 0.50, 103.12 -CTUN, 996, 0.00, 2.52, 5.341821, 0, 0, 221, 307, 247 -ATT, 0.00, 0.36, -4.01, -1.60, 0.00, 105.19, 105.89 -GPS, 3, 594444400, 6, 4.67, 44.0290534, -77.7367825, 3.58, 95.81, 0.47, 108.56 -ATT, 0.58, 0.09, -6.85, -3.47, 0.00, 105.35, 105.89 -CTUN, 996, 0.00, 3.39, 5.712414, 0, 0, 221, 308, 247 -ATT, 1.76, 0.40, -8.26, -4.69, 0.00, 105.36, 105.89 -CTUN, 996, 0.00, 3.95, 6.032713, 0, 0, 220, 293, 247 -GPS, 3, 594444600, 6, 4.67, 44.0290532, -77.7367816, 3.93, 96.21, 0.51, 111.12 -CTUN, 996, 0.00, 3.44, 6.306745, 0, 1, 224, 298, 247 -ATT, 2.47, 1.44, -8.50, -6.23, 0.00, 105.39, 105.89 -DU32, 7, 426229 -CURR, 996, 38220, 1396, 1808, 4962, 57.350994 -CTUN, 996, 0.00, 3.52, 6.552351, 0, 1, 227, 295, 247 -ATT, 2.70, 1.93, -8.50, -7.13, -0.24, 105.40, 105.83 -GPS, 3, 594444800, 6, 4.67, 44.0290530, -77.7367805, 4.29, 96.59, 0.46, 110.83 -CTUN, 997, 0.00, 3.86, 6.826670, 0, 1, 230, 289, 247 -ATT, 2.70, 1.98, -8.38, -7.29, -1.21, 105.12, 105.35 -ATT, 2.70, 2.02, -7.79, -7.27, -1.82, 104.68, 104.64 -GPS, 3, 594445000, 6, 4.67, 44.0290528, -77.7367791, 4.70, 96.98, 0.58, 110.11 -CTUN, 997, 0.00, 4.10, 7.046747, 0, 1, 233, 299, 248 -PM, 0, 0, 34, 35, 1010, 59072, 10, 0 -ATT, 2.47, 2.06, -6.85, -8.03, -2.31, 103.60, 103.38 -GPS, 3, 594445200, 6, 4.67, 44.0290523, -77.7367771, 5.13, 97.34, 0.58, 110.11 -CTUN, 997, 0.00, 4.36, 7.568981, 0, 1, 233, 311, 247 -ATT, 2.12, 2.15, -6.14, -6.87, -2.56, 102.03, 101.73 -ATT, 1.64, 2.29, -5.66, -6.83, -2.80, 100.76, 100.30 -CTUN, 998, 0.00, 4.76, 8.065793, 0, 1, 238, 331, 248 -GPS, 3, 594445400, 6, 4.67, 44.0290516, -77.7367752, 5.53, 97.76, 0.76, 117.59 -CTUN, 996, 0.00, 5.21, 8.389195, 0, 0, 242, 300, 248 -ATT, 1.06, 1.40, -4.48, -6.30, -2.68, 98.93, 98.61 -GPS, 3, 594445600, 6, 4.67, 44.0290503, -77.7367726, 5.95, 98.11, 1.13, 126.18 -ATT, 0.11, 1.56, -3.18, -4.69, -2.56, 97.11, 97.10 -CTUN, 997, 0.00, 5.56, 8.561729, 0, 0, 250, 311, 247 -ATT, 0.11, 1.07, -2.71, -4.71, -1.95, 95.88, 96.08 -CTUN, 996, 0.00, 5.60, 8.983974, 0, 0, 264, 267, 248 -GPS, 3, 594445800, 6, 4.67, 44.0290492, -77.7367703, 6.35, 98.57, 1.17, 125.84 -CTUN, 996, 0.00, 6.42, 9.284063, 0, 0, 257, 316, 248 -ATT, 0.00, 0.66, -2.24, -3.28, -1.34, 94.56, 94.91 -CTUN, 996, 0.00, 6.78, 9.431405, 0, 0, 261, 292, 248 -ATT, 0.00, 0.53, -2.12, -3.83, -0.36, 93.85, 94.36 -GPS, 3, 594446000, 6, 4.67, 44.0290479, -77.7367675, 6.78, 99.01, 1.36, 126.89 -CTUN, 997, 0.00, 7.02, 9.781522, 0, 0, 258, 309, 248 -ATT, 0.00, 0.72, -2.00, -2.99, 0.00, 93.55, 94.33 -CTUN, 997, 0.00, 7.47, 10.001349, 0, 0, 261, 273, 248 -GPS, 3, 594446200, 6, 4.67, 44.0290466, -77.7367645, 7.57, 99.45, 1.56, 124.82 -ATT, 0.00, 0.60, -1.77, -1.62, 0.00, 93.56, 94.33 -CTUN, 997, 0.00, 8.41, 10.276600, 0, 0, 258, 292, 248 -ATT, 0.00, -0.43, -1.65, -1.77, 0.00, 93.76, 94.33 -CTUN, 996, 0.00, 9.29, 10.498203, 0, 0, 259, 278, 248 -GPS, 3, 594446400, 6, 4.67, 44.0290451, -77.7367614, 8.03, 99.83, 1.57, 124.62 -CTUN, 996, 0.00, 10.04, 10.772789, 0, 0, 254, 283, 248 -ATT, 0.00, -0.14, -1.77, -1.73, 0.00, 93.66, 94.33 -CTUN, 996, 0.00, 10.49, 10.994082, 0, 0, 249, 263, 247 -ATT, 0.00, -0.57, -1.77, -1.94, 0.00, 93.73, 94.33 -GPS, 3, 594446600, 6, 4.67, 44.0290436, -77.7367583, 8.62, 100.22, 1.50, 124.18 -CTUN, 996, 0.00, 10.52, 11.067945, 0, 0, 247, 290, 247 -ATT, 0.00, -0.07, -1.77, -1.60, 0.00, 93.62, 94.33 -DU32, 7, 426229 -CURR, 996, 43471, 1391, 1907, 4918, 66.318352 -CTUN, 996, 0.00, 10.61, 11.512257, 0, 0, 233, 295, 247 -ATT, 0.00, 0.14, -1.18, -2.50, 0.00, 93.58, 94.33 -GPS, 3, 594446800, 6, 4.67, 44.0290422, -77.7367556, 9.35, 100.61, 1.33, 124.68 -CTUN, 996, 0.00, 10.78, 11.761680, 0, 0, 234, 284, 246 -ATT, 0.00, 0.51, -1.18, -1.81, 0.00, 93.53, 94.33 -CTUN, 996, 0.00, 11.23, 12.032876, 0, 0, 226, 287, 247 -ATT, 0.00, 0.28, -0.94, -1.11, 0.00, 93.42, 94.33 -GPS, 3, 594447000, 6, 4.67, 44.0290408, -77.7367525, 9.85, 100.93, 1.33, 124.68 -CTUN, 996, 0.00, 11.53, 12.329591, 0, 0, 221, 290, 247 -ATT, 0.00, -0.53, -0.70, -1.52, 0.00, 93.55, 94.33 -GPS, 3, 594447200, 6, 4.67, 44.0290397, -77.7367501, 10.45, 101.29, 0.98, 125.45 -ATT, 0.00, -0.32, -0.47, -0.95, 0.00, 93.66, 94.33 -CTUN, 996, 0.00, 11.82, 12.650966, 0, 0, 215, 288, 246 -ATT, 0.00, 0.00, 0.00, -0.56, 0.00, 93.79, 94.33 -CTUN, 996, 0.00, 12.40, 12.947069, 0, 0, 212, 292, 247 -GPS, 3, 594447400, 6, 4.67, 44.0290385, -77.7367476, 10.85, 101.63, 1.02, 123.82 -CTUN, 996, 0.00, 12.68, 13.221881, 0, 0, 212, 287, 247 -ATT, 0.00, 0.05, 0.00, -0.82, 0.00, 93.96, 94.33 -CTUN, 996, 0.00, 12.98, 13.442156, 0, 0, 211, 282, 247 -ATT, 0.00, -0.02, 0.00, -0.57, 0.00, 93.98, 94.33 -GPS, 3, 594447600, 6, 4.67, 44.0290374, -77.7367453, 11.47, 101.95, 0.93, 124.22 -CTUN, 996, 0.00, 13.64, 13.590998, 0, 0, 210, 279, 247 -ATT, 0.00, -0.32, 0.00, 0.37, 0.00, 94.16, 94.33 -CTUN, 995, 0.00, 14.77, 13.911060, 0, 0, 208, 284, 247 -ATT, 0.00, 0.93, 0.00, 0.31, 0.00, 94.34, 94.33 -GPS, 3, 594447800, 6, 4.67, 44.0290365, -77.7367432, 12.01, 102.24, 0.93, 124.22 -CTUN, 996, 0.00, 15.81, 14.283872, 0, 0, 204, 242, 247 -ATT, 0.00, 0.94, 0.00, 0.04, 0.00, 94.40, 94.33 -CTUN, 996, 0.00, 15.78, 14.431864, 0, 0, 199, 286, 247 -GPS, 3, 594448000, 6, 4.67, 44.0290358, -77.7367410, 12.49, 102.46, 0.71, 123.15 -ATT, 0.00, -0.17, 0.00, -0.07, 0.00, 94.52, 94.33 -CTUN, 996, 0.00, 15.50, 14.804152, 0, 0, 188, 286, 247 -ATT, 0.00, -0.52, 0.00, -0.62, 0.00, 94.45, 94.33 -GPS, 3, 594448200, 6, 4.67, 44.0290351, -77.7367394, 13.16, 102.69, 0.56, 118.86 -CTUN, 995, 0.00, 15.60, 14.976488, 0, 0, 187, 277, 247 -ATT, 0.00, 0.76, 0.00, 0.53, 0.00, 94.18, 94.33 -CTUN, 996, 0.00, 16.25, 15.444947, 0, 0, 182, 275, 247 -ATT, 0.00, 0.19, 0.00, 0.08, 0.00, 94.10, 94.33 -GPS, 3, 594448400, 6, 4.67, 44.0290344, -77.7367379, 13.85, 102.91, 0.56, 118.86 -CTUN, 996, 0.00, 15.99, 15.593345, 0, 0, 183, 258, 247 -ATT, 0.00, -0.22, 0.00, 0.10, 0.00, 94.17, 94.33 -CTUN, 996, 0.00, 15.55, 15.964941, 0, 0, 176, 274, 247 -ATT, 0.00, -0.16, 0.00, 0.15, 0.00, 94.32, 94.33 -GPS, 3, 594448600, 6, 4.67, 44.0290339, -77.7367367, 14.31, 103.09, 0.46, 122.68 -CTUN, 996, 0.00, 15.78, 16.212021, 0, 0, 173, 273, 247 -ATT, 0.00, 0.51, 0.00, -0.38, 0.00, 94.40, 94.33 -CTUN, 996, 0.00, 15.95, 16.459574, 0, 0, 172, 291, 247 -GPS, 3, 594448800, 6, 4.67, 44.0290335, -77.7367357, 14.80, 103.27, 0.29, 123.99 -ATT, 0.00, -0.27, 0.00, -0.58, 0.00, 94.39, 94.33 -CTUN, 996, 0.00, 16.42, 16.706751, 0, 0, 176, 280, 247 -DU32, 7, 426229 -CURR, 996, 48485, 1392, 1788, 4962, 74.207115 -ATT, 0.00, -0.33, 0.00, 0.24, 0.00, 94.28, 94.33 -CTUN, 996, 0.00, 15.77, 16.953911, 0, 0, 180, 280, 247 -GPS, 3, 594449000, 6, 4.67, 44.0290332, -77.7367350, 15.23, 103.45, 0.23, 127.73 -CTUN, 997, 0.00, 16.05, 17.203630, 0, 0, 184, 284, 248 -ATT, 0.00, -0.39, 0.00, -0.06, 0.00, 94.27, 94.33 -CTUN, 997, 0.00, 15.59, 17.474089, 0, 0, 189, 276, 248 -ATT, 0.00, -0.12, 0.00, -0.18, 0.00, 94.11, 94.33 -GPS, 3, 594449200, 6, 4.67, 44.0290328, -77.7367345, 15.58, 103.62, 0.23, 127.73 -CTUN, 997, 0.00, 15.85, 17.773514, 0, 0, 194, 307, 248 -ATT, 0.00, 0.31, 0.00, -0.24, 0.00, 94.04, 94.33 -CTUN, 997, 0.00, 16.01, 17.921450, 0, 0, 198, 269, 248 -GPS, 3, 594449400, 6, 4.67, 44.0290326, -77.7367342, 15.94, 103.84, 0.12, 127.73 -ATT, 0.00, -0.01, 0.00, -0.45, 0.00, 93.97, 94.33 -CTUN, 997, 0.00, 16.26, 18.243938, 0, 0, 206, 271, 248 -ATT, 0.00, -0.10, 0.00, 0.46, 0.00, 93.93, 94.33 -GPS, 3, 594449600, 6, 4.67, 44.0290326, -77.7367345, 16.39, 104.10, 0.18, 127.73 -CTUN, 996, 0.00, 15.92, 18.467680, 0, 0, 207, 286, 247 -ATT, 0.00, -0.21, -2.59, -0.19, 0.00, 94.02, 94.33 -CTUN, 998, 0.00, 16.74, 18.864338, 0, 0, 211, 286, 248 -ATT, 0.00, 0.04, -3.89, -1.81, 0.00, 94.13, 94.33 -GPS, 3, 594449800, 6, 4.67, 44.0290326, -77.7367348, 16.84, 104.38, 0.19, 127.73 -CTUN, 996, 0.00, 17.87, 19.164223, 0, 0, 210, 302, 247 -ATT, 0.00, -0.19, -4.72, -3.01, 0.00, 94.03, 94.33 -CTUN, 996, 0.00, 17.48, 19.434532, 0, 0, 222, 271, 247 -GPS, 3, 594450000, 6, 4.67, 44.0290325, -77.7367353, 17.33, 104.67, 0.19, 127.73 -ATT, 0.00, -0.19, -7.79, -2.87, 0.00, 94.00, 94.33 -CTUN, 997, 0.00, 17.80, 19.709078, 0, 0, 223, 285, 248 -ATT, 0.00, -0.19, -8.62, -5.31, 0.00, 94.08, 94.33 -GPS, 3, 594450200, 6, 4.66, 44.0290326, -77.7367361, 17.71, 104.99, 0.30, 127.73 -CTUN, 997, 0.00, 16.77, 19.956036, 0, 1, 226, 286, 248 -ATT, 0.00, 0.11, -9.33, -6.87, 0.00, 94.12, 94.33 -CTUN, 997, 0.00, 16.23, 20.377537, 0, 1, 227, 292, 248 -ATT, 0.00, 0.11, -9.68, -7.58, 0.00, 94.14, 94.33 -GPS, 3, 594450400, 6, 4.66, 44.0290326, -77.7367363, 18.18, 105.26, 0.17, 127.73 -CTUN, 998, 0.00, 16.25, 20.677319, 0, 1, 227, 317, 248 -ATT, 0.00, -0.01, -10.15, -8.87, 0.00, 94.16, 94.33 -GPS, 3, 594450600, 6, 4.66, 44.0290325, -77.7367366, 18.45, 105.55, 0.17, 127.73 -CTUN, 977, 0.00, 15.81, 20.949463, 0, 2, 240, 295, 247 -ATT, 0.00, 0.20, -9.56, -9.44, 0.00, 94.06, 94.33 -DU32, 7, 426229 -CURR, 957, 52786, 1376, 2252, 4855, 81.393112 -CTUN, 913, 0.00, 16.09, 21.305325, 0, 2, 259, 305, 205 -ATT, 0.00, 0.57, -7.91, -8.84, 0.00, 93.90, 94.33 -GPS, 3, 594450800, 6, 4.66, 44.0290322, -77.7367364, 18.79, 105.87, 0.16, 127.73 -CTUN, 844, 0.00, 16.47, 21.402895, 0, 1, 265, 290, 195 -ATT, 0.00, -0.12, -5.19, -7.42, 0.00, 93.87, 94.33 -CTUN, 770, 0.00, 17.17, 21.638063, 0, 0, 273, 229, 115 -ATT, 0.00, -0.17, -3.89, -6.03, 0.00, 93.81, 94.33 -GPS, 3, 594451000, 6, 4.66, 44.0290315, -77.7367357, 19.20, 106.25, 0.16, 127.73 -CTUN, 746, 0.00, 18.20, 21.748817, 0, 0, 263, 259, 98 -ATT, 0.00, 0.06, -2.83, -4.16, 0.00, 93.87, 94.33 -GPS, 3, 594451200, 6, 4.66, 44.0290309, -77.7367346, 19.50, 106.61, 0.52, 137.61 -CTUN, 701, 0.00, 19.28, 21.832693, 0, 0, 246, 262, 75 -ATT, 0.00, 0.26, -2.12, -3.46, 0.00, 93.98, 94.33 -CTUN, 701, 0.00, 19.61, 21.939583, 0, 0, 209, 230, 62 -ATT, 0.00, 0.14, -1.77, -2.95, 0.00, 93.98, 94.33 -GPS, 3, 594451400, 6, 4.66, 44.0290301, -77.7367336, 19.97, 106.93, 0.68, 133.48 -CTUN, 702, 0.00, 19.59, 21.982822, 0, 0, 192, 262, 62 -ATT, 0.00, 0.31, -1.77, -2.65, 0.00, 94.09, 94.33 -GPS, 3, 594451600, 6, 4.66, 44.0290292, -77.7367326, 20.31, 107.16, 0.47, 140.50 -ATT, 0.00, 0.25, -1.41, -2.34, 0.00, 94.20, 94.33 -CTUN, 702, 0.00, 19.41, 22.115652, 0, 0, 160, 277, 63 -ATT, 0.00, -0.05, -1.29, -2.64, 0.00, 94.17, 94.33 -CTUN, 701, 0.00, 19.55, 22.191137, 0, 0, 150, 284, 63 -GPS, 3, 594451800, 6, 4.66, 44.0290284, -77.7367319, 20.49, 107.36, 0.47, 140.50 -CTUN, 702, 0.00, 19.65, 22.255476, 0, 0, 145, 256, 63 -ATT, 0.00, -0.51, -0.70, -1.63, 0.00, 94.13, 94.33 -CTUN, 701, 0.00, 19.54, 22.323393, 0, 0, 146, 281, 63 -ATT, 0.00, -0.58, -0.47, -0.59, 0.00, 94.15, 94.33 -GPS, 3, 594452000, 6, 4.66, 44.0290277, -77.7367314, 20.71, 107.53, 0.39, 146.62 -CTUN, 702, 0.00, 19.42, 22.336330, 0, 0, 145, 264, 63 -ATT, 0.00, 0.30, -0.59, -1.33, 0.00, 94.03, 94.33 -CTUN, 702, 0.00, 19.45, 22.437002, 0, 0, 148, 279, 63 -ATT, 0.00, 0.45, -0.59, -0.66, 0.00, 94.10, 94.33 -GPS, 3, 594452200, 6, 4.66, 44.0290270, -77.7367315, 20.93, 107.79, 0.43, 150.18 -CTUN, 702, 0.00, 19.45, 22.513239, 0, 0, 145, 257, 63 -ATT, 0.00, 0.01, -1.65, -1.25, 0.00, 94.17, 94.33 -GPS, 3, 594452400, 6, 4.66, 44.0290264, -77.7367315, 21.08, 107.95, 0.30, 162.75 -ATT, 0.00, -0.20, -2.83, -1.46, 0.00, 94.14, 94.33 -CTUN, 699, 0.00, 19.54, 22.582130, 0, 0, 142, 284, 62 -ATT, 0.00, -0.59, -2.83, -2.89, 0.00, 94.21, 94.33 -CTUN, 667, 0.00, 20.03, 22.684349, 0, 0, 137, 287, 45 -GPS, 3, 594452600, 6, 4.66, 44.0290258, -77.7367317, 21.26, 108.14, 0.30, 162.75 -CTUN, 660, 0.00, 20.14, 22.700840, 0, 0, 136, 266, 41 -ATT, 0.00, -0.45, -4.96, -3.08, 0.00, 94.16, 94.33 -CTUN, 653, 0.00, 20.22, 22.759605, 0, 0, 133, 267, 36 -ATT, -0.35, 0.05, -6.02, -3.16, 0.00, 94.14, 94.33 -GPS, 3, 594452800, 6, 4.66, 44.0290254, -77.7367322, 21.44, 108.32, 0.30, 162.75 -CTUN, 642, 0.00, 20.36, 22.771666, 0, 0, 130, 275, 30 -ATT, -0.93, -0.16, -6.49, -4.32, 0.00, 94.19, 94.33 -DU32, 7, 426229 -CURR, 638, 57838, 1417, 1491, 4962, 89.100349 -CTUN, 624, 0.00, 20.29, 22.814585, 0, 0, 115, 272, 15 -ATT, -1.99, -0.57, -7.79, -5.49, 0.00, 94.28, 94.33 -GPS, 3, 594453000, 6, 4.66, 44.0290250, -77.7367329, 21.61, 108.47, 0.39, 201.97 -CTUN, 620, 0.00, 20.08, 22.824575, 0, 0, 107, 274, 12 -ATT, -3.05, -1.48, -8.50, -6.80, 0.00, 94.35, 94.33 -GPS, 3, 594453200, 6, 4.66, 44.0290245, -77.7367333, 21.69, 108.58, 0.39, 201.97 -CTUN, 621, 0.00, 19.23, 22.837873, 0, 1, 99, 284, 12 -ATT, -3.17, -2.39, -8.62, -7.73, 0.00, 94.28, 94.33 -CTUN, 620, 0.00, 19.09, 22.857431, 0, 1, 95, 299, 13 -ATT, -2.70, -2.79, -7.79, -7.82, 0.00, 94.23, 94.33 -GPS, 3, 594453400, 6, 4.66, 44.0290239, -77.7367335, 21.73, 108.65, 0.38, 201.97 -CTUN, 623, 0.00, 19.20, 22.864586, 0, 1, 93, 285, 12 -ATT, -1.99, -2.36, -6.37, -7.65, 0.00, 94.05, 94.33 -CTUN, 621, 0.00, 19.31, 22.887592, 0, 1, 97, 306, 13 -GPS, 3, 594453600, 6, 4.66, 44.0290235, -77.7367336, 21.73, 108.77, 0.30, 201.97 -CTUN, 620, 0.00, 19.75, 22.899721, 0, 0, 96, 260, 12 -ATT, -1.76, -1.96, -6.14, -6.91, 0.00, 94.06, 94.33 -CTUN, 620, 0.00, 19.53, 22.911694, 0, 1, 100, 304, 12 -ATT, -1.17, -1.21, -5.90, -7.48, 0.00, 94.32, 94.33 -GPS, 3, 594453800, 6, 4.66, 44.0290230, -77.7367328, 21.77, 108.79, 0.21, 201.97 -CTUN, 620, 0.00, 20.08, 22.920172, 0, 0, 96, 277, 12 -ATT, 0.00, -1.51, -3.18, -6.49, 0.00, 94.28, 94.33 -CTUN, 623, 0.00, 20.14, 22.936308, 0, 0, 105, 287, 12 -ATT, 0.00, -0.31, 0.00, -3.48, 0.00, 94.15, 94.33 -GPS, 3, 594454000, 6, 4.66, 44.0290225, -77.7367321, 21.83, 108.90, 0.34, 153.11 -CTUN, 620, 0.00, 20.32, 22.950808, 0, 0, 104, 267, 12 -ATT, 0.00, -0.65, 0.00, -2.21, 0.00, 94.17, 94.33 -CTUN, 623, 0.00, 20.41, 22.964832, 0, 0, 105, 291, 13 -GPS, 3, 594454200, 6, 4.66, 44.0290221, -77.7367312, 21.90, 109.05, 0.45, 135.06 -ATT, 0.00, -0.73, 0.00, -1.31, 0.00, 94.27, 94.33 -CTUN, 621, 0.00, 20.66, 22.985695, 0, 0, 99, 260, 14 -ATT, 0.00, -0.11, 0.00, -1.84, 0.00, 94.19, 94.33 -GPS, 3, 594454400, 6, 4.66, 44.0290218, -77.7367306, 21.99, 109.23, 0.45, 135.06 -CTUN, 618, 0.00, 20.59, 22.993908, 0, 0, 95, 272, 14 -ATT, 0.00, -0.44, 0.00, -0.47, 0.00, 93.92, 94.33 -CTUN, 600, 0.00, 20.69, 23.006685, 0, 0, 90, 269, 1 -ATT, 0.00, -0.20, 0.00, 0.05, 0.00, 93.74, 94.33 -GPS, 3, 594454600, 6, 4.66, 44.0290216, -77.7367299, 22.09, 109.35, 0.24, 129.02 -CTUN, 558, 0.00, 20.58, 23.006685, 0, 0, 85, 256, 0 -ATT, 0.00, -0.56, 0.00, -0.35, 0.00, 93.64, 94.33 -CTUN, 506, 0.00, 20.73, 23.006685, 0, 0, 82, 283, 0 -GPS, 3, 594454800, 6, 4.66, 44.0290214, -77.7367292, 22.14, 109.46, 0.24, 129.02 -ATT, 0.00, -0.27, 0.00, -0.28, 0.00, 93.83, 94.33 -CTUN, 451, 0.00, 20.73, 23.006685, 0, 0, 78, 269, 0 -ATT, 0.00, 0.98, 0.00, -0.37, 0.00, 93.72, 94.33 -CTUN, 426, 0.00, 20.75, 23.006685, 0, 0, 77, 272, 0 -GPS, 3, 594455000, 6, 4.66, 44.0290214, -77.7367291, 22.20, 109.59, 0.06, 129.02 -ATT, 0.00, -0.51, 0.00, 1.28, 0.00, 94.13, 94.33 -CTUN, 406, 0.00, 21.05, 23.006685, 0, 0, 76, 256, 0 -ATT, 0.00, 0.20, 0.00, 0.94, 0.00, 94.11, 94.33 -PM, 0, 0, 50, 73, 1000, 11500, 10, 0 -CTUN, 385, 0.00, 20.97, 23.004013, 0, 0, 76, 251, -6 -GPS, 3, 594455200, 6, 4.66, 44.0290215, -77.7367291, 22.25, 109.71, 0.06, 129.02 -CTUN, 373, 0.00, 21.01, 22.990314, 0, 0, 71, 252, -15 -ATT, 0.00, -0.11, 0.00, 0.05, 0.00, 94.36, 94.33 -CTUN, 346, 0.00, 20.83, 22.965805, 0, 0, 65, 271, -33 -ATT, 0.00, 0.46, 0.00, -0.69, 0.00, 94.38, 94.33 -GPS, 3, 594455400, 6, 4.66, 44.0290219, -77.7367296, 22.29, 109.78, 0.16, 129.02 -CTUN, 313, 0.00, 20.99, 22.950945, 0, 0, 61, 279, -37 -ATT, 0.00, -0.34, 0.00, -1.13, 0.00, 94.34, 94.33 -CTUN, 309, 0.00, 21.02, 22.873672, 0, 0, 54, 270, -56 -ATT, 0.00, -1.05, 0.00, -0.19, 0.00, 94.33, 94.33 -GPS, 3, 594455600, 6, 4.66, 44.0290223, -77.7367303, 22.30, 109.83, 0.40, 346.02 -CTUN, 307, 0.00, 20.97, 22.797178, 0, 0, 43, 251, -58 -ATT, 0.00, 0.45, 0.00, -0.24, 0.00, 94.16, 94.33 -CTUN, 302, 0.00, 20.89, 22.744253, 0, 0, 35, 292, -61 -GPS, 3, 594455800, 6, 4.66, 44.0290228, -77.7367312, 22.28, 109.85, 0.40, 346.02 -ATT, 0.00, 0.51, 0.00, -0.32, 0.00, 94.09, 94.33 -DU32, 7, 426229 -CURR, 301, 64702, 1414, 1237, 5006, 99.835197 -CTUN, 296, 0.00, 20.89, 22.677025, 0, 0, 31, 254, -61 -ATT, 0.00, 0.43, 0.00, -0.81, 0.00, 94.12, 94.33 -CTUN, 290, 0.00, 20.95, 22.605463, 0, 0, 24, 293, -65 -GPS, 3, 594456000, 6, 4.66, 44.0290234, -77.7367324, 22.24, 109.84, 0.51, 318.36 -ATT, 0.00, -0.33, 0.00, -0.22, 0.00, 94.05, 94.33 -CTUN, 278, 0.00, 20.96, 22.489635, 0, 0, 21, 273, -76 -ATT, 0.00, -0.14, 0.00, 0.00, 0.00, 94.03, 94.33 -GPS, 3, 594456200, 6, 4.66, 44.0290243, -77.7367342, 22.18, 109.87, 0.75, 306.23 -CTUN, 275, 0.00, 20.83, 22.381668, 0, 0, 15, 270, -78 -ATT, 0.00, -0.27, 0.00, -0.40, 0.00, 94.03, 94.33 -GPS, 3, 594456400, 6, 4.66, 44.0290251, -77.7367358, 22.11, 109.84, 0.82, 303.78 -ATT, 0.00, -0.31, 0.00, 0.21, 0.00, 94.04, 94.33 -CTUN, 251, 0.00, 20.89, 22.272120, 0, 0, 9, 273, -89 -ATT, 0.00, -0.26, 0.00, -0.10, 0.00, 94.11, 94.33 -CTUN, 237, 0.00, 20.88, 22.137690, 0, 0, 3, 265, -101 -GPS, 3, 594456600, 6, 4.66, 44.0290260, -77.7367378, 22.04, 109.79, 0.82, 303.78 -CTUN, 230, 0.00, 20.82, 22.097113, 0, 0, 0, 272, -101 -ATT, 0.00, -0.18, 0.00, 0.35, 0.00, 94.27, 94.33 -CTUN, 220, 0.00, 20.71, 21.958555, 0, 0, -9, 259, -109 -ATT, 0.00, -0.03, -1.77, 0.11, 0.00, 94.38, 94.33 -GPS, 3, 594456800, 6, 4.66, 44.0290271, -77.7367402, 21.92, 109.73, 1.16, 302.43 -CTUN, 208, 0.00, 20.75, 21.807590, 0, 0, -20, 262, -117 -ATT, 0.00, -0.22, -4.60, -1.04, 0.00, 94.51, 94.33 -GPS, 3, 594457000, 6, 4.66, 44.0290281, -77.7367427, 21.83, 109.63, 1.16, 302.43 -ATT, 0.00, 0.06, -7.67, -2.54, 0.00, 94.65, 94.33 -CTUN, 198, 0.00, 20.71, 21.686729, 0, 0, -28, 266, -125 -ATT, 0.00, 0.29, -10.03, -4.74, 0.00, 94.78, 94.33 -CTUN, 196, 0.00, 20.62, 21.446880, 0, 0, -35, 280, -127 -GPS, 3, 594457200, 6, 4.66, 44.0290293, -77.7367455, 21.66, 109.53, 1.26, 300.98 -CTUN, 196, 0.00, 20.36, 21.395458, 0, 0, -35, 259, -127 -ATT, 0.00, 0.02, -11.69, -7.08, 0.00, 94.89, 94.33 -CTUN, 197, 0.00, 20.11, 21.217314, 0, 1, -40, 262, -127 -ATT, 0.00, -0.16, -12.04, -7.91, 0.00, 94.92, 94.33 -GPS, 3, 594457400, 6, 4.66, 44.0290302, -77.7367481, 21.49, 109.39, 1.37, 301.05 -CTUN, 196, 0.00, 19.77, 21.141075, 0, 1, -43, 256, -127 -ATT, 0.00, -0.26, -12.16, -8.83, 0.00, 94.98, 94.33 -CTUN, 196, 0.00, 19.53, 20.937515, 0, 1, -49, 267, -127 -ATT, 0.00, -0.12, -12.16, -9.97, 0.00, 94.95, 94.33 -GPS, 3, 594457600, 6, 4.66, 44.0290312, -77.7367507, 21.26, 109.26, 1.27, 297.86 -CTUN, 196, 0.00, 19.40, 20.795479, 0, 2, -54, 259, -127 -ATT, 0.00, 0.46, -12.16, -11.27, 0.00, 94.73, 94.33 -GPS, 3, 594457800, 6, 4.65, 44.0290320, -77.7367528, 21.04, 109.11, 1.27, 298.95 -ATT, 0.00, -0.52, -10.86, -10.23, 0.00, 94.62, 94.33 -CTUN, 196, 0.00, 19.02, 20.631269, 0, 2, -50, 268, -127 -ATT, 0.00, -0.51, -10.74, -10.43, 0.00, 94.47, 94.33 -CTUN, 196, 0.00, 18.97, 20.415716, 0, 2, -46, 252, -127 -GPS, 3, 594458000, 6, 4.65, 44.0290324, -77.7367546, 20.84, 108.97, 0.77, 295.68 -CTUN, 190, 0.00, 19.21, 20.415716, 0, 2, -46, 270, -127 -ATT, 0.00, 0.10, -10.51, -10.28, 0.00, 94.40, 94.33 -CTUN, 189, 0.00, 18.94, 20.192528, 0, 1, -48, 243, -131 -ATT, 0.00, 0.50, -10.39, -10.52, 0.00, 94.36, 94.33 -GPS, 3, 594458200, 6, 4.65, 44.0290325, -77.7367558, 20.55, 108.84, 0.77, 295.68 -CTUN, 184, 0.00, 19.31, 20.007109, 0, 1, -50, 243, -135 -ATT, 0.00, -0.16, -9.68, -9.34, 0.00, 94.38, 94.33 -CTUN, 184, 0.00, 19.12, 19.871752, 0, 1, -54, 246, -135 -GPS, 3, 594458400, 6, 4.65, 44.0290325, -77.7367566, 20.35, 108.65, 0.40, 284.11 -ATT, 0.00, -0.14, -9.33, -9.70, 0.00, 94.27, 94.33 -CTUN, 183, 0.00, 18.99, 19.735138, 0, 1, -58, 225, -135 -ATT, 0.00, -0.19, -8.50, -9.11, 0.00, 94.47, 94.33 -CTUN, 183, 0.00, 18.84, 19.615398, 0, 1, -61, 278, -135 -GPS, 3, 594458600, 6, 4.65, 44.0290323, -77.7367568, 20.15, 108.44, 0.40, 284.11 -CTUN, 184, 0.00, 18.92, 19.561449, 0, 0, -64, 216, -134 -ATT, 0.00, 0.33, -7.08, -7.15, 0.00, 94.32, 94.33 -CTUN, 185, 0.00, 18.78, 19.373919, 0, 0, -65, 237, -134 -ATT, 0.00, -0.60, -6.49, -4.17, 0.00, 94.59, 94.33 -GPS, 3, 594458800, 6, 4.65, 44.0290319, -77.7367572, 19.91, 108.29, 0.18, 284.11 -CTUN, 185, 0.00, 18.50, 19.158817, 0, 1, -71, 244, -134 -ATT, 0.00, -2.60, -5.43, -9.53, 0.00, 94.85, 94.33 -GPS, 3, 594459000, 6, 4.65, 44.0290314, -77.7367571, 19.73, 108.10, 0.22, 284.11 -ATT, 0.00, 1.48, -4.84, -11.41, 0.00, 94.81, 94.33 -CTUN, 185, 0.00, 18.40, 19.065163, 0, 2, -77, 263, -134 -DU32, 7, 426229 -CURR, 184, 71961, 1393, 1893, 5006, 110.931320 -ATT, 0.00, 2.67, -4.25, -7.44, 0.00, 94.77, 94.33 -CTUN, 184, 0.00, 18.72, 18.822609, 0, 1, -76, 252, -135 -GPS, 3, 594459200, 6, 4.65, 44.0290307, -77.7367567, 19.42, 107.89, 0.36, 210.21 -CTUN, 185, 0.00, 18.72, 18.714340, 0, 0, -75, 227, -134 -ATT, 0.00, -0.53, -4.13, -2.77, 0.00, 95.08, 94.33 -CTUN, 185, 0.00, 18.40, 18.553810, 0, 0, -72, 229, -134 -ATT, 0.00, -0.87, -4.01, -1.61, 0.00, 94.91, 94.33 -GPS, 3, 594459400, 6, 4.65, 44.0290300, -77.7367565, 19.25, 107.72, 0.53, 160.22 -CTUN, 185, 0.00, 18.19, 18.486864, 0, 0, -75, 261, -134 -ATT, 0.00, -0.43, -3.66, -3.12, 0.00, 94.80, 94.33 -CTUN, 184, 0.00, 18.60, 18.243881, 0, 0, -87, 273, -135 -ATT, 0.00, 0.97, -3.30, -7.19, 0.00, 94.62, 94.33 -GPS, 3, 594459600, 6, 4.65, 44.0290293, -77.7367563, 19.04, 107.54, 0.42, 160.57 -CTUN, 185, 0.00, 18.34, 18.122988, 0, 0, -84, 202, -134 -ATT, 0.00, 0.83, -3.18, -4.14, 0.00, 94.46, 94.33 -GPS, 3, 594459800, 6, 4.65, 44.0290286, -77.7367560, 18.83, 107.32, 0.42, 160.57 -CTUN, 185, 0.00, 18.09, 17.975914, 0, 0, -89, 212, -134 -ATT, 0.00, -3.61, -2.95, 0.61, 0.00, 95.26, 94.33 -CTUN, 184, 0.00, 18.07, 17.747089, 0, 0, -87, 187, -135 -ATT, 0.00, -2.71, -2.59, 0.16, 0.00, 95.47, 94.33 -GPS, 3, 594460000, 6, 4.65, 44.0290279, -77.7367558, 18.59, 107.09, 0.30, 172.15 -CTUN, 184, 0.00, 17.54, 17.692816, 0, 0, -89, 296, -135 -ATT, 0.00, -0.22, -2.48, -5.62, 0.00, 95.40, 94.33 -CTUN, 185, 0.00, 17.05, 17.490681, 0, 0, -100, 247, -134 -ATT, 0.00, -0.85, -2.24, -5.60, 0.00, 95.24, 94.33 -GPS, 3, 594460200, 6, 4.65, 44.0290276, -77.7367556, 18.32, 106.87, 0.30, 172.15 -CTUN, 185, 0.00, 16.96, 17.328739, 0, 0, -99, 239, -134 -ATT, 0.00, 0.34, -2.36, -2.66, 0.00, 94.65, 94.33 -DU32, 7, 426229 -CURR, 185, 74323, 1411, 1228, 4962, 114.804670 -CTUN, 185, 0.00, 17.14, 17.208815, 0, 0, -98, 255, -134 -GPS, 3, 594460400, 6, 4.65, 44.0290273, -77.7367555, 17.98, 106.65, 0.14, 172.15 -ATT, 0.00, -0.23, -2.24, -3.31, 0.00, 94.08, 94.33 -CTUN, 185, 0.00, 16.96, 17.087770, 0, 0, -97, 272, -134 -ATT, 0.00, -0.36, -2.24, -3.73, 0.00, 93.92, 94.33 -CTUN, 185, 0.00, 16.65, 16.940208, 0, 0, -92, 254, -134 -GPS, 3, 594460600, 6, 4.65, 44.0290270, -77.7367551, 17.77, 106.38, 0.15, 172.15 -CTUN, 185, 0.00, 16.86, 16.872993, 0, 0, -92, 230, -134 -ATT, 0.00, 3.54, -2.12, -1.76, 0.00, 92.68, 94.33 -CTUN, 185, 0.00, 16.87, 16.698580, 0, 0, -91, 262, -134 -ATT, 0.00, 0.59, -2.24, -0.94, 0.00, 92.62, 94.33 -GPS, 3, 594460800, 6, 4.65, 44.0290265, -77.7367548, 17.52, 106.16, 0.15, 172.15 -CTUN, 185, 0.00, 16.63, 16.510649, 0, 0, -91, 246, -134 -ATT, 0.00, -4.33, -2.24, -3.07, 0.00, 92.74, 94.33 -CTUN, 185, 0.00, 16.14, 16.376429, 0, 0, -96, 259, -134 -GPS, 3, 594461000, 6, 4.65, 44.0290261, -77.7367543, 17.31, 105.91, 0.24, 172.15 -ATT, 0.00, -0.19, -2.12, -3.81, 0.00, 92.84, 94.33 -CTUN, 185, 0.00, 16.15, 16.241625, 0, 0, -98, 260, -134 -ATT, 0.00, 4.65, -2.24, -2.15, 0.00, 92.33, 94.33 -CTUN, 185, 0.00, 16.53, 16.135410, 0, 0, -99, 255, -134 -GPS, 3, 594461200, 6, 4.65, 44.0290258, -77.7367541, 17.06, 105.67, 0.16, 172.15 -CTUN, 185, 0.00, 16.27, 15.973136, 0, 0, -98, 261, -134 -ATT, 0.00, 0.28, -2.24, -2.04, 0.00, 92.35, 94.33 -CTUN, 185, 0.00, 16.06, 15.893760, 0, 0, -97, 247, -134 -ATT, 0.00, -0.64, -2.12, -1.66, 0.00, 92.22, 94.33 -GPS, 3, 594461400, 6, 4.65, 44.0290254, -77.7367538, 16.73, 105.42, 0.17, 172.15 -CTUN, 185, 0.00, 15.96, 15.772635, 0, 0, -101, 238, -134 -ATT, 0.00, -1.00, -2.24, -1.82, 0.00, 92.44, 94.33 -CTUN, 186, 0.00, 15.84, 15.585222, 0, 0, -101, 255, -134 -GPS, 3, 594461600, 6, 4.65, 44.0290250, -77.7367534, 16.47, 105.10, 0.17, 172.15 -ATT, 0.00, 1.71, -2.24, -3.87, 0.00, 92.19, 94.33 -CTUN, 184, 0.00, 15.83, 15.436719, 0, 0, -105, 267, -134 -ATT, 0.00, 1.56, -2.24, -4.43, 0.00, 92.29, 94.33 -GPS, 3, 594461800, 6, 4.65, 44.0290248, -77.7367536, 16.27, 104.90, 0.10, 166.34 -CTUN, 178, 0.00, 15.75, 15.289831, 0, 0, -103, 262, -135 -ATT, 0.00, -0.06, -2.12, -1.94, 0.00, 92.40, 94.33 -CTUN, 174, 0.00, 15.54, 15.052690, 0, 0, -103, 247, -141 -ATT, 0.00, -2.03, -2.24, -1.29, 0.00, 92.40, 94.33 -GPS, 3, 594462000, 6, 4.65, 44.0290245, -77.7367535, 16.03, 104.63, 0.10, 166.34 -CTUN, 173, 0.00, 15.02, 14.868915, 0, 0, -104, 251, -141 -ATT, 0.00, 0.95, -2.12, -2.36, 0.00, 92.43, 94.33 -CTUN, 173, 0.00, 15.30, 14.784607, 0, 0, -106, 300, -141 -ATT, 0.00, 2.99, -2.24, -4.81, 0.00, 92.24, 94.33 -GPS, 3, 594462200, 7, 2.66, 44.0290236, -77.7367513, 15.66, 104.06, 0.16, 166.34 -CTUN, 172, 0.00, 15.31, 14.628605, 0, 0, -114, 220, -141 -ATT, 0.00, 2.17, -2.00, -5.25, 0.00, 91.91, 94.33 -CTUN, 174, 0.00, 14.99, 14.472574, 0, 0, -105, 220, -142 -GPS, 3, 594462400, 7, 2.66, 44.0290227, -77.7367496, 15.45, 103.53, 0.16, 166.34 -ATT, 0.00, -6.25, -2.00, 2.36, 0.00, 93.00, 94.33 -CTUN, 174, 0.00, 15.34, 14.302330, 0, 0, -100, 145, -141 -ATT, 0.00, -8.99, -1.88, 5.40, 0.00, 93.55, 94.33 -CTUN, 174, 0.00, 15.98, 14.162243, 0, 1, -100, 248, -141 -GPS, 3, 594462600, 7, 2.66, 44.0290219, -77.7367480, 15.28, 103.02, 0.17, 166.34 -ATT, 0.00, -3.92, -2.00, 1.40, 0.00, 94.40, 94.33 -CTUN, 174, 0.00, 15.03, 13.923046, 0, 0, -123, 261, -141 -ATT, 0.00, 1.64, -2.00, -5.46, 0.00, 94.07, 94.33 -GPS, 3, 594462800, 7, 2.66, 44.0290216, -77.7367467, 15.06, 102.52, 0.17, 166.34 -CTUN, 174, 0.00, 14.16, 13.766777, 0, 0, -131, 257, -141 -ATT, 0.00, -1.24, -1.88, -2.56, 0.00, 94.52, 94.33 -CTUN, 174, 0.00, 14.55, 13.641389, 0, 0, -133, 244, -141 -ATT, 0.00, -1.08, -1.88, -0.53, 0.00, 94.62, 94.33 -GPS, 3, 594463000, 7, 2.66, 44.0290214, -77.7367457, 14.72, 102.06, 0.07, 166.34 -CTUN, 174, 0.00, 14.32, 13.429020, 0, 0, -131, 270, -141 -ATT, 0.00, -0.28, -1.88, -2.96, 0.00, 94.50, 94.33 -GPS, 3, 594463200, 7, 2.66, 44.0290214, -77.7367449, 14.54, 101.60, 0.09, 166.34 -CTUN, 174, 0.00, 13.76, 13.344915, 0, 0, -129, 282, -141 -ATT, 0.00, -0.34, -1.88, -3.51, 0.00, 94.66, 94.33 -CTUN, 174, 0.00, 13.78, 13.062453, 0, 0, -124, 236, -141 -ATT, 0.00, -0.61, -1.88, -2.61, 0.00, 94.77, 94.33 -GPS, 3, 594463400, 7, 2.66, 44.0290214, -77.7367440, 14.19, 101.14, 0.18, 166.34 -CTUN, 174, 0.00, 13.64, 13.005935, 0, 0, -126, 277, -141 -ATT, 0.00, 0.23, -1.88, -1.31, 0.00, 94.57, 94.33 -CTUN, 174, 0.00, 13.63, 12.765721, 0, 0, -124, 264, -141 -GPS, 3, 594463600, 7, 2.66, 44.0290216, -77.7367434, 13.89, 100.70, 0.18, 166.34 -ATT, 0.00, -1.95, -1.88, -2.63, 0.00, 94.80, 94.33 -CTUN, 174, 0.00, 13.48, 12.609921, 0, 0, -126, 284, -141 -ATT, 0.00, 0.54, -1.88, -1.85, 0.00, 94.58, 94.33 -CTUN, 174, 0.00, 13.37, 12.483740, 0, 0, -124, 262, -141 -GPS, 3, 594463800, 7, 2.66, 44.0290216, -77.7367428, 13.67, 100.28, 0.27, 267.95 -ATT, 0.00, -0.04, -2.12, -1.86, 0.00, 94.81, 94.33 -CTUN, 175, 0.00, 13.23, 12.354923, 0, 0, -124, 273, -141 -ATT, 0.00, 0.10, -2.12, -2.28, 0.00, 95.01, 94.33 -CTUN, 174, 0.00, 13.27, 12.201469, 0, 0, -122, 249, -141 -GPS, 3, 594464000, 7, 2.66, 44.0290217, -77.7367424, 13.40, 99.87, 0.25, 303.78 -CTUN, 174, 0.00, 12.83, 12.201469, 0, 0, -122, 280, -141 -ATT, 0.00, -0.18, -2.00, -1.97, 0.00, 94.97, 94.33 -GPS, 3, 594464200, 7, 2.66, 44.0290217, -77.7367421, 13.08, 99.46, 0.25, 303.78 -ATT, 0.00, 0.33, -2.24, -1.23, 0.00, 94.85, 94.33 -CTUN, 174, 0.00, 12.98, 11.862492, 0, 0, -125, 282, -141 -ATT, 0.00, 0.18, -2.24, -1.49, 0.00, 94.60, 94.33 -CTUN, 174, 0.00, 12.64, 11.664533, 0, 0, -127, 256, -141 -GPS, 3, 594464400, 7, 2.66, 44.0290219, -77.7367421, 12.78, 99.07, 0.24, 305.95 -CTUN, 174, 0.00, 12.20, 11.551405, 0, 0, -129, 279, -141 -ATT, 0.00, 0.06, -2.12, -2.96, 0.00, 94.46, 94.33 -CTUN, 175, 0.00, 12.05, 11.369087, 0, 0, -129, 270, -141 -ATT, 0.00, -0.31, -2.24, -2.86, 0.00, 94.28, 94.33 -GPS, 3, 594464600, 7, 2.66, 44.0290221, -77.7367422, 12.53, 98.66, 0.28, 303.47 -CTUN, 175, 0.00, 12.07, 11.311864, 0, 0, -129, 279, -141 -ATT, 0.00, 0.85, -2.36, -2.48, 0.00, 93.75, 94.33 -CTUN, 175, 0.00, 11.82, 11.087101, 0, 0, -128, 292, -141 -GPS, 3, 594464800, 7, 2.66, 44.0290222, -77.7367426, 12.21, 98.33, 0.32, 304.70 -ATT, 0.00, 1.10, -2.36, -3.89, 0.00, 93.21, 94.33 -CTUN, 175, 0.00, 11.62, 10.917410, 0, 0, -131, 257, -141 -ATT, 0.00, -1.60, -2.12, -3.38, 0.00, 93.11, 94.33 -GPS, 3, 594465000, 7, 2.66, 44.0290223, -77.7367431, 11.96, 97.99, 0.35, 299.16 -CTUN, 174, 0.00, 11.24, 10.762864, 0, 0, -127, 312, -141 -ATT, 0.00, 0.24, -2.00, -2.46, 0.00, 92.71, 94.33 -PM, 0, 0, 50, 77, 1000, 13000, 9, 0 -CTUN, 174, 0.00, 11.23, 10.550889, 0, 0, -127, 277, -141 -ATT, 0.00, 0.18, -2.00, -1.13, 0.00, 92.74, 94.33 -GPS, 3, 594465200, 7, 2.66, 44.0290224, -77.7367437, 11.63, 97.65, 0.35, 288.50 -CTUN, 174, 0.00, 11.01, 10.325151, 0, 0, -120, 256, -140 -ATT, 0.00, -2.16, -1.77, -0.84, 0.00, 93.05, 94.33 -CTUN, 174, 0.00, 10.63, 10.240535, 0, 0, -118, 280, -141 -GPS, 3, 594465400, 7, 2.66, 44.0290225, -77.7367441, 11.31, 97.31, 0.34, 285.11 -ATT, 0.00, -0.65, -1.65, -1.46, 0.00, 93.41, 94.33 -CTUN, 175, 0.00, 10.65, 10.042678, 0, 0, -121, 256, -141 -ATT, 0.00, 0.34, -1.53, -1.79, 0.00, 93.79, 94.33 -GPS, 3, 594465600, 7, 2.66, 44.0290226, -77.7367448, 11.10, 97.04, 0.38, 286.48 -CTUN, 174, 0.00, 10.45, 9.915901, 0, 0, -120, 278, -141 -ATT, 0.00, -0.32, -1.41, -1.36, 0.00, 94.25, 94.33 -CTUN, 174, 0.00, 10.36, 9.717994, 0, 0, -123, 267, -141 -ATT, 0.00, 0.39, -1.41, -1.57, 0.00, 94.38, 94.33 -GPS, 3, 594465800, 7, 2.66, 44.0290229, -77.7367454, 10.76, 96.75, 0.45, 291.19 -CTUN, 174, 0.00, 10.23, 9.505462, 0, 0, -123, 272, -141 -ATT, 0.00, -0.11, -1.41, -1.32, 0.00, 94.74, 94.33 -GPS, 3, 594466000, 7, 2.66, 44.0290230, -77.7367460, 10.49, 96.40, 0.45, 291.19 -ATT, 0.00, -0.44, -1.41, -1.71, 0.00, 94.99, 94.33 -CTUN, 174, 0.00, 10.21, 9.308712, 0, 0, -123, 271, -141 -ATT, 0.00, 0.28, -1.41, -1.86, 0.00, 95.13, 94.33 -CTUN, 174, 0.00, 10.12, 9.139888, 0, 0, -122, 267, -141 -GPS, 3, 594466200, 7, 2.66, 44.0290231, -77.7367467, 10.28, 96.08, 0.43, 290.90 -CTUN, 174, 0.00, 9.92, 9.083538, 0, 0, -123, 266, -141 -ATT, 0.00, -0.50, -1.53, -1.07, 0.00, 95.54, 94.33 -CTUN, 174, 0.00, 10.13, 8.885449, 0, 0, -124, 266, -141 -ATT, 0.00, 0.17, -1.53, -1.95, 0.00, 95.68, 94.33 -GPS, 3, 594466400, 7, 2.66, 44.0290235, -77.7367474, 9.95, 95.72, 0.46, 289.82 -CTUN, 174, 0.00, 9.87, 8.730204, 0, 0, -125, 264, -141 -ATT, 0.00, -0.33, -1.41, -1.08, 0.00, 95.84, 94.33 -CTUN, 174, 0.00, 9.64, 8.518032, 0, 0, -128, 264, -141 -ATT, 0.00, 0.68, -1.41, -0.93, 0.00, 95.72, 94.33 -GPS, 3, 594466600, 7, 2.66, 44.0290236, -77.7367482, 9.76, 95.39, 0.52, 295.01 -CTUN, 174, 0.00, 9.22, 8.391183, 0, 0, -132, 266, -141 -ATT, -1.76, -0.04, -1.41, -2.09, 0.00, 95.69, 94.33 -GPS, 3, 594466800, 7, 2.66, 44.0290239, -77.7367491, 9.49, 95.02, 0.49, 294.17 -CTUN, 174, 0.00, 7.55, 8.235806, 0, 0, -132, 270, -141 -ATT, -2.93, -1.38, -1.65, -1.58, 0.00, 95.54, 94.33 -CTUN, 174, 0.00, 6.86, 7.996199, 0, 0, -134, 298, -141 -ATT, -4.34, -1.99, -2.24, -1.48, 0.00, 95.51, 94.33 -GPS, 3, 594467000, 7, 2.66, 44.0290241, -77.7367501, 9.10, 94.68, 0.52, 294.69 -CTUN, 174, 0.00, 6.23, 7.939585, 0, 0, -133, 266, -141 -ATT, -5.05, -2.94, -3.54, -3.44, 0.00, 95.38, 94.33 -GPS, 3, 594467200, 7, 2.66, 44.0290244, -77.7367509, 8.73, 94.32, 0.53, 294.81 -ATT, -4.81, -4.01, -3.89, -1.23, 0.00, 95.39, 94.33 -CTUN, 175, 0.00, 6.38, 7.699783, 0, 0, -118, 307, -141 -CTUN, 174, 0.00, 5.59, 7.445476, 0, 0, -116, 260, -141 -ATT, -4.58, -4.47, -4.01, -5.42, 0.00, 95.36, 94.33 -GPS, 3, 594467400, 7, 2.66, 44.0290249, -77.7367518, 8.27, 94.02, 0.53, 294.81 -CTUN, 174, 0.00, 5.48, 7.388793, 0, 0, -115, 312, -141 -ATT, -4.46, -3.21, -4.01, -4.25, 0.00, 94.97, 94.33 -CTUN, 174, 0.00, 5.30, 7.134498, 0, 0, -98, 298, -141 -ATT, -4.11, -3.49, -4.25, -4.47, 0.00, 94.68, 94.33 -GPS, 3, 594467600, 7, 2.66, 44.0290254, -77.7367521, 7.81, 93.71, 0.56, 301.18 -CTUN, 174, 0.00, 5.36, 7.078148, 0, 0, -91, 296, -141 -ATT, -3.40, -4.00, -4.25, -3.31, 0.00, 94.00, 94.33 -CTUN, 174, 0.00, 5.17, 6.880652, 0, 0, -71, 272, -141 -ATT, -2.70, -3.06, -4.25, -3.83, 0.00, 93.59, 94.33 -GPS, 3, 594467800, 7, 2.66, 44.0290261, -77.7367524, 7.47, 93.45, 0.39, 307.40 -CTUN, 174, 0.00, 5.20, 6.723262, 0, 0, -62, 282, -141 -ATT, -2.58, -3.10, -4.25, -3.60, 0.00, 93.34, 94.33 -ATT, 0.00, -2.30, -3.07, -4.03, 0.00, 93.23, 94.33 -CTUN, 157, 0.00, 5.08, 6.570187, 0, 0, -57, 282, -141 -GPS, 3, 594468000, 7, 2.66, 44.0290269, -77.7367524, 7.24, 93.28, 0.44, 324.85 -ATT, 0.00, -1.03, -2.59, -3.57, 0.00, 93.10, 94.33 -CTUN, 157, 0.00, 4.87, 6.297755, 0, 0, -59, 263, -152 -GPS, 3, 594468200, 8, 2.28, 44.0290278, -77.7367520, 6.84, 93.09, 0.50, 353.25 -ATT, 0.00, -1.27, -2.59, -2.84, 0.00, 93.16, 94.33 -CTUN, 143, 0.00, 4.85, 6.126254, 0, 0, -61, 264, -160 -ATT, 0.00, -0.38, -2.59, -2.88, 0.00, 93.10, 94.33 -CTUN, 137, 0.00, 4.75, 5.948460, 0, 0, -72, 265, -163 -GPS, 3, 594468400, 8, 2.28, 44.0290286, -77.7367517, 6.69, 92.93, 0.45, 358.35 -CTUN, 136, 0.00, 5.06, 5.764894, 0, 0, -78, 271, -165 -ATT, 0.00, -1.23, -2.59, -2.72, 0.00, 93.26, 94.33 -CTUN, 134, 0.00, 4.99, 5.601742, 0, 0, -85, 271, -165 -ATT, 0.00, -0.15, -2.59, -2.90, 0.00, 93.10, 94.33 -GPS, 3, 594468600, 8, 2.28, 44.0290295, -77.7367514, 6.32, 92.75, 0.45, 358.35 -CTUN, 134, 0.00, 4.69, 5.518284, 0, 0, -83, 263, -166 -ATT, 0.00, -0.72, -2.59, -2.88, 0.00, 93.10, 94.33 -GPS, 3, 594468800, 8, 2.28, 44.0290304, -77.7367511, 6.14, 92.56, 0.46, 1.67 -ATT, 0.00, 0.12, -2.59, -2.25, 0.00, 92.92, 94.33 -CTUN, 134, 0.00, 4.45, 5.302716, 0, 0, -88, 258, -166 -ATT, 0.00, -0.18, -2.71, -2.64, 0.00, 93.06, 94.33 -CTUN, 134, 0.00, 4.21, 4.952861, 0, 0, -94, 284, -166 -GPS, 3, 594469000, 8, 2.28, 44.0290312, -77.7367509, 5.79, 92.37, 0.50, 4.52 -CTUN, 136, 0.00, 4.34, 4.785707, 0, 0, -95, 271, -165 -ATT, 0.00, -0.07, -2.59, -2.86, 0.00, 93.09, 94.33 -DU32, 7, 426229 -CURR, 136, 93854, 1403, 1604, 4984, 145.928890 -CTUN, 134, 0.00, 4.27, 4.638982, 0, 0, -95, 277, -165 -ATT, 0.00, 0.02, -2.59, -2.51, 0.00, 93.21, 94.33 -GPS, 3, 594469200, 8, 2.28, 44.0290323, -77.7367507, 5.45, 92.20, 0.56, 1.63 -CTUN, 135, 0.00, 4.29, 4.539546, 0, 0, -96, 274, -165 -ATT, 0.00, -0.51, -2.48, -2.54, 0.00, 93.46, 94.33 -CTUN, 135, 0.00, 4.57, 4.325079, 0, 0, -99, 262, -165 -ATT, 0.00, -0.15, -2.59, -2.27, 0.00, 93.52, 94.33 -GPS, 3, 594469400, 8, 2.28, 44.0290331, -77.7367505, 5.13, 91.98, 0.48, 1.04 -CTUN, 135, 0.00, 4.60, 4.159294, 0, 0, -101, 260, -165 -ATT, 0.00, -0.08, -2.59, -2.31, 0.00, 93.64, 94.33 -CTUN, 135, 0.00, 4.01, 3.961895, 0, 0, -105, 263, -165 -GPS, 3, 594469600, 8, 2.28, 44.0290339, -77.7367502, 4.91, 91.76, 0.48, 1.04 -ATT, 0.00, 0.10, -2.59, -2.28, 0.00, 93.73, 94.33 -CTUN, 135, 0.00, 3.76, 3.762033, 0, 0, -111, 267, -165 -ATT, 0.00, 0.12, -2.48, -2.45, 0.00, 93.85, 94.33 -GPS, 3, 594469800, 8, 2.28, 44.0290348, -77.7367500, 4.65, 91.54, 0.44, 2.86 -CTUN, 135, 0.00, 4.28, 3.581405, 0, 0, -116, 276, -165 -ATT, 0.00, 0.16, -2.36, -2.92, 0.00, 93.90, 94.33 -CTUN, 136, 0.00, 3.90, 3.317253, 0, 0, -116, 247, -165 -ATT, 0.00, 0.23, -2.24, -2.47, 0.00, 93.89, 94.33 -GPS, 3, 594470000, 8, 2.28, 44.0290356, -77.7367499, 4.38, 91.31, 0.40, 358.81 -CTUN, 135, 0.00, 3.70, 3.250883, 0, 0, -116, 278, -165 -ATT, 0.00, 0.25, -2.12, -2.05, 0.00, 93.84, 94.33 -CTUN, 136, 0.00, 3.61, 3.002835, 0, 0, -120, 254, -165 -ATT, 0.00, 0.34, -1.77, -2.72, 0.00, 93.93, 94.33 -GPS, 3, 594470200, 8, 2.28, 44.0290364, -77.7367498, 4.08, 91.10, 0.40, 358.81 -CTUN, 135, 0.00, 3.08, 2.903816, 0, 0, -122, 279, -165 -ATT, 0.00, 0.26, -1.65, -1.95, 0.00, 93.81, 94.33 -CTUN, 135, 0.00, 2.99, 2.655827, 0, 0, -127, 270, -165 -GPS, 3, 594470400, 8, 2.28, 44.0290369, -77.7367497, 3.73, 90.87, 0.43, 359.44 -ATT, 0.00, -0.16, -1.29, -1.82, 0.00, 93.70, 94.33 -CTUN, 135, 0.00, 2.92, 2.523227, 0, 0, -127, 269, -165 -ATT, 0.00, -0.25, -1.18, -1.71, 0.00, 93.49, 94.33 -CTUN, 135, 0.00, 2.78, 2.308496, 0, 0, -127, 271, -165 -GPS, 3, 594470600, 8, 2.28, 44.0290373, -77.7367496, 3.49, 90.63, 0.31, 359.65 -CTUN, 136, 0.00, 2.86, 2.275509, 0, 0, -127, 272, -165 -ATT, 0.00, 0.23, -0.23, -1.79, 0.00, 93.24, 94.33 -CTUN, 139, 0.00, 2.70, 1.977924, 0, 0, -128, 267, -163 -ATT, 0.00, -0.34, 0.00, -1.18, 0.00, 93.22, 94.33 -GPS, 3, 594470800, 8, 2.28, 44.0290379, -77.7367497, 3.12, 90.40, 0.25, 358.53 -CTUN, 144, 0.00, 2.42, 1.864797, 0, 0, -130, 270, -161 -ATT, 0.00, -0.21, 0.00, -0.98, 0.00, 93.23, 94.33 -CTUN, 146, 0.00, 2.33, 1.641489, 0, 0, -132, 284, -158 -ATT, 0.00, 0.10, 0.00, -0.92, 0.00, 93.17, 94.33 -GPS, 3, 594471000, 8, 2.28, 44.0290386, -77.7367498, 2.79, 90.16, 0.39, 345.16 -CTUN, 153, 0.00, 2.27, 1.531763, 0, 0, -132, 262, -157 -ATT, 0.00, -0.18, 0.00, -0.18, 0.00, 93.13, 94.33 -CTUN, 210, 0.00, 2.25, 1.332452, 0, 0, -131, 283, -126 -GPS, 3, 594471200, 8, 2.28, 44.0290391, -77.7367498, 2.53, 89.90, 0.39, 345.16 -ATT, 0.00, 0.18, 0.00, 0.22, 0.00, 93.02, 94.33 -CTUN, 270, 0.00, 2.07, 1.237100, 0, 0, -131, 283, -94 -ATT, 0.00, 0.65, 0.00, -0.45, 0.00, 92.93, 94.33 -CTUN, 323, 0.00, 1.85, 1.168435, 0, 0, -126, 268, -72 -GPS, 3, 594471400, 8, 2.28, 44.0290396, -77.7367501, 2.33, 89.67, 0.37, 337.12 -ATT, 0.00, -0.01, 0.00, -0.54, 0.00, 92.99, 94.33 -CTUN, 374, 0.00, 1.77, 1.110021, 0, 0, -115, 275, -29 -ATT, 0.00, 0.21, 0.00, 0.02, 0.00, 93.02, 94.33 -GPS, 3, 594471600, 8, 2.28, 44.0290402, -77.7367507, 2.02, 89.48, 0.40, 330.53 -CTUN, 428, 0.00, 2.15, 1.106414, 0, 0, -116, 280, -3 -ATT, 0.00, -0.06, 0.00, -1.62, 0.00, 92.97, 94.33 -CTUN, 446, 0.00, 1.59, 1.106414, 0, 0, -92, 326, 0 -ATT, 0.00, 0.02, 0.00, -0.73, 0.00, 92.92, 94.33 -GPS, 3, 594471800, 8, 2.28, 44.0290408, -77.7367512, 1.77, 89.28, 0.44, 327.28 -CTUN, 476, 0.00, 1.65, 1.106414, 0, 0, -72, 311, 0 -ATT, 0.00, 0.31, 0.00, -0.65, 0.00, 92.81, 94.33 -CTUN, 490, 0.00, 1.41, 1.106414, 0, 0, -48, 268, 0 -GPS, 3, 594472000, 8, 2.28, 44.0290414, -77.7367520, 1.67, 89.16, 0.44, 327.28 -ATT, 0.00, -0.10, 0.00, 1.41, 0.00, 92.81, 94.33 -CTUN, 488, 0.00, 1.52, 1.106414, 0, 0, -39, 294, 0 -ATT, 0.00, 0.42, 0.00, 0.26, 0.00, 92.85, 94.33 -GPS, 3, 594472200, 8, 2.28, 44.0290420, -77.7367529, 1.60, 89.12, 0.45, 323.02 -CTUN, 488, 0.00, 1.41, 1.106414, 0, 0, -32, 280, 0 -ATT, 0.00, -0.35, 0.00, 0.12, 0.00, 93.10, 94.33 -CTUN, 488, 0.00, 1.43, 1.106414, 0, 0, -38, 287, 0 -ATT, 0.00, 0.31, 0.00, -0.21, 0.00, 93.12, 94.33 -GPS, 3, 594472400, 8, 2.28, 44.0290425, -77.7367541, 1.50, 89.12, 0.36, 310.75 -CTUN, 488, 0.00, 1.34, 1.106414, 0, 0, -37, 300, 0 -ATT, 0.00, 0.36, 0.00, -0.11, 0.00, 93.13, 94.33 -CTUN, 488, 0.00, 1.34, 1.106414, 0, 0, -36, 287, 0 -ATT, 0.00, 0.45, -1.65, -0.38, 0.00, 92.99, 94.33 -GPS, 3, 594472600, 8, 2.28, 44.0290430, -77.7367552, 1.42, 89.13, 0.36, 310.75 -CTUN, 488, 0.00, 1.33, 1.106414, 0, 0, -32, 288, 0 -ATT, 0.00, -0.35, -2.48, -0.48, 0.00, 92.97, 94.33 -CTUN, 490, 0.00, 1.32, 1.106414, 0, 0, -28, 273, 0 -GPS, 3, 594472800, 8, 2.27, 44.0290437, -77.7367566, 1.37, 89.13, 0.36, 302.01 -ATT, 0.00, -0.50, -2.36, -1.55, 0.00, 93.10, 94.33 -CTUN, 607, 0.00, 1.35, 1.106414, 0, 0, -23, 287, 0 -ATT, 0.00, -0.06, -2.48, -1.43, 0.00, 93.19, 94.33 -GPS, 3, 594473000, 8, 2.27, 44.0290443, -77.7367580, 1.31, 89.12, 0.52, 300.06 -CTUN, 777, 0.00, 1.31, 1.121012, 0, 0, -19, 286, 41 -ATT, 0.00, -0.09, -2.36, -2.24, 0.00, 93.37, 94.33 -CTUN, 833, 0.00, 1.25, 1.349079, 0, 0, -11, 302, 143 -ATT, 0.00, -0.25, -2.36, -1.92, 0.00, 93.53, 94.33 -GPS, 3, 594473200, 8, 2.27, 44.0290449, -77.7367593, 1.28, 89.17, 0.57, 299.89 -CTUN, 873, 0.00, 1.27, 1.423180, 0, 0, -10, 326, 149 -ATT, 0.00, 0.10, -2.36, -3.27, 0.00, 93.80, 94.33 -CTUN, 890, 0.00, 1.45, 1.702056, 0, 0, 22, 343, 181 -ATT, 0.00, 0.09, -2.24, -3.42, 0.00, 93.93, 94.33 -GPS, 3, 594473400, 8, 2.27, 44.0290453, -77.7367606, 1.29, 89.21, 0.57, 299.89 -CTUN, 907, 0.00, 1.71, 1.890950, 0, 0, 51, 341, 191 -ATT, 0.00, -0.49, -2.48, -3.16, 0.00, 94.02, 94.33 -GPS, 3, 594473600, 8, 2.27, 44.0290456, -77.7367617, 1.47, 89.31, 0.49, 296.23 -ATT, 0.00, -0.74, -3.66, -1.56, 0.00, 94.06, 94.33 -CTUN, 904, 0.00, 1.66, 2.198620, 0, 0, 96, 322, 191 -ATT, 0.00, -0.22, -4.60, -1.43, 0.00, 94.10, 94.33 -CTUN, 906, 0.00, 1.77, 2.465711, 0, 0, 113, 280, 191 -GPS, 3, 594473800, 8, 2.27, 44.0290459, -77.7367626, 1.65, 89.54, 0.49, 296.23 -CTUN, 906, 0.00, 1.88, 2.657734, 0, 0, 125, 273, 191 -ATT, 0.00, -0.64, -5.43, -5.01, 0.00, 94.05, 94.33 -CTUN, 909, 0.00, 2.07, 2.848024, 0, 0, 122, 286, 191 -ATT, 0.00, -0.59, -10.15, -4.35, 0.00, 94.22, 94.33 -GPS, 3, 594474000, 8, 2.27, 44.0290462, -77.7367635, 1.93, 89.82, 0.35, 291.77 -CTUN, 925, 0.00, 2.20, 2.925301, 0, 0, 121, 281, 193 -ATT, 0.00, -0.20, -11.10, -5.94, 0.00, 94.35, 94.33 -CTUN, 927, 0.00, 2.51, 3.230730, 0, 1, 113, 324, 204 -GPS, 3, 594474200, 8, 2.27, 44.0290462, -77.7367642, 2.20, 90.11, 0.26, 290.96 -ATT, 0.00, 0.17, -11.57, -8.85, 0.00, 94.28, 94.33 -DU32, 7, 426229 -CURR, 942, 106677, 1387, 1818, 5006, 166.691390 -CTUN, 959, 0.00, 2.52, 3.480227, 0, 2, 117, 302, 213 -ATT, 0.00, -0.04, -10.39, -10.47, 0.00, 94.39, 94.33 -GPS, 3, 594474400, 8, 2.27, 44.0290462, -77.7367644, 2.40, 90.38, 0.26, 290.96 -CTUN, 997, 0.00, 2.72, 3.715601, 0, 2, 124, 307, 242 -ATT, 0.00, 0.19, -9.44, -9.84, 0.00, 94.37, 94.33 -CTUN, 997, 0.00, 3.04, 4.088010, 0, 2, 143, 321, 247 -ATT, 0.00, 0.07, -9.44, -8.91, 0.00, 94.39, 94.33 -GPS, 3, 594474600, 8, 2.27, 44.0290461, -77.7367643, 2.74, 90.66, 0.01, 290.96 -CTUN, 997, 0.00, 3.39, 4.287271, 0, 2, 157, 299, 248 -ATT, 0.00, -0.02, -8.74, -8.72, 0.00, 94.34, 94.33 -CTUN, 997, 0.00, 3.78, 4.633630, 0, 1, 172, 317, 248 -ATT, 0.00, 0.13, -8.03, -8.45, 0.00, 94.26, 94.33 -GPS, 3, 594474800, 8, 2.27, 44.0290455, -77.7367632, 3.16, 90.96, 0.49, 167.82 -CTUN, 997, 0.00, 3.60, 4.909217, 0, 1, 187, 276, 248 -ATT, 0.00, 0.13, -7.32, -8.05, 0.00, 94.31, 94.33 -CTUN, 998, 0.00, 3.97, 5.179730, 0, 1, 187, 304, 248 -GPS, 3, 594475000, 8, 2.27, 44.0290447, -77.7367616, 3.45, 91.36, 0.49, 167.82 -ATT, 0.00, -0.11, -6.14, -7.26, 0.00, 94.37, 94.33 -CTUN, 997, 0.00, 4.02, 5.453324, 0, 1, 190, 302, 248 -ATT, 0.00, 0.14, -5.19, -6.96, 0.00, 94.58, 94.33 -PM, 0, 0, 50, 75, 1001, 12000, 10, 0 -GPS, 3, 594475200, 8, 2.27, 44.0290436, -77.7367595, 3.89, 91.74, 0.76, 140.08 -CTUN, 996, 0.00, 4.37, 5.724888, 0, 1, 189, 291, 248 -ATT, 0.00, 0.79, -4.96, -6.58, 0.00, 94.55, 94.33 -CTUN, 997, 0.00, 4.80, 6.073343, 0, 0, 190, 313, 247 -ATT, 0.00, 0.13, -4.37, -5.55, 0.00, 94.58, 94.33 -GPS, 3, 594475400, 8, 2.27, 44.0290422, -77.7367570, 4.39, 92.13, 1.00, 131.12 -CTUN, 997, 0.00, 4.94, 6.321953, 0, 0, 194, 311, 248 -ATT, 0.00, 0.12, -3.30, -5.05, 0.00, 94.54, 94.33 -GPS, 3, 594475600, 8, 2.27, 44.0290407, -77.7367542, 4.80, 92.55, 1.20, 128.79 -ATT, 0.00, 0.00, -2.95, -4.56, 0.00, 94.48, 94.33 -CTUN, 996, 0.00, 5.38, 6.793408, 0, 0, 203, 293, 247 -ATT, 0.00, 0.20, -2.59, -3.44, 0.00, 94.49, 94.33 -CTUN, 997, 0.00, 6.36, 7.140936, 0, 0, 205, 320, 248 -GPS, 3, 594475800, 8, 2.27, 44.0290388, -77.7367513, 5.18, 92.97, 1.35, 127.56 -CTUN, 997, 0.00, 6.11, 7.214869, 0, 0, 206, 294, 248 -ATT, 0.00, 0.10, -2.24, -3.56, 0.00, 94.41, 94.33 -CTUN, 997, 0.00, 6.85, 7.662022, 0, 0, 210, 288, 248 -ATT, 0.00, 0.06, -2.00, -2.45, 0.00, 94.40, 94.33 -GPS, 3, 594476000, 8, 2.27, 44.0290373, -77.7367485, 5.70, 93.44, 1.49, 129.15 -CTUN, 997, 0.00, 7.28, 7.911314, 0, 0, 207, 305, 247 -ATT, 0.00, 0.71, -1.88, -2.49, 0.00, 94.43, 94.33 -CTUN, 997, 0.00, 7.21, 8.180839, 0, 0, 204, 286, 247 -ATT, 0.00, 0.90, -1.88, -2.49, 0.00, 94.44, 94.33 -GPS, 3, 594476200, 8, 2.27, 44.0290358, -77.7367456, 6.16, 93.91, 1.39, 128.77 -CTUN, 998, 0.00, 8.97, 8.358994, 0, 0, 203, 294, 247 -ATT, 0.00, -0.32, -1.41, -1.64, 0.00, 94.61, 94.33 -CTUN, 997, 0.00, 11.45, 8.627868, 0, 0, 201, 287, 248 -GPS, 3, 594476400, 8, 2.27, 44.0290340, -77.7367425, 6.62, 94.35, 1.53, 127.98 -ATT, 0.00, -0.25, -1.53, -1.59, 0.00, 94.66, 94.33 -CTUN, 997, 0.00, 15.97, 9.023416, 0, 0, 198, 286, 248 -ATT, 0.00, 0.43, -1.53, -2.02, 0.00, 94.63, 94.33 -GPS, 3, 594476600, 8, 2.27, 44.0290322, -77.7367397, 7.52, 94.80, 1.53, 127.98 -CTUN, 997, 0.00, 16.67, 9.197879, 0, 0, 199, 193, 248 -ATT, 0.00, 0.12, -1.41, -1.16, 0.00, 94.96, 94.33 -CTUN, 997, 0.00, 19.15, 9.545108, 0, 0, 170, 145, 248 -ATT, 0.00, -0.44, -1.41, 2.43, 0.00, 95.40, 94.33 -GPS, 3, 594476800, 8, 2.27, 44.0290308, -77.7367369, 8.67, 95.20, 1.44, 128.50 -CTUN, 997, 0.00, 14.63, 9.743741, 0, 0, 141, 130, 248 -ATT, 0.00, -1.51, -1.41, 3.92, 0.00, 95.84, 94.33 -CTUN, 996, 0.00, 14.02, 10.065366, 0, 0, 96, 130, 247 -ATT, 0.00, -1.16, -1.41, -2.02, 0.00, 95.99, 94.33 -GPS, 3, 594477000, 8, 2.27, 44.0290293, -77.7367345, 9.39, 95.51, 1.17, 128.98 -CTUN, 997, 0.00, 16.57, 10.363456, 0, 0, 49, 315, 247 -ATT, 0.00, 1.37, -1.29, -4.62, 0.00, 95.74, 94.33 -CTUN, 996, 0.00, 14.26, 10.584755, 0, 0, 35, 324, 247 -GPS, 3, 594477200, 8, 2.27, 44.0290278, -77.7367319, 9.96, 95.71, 1.19, 129.50 -ATT, 0.00, -0.63, -1.41, -3.00, 0.00, 95.22, 94.33 -CTUN, 996, 0.00, 14.01, 10.860574, 0, 0, 52, 256, 247 -ATT, 0.00, -0.61, -1.41, 0.15, 0.00, 94.85, 94.33 -CTUN, 997, 0.00, 17.63, 11.081609, 0, 0, 55, 341, 247 -GPS, 3, 594477400, 8, 2.27, 44.0290266, -77.7367294, 10.29, 95.70, 1.05, 127.86 -CTUN, 997, 0.00, 18.00, 11.356475, 0, 0, 82, 246, 247 -ATT, 0.00, 0.05, -1.41, -2.24, 0.00, 94.68, 94.33 -CTUN, 997, 0.00, 17.85, 11.552865, 0, 0, 90, 220, 248 -ATT, 0.00, 0.84, -1.41, -0.35, 0.00, 94.60, 94.33 -GPS, 3, 594477600, 8, 2.27, 44.0290252, -77.7367270, 11.11, 95.78, 1.06, 127.93 -CTUN, 996, 0.00, 13.53, 11.727357, 0, 0, 86, 224, 248 -DU32, 7, 426229 -CURR, 996, 115003, 1428, 785, 4897, 181.241040 -ATT, 0.00, 0.13, -1.41, 1.37, 0.00, 95.05, 94.33 -CTUN, 996, 0.00, 18.43, 12.023623, 0, 0, 67, 304, 248 -ATT, 0.00, -0.21, -1.41, -2.07, 0.00, 95.31, 94.33 -GPS, 3, 594477800, 8, 2.27, 44.0290241, -77.7367249, 11.63, 95.93, 1.06, 127.93 -CTUN, 996, 0.00, 16.44, 12.323941, 0, 0, 56, 227, 247 -ATT, 0.00, 0.22, -1.41, -4.34, 0.00, 95.30, 94.33 -CTUN, 997, 0.00, 16.45, 12.693550, 0, 0, 53, 292, 248 -GPS, 3, 594478000, 8, 2.27, 44.0290229, -77.7367227, 12.11, 96.00, 1.03, 127.55 -ATT, 0.00, -0.21, -1.41, 0.02, 0.00, 95.27, 94.33 -CTUN, 996, 0.00, 19.72, 12.916512, 0, 0, 53, 260, 248 -ATT, 0.00, -0.25, -1.41, -1.42, 0.00, 95.31, 94.33 -GPS, 3, 594478200, 8, 2.27, 44.0290217, -77.7367208, 12.60, 96.02, 0.98, 126.32 -CTUN, 997, 0.00, 17.95, 13.165049, 0, 0, 57, 260, 247 -ATT, 0.00, 0.17, -1.29, -1.63, 0.00, 95.31, 94.33 -CTUN, 997, 0.00, 18.87, 13.485793, 0, 0, 57, 249, 248 -ATT, 0.00, 0.82, -1.18, -1.30, 0.00, 95.36, 94.33 -GPS, 3, 594478400, 8, 2.27, 44.0290207, -77.7367188, 13.28, 96.05, 0.88, 126.81 -CTUN, 996, 0.00, 18.96, 13.760123, 0, 0, 49, 282, 247 -ATT, 0.00, -0.26, -1.18, -1.47, 0.00, 95.44, 94.33 -CTUN, 996, 0.00, 17.50, 14.107283, 0, 0, 45, 267, 248 -ATT, 0.00, -0.25, -1.18, -1.72, 0.00, 95.28, 94.33 -GPS, 3, 594478600, 8, 2.27, 44.0290196, -77.7367171, 13.64, 96.09, 0.84, 128.95 -CTUN, 997, 0.00, 16.76, 14.356294, 0, 0, 43, 295, 248 -ATT, 0.00, -1.15, -1.06, -0.99, 0.00, 95.20, 94.33 -GPS, 3, 594478800, 8, 2.27, 44.0290186, -77.7367155, 14.01, 96.07, 0.84, 128.95 -CTUN, 997, 0.00, 16.18, 14.602805, 0, 0, 46, 289, 247 -ATT, 0.00, -0.80, -0.94, -1.88, 0.00, 95.00, 94.33 -DU32, 7, 426229 -CURR, 996, 117698, 1378, 2063, 4940, 185.387120 -CTUN, 996, 0.00, 14.58, 14.999996, 0, 0, 64, 319, 247 -ATT, 0.00, 0.07, -0.94, -2.10, 0.00, 94.77, 94.33 -GPS, 3, 594479000, 8, 2.27, 44.0290176, -77.7367139, 14.31, 96.04, 0.74, 130.91 -CTUN, 998, 0.00, 14.48, 15.174539, 0, 0, 76, 304, 248 -ATT, 0.00, -0.04, -0.82, -1.68, 0.00, 94.63, 94.33 -CTUN, 997, 0.00, 15.57, 15.597180, 0, 0, 110, 307, 248 -ATT, 0.00, 0.52, -0.47, -1.46, 0.00, 94.48, 94.33 -GPS, 3, 594479200, 8, 2.27, 44.0290168, -77.7367123, 14.53, 96.09, 0.72, 129.51 -CTUN, 997, 0.00, 16.43, 15.820420, 0, 0, 131, 324, 248 -ATT, 0.00, 0.44, -0.35, -0.56, 0.00, 94.47, 94.33 -GPS, 3, 594479400, 8, 2.27, 44.0290160, -77.7367108, 14.80, 96.22, 0.71, 128.05 -ATT, 0.00, -0.40, -0.23, 0.02, 0.00, 94.35, 94.33 -CTUN, 998, 0.00, 19.05, 16.042631, 0, 0, 147, 307, 247 -ATT, 0.00, -0.37, -0.23, 0.73, 0.00, 94.24, 94.33 -CTUN, 998, 0.00, 19.38, 16.539513, 0, 0, 162, 185, 248 -GPS, 3, 594479600, 8, 2.27, 44.0290153, -77.7367096, 15.45, 96.39, 0.71, 128.05 -CTUN, 998, 0.00, 19.40, 16.790707, 0, 0, 154, 188, 248 -ATT, 0.00, 0.12, -0.23, -1.35, 0.00, 94.47, 94.33 -CTUN, 998, 0.00, 18.42, 17.011307, 0, 0, 131, 280, 248 -ATT, 0.00, 1.10, -0.23, -0.12, 0.00, 94.55, 94.33 -GPS, 3, 594479800, 8, 2.27, 44.0290148, -77.7367085, 16.07, 96.59, 0.60, 127.32 -CTUN, 998, 0.00, 13.15, 17.210321, 0, 0, 112, 270, 248 -ATT, 0.00, 0.28, -0.23, 0.19, -0.12, 94.54, 94.31 -CTUN, 998, 0.00, 19.80, 17.607977, 0, 0, 103, 403, 248 -ATT, 0.00, -0.04, -0.23, -0.75, -0.60, 94.36, 94.03 -GPS, 3, 594480000, 8, 2.27, 44.0290143, -77.7367077, 16.19, 96.68, 0.52, 125.14 -CTUN, 998, 0.00, 16.71, 17.856035, 0, 0, 133, 259, 248 -ATT, 0.00, -0.52, -0.23, -2.10, -1.21, 93.73, 93.37 -CTUN, 997, 0.00, 15.23, 18.079622, 0, 0, 156, 309, 248 -GPS, 3, 594480200, 8, 2.27, 44.0290140, -77.7367071, 16.55, 96.78, 0.34, 125.77 -CTUN, 997, 0.00, 14.61, 18.352571, 0, 0, 169, 324, 248 -ATT, 0.00, -0.70, -0.23, 0.89, -1.58, 92.68, 92.44 -ATT, 0.00, -0.61, -0.23, -0.08, -1.70, 92.07, 91.64 -GPS, 3, 594480400, 8, 2.27, 44.0290137, -77.7367065, 16.80, 96.98, 0.27, 123.89 -CTUN, 997, 0.00, 15.31, 18.625868, 0, 0, 188, 312, 247 -ATT, 0.00, -0.05, -0.23, -0.57, -1.70, 91.38, 90.62 -GPS, 3, 594480600, 8, 2.27, 44.0290138, -77.7367062, 17.00, 97.22, 0.11, 120.02 -ATT, 0.00, 0.72, -0.47, 0.49, -1.95, 90.44, 89.27 -CTUN, 996, 0.00, 13.83, 19.021746, 0, 0, 210, 320, 248 -ATT, 0.00, -0.20, -1.18, -0.50, -2.07, 89.27, 88.30 -CTUN, 998, 0.00, 13.76, 19.518286, 0, 0, 210, 300, 248 -GPS, 3, 594480800, 8, 2.27, 44.0290138, -77.7367059, 17.28, 97.51, 0.08, 120.02 -CTUN, 997, 0.00, 13.56, 19.794083, 0, 0, 221, 340, 248 -ATT, 0.00, -0.29, -1.53, -1.56, -2.07, 87.83, 86.90 -CTUN, 997, 0.00, 13.74, 19.965067, 0, 0, 236, 319, 247 -ATT, 0.00, -0.02, -2.12, -2.27, -2.19, 86.75, 85.78 -GPS, 3, 594481000, 8, 2.27, 44.0290139, -77.7367059, 17.46, 97.77, 0.08, 120.02 -CTUN, 998, 0.00, 13.86, 20.287964, 0, 0, 270, 356, 248 -ATT, 0.00, -0.10, -2.24, -2.04, -2.07, 85.15, 84.47 -CTUN, 996, 0.00, 14.37, 20.535288, 0, 0, 299, 289, 248 -GPS, 3, 594481200, 8, 2.27, 44.0290142, -77.7367062, 17.80, 98.15, 0.06, 120.02 -ATT, 0.00, 0.18, -3.54, -1.24, -1.34, 83.82, 83.47 -CTUN, 997, 0.00, 14.65, 20.686548, 0, 0, 313, 323, 248 -ATT, 0.00, 0.90, -5.55, -1.71, -0.36, 83.01, 83.10 -CTUN, 997, 0.00, 14.97, 21.008263, 0, 0, 325, 271, 248 -GPS, 3, 594481400, 8, 2.27, 44.0290144, -77.7367063, 18.14, 98.61, 0.17, 120.02 -CTUN, 996, 0.00, 15.99, 21.260056, 0, 0, 328, 302, 248 -ATT, 0.00, -0.12, -9.09, -4.73, 0.00, 82.88, 83.10 -CTUN, 996, 0.00, 15.84, 21.528435, 0, 0, 321, 244, 247 -ATT, 0.00, 0.54, -9.44, -5.92, 0.00, 82.83, 83.10 -GPS, 3, 594481600, 8, 2.27, 44.0290148, -77.7367067, 18.63, 99.15, 0.12, 120.02 -CTUN, 996, 0.00, 15.91, 21.802273, 0, 1, 309, 308, 248 -ATT, 0.00, 0.96, -9.92, -6.94, 0.00, 82.95, 83.10 -CTUN, 996, 0.00, 16.10, 21.950554, 0, 1, 301, 295, 247 -ATT, 0.00, 0.07, -10.03, -8.15, 0.00, 82.93, 83.10 -GPS, 3, 594481800, 8, 2.27, 44.0290150, -77.7367072, 19.00, 99.71, 0.21, 46.09 -CTUN, 996, 0.00, 15.61, 22.296621, 0, 2, 298, 323, 247 -ATT, 0.00, -0.55, -9.92, -8.47, 0.00, 82.87, 83.10 -CTUN, 995, 0.00, 15.51, 22.519625, 0, 2, 298, 295, 247 -GPS, 3, 594482000, 8, 2.27, 44.0290152, -77.7367075, 19.31, 100.22, 0.15, 4.02 -ATT, 0.00, -0.53, -9.68, -9.86, 0.00, 82.94, 83.10 -CTUN, 906, 0.00, 15.65, 22.823658, 0, 2, 308, 283, 220 -ATT, 0.00, 0.24, -8.62, -9.05, 0.00, 82.87, 83.10 -GPS, 3, 594482200, 8, 2.27, 44.0290151, -77.7367073, 19.68, 100.72, 0.15, 4.02 -CTUN, 755, 0.00, 16.33, 22.996225, 0, 1, 305, 307, 143 -ATT, 0.00, -0.47, -7.20, -8.67, 0.00, 82.96, 83.10 -CTUN, 729, 0.00, 16.56, 23.116047, 0, 1, 310, 263, 82 -ATT, 0.00, 0.37, -6.49, -7.57, 0.00, 83.11, 83.10 -GPS, 3, 594482400, 8, 2.27, 44.0290147, -77.7367066, 20.03, 101.24, 0.25, 63.06 -CTUN, 730, 0.00, 17.42, 23.164745, 0, 1, 306, 299, 80 -ATT, 0.00, -0.16, -4.25, -6.53, 0.00, 83.22, 83.10 -CTUN, 731, 0.00, 17.84, 23.286297, 0, 0, 292, 274, 81 -GPS, 3, 594482600, 8, 2.27, 44.0290144, -77.7367056, 20.43, 101.75, 0.25, 63.06 -ATT, 0.00, -0.34, -2.12, -4.91, 0.00, 83.24, 83.10 -CTUN, 731, 0.00, 18.22, 23.399792, 0, 0, 276, 254, 81 -ATT, 0.00, 0.20, -0.70, -3.78, 0.00, 83.15, 83.10 -GPS, 3, 594482800, 8, 2.27, 44.0290136, -77.7367042, 20.76, 102.24, 0.64, 118.89 -CTUN, 731, 0.00, 18.74, 23.489170, 0, 0, 259, 292, 81 -ATT, 0.00, 0.44, 0.00, -2.72, 0.00, 83.13, 83.10 -CTUN, 718, 0.00, 18.94, 23.615362, 0, 0, 244, 290, 73 -ATT, 0.00, 0.17, 0.00, -2.45, 0.00, 83.14, 83.10 -GPS, 3, 594483000, 8, 2.27, 44.0290129, -77.7367028, 21.14, 102.70, 0.64, 118.89 -CTUN, 705, 0.00, 19.05, 23.663609, 0, 0, 235, 309, 68 -DU32, 7, 426229 -CURR, 703, 128254, 1378, 2084, 4962, 204.376890 -ATT, 0.00, -0.20, 0.00, -1.94, 0.00, 83.04, 83.10 -CTUN, 693, 0.00, 19.15, 23.734644, 0, 0, 231, 286, 61 -ATT, 0.00, -0.59, 0.00, -0.70, 0.00, 83.12, 83.10 -GPS, 3, 594483200, 8, 2.27, 44.0290122, -77.7367015, 21.41, 103.11, 0.62, 121.72 -CTUN, 686, 0.00, 19.61, 23.807728, 0, 0, 222, 268, 54 -ATT, 0.00, -0.83, 0.00, -0.41, 0.00, 83.10, 83.10 -CTUN, 674, 0.00, 19.97, 23.871225, 0, 0, 211, 279, 47 -GPS, 3, 594483400, 8, 2.27, 44.0290119, -77.7367005, 21.73, 103.47, 0.56, 122.68 -ATT, 0.00, -1.20, 0.00, 0.47, 0.00, 83.41, 83.10 -CTUN, 662, 0.00, 20.25, 23.907066, 0, 0, 202, 250, 44 -ATT, 0.00, -0.17, 0.00, -0.08, 0.00, 83.62, 83.10 -GPS, 3, 594483600, 8, 2.27, 44.0290114, -77.7366995, 22.00, 103.84, 0.40, 120.59 -CTUN, 659, 0.00, 20.17, 23.963633, 0, 0, 190, 272, 37 -ATT, 0.00, 1.20, 0.00, 1.03, 0.00, 83.66, 83.10 -CTUN, 650, 0.00, 20.38, 24.000381, 0, 0, 175, 287, 31 -ATT, 0.00, 0.96, 0.00, -0.23, 0.00, 83.62, 83.10 -GPS, 3, 594483800, 8, 2.27, 44.0290112, -77.7366989, 22.20, 104.18, 0.27, 120.59 -CTUN, 638, 0.00, 20.51, 24.020752, 0, 0, 170, 274, 27 -ATT, 0.00, 0.23, 0.00, 0.00, 0.00, 83.52, 83.10 -CTUN, 634, 0.00, 20.66, 24.055830, 0, 0, 160, 275, 21 -ATT, 0.00, 0.43, 0.00, 0.11, 0.00, 83.45, 83.10 -GPS, 3, 594484000, 8, 2.27, 44.0290111, -77.7366984, 22.39, 104.47, 0.27, 120.59 -CTUN, 636, 0.00, 20.80, 24.073708, 0, 0, 153, 262, 22 -DU32, 7, 426229 -CURR, 636, 130686, 1403, 1693, 4984, 208.151410 -ATT, 0.00, -0.05, 0.00, 0.07, 0.00, 83.47, 83.10 -CTUN, 636, 0.00, 21.16, 24.097773, 0, 0, 147, 272, 23 -ATT, 0.00, -0.76, 0.00, 0.12, 0.00, 83.78, 83.10 -GPS, 3, 594484200, 8, 2.27, 44.0290108, -77.7366982, 22.58, 104.76, 0.06, 120.59 -CTUN, 637, 0.00, 21.25, 24.122160, 0, 0, 138, 258, 22 -ATT, 0.00, 0.01, 0.00, -0.33, 0.00, 83.86, 83.10 -GPS, 3, 594484400, 8, 2.27, 44.0290108, -77.7366983, 22.71, 104.98, 0.06, 120.59 -CTUN, 603, 0.00, 21.21, 24.144621, 0, 0, 128, 284, 18 -ATT, 0.00, 0.67, 0.00, -0.41, 0.00, 84.01, 83.10 -CTUN, 546, 0.00, 21.31, 24.145531, 0, 0, 124, 241, 0 -ATT, 0.00, 0.19, 0.00, -0.88, 0.00, 83.98, 83.10 -GPS, 3, 594484600, 8, 2.27, 44.0290109, -77.7366989, 22.86, 105.20, 0.25, 180.17 -CTUN, 543, 0.00, 21.44, 24.145531, 0, 0, 118, 284, 0 -ATT, 0.00, -0.05, 0.00, 0.07, 0.00, 83.70, 83.10 -CTUN, 543, 0.00, 21.51, 24.145531, 0, 0, 110, 271, 0 -ATT, 0.00, 0.37, 0.00, -0.93, 0.00, 83.53, 83.10 -GPS, 3, 594484800, 8, 2.27, 44.0290111, -77.7366996, 22.97, 105.42, 0.25, 180.17 -CTUN, 544, 0.00, 21.70, 24.145531, 0, 0, 98, 282, 0 -ATT, 0.00, 0.10, 0.00, 0.38, 0.00, 83.39, 83.10 -CTUN, 544, 0.00, 21.82, 24.145531, 0, 0, 95, 299, 0 -GPS, 3, 594485000, 8, 2.27, 44.0290113, -77.7367005, 23.08, 105.58, 0.34, 251.07 -ATT, 0.00, -0.28, 0.00, -0.04, 0.00, 83.43, 83.10 -CTUN, 544, 0.00, 21.99, 24.145531, 0, 0, 89, 273, 0 -ATT, 0.00, -0.33, 0.00, -0.95, 0.00, 83.42, 83.10 -PM, 0, 0, 50, 75, 1000, 11452, 10, 0 -GPS, 3, 594485200, 8, 2.27, 44.0290115, -77.7367018, 23.15, 105.76, 0.45, 272.00 -CTUN, 543, 0.00, 22.10, 24.145531, 0, 0, 87, 290, 0 -ATT, 0.00, -0.23, 0.00, -0.21, 0.00, 83.32, 83.10 -CTUN, 543, 0.00, 22.31, 24.145531, 0, 0, 86, 268, 0 -ATT, 0.00, -0.14, 0.00, -0.28, 0.00, 83.25, 83.10 -GPS, 3, 594485400, 8, 2.27, 44.0290118, -77.7367032, 23.24, 105.90, 0.65, 284.53 -CTUN, 543, 0.00, 22.13, 24.145531, 0, 0, 83, 280, 0 -ATT, 0.00, 0.10, 0.00, 0.26, 0.00, 83.16, 83.10 -CTUN, 543, 0.00, 22.15, 24.145531, 0, 0, 78, 282, 0 -ATT, 0.00, 0.16, 0.00, 0.36, 0.00, 83.19, 83.10 -GPS, 3, 594485600, 8, 2.27, 44.0290122, -77.7367049, 23.33, 106.04, 0.79, 287.74 -CTUN, 543, 0.00, 22.32, 24.145531, 0, 0, 76, 265, 0 -ATT, 0.00, -0.56, 0.00, 0.29, 0.00, 83.27, 83.10 -CTUN, 543, 0.00, 22.49, 24.145531, 0, 0, 73, 280, 0 -GPS, 3, 594485800, 8, 2.27, 44.0290127, -77.7367068, 23.38, 106.16, 0.79, 287.74 -ATT, 0.00, -0.83, -7.79, 0.09, 0.00, 83.40, 83.10 -CTUN, 541, 0.00, 22.74, 24.145531, 0, 0, 66, 283, 0 -ATT, 0.00, -0.18, -10.27, -3.97, 0.00, 83.55, 83.10 -GPS, 3, 594486000, 8, 2.27, 44.0290132, -77.7367089, 23.46, 106.25, 0.96, 288.59 -CTUN, 541, 0.00, 23.02, 24.145531, 0, 1, 64, 272, 0 -ATT, 0.00, 0.57, -14.88, -7.35, 0.00, 83.58, 83.10 -CTUN, 543, 0.00, 22.37, 24.145531, 0, 1, 60, 277, 0 -ATT, 0.00, 0.42, -16.65, -9.53, 0.00, 83.56, 83.10 -GPS, 3, 594486200, 8, 2.27, 44.0290137, -77.7367110, 23.54, 106.36, 0.91, 287.90 -CTUN, 542, 0.00, 21.42, 24.145531, 0, 2, 59, 273, 0 -ATT, 0.00, -0.07, -18.42, -12.18, 0.00, 83.61, 83.10 -CTUN, 541, 0.00, 21.23, 24.145531, 0, 4, 53, 291, 0 -ATT, 0.00, 0.01, -20.78, -14.40, 0.00, 83.57, 83.10 -GPS, 3, 594486400, 8, 2.27, 44.0290139, -77.7367128, 23.51, 106.45, 0.91, 287.90 -CTUN, 543, 0.00, 20.65, 24.145531, 0, 6, 51, 287, 0 -ATT, 0.00, -0.72, -21.02, -17.49, 0.00, 83.44, 83.10 -GPS, 3, 594486600, 8, 2.27, 44.0290137, -77.7367140, 23.46, 106.51, 0.80, 285.88 -CTUN, 542, 0.00, 19.98, 24.145531, 0, 8, 53, 302, 0 -ATT, 0.00, 0.04, -17.12, -17.76, 0.00, 83.17, 83.10 -ATT, 0.00, 0.01, -12.16, -17.09, 0.00, 83.14, 83.10 -GPS, 3, 594486800, 8, 2.27, 44.0290134, -77.7367145, 23.35, 106.61, 0.28, 279.46 -CTUN, 541, 0.00, 20.08, 24.145531, 0, 7, 54, 301, 0 -ATT, 0.00, 0.38, -8.26, -15.03, 0.00, 82.96, 83.10 -CTUN, 542, 0.00, 21.12, 24.145531, 0, 5, 63, 315, 0 -GPS, 3, 594487000, 8, 2.27, 44.0290124, -77.7367136, 23.22, 106.71, 0.28, 279.46 -ATT, 0.00, 0.40, -6.25, -10.74, 0.00, 82.88, 83.10 -CTUN, 541, 0.00, 22.47, 24.145531, 0, 2, 69, 299, 0 -ATT, 0.00, -0.33, -4.13, -9.73, 0.00, 82.89, 83.10 -CTUN, 541, 0.00, 22.92, 24.145531, 0, 2, 82, 279, 0 -GPS, 3, 594487200, 8, 2.27, 44.0290113, -77.7367122, 23.26, 106.85, 0.52, 174.50 -CTUN, 541, 0.00, 23.55, 24.145531, 0, 0, 87, 266, 0 -ATT, 0.00, -0.35, -1.53, -6.46, 0.00, 82.75, 83.10 -CTUN, 541, 0.00, 24.29, 24.145531, 0, 0, 85, 231, 0 -ATT, 0.00, 0.39, 0.00, -4.25, 0.00, 82.90, 83.10 -GPS, 3, 594487400, 8, 2.27, 44.0290099, -77.7367101, 23.48, 107.01, 1.11, 139.66 -CTUN, 532, 0.00, 25.02, 24.145531, 0, 0, 78, 222, 0 -ATT, 0.00, -0.19, 0.00, -1.29, 0.00, 83.17, 83.10 -CTUN, 521, 0.00, 24.59, 24.145531, 0, 0, 63, 225, 0 -GPS, 3, 594487600, 8, 2.27, 44.0290085, -77.7367080, 23.69, 107.18, 1.11, 139.66 -ATT, 0.00, 0.63, 0.00, -0.84, 0.00, 83.27, 83.10 -CTUN, 492, 0.00, 24.53, 24.145531, 0, 0, 40, 233, 0 -ATT, 0.00, 0.30, 0.00, -1.23, 0.00, 83.29, 83.10 -CTUN, 448, 0.00, 24.53, 24.145531, 0, 0, 24, 264, 0 -GPS, 3, 594487800, 8, 2.27, 44.0290072, -77.7367059, 23.78, 107.30, 1.14, 136.63 -ATT, 0.00, -0.29, 0.00, -1.16, 0.00, 83.35, 83.10 -CTUN, 405, 0.00, 24.76, 24.145531, 0, 0, 14, 262, 0 -ATT, 0.00, -0.13, 0.00, -0.93, 0.00, 83.48, 83.10 -CTUN, 358, 0.00, 24.58, 24.136120, 0, 0, 12, 270, -20 -GPS, 3, 594488000, 8, 2.27, 44.0290061, -77.7367041, 23.89, 107.34, 0.94, 133.33 -CTUN, 335, 0.00, 24.38, 24.099625, 0, 0, 16, 232, -40 -ATT, 0.00, 0.57, 0.00, -0.78, 0.00, 83.46, 83.10 -CTUN, 317, 0.00, 24.03, 24.053452, 0, 0, 10, 242, -47 -ATT, 0.00, 0.29, 0.00, 1.10, 0.00, 83.50, 83.10 -GPS, 3, 594488200, 8, 2.27, 44.0290052, -77.7367026, 23.96, 107.37, 0.94, 133.33 -CTUN, 302, 0.00, 23.90, 24.001343, 0, 0, 3, 217, -60 -ATT, 0.00, -0.65, 0.00, 0.80, 0.00, 83.74, 83.10 -CTUN, 298, 0.00, 24.73, 23.940882, 0, 0, -6, 276, -62 -GPS, 3, 594488400, 8, 2.27, 44.0290044, -77.7367013, 23.96, 107.37, 0.82, 133.50 -ATT, 0.00, 0.03, 0.00, -0.92, 0.00, 83.68, 83.10 -CTUN, 289, 0.00, 24.20, 23.853193, 0, 0, -16, 222, -68 -ATT, 0.00, -0.03, 0.00, -1.53, 0.00, 83.70, 83.10 -CTUN, 289, 0.00, 24.13, 23.784534, 0, 0, -28, 287, -68 -GPS, 3, 594488600, 8, 2.27, 44.0290038, -77.7367004, 23.96, 107.35, 0.68, 133.89 -ATT, 0.00, -0.70, 0.00, -0.04, 0.00, 83.92, 83.10 -CTUN, 272, 0.00, 24.05, 23.699940, 0, 0, -33, 232, -75 -ATT, 0.00, 0.04, 0.00, -0.15, 0.00, 83.95, 83.10 -GPS, 3, 594488800, 8, 2.27, 44.0290031, -77.7366997, 23.91, 107.31, 0.48, 141.37 -CTUN, 270, 0.00, 23.93, 23.643650, 0, 0, -37, 255, -80 -ATT, 0.00, 0.38, 0.00, 0.01, 0.00, 83.86, 83.10 -DU32, 7, 426229 -CURR, 265, 141612, 1402, 1443, 4962, 225.016750 -CTUN, 267, 0.00, 23.83, 23.512724, 0, 0, -40, 243, -84 -ATT, 0.00, -0.23, 0.00, 0.31, 0.00, 84.00, 83.10 -GPS, 3, 594489000, 8, 2.27, 44.0290030, -77.7366993, 23.80, 107.20, 0.25, 140.17 -CTUN, 260, 0.00, 23.72, 23.429802, 0, 0, -46, 239, -83 -ATT, 0.00, 0.52, 0.00, 0.93, 0.00, 84.02, 83.10 -CTUN, 259, 0.00, 23.75, 23.316067, 0, 0, -48, 255, -88 -GPS, 3, 594489200, 8, 2.27, 44.0290029, -77.7366992, 23.71, 107.11, 0.25, 140.17 -ATT, 0.00, 1.68, 0.00, 1.78, 0.00, 83.74, 83.10 -CTUN, 259, 0.00, 23.62, 23.218601, 0, 0, -54, 255, -88 -ATT, 0.00, 0.37, 0.00, -0.39, 0.00, 83.64, 83.10 -GPS, 3, 594489400, 8, 2.27, 44.0290027, -77.7366994, 23.63, 107.00, 0.11, 140.17 -CTUN, 258, 0.00, 24.07, 23.131184, 0, 0, -60, 275, -88 -ATT, 0.00, -1.10, 0.00, -1.93, 0.00, 83.61, 83.10 -CTUN, 258, 0.00, 24.11, 22.981533, 0, 0, -59, 227, -88 -ATT, 0.00, 0.31, 0.00, -0.85, 0.00, 83.64, 83.10 -GPS, 3, 594489600, 8, 2.27, 44.0290027, -77.7366997, 23.52, 106.87, 0.16, 140.17 -CTUN, 259, 0.00, 23.62, 22.937431, 0, 0, -61, 229, -88 -ATT, 0.00, 1.69, 0.00, 3.80, 0.00, 83.12, 83.10 -CTUN, 260, 0.00, 23.45, 22.798025, 0, 0, -69, 272, -87 -ATT, 0.00, -0.30, 0.00, 2.11, 0.00, 83.07, 83.10 -GPS, 3, 594489800, 8, 2.27, 44.0290027, -77.7367008, 23.38, 106.77, 0.40, 203.50 -CTUN, 260, 0.00, 23.66, 22.728008, 0, 0, -75, 267, -87 -ATT, 0.00, -2.05, 0.00, -4.00, 0.00, 83.38, 83.10 -CTUN, 259, 0.00, 23.15, 22.604267, 0, 0, -75, 268, -88 -ATT, 0.00, 0.25, 0.00, -3.60, 0.00, 83.12, 83.10 -GPS, 3, 594490000, 8, 2.27, 44.0290027, -77.7367018, 23.26, 106.61, 0.44, 239.37 -CTUN, 260, 0.00, 24.28, 22.490767, 0, 0, -73, 250, -87 -ATT, 0.00, -0.35, 0.00, 0.54, 0.00, 83.09, 83.10 -CTUN, 260, 0.00, 23.20, 22.402803, 0, 0, -72, 231, -88 -GPS, 3, 594490200, 8, 2.27, 44.0290029, -77.7367033, 23.13, 106.45, 0.58, 266.29 -ATT, 0.00, -0.38, 0.00, 1.36, 0.00, 82.86, 83.10 -CTUN, 259, 0.00, 23.36, 22.297016, 0, 0, -81, 280, -88 -ATT, 0.00, -0.94, 0.00, 0.19, 0.00, 82.83, 83.10 -GPS, 3, 594490400, 8, 2.27, 44.0290031, -77.7367047, 23.01, 106.32, 0.57, 270.24 -CTUN, 260, 0.00, 23.76, 22.235634, 0, 0, -83, 262, -87 -ATT, 0.00, 0.20, 0.00, -0.85, 0.00, 82.83, 83.10 -CTUN, 258, 0.00, 23.22, 22.103374, 0, 0, -85, 245, -88 -ATT, 0.00, 0.22, 0.00, 0.82, 0.00, 82.90, 83.10 -GPS, 3, 594490600, 8, 2.27, 44.0290035, -77.7367064, 22.87, 106.14, 0.73, 281.88 -CTUN, 258, 0.00, 22.96, 22.041689, 0, 0, -85, 276, -88 -ATT, 0.00, -1.25, 0.00, 0.54, 0.00, 83.38, 83.10 -CTUN, 258, 0.00, 23.29, 21.900259, 0, 0, -92, 257, -88 -ATT, 0.00, 0.50, 0.00, -1.45, 0.00, 83.57, 83.10 -GPS, 3, 594490800, 8, 2.27, 44.0290040, -77.7367083, 22.72, 105.98, 0.78, 284.90 -CTUN, 258, 0.00, 23.23, 21.829859, 0, 0, -91, 258, -87 -ATT, 0.00, 1.16, -0.23, -2.25, 0.00, 83.67, 83.10 -CTUN, 258, 0.00, 23.21, 21.707409, 0, 0, -92, 265, -88 -GPS, 3, 594491000, 8, 2.27, 44.0290043, -77.7367102, 22.58, 105.81, 0.78, 284.90 -ATT, 0.00, -0.38, -5.07, -0.64, 0.00, 83.96, 83.10 -CTUN, 258, 0.00, 23.10, 21.637495, 0, 0, -90, 255, -87 -ATT, 0.00, -0.50, -6.96, -1.49, 0.00, 83.86, 83.10 -GPS, 3, 594491200, 8, 2.27, 44.0290048, -77.7367125, 22.46, 105.62, 0.96, 286.09 -CTUN, 259, 0.00, 22.65, 21.549328, 0, 0, -93, 258, -88 -ATT, 0.00, -0.40, -7.91, -4.22, 0.00, 84.05, 83.10 -CTUN, 258, 0.00, 22.60, 21.399572, 0, 0, -99, 273, -88 -ATT, 0.00, 1.04, -8.74, -6.49, 0.00, 83.75, 83.10 -GPS, 3, 594491400, 8, 2.27, 44.0290053, -77.7367146, 22.27, 105.42, 0.92, 287.76 -CTUN, 258, 0.00, 21.39, 21.346739, 0, 1, -100, 259, -88 -ATT, 0.00, -2.59, -10.03, -7.17, 0.00, 84.20, 83.10 -CTUN, 258, 0.00, 20.77, 21.196909, 0, 1, -97, 298, -88 -ATT, 0.00, 0.35, -10.27, -7.58, 0.00, 83.69, 83.10 -GPS, 3, 594491600, 8, 2.27, 44.0290058, -77.7367166, 22.05, 105.21, 0.92, 287.76 -CTUN, 259, 0.00, 20.94, 21.125422, 0, 1, -94, 266, -88 -ATT, 0.00, 0.30, -10.27, -9.84, 0.00, 83.59, 83.10 -CTUN, 258, 0.00, 20.03, 21.039099, 0, 2, -87, 275, -88 -ATT, 0.00, 0.71, -9.92, -9.67, 0.00, 83.26, 83.10 -GPS, 3, 594491800, 8, 2.27, 44.0290061, -77.7367182, 21.73, 105.02, 0.70, 286.30 -CTUN, 258, 0.00, 20.11, 20.933142, 0, 1, -76, 288, -88 -ATT, 0.00, 0.10, -9.56, -8.67, 0.00, 83.06, 83.10 -GPS, 3, 594492000, 8, 2.27, 44.0290063, -77.7367194, 21.52, 104.84, 0.70, 286.30 -CTUN, 259, 0.00, 20.08, 20.836889, 0, 1, -68, 253, -88 -ATT, 0.00, 0.00, -9.09, -9.35, 0.00, 82.85, 83.10 -CTUN, 259, 0.00, 19.66, 20.695435, 0, 1, -56, 285, -88 -ATT, 0.00, 0.29, -8.85, -8.99, 0.00, 82.84, 83.10 -GPS, 3, 594492200, 8, 2.27, 44.0290064, -77.7367201, 21.27, 104.73, 0.29, 286.50 -CTUN, 260, 0.00, 19.84, 20.642569, 0, 1, -52, 243, -88 -ATT, 0.00, -0.33, -8.62, -9.02, 0.00, 82.83, 83.10 -CTUN, 258, 0.00, 19.73, 20.501959, 0, 1, -53, 255, -88 -ATT, 0.00, 0.46, -8.14, -7.77, 0.00, 82.89, 83.10 -GPS, 3, 594492400, 8, 2.27, 44.0290062, -77.7367204, 21.06, 104.61, 0.29, 286.50 -CTUN, 260, 0.00, 20.57, 20.466646, 0, 1, -52, 256, -88 -ATT, 0.00, 1.03, -7.79, -8.09, 0.00, 82.90, 83.10 -CTUN, 259, 0.00, 20.61, 20.326878, 0, 1, -58, 264, -87 -ATT, 0.00, 0.11, -7.44, -7.89, 0.00, 83.04, 83.10 -GPS, 3, 594492600, 8, 2.27, 44.0290059, -77.7367203, 20.88, 104.51, 0.15, 286.50 -CTUN, 260, 0.00, 19.99, 20.246935, 0, 1, -58, 262, -87 -ATT, 0.00, 0.22, -7.08, -8.10, 0.00, 83.03, 83.10 -GPS, 3, 594492800, 8, 2.27, 44.0290055, -77.7367198, 20.73, 104.40, 0.17, 253.85 -ATT, 0.00, 0.93, -6.85, -7.71, 0.00, 82.88, 83.10 -CTUN, 260, 0.00, 20.44, 20.071964, 0, 1, -65, 255, -87 -ATT, 0.00, 0.25, -6.49, -6.81, 0.00, 82.89, 83.10 -CTUN, 259, 0.00, 20.58, 19.995089, 0, 0, -65, 258, -87 -GPS, 3, 594493000, 8, 2.27, 44.0290048, -77.7367191, 20.58, 104.28, 0.27, 178.77 -CTUN, 260, 0.00, 20.49, 19.968832, 0, 0, -65, 262, -88 -ATT, 0.00, 0.17, -4.48, -6.61, 0.00, 82.76, 83.10 -DU32, 7, 426229 -CURR, 260, 151195, 1409, 1452, 5006, 239.699800 -CTUN, 260, 0.00, 20.61, 19.812160, 0, 0, -68, 255, -87 -ATT, 0.00, 0.15, -2.36, -5.80, 0.00, 82.68, 83.10 -GPS, 3, 594493200, 8, 2.27, 44.0290041, -77.7367182, 20.43, 104.15, 0.55, 142.06 -CTUN, 260, 0.00, 21.31, 19.776518, 0, 0, -68, 250, -87 -ATT, 0.00, 0.61, -1.18, -3.52, 0.00, 82.57, 83.10 -CTUN, 260, 0.00, 22.54, 19.655025, 0, 0, -70, 248, -87 -ATT, 0.00, 0.38, -1.18, -2.23, 0.00, 82.57, 83.10 -GPS, 3, 594493400, 8, 2.27, 44.0290034, -77.7367173, 20.35, 104.03, 0.56, 138.96 -CTUN, 260, 0.00, 22.35, 19.567392, 0, 0, -74, 225, -87 -ATT, 0.00, 0.00, -1.06, -2.00, 0.00, 82.62, 83.10 -CTUN, 260, 0.00, 22.04, 19.463041, 0, 0, -85, 242, -87 -GPS, 3, 594493600, 8, 2.27, 44.0290025, -77.7367162, 20.34, 103.91, 0.56, 138.96 -ATT, 0.00, 1.06, -1.06, -0.49, 0.00, 82.64, 83.10 -CTUN, 260, 0.00, 21.08, 19.358410, 0, 0, -99, 237, -87 -ATT, 0.00, 0.66, -1.06, 0.15, 0.00, 82.78, 83.10 -CTUN, 260, 0.00, 20.65, 19.236212, 0, 0, -111, 282, -87 -GPS, 3, 594493800, 8, 2.27, 44.0290016, -77.7367154, 20.22, 103.76, 0.59, 141.21 -ATT, 0.00, 1.15, -0.94, -1.66, 0.00, 82.87, 83.10 -CTUN, 260, 0.00, 21.40, 19.148094, 0, 0, -114, 266, -87 -ATT, 0.00, -0.10, -1.06, -2.93, 0.00, 83.06, 83.10 -GPS, 3, 594494000, 8, 2.27, 44.0290007, -77.7367147, 20.07, 103.53, 0.59, 141.21 -CTUN, 260, 0.00, 20.59, 19.078825, 0, 0, -112, 222, -87 -ATT, 0.00, -2.02, -1.41, -2.09, 0.00, 83.73, 83.10 -CTUN, 260, 0.00, 20.46, 18.956495, 0, 0, -106, 256, -88 -ATT, -0.11, 0.16, -1.65, 0.00, 0.00, 83.72, 83.10 -GPS, 3, 594494200, 8, 2.27, 44.0289998, -77.7367141, 19.90, 103.33, 0.52, 149.02 -CTUN, 259, 0.00, 20.13, 18.886791, 0, 0, -103, 278, -87 -ATT, -2.81, 0.49, -1.77, -1.33, 0.00, 83.65, 83.10 -CTUN, 259, 0.00, 20.24, 18.730419, 0, 0, -103, 213, -86 -GPS, 3, 594494400, 8, 2.27, 44.0289990, -77.7367137, 19.74, 103.14, 0.52, 149.02 -ATT, -3.40, -2.45, -1.88, -3.17, 0.00, 83.91, 83.10 -CTUN, 260, 0.00, 19.69, 18.651834, 0, 0, -105, 287, -88 -ATT, -3.28, -1.96, -1.77, -2.83, 0.00, 83.87, 83.10 -GPS, 3, 594494600, 8, 2.27, 44.0289982, -77.7367133, 19.56, 102.91, 0.47, 156.16 -CTUN, 260, 0.00, 19.83, 18.555710, 0, 0, -104, 258, -87 -ATT, -2.93, -2.55, -1.77, -1.17, 0.00, 83.76, 83.10 -CTUN, 259, 0.00, 19.57, 18.406052, 0, 0, -102, 268, -87 -ATT, -2.70, -2.82, -1.77, -1.01, 0.00, 83.79, 83.10 -GPS, 3, 594494800, 8, 2.27, 44.0289975, -77.7367130, 19.34, 102.71, 0.47, 156.16 -CTUN, 260, 0.00, 19.46, 18.353355, 0, 0, -102, 269, -88 -ATT, -2.70, -1.54, -1.53, -3.14, 0.00, 83.90, 83.10 -CTUN, 260, 0.00, 19.25, 18.240053, 0, 0, -102, 257, -88 -ATT, -2.70, -3.46, -0.70, -2.17, 0.00, 84.19, 83.10 -GPS, 3, 594495000, 8, 2.27, 44.0289970, -77.7367129, 19.15, 102.51, 0.43, 160.64 -CTUN, 259, 0.00, 18.69, 18.135082, 0, 0, -97, 233, -88 -ATT, -2.58, -3.34, 0.00, -0.86, 0.00, 84.25, 83.10 -PM, 0, 0, 50, 72, 1000, 11772, 10, 0 -GPS, 3, 594495200, 8, 2.27, 44.0289966, -77.7367127, 19.01, 102.31, 0.29, 162.80 -CTUN, 259, 0.00, 18.67, 18.056581, 0, 0, -97, 269, -87 -ATT, -2.11, -1.36, 0.00, -0.74, 0.00, 84.27, 83.10 -CTUN, 260, 0.00, 18.78, 17.898827, 0, 0, -96, 243, -87 -ATT, -1.99, -2.08, 0.00, -1.24, 0.00, 84.45, 83.10 -GPS, 3, 594495400, 8, 2.27, 44.0289964, -77.7367126, 18.75, 102.11, 0.21, 157.67 -CTUN, 260, 0.00, 18.44, 17.845802, 0, 0, -97, 288, -88 -ATT, -1.64, -2.78, 0.00, -0.87, 0.00, 84.52, 83.10 -CTUN, 258, 0.00, 18.29, 17.722725, 0, 0, -93, 262, -88 -ATT, -1.52, -1.86, 0.00, -0.39, 0.00, 84.44, 83.10 -GPS, 3, 594495600, 8, 2.27, 44.0289961, -77.7367125, 18.55, 101.90, 0.21, 157.67 -CTUN, 244, 0.00, 18.56, 17.620413, 0, 0, -92, 278, -95 -ATT, -1.17, -2.34, 0.00, 0.60, 0.00, 84.54, 83.10 -CTUN, 242, 0.00, 18.46, 17.495052, 0, 0, -89, 251, -97 -GPS, 3, 594495800, 8, 2.27, 44.0289960, -77.7367126, 18.34, 101.72, 0.14, 157.67 -ATT, -1.29, -1.01, 0.00, -0.63, 0.00, 84.39, 83.10 -CTUN, 239, 0.00, 18.62, 17.396212, 0, 0, -88, 267, -100 -ATT, -1.17, -0.52, 0.00, -1.01, 0.00, 84.24, 83.10 -GPS, 3, 594496000, 8, 2.27, 44.0289959, -77.7367127, 18.21, 101.52, 0.04, 157.67 -CTUN, 236, 0.00, 18.57, 17.295704, 0, 0, -91, 256, -101 -ATT, -1.17, -2.62, 0.00, 0.26, 0.00, 84.03, 83.10 -CTUN, 236, 0.00, 18.04, 17.132296, 0, 0, -96, 248, -102 -ATT, -1.29, -1.90, 0.00, 0.23, 0.00, 83.86, 83.10 -GPS, 3, 594496200, 8, 2.27, 44.0289962, -77.7367132, 18.02, 101.36, 0.26, 221.02 -CTUN, 235, 0.00, 18.55, 17.070633, 0, 0, -99, 279, -103 -ATT, -1.29, 0.28, 0.00, -1.04, 0.00, 83.44, 83.10 -CTUN, 227, 0.00, 18.39, 16.934206, 0, 0, -102, 247, -107 -ATT, -1.05, -1.41, 0.00, -0.29, 0.00, 83.27, 83.10 -GPS, 3, 594496400, 8, 2.27, 44.0289965, -77.7367137, 17.84, 101.15, 0.26, 221.02 -CTUN, 222, 0.00, 18.52, 16.814018, 0, 0, -105, 260, -108 -ATT, -1.05, -1.72, 0.00, 0.64, 0.00, 83.00, 83.10 -CTUN, 219, 0.00, 18.49, 16.703835, 0, 0, -106, 253, -112 -ATT, -1.05, -2.20, 0.00, 0.07, 0.00, 82.99, 83.10 -GPS, 3, 594496600, 8, 2.27, 44.0289968, -77.7367144, 17.68, 100.94, 0.41, 294.01 -CTUN, 210, 0.00, 18.34, 16.540697, 0, 0, -112, 265, -116 -DU32, 7, 426229 -CURR, 211, 159317, 1408, 1233, 4984, 252.148700 -ATT, -1.05, -0.48, -0.35, -0.36, 0.00, 82.84, 83.10 -GPS, 3, 594496800, 8, 2.27, 44.0289973, -77.7367153, 17.54, 100.70, 0.41, 294.01 -CTUN, 206, 0.00, 18.42, 16.314606, 0, 0, -118, 257, -121 -ATT, -0.82, -1.19, -1.18, -0.79, 0.00, 82.93, 83.10 -CTUN, 205, 0.00, 18.14, 16.193871, 0, 0, -122, 255, -121 -ATT, -1.29, -0.44, -2.83, -0.95, 0.00, 83.02, 83.10 -GPS, 3, 594497000, 8, 2.27, 44.0289979, -77.7367165, 17.35, 100.46, 0.44, 299.47 -CTUN, 202, 0.00, 18.12, 16.083424, 0, 0, -127, 256, -123 -ATT, -1.52, -1.31, -4.48, -1.88, 0.00, 83.18, 83.10 -GPS, 3, 594497200, 8, 2.27, 44.0289985, -77.7367178, 17.17, 100.21, 0.59, 302.53 -CTUN, 202, 0.00, 17.65, 15.947953, 0, 0, -132, 266, -123 -ATT, -1.52, -0.63, -4.96, -3.72, 0.00, 83.39, 83.10 -CTUN, 202, 0.00, 16.98, 15.751019, 0, 0, -138, 290, -123 -ATT, -1.99, -2.56, -4.96, -4.00, 0.00, 83.59, 83.10 -GPS, 3, 594497400, 8, 2.27, 44.0289990, -77.7367189, 16.92, 99.95, 0.65, 302.74 -CTUN, 202, 0.00, 15.73, 15.677063, 0, 0, -139, 264, -123 -ATT, -2.46, -2.30, -5.19, -5.28, 0.00, 83.51, 83.10 -CTUN, 202, 0.00, 16.46, 15.529227, 0, 0, -136, 288, -123 -ATT, -2.46, 0.18, -5.19, -4.48, 0.00, 82.54, 83.10 -GPS, 3, 594497600, 8, 2.27, 44.0289996, -77.7367202, 16.57, 99.69, 0.54, 302.37 -CTUN, 202, 0.00, 16.88, 15.344251, 0, 0, -124, 271, -123 -ATT, -2.70, -1.62, -4.48, -4.08, 0.00, 82.49, 83.10 -CTUN, 202, 0.00, 16.11, 15.232966, 0, 0, -115, 243, -123 -GPS, 3, 594497800, 8, 2.27, 44.0290002, -77.7367213, 16.36, 99.42, 0.61, 302.82 -ATT, -2.58, -2.93, -4.01, -3.35, 0.00, 82.22, 83.10 -CTUN, 202, 0.00, 15.61, 15.097021, 0, 0, -114, 267, -123 -ATT, -2.70, -2.35, -3.77, -3.79, 0.00, 82.12, 83.10 -CTUN, 202, 0.00, 15.37, 14.973803, 0, 0, -115, 266, -123 -GPS, 3, 594498000, 8, 2.27, 44.0290007, -77.7367223, 16.08, 99.19, 0.44, 306.30 -CTUN, 201, 0.00, 15.25, 14.924073, 0, 0, -115, 278, -124 -ATT, -2.81, -2.05, -3.42, -3.95, 0.00, 81.77, 83.10 -CTUN, 202, 0.00, 15.02, 14.750191, 0, 0, -116, 257, -125 -ATT, -2.93, -2.97, -3.07, -4.07, 0.00, 81.63, 83.10 -GPS, 3, 594498200, 8, 2.27, 44.0290012, -77.7367230, 15.81, 98.95, 0.44, 306.30 -CTUN, 201, 0.00, 14.73, 14.589051, 0, 0, -113, 271, -124 -ATT, -2.93, -2.41, -3.18, -3.82, 0.00, 81.44, 83.10 -CTUN, 202, 0.00, 14.67, 14.465165, 0, 0, -113, 279, -124 -GPS, 3, 594498400, 8, 2.27, 44.0290020, -77.7367237, 15.47, 98.71, 0.53, 323.17 -ATT, -2.81, -2.56, -3.18, -3.21, 0.00, 81.45, 83.10 -CTUN, 201, 0.00, 14.62, 14.340752, 0, 0, -108, 266, -124 -ATT, -2.70, -3.06, -3.18, -2.88, 0.00, 81.48, 83.10 -CTUN, 202, 0.00, 14.66, 14.229832, 0, 0, -106, 266, -124 -GPS, 3, 594498600, 8, 2.27, 44.0290025, -77.7367240, 15.28, 98.47, 0.34, 326.53 -CTUN, 201, 0.00, 14.57, 14.079702, 0, 0, -104, 261, -124 -ATT, -2.34, -2.79, -2.95, -3.27, 0.00, 81.57, 83.10 -CTUN, 201, 0.00, 14.41, 13.956217, 0, 0, -106, 271, -124 -ATT, -1.87, -2.39, -3.07, -3.19, 0.00, 81.67, 83.10 -GPS, 3, 594498800, 8, 2.27, 44.0290032, -77.7367245, 15.00, 98.24, 0.34, 326.53 -CTUN, 201, 0.00, 14.57, 13.869363, 0, 0, -107, 262, -124 -ATT, -1.05, -1.84, -3.07, -3.26, 0.00, 81.76, 83.10 -CTUN, 200, 0.00, 14.53, 13.732919, 0, 0, -108, 275, -124 -GPS, 3, 594499000, 8, 2.27, 44.0290042, -77.7367247, 14.70, 98.03, 0.47, 332.67 -ATT, 0.00, -1.15, -2.95, -3.29, 0.00, 81.84, 83.10 -CTUN, 201, 0.00, 14.96, 13.595669, 0, 0, -107, 256, -124 -ATT, 0.00, -0.99, -2.83, -3.25, 0.00, 81.91, 83.10 -GPS, 3, 594499200, 8, 2.27, 44.0290050, -77.7367249, 14.54, 97.83, 0.56, 340.47 -CTUN, 200, 0.00, 15.03, 13.370480, 0, 0, -109, 258, -125 -ATT, 0.00, -0.63, -2.59, -2.72, 0.00, 81.89, 83.10 -DU32, 7, 426229 -CURR, 200, 164934, 1411, 1350, 4984, 260.660430 -CTUN, 201, 0.00, 14.70, 13.296675, 0, 0, -111, 262, -125 -ATT, 0.00, -0.14, -2.59, -2.75, 0.00, 81.92, 83.10 -GPS, 3, 594499400, 8, 2.27, 44.0290059, -77.7367251, 14.35, 97.62, 0.50, 348.03 -CTUN, 200, 0.00, 14.58, 13.209160, 0, 0, -115, 246, -125 -ATT, 0.00, -0.42, -2.36, -3.02, 0.00, 81.95, 83.10 -CTUN, 200, 0.00, 14.37, 12.971410, 0, 0, -126, 289, -125 -ATT, 0.00, -0.34, -2.36, -2.49, 0.00, 81.96, 83.10 -GPS, 3, 594499600, 8, 2.27, 44.0290068, -77.7367254, 14.14, 97.39, 0.56, 347.37 -CTUN, 200, 0.00, 14.52, 12.870291, 0, 0, -123, 245, -125 -ATT, 0.00, -0.08, -2.24, -2.81, 0.00, 82.17, 83.10 -CTUN, 200, 0.00, 14.97, 12.733401, 0, 0, -125, 277, -125 -ATT, 0.00, 0.24, -2.36, -2.32, 0.00, 82.19, 83.10 -GPS, 3, 594499800, 8, 2.27, 44.0290076, -77.7367255, 13.93, 97.13, 0.48, 349.54 -CTUN, 199, 0.00, 14.81, 12.607221, 0, 0, -126, 246, -125 -ATT, 0.00, -0.53, -2.36, -2.78, 0.00, 82.37, 83.10 -GPS, 3, 594500000, 8, 2.27, 44.0290085, -77.7367258, 13.75, 96.87, 0.48, 349.54 -CTUN, 199, 0.00, 14.78, 12.482975, 0, 0, -128, 257, -125 -ATT, 0.00, 0.50, -2.36, -1.73, 0.00, 82.19, 83.10 -CTUN, 199, 0.00, 14.89, 12.269819, 0, 0, -136, 259, -125 -ATT, 0.00, -0.69, -2.48, -2.18, 0.00, 82.46, 83.10 -GPS, 3, 594500200, 8, 2.27, 44.0290091, -77.7367260, 13.53, 96.62, 0.43, 347.71 -CTUN, 199, 0.00, 14.24, 12.182199, 0, 0, -141, 259, -126 -ATT, 0.00, 0.42, -2.71, -3.98, 0.00, 82.43, 83.10 -CTUN, 198, 0.00, 12.90, 11.980483, 0, 0, -145, 271, -126 -ATT, 0.00, 0.49, -2.83, -2.88, 0.00, 82.63, 83.10 -GPS, 3, 594500400, 8, 2.27, 44.0290098, -77.7367263, 13.33, 96.34, 0.43, 347.71 -CTUN, 198, 0.00, 14.34, 11.878039, 0, 0, -149, 278, -126 -ATT, 0.00, -0.85, -2.83, -2.29, 0.00, 82.74, 83.10 -CTUN, 199, 0.00, 14.07, 11.741538, 0, 0, -145, 274, -126 -GPS, 3, 594500600, 8, 2.27, 44.0290104, -77.7367266, 13.04, 96.02, 0.42, 346.70 -ATT, 0.00, -0.41, -3.18, -3.05, 0.00, 82.64, 83.10 -CTUN, 198, 0.00, 13.18, 11.602172, 0, 0, -141, 264, -126 -ATT, 0.00, -0.65, -3.30, -3.17, 0.00, 82.84, 83.10 -GPS, 3, 594500800, 8, 2.27, 44.0290110, -77.7367268, 12.87, 95.72, 0.40, 343.73 -CTUN, 198, 0.00, 13.49, 11.362183, 0, 0, -142, 264, -126 -ATT, 0.00, 0.66, -3.77, -3.10, 0.00, 82.73, 83.10 -CTUN, 197, 0.00, 13.35, 11.249468, 0, 0, -142, 265, -126 -ATT, 0.00, -0.03, -3.89, -2.49, 0.00, 82.81, 83.10 -GPS, 3, 594501000, 8, 2.27, 44.0290116, -77.7367269, 12.60, 95.41, 0.34, 346.79 -CTUN, 197, 0.00, 13.04, 11.199027, 0, 0, -142, 252, -126 -ATT, 0.00, -0.34, -3.89, -3.32, 0.00, 82.85, 83.10 -CTUN, 197, 0.00, 12.01, 11.009749, 0, 0, -145, 264, -126 -ATT, 0.00, 0.07, -3.77, -4.06, 0.00, 82.79, 83.10 -GPS, 3, 594501200, 8, 2.27, 44.0290120, -77.7367269, 12.42, 95.11, 0.34, 346.79 -CTUN, 197, 0.00, 11.73, 10.844700, 0, 0, -144, 255, -126 -ATT, 0.00, -0.06, -3.66, -3.30, 0.00, 82.88, 83.10 -CTUN, 196, 0.00, 11.93, 10.731807, 0, 0, -148, 304, -127 -GPS, 3, 594501400, 8, 2.27, 44.0290124, -77.7367272, 11.98, 94.82, 0.26, 352.10 -ATT, 0.00, -0.02, -3.77, -3.37, 0.00, 82.92, 83.10 -CTUN, 195, 0.00, 11.68, 10.588860, 0, 0, -140, 269, -128 -ATT, 0.00, -0.12, -3.77, -3.62, 0.00, 82.97, 83.10 -GPS, 3, 594501600, 8, 2.27, 44.0290128, -77.7367273, 11.75, 94.52, 0.24, 349.64 -CTUN, 195, 0.00, 11.59, 10.449924, 0, 0, -136, 263, -128 -ATT, 0.00, -0.94, -3.77, -3.90, 0.00, 82.96, 83.10 -CTUN, 195, 0.00, 11.18, 10.244890, 0, 0, -128, 266, -128 -ATT, 0.00, 0.05, -3.89, -3.86, 0.00, 82.81, 83.10 -GPS, 3, 594501800, 8, 2.27, 44.0290132, -77.7367274, 11.48, 94.24, 0.24, 349.88 -CTUN, 195, 0.00, 10.73, 10.193789, 0, 0, -127, 272, -128 -ATT, 0.00, -0.03, -3.89, -3.88, 0.00, 82.55, 83.10 -CTUN, 196, 0.00, 10.32, 9.988882, 0, 0, -127, 263, -127 -ATT, 0.00, 0.57, -3.89, -4.08, 0.00, 82.20, 83.10 -GPS, 3, 594502000, 8, 2.27, 44.0290136, -77.7367273, 11.17, 93.96, 0.22, 349.88 -CTUN, 195, 0.00, 10.02, 9.836132, 0, 0, -128, 276, -127 -ATT, 0.00, -0.18, -3.89, -3.37, 0.00, 82.27, 83.10 -CTUN, 195, 0.00, 10.07, 9.708106, 0, 0, -126, 266, -127 -GPS, 3, 594502200, 8, 2.27, 44.0290139, -77.7367273, 10.90, 93.71, 0.22, 349.88 -ATT, 0.00, -0.05, -3.77, -3.69, 0.00, 82.10, 83.10 -CTUN, 194, 0.00, 9.70, 9.541476, 0, 0, -120, 278, -128 -ATT, 0.00, -0.33, -3.89, -4.28, 0.00, 82.05, 83.10 -GPS, 3, 594502400, 8, 2.27, 44.0290142, -77.7367271, 10.54, 93.43, 0.23, 349.88 -CTUN, 195, 0.00, 9.55, 9.413486, 0, 0, -116, 266, -127 -ATT, 0.00, 0.17, -4.01, -4.05, 0.00, 81.87, 83.10 -CTUN, 194, 0.00, 9.34, 9.208482, 0, 0, -107, 236, -128 -ATT, 0.00, 0.15, -3.89, -3.06, 0.00, 81.82, 83.10 -GPS, 3, 594502600, 8, 2.27, 44.0290145, -77.7367270, 10.21, 93.18, 0.20, 349.88 -CTUN, 196, 0.00, 9.63, 9.054636, 0, 0, -110, 279, -128 -ATT, 0.00, -0.07, -3.66, -3.12, 0.00, 81.80, 83.10 -CTUN, 189, 0.00, 8.94, 8.939090, 0, 0, -109, 240, -130 -GPS, 3, 594502800, 8, 2.27, 44.0290148, -77.7367266, 10.02, 92.96, 0.19, 349.88 -ATT, 0.00, -0.80, -3.42, -5.23, 0.00, 81.81, 83.10 -CTUN, 178, 0.00, 8.41, 8.750401, 0, 0, -110, 281, -137 -ATT, 0.00, 0.30, -3.07, -3.36, 0.00, 81.80, 83.10 -GPS, 3, 594503000, 8, 2.27, 44.0290151, -77.7367262, 9.68, 92.73, 0.20, 349.88 -CTUN, 169, 0.00, 8.99, 8.622946, 0, 0, -109, 264, -143 -ATT, 0.00, 0.56, -2.95, -2.73, 0.00, 81.93, 83.10 -CTUN, 167, 0.00, 9.20, 8.406070, 0, 0, -108, 264, -145 -ATT, 0.00, 0.22, -2.95, -2.93, 0.00, 82.01, 83.10 -GPS, 3, 594503200, 8, 2.27, 44.0290154, -77.7367258, 9.38, 92.51, 0.21, 349.88 -CTUN, 163, 0.00, 8.99, 8.230280, 0, 0, -107, 264, -146 -ATT, 0.00, 0.07, -2.83, -2.97, 0.00, 82.44, 83.10 -CTUN, 153, 0.00, 9.23, 8.079770, 0, 0, -109, 243, -151 -GPS, 3, 594503400, 8, 2.27, 44.0290156, -77.7367254, 9.20, 92.27, 0.20, 349.88 -ATT, 0.00, -0.17, -2.71, -3.22, 0.00, 82.73, 83.10 -CTUN, 152, 0.00, 9.28, 7.832037, 0, 0, -118, 284, -155 -ATT, 0.00, -0.28, -2.59, -2.39, 0.00, 82.98, 83.10 -GPS, 3, 594503600, 8, 2.27, 44.0290158, -77.7367250, 8.96, 92.04, 0.20, 349.88 -CTUN, 151, 0.00, 10.17, 7.754188, 0, 0, -118, 236, -155 -ATT, 0.00, -0.35, -2.59, -2.80, 0.00, 83.43, 83.10 -CTUN, 147, 0.00, 9.93, 7.519411, 0, 0, -124, 235, -158 -ATT, 0.00, 0.10, -2.59, -1.76, 0.00, 83.56, 83.10 -GPS, 3, 594503800, 8, 2.27, 44.0290161, -77.7367245, 8.75, 91.80, 0.21, 349.88 -CTUN, 145, 0.00, 9.92, 7.392309, 0, 0, -130, 262, -158 -ATT, 0.00, 0.19, -2.36, -1.88, 0.00, 83.87, 83.10 -CTUN, 145, 0.00, 9.91, 7.107321, 0, 0, -149, 269, -158 -ATT, 0.00, 0.41, -2.12, -3.48, 0.00, 83.83, 83.10 -GPS, 3, 594504000, 8, 2.27, 44.0290162, -77.7367240, 8.56, 91.55, 0.26, 349.88 -CTUN, 145, 0.00, 9.41, 6.962879, 0, 0, -147, 237, -159 -ATT, 0.00, 0.43, -1.88, -2.82, 0.00, 83.98, 83.10 -CTUN, 145, 0.00, 9.36, 6.772177, 0, 0, -158, 257, -159 -GPS, 3, 594504200, 8, 2.27, 44.0290163, -77.7367235, 8.35, 91.23, 0.20, 349.88 -ATT, 0.00, -0.72, -1.77, -0.53, 0.00, 84.08, 83.10 -CTUN, 146, 0.00, 8.56, 6.613750, 0, 0, -164, 238, -159 -ATT, 0.00, 0.47, -1.77, -2.44, 0.00, 84.11, 83.10 -GPS, 3, 594504400, 8, 2.27, 44.0290166, -77.7367232, 8.07, 90.89, 0.19, 349.88 -CTUN, 146, 0.00, 8.92, 6.438194, 0, 0, -172, 288, -159 -ATT, 0.00, -0.44, -1.65, -3.42, 0.00, 84.27, 83.10 -CTUN, 145, 0.00, 8.04, 6.247955, 0, 0, -179, 271, -159 -ATT, 0.00, -0.92, -1.53, -2.31, 0.00, 84.34, 83.10 -GPS, 3, 594504600, 8, 2.27, 44.0290167, -77.7367230, 7.80, 90.57, 0.13, 349.88 -CTUN, 144, 0.00, 8.32, 6.022111, 0, 0, -178, 267, -159 -ATT, 0.00, 0.00, -1.65, -1.32, 0.00, 84.37, 83.10 -CTUN, 148, 0.00, 8.02, 5.882883, 0, 0, -175, 292, -157 -GPS, 3, 594504800, 8, 2.27, 44.0290170, -77.7367227, 7.43, 90.15, 0.13, 349.88 -ATT, 0.00, -0.55, -1.65, -2.55, 0.00, 84.64, 83.10 -CTUN, 158, 0.00, 7.23, 5.696912, 0, 0, -172, 275, -151 -ATT, 0.00, 0.21, -1.65, -3.24, 0.00, 84.68, 83.10 -CTUN, 183, 0.00, 7.57, 5.572613, 0, 0, -171, 309, -138 -GPS, 3, 594505000, 8, 2.27, 44.0290171, -77.7367223, 7.09, 89.81, 0.23, 359.54 -ATT, 0.00, 0.06, -1.77, -2.68, 0.00, 84.81, 83.10 -CTUN, 196, 0.00, 7.21, 5.429297, 0, 0, -165, 274, -128 -ATT, 0.00, 2.32, -1.65, -3.21, 0.00, 84.68, 83.10 -CTUN, 209, 0.00, 3.34, 5.318625, 0, 0, -158, 269, -119 -GPS, 3, 594505200, 8, 2.27, 44.0290172, -77.7367222, 6.78, 89.46, 0.10, 359.54 -CTUN, 244, 0.00, 2.63, 5.202417, 0, 0, -157, 315, -100 -ATT, 0.00, -0.61, -1.77, -0.44, 0.00, 84.63, 83.10 -PM, 0, 0, 51, 74, 1010, 11712, 10, 0 -CTUN, 275, 0.00, 2.63, 5.115500, 0, 0, -142, 355, -78 -ATT, 0.00, -1.35, -1.77, -4.05, 0.00, 84.50, 83.10 -GPS, 3, 594505400, 8, 2.27, 44.0290174, -77.7367221, 6.12, 89.11, 0.08, 359.54 -CTUN, 300, 0.00, 2.52, 5.073157, 0, 0, -123, 287, -66 -ATT, 0.00, 2.46, -1.65, -1.20, 0.00, 83.90, 83.10 -CTUN, 340, 0.00, 2.75, 5.002417, 0, 0, -77, 266, -43 -GPS, 3, 594505600, 8, 2.27, 44.0290174, -77.7367220, 5.72, 88.83, 0.08, 359.54 -ATT, 0.00, 0.68, -1.53, 0.54, 0.00, 83.60, 83.10 -CTUN, 370, 0.00, 3.56, 4.974866, 0, 0, -58, 299, -27 -ATT, 0.00, -0.71, -0.23, -1.71, 0.00, 83.49, 83.10 -GPS, 3, 594505800, 8, 2.27, 44.0290173, -77.7367221, 5.43, 88.70, 0.05, 359.54 -CTUN, 388, 0.00, 4.00, 4.954550, 0, 0, -30, 283, -8 -ATT, 0.00, -1.40, 0.00, -1.27, 0.00, 83.56, 83.10 -CTUN, 401, 0.00, 3.94, 4.947358, 0, 0, -13, 254, 0 -ATT, 0.00, -1.22, 0.00, 0.42, 0.00, 83.51, 83.10 -GPS, 3, 594506000, 8, 2.27, 44.0290174, -77.7367223, 5.29, 88.61, 0.10, 359.54 -CTUN, 406, 0.00, 3.89, 4.947358, 0, 0, -8, 259, 0 -ATT, 0.00, 1.51, 0.00, -0.67, 0.00, 83.68, 83.10 -DU32, 7, 426229 -CURR, 417, 180794, 1410, 1270, 4984, 285.276430 -CTUN, 426, 0.00, 3.56, 4.947358, 0, 0, -13, 283, 0 -ATT, -0.11, -0.11, 0.00, -0.23, 0.00, 83.59, 83.10 -GPS, 3, 594506200, 8, 2.27, 44.0290174, -77.7367227, 5.15, 88.62, 0.10, 359.54 -CTUN, 428, 0.00, 3.38, 4.947358, 0, 0, -12, 273, 0 -ATT, -0.23, -0.57, 0.00, -0.57, 0.00, 83.61, 83.10 -CTUN, 427, 0.00, 3.17, 4.947358, 0, 0, -13, 300, 0 -GPS, 3, 594506400, 8, 2.27, 44.0290175, -77.7367233, 5.00, 88.61, 0.17, 359.54 -ATT, -0.35, -0.59, 0.00, -0.51, 0.00, 83.56, 83.10 -CTUN, 427, 0.00, 2.89, 4.947358, 0, 0, -4, 287, 0 -ATT, -0.35, 0.24, 0.00, -0.27, 0.00, 83.50, 83.10 -CTUN, 426, 0.00, 2.44, 4.947358, 0, 0, 1, 296, 0 -GPS, 3, 594506600, 8, 2.27, 44.0290176, -77.7367240, 4.87, 88.60, 0.27, 359.54 -CTUN, 426, 0.00, 2.26, 4.947358, 0, 0, 11, 295, 0 -ATT, -0.82, -0.54, 0.00, -0.46, 0.00, 83.55, 83.10 -ATT, -0.82, -0.97, 0.00, -0.40, 0.00, 83.45, 83.10 -GPS, 3, 594506800, 8, 2.27, 44.0290179, -77.7367250, 4.69, 88.64, 0.37, 306.40 -CTUN, 427, 0.00, 2.23, 4.947358, 0, 0, 24, 281, 0 -ATT, -0.46, -0.74, 0.00, -0.26, 0.00, 83.49, 83.10 -CTUN, 426, 0.00, 2.53, 4.947358, 0, 0, 35, 276, 0 -ATT, -0.11, -0.91, 0.00, -0.45, 0.00, 83.42, 83.10 -GPS, 3, 594507000, 8, 2.27, 44.0290182, -77.7367259, 4.58, 88.69, 0.36, 296.90 -CTUN, 426, 0.00, 2.42, 4.947358, 0, 0, 46, 292, 0 -ATT, 0.00, -0.09, -0.47, 0.23, 0.00, 83.38, 83.10 -CTUN, 427, 0.00, 2.36, 4.947358, 0, 0, 50, 264, 0 -GPS, 3, 594507200, 8, 2.27, 44.0290184, -77.7367272, 4.51, 88.80, 0.48, 288.20 -ATT, 0.00, -0.33, -0.59, -0.67, 0.00, 83.48, 83.10 -CTUN, 426, 0.00, 2.22, 4.947358, 0, 0, 51, 284, 0 -ATT, 0.00, -0.24, -0.47, 0.25, 0.00, 83.36, 83.10 -CTUN, 426, 0.00, 2.25, 4.947358, 0, 0, 49, 282, 0 -GPS, 3, 594507400, 8, 2.27, 44.0290188, -77.7367285, 4.46, 88.99, 0.50, 289.47 -CTUN, 426, 0.00, 2.35, 4.947358, 0, 0, 50, 277, 0 -ATT, 0.00, -0.11, -0.59, -0.78, 0.00, 83.32, 83.10 -CTUN, 426, 0.00, 2.40, 4.947358, 0, 0, 49, 293, 0 -ATT, 0.00, -0.30, -0.59, -0.32, 0.00, 83.30, 83.10 -GPS, 3, 594507600, 8, 2.27, 44.0290195, -77.7367300, 4.38, 89.12, 0.67, 293.87 -DU32, 7, 426229 -CURR, 426, 184542, 1401, 1477, 4984, 291.341060 -CTUN, 426, 0.00, 2.73, 4.947358, 0, 0, 48, 295, 0 -ATT, 0.00, -0.01, -0.70, -1.04, 0.00, 83.27, 83.10 -CTUN, 426, 0.00, 3.51, 4.947358, 0, 0, 53, 278, 0 -GPS, 3, 594507800, 8, 2.27, 44.0290198, -77.7367315, 4.36, 89.25, 0.67, 293.87 -ATT, -0.35, -0.09, -1.18, -0.89, 0.00, 83.30, 83.10 -CTUN, 425, 0.00, 4.43, 4.947358, 0, 0, 56, 261, 0 -ATT, -0.35, -0.14, -2.12, -0.97, 0.00, 83.26, 83.10 -GPS, 3, 594508000, 8, 2.27, 44.0290203, -77.7367332, 4.41, 89.41, 0.70, 292.61 -CTUN, 426, 0.00, 3.11, 4.947358, 0, 0, 56, 287, 0 -ATT, -0.11, -0.45, -2.95, -1.12, 0.00, 83.30, 83.10 -CTUN, 404, 0.00, 3.16, 4.947358, 0, 0, 47, 286, 0 -ATT, -0.11, -0.45, -3.42, -2.54, 0.00, 83.31, 83.10 -GPS, 3, 594508200, 8, 2.27, 44.0290207, -77.7367351, 4.46, 89.61, 0.77, 290.89 -CTUN, 400, 0.00, 3.76, 4.947358, 0, 0, 47, 279, 0 -ATT, -0.93, -0.33, -4.37, -2.45, 0.00, 83.29, 83.10 -CTUN, 400, 0.00, 3.36, 4.947358, 0, 0, 44, 280, 0 -GPS, 3, 594508400, 8, 2.27, 44.0290212, -77.7367368, 4.48, 89.72, 0.77, 290.89 -ATT, -0.23, -0.67, -3.42, -3.41, 0.00, 83.36, 83.10 -CTUN, 401, 0.00, 3.33, 4.947358, 0, 0, 41, 279, 0 -ATT, 0.00, -0.53, 0.00, -2.92, 0.00, 83.42, 83.10 -CTUN, 403, 0.00, 3.28, 4.947358, 0, 0, 38, 296, 0 -GPS, 3, 594508600, 8, 2.27, 44.0290218, -77.7367386, 4.48, 89.85, 0.80, 292.21 -CTUN, 404, 0.00, 3.41, 4.947358, 0, 0, 39, 283, 0 -ATT, 0.00, -0.23, 0.00, -1.41, 0.00, 83.38, 83.10 -CTUN, 404, 0.00, 3.38, 4.947358, 0, 0, 40, 289, 0 -ATT, 0.00, -0.02, 0.00, -0.98, 0.00, 83.39, 83.10 -GPS, 3, 594508800, 8, 2.27, 44.0290223, -77.7367403, 4.47, 90.01, 0.80, 292.21 -CTUN, 404, 0.00, 3.48, 4.947358, 0, 0, 42, 289, 0 -ATT, 0.00, -0.19, 0.00, -0.90, 0.00, 83.50, 83.10 -CTUN, 404, 0.00, 3.36, 4.947358, 0, 0, 43, 278, 0 -GPS, 3, 594509000, 8, 2.27, 44.0290229, -77.7367420, 4.48, 90.15, 0.75, 293.48 -ATT, 0.00, -0.07, 0.00, -0.35, 0.00, 83.52, 83.10 -CTUN, 403, 0.00, 3.66, 4.947358, 0, 0, 43, 282, 0 -ATT, 0.00, -0.10, 0.00, -0.24, 0.00, 83.51, 83.10 -GPS, 3, 594509200, 8, 2.27, 44.0290233, -77.7367437, 4.49, 90.28, 0.74, 292.22 -CTUN, 404, 0.00, 3.66, 4.947358, 0, 0, 43, 284, 0 -ATT, 0.00, -0.02, 0.00, -0.25, 0.00, 83.48, 83.10 -CTUN, 403, 0.00, 3.84, 4.947358, 0, 0, 40, 281, 0 -MODE, LOITER, 269 -ATT, 0.00, -0.10, 0.00, -0.16, 0.00, 83.45, 83.10 -NTUN, 0.00, 0.00, -0.392242, 0.824524, 20.477097, -79.366447, 20.892122, -80.301155, 0.000000, 0.000000, 0.00, 0.00 -GPS, 3, 594509400, 8, 2.27, 44.0290237, -77.7367454, 4.51, 90.43, 0.72, 290.87 -CTUN, 403, 0.00, 3.83, 4.947358, 0, 0, 39, 285, 0 -NTUN, 0.00, 1.15, -2.404617, 1.562561, 15.465466, -74.281067, 21.428757, -83.369041, -54.620106, 59.350300, 3.56, -3.07 -ATT, 0.00, 0.06, 0.00, -0.14, 0.00, 83.45, 83.10 -DU32, 7, 426225 -CURR, 403, 189076, 1403, 1501, 4918, 298.326320 -NTUN, 0.02, 1.30, -4.433701, 2.705994, 10.563326, -68.973221, 20.355684, -83.640121, -58.516563, 68.614609, 3.83, -3.60 -GPS, 3, 594509600, 8, 2.27, 44.0290244, -77.7367475, 4.53, 90.59, 0.72, 290.87 -CTUN, 404, 0.00, 4.01, 4.947358, 0, 0, 38, 288, 0 -ATT, 0.00, 2.28, 0.00, -2.22, 0.00, 83.62, 83.10 -NTUN, 0.05, 1.36, -6.666534, 4.346115, 5.493059, -63.220314, 19.507177, -84.584747, -65.702667, 80.529068, 4.32, -4.23 -CTUN, 404, 0.00, 3.92, 4.947358, 0, 0, 34, 274, 0 -ATT, 0.00, 2.39, 0.00, -2.66, 0.00, 83.65, 83.10 -NTUN, 0.07, 1.37, -9.129379, 6.334610, 0.228888, -57.171371, 16.819878, -82.477005, -70.120514, 87.890518, 4.62, -4.64 -GPS, 3, 594509800, 8, 2.27, 44.0290251, -77.7367496, 4.57, 90.73, 0.84, 292.24 -NTUN, 0.07, 1.37, -11.545441, 8.488007, -4.897735, -51.089088, 13.520729, -80.020439, -72.266220, 92.822830, 4.78, -4.90 -CTUN, 404, 0.00, 4.13, 4.947358, 0, 0, 33, 283, 0 -ATT, 0.00, 3.15, 0.00, -3.32, 0.00, 83.61, 83.10 -NTUN, 0.14, 1.38, -13.961502, 10.692932, -9.989865, -45.005272, 9.815739, -76.039467, -73.417130, 97.235809, 4.86, -5.16 -CTUN, 404, 0.00, 4.25, 4.947358, 0, 0, 31, 288, 0 -GPS, 3, 594510000, 8, 2.27, 44.0290256, -77.7367520, 4.60, 90.89, 0.90, 292.82 -NTUN, 0.14, 1.38, -16.145523, 13.078400, -14.737354, -38.904129, 5.566157, -71.954544, -72.954437, 102.627700, 4.87, -5.46 -ATT, 0.00, 3.81, 0.00, -4.17, 0.00, 83.61, 83.10 -CTUN, 403, 0.00, 4.66, 4.947358, 0, 0, 30, 273, 0 -NTUN, 0.20, 1.38, -17.937027, 15.638824, -17.937027, -32.091202, 0.452021, -67.297890, -54.996727, 112.129270, 3.90, -6.13 -GPS, 3, 594510200, 8, 2.27, 44.0290259, -77.7367542, 4.63, 91.01, 0.95, 291.36 -ATT, 0.00, 4.20, -7.20, -4.53, 0.00, 83.60, 83.10 -CTUN, 404, 0.00, 4.60, 4.947358, 0, 0, 28, 279, 0 -NTUN, 0.23, 1.35, -19.205704, 18.572693, -19.205704, -21.231709, -3.512497, -61.722225, -33.561157, 158.519730, 2.96, -8.91 -CTUN, 404, 0.00, 4.22, 4.947358, 0, 1, 22, 290, 0 -NTUN, 0.26, 1.29, -19.978668, 21.850494, -19.978668, -10.068531, -7.855273, -54.398079, -26.729645, 169.631770, 2.63, -9.58 -ATT, -2.23, 3.42, -8.50, -6.23, 0.00, 83.60, 83.10 -GPS, 3, 594510400, 8, 2.27, 44.0290260, -77.7367565, 4.68, 91.15, 0.92, 279.61 -NTUN, 0.26, 1.29, -20.202087, 25.525101, -19.176048, 0.955887, -11.888488, -46.337727, -6.833751, 161.432300, 1.43, -9.24 -CTUN, 405, 0.00, 4.27, 4.947358, 0, 1, 21, 282, 0 -ATT, -7.98, 3.11, -5.43, -7.56, 0.00, 83.63, 83.10 -NTUN, 0.32, 1.25, -19.688385, 28.757706, -16.286692, 9.146431, -14.270606, -36.331989, 20.483231, 146.576980, -0.23, -8.57 -GPS, 3, 594510600, 8, 2.27, 44.0290258, -77.7367585, 4.69, 91.27, 0.85, 273.25 -NTUN, 0.32, 1.25, -18.563980, 31.683762, -12.049763, 16.642811, -15.144937, -27.239239, 38.369289, 138.963810, -1.31, -8.25 -CTUN, 404, 0.00, 4.37, 4.947358, 0, 1, 18, 280, 0 -ATT, -10.45, 1.44, -4.25, -7.72, 0.00, 83.65, 83.10 -NTUN, 0.36, 1.18, -16.874817, 34.403885, -6.984402, 23.942232, -15.467101, -17.960855, 51.152088, 136.271480, -2.07, -8.18 -GPS, 3, 594510800, 8, 2.27, 44.0290254, -77.7367604, 4.70, 91.36, 0.85, 273.25 -CTUN, 404, 0.00, 4.53, 4.947358, 0, 1, 18, 286, 0 -NTUN, 0.38, 1.13, -14.556931, 37.236206, -0.166468, 31.654922, -13.338625, -9.533600, 75.179337, 143.126890, -3.40, -8.72 -ATT, -12.80, -0.11, -5.43, -7.48, 0.00, 83.62, 83.10 -DU32, 7, 426225 -CURR, 404, 191585, 1398, 1541, 4855, 302.196590 -NTUN, 0.38, 1.13, -11.882385, 39.889313, 7.488876, 39.016869, -10.454329, -0.951527, 88.553436, 139.619460, -4.19, -8.61 -GPS, 3, 594511000, 8, 2.27, 44.0290246, -77.7367619, 4.71, 91.47, 0.74, 250.20 -ATT, -15.86, -1.49, -4.96, -8.21, 0.00, 83.61, 83.10 -NTUN, 0.38, 1.13, -8.596344, 42.060745, 16.756845, 42.060745, -5.446555, 6.962512, 110.679690, 93.438766, -5.73, -6.12 -CTUN, 404, 0.00, 4.69, 4.947358, 0, 1, 16, 283, 0 -NTUN, 0.42, 1.01, -4.794006, 43.703781, 26.558308, 43.703781, -0.077199, 13.445208, 121.014620, 76.430359, -6.43, -5.21 -GPS, 3, 594511200, 8, 2.27, 44.0290239, -77.7367631, 4.73, 91.59, 0.63, 242.37 -ATT, -16.68, -3.40, -2.83, -6.42, 0.00, 83.40, 83.10 -CTUN, 404, 0.00, 4.80, 4.947358, 0, 1, 15, 279, 0 -NTUN, 0.43, 0.95, -0.656754, 45.129807, 36.678032, 45.129807, 7.130199, 19.340948, 129.197240, 70.260254, -6.95, -4.93 -ATT, -15.97, -4.42, -0.59, -5.95, 0.00, 83.37, 83.10 -CTUN, 403, 0.00, 4.86, 4.947358, 0, 1, 14, 282, 0 -NTUN, 0.45, 0.90, 3.557236, 46.273834, 46.146534, 46.273834, 15.082404, 22.743402, 124.747540, 66.327003, -6.72, -4.68 -GPS, 3, 594511400, 8, 2.27, 44.0290230, -77.7367636, 4.76, 91.69, 0.63, 242.37 -CTUN, 405, 0.00, 4.94, 4.947358, 0, 1, 14, 274, 0 -NTUN, 0.45, 0.90, 7.915848, 47.149109, 55.106014, 47.149109, 23.907164, 25.883261, 121.594800, 62.752747, -6.57, -4.45 -ATT, -14.80, -5.48, 0.00, -5.75, 0.00, 83.36, 83.10 -NTUN, 0.47, 0.80, 12.253830, 47.801376, 63.648315, 47.801376, 33.164303, 27.460516, 117.423010, 60.522675, -6.34, -4.30 -GPS, 3, 594511600, 8, 2.27, 44.0290222, -77.7367639, 4.80, 91.80, 0.44, 208.66 -ATT, -13.98, -5.88, 0.00, -4.88, 0.00, 83.21, 83.10 -CTUN, 404, 0.00, 5.19, 4.947358, 0, 1, 11, 272, 0 -NTUN, 0.49, 0.76, 16.483765, 48.320267, 71.695786, 48.320267, 42.626343, 28.662865, 113.474700, 59.188904, -6.12, -4.21 -CTUN, 404, 0.00, 5.14, 4.947358, 0, 1, 9, 280, 0 -NTUN, 0.51, 0.71, 20.641357, 48.771469, 79.195396, 48.771469, 51.536797, 29.155905, 106.996110, 59.512024, -5.75, -4.19 -ATT, -13.15, -5.95, 0.00, -4.42, 0.00, 83.08, 83.10 -GPS, 3, 594511800, 8, 2.27, 44.0290215, -77.7367638, 4.84, 91.92, 0.46, 174.41 -NTUN, 0.52, 0.68, 25.169983, 49.098572, 86.873207, 49.098572, 61.108898, 29.163519, 100.798280, 58.973660, -5.39, -4.12 -CTUN, 404, 0.00, 5.30, 4.947358, 0, 1, 7, 281, 0 -ATT, -11.86, -5.41, 0.00, -4.44, 0.00, 83.07, 83.10 -NTUN, 0.55, 0.63, 29.564758, 49.366730, 94.138573, 49.366730, 70.025269, 28.870190, 98.048782, 60.437801, -5.22, -4.19 -GPS, 3, 594512000, 8, 2.27, 44.0290212, -77.7367632, 4.88, 92.02, 0.33, 166.00 -CTUN, 404, 0.00, 5.30, 4.947358, 0, 1, 6, 274, 0 -NTUN, 0.57, 0.60, 33.591965, 49.145493, 100.186520, 49.145493, 77.083549, 28.632116, 91.880623, 56.809532, -4.90, -3.93 -ATT, -11.39, -5.32, -0.23, -4.42, 0.00, 83.12, 83.10 -NTUN, 0.59, 0.57, 37.247192, 48.857819, 105.665430, 48.857819, 84.266220, 28.231627, 85.789124, 57.123260, -4.55, -3.91 -GPS, 3, 594512200, 8, 2.27, 44.0290211, -77.7367624, 4.92, 92.14, 0.38, 138.38 -CTUN, 404, 0.00, 5.30, 4.947358, 0, 0, 1, 264, 0 -ATT, -10.45, -5.02, 0.00, -4.25, 0.00, 83.01, 83.10 -NTUN, 0.61, 0.54, 40.893738, 48.067963, 110.899880, 48.067963, 90.061859, 27.095455, 83.344513, 53.101440, -4.43, -3.66 -CTUN, 403, 0.00, 5.27, 4.947358, 0, 0, 0, 280, 0 -ATT, -10.80, -4.55, -0.11, -3.88, 0.00, 82.93, 83.10 -NTUN, 0.63, 0.51, 44.364899, 47.188538, 116.046740, 47.188538, 96.079414, 27.407248, 81.958992, 52.292824, -4.35, -3.61 -GPS, 3, 594512400, 8, 2.27, 44.0290213, -77.7367612, 4.95, 92.21, 0.38, 138.38 -CTUN, 404, 0.00, 5.26, 4.947358, 0, 0, 0, 271, 0 -NTUN, 0.63, 0.51, 47.627281, 45.683136, 120.652680, 45.683136, 100.510120, 25.294455, 79.524666, 47.793922, -4.25, -3.33 -ATT, -9.98, -4.35, -0.70, -3.44, 0.00, 82.93, 83.10 -CTUN, 405, 0.00, 5.37, 4.947358, 0, 0, -3, 279, 0 -NTUN, 0.65, 0.44, 50.769234, 44.071320, 125.023090, 44.071320, 104.258620, 25.208780, 77.704071, 45.881836, -4.16, -3.21 -GPS, 3, 594512600, 8, 2.27, 44.0290217, -77.7367599, 4.98, 92.29, 0.61, 79.16 -CTUN, 404, 0.00, 5.30, 4.947358, 0, 0, -3, 272, 0 -NTUN, 0.65, 0.44, 53.940353, 41.966721, 129.283630, 41.966721, 107.739780, 23.351629, 78.183601, 42.162384, -4.21, -3.00 -ATT, -8.81, -4.16, 0.00, -3.56, 0.00, 82.95, 83.10 -NTUN, 0.68, 0.38, 56.581917, 39.692719, 129.864320, 39.692719, 110.882550, 23.687168, 39.806885, 39.259979, -2.02, -2.55 -GPS, 3, 594512800, 8, 2.27, 44.0290222, -77.7367583, 4.99, 92.37, 0.72, 72.70 -CTUN, 403, 0.00, 5.41, 4.947358, 0, 0, -6, 276, 0 -NTUN, 0.69, 0.35, 58.902969, 36.668243, 128.558350, 36.668243, 111.643350, 22.770132, 19.808392, 29.449747, -0.93, -1.84 -ATT, -0.35, -3.21, 0.00, -3.44, 0.00, 82.94, 83.10 -CTUN, 404, 0.00, 5.58, 4.947358, 0, 0, -7, 277, 0 -NTUN, 0.69, 0.35, 61.041809, 33.206818, 126.182550, 33.206818, 113.372570, 21.952679, 7.596386, 26.815985, -0.24, -1.60 -GPS, 3, 594513000, 8, 2.27, 44.0290231, -77.7367565, 5.00, 92.44, 0.85, 63.35 -CTUN, 404, 0.00, 5.58, 4.947358, 0, 0, -8, 278, 0 -ATT, 0.00, -1.76, 0.00, -2.35, 0.00, 82.87, 83.10 -NTUN, 0.69, 0.28, 62.388824, 29.359894, 123.563900, 29.359894, 111.305970, 21.619900, 3.813477, 16.530762, -0.10, -0.98 -CTUN, 404, 0.00, 6.09, 4.947358, 0, 0, -9, 268, 0 -GPS, 3, 594513200, 8, 2.27, 44.0290240, -77.7367547, 5.04, 92.48, 0.85, 63.35 -NTUN, 0.69, 0.28, 63.739120, 24.116776, 119.874820, 24.116776, 108.904940, 18.910702, 0.622465, 12.668320, 0.05, -0.73 -ATT, 0.00, -1.41, 0.00, -1.77, 0.00, 82.85, 83.10 -CTUN, 404, 0.00, 6.19, 4.947358, 0, 0, -10, 274, 0 -NTUN, 0.68, 0.20, 64.842690, 19.622635, 117.177700, 19.622635, 105.783760, 18.148106, 3.295912, 4.503559, -0.15, -0.28 -ATT, 0.00, -1.07, 0.00, -1.54, 0.00, 82.86, 83.10 -CTUN, 405, 0.00, 7.31, 4.947358, 0, 0, -12, 259, 0 -GPS, 3, 594513400, 8, 2.27, 44.0290251, -77.7367530, 5.10, 92.55, 0.94, 52.70 -NTUN, 0.67, 0.16, 65.724808, 15.145828, 114.345500, 15.145828, 102.220630, 15.186641, 3.958426, 3.675182, -0.20, -0.24 -CTUN, 404, 0.00, 7.41, 4.947358, 0, 0, -17, 270, 0 -ATT, 0.00, -0.66, -0.94, -0.78, 0.00, 82.99, 83.10 -DU32, 7, 426225 -CURR, 404, 196284, 1411, 1260, 4984, 309.341130 -NTUN, 0.67, 0.12, 66.205170, 10.664139, 111.525160, 10.664139, 98.937981, 13.244717, 3.220989, 0.268475, -0.18, -0.03 -CTUN, 404, 0.00, 6.23, 4.947358, 0, 0, -19, 267, 0 -GPS, 3, 594513600, 8, 2.27, 44.0290261, -77.7367514, 5.19, 92.60, 0.89, 49.24 -NTUN, 0.67, 0.12, 66.371475, 5.913437, 104.697200, 6.455256, 94.823051, 9.085901, -31.513126, 8.082134, 1.88, -0.24 -ATT, 5.77, -0.56, -4.96, -0.06, 0.00, 83.10, 83.10 -CTUN, 405, 0.00, 5.82, 4.947358, 0, 0, -38, 304, 0 -NTUN, 0.66, 0.04, 65.964310, 1.637253, 96.983963, 2.897467, 89.405396, 8.082429, -49.132416, 6.422112, 2.89, -0.03 -ATT, 8.59, 0.89, -5.43, -1.21, 0.00, 83.03, 83.10 -GPS, 3, 594513800, 8, 2.27, 44.0290273, -77.7367498, 5.24, 92.62, 0.90, 44.83 -NTUN, 0.66, 0.04, 65.164627, -2.501617, 88.418808, -0.251928, 83.850922, 5.167932, -59.803513, 10.817877, 3.53, -0.19 -CTUN, 404, 0.00, 5.66, 4.947358, 0, 0, -39, 272, 0 -NTUN, 0.65, 3.56, 63.672657, -6.502640, 78.671219, -2.908601, 77.317062, 3.396787, -75.475891, 14.433266, 4.47, -0.29 -ATT, 10.60, 1.88, -6.14, -0.41, 0.00, 82.96, 83.10 -GPS, 3, 594514000, 8, 2.27, 44.0290286, -77.7367486, 5.24, 92.63, 0.90, 39.02 -NTUN, 0.64, 3.52, 61.307583, -10.930817, 66.321632, -5.617483, 66.605743, 1.387981, -81.913223, 16.425983, 4.85, -0.36 -CTUN, 400, 0.00, 5.60, 4.947358, 0, 0, -39, 283, 0 -ATT, 11.19, 3.00, -6.37, -0.39, 0.00, 82.83, 83.10 -NTUN, 0.62, 3.48, 59.201450, -14.246979, 59.201450, -7.410961, 57.807575, -0.281552, -49.201820, 21.065220, 3.00, -0.86 -GPS, 3, 594514200, 8, 2.27, 44.0290299, -77.7367477, 5.17, 92.62, 0.81, 32.99 -NTUN, 0.62, 3.48, 57.211781, -17.135773, 54.008438, -8.192105, 49.026073, -2.087391, -25.930122, 32.188560, 1.73, -1.67 -ATT, 11.66, 3.17, -7.67, -0.55, 0.00, 82.82, 83.10 -NTUN, 0.59, 3.42, 55.313534, -19.578644, 49.102512, -7.518929, 40.548035, -2.312264, -19.059258, 47.731766, 1.44, -2.62 -GPS, 3, 594514400, 8, 2.27, 44.0290308, -77.7367470, 5.14, 92.63, 0.62, 29.43 -CTUN, 442, 0.00, 5.61, 4.947358, 0, 0, -30, 284, 0 -NTUN, 0.58, 3.39, 53.758736, -21.427109, 46.040321, -4.888256, 32.409458, -2.294425, 5.681278, 69.046265, 0.16, -4.03 -ATT, 8.12, 1.85, -12.28, -1.63, 0.00, 82.96, 83.10 -NTUN, 0.58, 3.39, 52.536484, -22.720276, 44.685551, -1.421616, 27.068195, -1.527096, 27.452293, 79.666405, -1.02, -4.80 -ATT, 6.59, 1.23, -13.58, -2.02, 0.00, 83.07, 83.10 -GPS, 3, 594514600, 8, 2.26, 44.0290318, -77.7367467, 5.12, 92.65, 0.58, 17.15 -CTUN, 617, 0.00, 5.53, 4.947358, 0, 0, -20, 297, 0 -NTUN, 0.57, 3.35, 51.270050, -23.390015, 43.667931, 2.553919, 23.008839, 0.173188, 34.924553, 87.361725, -1.41, -5.29 -ATT, 6.47, -0.35, -12.99, -3.86, 0.00, 83.20, 83.10 -CTUN, 724, 0.00, 5.58, 5.018160, 0, 0, -22, 283, 77 -NTUN, 0.56, 3.33, 49.820797, -23.643387, 42.320843, 6.567808, 19.913919, 3.164111, 34.393051, 89.544342, -1.37, -5.41 -GPS, 3, 594514800, 8, 2.26, 44.0290327, -77.7367466, 5.11, 92.69, 0.53, 11.19 -NTUN, 0.56, 3.33, 48.212811, -23.568069, 40.548885, 10.237755, 18.980471, 7.754626, 30.455868, 84.336105, -1.17, -5.09 -CTUN, 869, 0.00, 5.68, 5.018160, 0, 0, -22, 274, 77 -ATT, 6.83, -0.52, -11.33, -5.31, 0.00, 83.11, 83.10 -NTUN, 0.53, 3.32, 46.041733, -23.430756, 38.078236, 13.449219, 18.016365, 12.016790, 23.043941, 79.439026, -0.77, -4.75 -GPS, 3, 594515000, 8, 2.26, 44.0290333, -77.7367465, 5.11, 92.71, 0.45, 4.16 -CTUN, 951, 0.00, 5.59, 5.341995, 0, 0, -12, 329, 181 -NTUN, 0.53, 3.32, 43.603634, -23.066315, 34.721764, 16.746593, 18.556717, 19.672707, 11.767605, 76.647278, -0.15, -4.51 -ATT, 8.01, -0.69, -10.62, -4.66, 0.00, 83.24, 83.10 -CTUN, 997, 0.00, 5.67, 5.720915, 0, 1, 3, 318, 235 -NTUN, 0.49, 3.31, 40.825989, -22.898254, 30.743618, 19.776306, 17.820837, 24.725740, 1.218544, 72.297127, 0.41, -4.19 -GPS, 3, 594515200, 8, 2.26, 44.0290338, -77.7367462, 5.13, 92.77, 0.45, 4.16 -ATT, 9.07, -0.13, -10.27, -4.95, 0.00, 83.50, 83.10 -NTUN, 0.46, 3.29, 37.616764, -22.770721, 26.023319, 22.434677, 18.322371, 31.664955, -11.202988, 62.583710, 1.05, -3.55 -CTUN, 996, 0.00, 5.76, 6.091979, 0, 0, 22, 194, 247 -PM, 0, 0, 50, 143, 1000, 12148, 10, 0 -NTUN, 0.43, 3.24, 34.096344, -23.087799, 20.732347, 24.534332, 16.572750, 36.279903, -18.909718, 54.996552, 1.45, -3.06 -ATT, 9.89, 0.25, -9.56, -4.33, 0.00, 83.38, 83.10 -GPS, 3, 594515400, 8, 2.26, 44.0290344, -77.7367458, 5.21, 92.87, 0.39, 17.37 -NTUN, 0.43, 3.24, 30.545738, -23.188171, 15.133827, 26.457859, 15.594054, 42.580524, -25.985203, 47.235268, 1.82, -2.55 -CTUN, 996, 0.00, 5.85, 6.290305, 0, 0, 39, 282, 247 -ATT, 10.95, 0.60, -8.50, -5.13, 0.00, 82.99, 83.10 -NTUN, 0.38, 3.19, 26.859325, -23.287567, 9.044363, 28.027706, 13.170069, 46.969913, -35.894642, 40.698471, 2.36, -2.09 -GPS, 3, 594515600, 8, 2.26, 44.0290349, -77.7367453, 5.38, 93.02, 0.36, 23.78 -CTUN, 996, 0.00, 6.04, 6.833083, 0, 0, 89, 407, 247 -NTUN, 0.38, 3.19, 23.188778, -23.099823, 3.286053, 29.611332, 9.730205, 45.843460, -34.583103, 41.836258, 2.30, -2.17 -ATT, 10.01, 1.22, -8.14, -1.21, 0.00, 82.99, 83.10 -CTUN, 996, 0.00, 6.47, 7.281101, 0, 0, 107, 221, 247 -NTUN, 0.32, 3.12, 19.542210, -22.601776, -2.323345, 31.473457, 6.705809, 51.936249, -35.538589, 39.436882, 2.34, -2.03 -ATT, 10.13, 2.19, -8.03, -4.12, 0.00, 82.84, 83.10 -GPS, 3, 594515800, 8, 2.26, 44.0290354, -77.7367447, 5.68, 93.25, 0.42, 23.78 -NTUN, 0.29, 3.07, 16.220535, -22.029694, -6.556309, 34.023930, 0.531928, 50.321095, -21.757210, 49.762344, 1.61, -2.72 -CTUN, 996, 0.00, 6.31, 7.429094, 0, 0, 119, 375, 247 -ATT, 7.65, 2.25, -10.51, -3.03, 0.00, 82.70, 83.10 -NTUN, 0.27, 3.02, 13.233749, -20.901581, -9.778400, 37.527378, -3.627416, 55.202225, -10.220917, 57.034485, 1.01, -3.22 -GPS, 3, 594516000, 8, 2.26, 44.0290353, -77.7367436, 5.93, 93.49, 0.42, 23.78 -CTUN, 996, 0.00, 7.93, 7.823750, 0, 0, 151, 287, 247 -NTUN, 0.27, 3.02, 10.886833, -19.772919, -12.022072, 41.073105, -7.468875, 55.331085, 1.785433, 60.106205, 0.36, -3.49 -ATT, 6.24, -0.06, -10.74, -2.27, 0.00, 82.40, 83.10 -NTUN, 0.22, 2.97, 9.175865, -18.399902, -13.256380, 44.730247, -11.331161, 56.333790, 14.656918, 63.571426, -0.36, -3.78 -CTUN, 996, 0.00, 7.98, 8.267667, 0, 0, 158, 279, 247 -GPS, 3, 594516200, 8, 2.26, 44.0290353, -77.7367429, 6.29, 93.81, 0.43, 57.46 -ATT, 5.65, 1.43, -10.74, -2.46, 0.00, 82.36, 83.10 -NTUN, 0.22, 2.97, 7.807083, -16.633209, -13.761482, 48.681969, -13.450500, 55.087341, 22.948978, 71.517212, -0.77, -4.31 -CTUN, 996, 0.00, 7.05, 8.564304, 0, 0, 169, 289, 247 -NTUN, 0.18, 2.94, 6.766296, -14.222107, -13.877350, 53.997131, -15.756840, 55.614418, 27.841324, 90.151627, -0.93, -5.41 -ATT, 5.53, 0.62, -12.87, -2.63, 0.00, 82.60, 83.10 -GPS, 3, 594516400, 8, 2.26, 44.0290350, -77.7367423, 6.76, 94.21, 0.38, 98.63 -NTUN, 0.15, 2.94, 6.119110, -11.371094, -13.131790, 60.537849, -16.921707, 58.560497, 38.381779, 103.759580, -1.45, -6.27 -CTUN, 996, 0.00, 7.70, 8.812154, 0, 0, 169, 292, 247 -ATT, 4.59, -0.53, -14.05, -5.23, 0.00, 82.83, 83.10 -NTUN, 0.12, 2.97, 5.873497, -8.233704, -11.646658, 67.354820, -17.316105, 60.075607, 48.001335, 113.858290, -1.94, -6.91 -GPS, 3, 594516600, 8, 2.26, 44.0290352, -77.7367421, 7.12, 94.64, 0.20, 98.63 -NTUN, 0.12, 2.97, 5.469841, -4.422546, -10.339266, 74.830215, -16.322216, 64.085983, 46.944477, 123.013810, -1.83, -7.42 -ATT, 3.88, -0.89, -14.05, -5.00, 0.00, 83.04, 83.10 -CTUN, 996, 0.00, 8.05, 9.554359, 0, 0, 186, 272, 247 -NTUN, 0.07, 3.16, 4.770439, -0.531769, -9.268784, 81.851746, -14.984042, 69.008881, 44.704823, 121.215300, -1.74, -7.30 -GPS, 3, 594516800, 8, 2.26, 44.0290348, -77.7367415, 7.68, 95.10, 0.20, 98.63 -CTUN, 996, 0.00, 8.47, 9.901629, 0, 1, 190, 366, 247 -ATT, 4.12, -1.51, -12.99, -6.61, 0.00, 83.28, 83.10 -NTUN, 0.04, 3.19, 4.236908, 3.541565, -8.283539, 88.839890, -11.738020, 74.120995, 41.754898, 123.189540, -1.56, -7.39 -CTUN, 995, 0.00, 9.05, 10.246243, 0, 1, 206, 297, 246 -NTUN, 0.05, 3.47, 3.632957, 7.161346, -7.337574, 95.243729, -8.811634, 81.585648, 39.555199, 118.685240, -1.47, -7.11 -ATT, 3.65, -1.75, -12.75, -7.42, 0.00, 83.21, 83.10 -GPS, 3, 594517000, 8, 2.26, 44.0290347, -77.7367407, 8.13, 95.51, 0.37, 109.47 -CTUN, 996, 0.00, 9.59, 10.397268, 0, 1, 211, 347, 247 -NTUN, 0.05, 3.47, 2.831207, 10.609314, -6.501667, 101.239170, -4.097023, 88.372276, 35.359070, 112.954450, -1.24, -6.76 -ATT, 4.00, -1.31, -10.39, -6.91, 0.00, 83.08, 83.10 -CTUN, 996, 0.00, 10.73, 10.740984, 0, 1, 228, 273, 247 -NTUN, 0.10, 0.71, 1.745003, 13.640472, -6.378380, 105.140030, -2.579014, 94.425682, 27.220665, 90.622337, -0.93, -5.43 -GPS, 3, 594517200, 8, 2.26, 44.0290345, -77.7367393, 8.50, 95.98, 0.62, 105.55 -CTUN, 996, 0.00, 11.65, 10.740984, 0, 0, 228, 330, 247 -NTUN, 0.10, 0.71, 0.610008, 16.108124, -7.446008, 107.408540, -0.313636, 97.948044, 10.323721, 73.685089, -0.07, -4.33 -ATT, 6.24, -0.71, -7.08, -4.97, 0.00, 83.01, 83.10 -DU32, 7, 426225 -CURR, 996, 203423, 1397, 1377, 4984, 323.161320 -NTUN, 0.16, 0.87, -0.589127, 18.040588, -8.891955, 109.078540, -0.093395, 102.910540, 5.540524, 65.699982, 0.13, -3.84 -GPS, 3, 594517400, 8, 2.26, 44.0290343, -77.7367379, 9.11, 96.54, 0.70, 103.80 -ATT, 7.18, -0.13, -7.32, -5.31, 0.00, 83.20, 83.10 -CTUN, 996, 0.00, 12.31, 11.211786, 0, 0, 235, 311, 247 -NTUN, 0.18, 0.92, -1.631912, 19.855225, -10.575403, 110.675990, -0.924817, 103.567310, 1.332201, 65.816414, 0.37, -3.82 -CTUN, 996, 0.00, 13.92, 11.731929, 0, 0, 219, 279, 247 -NTUN, 0.19, 0.95, -2.655251, 21.588104, -13.187680, 112.317860, -0.717605, 107.185630, -11.122770, 64.418610, 1.08, -3.65 -ATT, 8.83, -0.13, -7.32, -4.71, 0.00, 83.21, 83.10 -GPS, 3, 594517600, 8, 2.26, 44.0290340, -77.7367359, 9.82, 97.06, 0.70, 103.80 -NTUN, 0.21, 0.98, -3.466019, 22.890808, -16.240339, 113.496640, -4.248571, 106.826320, -15.834940, 60.906940, 1.32, -3.42 -CTUN, 996, 0.00, 14.06, 12.002769, 0, 0, 217, 361, 247 -ATT, 11.07, 0.62, -6.85, -3.60, 0.00, 83.28, 83.10 -NTUN, 0.21, 0.98, -4.198929, 24.319855, -19.795225, 114.784670, -4.891054, 109.411570, -23.196888, 61.752724, 1.76, -3.41 -GPS, 3, 594517800, 8, 2.26, 44.0290337, -77.7367341, 10.61, 97.56, 0.83, 106.99 -CTUN, 995, 0.00, 14.86, 12.274844, 0, 0, 211, 157, 247 -NTUN, 0.24, 1.00, -4.835068, 25.417725, -23.260252, 115.758580, -9.420823, 108.926410, -22.650269, 59.739151, 1.71, -3.30 -ATT, 11.07, 1.13, -6.49, -4.49, 0.00, 83.32, 83.10 -CTUN, 996, 0.00, 15.01, 12.720007, 0, 0, 191, 360, 247 -NTUN, 0.25, 1.00, -5.163841, 26.782562, -26.079451, 116.674250, -12.716425, 104.909380, -17.476753, 65.249138, 1.45, -3.66 -GPS, 3, 594518000, 8, 2.26, 44.0290333, -77.7367320, 11.23, 98.00, 0.91, 107.41 -CTUN, 996, 0.00, 16.02, 12.994049, 0, 0, 185, 232, 247 -NTUN, 0.27, 0.99, -5.396782, 28.360809, -28.344652, 117.643440, -15.173414, 104.862380, -10.992249, 66.409637, 1.09, -3.77 -ATT, 10.13, 0.39, -6.14, -2.59, 0.00, 83.22, 83.10 -NTUN, 0.28, 0.98, -5.245308, 29.838165, -29.918043, 118.348500, -19.706738, 100.363130, -3.055010, 70.194519, 0.66, -4.04 -GPS, 3, 594518200, 8, 2.26, 44.0290329, -77.7367302, 11.94, 98.43, 0.84, 109.12 -ATT, 8.12, 1.19, -5.43, -2.35, 0.00, 83.19, 83.10 -CTUN, 995, 0.00, 16.19, 13.239262, 0, 0, 180, 225, 247 -NTUN, 0.28, 0.98, -4.768707, 31.720001, -30.418396, 119.074580, -23.524244, 95.615501, 11.996471, 77.260818, -0.16, -4.55 -CTUN, 996, 0.00, 16.62, 13.734447, 0, 0, 149, 284, 247 -NTUN, 0.32, 0.97, -4.118805, 33.989838, -30.224588, 119.448100, -24.862030, 95.006493, 19.918888, 75.698143, -0.62, -4.52 -ATT, 6.59, 1.07, -3.42, -3.94, 0.00, 83.20, 83.10 -GPS, 3, 594518400, 8, 2.26, 44.0290323, -77.7367284, 12.58, 98.81, 0.88, 114.11 -NTUN, 0.34, 0.95, -3.036987, 35.888702, -29.571508, 117.939770, -29.229357, 92.590385, 28.991560, 61.162167, -1.25, -3.74 -CTUN, 996, 0.00, 15.25, 13.959503, 0, 0, 154, 179, 247 -ATT, 6.95, -0.32, -1.18, -6.50, 0.00, 83.06, 83.10 -NTUN, 0.36, 0.92, -1.833771, 37.668091, -28.890047, 116.377600, -30.135595, 89.037308, 30.747143, 62.532951, -1.32, -3.84 -GPS, 3, 594518600, 8, 2.26, 44.0290316, -77.7367265, 13.19, 99.15, 0.82, 116.94 -CTUN, 996, 0.00, 15.26, 14.278409, 0, 0, 126, 256, 247 -NTUN, 0.36, 0.92, -0.596481, 39.175598, -28.170195, 114.555980, -30.237619, 88.488266, 32.198524, 59.783752, -1.43, -3.69 -ATT, 6.95, -1.13, -0.70, -2.25, 0.00, 82.94, 83.10 -NTUN, 0.39, 0.89, 0.642113, 40.224854, -27.361994, 112.174480, -30.032408, 85.003487, 33.163643, 56.944443, -1.51, -3.53 -GPS, 3, 594518800, 8, 2.26, 44.0290311, -77.7367251, 13.53, 99.41, 0.65, 117.10 -CTUN, 996, 0.00, 16.79, 14.723810, 0, 0, 99, 281, 247 -ATT, 6.59, -0.78, -0.59, -3.97, 0.00, 83.02, 83.10 -NTUN, 0.40, 0.87, 1.590019, 41.442474, -26.645962, 109.944880, -29.658508, 83.124626, 33.089424, 58.924763, -1.49, -3.64 -CTUN, 998, 0.00, 15.68, 15.194016, 0, 0, 112, 271, 248 -NTUN, 0.41, 0.86, 2.527641, 42.761108, -25.839230, 107.903080, -31.172449, 76.712410, 36.067322, 67.582062, -1.62, -4.16 -GPS, 3, 594519000, 8, 2.26, 44.0290306, -77.7367234, 13.94, 99.62, 0.73, 116.42 -ATT, 6.12, -0.56, -0.47, -2.80, 0.00, 83.26, 83.10 -CTUN, 997, 0.00, 17.21, 15.243408, 0, 0, 110, 308, 248 -NTUN, 0.42, 0.81, 3.282906, 43.912109, -25.041054, 105.549690, -28.932016, 76.622818, 33.981758, 62.466064, -1.54, -3.85 -CTUN, 996, 0.00, 15.95, 15.688286, 0, 0, 128, 289, 247 -ATT, 5.65, -2.07, 0.00, -3.93, 0.00, 83.35, 83.10 -NTUN, 0.42, 0.81, 3.883347, 44.952148, -24.212851, 103.009670, -29.877666, 70.973190, 37.200031, 66.851250, -1.69, -4.12 -GPS, 3, 594519200, 8, 2.26, 44.0290303, -77.7367221, 14.46, 99.86, 0.58, 116.38 -CTUN, 996, 0.00, 15.94, 15.864447, 0, 0, 136, 287, 247 -NTUN, 0.42, 0.81, 4.165695, 45.885040, -23.712097, 100.526260, -26.579601, 69.123634, 31.058115, 66.915092, -1.32, -4.09 -ATT, 5.41, -1.78, 0.00, -3.98, 0.00, 83.10, 83.10 -NTUN, 0.46, 0.83, 4.091446, 46.878204, -23.469473, 98.097061, -26.620733, 65.894867, 29.402220, 70.948524, -1.20, -4.31 -CTUN, 996, 0.00, 15.87, 16.209011, 0, 0, 148, 297, 247 -GPS, 3, 594519400, 8, 2.26, 44.0290298, -77.7367206, 14.73, 100.10, 0.68, 115.04 -ATT, 5.30, -0.76, 0.00, -4.70, 0.00, 82.92, 83.10 -NTUN, 0.47, 0.81, 3.953842, 47.496094, -23.300184, 95.411171, -24.190737, 63.679607, 25.692886, 68.141098, -0.99, -4.12 -CTUN, 996, 0.00, 15.73, 16.557726, 0, 0, 161, 267, 247 -ATT, 6.00, -1.77, -0.47, -4.21, 0.00, 83.07, 83.10 -NTUN, 0.47, 0.81, 3.643936, 47.980103, -23.772636, 92.911438, -24.237890, 60.313282, 19.275478, 73.002670, -0.60, -4.36 -GPS, 3, 594519600, 8, 2.26, 44.0290295, -77.7367191, 15.15, 100.41, 0.68, 115.04 -CTUN, 996, 0.00, 16.22, 16.728334, 0, 0, 160, 297, 247 -NTUN, 0.47, 0.81, 3.288925, 47.572388, -24.837254, 90.734863, -23.044531, 60.794445, 12.353828, 74.234253, -0.19, -4.38 -ATT, 8.48, -0.92, -3.77, -4.88, 0.00, 83.16, 83.10 -CTUN, 996, 0.00, 16.32, 17.149193, 0, 0, 163, 280, 247 -NTUN, 0.47, 0.84, 2.710556, 46.968201, -26.893736, 89.367302, -23.627893, 57.969761, 0.638790, 86.459793, 0.56, -5.00 -GPS, 3, 594519800, 8, 2.26, 44.0290293, -77.7367176, 15.55, 100.74, 0.65, 108.70 -NTUN, 0.47, 0.84, 1.732132, 46.637024, -30.054409, 88.589165, -23.593784, 58.781097, -14.606731, 91.218628, 1.47, -5.17 -CTUN, 996, 0.00, 17.28, 17.246727, 0, 0, 162, 279, 247 -ATT, 10.95, -0.10, -4.84, -4.82, 0.00, 83.18, 83.10 -NTUN, 0.46, 0.87, 0.158478, 46.511658, -34.546696, 88.302902, -25.764132, 58.522488, -29.478085, 98.165718, 2.37, -5.47 -CTUN, 996, 0.00, 17.10, 17.692158, 0, 0, 166, 298, 247 -GPS, 3, 594520000, 8, 2.26, 44.0290293, -77.7367162, 15.91, 101.06, 0.61, 104.10 -ATT, 11.89, 0.45, -4.72, -4.63, 0.00, 83.17, 83.10 -NTUN, 0.46, 0.87, -1.698029, 46.192993, -39.199146, 87.836555, -27.263979, 58.985443, -35.994450, 96.289429, 2.74, -5.32 -CTUN, 996, 0.00, 17.61, 17.942526, 0, 0, 164, 282, 247 -NTUN, 0.46, 0.90, -3.835083, 45.677734, -43.659470, 86.723969, -29.615387, 59.018776, -36.603233, 90.874130, 2.73, -5.00 -GPS, 3, 594520200, 8, 2.26, 44.0290292, -77.7367147, 16.38, 101.34, 0.61, 104.10 -ATT, 10.95, 1.32, -3.89, -5.04, 0.00, 83.20, 83.10 -CTUN, 997, 0.00, 17.57, 18.238728, 0, 0, 165, 318, 248 -NTUN, 0.45, 0.92, -6.151901, 44.841797, -48.020977, 84.871262, -31.377905, 60.375694, -38.183239, 81.656372, 2.76, -4.46 -CTUN, 997, 0.00, 17.63, 18.636013, 0, 0, 174, 306, 248 -ATT, 9.77, 1.87, -2.71, -5.41, 0.00, 83.19, 83.10 -NTUN, 0.45, 0.92, -8.378418, 43.612000, -51.856861, 82.338425, -34.917248, 60.438259, -34.746304, 72.415787, 2.50, -3.95 -GPS, 3, 594520400, 8, 2.26, 44.0290288, -77.7367131, 16.80, 101.67, 0.63, 105.31 -CTUN, 978, 0.00, 17.88, 18.735601, 0, 0, 179, 325, 248 -NTUN, 0.44, 1.00, -10.449356, 41.817505, -55.120907, 78.505508, -37.006977, 62.325958, -31.317284, 56.050335, 2.20, -3.02 -ATT, 8.59, 1.68, -0.59, -4.93, 0.00, 83.08, 83.10 -NTUN, 0.43, 1.03, -12.512131, 39.105408, -58.308384, 72.458130, -43.066788, 61.950974, -23.562309, 37.605179, 1.62, -2.01 -GPS, 3, 594520600, 8, 2.26, 44.0290287, -77.7367116, 17.20, 101.98, 0.58, 103.66 -CTUN, 819, 0.00, 18.13, 19.137781, 0, 0, 200, 310, 195 -ATT, 8.12, 2.60, 0.00, -2.85, 0.00, 83.00, 83.10 -NTUN, 0.41, 1.06, -14.138824, 36.589355, -60.763363, 67.254189, -45.910439, 59.645058, -20.797768, 33.434937, 1.44, -1.79 -CTUN, 687, 0.00, 19.10, 19.345133, 0, 0, 202, 202, 62 -NTUN, 0.39, 1.09, -15.757019, 34.042969, -63.014751, 61.977695, -49.635990, 57.315918, -18.072437, 31.269676, 1.26, -1.68 -GPS, 3, 594520800, 8, 2.26, 44.0290283, -77.7367102, 17.71, 102.37, 0.65, 109.25 -ATT, 7.42, 1.38, 0.00, -2.81, 0.00, 82.96, 83.10 -CTUN, 656, 0.00, 19.64, 19.394588, 0, 0, 186, 213, 41 -NTUN, 0.37, 1.13, -17.047104, 31.622864, -64.428223, 56.882774, -52.698086, 51.843559, -9.134712, 33.050789, 0.76, -1.85 -ATT, 5.89, 1.65, 0.00, -1.05, 0.00, 83.18, 83.10 -CTUN, 634, 0.00, 20.16, 19.418957, 0, 0, 157, 183, 23 -NTUN, 0.37, 1.13, -18.057571, 29.307922, -64.285995, 51.519585, -55.201878, 45.285732, 8.292974, 36.243729, -0.23, -2.15 -GPS, 3, 594521000, 8, 2.26, 44.0290279, -77.7367090, 18.12, 102.74, 0.58, 113.58 -CTUN, 629, 0.00, 18.72, 19.418957, 0, 0, 157, 203, 23 -NTUN, 0.34, 1.20, -18.806976, 27.543152, -63.145977, 46.946213, -56.072815, 40.838249, 20.400185, 40.266281, -0.91, -2.47 -ATT, 3.18, 1.24, 0.00, 1.21, 0.00, 83.41, 83.10 -CTUN, 629, 0.00, 19.81, 19.458111, 0, 0, 74, 360, 18 -NTUN, 0.34, 1.20, -19.284317, 25.802368, -61.582127, 42.438213, -56.926636, 40.490993, 26.638504, 35.920006, -1.30, -2.26 -GPS, 3, 594521200, 8, 2.26, 44.0290275, -77.7367081, 18.49, 103.01, 0.44, 120.51 -ATT, 2.47, -0.28, 0.00, -6.96, 0.00, 83.20, 83.10 -CTUN, 628, 0.00, 18.65, 19.478052, 0, 0, 92, 130, 18 -NTUN, 0.32, 1.25, -19.715759, 23.944580, -59.726486, 37.846092, -57.693081, 36.980595, 31.556404, 34.078789, -1.57, -2.19 -ATT, 2.23, -0.54, 0.00, -5.53, 0.00, 83.21, 83.10 -NTUN, 0.31, 1.28, -19.945694, 22.280396, -57.600418, 33.468452, -57.788635, 30.821573, 36.050179, 38.657032, -1.82, -2.48 -GPS, 3, 594521400, 8, 2.26, 44.0290269, -77.7367071, 18.73, 103.09, 0.47, 127.13 -CTUN, 629, 0.00, 18.58, 19.496891, 0, 0, 86, 274, 18 -NTUN, 0.31, 1.28, -20.048599, 20.818237, -55.254745, 29.383919, -55.639557, 28.401787, 38.693665, 38.742085, -1.97, -2.51 -CTUN, 629, 0.00, 19.43, 19.527475, 0, 0, 60, 204, 18 -ATT, 1.76, -1.39, 0.00, 1.78, 0.00, 83.33, 83.10 -NTUN, 0.28, 1.33, -20.140701, 19.197083, -52.904259, 25.145082, -54.163177, 24.874306, 39.272148, 38.031326, -2.02, -2.46 -GPS, 3, 594521600, 8, 2.26, 44.0290266, -77.7367065, 18.84, 103.23, 0.35, 130.18 -CTUN, 628, 0.00, 19.91, 19.527475, 0, 0, 60, 288, 18 -NTUN, 0.27, 1.35, -20.389679, 17.888855, -50.717720, 21.317791, -52.976021, 18.875074, 39.086250, 43.340488, -1.96, -2.77 -ATT, 1.53, -1.24, 0.00, -5.92, 0.00, 83.39, 83.10 -GPS, 3, 594521800, 8, 2.26, 44.0290263, -77.7367058, 18.99, 103.30, 0.35, 130.18 -NTUN, 0.27, 1.35, -20.943604, 16.632690, -48.331825, 17.028605, -48.772041, 14.273384, 34.556515, 46.842735, -1.68, -2.95 -CTUN, 629, 0.00, 18.58, 19.565386, 0, 0, 31, 277, 18 -ATT, 1.53, -2.13, 0.00, -2.57, 0.00, 83.24, 83.10 -NTUN, 0.26, 1.41, -21.821274, 15.611633, -46.989532, 15.611633, -45.023384, 11.958056, 27.558514, 68.687157, -1.12, -4.16 -CTUN, 629, 0.00, 19.94, 19.591255, 0, 0, 33, 279, 18 -ATT, 1.64, -1.62, 0.00, -1.66, 0.00, 83.32, 83.10 -GPS, 3, 594522000, 8, 2.26, 44.0290262, -77.7367055, 19.09, 103.32, 0.32, 127.79 -NTUN, 0.26, 1.44, -22.994476, 14.969910, -45.726563, 14.969910, -40.984604, 7.964291, 22.378109, 82.218704, -0.73, -4.91 -CTUN, 628, 0.00, 20.72, 19.607529, 0, 0, 31, 279, 18 -NTUN, 0.27, 1.46, -24.496246, 14.590332, -45.208481, 14.590332, -37.777061, 5.676223, 13.233149, 85.165886, -0.19, -5.01 -ATT, 1.88, -1.08, 0.00, -4.97, 0.00, 83.39, 83.10 -CTUN, 629, 0.00, 19.08, 19.628593, 0, 0, 39, 254, 18 -GPS, 3, 594522200, 8, 2.26, 44.0290262, -77.7367051, 19.24, 103.34, 0.19, 127.79 -NTUN, 0.28, 1.49, -26.401016, 14.452637, -45.641159, 14.452637, -36.120213, 3.103363, 1.394348, 91.852539, 0.54, -5.32 -CTUN, 629, 0.00, 18.77, 19.640608, 0, 0, 36, 275, 18 -ATT, 4.82, -0.33, 0.00, -4.27, 0.00, 83.21, 83.10 -NTUN, 0.30, 1.51, -28.322067, 14.158203, -47.541531, 14.158203, -34.380619, 4.074688, -18.003716, 89.055664, 1.64, -5.03 -GPS, 3, 594522400, 8, 2.26, 44.0290262, -77.7367047, 19.28, 103.37, 0.18, 127.79 -NTUN, 0.31, 1.53, -30.431732, 13.750671, -50.512436, 13.750671, -34.377316, 3.844102, -32.414902, 87.965034, 2.47, -4.87 -CTUN, 629, 0.00, 18.86, 19.692930, 0, 0, 28, 271, 18 -ATT, 7.18, 0.49, 0.00, -4.82, 0.00, 83.22, 83.10 -NTUN, 0.33, 1.56, -32.773254, 13.122559, -54.076080, 13.122559, -33.600674, 4.177753, -43.636444, 84.718872, 3.10, -4.60 -GPS, 3, 594522600, 8, 2.26, 44.0290263, -77.7367043, 19.30, 103.39, 0.18, 127.79 -ATT, 8.12, 1.41, 0.00, -4.60, 0.00, 83.18, 83.10 -CTUN, 629, 0.00, 18.89, 19.701591, 0, 0, 28, 279, 18 -NTUN, 0.35, 1.59, -35.078079, 12.309021, -57.769184, 12.309021, -34.540733, 5.109887, -48.931038, 81.864624, 3.39, -4.40 -CTUN, 629, 0.00, 19.02, 19.737644, 0, 0, 29, 269, 18 -NTUN, 0.37, 1.61, -37.362045, 11.256592, -61.519882, 11.256592, -35.903126, 5.037075, -53.135624, 79.579910, 3.62, -4.23 -ATT, 8.36, 1.91, 0.00, -4.52, 0.00, 83.07, 83.10 -GPS, 3, 594522800, 8, 2.26, 44.0290265, -77.7367040, 19.33, 103.41, 0.19, 127.79 -NTUN, 0.37, 1.61, -39.726852, 10.205627, -65.207771, 10.205627, -38.453304, 5.121856, -54.878891, 78.490356, 3.72, -4.15 -CTUN, 627, 0.00, 19.03, 19.755886, 0, 0, 27, 280, 17 -ATT, 8.01, 2.51, 0.00, -3.87, 0.00, 83.05, 83.10 -NTUN, 0.41, 1.66, -42.075409, 9.057434, -68.645226, 9.057434, -40.445374, 6.199208, -55.721760, 74.402084, 3.74, -3.91 -GPS, 3, 594523000, 8, 2.26, 44.0290266, -77.7367036, 19.36, 103.43, 0.15, 127.79 -CTUN, 562, 0.00, 18.88, 19.769218, 0, 0, 29, 279, 1 -NTUN, 0.41, 1.66, -44.526321, 7.822876, -72.179619, 7.822876, -43.791599, 5.788334, -57.993992, 73.776657, 3.87, -3.85 -ATT, 7.77, 3.15, 0.00, -4.53, 0.00, 82.93, 83.10 -NTUN, 0.45, 1.70, -46.951752, 6.598022, -75.460548, 6.598022, -47.562805, 6.149285, -55.809296, 71.751465, 3.73, -3.75 -GPS, 3, 594523200, 8, 2.26, 44.0290266, -77.7367033, 19.39, 103.43, 0.18, 127.79 -CTUN, 386, 0.00, 18.93, 19.769218, 0, 0, 33, 285, 0 -ATT, 7.18, 3.51, 0.00, -3.65, 0.00, 83.05, 83.10 -NTUN, 0.47, 1.73, -48.795883, 5.310669, -77.953117, 5.310669, -51.416599, 6.185412, -47.678902, 71.253929, 3.25, -3.79 -CTUN, 342, 0.00, 19.03, 19.751915, 0, 0, 29, 256, -25 -NTUN, 0.49, 1.74, -50.100845, 4.008423, -79.496582, 4.008423, -54.860119, 5.216892, -37.590553, 69.846001, 2.66, -3.77 -ATT, 5.77, 3.15, 0.00, -3.87, 0.00, 83.07, 83.10 -GPS, 3, 594523400, 8, 2.26, 44.0290264, -77.7367032, 19.42, 103.46, 0.24, 146.59 -CTUN, 301, 0.00, 19.06, 19.719854, 0, 0, 29, 263, -46 -NTUN, 0.49, 1.74, -51.149078, 2.926575, -79.703491, 2.926575, -58.349648, 4.475074, -23.048605, 72.288635, 1.84, -4.02 -ATT, 3.41, 3.08, 0.00, -3.48, 0.00, 83.11, 83.10 -CTUN, 282, 0.00, 19.21, 19.596949, 0, 0, 17, 281, -73 -NTUN, 0.51, 1.77, -52.078003, 2.105652, -79.139717, 2.105652, -60.540531, 4.171397, -12.362259, 73.790771, 1.23, -4.18 -GPS, 3, 594523600, 8, 2.26, 44.0290261, -77.7367032, 19.43, 103.47, 0.24, 146.59 -CTUN, 265, 0.00, 18.94, 19.596949, 0, 0, 17, 255, -73 -NTUN, 0.52, 1.78, -52.169571, 1.420898, -77.383957, 1.420898, -63.197117, 3.027788, 3.557602, 76.152466, 0.32, -4.43 -ATT, 1.64, 1.95, 0.00, -4.22, 0.00, 83.08, 83.10 -NTUN, 0.52, 1.78, -51.531982, 0.884827, -74.067146, 0.884827, -64.491882, 3.068492, 23.168106, 76.639282, -0.79, -4.59 -CTUN, 242, 0.00, 18.90, 19.432602, 0, 0, 10, 249, -92 -GPS, 3, 594523800, 8, 2.26, 44.0290257, -77.7367034, 19.44, 103.45, 0.33, 177.39 -ATT, 0.00, 1.27, 0.00, -4.44, 0.00, 82.97, 83.10 -NTUN, 0.51, 1.79, -50.916138, 0.545044, -70.444260, 0.545044, -64.279083, 2.208198, 29.228867, 79.602173, -1.12, -4.81 -CTUN, 230, 0.00, 18.88, 19.257757, 0, 0, 1, 269, -105 -ATT, 0.00, 0.25, 0.00, -4.12, 0.00, 83.03, 83.10 -NTUN, 0.50, 1.79, -50.479767, 0.504395, -67.068512, 0.504395, -62.800655, 2.330840, 28.757477, 82.593506, -1.08, -4.98 -GPS, 3, 594524000, 8, 2.26, 44.0290251, -77.7367038, 19.40, 103.42, 0.44, 188.93 -CTUN, 217, 0.00, 18.67, 19.182940, 0, 0, -1, 242, -108 -NTUN, 0.50, 1.79, -49.777725, 0.630981, -63.493217, 0.630981, -61.302757, 0.089084, 32.752945, 85.265869, -1.29, -5.16 -ATT, 0.00, -0.13, 0.00, -3.86, 0.00, 83.02, 83.10 -NTUN, 0.49, 1.79, -48.821991, 1.218018, -59.700798, 1.218018, -57.969376, 0.755760, 35.548706, 89.812241, -1.41, -5.44 -CTUN, 202, 0.00, 18.90, 19.010788, 0, 0, -24, 288, -120 -ATT, 0.00, -0.72, 0.00, -5.00, 0.00, 82.87, 83.10 -GPS, 3, 594524200, 8, 2.26, 44.0290245, -77.7367041, 19.31, 103.38, 0.42, 192.65 -NTUN, 0.48, 1.78, -47.850937, 1.676392, -55.984974, 1.676392, -54.052479, 1.942502, 35.158241, 88.583740, -1.38, -5.37 -CTUN, 196, 0.00, 17.97, 18.860941, 0, 0, -24, 186, -125 -ATT, 0.00, -0.81, 0.00, -5.81, 0.00, 82.97, 83.10 -NTUN, 0.48, 1.78, -46.804688, 2.409119, -52.282539, 2.409119, -52.043980, -1.808660, 36.398331, 95.401283, -1.42, -5.77 -GPS, 3, 594524400, 8, 2.26, 44.0290238, -77.7367044, 19.19, 103.25, 0.42, 192.65 -CTUN, 193, 0.00, 18.51, 18.669348, 0, 0, -48, 258, -128 -NTUN, 0.48, 1.78, -45.624100, 3.407349, -48.452465, 3.407349, -46.856667, -0.259074, 35.921528, 96.883469, -1.40, -5.84 -ATT, 0.00, -1.10, 0.00, -3.20, 0.00, 83.24, 83.10 -NTUN, 0.45, 1.75, -44.370697, 4.227051, -44.635426, 4.227051, -44.530945, 0.182919, 37.170395, 96.197021, -1.50, -5.81 -GPS, 3, 594524600, 8, 2.26, 44.0290231, -77.7367047, 19.08, 103.16, 0.42, 196.36 -ATT, 0.00, -0.83, 0.00, -6.26, 0.00, 83.48, 83.10 -CTUN, 193, 0.00, 18.19, 18.515924, 0, 0, -62, 261, -129 -NTUN, 0.44, 1.74, -42.725281, 5.271179, -42.725281, 5.271179, -40.308460, -1.066855, 16.101448, 100.441280, -0.26, -5.91 -ATT, 0.00, -1.51, 0.00, -5.72, 0.00, 83.50, 83.10 -CTUN, 191, 0.00, 17.75, 18.244871, 0, 0, -79, 283, -130 -DU32, 7, 426225 -CURR, 191, 216971, 1401, 1535, 4962, 346.119170 -NTUN, 0.43, 1.72, -41.095291, 6.236694, -41.095291, 6.236694, -37.769100, 1.383498, 11.299896, 98.655151, 0.00, -5.78 -GPS, 3, 594524800, 8, 2.26, 44.0290226, -77.7367048, 18.84, 102.98, 0.35, 190.77 -CTUN, 191, 0.00, 17.60, 18.218542, 0, 0, -79, 266, -130 -NTUN, 0.43, 1.72, -39.931061, 6.910156, -39.931061, 6.910156, -33.252842, 2.330999, 3.642303, 95.734619, 0.44, -5.56 -ATT, 0.00, -0.62, 0.00, -5.94, 0.00, 83.26, 83.10 -CTUN, 191, 0.00, 17.62, 17.971729, 0, 0, -73, 265, -130 -NTUN, 0.40, 1.69, -39.319489, 7.420959, -39.319489, 7.420959, -30.518074, 3.237051, -3.884277, 94.108032, 0.86, -5.41 -ATT, 0.00, -0.27, 0.00, -5.24, 0.00, 83.22, 83.10 -GPS, 3, 594525000, 8, 2.26, 44.0290220, -77.7367049, 18.58, 102.81, 0.35, 190.77 -NTUN, 0.40, 1.69, -38.672516, 7.779602, -38.672516, 7.779602, -28.115263, 4.717040, -6.594330, 91.550919, 1.01, -5.25 -CTUN, 191, 0.00, 17.85, 17.917816, 0, 0, -74, 265, -130 -ATT, 0.00, 0.15, 0.00, -5.36, 0.00, 83.14, 83.10 -NTUN, 0.39, 1.68, -37.903442, 7.970093, -37.903442, 7.970093, -27.089132, 5.955593, -5.309265, 88.904907, 0.92, -5.10 -CTUN, 191, 0.00, 17.63, 17.658070, 0, 0, -75, 259, -129 -GPS, 3, 594525200, 8, 2.26, 44.0290215, -77.7367049, 18.32, 102.65, 0.35, 178.71 -ATT, 0.00, 0.52, 0.00, -5.47, 0.00, 83.08, 83.10 -NTUN, 0.39, 1.68, -37.075821, 8.036255, -37.075821, 8.036255, -25.581520, 6.863884, -6.723785, 86.661621, 0.99, -4.96 -CTUN, 194, 0.00, 17.57, 17.528648, 0, 0, -77, 261, -128 -PM, 0, 0, 50, 186, 1005, 12288, 10, 0 -ATT, 0.00, 0.54, 0.00, -5.23, 0.00, 83.10, 83.10 -NTUN, 0.37, 1.67, -36.056839, 7.940735, -36.056839, 7.940735, -25.308338, 8.001395, -3.810181, 84.044800, 0.80, -4.83 -CTUN, 194, 0.00, 17.57, 17.399775, 0, 0, -81, 272, -128 -GPS, 3, 594525400, 8, 2.26, 44.0290210, -77.7367047, 18.16, 102.47, 0.35, 178.71 -NTUN, 0.37, 1.67, -34.930420, 7.673279, -34.930420, 7.673279, -24.324539, 9.064540, -3.735809, 81.325439, 0.78, -4.68 -ATT, 0.00, 0.79, 0.00, -5.02, 0.00, 83.07, 83.10 -CTUN, 194, 0.00, 17.43, 17.270796, 0, 0, -83, 258, -129 -NTUN, 0.35, 1.67, -33.635361, 7.231262, -33.635361, 7.231262, -24.225967, 8.854257, -1.177632, 79.623596, 0.62, -4.60 -ATT, 0.00, 0.60, 0.00, -4.59, 0.00, 83.08, 83.10 -GPS, 3, 594525600, 8, 2.26, 44.0290205, -77.7367044, 17.93, 102.29, 0.36, 167.08 -CTUN, 193, 0.00, 17.46, 17.130007, 0, 0, -86, 262, -128 -NTUN, 0.34, 1.68, -32.207504, 6.621033, -32.207504, 6.621033, -23.837650, 10.009679, 0.137192, 75.958122, 0.52, -4.39 -ATT, 0.00, 0.64, 0.00, -4.84, 0.00, 83.05, 83.10 -CTUN, 191, 0.00, 17.19, 16.962297, 0, 0, -89, 257, -129 -NTUN, 0.32, 1.69, -30.617386, 5.892578, -30.617386, 5.892578, -23.886414, 10.131125, 4.061802, 73.641876, 0.28, -4.29 -GPS, 3, 594525800, 8, 2.26, 44.0290201, -77.7367042, 17.76, 102.09, 0.36, 167.08 -CTUN, 193, 0.00, 17.25, 16.923428, 0, 0, -90, 263, -130 -NTUN, 0.32, 1.69, -28.944366, 5.156494, -28.944366, 5.156494, -24.073055, 9.867669, 6.730194, 73.639160, 0.12, -4.31 -ATT, 0.00, 0.68, 0.00, -4.35, 0.00, 83.11, 83.10 -NTUN, 0.29, 1.69, -27.168274, 4.450317, -27.168274, 4.450317, -24.128586, 9.075647, 8.760925, 72.938232, 0.00, -4.28 -CTUN, 191, 0.00, 17.28, 16.650986, 0, 0, -95, 277, -130 -ATT, 0.00, 0.45, 0.00, -4.15, 0.00, 83.16, 83.10 -GPS, 3, 594526000, 8, 2.26, 44.0290195, -77.7367039, 17.53, 101.90, 0.39, 162.35 -NTUN, 0.27, 1.71, -25.188202, 3.701721, -25.188202, 3.701721, -24.212435, 9.553790, 13.800720, 71.514038, -0.29, -4.23 -CTUN, 194, 0.00, 16.91, 16.650986, 0, 0, -95, 260, -130 -ATT, -1.99, 0.11, 1.54, -4.65, 0.00, 83.14, 83.10 -NTUN, 0.25, 1.72, -23.101379, 2.938843, -23.101379, 2.938843, -23.030058, 8.414274, 14.661608, 71.446747, -0.35, -4.23 -GPS, 3, 594526200, 8, 2.26, 44.0290188, -77.7367036, 17.27, 101.69, 0.42, 162.78 -NTUN, 0.25, 1.72, -20.903503, 2.185120, -20.903503, 2.185120, -22.645512, 8.249600, 16.978760, 70.462769, -0.49, -4.19 -CTUN, 191, 0.00, 16.90, 16.339056, 0, 0, -94, 262, -129 -ATT, -3.64, -0.18, 4.52, -4.33, 0.00, 83.20, 83.10 -NTUN, 0.21, 1.74, -18.342499, 1.323608, -18.342499, 0.943453, -21.342350, 7.751147, 19.281860, 65.712120, -0.66, -3.93 -GPS, 3, 594526400, 8, 2.26, 44.0290182, -77.7367032, 17.11, 101.48, 0.44, 158.62 -ATT, -3.87, -0.27, 5.95, -4.32, 0.00, 83.23, 83.10 -CTUN, 191, 0.00, 16.67, 16.145613, 0, 0, -98, 252, -129 -NTUN, 0.18, 1.76, -16.028442, 0.388367, -16.028442, -0.948374, -20.099636, 7.049686, 20.911449, 57.269035, -0.81, -3.46 -CTUN, 191, 0.00, 16.50, 15.886445, 0, 0, -102, 267, -130 -NTUN, 0.16, 1.80, -13.726471, -0.700928, -13.726471, -3.362844, -18.524250, 6.298442, 21.252237, 49.611420, -0.88, -3.02 -ATT, -4.46, -0.58, 6.66, -4.09, 0.00, 83.27, 83.10 -GPS, 3, 594526600, 8, 2.26, 44.0290175, -77.7367027, 16.88, 101.28, 0.44, 158.16 -NTUN, 0.13, 1.86, -11.416199, -2.012085, -11.416199, -6.232275, -17.037632, 5.129164, 21.873981, 42.589790, -0.97, -2.61 -CTUN, 194, 0.00, 16.48, 15.655657, 0, 0, -105, 266, -128 -ATT, -5.28, -0.70, 7.38, -3.18, 0.00, 83.29, 83.10 -NTUN, 0.11, 1.95, -9.029358, -3.443970, -9.029358, -9.391945, -15.536205, 3.664722, 24.868408, 36.403297, -1.19, -2.28 -GPS, 3, 594526800, 8, 2.26, 44.0290168, -77.7367022, 16.58, 101.05, 0.44, 156.15 -NTUN, 0.11, 1.95, -6.666595, -5.000305, -6.456655, -12.848326, -13.462120, 1.120645, 27.986902, 33.087063, -1.39, -2.11 -CTUN, 194, 0.00, 16.51, 15.551487, 0, 0, -105, 259, -129 -ATT, -5.99, -1.17, 7.85, -2.97, 0.00, 83.30, 83.10 -NTUN, 0.08, 2.19, -4.299500, -6.638000, -3.876449, -16.394724, -11.753304, -1.422336, 27.296137, 31.231388, -1.36, -1.99 -GPS, 3, 594527000, 8, 2.26, 44.0290163, -77.7367019, 16.41, 100.82, 0.36, 154.88 -NTUN, 0.07, 2.51, -2.104736, -8.180725, -1.672493, -19.729469, -9.866274, -4.445631, 26.262180, 30.315704, -1.31, -1.93 -CTUN, 194, 0.00, 16.34, 15.347168, 0, 0, -108, 259, -128 -ATT, -5.52, -1.00, 7.73, -2.33, 0.00, 83.29, 83.10 -NTUN, 0.07, 2.51, -0.067261, -9.653137, 0.287873, -22.862110, -7.631629, -7.019648, 22.603661, 32.673592, -1.08, -2.04 -GPS, 3, 594527200, 8, 2.26, 44.0290159, -77.7367015, 16.25, 100.60, 0.36, 154.88 -NTUN, 0.09, 2.79, 1.767700, -11.157898, 1.963958, -25.893032, -6.626789, -10.772139, 21.594893, 32.990875, -1.02, -2.05 -ATT, -5.16, -1.05, 7.14, -2.22, 0.00, 83.35, 83.10 -CTUN, 194, 0.00, 16.13, 14.975456, 0, 0, -116, 256, -128 -NTUN, 0.09, 2.79, 3.453827, -12.519043, 3.453827, -28.264385, -4.466998, -13.471265, 18.898693, 39.286469, -0.82, -2.40 -GPS, 3, 594527400, 8, 2.26, 44.0290155, -77.7367012, 15.96, 100.37, 0.26, 153.80 -ATT, -2.70, -0.87, 5.83, -2.49, 0.00, 83.37, 83.10 -NTUN, 0.09, 2.79, 5.026398, -13.722900, 5.026398, -29.886896, -3.660363, -17.001663, 20.884554, 47.611000, -0.88, -2.90 -NTUN, 0.14, 2.93, 6.513855, -14.798035, 6.513855, -30.808498, -2.057802, -19.053970, 20.727299, 55.875225, -0.82, -3.37 -GPS, 3, 594527600, 8, 2.26, 44.0290153, -77.7367009, 15.74, 100.12, 0.17, 150.74 -ATT, -1.05, -0.78, 4.28, -2.79, 0.00, 83.29, 83.10 -NTUN, 0.16, 2.97, 7.827209, -15.785034, 7.827209, -31.225281, -1.009068, -21.309607, 19.133545, 61.832176, -0.68, -3.71 -CTUN, 195, 0.00, 15.59, 14.462577, 0, 0, -121, 263, -128 -ATT, -0.82, -0.99, 3.92, -2.94, 0.00, 83.27, 83.10 -NTUN, 0.17, 2.99, 8.971039, -16.652405, 8.971039, -31.329704, -0.217032, -22.939009, 19.438293, 65.955765, -0.67, -3.95 -GPS, 3, 594527800, 8, 2.26, 44.0290151, -77.7367007, 15.44, 99.86, 0.15, 149.68 -NTUN, 0.17, 2.99, 9.991486, -17.467285, 9.991486, -31.301840, 1.165375, -23.300810, 17.204468, 67.278641, -0.53, -4.01 -CTUN, 193, 0.00, 14.96, 14.269168, 0, 0, -121, 276, -128 -ATT, -0.82, -0.62, 3.69, -3.61, 0.00, 83.22, 83.10 -NTUN, 0.20, 3.00, 10.892426, -18.300537, 10.892426, -31.420002, 1.932494, -24.027554, 16.009399, 65.818375, -0.47, -3.92 -GPS, 3, 594528000, 8, 2.26, 44.0290150, -77.7367005, 15.25, 99.60, 0.14, 149.68 -NTUN, 0.21, 3.01, 11.661682, -19.127136, 11.661682, -31.341951, 2.748880, -23.682123, 15.692566, 67.780502, -0.43, -4.03 -ATT, -0.58, -0.40, 3.45, -3.95, 0.00, 83.17, 83.10 -CTUN, 183, 0.00, 14.61, 14.073771, 0, 0, -125, 267, -133 -NTUN, 0.22, 3.02, 12.295502, -20.063843, 12.295502, -30.957851, 3.242983, -23.539745, 15.275441, 70.802971, -0.39, -4.20 -GPS, 3, 594528200, 8, 2.26, 44.0290150, -77.7367004, 14.97, 99.31, 0.14, 149.68 -ATT, 0.00, -0.64, 2.85, -3.36, 0.00, 83.17, 83.10 -CTUN, 178, 0.00, 14.36, 13.803241, 0, 0, -124, 263, -135 -NTUN, 0.23, 3.02, 12.779388, -20.881836, 12.779388, -29.983320, 3.952775, -23.676136, 12.790957, 76.648819, -0.20, -4.52 -CTUN, 177, 0.00, 14.29, 13.569279, 0, 0, -124, 270, -139 -ATT, 0.00, -0.78, 1.78, -3.46, 0.00, 83.19, 83.10 -NTUN, 0.23, 3.02, 13.125397, -21.637939, 13.125397, -28.945175, 4.260467, -22.924782, 11.530697, 77.593315, -0.12, -4.57 -GPS, 3, 594528400, 8, 2.26, 44.0290152, -77.7367004, 14.67, 99.07, 0.07, 149.68 -NTUN, 0.25, 3.01, 13.226929, -22.229065, 13.226929, -27.335260, 5.601919, -21.937605, 8.005267, 83.939751, 0.11, -4.91 -CTUN, 173, 0.00, 14.00, 13.315204, 0, 0, -124, 251, -141 -ATT, 0.00, -0.21, 0.95, -4.97, 0.00, 83.19, 83.10 -NTUN, 0.25, 3.00, 13.055908, -22.726379, 13.055908, -25.508907, 5.410999, -20.914902, 6.289795, 87.263535, 0.23, -5.09 -GPS, 3, 594528600, 8, 2.26, 44.0290152, -77.7367003, 14.39, 98.81, 0.04, 149.68 -CTUN, 167, 0.00, 13.69, 13.230608, 0, 0, -123, 279, -143 -NTUN, 0.25, 3.00, 12.887390, -22.936340, 12.887390, -23.130636, 5.865898, -18.801027, 6.331504, 91.547241, 0.25, -5.33 -ATT, 0.00, -0.11, 0.00, -4.54, 0.00, 83.26, 83.10 -NTUN, 0.26, 2.99, 12.630524, -23.355408, 12.630524, -23.355408, 6.239977, -17.014587, 4.431335, 63.752285, 0.17, -3.72 -CTUN, 159, 0.00, 13.56, 12.966876, 0, 0, -124, 265, -148 -GPS, 3, 594528800, 8, 2.26, 44.0290152, -77.7367002, 14.13, 98.53, 0.09, 149.68 -ATT, 0.00, 0.09, 0.11, -4.40, 0.00, 83.31, 83.10 -NTUN, 0.26, 2.97, 12.459381, -24.008240, 12.459381, -24.008240, 6.030226, -16.529181, 6.271287, 58.405739, 0.03, -3.42 -CTUN, 153, 0.00, 13.36, 12.752306, 0, 0, -127, 256, -153 -ATT, 0.00, -0.06, 0.00, -3.95, 0.00, 83.19, 83.10 -NTUN, 0.27, 2.96, 12.283447, -24.957092, 12.283447, -24.957092, 6.446321, -14.358841, 5.258081, 51.605423, 0.05, -3.02 -GPS, 3, 594529000, 8, 2.26, 44.0290153, -77.7367000, 13.81, 98.27, 0.09, 149.68 -CTUN, 153, 0.00, 13.24, 12.504939, 0, 0, -127, 282, -155 -NTUN, 0.27, 2.96, 12.053680, -25.998779, 12.053680, -25.998779, 6.459114, -14.281347, 4.725080, 49.686268, 0.07, -2.91 -ATT, 0.00, 0.00, 0.00, -3.63, 0.00, 83.13, 83.10 -NTUN, 0.28, 2.94, 11.787506, -27.090942, 11.787506, -27.090942, 6.209579, -13.369525, 4.311371, 45.968048, 0.06, -2.69 -GPS, 3, 594529200, 8, 2.26, 44.0290153, -77.7366999, 13.55, 98.00, 0.06, 149.68 -CTUN, 152, 0.00, 13.06, 12.351960, 0, 0, -126, 271, -155 -ATT, 0.00, 0.40, 0.00, -3.44, 0.00, 83.24, 83.10 -NTUN, 0.29, 2.93, 11.608124, -28.112122, 11.608124, -28.112122, 5.845966, -13.484419, 6.223938, 44.889317, -0.05, -2.64 -CTUN, 152, 0.00, 12.90, 12.072197, 0, 0, -126, 248, -155 -ATT, 0.00, 0.01, 0.00, -3.01, 0.00, 83.29, 83.10 -NTUN, 0.30, 2.91, 11.469147, -29.036499, 11.469147, -29.036499, 5.427358, -14.448601, 7.596191, 45.662853, -0.12, -2.69 -GPS, 3, 594529400, 8, 2.26, 44.0290153, -77.7366998, 13.19, 97.73, 0.05, 149.68 -CTUN, 152, 0.00, 12.79, 11.963046, 0, 0, -127, 276, -155 -NTUN, 0.30, 2.91, 11.424438, -29.809875, 11.424438, -29.809875, 4.734239, -15.357220, 8.557344, 46.342808, -0.18, -2.74 -ATT, 0.00, -0.11, 0.00, -2.64, 0.00, 83.29, 83.10 -NTUN, 0.31, 2.90, 11.446899, -30.373901, 11.446899, -30.373901, 4.489709, -16.534981, 10.224609, 48.359741, -0.26, -2.87 -CTUN, 153, 0.00, 12.74, 11.745964, 0, 0, -128, 254, -155 -GPS, 3, 594529600, 8, 2.26, 44.0290153, -77.7366996, 13.00, 97.45, 0.09, 149.68 -ATT, 0.00, 0.12, 0.00, -2.31, 0.00, 83.17, 83.10 -NTUN, 0.32, 2.90, 11.490936, -30.820129, 11.490936, -30.820129, 3.904852, -18.300228, 11.440369, 50.537720, -0.31, -3.00 -CTUN, 152, 0.00, 12.48, 11.465426, 0, 0, -132, 263, -155 -ATT, 0.00, -0.25, 0.00, -2.72, 0.00, 83.13, 83.10 -NTUN, 0.32, 2.90, 11.551300, -31.210266, 11.551300, -31.210266, 3.650614, -18.788343, 11.603638, 50.098633, -0.32, -2.98 -GPS, 3, 594529800, 8, 2.26, 44.0290153, -77.7366995, 12.62, 97.18, 0.05, 149.68 -CTUN, 152, 0.00, 12.12, 11.276896, 0, 0, -134, 262, -155 -NTUN, 0.32, 2.90, 11.725616, -31.412109, 11.725616, -31.412109, 3.073101, -21.352835, 14.725904, 54.001553, -0.46, -3.23 -ATT, 0.00, 0.29, 0.00, -2.19, 0.00, 82.86, 83.10 -NTUN, 0.33, 2.90, 11.937714, -31.471130, 11.937714, -31.471130, 2.049571, -21.460638, 16.120972, 54.409790, -0.53, -3.26 -CTUN, 153, 0.00, 11.99, 11.125392, 0, 0, -135, 262, -155 -GPS, 3, 594530000, 8, 2.26, 44.0290154, -77.7366995, 12.43, 96.88, 0.03, 149.68 -ATT, 0.00, 0.04, 0.00, -2.78, 0.00, 82.82, 83.10 -NTUN, 0.33, 2.91, 12.243317, -31.379517, 12.243317, -31.379517, -0.067396, -23.668592, 21.086899, 58.925392, -0.78, -3.56 -CTUN, 152, 0.00, 11.68, 10.845295, 0, 0, -136, 268, -155 -ATT, 0.00, -0.06, 0.00, -3.12, 0.00, 82.74, 83.10 -NTUN, 0.33, 2.91, 12.574005, -31.163452, 12.574005, -31.163452, -0.431915, -23.425413, 22.274143, 59.139252, -0.85, -3.58 -GPS, 3, 594530200, 8, 2.26, 44.0290155, -77.7366996, 12.02, 96.61, 0.05, 149.68 -NTUN, 0.33, 2.92, 12.842224, -30.841980, 12.842224, -30.841980, -1.266653, -24.717035, 23.682190, 61.214722, -0.92, -3.71 -CTUN, 152, 0.00, 11.38, 10.705014, 0, 0, -136, 274, -155 -ATT, 0.00, -0.93, 0.00, -3.24, 0.00, 82.79, 83.10 -NTUN, 0.33, 2.93, 13.088074, -30.455383, 13.088074, -30.455383, -0.651439, -24.212105, 23.483330, 61.905018, -0.90, -3.75 -CTUN, 152, 0.00, 11.23, 10.504215, 0, 0, -137, 262, -155 -GPS, 3, 594530400, 8, 2.26, 44.0290156, -77.7367000, 11.82, 96.31, 0.05, 149.68 -ATT, 0.00, -0.74, 0.00, -3.46, 0.00, 82.68, 83.10 -NTUN, 0.33, 2.93, 13.166748, -29.637573, 13.166748, -29.637573, 0.173747, -25.073702, 20.778954, 68.097130, -0.69, -4.09 -CTUN, 152, 0.00, 10.88, 10.303885, 0, 0, -137, 255, -154 -ATT, 0.00, -0.90, 0.00, -3.89, 0.00, 82.68, 83.10 -NTUN, 0.32, 2.94, 13.096924, -28.661682, 13.096924, -28.661682, 0.619174, -24.062599, 20.308672, 68.662285, -0.66, -4.12 -GPS, 3, 594530600, 8, 2.26, 44.0290156, -77.7367002, 11.45, 96.00, 0.15, 149.68 -CTUN, 152, 0.00, 10.69, 10.147769, 0, 0, -137, 282, -155 -NTUN, 0.31, 2.94, 12.873169, -27.813354, 12.873169, -27.813354, 2.954730, -22.875620, 15.739849, 67.568970, -0.41, -4.02 -ATT, 0.00, -1.11, 0.00, -4.82, 0.00, 82.78, 83.10 -CTUN, 152, 0.00, 10.22, 9.929703, 0, 0, -136, 270, -155 -NTUN, 0.30, 2.94, 12.482025, -27.169922, 12.482025, -27.169922, 3.526880, -21.110765, 14.127289, 63.370621, -0.36, -3.77 -ATT, 0.00, -0.43, 0.00, -5.07, 0.00, 82.90, 83.10 -GPS, 3, 594530800, 8, 2.26, 44.0290158, -77.7367005, 11.05, 95.72, 0.11, 149.68 -CTUN, 152, 0.00, 10.15, 9.774666, 0, 0, -135, 278, -155 -NTUN, 0.30, 2.94, 11.906128, -26.877380, 11.906128, -26.877380, 4.933895, -18.192234, 10.241028, 56.925415, -0.17, -3.37 -ATT, 0.00, 0.33, 0.00, -4.44, 0.00, 82.66, 83.10 -CTUN, 151, 0.00, 10.17, 9.605405, 0, 0, -132, 263, -155 -NTUN, 0.29, 2.93, 11.032074, -26.945984, 11.032074, -26.945984, 4.832975, -15.668679, 8.054054, 50.376331, -0.09, -2.97 -GPS, 3, 594531000, 8, 2.26, 44.0290158, -77.7367007, 10.81, 95.45, 0.11, 149.68 -CTUN, 149, 0.00, 10.06, 9.401373, 0, 0, -129, 266, -156 -NTUN, 0.29, 2.91, 10.415253, -26.973145, 10.415253, -26.973145, 3.566911, -13.615045, 10.892859, 47.731083, -0.27, -2.84 -ATT, 0.00, -0.26, 0.00, -3.58, 0.00, 82.69, 83.10 -NTUN, 0.28, 2.90, 9.866333, -27.082153, 9.866333, -27.082153, 3.334191, -12.809233, 11.964039, 44.999920, -0.35, -2.69 -GPS, 3, 594531200, 8, 2.26, 44.0290159, -77.7367008, 10.55, 95.18, 0.09, 149.68 -CTUN, 141, 0.00, 10.13, 9.275442, 0, 0, -128, 265, -160 -ATT, 0.00, -0.26, 0.00, -3.06, 0.00, 82.62, 83.10 -NTUN, 0.28, 2.89, 9.437195, -27.191223, 9.437195, -27.191223, 2.378389, -12.578546, 13.708618, 44.909302, -0.45, -2.70 -CTUN, 133, 0.00, 9.86, 9.014599, 0, 0, -129, 263, -164 -ATT, 0.00, -0.57, 0.00, -3.05, 0.00, 82.69, 83.10 -NTUN, 0.28, 2.88, 9.099304, -27.326843, 9.099304, -27.326843, 1.502735, -12.498714, 15.654549, 43.657227, -0.58, -2.64 -GPS, 3, 594531400, 8, 2.26, 44.0290159, -77.7367010, 10.18, 94.90, 0.07, 149.68 -CTUN, 131, 0.00, 9.67, 8.864688, 0, 0, -130, 262, -166 -NTUN, 0.28, 2.88, 9.008667, -27.304810, 9.008667, -27.304810, 0.608635, -14.082976, 19.093628, 45.220337, -0.77, -2.75 -ATT, 0.00, -0.18, 0.00, -2.25, 0.00, 82.74, 83.10 -CTUN, 0, 0.00, 9.65, 8.595818, 0, 0, -135, 233, -250 -GPS, 3, 594531600, 8, 2.26, 44.0290160, -77.7367011, 9.92, 94.65, 0.07, 149.68 -NTUN, 0.28, 2.88, 8.967590, -27.072021, 8.967590, -27.072021, -1.727190, -15.180876, 22.686438, 48.777008, -0.96, -2.98 -CTUN, 0, 0.00, 9.48, 8.496497, 0, 0, -136, 241, -250 -DU32, 7, 426225 -CURR, 0, 229833, 1413, 1223, 4984, 365.249760 -ATT, 0.00, -0.09, 0.00, -2.31, 0.00, 82.83, 83.10 -NTUN, 0.28, 2.88, 9.035339, -26.558289, 9.035339, -26.558289, -1.695441, -17.144203, 23.684334, 53.189220, -0.97, -3.25 -CTUN, 0, 0.00, 9.27, 8.041906, 0, 0, -158, 241, -250 -GPS, 3, 594531800, 8, 2.26, 44.0290160, -77.7367014, 9.55, 94.36, 0.06, 149.68 -NTUN, 0.28, 2.88, 9.111053, -25.795959, 9.111053, -25.795959, -2.127477, -18.462408, 25.757141, 57.623291, -1.06, -3.52 -ATT, 0.00, -1.26, 0.00, -2.16, 0.00, 82.80, 83.10 -CTUN, 0, 0.00, 9.02, 7.769476, 0, 0, -175, 248, -250 -NTUN, 0.27, 2.89, 9.285980, -24.788208, 9.285980, -24.788208, -2.465944, -19.135872, 26.731949, 61.977737, -1.09, -3.78 -ATT, 0.00, -1.00, 0.23, -3.30, 0.00, 82.84, 83.10 -GPS, 3, 594532000, 8, 2.26, 44.0290158, -77.7367017, 9.26, 94.03, 0.12, 149.68 -NTUN, 0.27, 2.89, 9.530457, -23.642395, 9.530457, -23.642395, -2.065629, -19.387688, 28.420557, 63.344681, -1.18, -3.87 -CTUN, 0, 0.00, 8.53, 7.541926, 0, 0, -186, 250, -250 -NTUN, 0.25, 2.93, 9.927948, -22.210083, 9.927948, -22.210083, -0.975097, -20.359032, 29.340263, 67.036232, -1.21, -4.09 -ATT, 0.00, -1.09, 0.47, -3.71, 0.00, 82.91, 83.10 -CTUN, 0, 0.00, 8.18, 7.142856, 0, 0, -193, 280, -250 -GPS, 3, 594532200, 8, 2.26, 44.0290158, -77.7367021, 8.93, 93.64, 0.16, 149.68 -NTUN, 0.25, 2.93, 10.153168, -20.971680, 10.153168, -20.971680, -0.375011, -18.625286, 28.252197, 66.384033, -1.15, -4.04 -CTUN, 0, 0.00, 8.00, 7.142856, 0, 0, -193, 242, -250 -ATT, 0.00, -1.20, 0.47, -3.99, 0.00, 82.78, 83.10 -NTUN, 0.23, 2.96, 10.210571, -19.667114, 10.210571, -19.667114, 0.443831, -20.765863, 26.574036, 70.045654, -1.02, -4.24 -GPS, 3, 594532400, 8, 2.26, 44.0290158, -77.7367026, 8.41, 93.23, 0.17, 149.68 -CTUN, 0, 0.00, 7.80, 6.542996, 0, 0, -195, 261, -250 -NTUN, 0.23, 2.96, 10.147400, -18.232605, 10.147400, -18.232605, 1.783662, -19.748823, 24.368286, 71.345093, -0.88, -4.30 -ATT, 0.00, -1.22, 0.47, -3.07, 0.00, 82.83, 83.10 -CTUN, 0, 0.00, 7.55, 6.067437, 0, 0, -196, 260, -250 -NTUN, 0.20, 2.99, 10.027252, -16.704956, 10.027252, -16.704956, 1.428203, -20.285858, 23.798523, 74.276489, -0.83, -4.46 -ATT, 0.00, -0.41, 0.35, -3.72, 0.00, 82.78, 83.10 -GPS, 3, 594532600, 8, 2.26, 44.0290158, -77.7367031, 7.92, 92.82, 0.23, 149.68 -NTUN, 0.19, 3.01, 9.772980, -15.060181, 9.772980, -15.060181, 3.543862, -21.055464, 21.482450, 78.284904, -0.67, -4.68 -CTUN, 0, 0.00, 7.28, 5.967047, 0, 0, -197, 273, -250 -ATT, 0.00, -1.53, 0.23, -2.81, 0.00, 82.97, 83.10 -NTUN, 0.17, 3.03, 9.502625, -13.263245, 9.502625, -13.263245, 2.995374, -21.041756, 21.296448, 81.969360, -0.64, -4.89 -GPS, 3, 594532800, 8, 2.26, 44.0290159, -77.7367034, 7.50, 92.42, 0.19, 149.68 -NTUN, 0.16, 3.07, 8.995514, -11.756897, 8.995514, -11.756897, 5.029696, -18.079544, 15.877670, 78.215637, -0.36, -4.63 -CTUN, 0, 0.00, 6.86, 5.488717, 0, 0, -205, 264, -250 -ATT, 0.00, -1.00, 0.00, -5.40, 0.00, 83.06, 83.10 -NTUN, 0.16, 3.07, 8.482178, -10.367676, 8.482178, -10.367676, 4.687744, -17.693447, 15.917463, 78.754662, -0.34, -4.67 -CTUN, 0, 0.00, 6.41, 4.987566, 0, 0, -207, 217, -250 -GPS, 3, 594533000, 8, 2.26, 44.0290157, -77.7367036, 7.06, 92.00, 0.14, 149.68 -ATT, 0.00, 0.33, 0.00, -4.81, 0.00, 82.68, 83.10 -NTUN, 0.13, 3.10, 7.970795, -9.387756, 7.970795, -9.387756, 7.423034, -14.469273, 12.886169, 72.799194, -0.20, -4.30 -CTUN, 0, 0.00, 6.13, 4.688806, 0, 0, -208, 251, -250 -ATT, 0.00, -1.73, 0.00, -3.63, 0.00, 83.02, 83.10 -NTUN, 0.12, 3.11, 7.574371, -8.582886, 7.574371, -8.582886, 5.969403, -14.292980, 15.035767, 71.048706, -0.37, -4.21 -GPS, 3, 594533200, 8, 2.26, 44.0290158, -77.7367041, 6.65, 91.58, 0.11, 149.68 -CTUN, 0, 0.00, 6.17, 4.539646, 0, 0, -214, 235, -250 -ATT, 0.00, 0.03, 0.00, -4.39, 0.00, 83.08, 83.10 -NTUN, 0.11, 3.11, 7.229919, -8.084839, 7.229919, -8.084839, 8.683860, -9.858600, 13.589585, 63.931156, -0.33, -3.79 -CTUN, 0, 0.00, 5.68, 4.139056, 0, 0, -219, 255, -250 -ATT, 0.00, -1.18, 0.00, -4.31, 0.00, 83.57, 83.10 -NTUN, 0.10, 3.11, 6.538208, -7.517151, 6.538208, -7.517151, 6.899766, -9.008416, 11.013016, 64.734222, -0.22, -3.82 -GPS, 3, 594533400, 8, 2.26, 44.0290158, -77.7367042, 6.13, 91.13, 0.15, 149.68 -NTUN, 0.10, 3.11, 5.983276, -7.372314, 5.983276, -7.372314, 9.314101, -5.038880, 9.505628, 57.434025, -0.17, -3.39 -CTUN, 160, 0.00, 5.55, 3.817148, 0, 0, -223, 262, -155 -ATT, 0.00, -0.13, 0.00, -4.78, 0.00, 83.71, 83.10 -NTUN, 0.09, 3.07, 5.330261, -7.628540, 5.330261, -7.628540, 8.797270, -0.517222, 8.469849, 48.437744, -0.18, -2.86 -ATT, 0.00, 0.16, 0.00, -5.91, 0.00, 83.92, 83.10 -CTUN, 262, 0.00, 5.11, 3.677149, 0, 1, -226, 352, -86 -GPS, 3, 594533600, 8, 2.26, 44.0290157, -77.7367042, 5.58, 90.69, 0.04, 149.68 -NTUN, 0.09, 3.07, 4.989227, -8.638855, 4.989227, -8.638855, 7.887066, 9.470516, 12.589661, 28.896851, -0.54, -1.75 -CTUN, 357, 0.00, 4.75, 3.634397, 0, 3, -208, 385, -26 -ATT, 0.00, 1.64, 0.00, -9.25, 0.00, 83.50, 83.10 -NTUN, 0.09, 2.97, 4.969818, -10.803589, 4.969818, -10.803589, 7.991257, 18.556053, 14.807830, 5.566992, -0.81, -0.42 -GPS, 3, 594533800, 8, 2.26, 44.0290155, -77.7367040, 5.19, 90.22, 0.09, 149.68 -CTUN, 408, 0.00, 4.50, 3.624663, 0, 0, -190, 229, -8 -NTUN, 0.11, 2.91, 4.784149, -13.569824, 4.784149, -13.569824, 9.185229, 20.631901, 11.143311, -7.662354, -0.69, 0.37 -ATT, 0.00, -3.33, 0.00, -0.71, 0.00, 83.55, 83.10 -CTUN, 410, 0.00, 6.08, 3.624663, 0, 0, -120, 130, 0 -NTUN, 0.14, 2.87, 4.797577, -15.720703, 4.797577, -15.720703, 12.334013, 10.213062, 10.135633, 6.273951, -0.54, -0.43 -DU32, 7, 426225 -CURR, 410, 234246, 1370, 2024, 4984, 373.249850 -ATT, 0.00, -3.38, 0.00, 7.58, 0.00, 83.12, 83.10 -GPS, 3, 594534000, 8, 2.26, 44.0290151, -77.7367036, 4.84, 89.86, 0.09, 149.68 -NTUN, 0.14, 2.87, 4.825256, -16.818665, 4.825256, -16.818665, 8.991418, -0.354503, 13.274054, 25.129095, -0.59, -1.54 -CTUN, 408, 0.00, 4.69, 3.624663, 0, 0, -111, 270, 0 -ATT, 0.00, 2.16, 0.00, 3.48, 0.00, 83.21, 83.10 -NTUN, 0.17, 2.86, 5.275940, -17.187378, 5.275940, -17.187378, 11.378241, -2.808609, 15.506836, 33.312866, -0.65, -2.04 -GPS, 3, 594534200, 8, 2.26, 44.0290150, -77.7367033, 4.70, 89.59, 0.30, 140.14 -CTUN, 408, 0.00, 4.34, 3.624663, 0, 1, -116, 279, 0 -ATT, 0.00, -0.38, 0.00, -7.52, 0.00, 82.87, 83.10 -NTUN, 0.17, 2.87, 5.604919, -17.257874, 5.604919, -17.257874, 8.711912, -5.903410, 16.289795, 39.295044, -0.65, -2.39 -CTUN, 408, 0.00, 3.42, 3.624663, 0, 0, -93, 289, 0 -ATT, 0.00, -0.67, 0.00, -2.91, 0.00, 82.75, 83.10 -NTUN, 0.18, 2.90, 6.379181, -16.989868, 6.379181, -16.989868, 7.090493, -6.182792, 23.665955, 42.653519, -1.05, -2.64 -GPS, 3, 594534400, 8, 2.26, 44.0290148, -77.7367031, 4.46, 89.35, 0.07, 140.14 -NTUN, 0.18, 2.92, 7.041199, -17.175415, 7.041199, -17.175415, 8.599341, -0.663908, 21.687050, 31.125790, -1.02, -1.96 -CTUN, 409, 0.00, 4.44, 3.624663, 0, 0, -88, 282, 0 -ATT, 0.00, -1.21, 0.00, -1.68, 0.00, 82.95, 83.10 -NTUN, 0.18, 2.93, 7.881592, -17.552429, 7.881592, -17.552429, 8.085602, -3.486506, 24.403931, 31.229858, -1.19, -1.97 -CTUN, 408, 0.00, 4.04, 3.624663, 0, 0, -66, 223, 0 -ATT, 0.00, -0.18, 0.00, -2.18, 0.00, 83.33, 83.10 -GPS, 3, 594534600, 8, 2.26, 44.0290149, -77.7367032, 4.25, 89.20, 0.07, 140.14 -NTUN, 0.19, 2.95, 8.401550, -17.627502, 8.401550, -17.627502, 10.524741, -4.158237, 19.097633, 34.263988, -0.89, -2.11 -CTUN, 407, 0.00, 4.66, 3.624663, 0, 0, -69, 344, 0 -ATT, 0.00, -2.04, 0.00, -2.75, 0.00, 84.21, 83.10 -NTUN, 0.19, 2.95, 8.645538, -17.941467, 8.645538, -17.941467, 10.136940, -0.023440, 17.464525, 26.828638, -0.85, -1.65 -GPS, 3, 594534800, 8, 2.26, 44.0290147, -77.7367030, 4.15, 89.09, 0.11, 140.14 -NTUN, 0.19, 2.95, 8.968445, -18.352478, 8.968445, -18.352478, 11.522587, -2.130584, 17.229065, 25.889893, -0.86, -1.59 -CTUN, 408, 0.00, 4.19, 3.624663, 0, 0, -56, 298, 0 -ATT, 0.00, -0.05, 0.00, -2.43, 0.00, 84.80, 83.10 -NTUN, 0.20, 2.95, 9.056091, -18.903320, 9.056091, -18.903320, 13.992661, 1.093514, 12.876465, 20.491577, -0.64, -1.25 -CTUN, 408, 0.00, 5.95, 3.624663, 0, 0, -49, 252, 0 -ATT, 0.00, -1.96, 0.00, -1.56, 0.00, 85.05, 83.10 -GPS, 3, 594535000, 8, 2.26, 44.0290145, -77.7367027, 4.07, 88.95, 0.11, 140.14 -NTUN, 0.20, 2.95, 9.294922, -19.618103, 9.294922, -19.618103, 12.545381, -1.244459, 15.388306, 18.852173, -0.80, -1.17 -CTUN, 409, 0.00, 6.00, 3.624663, 0, 0, -48, 281, 0 -ATT, 0.00, -0.88, 2.14, -0.98, 0.00, 85.07, 83.10 -NTUN, 0.21, 2.94, 9.452393, -20.375061, 9.452393, -20.375061, 15.319150, 0.090187, 12.574707, 15.430420, -0.65, -0.96 -GPS, 3, 594535200, 8, 2.26, 44.0290147, -77.7367028, 4.11, 88.83, 0.15, 139.97 -NTUN, 0.21, 2.94, 9.489685, -20.913147, 9.489685, -20.913147, 13.361884, -2.252762, 12.369232, 18.672417, -0.63, -1.14 -CTUN, 408, 0.00, 5.82, 3.624663, 0, 0, -47, 264, 0 -ATT, 0.00, -0.13, 5.47, -0.69, 0.00, 85.28, 83.10 -NTUN, 0.22, 2.94, 9.250671, -21.213989, 9.250671, -21.734215, 16.526838, -2.490180, 5.609863, 13.789322, -0.26, -0.82 -GPS, 3, 594535400, 8, 2.26, 44.0290146, -77.7367025, 4.15, 88.72, 0.14, 139.97 -CTUN, 408, 0.00, 5.83, 3.624663, 0, 0, -51, 252, 0 -NTUN, 0.22, 2.94, 9.055511, -21.601257, 9.055511, -22.406136, 14.266391, -3.949039, 8.048401, 16.280792, -0.39, -0.98 -PM, 0, 0, 51, 188, 1013, 12992, 10, 0 -ATT, 3.53, -0.56, 4.88, -0.65, 0.00, 85.53, 83.10 -NTUN, 0.23, 2.92, 8.955353, -21.953796, 8.830591, -22.346169, 16.547379, -4.041611, 4.955270, 22.545155, -0.18, -1.33 -GPS, 3, 594535600, 8, 2.26, 44.0290149, -77.7367023, 4.17, 88.59, 0.20, 139.97 -ATT, 7.42, -0.90, 4.52, -1.84, 0.00, 85.73, 83.10 -CTUN, 410, 0.00, 5.53, 3.624663, 0, 0, -53, 272, 0 -NTUN, 0.23, 2.91, 8.396454, -22.322571, 6.298198, -22.424345, 14.631391, -3.693133, -19.323929, 20.218235, 1.21, -1.09 -CTUN, 408, 0.00, 5.52, 3.624663, 0, 0, -55, 278, 0 -NTUN, 0.23, 2.90, 7.380676, -22.783142, 1.681800, -23.567194, 15.174623, -3.686439, -45.706909, 7.684664, 2.69, -0.25 -GPS, 3, 594535800, 8, 2.26, 44.0290152, -77.7367020, 4.17, 88.47, 0.20, 139.97 -ATT, 11.30, -0.18, 8.21, -0.92, 0.00, 85.92, 83.10 -CTUN, 407, 0.00, 5.24, 3.624663, 0, 0, -57, 269, 0 -NTUN, 0.23, 2.86, 5.823090, -23.596069, -4.110680, -26.082094, 12.590988, -3.421020, -60.924801, -10.149002, 3.50, 0.84 -ATT, 13.07, 1.80, 10.35, -0.54, 0.00, 85.97, 83.10 -CTUN, 409, 0.00, 4.54, 3.624663, 0, 0, -56, 279, 0 -NTUN, 0.24, 2.82, 4.030853, -24.749084, -10.597647, -29.841188, 9.616211, -3.525740, -72.869667, -28.590942, 4.12, 1.96 -GPS, 3, 594536000, 8, 2.26, 44.0290153, -77.7367019, 4.15, 88.31, 0.10, 139.97 -NTUN, 0.24, 2.82, 1.887482, -26.244690, -17.669342, -34.124767, 4.981603, -4.156044, -76.288139, -33.941628, 4.29, 2.29 -CTUN, 408, 0.00, 3.53, 3.624663, 0, 0, -56, 270, 0 -ATT, 8.83, 3.22, 8.92, 0.13, 0.00, 85.91, 83.10 -NTUN, 0.26, 2.74, 0.494965, -27.515381, -20.096914, -36.152359, -1.157485, -5.756174, -33.275723, -18.275917, 1.86, 1.20 -GPS, 3, 594536200, 8, 2.26, 44.0290155, -77.7367019, 4.04, 88.18, 0.10, 139.97 -CTUN, 409, 0.00, 3.42, 3.624663, 0, 0, -55, 303, 0 -NTUN, 0.26, 2.74, -0.278809, -28.398071, -18.012196, -36.085361, -5.928309, -7.940595, 17.640778, 3.663342, -1.01, -0.29 -ATT, 0.00, 1.89, 3.33, 1.15, 0.00, 85.61, 83.10 -NTUN, 0.28, 2.70, -0.286560, -28.856995, -15.120945, -33.871323, -10.726332, -8.132366, 33.912506, 27.140388, -1.84, -1.73 -CTUN, 412, 0.00, 3.70, 3.624663, 0, 0, -48, 294, 0 -GPS, 3, 594536400, 8, 2.26, 44.0290156, -77.7367020, 3.90, 88.01, 0.08, 139.97 -ATT, 0.00, 0.38, 0.00, -1.37, 0.00, 85.32, 83.10 -NTUN, 0.28, 2.72, 0.198395, -28.868408, -11.830555, -31.296041, -14.004481, -10.425566, 44.236263, 35.012939, -2.40, -2.24 -CTUN, 483, 0.00, 5.21, 3.624663, 0, 0, -25, 227, 0 -ATT, 0.00, 0.26, 0.00, 0.01, 0.00, 85.23, 83.10 -NTUN, 0.28, 2.73, 1.072479, -28.364014, -8.158113, -28.364014, -13.796329, -11.799843, 50.360806, 41.029976, -2.73, -2.63 -GPS, 3, 594536600, 8, 2.26, 44.0290158, -77.7367021, 3.82, 87.93, 0.08, 139.97 -CTUN, 561, 0.00, 4.07, 3.624663, 0, 0, -24, 336, 0 -NTUN, 0.28, 2.74, 1.633362, -27.836670, -4.889543, -27.836670, -11.974592, -9.459455, 48.685707, 14.273438, -2.76, -1.06 -ATT, 0.00, -2.05, 0.00, -1.32, 0.00, 85.18, 83.10 -CTUN, 636, 0.00, 4.96, 3.625654, 0, 0, -24, 214, 5 -NTUN, 0.28, 2.74, 2.194489, -27.537659, -1.681651, -27.537659, -10.419547, -9.186655, 50.078918, 10.990112, -2.85, -0.87 -GPS, 3, 594536800, 8, 2.26, 44.0290156, -77.7367027, 3.83, 87.84, 0.24, 71.49 -CTUN, 782, 0.00, 4.35, 3.632165, 0, 0, -21, 289, 22 -ATT, 0.00, -1.23, 0.00, -2.45, 0.00, 85.25, 83.10 -NTUN, 0.27, 2.75, 2.720642, -26.851990, 1.431716, -26.851990, -5.478711, -10.292336, 47.133667, 15.856689, -2.66, -1.15 -CTUN, 890, 0.00, 4.67, 3.875132, 0, 0, -26, 334, 165 -NTUN, 0.26, 2.75, 2.765198, -26.043213, 2.765198, -26.043213, -0.433768, -6.265843, 25.122562, 12.352517, -1.40, -0.84 -GPS, 3, 594537000, 8, 2.26, 44.0290154, -77.7367031, 3.84, 87.77, 0.24, 71.49 -ATT, 0.00, -3.14, 0.00, -2.09, 0.00, 85.07, 83.10 -CTUN, 974, 0.00, 3.67, 3.935570, 0, 0, -24, 320, 202 -NTUN, 0.26, 2.75, 2.418152, -25.325378, 2.418152, -25.325378, 5.150494, -7.649846, 4.563902, 13.107271, -0.19, -0.78 -ATT, 0.00, -2.13, 0.00, -2.07, 0.00, 84.75, 83.10 -CTUN, 997, 0.00, 3.91, 4.391222, 0, 0, 19, 426, 248 -NTUN, 0.25, 2.74, 1.201172, -24.466614, 1.201172, -24.466614, 12.456189, -4.131463, -12.164954, 9.878574, 0.75, -0.51 -GPS, 3, 594537200, 8, 2.26, 44.0290156, -77.7367033, 3.86, 87.71, 0.16, 71.49 -CTUN, 997, 0.00, 3.52, 4.664129, 0, 0, 76, 321, 248 -NTUN, 0.24, 2.68, -0.653778, -24.001404, -0.653778, -24.001404, 15.561603, -6.178999, -25.365841, 8.606039, 1.52, -0.35 -ATT, 0.00, -0.16, 0.00, -2.34, 0.00, 84.40, 83.10 -CTUN, 998, 0.00, 4.14, 4.837818, 0, 0, 99, 295, 248 -NTUN, 0.24, 2.68, -2.761047, -23.376892, -2.761047, -23.376892, 16.891056, -4.391758, -32.072693, 8.245117, 1.91, -0.27 -GPS, 3, 594537400, 8, 2.26, 44.0290157, -77.7367034, 3.96, 87.74, 0.14, 71.49 -ATT, 0.00, 0.83, 0.00, 0.39, 0.00, 83.48, 83.10 -CTUN, 997, 0.00, 4.64, 5.185029, 0, 0, 145, 237, 248 -NTUN, 0.23, 2.60, -4.680786, -22.665283, -4.680786, -22.665283, 15.289298, -10.452983, -31.197388, 15.116089, 1.91, -0.66 -ATT, 0.00, 0.20, 0.00, 2.74, 0.00, 83.16, 83.10 -CTUN, 998, 0.00, 4.55, 5.407980, 0, 0, 150, 241, 248 -NTUN, 0.23, 2.54, -6.488617, -21.349365, -6.488617, -21.349365, 15.422388, -16.663403, -32.899315, 29.028891, 2.10, -1.45 -GPS, 3, 594537600, 8, 2.26, 44.0290160, -77.7367031, 4.29, 87.96, 0.29, 51.87 -CTUN, 998, 0.00, 3.08, 5.707247, 0, 0, 133, 338, 248 -NTUN, 0.23, 2.54, -8.198090, -19.947571, -8.198090, -19.947571, 13.569041, -17.127804, -33.267403, 32.159538, 2.14, -1.63 -ATT, 0.00, 0.63, 0.00, 0.25, 0.00, 83.24, 83.10 -NTUN, 0.21, 2.46, -9.767883, -18.468628, -9.767883, -18.468628, 12.710349, -21.549721, -33.697937, 37.789429, 2.21, -1.95 -GPS, 3, 594537800, 8, 2.26, 44.0290165, -77.7367037, 4.53, 88.14, 0.29, 51.87 -CTUN, 998, 0.00, 4.16, 5.880629, 0, 0, 133, 284, 248 -ATT, 0.00, 3.39, 0.00, -3.09, 0.00, 82.88, 83.10 -NTUN, 0.20, 2.37, -11.294800, -16.352478, -11.294800, -16.352478, 9.087812, -21.718174, -32.117985, 45.951981, 2.19, -2.42 -CTUN, 998, 0.00, 3.80, 6.377968, 0, 0, 147, 323, 248 -NTUN, 0.19, 2.30, -12.514221, -14.268066, -12.514221, -14.268066, 5.881988, -21.012257, -28.194214, 46.844116, 1.96, -2.51 -GPS, 3, 594538000, 8, 2.26, 44.0290169, -77.7367040, 4.77, 88.35, 0.41, 348.47 -ATT, 0.00, 2.01, 0.00, -1.01, 0.00, 83.05, 83.10 -CTUN, 998, 0.00, 4.52, 6.626305, 0, 0, 152, 330, 248 -NTUN, 0.19, 2.30, -13.581482, -12.559448, -13.581482, -12.559448, 3.698432, -17.512955, -26.780411, 41.258770, 1.83, -2.20 -ATT, 0.00, 0.73, 0.00, -3.44, 0.00, 83.18, 83.10 -CTUN, 998, 0.00, 4.22, 6.874632, 0, 0, 172, 331, 248 -GPS, 3, 594538200, 8, 2.26, 44.0290171, -77.7367042, 5.04, 88.65, 0.29, 331.95 -NTUN, 0.18, 2.21, -14.560120, -10.417358, -14.560120, -10.417358, 0.331049, -16.655573, -20.891815, 42.085140, 1.50, -2.29 -CTUN, 998, 0.00, 4.22, 7.125806, 0, 0, 192, 322, 248 -ATT, 0.00, 2.09, 0.00, -2.41, 0.00, 83.02, 83.10 -NTUN, 0.17, 2.14, -14.969635, -9.351440, -14.969635, -9.351440, -2.520111, -15.044822, -16.095154, 36.659180, 1.19, -2.01 -CTUN, 998, 0.00, 4.60, 7.296569, 0, 0, 203, 295, 248 -GPS, 3, 594538400, 8, 2.26, 44.0290174, -77.7367046, 5.42, 88.97, 0.29, 331.95 -ATT, 0.00, 2.11, 0.00, -2.06, 0.00, 82.82, 83.10 -NTUN, 0.17, 2.11, -15.166382, -8.406250, -15.166382, -8.406250, -4.873636, -13.611655, -11.967468, 35.451904, 0.95, -1.96 -CTUN, 998, 0.00, 4.94, 7.744071, 0, 0, 227, 311, 248 -NTUN, 0.17, 2.08, -15.231323, -7.470215, -15.231323, -7.470215, -7.995880, -13.014085, -8.649414, 36.360352, 0.77, -2.04 -ATT, 0.00, 1.77, 0.00, -1.81, 0.00, 82.60, 83.10 -GPS, 3, 594538600, 8, 2.26, 44.0290174, -77.7367049, 5.75, 89.35, 0.27, 326.93 -NTUN, 0.17, 2.08, -14.961700, -6.562500, -14.961700, -6.562500, -10.940986, -13.899094, -2.303772, 38.077148, 0.41, -2.18 -CTUN, 998, 0.00, 5.33, 7.918365, 0, 0, 235, 327, 248 -ATT, 0.00, 1.90, 0.00, -1.37, 0.00, 82.69, 83.10 -NTUN, 0.16, 2.03, -14.407623, -5.573181, -14.407623, -5.573181, -11.841957, -12.950490, 2.596739, 38.993118, 0.13, -2.27 -GPS, 3, 594538800, 8, 2.26, 44.0290176, -77.7367053, 6.15, 89.86, 0.14, 326.93 -ATT, 0.00, 0.12, 0.00, -2.35, 0.00, 82.74, 83.10 -CTUN, 998, 0.00, 5.78, 8.391579, 0, 0, 234, 300, 248 -NTUN, 0.15, 2.00, -13.829224, -4.603455, -13.829224, -4.603455, -14.325343, -13.804881, 4.670585, 41.507122, 0.03, -2.43 -ATT, 0.00, 0.52, 0.00, -1.75, 0.00, 82.66, 83.10 -CTUN, 997, 0.00, 6.08, 8.762037, 0, 0, 230, 318, 247 -NTUN, 0.14, 1.96, -13.304443, -3.477783, -13.304443, -3.477783, -14.096318, -12.901963, 4.300811, 43.370419, 0.07, -2.54 -GPS, 3, 594539000, 8, 2.26, 44.0290174, -77.7367058, 6.56, 90.27, 0.23, 326.93 -NTUN, 0.13, 1.92, -12.776703, -2.417419, -12.776703, -2.417419, -13.908358, -12.400812, 5.277405, 43.603638, 0.02, -2.56 -CTUN, 998, 0.00, 6.30, 8.863568, 0, 0, 230, 297, 248 -ATT, 0.00, 0.20, 0.00, -2.63, 0.00, 82.62, 83.10 -NTUN, 0.13, 1.86, -12.113403, -1.195129, -12.113403, -1.195129, -13.342925, -12.601990, 6.567322, 47.101883, -0.02, -2.77 -CTUN, 998, 0.00, 6.64, 9.233912, 0, 0, 234, 299, 248 -ATT, 0.00, 0.17, 0.00, -2.11, 0.00, 82.58, 83.10 -GPS, 3, 594539200, 8, 2.26, 44.0290172, -77.7367062, 7.01, 90.72, 0.19, 326.93 -NTUN, 0.13, 1.86, -11.515259, 0.087280, -11.515259, 0.087280, -12.222870, -12.276841, 4.981445, 49.824097, 0.08, -2.92 -CTUN, 997, 0.00, 6.92, 9.383486, 0, 0, 233, 309, 248 -ATT, 0.00, 0.17, 0.00, -2.36, 0.00, 82.48, 83.10 -NTUN, 0.11, 1.77, -10.957581, 1.331177, -10.957581, 1.331177, -11.155467, -12.319818, 4.633113, 50.564613, 0.12, -2.96 -ATT, 0.00, 0.15, 0.00, -2.55, 0.00, 82.41, 83.10 -GPS, 3, 594539400, 8, 2.26, 44.0290172, -77.7367066, 7.52, 91.18, 0.17, 326.93 -NTUN, 0.11, 1.70, -10.568298, 2.709290, -10.568298, 2.709290, -9.424988, -12.573922, 1.816493, 54.510910, 0.31, -3.16 -CTUN, 998, 0.00, 7.23, 9.955711, 0, 0, 234, 316, 248 -NTUN, 0.10, 1.62, -10.482239, 3.992371, -10.482239, 3.992371, -7.940392, -11.472687, -2.130711, 54.960415, 0.54, -3.16 -ATT, 0.00, -0.10, 0.00, -3.18, 0.00, 82.50, 83.10 -CTUN, 998, 0.00, 7.20, 10.303169, 0, 0, 240, 306, 248 -GPS, 3, 594539600, 8, 2.26, 44.0290172, -77.7367071, 7.97, 91.64, 0.17, 326.93 -NTUN, 0.10, 1.62, -10.591827, 5.326111, -10.591827, 5.326111, -6.205369, -10.919539, -6.085036, 57.205349, 0.78, -3.26 -CTUN, 998, 0.00, 7.38, 10.451791, 0, 0, 242, 311, 248 -ATT, 0.00, 0.35, 0.00, -3.25, 0.00, 82.49, 83.10 -NTUN, 0.11, 1.51, -10.921265, 6.556396, -10.921265, 6.556396, -5.163648, -8.732000, -9.294373, 56.302856, 0.96, -3.18 -CTUN, 997, 0.00, 7.50, 10.798833, 0, 0, 249, 304, 248 -GPS, 3, 594539800, 8, 2.26, 44.0290172, -77.7367076, 8.41, 92.08, 0.16, 326.93 -NTUN, 0.12, 1.47, -11.344818, 7.828918, -11.344818, 7.828918, -4.030369, -7.669691, -12.885812, 55.674515, 1.17, -3.12 -ATT, 0.00, 1.09, 0.00, -2.79, 0.00, 82.39, 83.10 -CTUN, 998, 0.00, 7.83, 10.949806, 0, 0, 252, 305, 248 -NTUN, 0.13, 1.44, -11.788239, 8.866577, -11.788239, 8.866577, -4.163734, -5.773709, -13.390301, 54.273849, 1.18, -3.03 -CTUN, 998, 0.00, 8.11, 11.295676, 0, 0, 257, 309, 248 -ATT, 0.00, 0.73, 0.00, -3.03, 0.00, 82.46, 83.10 -GPS, 3, 594540000, 8, 2.26, 44.0290173, -77.7367079, 8.86, 92.56, 0.16, 326.93 -NTUN, 0.14, 1.42, -12.231476, 9.890869, -12.231476, 9.890869, -5.252106, -4.669382, -12.066397, 54.397175, 1.11, -3.05 -CTUN, 998, 0.00, 8.33, 11.444416, 0, 0, 259, 309, 248 -ATT, 0.00, 1.24, 0.00, -2.53, 0.00, 82.43, 83.10 -NTUN, 0.15, 1.40, -12.649078, 10.707458, -12.649078, 10.707458, -4.642654, -3.778900, -15.094143, 54.005779, 1.28, -3.00 -GPS, 3, 594540200, 8, 2.26, 44.0290174, -77.7367082, 9.21, 93.06, 0.09, 326.93 -CTUN, 998, 0.00, 8.85, 11.816942, 0, 0, 260, 300, 248 -NTUN, 0.16, 1.39, -13.117859, 11.463013, -13.117859, 11.463013, -4.417243, -3.377520, -15.687805, 53.555542, 1.31, -2.97 -ATT, 0.00, 0.47, 0.00, -3.17, 0.00, 82.49, 83.10 -CTUN, 998, 0.00, 9.34, 12.314253, 0, 0, 262, 291, 248 -NTUN, 0.17, 1.38, -13.622314, 12.272339, -13.622314, 12.272339, -3.611050, -3.778551, -19.095510, 57.175011, 1.54, -3.16 -ATT, 0.00, 0.84, 0.00, -2.61, 0.00, 82.47, 83.10 -GPS, 3, 594540400, 8, 2.26, 44.0290173, -77.7367084, 9.86, 93.57, 0.06, 326.93 -NTUN, 0.17, 1.38, -14.114136, 13.052917, -14.114136, 13.052917, -3.420176, -3.524214, -18.869518, 57.728500, 1.52, -3.19 -CTUN, 997, 0.00, 9.59, 12.662206, 0, 0, 259, 304, 248 -ATT, 0.00, 1.18, 0.00, -3.03, 0.00, 82.51, 83.10 -NTUN, 0.19, 1.36, -14.524475, 13.782715, -14.524475, 13.782715, -2.410246, -2.353056, -21.103394, 58.297974, 1.66, -3.21 -GPS, 3, 594540600, 8, 2.26, 44.0290173, -77.7367087, 10.18, 94.10, 0.06, 326.93 -CTUN, 996, 0.00, 9.96, 12.810509, 0, 0, 258, 296, 247 -NTUN, 0.19, 1.36, -14.804199, 14.418091, -14.804199, 14.418091, -5.106946, -1.638173, -16.769547, 57.290852, 1.40, -3.18 -ATT, 0.00, 2.35, 0.00, -3.56, 0.00, 82.43, 83.10 -CTUN, 996, 0.00, 10.34, 13.280758, 0, 0, 258, 303, 247 -NTUN, 0.20, 1.35, -14.806244, 15.095276, -14.806244, 15.095276, -7.206254, -0.841447, -13.020654, 57.840252, 1.20, -3.24 -ATT, 0.00, 3.01, 0.00, -2.48, 0.00, 82.36, 83.10 -GPS, 3, 594540800, 8, 2.26, 44.0290173, -77.7367088, 10.74, 94.60, 0.05, 326.93 -CTUN, 996, 0.00, 11.02, 13.380773, 0, 0, 258, 314, 247 -NTUN, 0.21, 1.34, -14.471558, 15.565247, -14.471558, 15.565247, -11.499073, 0.318551, -4.653137, 56.699707, 0.70, -3.24 -ATT, 0.00, 1.82, 0.00, -3.40, 0.00, 82.40, 83.10 -CTUN, 997, 0.00, 10.95, 13.802769, 0, 0, 259, 294, 248 -NTUN, 0.21, 1.32, -13.709106, 15.952942, -13.709106, 15.952942, -14.164777, 0.128674, 1.549021, 56.838566, 0.34, -3.29 -ATT, 0.00, 0.80, 0.00, -2.76, 0.00, 82.49, 83.10 -GPS, 3, 594541000, 8, 2.26, 44.0290173, -77.7367090, 11.30, 95.06, 0.07, 326.93 -CTUN, 998, 0.00, 11.50, 14.052079, 0, 0, 258, 303, 248 -NTUN, 0.21, 1.32, -12.677277, 16.318481, -12.677277, 16.318481, -16.277756, 2.057843, 7.318298, 55.655396, 0.00, -3.27 -ATT, 0.00, 0.38, 0.00, -3.77, 0.00, 82.59, 83.10 -CTUN, 996, 0.00, 11.43, 14.273411, 0, 0, 257, 305, 247 -NTUN, 0.20, 1.26, -11.538940, 16.537964, -11.538940, 16.537964, -17.673187, 2.391482, 12.383362, 55.194824, -0.30, -3.28 -GPS, 3, 594541200, 8, 2.26, 44.0290168, -77.7367092, 11.76, 95.55, 0.07, 326.93 -CTUN, 997, 0.00, 11.65, 14.375200, 0, 0, 257, 311, 248 -NTUN, 0.20, 1.22, -10.121277, 16.841858, -10.121277, 16.841858, -17.074354, 1.933644, 15.176636, 57.038940, -0.44, -3.41 -ATT, 0.00, 0.19, 0.00, -3.21, 0.00, 82.55, 83.10 -DU32, 7, 426225 -CURR, 996, 249731, 1377, 1909, 4962, 401.245270 -CTUN, 996, 0.00, 12.07, 14.793382, 0, 0, 256, 312, 247 -NTUN, 0.19, 1.17, -8.516174, 17.194153, -8.516174, 17.194153, -16.592892, 2.486956, 19.051025, 57.522949, -0.66, -3.47 -ATT, 0.00, -0.12, 0.00, -2.83, 0.00, 82.54, 83.10 -GPS, 3, 594541400, 8, 2.26, 44.0290165, -77.7367093, 12.33, 96.07, 0.22, 326.93 -CTUN, 996, 0.00, 12.28, 14.942746, 0, 0, 256, 302, 248 -NTUN, 0.19, 1.17, -7.025818, 17.562073, -7.025818, 17.562073, -14.855079, 1.818538, 17.903564, 59.679199, -0.58, -3.58 -ATT, 0.00, -0.39, 0.00, -3.14, 0.00, 82.61, 83.10 -CTUN, 997, 0.00, 12.79, 15.289813, 0, 0, 257, 311, 247 -NTUN, 0.18, 1.10, -5.665619, 17.931091, -5.665619, 17.931091, -13.651589, 2.712042, 16.467316, 60.653648, -0.49, -3.63 -GPS, 3, 594541600, 8, 2.26, 44.0290160, -77.7367093, 12.68, 96.56, 0.20, 326.93 -CTUN, 997, 0.00, 12.87, 15.537109, 0, 0, 256, 310, 247 -NTUN, 0.18, 1.05, -4.298340, 18.160522, -4.298340, 18.160522, -12.746624, 3.226578, 18.672791, 59.294312, -0.63, -3.57 -ATT, 0.00, -0.06, 0.00, -3.99, 0.00, 82.69, 83.10 -CTUN, 997, 0.00, 13.04, 15.760673, 0, 0, 256, 310, 248 -NTUN, 0.18, 0.99, -2.805511, 18.243286, -2.805511, 18.243286, -12.445741, 5.597291, 21.079075, 55.835999, -0.80, -3.38 -ATT, 0.00, 0.50, 0.00, -3.57, 0.00, 82.58, 83.10 -GPS, 3, 594541800, 8, 2.26, 44.0290157, -77.7367094, 13.27, 97.06, 0.28, 235.78 -CTUN, 997, 0.00, 13.46, 15.861686, 0, 0, 254, 316, 247 -NTUN, 0.18, 0.99, -1.392090, 18.236023, -1.392090, 18.236023, -12.151198, 5.297972, 20.994274, 55.928089, -0.79, -3.39 -ATT, 0.00, -0.93, 0.00, -2.78, 0.00, 82.67, 83.10 -NTUN, 0.18, 0.92, 0.066345, 18.047119, 0.066345, 18.047119, -12.452742, 8.951511, 24.584351, 51.110962, -1.03, -3.14 -CTUN, 996, 0.00, 13.87, 16.207037, 0, 0, 254, 321, 248 -ATT, 0.00, -0.09, 0.00, -4.51, 0.00, 82.56, 83.10 -GPS, 3, 594542000, 8, 2.26, 44.0290152, -77.7367092, 13.62, 97.55, 0.17, 235.78 -NTUN, 0.18, 0.87, 1.716003, 17.622131, 1.716003, 17.622131, -12.465354, 8.397877, 29.496582, 49.750122, -1.32, -3.10 -CTUN, 997, 0.00, 13.64, 16.508099, 0, 0, 250, 304, 248 -ATT, 0.00, -0.55, 0.00, -3.18, 0.00, 82.54, 83.10 -NTUN, 0.17, 0.82, 3.499817, 16.987854, 3.499817, 16.987854, -13.259588, 10.743642, 33.661518, 44.720028, -1.60, -2.84 -GPS, 3, 594542200, 8, 2.26, 44.0290149, -77.7367091, 14.22, 98.04, 0.26, 195.13 -CTUN, 997, 0.00, 14.79, 16.802509, 0, 0, 250, 328, 248 -NTUN, 0.17, 0.82, 5.328369, 16.193359, 5.328369, 16.193359, -12.300261, 11.553348, 35.470222, 40.974800, -1.74, -2.64 -ATT, 0.00, -1.02, 0.00, -3.12, 0.00, 82.58, 83.10 -DU32, 7, 426225 -CURR, 996, 252212, 1373, 1882, 4897, 405.655180 -CTUN, 997, 0.00, 14.62, 17.153149, 0, 0, 251, 294, 247 -NTUN, 0.17, 0.70, 7.071686, 15.413757, 7.071686, 15.413757, -12.109844, 10.733702, 36.433167, 41.203979, -1.80, -2.65 -ATT, 0.00, -1.52, 0.00, -2.95, 0.00, 82.72, 83.10 -GPS, 3, 594542400, 8, 2.26, 44.0290145, -77.7367088, 14.77, 98.50, 0.19, 180.95 -CTUN, 997, 0.00, 14.76, 17.351299, 0, 0, 250, 332, 247 -NTUN, 0.16, 0.63, 8.812866, 14.521362, 8.812866, 14.521362, -11.605440, 12.749834, 38.239410, 38.164406, -1.93, -2.49 -ATT, 0.00, -1.25, 0.00, -3.47, 0.00, 82.72, 83.10 -NTUN, 0.16, 0.57, 10.566132, 13.434814, 10.566132, 13.434814, -11.272931, 12.485708, 40.709751, 35.024769, -2.09, -2.33 -CTUN, 997, 0.00, 14.63, 17.696634, 0, 0, 249, 317, 248 -ATT, 0.00, -1.00, 0.00, -3.06, 0.00, 82.69, 83.10 -GPS, 3, 594542600, 8, 2.26, 44.0290140, -77.7367084, 15.28, 99.00, 0.30, 154.63 -NTUN, 0.17, 0.49, 12.440735, 12.274719, 12.440735, 12.274719, -11.130907, 13.312426, 45.560429, 32.513908, -2.39, -2.22 -CTUN, 996, 0.00, 16.31, 18.120861, 0, 0, 250, 313, 247 -ATT, 0.00, -1.59, 0.00, -2.39, 0.00, 82.70, 83.10 -NTUN, 0.17, 0.40, 14.423950, 10.966248, 14.423950, 10.966248, -11.749087, 12.840271, 50.832153, 30.915283, -2.71, -2.16 -CTUN, 997, 0.00, 16.36, 18.266418, 0, 0, 255, 306, 247 -GPS, 3, 594542800, 8, 2.26, 44.0290137, -77.7367082, 15.67, 99.49, 0.30, 154.63 -NTUN, 0.18, 0.31, 16.373688, 9.876953, 16.373688, 9.876953, -11.381597, 10.685307, 52.497375, 34.107056, -2.78, -2.35 -ATT, 0.00, -2.27, 0.00, -1.91, 0.00, 82.80, 83.10 -CTUN, 996, 0.00, 16.03, 18.638845, 0, 0, 258, 281, 247 -NTUN, 0.19, 0.26, 18.195435, 9.048950, 18.195435, 9.048950, -9.587261, 8.694448, 53.217468, 36.719971, -2.80, -2.52 -ATT, 0.00, -2.61, 0.00, -2.06, 0.00, 82.68, 83.10 -GPS, 3, 594543000, 8, 2.26, 44.0290132, -77.7367077, 16.30, 99.99, 0.33, 152.17 -NTUN, 0.19, 0.26, 20.030121, 8.335632, 20.030121, 8.335632, -8.929605, 6.451656, 55.165211, 38.937447, -2.90, -2.65 -CTUN, 996, 0.00, 16.17, 19.035683, 0, 0, 250, 324, 248 -ATT, 0.00, -2.29, 0.00, -2.66, 0.00, 82.78, 83.10 -NTUN, 0.21, 0.21, 21.672943, 7.719727, 21.672943, 7.719727, -5.173303, 4.223622, 52.428223, 42.840942, -2.72, -2.86 -CTUN, 997, 0.00, 16.10, 19.283760, 0, 0, 249, 313, 248 -ATT, 0.00, -3.42, 0.00, -2.83, 0.00, 82.89, 83.10 -GPS, 3, 594543200, 8, 2.26, 44.0290127, -77.7367073, 16.85, 100.45, 0.32, 152.17 -NTUN, 0.23, 0.17, 23.175354, 7.264404, 23.175354, 7.264404, -3.225033, 2.749436, 53.024109, 45.446777, -2.73, -3.01 -CTUN, 996, 0.00, 16.22, 19.508003, 0, 0, 247, 326, 248 -ATT, 0.00, -2.34, 0.00, -3.03, 0.00, 82.66, 83.10 -NTUN, 0.24, 0.15, 24.503937, 6.872803, 24.503937, 6.872803, -0.318589, 0.192299, 50.285828, 48.083984, -2.54, -3.16 -CTUN, 997, 0.00, 16.77, 19.754488, 0, 0, 250, 323, 248 -GPS, 3, 594543400, 8, 2.26, 44.0290125, -77.7367068, 17.16, 100.96, 0.32, 152.17 -NTUN, 0.25, 0.14, 25.438446, 6.593018, 25.438446, 6.593018, 3.086170, -1.455423, 45.345093, 52.202148, -2.22, -3.36 -ATT, 0.00, -2.51, 0.00, -2.17, 0.00, 82.55, 83.10 -CTUN, 932, 0.00, 17.37, 20.111841, 0, 0, 257, 266, 207 -NTUN, 0.25, 0.14, 26.085388, 6.319336, 26.085388, 6.319336, 3.478465, -4.233606, 43.405369, 54.290279, -2.10, -3.46 -ATT, 0.00, -2.04, 0.00, -2.06, 0.00, 82.60, 83.10 -GPS, 3, 594543600, 8, 2.26, 44.0290125, -77.7367066, 17.76, 101.51, 0.28, 144.46 -NTUN, 0.25, 0.14, 26.406677, 6.372498, 26.406677, 6.372498, 6.771284, -7.333781, 38.212891, 61.531616, -1.74, -3.84 -CTUN, 691, 0.00, 18.00, 20.335735, 0, 0, 252, 254, 85 -ATT, 0.00, -2.86, 0.00, -1.65, 0.00, 82.75, 83.10 -NTUN, 0.27, 0.13, 26.444000, 6.694214, 26.444000, 6.694214, 7.070109, -10.502822, 36.373230, 69.217163, -1.61, -4.26 -CTUN, 672, 0.00, 17.59, 20.396154, 0, 0, 236, 244, 47 -GPS, 3, 594543800, 8, 2.26, 44.0290125, -77.7367061, 18.20, 102.03, 0.19, 144.46 -ATT, 0.00, -2.12, 0.00, -3.27, 0.00, 83.29, 83.10 -NTUN, 0.27, 0.14, 26.373749, 7.098816, 26.373749, 7.098816, 8.400754, -11.979584, 34.361351, 72.678200, -1.49, -4.44 -CTUN, 674, 0.00, 17.76, 20.445671, 0, 0, 202, 241, 45 -ATT, 0.00, -1.09, 0.00, -4.04, 0.00, 83.30, 83.10 -NTUN, 0.27, 0.15, 26.125397, 7.398804, 26.125397, 7.398804, 9.198740, -13.535044, 32.516479, 73.999878, -1.37, -4.50 -GPS, 3, 594544000, 8, 2.26, 44.0290127, -77.7367058, 18.54, 102.49, 0.18, 144.46 -CTUN, 673, 0.00, 18.19, 20.477551, 0, 0, 182, 264, 46 -NTUN, 0.27, 0.15, 25.649261, 7.599915, 25.649261, 7.599915, 10.257668, -12.788925, 29.238647, 74.011108, -1.18, -4.48 -ATT, 0.00, -1.63, 0.00, -3.71, 0.00, 83.24, 83.10 -CTUN, 673, 0.00, 18.03, 20.554350, 0, 1, 139, 389, 45 -NTUN, 0.26, 0.16, 24.886169, 7.569031, 24.886169, 7.569031, 13.065922, -11.262971, 23.444633, 70.694221, -0.86, -4.25 -GPS, 3, 594544200, 8, 2.26, 44.0290129, -77.7367053, 18.85, 102.82, 0.18, 144.46 -ATT, 0.00, -2.75, 0.00, -6.27, 0.00, 83.09, 83.10 -CTUN, 673, 0.00, 17.37, 20.609207, 0, 0, 153, 220, 45 -NTUN, 0.26, 0.16, 23.844635, 6.898987, 23.844635, 6.898987, 11.864396, -8.840005, 20.479450, 61.231880, -0.74, -3.69 -ATT, 0.00, 2.26, 0.00, -4.98, 0.00, 82.97, 83.10 -CTUN, 674, 0.00, 18.29, 20.655106, 0, 0, 153, 285, 46 -NTUN, 0.24, 0.15, 23.100586, 6.042664, 23.100586, 6.042664, 9.339542, -9.337297, 26.633179, 60.521553, -1.10, -3.69 -GPS, 3, 594544400, 8, 2.26, 44.0290132, -77.7367048, 19.09, 103.09, 0.24, 144.46 -CTUN, 674, 0.00, 19.82, 20.705332, 0, 0, 154, 259, 46 -NTUN, 0.23, 0.12, 22.267639, 5.011292, 22.267639, 5.011292, 9.251355, -8.334293, 26.753002, 57.788395, -1.12, -3.54 -ATT, 0.00, -0.30, 0.00, -1.10, 0.00, 82.83, 83.10 -DU32, 7, 426225 -CURR, 673, 257531, 1375, 1795, 4940, 415.205570 -CTUN, 673, 0.00, 20.31, 20.750217, 0, 0, 146, 265, 45 -NTUN, 0.22, 0.10, 21.594574, 3.807007, 21.594574, 3.807007, 5.629529, -8.824551, 31.269348, 54.957153, -1.42, -3.40 -GPS, 3, 594544600, 8, 2.26, 44.0290135, -77.7367046, 19.40, 103.41, 0.19, 144.46 -ATT, 0.00, -3.94, 0.00, -3.65, 0.00, 83.20, 83.10 -CTUN, 674, 0.00, 18.41, 20.795776, 0, 0, 135, 238, 45 -NTUN, 0.21, 0.07, 21.066406, 2.678345, 21.066406, 2.678345, 4.808172, -9.371012, 33.718323, 56.713379, -1.56, -3.51 -ATT, 0.00, -1.00, 0.00, -5.07, 0.00, 83.38, 83.10 -CTUN, 673, 0.00, 18.76, 20.836357, 0, 0, 118, 292, 46 -NTUN, 0.21, 0.07, 20.492310, 1.590393, 20.492310, 1.590393, 5.183752, -8.799155, 33.259033, 55.120483, -1.55, -3.41 -GPS, 3, 594544800, 8, 2.26, 44.0290139, -77.7367043, 19.58, 103.70, 0.25, 144.46 -CTUN, 674, 0.00, 19.32, 20.836357, 0, 0, 118, 255, 46 -NTUN, 0.20, 0.03, 19.609863, 0.374634, 19.609863, 0.374634, 5.960292, -6.778088, 29.086401, 51.719604, -1.33, -3.19 -ATT, 0.00, -0.91, 0.00, -4.37, 0.00, 83.37, 83.10 -NTUN, 0.19, 3.59, 18.724701, -1.024231, 18.724701, -1.024231, 4.002227, -6.080880, 30.236015, 48.149857, -1.42, -2.99 -ATT, 0.00, -1.56, 0.00, -3.08, 0.00, 83.15, 83.10 -GPS, 3, 594545000, 8, 2.26, 44.0290143, -77.7367040, 19.77, 103.89, 0.21, 144.46 -CTUN, 676, 0.00, 19.64, 20.946033, 0, 0, 95, 254, 46 -NTUN, 0.18, 3.54, 17.636139, -2.685303, 17.636139, -2.685303, 4.949340, -1.822776, 27.114380, 40.389282, -1.28, -2.53 -ATT, 0.00, -1.73, 0.00, -4.21, 0.00, 82.92, 83.10 -CTUN, 674, 0.00, 19.05, 21.006777, 0, 0, 104, 271, 47 -NTUN, 0.17, 3.48, 16.472076, -4.460754, 16.472076, -4.460754, 3.816261, -3.103883, 27.359375, 38.245483, -1.30, -2.41 -GPS, 3, 594545200, 8, 2.26, 44.0290146, -77.7367040, 19.93, 104.11, 0.21, 144.46 -CTUN, 676, 0.00, 19.94, 21.062654, 0, 0, 100, 275, 46 -NTUN, 0.17, 3.48, 15.151855, -6.062744, 15.151855, -6.062744, 6.060216, -1.136068, 22.797791, 36.980103, -1.04, -2.31 -ATT, 0.00, -1.11, 0.00, -2.19, 0.00, 82.58, 83.10 -CTUN, 676, 0.00, 20.47, 21.094746, 0, 0, 99, 274, 47 -NTUN, 0.16, 3.36, 13.817657, -7.627136, 13.817657, -7.627136, 4.055489, -2.258278, 23.658020, 35.356079, -1.10, -2.22 -ATT, 0.00, -1.14, 0.00, -2.09, 0.00, 82.72, 83.10 -GPS, 3, 594545400, 8, 2.26, 44.0290148, -77.7367038, 20.14, 104.36, 0.19, 144.46 -CTUN, 676, 0.00, 20.53, 21.159927, 0, 0, 96, 253, 46 -NTUN, 0.16, 3.36, 12.487915, -8.955872, 12.487915, -8.955872, 5.451126, -3.097146, 21.834234, 37.844204, -0.98, -2.35 -PM, 0, 0, 50, 174, 1003, 12300, 11, 0 -ATT, 0.00, -2.19, 0.00, -1.47, 0.00, 82.93, 83.10 -CTUN, 673, 0.00, 21.09, 21.206341, 0, 0, 89, 271, 45 -NTUN, 0.15, 3.22, 11.191711, -10.164185, 11.191711, -10.164185, 4.340525, -3.827069, 21.037964, 37.916870, -0.94, -2.34 -GPS, 3, 594545600, 8, 2.26, 44.0290149, -77.7367034, 20.32, 104.52, 0.18, 144.46 -CTUN, 673, 0.00, 21.01, 21.251883, 0, 0, 81, 262, 45 -NTUN, 0.15, 3.12, 10.012787, -11.332520, 10.012787, -11.332520, 5.018810, -4.505648, 20.210754, 38.316650, -0.89, -2.36 -ATT, 0.00, -1.03, 0.00, -3.03, 0.00, 82.96, 83.10 -CTUN, 644, 0.00, 20.55, 21.285061, 0, 0, 74, 266, 33 -NTUN, 0.15, 3.12, 8.903656, -12.440552, 8.903656, -12.440552, 4.474064, -5.401686, 21.908691, 36.919678, -1.00, -2.29 -GPS, 3, 594545800, 8, 2.26, 44.0290150, -77.7367031, 20.51, 104.69, 0.18, 144.46 -ATT, 0.00, -1.07, 0.00, -2.31, 0.00, 83.11, 83.10 -CTUN, 552, 0.00, 20.68, 21.285061, 0, 0, 61, 284, 0 -NTUN, 0.15, 3.04, 7.934235, -13.430115, 7.934235, -13.430115, 4.527987, -6.137476, 22.305786, 38.104370, -1.02, -2.36 -DU32, 7, 426225 -CURR, 482, 260493, 1395, 1597, 4876, 419.653870 -ATT, 0.00, -1.26, 0.00, -2.18, 0.00, 83.03, 83.10 -CTUN, 455, 0.00, 20.76, 21.285061, 0, 0, 59, 263, 0 -NTUN, 0.15, 2.99, 7.006226, -14.520935, 7.006226, -14.520935, 3.856381, -4.476139, 22.719910, 33.091797, -1.08, -2.07 -GPS, 3, 594546000, 8, 2.26, 44.0290153, -77.7367030, 20.69, 104.84, 0.16, 144.46 -ATT, 0.00, -0.49, 0.00, -2.93, 0.00, 83.04, 83.10 -CTUN, 396, 0.00, 20.54, 21.284657, 0, 0, 56, 263, -1 -NTUN, 0.15, 2.99, 6.135773, -15.419495, 6.135773, -15.419495, 2.388277, -7.335052, 23.295471, 37.014404, -1.08, -2.31 -ATT, 0.00, -0.69, 0.00, -1.63, 0.00, 82.96, 83.10 -NTUN, 0.16, 2.90, 5.241455, -16.140991, 5.241455, -16.140991, 1.837882, -6.826429, 23.145370, 37.856468, -1.07, -2.35 -CTUN, 322, 0.00, 21.07, 21.250889, 0, 0, 48, 251, -36 -GPS, 3, 594546200, 8, 2.26, 44.0290153, -77.7367028, 20.79, 104.94, 0.11, 144.46 -NTUN, 0.16, 2.85, 4.702637, -16.863403, 4.702637, -16.863403, -0.726439, -8.190484, 28.611816, 37.775879, -1.38, -2.39 -CTUN, 294, 0.00, 20.99, 21.196684, 0, 0, 41, 217, -60 -ATT, 0.00, -0.28, 0.00, -1.44, 0.00, 82.87, 83.10 -NTUN, 0.16, 2.85, 4.342285, -17.357178, 4.342285, -17.357178, 0.351017, -10.945901, 29.432163, 42.111145, -1.40, -2.65 -CTUN, 260, 0.00, 20.96, 21.139910, 0, 0, 32, 259, -78 -GPS, 3, 594546400, 8, 2.26, 44.0290154, -77.7367028, 20.86, 105.04, 0.14, 144.46 -ATT, 0.00, -3.24, 0.00, -0.89, 0.00, 83.24, 83.10 -NTUN, 0.17, 2.83, 3.947357, -17.500427, 3.947357, -17.500427, -0.274475, -12.223483, 30.010828, 46.553036, -1.42, -2.90 -CTUN, 223, 0.00, 21.23, 21.006224, 0, 0, 7, 214, -103 -ATT, 0.00, -1.31, 0.00, -2.74, 0.00, 83.22, 83.10 -NTUN, 0.17, 2.81, 3.618500, -17.500549, 3.618500, -17.500549, -0.952316, -12.651134, 30.711426, 47.998779, -1.44, -2.99 -GPS, 3, 594546600, 8, 2.26, 44.0290157, -77.7367030, 20.90, 105.12, 0.20, 39.87 -CTUN, 190, 0.00, 20.29, 20.890692, 0, 0, -10, 274, -122 -NTUN, 0.17, 2.81, 3.056824, -17.237610, 3.056824, -17.237610, 1.332085, -14.428085, 25.438850, 52.603359, -1.09, -3.22 -ATT, 0.00, -0.11, 0.00, -3.55, 0.00, 82.89, 83.10 -CTUN, 166, 0.00, 20.19, 20.729935, 0, 0, -27, 252, -140 -NTUN, 0.17, 2.79, 2.219940, -16.760071, 2.219940, -16.760071, 0.002811, -14.343505, 23.631165, 54.775391, -0.97, -3.34 -ATT, 0.00, -1.74, 0.00, -2.42, 0.00, 82.87, 83.10 -GPS, 3, 594546800, 8, 2.26, 44.0290159, -77.7367032, 20.84, 105.10, 0.20, 4.03 -NTUN, 0.16, 2.76, 1.515625, -16.196594, 1.515625, -16.196594, -1.028619, -14.624989, 24.885704, 56.691681, -1.01, -3.46 -CTUN, 160, 0.00, 20.27, 20.536953, 0, 0, -43, 229, -148 -ATT, 0.00, -0.62, 0.00, -2.28, 0.00, 82.41, 83.10 -NTUN, 0.16, 2.74, 0.695068, -15.537231, 0.695068, -15.537231, 0.424241, -15.667809, 21.955326, 58.464340, -0.81, -3.55 -GPS, 3, 594547000, 8, 2.26, 44.0290162, -77.7367034, 20.71, 105.03, 0.20, 4.03 -ATT, 0.00, -1.55, 0.00, -3.03, 0.00, 82.33, 83.10 -NTUN, 0.15, 2.71, -0.296997, -14.798279, -0.296997, -14.798279, 0.437106, -14.314573, 19.979137, 59.464169, -0.69, -3.59 -CTUN, 160, 0.00, 20.13, 20.358591, 0, 0, -57, 233, -150 -ATT, 0.00, -1.16, 0.00, -4.59, 0.00, 82.07, 83.10 -NTUN, 0.14, 2.66, -1.392883, -14.194885, -1.392883, -14.194885, 0.616089, -14.274404, 17.041138, 58.033936, -0.51, -3.49 -GPS, 3, 594547200, 8, 2.26, 44.0290163, -77.7367038, 20.53, 104.88, 0.28, 340.14 -CTUN, 159, 0.00, 19.71, 20.043659, 0, 0, -68, 286, -150 -NTUN, 0.14, 2.66, -2.446442, -13.457703, -2.446442, -13.457703, 2.072532, -12.082836, 15.568729, 58.298836, -0.41, -3.49 -ATT, 0.00, -1.01, 0.00, -3.84, 0.00, 81.78, 83.10 -CTUN, 152, 0.00, 19.55, 19.802116, 0, 0, -66, 242, -154 -NTUN, 0.13, 2.58, -3.561859, -12.969971, -3.561859, -12.969971, 1.615249, -10.456310, 13.733157, 54.926586, -0.34, -3.28 -GPS, 3, 594547400, 8, 2.26, 44.0290165, -77.7367040, 20.31, 104.76, 0.26, 330.62 -ATT, 0.00, -0.80, 0.00, -3.75, 0.00, 82.01, 83.10 -CTUN, 146, 0.00, 19.50, 19.597597, 0, 0, -75, 267, -158 -NTUN, 0.13, 2.58, -4.528259, -12.497742, -4.528259, -12.497742, 0.301207, -10.071082, 16.431683, 54.675533, -0.50, -3.29 -ATT, 0.00, -0.21, 0.00, -2.86, 0.00, 82.02, 83.10 -CTUN, 145, 0.00, 19.71, 19.453943, 0, 0, -79, 262, -159 -NTUN, 0.13, 2.48, -5.535889, -12.178406, -5.535889, -12.178406, 0.554508, -8.639439, 13.023472, 52.161743, -0.33, -3.12 -GPS, 3, 594547600, 8, 2.26, 44.0290167, -77.7367044, 20.16, 104.62, 0.23, 321.51 -CTUN, 143, 0.00, 19.52, 19.276592, 0, 0, -86, 254, -160 -NTUN, 0.13, 2.48, -6.411133, -11.734741, -6.411133, -11.734741, -1.608868, -8.277006, 16.159149, 53.481461, -0.50, -3.22 -ATT, 0.00, -0.13, 0.00, -2.89, 0.00, 82.14, 83.10 -NTUN, 0.13, 2.40, -7.155731, -11.291931, -7.155731, -11.291931, -2.210310, -7.673615, 17.554016, 52.428101, -0.59, -3.17 -GPS, 3, 594547800, 8, 2.26, 44.0290170, -77.7367047, 19.95, 104.49, 0.23, 321.51 -CTUN, 139, 0.00, 19.35, 19.132593, 0, 0, -91, 285, -161 -ATT, 0.00, -0.48, 0.00, -3.14, 0.00, 82.20, 83.10 -NTUN, 0.13, 2.36, -7.980560, -10.788208, -7.980560, -10.788208, -2.180479, -6.522491, 15.833376, 51.987358, -0.50, -3.13 -CTUN, 137, 0.00, 19.23, 18.837286, 0, 0, -102, 251, -164 -ATT, 0.00, -0.99, 0.00, -3.84, 0.00, 82.30, 83.10 -NTUN, 0.13, 2.31, -8.802490, -10.437012, -8.802490, -10.437012, -3.907898, -4.848779, 15.697678, 49.547436, -0.52, -2.98 -GPS, 3, 594548000, 8, 2.26, 44.0290170, -77.7367051, 19.69, 104.33, 0.24, 320.81 -CTUN, 133, 0.00, 18.98, 18.771334, 0, 0, -104, 273, -165 -NTUN, 0.13, 2.27, -9.405609, -10.053833, -9.405609, -10.053833, -3.208894, -3.528242, 15.968811, 48.831787, -0.53, -2.95 -ATT, 0.00, 0.00, 0.00, -3.50, 0.00, 82.04, 83.10 -NTUN, 0.13, 2.27, -9.996094, -9.714172, -9.996094, -9.714172, -3.035399, -2.688259, 16.153618, 46.362976, -0.56, -2.81 -CTUN, 0, 0.00, 18.85, 18.411558, 0, 0, -108, 261, -250 -GPS, 3, 594548200, 8, 2.26, 44.0290170, -77.7367055, 19.44, 104.13, 0.17, 320.81 -ATT, 0.00, -1.00, 0.00, -2.70, 0.00, 82.15, 83.10 -NTUN, 0.13, 2.22, -10.444366, -9.341797, -10.444366, -9.341797, -4.148527, -0.429294, 16.517273, 45.723755, -0.59, -2.77 -CTUN, 0, 0.00, 18.72, 18.161949, 0, 0, -112, 218, -250 -ATT, 0.00, -0.01, 0.00, -3.38, 0.00, 82.27, 83.10 -NTUN, 0.14, 2.20, -10.728455, -9.015808, -10.728455, -9.015808, -5.124687, -0.323685, 19.159119, 45.259888, -0.75, -2.76 -GPS, 3, 594548400, 8, 2.26, 44.0290170, -77.7367058, 19.17, 103.94, 0.14, 320.81 -CTUN, 0, 0.00, 18.71, 17.911430, 0, 0, -121, 267, -250 -NTUN, 0.14, 2.18, -10.939148, -8.561890, -10.939148, -8.561890, -4.375811, -0.993803, 18.913927, 46.494244, -0.72, -2.83 -ATT, 0.00, -0.16, 0.00, -1.74, 0.00, 82.20, 83.10 -CTUN, 0, 0.00, 18.71, 17.435249, 0, 0, -151, 227, -250 -NTUN, 0.14, 2.18, -11.180298, -8.063660, -11.180298, -8.063660, -3.347436, -0.411691, 17.564142, 47.032627, -0.65, -2.85 -GPS, 3, 594548600, 8, 2.26, 44.0290170, -77.7367062, 18.79, 103.71, 0.19, 320.81 -ATT, 0.00, -2.25, 0.00, -2.11, 0.00, 82.48, 83.10 -CTUN, 0, 0.00, 18.30, 17.182711, 0, 0, -171, 272, -250 -NTUN, 0.13, 2.14, -11.332001, -7.454346, -11.332001, -7.454346, -5.811428, 0.926460, 19.512716, 45.973667, -0.77, -2.81 -DU32, 7, 426225 -CURR, 0, 266028, 1403, 1142, 4984, 427.507390 -ATT, 0.00, 1.10, 0.00, -4.11, 0.00, 82.20, 83.10 -CTUN, 0, 0.00, 18.09, 16.960081, 0, 0, -181, 268, -250 -NTUN, 0.13, 2.11, -11.338837, -6.925537, -11.338837, -6.925537, -5.371786, 1.804559, 20.930950, 45.341499, -0.84, -2.78 -GPS, 3, 594548800, 8, 2.26, 44.0290170, -77.7367066, 18.42, 103.42, 0.17, 320.81 -CTUN, 0, 0.00, 17.96, 16.681982, 0, 0, -187, 286, -250 -NTUN, 0.13, 2.09, -11.385925, -6.248962, -11.385925, -6.248962, -6.692578, 4.505222, 21.567995, 43.207108, -0.91, -2.66 -ATT, 0.00, -0.57, 0.00, -3.37, 0.00, 82.45, 83.10 -NTUN, 0.12, 2.08, -11.088867, -6.084839, -11.088867, -6.084839, -10.301647, 9.832729, 28.941170, 33.624985, -1.41, -2.16 -CTUN, 0, 0.00, 17.70, 16.483961, 0, 0, -189, 267, -250 -GPS, 3, 594549000, 8, 2.26, 44.0290169, -77.7367069, 18.15, 103.04, 0.15, 320.81 -ATT, 0.00, 1.46, 0.00, -4.86, 0.00, 82.28, 83.10 -NTUN, 0.12, 2.10, -10.433167, -6.248779, -10.433167, -6.248779, -10.650783, 12.667622, 32.557007, 26.360596, -1.66, -1.78 -CTUN, 0, 0.00, 17.46, 16.158722, 0, 0, -189, 300, -250 -ATT, 0.00, -1.20, 0.00, -3.22, 0.00, 82.21, 83.10 -NTUN, 0.12, 2.10, -9.780304, -6.706848, -9.780304, -6.706848, -10.126818, 15.882510, 31.881645, 18.873253, -1.69, -1.33 -GPS, 3, 594549200, 8, 2.26, 44.0290166, -77.7367071, 17.67, 102.68, 0.15, 320.81 -CTUN, 0, 0.00, 17.35, 15.883252, 0, 0, -194, 269, -250 -NTUN, 0.11, 2.17, -8.872559, -7.440735, -8.872559, -7.440735, -12.107986, 21.232389, 38.169144, 7.587003, -2.14, -0.73 -ATT, 0.00, -2.15, 0.00, -2.71, 0.00, 82.33, 83.10 -CTUN, 0, 0.00, 17.32, 15.508042, 0, 0, -195, 302, -250 -NTUN, 0.11, 2.25, -7.859497, -8.563904, -7.859497, -8.563904, -8.644477, 24.139324, 36.130615, -1.231689, -2.09, -0.23 -GPS, 3, 594549400, 8, 2.26, 44.0290163, -77.7367073, 17.28, 102.29, 0.17, 320.81 -CTUN, 0, 0.00, 17.19, 15.406942, 0, 0, -197, 300, -250 -ATT, 0.00, -0.40, 0.00, -5.33, 0.00, 81.33, 83.10 -NTUN, 0.11, 2.33, -7.095734, -9.667603, -7.095734, -9.667603, -7.233406, 23.136822, 33.562016, -2.927710, -1.95, -0.12 -CTUN, 0, 0.00, 17.10, 14.980663, 0, 0, -202, 235, -250 -ATT, 0.00, -2.80, 0.00, 0.26, 0.00, 81.11, 83.10 -NTUN, 0.11, 2.33, -5.978577, -10.627869, -5.978577, -10.627869, -11.391832, 23.118736, 41.155972, -3.729692, -2.40, -0.17 -GPS, 3, 594549600, 8, 2.26, 44.0290160, -77.7367071, 16.84, 101.94, 0.14, 320.81 -CTUN, 0, 0.00, 17.68, 14.856442, 0, 0, -203, 262, -250 -NTUN, 0.12, 2.43, -4.907318, -11.326721, -4.907318, -11.326721, -8.149932, 19.718243, 39.712585, -0.988525, -2.28, -0.37 -ATT, 0.00, 0.19, 0.00, 2.09, 0.00, 79.30, 83.10 -CTUN, 0, 0.00, 17.96, 14.479981, 0, 0, -215, 293, -250 -NTUN, 0.12, 2.49, -3.746246, -11.698303, -3.746246, -11.698303, -8.814607, 14.915759, 43.610718, 5.284180, -2.43, -0.79 -GPS, 3, 594549800, 8, 2.26, 44.0290156, -77.7367071, 16.56, 101.53, 0.19, 320.81 -ATT, 0.00, -2.46, 0.00, -1.75, 0.00, 78.53, 83.10 -CTUN, 0, 0.00, 17.25, 14.155252, 0, 0, -229, 320, -250 -NTUN, 0.12, 2.54, -2.692444, -11.341553, -2.692444, -11.341553, -1.933835, 11.504406, 37.538025, 15.567505, -1.96, -1.32 -ATT, 0.00, -6.59, 0.00, -3.86, 0.00, 78.85, 83.10 -GPS, 3, 594550000, 8, 2.26, 44.0290151, -77.7367070, 16.09, 101.10, 0.19, 320.81 -NTUN, 0.11, 2.57, -2.090546, -10.729736, -2.090546, -10.729736, 2.913818, 6.681769, 25.974365, 21.056334, -1.24, -1.50 -CTUN, 0, 0.00, 15.06, 13.829623, 0, 0, -226, 213, -250 -ATT, 0.00, -0.34, 0.00, 0.99, 0.00, 78.40, 83.10 -NTUN, 0.10, 2.59, -1.601501, -9.503235, -1.601501, -9.503235, 3.039858, 1.697534, 26.890442, 34.265015, -1.12, -2.27 -CTUN, 0, 0.00, 16.63, 13.477523, 0, 0, -233, 272, -250 -GPS, 3, 594550200, 8, 2.26, 44.0290148, -77.7367066, 15.66, 100.69, 0.21, 320.81 -NTUN, 0.09, 2.60, -1.345795, -8.198730, -1.345795, -8.198730, 9.038149, 1.687270, 18.531750, 35.915886, -0.61, -2.27 -CTUN, 0, 0.00, 16.60, 13.377664, 0, 0, -234, 276, -250 -ATT, 0.00, -0.42, 0.00, -0.65, 0.00, 78.20, 83.10 -NTUN, 0.08, 2.60, -1.216187, -7.206848, -1.216187, -7.206848, 7.277858, 2.268355, 18.309174, 33.019012, -0.67, -2.09 -CTUN, 0, 0.00, 15.21, 12.976645, 0, 0, -243, 292, -250 -DU32, 7, 426225 -CURR, 0, 269350, 1374, 1653, 4918, 433.421080 -ATT, 0.00, -3.10, 0.00, -6.55, 0.00, 79.50, 83.10 -NTUN, 0.07, 2.61, -0.955414, -6.301758, -0.955414, -6.301758, 5.882308, 1.191053, 21.581907, 32.961288, -0.89, -2.11 -GPS, 3, 594550400, 8, 2.26, 44.0290150, -77.7367069, 15.20, 100.23, 0.07, 320.81 -CTUN, 0, 0.00, 14.10, 12.826865, 0, 0, -247, 269, -250 -ATT, 0.00, 1.81, 0.00, -1.64, 0.00, 79.86, 83.10 -NTUN, 0.06, 2.61, -0.856628, -5.379639, -0.856628, -5.379639, 6.998095, 3.455119, 18.997833, 32.314335, -0.75, -2.05 -CTUN, 0, 0.00, 15.22, 12.476026, 0, 0, -249, 332, -250 -GPS, 3, 594550600, 8, 2.26, 44.0290151, -77.7367068, 14.64, 99.75, 0.12, 320.81 -NTUN, 0.06, 2.61, -0.950562, -5.058167, -0.950562, -5.058167, 8.159167, 14.469152, 14.153756, 13.896146, -0.66, -0.94 -ATT, 0.00, 1.03, 0.00, -1.51, 0.00, 79.65, 83.10 -CTUN, 0, 0.00, 14.52, 12.150885, 0, 0, -248, 273, -250 -NTUN, 0.05, 2.58, -1.254242, -5.932312, -1.254242, -5.932312, 7.770643, 18.952934, 11.963196, -3.741455, -0.71, 0.08 -ATT, 0.00, -3.11, 0.00, -8.46, 0.00, 79.67, 83.10 -GPS, 3, 594550800, 8, 2.26, 44.0290152, -77.7367068, 14.26, 99.31, 0.12, 320.81 -NTUN, 0.06, 2.57, -1.627045, -7.286133, -1.627045, -7.286133, 6.981309, 24.631176, 11.271973, -17.538208, -0.82, 0.89 -CTUN, 0, 0.00, 12.06, 11.902105, 0, 1, -234, 343, -250 -ATT, 0.00, -0.95, 0.00, -4.15, 0.00, 79.88, 83.10 -NTUN, 0.07, 2.57, -2.066925, -9.272949, -2.066925, -9.272949, 10.710123, 29.573656, 6.601196, -32.868164, -0.71, 1.82 -CTUN, 0, 0.00, 13.62, 11.447936, 0, 0, -243, 267, -250 -GPS, 3, 594551000, 8, 2.26, 44.0290150, -77.7367063, 13.63, 98.80, 0.04, 320.81 -ATT, 0.00, 1.38, 0.00, 0.70, 0.00, 79.98, 83.10 -NTUN, 0.07, 2.57, -2.414398, -11.554993, -2.414398, -11.554993, 5.608881, 26.421803, 10.559671, -36.594490, -0.97, 1.99 -CTUN, 0, 0.00, 13.97, 11.174926, 0, 0, -231, 254, -250 -NTUN, 0.11, 2.59, -2.152130, -13.292786, -2.152130, -13.292786, 5.473957, 19.291330, 17.649172, -27.553465, -1.29, 1.40 -ATT, 0.00, 0.03, 0.00, 5.16, 0.00, 79.86, 83.10 -CTUN, 0, 0.00, 13.97, 10.948505, 0, 0, -229, 264, -250 -GPS, 3, 594551200, 8, 2.26, 44.0290147, -77.7367057, 13.23, 98.34, 0.28, 320.81 -NTUN, 0.11, 2.59, -1.922455, -14.370789, -1.922455, -14.370789, 5.871748, 13.426779, 17.274014, -16.673296, -1.15, 0.79 -CTUN, 0, 0.00, 13.36, 10.674856, 0, 0, -234, 283, -250 -ATT, 0.00, -5.92, 0.00, 1.23, 0.00, 80.98, 83.10 -NTUN, 0.14, 2.63, -1.392303, -14.683044, -1.392303, -14.683044, 8.231184, 4.779432, 17.301514, -2.122559, -1.01, -0.03 -CTUN, 0, 0.00, 12.77, 10.447415, 0, 0, -242, 283, -250 -ATT, 0.00, -3.90, 0.00, -0.63, 0.00, 81.29, 83.10 -GPS, 3, 594551400, 8, 2.26, 44.0290148, -77.7367054, 12.72, 97.92, 0.17, 320.81 -NTUN, 0.14, 2.64, -1.361053, -14.432434, -1.361053, -14.432434, 11.650854, 2.150609, 7.312500, 5.506104, -0.37, -0.38 -CTUN, 0, 0.00, 12.70, 10.298956, 0, 0, -245, 252, -250 -ATT, 0.00, 2.60, 0.00, -2.05, 0.00, 81.72, 83.10 -NTUN, 0.14, 2.64, -1.513428, -14.067078, -1.513428, -14.067078, 9.405152, 1.921095, 8.476257, 6.653564, -0.43, -0.45 -GPS, 3, 594551600, 8, 2.26, 44.0290147, -77.7367053, 12.37, 97.47, 0.17, 320.81 -CTUN, 0, 0.00, 12.76, 9.947046, 0, 0, -248, 282, -250 -NTUN, 0.14, 2.64, -1.513092, -13.493286, -1.513092, -13.493286, 9.195786, -1.516436, 9.003324, 11.681104, -0.42, -0.74 -ATT, 0.00, 2.36, 0.00, 0.65, 0.00, 82.26, 83.10 -NTUN, 0.13, 2.63, -1.088898, -12.992554, -1.088898, -12.992554, 1.629563, 0.404807, 21.284792, 9.057903, -1.16, -0.68 -CTUN, 0, 0.00, 12.44, 9.623336, 0, 0, -255, 274, -250 -ATT, 0.00, -0.53, 0.00, -0.33, 0.00, 82.91, 83.10 -GPS, 3, 594551800, 8, 2.26, 44.0290148, -77.7367052, 11.81, 96.94, 0.07, 320.81 -NTUN, 0.13, 2.66, 0.004272, -12.519897, 0.004272, -12.519897, -0.188482, 0.372359, 28.937912, 8.296875, -1.62, -0.68 -CTUN, 0, 0.00, 11.85, 9.346166, 0, 0, -253, 254, -250 -ATT, 0.00, -0.99, 0.00, -2.30, 0.00, 83.50, 83.10 -NTUN, 0.12, 2.71, 0.893585, -12.217224, 0.893585, -12.217224, -1.094132, -0.492882, 28.805077, 7.996766, -1.62, -0.64 -CTUN, 0, 0.00, 11.45, 8.896846, 0, 0, -259, 300, -250 -GPS, 3, 594552000, 8, 2.26, 44.0290148, -77.7367052, 11.30, 96.43, 0.07, 320.81 -ATT, 0.00, -1.18, 0.00, -0.06, 0.00, 83.92, 83.10 -NTUN, 0.12, 2.71, 1.946991, -11.903076, 1.946991, -11.903076, -2.581181, -0.207863, 34.534058, 7.141479, -1.96, -0.62 -CTUN, 0, 0.00, 11.86, 8.669856, 0, 0, -253, 266, -250 -ATT, 0.00, -1.05, 0.00, 1.03, 0.00, 83.82, 83.10 -NTUN, 0.12, 2.80, 2.970642, -11.573303, 2.970642, -11.573303, -3.161332, -1.753131, 36.236511, 9.297729, -2.04, -0.76 -CTUN, 0, 0.00, 12.00, 8.418716, 0, 0, -254, 284, -250 -GPS, 3, 594552200, 8, 2.26, 44.0290148, -77.7367052, 10.91, 95.91, 0.03, 320.81 -NTUN, 0.11, 2.85, 3.948730, -11.244324, 3.948730, -11.244324, -2.748631, -1.890740, 35.684044, 8.257223, -2.02, -0.69 -ATT, 0.00, -2.46, 0.00, -1.07, 0.00, 84.02, 83.10 -CTUN, 0, 0.00, 11.14, 7.995596, 0, 0, -253, 242, -250 -NTUN, 0.11, 2.90, 4.796265, -10.764954, 4.796265, -10.764954, -3.424895, -3.911499, 37.475342, 12.793701, -2.10, -0.96 -ATT, 0.00, -0.99, 0.00, -0.85, 0.00, 84.14, 83.10 -GPS, 3, 594552400, 8, 2.26, 44.0290148, -77.7367055, 10.48, 95.39, 0.04, 320.81 -NTUN, 0.11, 2.95, 5.407654, -10.072327, 5.407654, -10.072327, 1.076130, -5.126287, 31.113892, 16.926270, -1.71, -1.15 -CTUN, 0, 0.00, 11.35, 7.918826, 0, 0, -253, 306, -250 -ATT, 0.00, -3.76, 0.00, -0.84, 0.00, 84.83, 83.10 -NTUN, 0.11, 2.99, 5.418915, -9.160217, 5.418915, -9.160217, 3.071300, -4.781685, 23.112610, 18.121094, -1.25, -1.16 -CTUN, 0, 0.00, 11.00, 7.519937, 0, 0, -268, 272, -250 -GPS, 3, 594552600, 8, 2.26, 44.0290147, -77.7367057, 9.93, 94.88, 0.10, 320.81 -ATT, 0.00, -2.23, 0.00, -1.61, 0.00, 85.31, 83.10 -NTUN, 0.10, 3.03, 5.460693, -8.210938, 5.460693, -8.210938, 3.283645, -6.386377, 23.417786, 21.492798, -1.25, -1.36 -CTUN, 0, 0.00, 11.16, 7.242316, 0, 0, -263, 230, -250 -NTUN, 0.09, 3.06, 5.395203, -7.237671, 5.395203, -7.237671, 4.620457, -4.749926, 20.345093, 20.732666, -1.08, -1.30 -ATT, 0.00, 1.94, 0.00, -0.71, 0.00, 85.08, 83.10 -CTUN, 0, 0.00, 11.08, 6.917006, 0, 0, -269, 296, -250 -GPS, 3, 594552800, 8, 2.26, 44.0290148, -77.7367059, 9.49, 94.34, 0.11, 320.81 -NTUN, 0.09, 3.06, 5.127258, -6.421387, 5.127258, -6.421387, 5.898046, -2.639202, 18.320557, 18.162842, -0.97, -1.14 -CTUN, 0, 0.00, 10.39, 6.716346, 0, 0, -274, 279, -250 -ATT, 0.00, -3.54, 0.00, -2.80, 0.00, 85.30, 83.10 -NTUN, 0.08, 3.08, 4.800812, -5.811768, 4.800812, -5.811768, 3.478981, -3.047536, 18.735535, 17.096191, -1.00, -1.08 -CTUN, 0, 0.00, 8.82, 6.468656, 0, 0, -273, 285, -250 -GPS, 3, 594553000, 8, 2.26, 44.0290149, -77.7367061, 9.02, 93.82, 0.05, 320.81 -ATT, 0.00, -1.16, 0.00, 0.48, 0.00, 84.92, 83.10 -NTUN, 0.07, 3.12, 4.731476, -5.035095, 4.731476, -5.035095, 1.239278, -5.247552, 23.313505, 20.689825, -1.24, -1.32 -CTUN, 0, 0.00, 10.46, 6.143106, 0, 0, -281, 304, -250 -NTUN, 0.06, 3.17, 4.765076, -4.292419, 4.765076, -4.292419, 0.215360, -3.303450, 25.339392, 20.501776, -1.35, -1.33 -ATT, 0.00, 1.94, 0.00, 1.35, 0.00, 84.25, 83.10 -CTUN, 0, 0.00, 8.71, 5.915746, 0, 0, -276, 275, -250 -GPS, 3, 594553200, 8, 2.26, 44.0290150, -77.7367063, 8.62, 93.30, 0.08, 320.81 -NTUN, 0.06, 3.17, 5.014496, -3.521973, 5.014496, -3.521973, -3.738454, -5.106814, 32.469505, 21.628185, -1.76, -1.44 -CTUN, 0, 0.00, 8.59, 5.665306, 0, 0, -278, 308, -250 -ATT, 0.00, -1.62, 0.00, -2.12, 0.00, 84.53, 83.10 -NTUN, 0.06, 3.26, 5.339966, -2.505554, 5.339966, -2.505554, -2.827499, -6.184464, 33.254700, 26.164185, -1.79, -1.70 -CTUN, 0, 0.00, 7.67, 5.413916, 0, 0, -275, 282, -250 -ATT, 0.00, -4.35, 0.00, -1.78, 0.00, 84.78, 83.10 -GPS, 3, 594553400, 8, 2.26, 44.0290152, -77.7367064, 8.08, 92.74, 0.08, 320.81 -NTUN, 0.05, 3.36, 5.657684, -1.619080, 5.657684, -1.619080, -3.828432, -6.036046, 35.209278, 25.954288, -1.90, -1.69 -CTUN, 0, 0.00, 7.70, 5.139246, 0, 0, -269, 295, -250 -ATT, 0.00, -1.10, 0.00, -0.30, 0.00, 84.53, 83.10 -NTUN, 0.05, 3.48, 5.721069, -0.733887, 5.721069, -0.733887, -0.603568, -4.417097, 29.627575, 25.764286, -1.57, -1.66 -CTUN, 0, 0.00, 7.87, 4.911716, 0, 0, -264, 270, -250 -GPS, 3, 594553600, 8, 2.26, 44.0290149, -77.7367064, 7.53, 92.21, 0.12, 320.81 -ATT, 0.00, -2.68, 0.00, -2.75, 0.00, 84.16, 83.10 -NTUN, 0.05, 3.56, 5.629517, -0.293884, 5.629517, -0.293884, 0.775808, -1.142054, 26.084473, 18.400024, -1.40, -1.22 -CTUN, 132, 0.00, 6.43, 4.663595, 0, 0, -262, 286, -250 -ATT, 0.00, -3.95, 0.00, -2.71, 0.00, 84.05, 83.10 -NTUN, 0.05, 3.56, 5.539825, 0.037048, 5.539825, 0.037048, 2.406527, -2.820111, 25.111969, 19.276560, -1.34, -1.27 -GPS, 3, 594553800, 8, 2.26, 44.0290151, -77.7367067, 7.01, 91.67, 0.05, 320.81 -CTUN, 141, 0.00, 6.46, 4.496947, 0, 0, -259, 315, -165 -NTUN, 0.05, 0.01, 5.091949, 0.205444, 5.091949, 0.205444, 8.062740, 3.062338, 16.521240, 13.683960, -0.87, -0.89 -ATT, 0.00, -1.96, 0.00, -2.38, 0.00, 83.67, 83.10 -DU32, 7, 426225 -CURR, 163, 277172, 1364, 1992, 4876, 446.555660 -NTUN, 0.05, 0.02, 3.721985, 0.195190, 3.721985, 0.195190, 14.105630, 1.074877, -0.838026, 13.896425, 0.13, -0.80 -CTUN, 198, 0.00, 5.94, 4.233568, 0, 0, -241, 320, -135 -ATT, 0.00, -3.67, 0.00, -2.14, 0.00, 83.56, 83.10 -GPS, 3, 594554000, 8, 2.26, 44.0290147, -77.7367069, 6.40, 91.23, 0.12, 320.81 -NTUN, 0.05, 0.02, 2.292084, 0.301453, 2.292084, 0.301453, 16.381807, 3.208166, -6.157436, 12.052101, 0.43, -0.65 -CTUN, 260, 0.00, 5.89, 4.125107, 0, 0, -219, 331, -91 -ATT, 0.00, 1.16, 0.00, -2.19, 0.00, 82.85, 83.10 -NTUN, 0.02, 0.08, 1.149109, 0.233704, 1.149109, 0.233704, 15.788677, 3.524395, -4.429749, 9.322510, 0.32, -0.50 -GPS, 3, 594554200, 8, 2.26, 44.0290148, -77.7367066, 5.95, 90.73, 0.15, 320.81 -ATT, 0.00, 1.73, 0.00, -1.30, 0.00, 81.89, 83.10 -CTUN, 342, 0.00, 6.01, 4.026579, 0, 0, -189, 320, -51 -NTUN, 0.01, 0.25, 0.118530, 0.155151, 0.118530, 0.155151, 12.938552, 1.980539, -1.305786, 11.214478, 0.16, -0.63 -NTUN, 0.00, 1.35, -0.128906, 0.087219, -0.128906, 0.087219, 5.079386, 1.723767, 12.550134, 11.327405, -0.62, -0.76 -ATT, 0.00, 1.53, 0.00, 1.05, 0.00, 81.50, 83.10 -CTUN, 362, 0.00, 5.66, 3.981962, 0, 0, -151, 309, -27 -GPS, 3, 594554400, 8, 2.26, 44.0290150, -77.7367064, 5.64, 90.35, 0.20, 320.81 -NTUN, 0.00, 1.35, -0.129242, -0.046021, -0.129242, -0.046021, 4.361028, -0.561546, 15.996643, 11.667603, -0.81, -0.81 -CTUN, 359, 0.00, 5.23, 3.958896, 0, 0, -126, 301, -23 -ATT, 0.00, -2.61, 0.00, -1.64, 0.00, 81.24, 83.10 -NTUN, 0.00, 2.13, 0.165253, -0.107300, 0.165253, -0.107300, 0.308259, 1.145796, 22.944946, 11.387207, -1.22, -0.85 -CTUN, 359, 0.00, 4.59, 3.928468, 0, 0, -110, 249, -25 -ATT, 0.00, -0.59, 0.00, -2.13, 0.00, 81.49, 83.10 -GPS, 3, 594554600, 8, 2.26, 44.0290148, -77.7367064, 5.34, 90.06, 0.04, 320.81 -NTUN, 0.00, 2.13, 0.761475, -0.270447, 0.761475, -0.270447, 0.131982, -0.136696, 25.903187, 11.384684, -1.40, -0.87 -CTUN, 359, 0.00, 4.70, 3.908747, 0, 0, -108, 318, -25 -ATT, 0.00, -0.23, 0.00, 1.12, 0.00, 81.84, 83.10 -NTUN, 0.00, 3.45, 1.487366, -0.204041, 1.487366, -0.204041, 0.195109, -1.257387, 28.332233, 14.670771, -1.51, -1.08 -GPS, 3, 594554800, 8, 2.26, 44.0290147, -77.7367070, 5.12, 89.86, 0.18, 320.81 -CTUN, 359, 0.00, 5.07, 3.878668, 0, 0, -119, 273, -25 -NTUN, 0.01, 3.54, 2.388458, -0.020935, 2.388458, -0.020935, -1.259392, -0.409192, 32.010925, 14.831055, -1.72, -1.12 -ATT, 0.00, -0.70, 0.00, -1.06, 0.00, 81.62, 83.10 -CTUN, 361, 0.00, 4.39, 3.836271, 0, 0, -103, 271, -25 -NTUN, 0.01, 3.54, 3.238892, 0.787292, 3.238892, 0.787292, 0.599214, -4.453668, 31.420132, 26.002253, -1.59, -1.77 -ATT, 0.00, -2.54, 0.00, -1.23, 0.00, 81.72, 83.10 -GPS, 3, 594555000, 8, 2.26, 44.0290146, -77.7367070, 4.89, 89.61, 0.18, 320.81 -NTUN, 0.03, 0.16, 4.020874, 1.780090, 4.020874, 1.780090, -0.867713, -3.964053, 32.898811, 29.028261, -1.66, -1.95 -CTUN, 359, 0.00, 4.23, 3.798733, 0, 0, -105, 262, -25 -ATT, 0.00, -0.72, 0.00, -1.15, 0.00, 81.65, 83.10 -NTUN, 0.04, 0.26, 4.745239, 2.526978, 4.745239, 2.526978, 1.859094, -4.205953, 30.243652, 27.468872, -1.51, -1.84 -GPS, 3, 594555200, 8, 2.26, 44.0290144, -77.7367070, 4.66, 89.42, 0.06, 320.81 -ATT, 0.00, -1.34, 0.00, -0.91, 0.00, 81.87, 83.10 -CTUN, 359, 0.00, 4.11, 3.783710, 0, 0, -100, 333, -25 -NTUN, 0.05, 0.31, 5.304657, 3.379456, 5.304657, 3.379456, 1.533070, -4.465644, 29.484488, 29.357628, -1.46, -1.94 -CTUN, 359, 0.00, 4.14, 3.736180, 0, 0, -89, 225, -25 -NTUN, 0.06, 0.33, 5.944611, 3.915161, 5.944611, 3.915161, 1.528400, -3.099164, 31.464178, 27.411167, -1.59, -1.84 -ATT, 0.00, -0.66, 0.00, -2.14, 0.00, 81.97, 83.10 -GPS, 3, 594555400, 8, 2.26, 44.0290141, -77.7367071, 4.41, 89.23, 0.10, 320.81 -NTUN, 0.06, 0.33, 6.643402, 4.533325, 6.643402, 4.533325, 2.221943, -4.505783, 31.987915, 30.181641, -1.60, -2.00 -CTUN, 362, 0.00, 3.87, 3.728276, 0, 0, -88, 346, -25 -ATT, 0.00, -1.61, 0.00, -1.06, 0.00, 82.25, 83.10 -PM, 0, 0, 50, 158, 1000, 11892, 10, 0 -NTUN, 0.08, 0.34, 7.411804, 4.935181, 7.411804, 4.935181, 2.040256, -1.224802, 34.684021, 25.018555, -1.81, -1.71 -CTUN, 368, 0.00, 3.74, 3.687183, 0, 0, -76, 291, -23 -GPS, 3, 594555600, 8, 2.25, 44.0290142, -77.7367073, 4.23, 89.03, 0.05, 320.81 -ATT, 0.00, -0.68, 0.00, -2.72, 0.00, 82.76, 83.10 -NTUN, 0.08, 0.33, 8.225281, 5.244812, 8.225281, 5.244812, 1.491918, -1.831028, 36.054222, 26.065657, -1.89, -1.77 -CTUN, 382, 0.00, 3.79, 3.670609, 0, 0, -73, 359, -12 -NTUN, 0.09, 0.32, 8.570496, 5.562927, 8.570496, 5.562927, 4.958934, 1.340474, 28.487019, 23.213285, -1.47, -1.55 -ATT, 0.00, -2.53, 0.00, -1.88, 0.00, 82.77, 83.10 -GPS, 3, 594555800, 8, 2.25, 44.0290143, -77.7367073, 4.03, 88.87, 0.08, 320.81 -CTUN, 399, 0.00, 3.52, 3.664502, 0, 0, -46, 270, -3 -NTUN, 0.09, 0.32, 8.800568, 5.544067, 8.800568, 5.544067, 3.159638, 1.340600, 29.277941, 19.813269, -1.55, -1.35 -ATT, 0.00, -1.03, 0.00, -1.88, 0.00, 83.09, 83.10 -CTUN, 405, 0.00, 3.71, 3.664502, 0, 0, -30, 320, 0 -NTUN, 0.10, 0.32, 8.669830, 5.550476, 8.669830, 5.550476, 8.901179, 2.233142, 20.679420, 19.064734, -1.06, -1.25 -ATT, 0.00, -2.53, 0.00, -0.95, 0.00, 82.99, 83.10 -GPS, 3, 594556000, 8, 2.25, 44.0290143, -77.7367072, 3.93, 88.78, 0.08, 320.81 -DU32, 7, 426225 -CURR, 408, 282261, 1372, 1729, 5006, 456.199310 -NTUN, 0.10, 0.32, 8.200317, 5.324463, 8.200317, 5.324463, 8.218399, 2.540105, 17.396931, 15.784184, -0.90, -1.03 -CTUN, 411, 0.00, 3.70, 3.664502, 0, 0, -14, 278, 0 -ATT, 0.00, -1.91, 0.00, -1.31, 0.00, 83.35, 83.10 -NTUN, 0.09, 0.33, 7.715515, 5.182983, 7.715515, 5.182983, 11.634118, 0.853672, 14.103008, 19.570915, -0.68, -1.23 -CTUN, 410, 0.00, 3.91, 3.664502, 0, 0, -9, 269, 0 -GPS, 3, 594556200, 8, 2.25, 44.0290144, -77.7367072, 3.91, 88.77, 0.06, 320.81 -ATT, 0.00, -2.30, 0.00, -0.31, 0.00, 83.63, 83.10 -NTUN, 0.09, 0.36, 6.871124, 5.090271, 6.871124, 5.090271, 12.111898, 1.301299, 8.556091, 19.072876, -0.37, -1.16 -CTUN, 409, 0.00, 4.05, 3.664502, 0, 0, -8, 276, 0 -ATT, 0.00, -0.87, 0.00, -0.50, 0.00, 83.65, 83.10 -NTUN, 0.08, 0.39, 5.987061, 5.091492, 5.987061, 5.091492, 13.656004, 0.236641, 6.246894, 21.012087, -0.22, -1.26 -GPS, 3, 594556400, 8, 2.25, 44.0290145, -77.7367072, 3.88, 88.79, 0.08, 320.81 -NTUN, 0.07, 0.45, 4.985779, 5.156860, 4.985779, 5.156860, 13.339834, -0.322295, 2.987183, 22.653687, -0.03, -1.33 -CTUN, 410, 0.00, 3.84, 3.664502, 0, 0, -9, 286, 0 -ATT, 0.00, -0.82, 0.00, -1.13, 0.00, 83.86, 83.10 -NTUN, 0.07, 0.51, 4.078033, 5.321350, 4.078033, 5.321350, 12.783135, -0.778271, 3.830854, 25.661512, -0.06, -1.51 -CTUN, 410, 0.00, 3.74, 3.664502, 0, 0, -14, 282, 0 -ATT, 0.00, -0.52, 0.00, -1.12, 0.00, 83.82, 83.10 -GPS, 3, 594556600, 8, 2.25, 44.0290146, -77.7367071, 3.86, 88.79, 0.11, 320.81 -NTUN, 0.07, 0.51, 3.282654, 5.357971, 3.282654, 5.357971, 11.874038, -0.122577, 4.202160, 23.359030, -0.09, -1.38 -CTUN, 410, 0.00, 3.65, 3.664502, 0, 0, -14, 294, 0 -ATT, 0.00, -0.11, 0.00, -1.65, 0.00, 83.84, 83.10 -NTUN, 0.06, 0.60, 2.642242, 5.353638, 2.642242, 5.353638, 10.885531, 0.140390, 5.531198, 22.956228, -0.17, -1.36 -GPS, 3, 594556800, 8, 2.25, 44.0290146, -77.7367070, 3.83, 88.76, 0.12, 320.81 -CTUN, 409, 0.00, 3.72, 3.664502, 0, 0, -15, 274, 0 -NTUN, 0.05, 0.65, 2.183319, 5.229126, 2.183319, 5.229126, 9.499699, 0.388227, 8.410767, 20.754883, -0.35, -1.25 -ATT, 0.00, -0.29, 0.00, -1.33, 0.00, 83.73, 83.10 -CTUN, 410, 0.00, 3.69, 3.664502, 0, 0, -16, 285, 0 -NTUN, 0.05, 0.68, 1.935974, 5.096985, 1.935974, 5.096985, 9.008889, 0.197921, 9.551040, 20.691671, -0.42, -1.26 -ATT, 0.00, -0.47, 0.00, -0.64, 0.00, 83.65, 83.10 -GPS, 3, 594557000, 8, 2.25, 44.0290146, -77.7367069, 3.77, 88.74, 0.11, 320.81 -NTUN, 0.05, 0.69, 1.799408, 4.857239, 1.799408, 4.857239, 7.809473, 0.760704, 11.634338, 20.602539, -0.54, -1.27 -CTUN, 410, 0.00, 3.69, 3.664502, 0, 0, -15, 283, 0 -ATT, 0.00, -0.36, 0.00, -1.63, 0.00, 83.65, 83.10 -NTUN, 0.05, 0.68, 1.816315, 4.608582, 1.816315, 4.608582, 7.396098, 0.738901, 14.170775, 19.488312, -0.69, -1.22 -CTUN, 410, 0.00, 3.51, 3.664502, 0, 0, -12, 291, 0 -GPS, 3, 594557200, 8, 2.25, 44.0290145, -77.7367068, 3.75, 88.72, 0.11, 320.81 -NTUN, 0.04, 0.65, 1.986328, 4.303589, 1.986328, 4.303589, 6.360699, 1.000431, 16.666798, 19.009876, -0.84, -1.21 -ATT, 0.00, -0.53, 0.00, -1.27, 0.00, 83.57, 83.10 -CTUN, 430, 0.00, 3.28, 3.664502, 0, 0, -9, 287, 0 -NTUN, 0.04, 0.65, 2.320068, 4.005310, 2.320068, 4.005310, 5.801785, 0.762260, 18.371113, 18.987083, -0.94, -1.22 -ATT, 0.00, -0.58, 0.00, -0.84, 0.00, 83.47, 83.10 -GPS, 3, 594557400, 8, 2.25, 44.0290144, -77.7367067, 3.71, 88.70, 0.09, 320.81 -NTUN, 0.04, 0.58, 2.711060, 3.664978, 2.711060, 3.664978, 5.626701, 1.066587, 19.909912, 17.596680, -1.03, -1.15 -CTUN, 698, 0.00, 3.17, 3.664502, 0, 0, -7, 283, 0 -ATT, 0.00, -0.89, 0.00, -1.45, 0.00, 83.43, 83.10 -NTUN, 0.04, 0.52, 3.199524, 3.372681, 3.199524, 3.372681, 5.168029, -0.037111, 21.836281, 19.105967, -1.13, -1.25 -CTUN, 948, 0.00, 3.20, 3.888857, 0, 0, -2, 357, 189 -GPS, 3, 594557600, 8, 2.25, 44.0290142, -77.7367065, 3.66, 88.70, 0.12, 320.81 -NTUN, 0.04, 0.39, 3.786011, 3.060120, 3.786011, 3.060120, 5.250757, 1.106120, 22.864868, 16.874390, -1.21, -1.13 -ATT, 0.00, -0.91, 0.00, -1.29, 0.00, 83.37, 83.10 -CTUN, 997, 0.00, 3.12, 4.182619, 0, 0, 14, 397, 248 -NTUN, 0.04, 0.39, 4.388550, 2.484863, 4.388550, 2.484863, 6.396073, 3.211353, 22.086254, 13.189329, -1.19, -0.91 -ATT, 0.00, -1.12, 0.00, -3.32, 0.00, 83.34, 83.10 -GPS, 3, 594557800, 8, 2.25, 44.0290139, -77.7367063, 3.66, 88.70, 0.09, 320.81 -CTUN, 997, 0.00, 3.30, 4.454082, 0, 0, 60, 341, 248 -NTUN, 0.05, 0.27, 5.026123, 1.669861, 5.026123, 1.669861, 6.966772, 4.481855, 23.312607, 8.930669, -1.28, -0.67 -ATT, 0.00, -1.06, 0.00, -1.46, 0.00, 83.11, 83.10 -NTUN, 0.05, 0.15, 5.673920, 0.645508, 5.673920, 0.645508, 8.694717, 7.337366, 21.477966, 2.756470, -1.22, -0.31 -GPS, 3, 594558000, 8, 2.25, 44.0290135, -77.7367060, 3.84, 88.79, 0.10, 320.81 -ATT, 0.00, -1.47, 0.00, -0.75, 0.00, 83.06, 83.10 -NTUN, 0.05, 0.02, 6.348724, -0.463745, 6.348724, -0.463745, 8.904783, 3.889812, 22.748047, 3.907471, -1.29, -0.38 -CTUN, 996, 0.00, 3.79, 4.974617, 0, 0, 137, 349, 248 -ATT, 0.00, -1.56, 0.00, 0.43, 0.00, 82.94, 83.10 -NTUN, 0.06, 3.51, 7.124634, -1.396851, 7.124634, -1.396851, 10.751319, 4.610923, 22.759094, 3.668945, -1.29, -0.37 -CTUN, 997, 0.00, 4.44, 5.322303, 0, 0, 163, 256, 248 -GPS, 3, 594558200, 8, 2.25, 44.0290136, -77.7367056, 4.09, 89.06, 0.29, 320.81 -NTUN, 0.07, 3.45, 7.721619, -2.291809, 7.721619, -2.291809, 10.186192, 0.669095, 21.910740, 7.139025, -1.21, -0.56 -ATT, 0.00, -1.00, 0.00, -1.06, 0.00, 83.07, 83.10 -CTUN, 997, 0.00, 4.42, 5.571525, 0, 0, 178, 303, 247 -NTUN, 0.08, 3.40, 8.038116, -2.873169, 8.038116, -2.873169, 11.556996, -1.197208, 17.164978, 11.186401, -0.91, -0.77 -CTUN, 997, 0.00, 4.96, 5.869033, 0, 0, 171, 283, 248 -ATT, 0.00, -1.09, 0.00, 0.41, 0.00, 83.06, 83.10 -GPS, 3, 594558400, 8, 2.25, 44.0290134, -77.7367056, 4.52, 89.40, 0.29, 320.81 -NTUN, 0.08, 3.40, 8.333069, -3.320740, 8.333069, -3.320740, 11.015637, -2.776326, 17.920321, 13.568605, -0.94, -0.91 -CTUN, 996, 0.00, 5.24, 5.968478, 0, 0, 173, 266, 248 -ATT, 0.00, -1.13, 0.00, -0.01, 0.00, 83.36, 83.10 -NTUN, 0.08, 3.38, 8.844910, -3.256531, 8.844910, -3.256531, 10.688743, -6.032141, 21.170109, 20.648575, -1.08, -1.34 -CTUN, 996, 0.00, 5.57, 6.312869, 0, 0, 161, 319, 248 -GPS, 3, 594558600, 8, 2.25, 44.0290134, -77.7367052, 4.89, 89.74, 0.21, 320.81 -NTUN, 0.08, 3.38, 9.235779, -3.271912, 9.235779, -3.271912, 11.551288, -5.413055, 18.908691, 20.846191, -0.95, -1.33 -ATT, 0.00, -1.17, 0.00, -1.43, 0.00, 83.36, 83.10 -CTUN, 997, 0.00, 5.42, 6.611866, 0, 0, 163, 295, 248 -NTUN, 0.09, 3.40, 9.576294, -3.281616, 9.576294, -3.281616, 11.079691, -8.319920, 19.405151, 23.902954, -0.96, -1.51 -ATT, 0.00, -1.13, 0.00, -1.30, 0.00, 83.36, 83.10 -CTUN, 997, 0.00, 5.47, 6.860828, 0, 0, 164, 315, 248 -GPS, 3, 594558800, 8, 2.25, 44.0290138, -77.7367051, 5.19, 90.12, 0.21, 320.81 -NTUN, 0.10, 3.41, 9.607147, -3.283997, 9.607147, -3.283997, 11.445112, -6.957796, 16.308533, 21.976196, -0.79, -1.38 -CTUN, 997, 0.00, 5.84, 7.157972, 0, 0, 173, 276, 248 -ATT, 0.00, -0.63, 0.00, -1.34, 0.00, 83.28, 83.10 -NTUN, 0.10, 3.40, 9.355347, -3.245605, 9.355347, -3.245605, 10.982143, -9.497841, 13.506926, 25.380110, -0.60, -1.56 -CTUN, 997, 0.00, 6.03, 7.254712, 0, 0, 174, 317, 248 -GPS, 3, 594559000, 8, 2.25, 44.0290139, -77.7367049, 5.48, 90.40, 0.15, 320.81 -ATT, 0.00, -0.73, 0.00, -0.28, 0.00, 83.28, 83.10 -NTUN, 0.09, 3.40, 9.084290, -3.155518, 9.084290, -3.155518, 10.533403, -8.607696, 13.316266, 25.891960, -0.59, -1.59 -CTUN, 996, 0.00, 6.38, 7.628770, 0, 0, 176, 284, 248 -NTUN, 0.09, 3.40, 8.866913, -3.221985, 8.866913, -3.221985, 9.173315, -9.899077, 14.804276, 25.328613, -0.68, -1.56 -ATT, 0.00, -0.72, 0.00, -1.93, 0.00, 83.40, 83.10 -GPS, 3, 594559200, 8, 2.25, 44.0290143, -77.7367047, 5.98, 90.76, 0.32, 346.48 -CTUN, 996, 0.00, 6.46, 7.902206, 0, 0, 176, 327, 248 -NTUN, 0.09, 3.40, 8.576965, -3.267578, 8.576965, -3.267578, 8.298918, -8.100377, 14.364114, 23.585516, -0.67, -1.46 -ATT, 0.00, -0.43, 0.00, -2.14, 0.00, 83.37, 83.10 -CTUN, 997, 0.00, 6.49, 8.247471, 0, 0, 192, 300, 248 -NTUN, 0.09, 3.38, 8.117157, -3.569214, 8.117157, -3.569214, 6.991155, -8.939245, 13.401917, 21.983643, -0.63, -1.36 -ATT, 0.00, -0.60, 0.00, -1.49, 0.00, 83.43, 83.10 -GPS, 3, 594559400, 8, 2.25, 44.0290149, -77.7367049, 6.42, 91.12, 0.30, 349.59 -CTUN, 997, 0.00, 6.91, 8.544685, 0, 0, 200, 325, 247 -NTUN, 0.09, 3.38, 7.437988, -3.699463, 7.437988, -3.699463, 6.495102, -7.448274, 10.275558, 21.710405, -0.45, -1.32 -ATT, 0.00, -0.92, 0.00, -1.57, 0.00, 83.41, 83.10 -NTUN, 0.08, 3.32, 6.527100, -3.856079, 6.527100, -3.856079, 5.143025, -7.987159, 8.891113, 23.433838, -0.35, -1.41 -CTUN, 996, 0.00, 7.19, 8.792692, 0, 0, 212, 301, 248 -GPS, 3, 594559600, 8, 2.25, 44.0290151, -77.7367048, 6.72, 91.49, 0.16, 349.59 -NTUN, 0.07, 3.25, 5.700043, -3.953979, 5.700043, -3.953979, 4.410153, -7.954855, 9.645890, 24.011106, -0.39, -1.45 -ATT, 0.00, -0.61, 0.00, -1.04, 0.00, 83.42, 83.10 -CTUN, 996, 0.00, 7.41, 9.165089, 0, 0, 218, 280, 247 -NTUN, 0.07, 3.25, 4.985046, -4.171570, 4.985046, -4.171570, 2.843244, -7.642245, 11.920829, 21.845640, -0.54, -1.34 -ATT, 0.00, -0.45, 0.00, -1.33, 0.00, 83.51, 83.10 -GPS, 3, 594559800, 8, 2.25, 44.0290155, -77.7367048, 7.28, 91.92, 0.16, 349.59 -CTUN, 997, 0.00, 7.52, 9.388742, 0, 0, 216, 307, 247 -NTUN, 0.07, 3.25, 4.171143, -4.390259, 4.171143, -4.390259, 1.957283, -6.688451, 10.860962, 20.813110, -0.49, -1.27 -ATT, 0.00, -0.73, 0.00, -1.53, 0.00, 83.58, 83.10 -CTUN, 996, 0.00, 7.89, 9.734226, 0, 0, 212, 305, 248 -NTUN, 0.06, 3.11, 3.333252, -4.744324, 3.333252, -4.744324, 1.369547, -5.698418, 9.621094, 17.459351, -0.44, -1.07 -GPS, 3, 594560000, 8, 2.25, 44.0290163, -77.7367049, 7.74, 92.30, 0.24, 349.59 -CTUN, 996, 0.00, 8.15, 9.910644, 0, 0, 213, 301, 248 -ATT, 0.00, -0.61, 0.00, -1.32, 0.00, 83.59, 83.10 -NTUN, 0.05, 2.94, 2.104614, -5.048523, 2.104614, -5.048523, -0.316976, -5.408750, 6.835271, 17.988127, -0.27, -1.08 -CTUN, 996, 0.00, 8.26, 10.131017, 0, 0, 216, 314, 247 -NTUN, 0.05, 2.78, 0.666321, -5.350769, 0.666321, -5.350769, -0.676248, -4.543587, 3.471784, 17.947010, -0.08, -1.06 -ATT, 0.00, 0.12, 0.00, -1.16, 0.00, 83.44, 83.10 -GPS, 3, 594560200, 8, 2.25, 44.0290169, -77.7367053, 8.20, 92.71, 0.40, 353.03 -CTUN, 997, 0.00, 8.52, 10.405038, 0, 0, 219, 303, 248 -NTUN, 0.05, 2.61, -0.974854, -5.462769, -0.974854, -5.462769, -1.576743, -4.295154, 0.588257, 18.880005, 0.09, -1.09 -ATT, 0.00, -0.60, 0.00, -1.51, 0.00, 83.50, 83.10 -CTUN, 996, 0.00, 8.56, 10.702497, 0, 0, 223, 303, 248 -NTUN, 0.05, 2.61, -2.692017, -5.356873, -2.692017, -5.356873, -2.169222, -4.749678, -0.001614, 22.048475, 0.14, -1.27 -ATT, 0.00, -0.89, 0.00, -0.99, 0.00, 83.57, 83.10 -GPS, 3, 594560400, 8, 2.25, 44.0290173, -77.7367054, 8.61, 93.16, 0.30, 348.46 -NTUN, 0.05, 2.32, -4.399170, -5.221619, -4.399170, -5.221619, -2.791173, -4.627096, -0.902508, 22.339148, 0.19, -1.29 -CTUN, 997, 0.00, 9.07, 11.001359, 0, 0, 225, 316, 247 -ATT, 0.00, -0.13, 0.00, -1.29, 0.00, 83.53, 83.10 -NTUN, 0.06, 2.21, -6.083771, -5.036987, -6.083771, -5.036987, -2.979368, -4.800372, -3.016171, 22.864964, 0.32, -1.30 -CTUN, 996, 0.00, 9.27, 11.220892, 0, 0, 226, 298, 247 -GPS, 3, 594560600, 8, 2.25, 44.0290174, -77.7367056, 8.95, 93.62, 0.10, 348.46 -NTUN, 0.07, 2.12, -7.588440, -4.744019, -7.588440, -4.744019, -3.955300, -5.675300, -0.897715, 23.900681, 0.21, -1.38 -ATT, 0.00, 0.22, 0.00, -1.10, 0.00, 83.44, 83.10 -CTUN, 997, 0.00, 9.61, 11.618021, 0, 0, 231, 293, 247 -NTUN, 0.07, 2.12, -8.812592, -4.333801, -8.812592, -4.333801, -4.941842, -5.430808, 1.634832, 26.143608, 0.07, -1.52 -GPS, 3, 594560800, 8, 2.25, 44.0290175, -77.7367059, 9.59, 94.08, 0.10, 348.46 -ATT, 0.00, -0.19, 0.00, -1.06, 0.00, 83.50, 83.10 -CTUN, 996, 0.00, 9.95, 11.890927, 0, 0, 230, 308, 248 -NTUN, 0.09, 2.02, -9.858185, -3.787842, -9.858185, -3.787842, -5.908094, -5.744977, 3.544067, 27.459595, -0.02, -1.61 -CTUN, 996, 0.00, 10.17, 12.188623, 0, 0, 229, 299, 247 -ATT, 0.00, -0.19, 0.00, -1.54, 0.00, 83.57, 83.10 -NTUN, 0.10, 1.96, -10.729553, -3.135437, -10.729553, -3.135437, -6.444268, -6.096008, 4.372590, 29.459454, -0.06, -1.73 -GPS, 3, 594561000, 8, 2.25, 44.0290179, -77.7367062, 10.10, 94.54, 0.23, 337.71 -CTUN, 996, 0.00, 10.23, 12.414286, 0, 0, 228, 309, 247 -NTUN, 0.11, 1.91, -11.708435, -2.379028, -11.708435, -2.379028, -7.012037, -6.211220, 2.211182, 31.564087, 0.07, -1.84 -ATT, 0.00, -0.02, 0.00, -1.46, 0.00, 83.63, 83.10 -CTUN, 998, 0.00, 10.61, 12.759173, 0, 0, 229, 301, 248 -NTUN, 0.11, 1.91, -12.769257, -1.558838, -12.769257, -1.558838, -7.188292, -6.196007, 0.391785, 34.201904, 0.19, -1.98 -ATT, 0.00, -0.02, 0.00, -1.60, 0.00, 83.64, 83.10 -GPS, 3, 594561200, 8, 2.25, 44.0290181, -77.7367065, 10.49, 95.00, 0.15, 337.71 -NTUN, 0.12, 1.85, -13.791046, -0.673096, -13.791046, -0.673096, -7.908571, -6.258597, 0.883272, 35.769722, 0.18, -2.08 -CTUN, 998, 0.00, 10.84, 12.985241, 0, 0, 230, 312, 248 -ATT, 0.00, 0.11, 0.00, -1.88, 0.00, 83.56, 83.10 -NTUN, 0.13, 1.81, -14.742981, 0.182190, -14.742981, 0.182190, -8.486031, -5.249773, 0.384497, 35.639248, 0.21, -2.07 -CTUN, 998, 0.00, 10.92, 13.280352, 0, 0, 234, 306, 248 -GPS, 3, 594561400, 8, 2.25, 44.0290183, -77.7367068, 10.92, 95.44, 0.16, 337.71 -ATT, 0.00, 0.32, 0.00, -2.01, 0.00, 83.55, 83.10 -NTUN, 0.14, 1.76, -15.633118, 1.028076, -15.633118, 1.028076, -9.217402, -4.456438, 0.273170, 35.293003, 0.21, -2.04 -CTUN, 998, 0.00, 11.16, 13.604557, 0, 0, 236, 311, 248 -NTUN, 0.15, 1.74, -16.462708, 1.760132, -16.462708, 1.760132, -10.093096, -3.376076, 0.620304, 35.394501, 0.19, -2.05 -ATT, 0.00, 0.15, 0.00, -2.02, 0.00, 83.48, 83.10 -GPS, 3, 594561600, 8, 2.25, 44.0290186, -77.7367073, 11.46, 95.89, 0.24, 325.04 -NTUN, 0.15, 1.74, -17.291138, 2.524170, -17.291138, 2.524170, -10.644116, -1.850612, 0.632018, 34.717556, 0.19, -2.01 -CTUN, 998, 0.00, 11.48, 13.853450, 0, 0, 238, 303, 248 -ATT, 0.00, 0.22, 0.00, -2.18, 0.00, 83.38, 83.10 -NTUN, 0.17, 1.71, -18.162628, 3.303955, -18.162628, 3.303955, -10.971177, -1.465330, -1.544024, 34.644951, 0.32, -1.99 -GPS, 3, 594561800, 8, 2.25, 44.0290187, -77.7367079, 11.83, 96.37, 0.24, 325.04 -CTUN, 997, 0.00, 11.89, 14.249207, 0, 0, 241, 303, 248 -ATT, 0.00, -0.16, 0.00, -1.64, 0.00, 83.39, 83.10 -NTUN, 0.18, 1.67, -18.992126, 4.238770, -18.992126, 4.238770, -10.969543, -0.319637, -2.378771, 36.442570, 0.38, -2.09 -CTUN, 997, 0.00, 12.32, 14.650382, 0, 0, 238, 316, 248 -DU32, 7, 426225 -CURR, 997, 296406, 1371, 1830, 4962, 480.683810 -ATT, 0.00, -0.03, 0.00, -1.84, 0.00, 83.38, 83.10 -NTUN, 0.18, 1.67, -19.755768, 5.226196, -19.755768, 5.226196, -11.360648, 0.264259, -1.636414, 36.874268, 0.34, -2.12 -GPS, 3, 594562000, 8, 2.25, 44.0290188, -77.7367084, 12.37, 96.84, 0.14, 325.04 -CTUN, 998, 0.00, 12.43, 14.822960, 0, 0, 240, 306, 248 -NTUN, 0.18, 1.67, -20.466919, 6.241028, -20.466919, 6.241028, -11.031275, 0.906916, -3.041100, 39.047836, 0.44, -2.24 -ATT, 0.00, 0.36, 0.00, -2.23, 0.00, 83.29, 83.10 -CTUN, 998, 0.00, 12.66, 15.168146, 0, 0, 243, 308, 248 -NTUN, 0.21, 1.62, -21.153076, 7.313721, -21.153076, 7.313721, -11.204557, 1.306932, -2.861572, 40.726929, 0.44, -2.34 -ATT, 0.00, 0.08, 0.00, -1.92, 0.00, 83.29, 83.10 -GPS, 3, 594562200, 8, 2.25, 44.0290189, -77.7367088, 12.90, 97.31, 0.14, 325.04 -NTUN, 0.22, 1.59, -21.813873, 8.385803, -21.813873, 8.385803, -11.378093, 1.780061, -4.607971, 40.720825, 0.54, -2.32 -CTUN, 998, 0.00, 13.15, 15.468047, 0, 0, 244, 304, 248 -ATT, 0.00, 0.45, 0.00, -1.98, 0.00, 83.25, 83.10 -NTUN, 0.23, 1.57, -22.449554, 9.468018, -22.449554, 9.468018, -11.369321, 2.119637, -5.356812, 42.822144, 0.60, -2.44 -CTUN, 998, 0.00, 13.46, 15.764188, 0, 0, 246, 306, 248 -GPS, 3, 594562400, 8, 2.25, 44.0290188, -77.7367090, 13.29, 97.77, 0.09, 325.04 -NTUN, 0.24, 1.55, -22.926697, 10.457886, -22.926697, 10.457886, -11.806796, 3.249754, -4.771423, 41.898682, 0.55, -2.39 -ATT, 0.00, 0.43, 0.00, -2.26, 0.00, 83.35, 83.10 -CTUN, 998, 0.00, 13.63, 16.064724, 0, 0, 246, 296, 248 -NTUN, 0.25, 1.54, -23.195160, 11.314026, -23.195160, 11.314026, -12.456424, 3.221462, -1.684631, 41.561401, 0.37, -2.39 -ATT, 0.00, 0.68, 0.00, -2.38, 0.00, 83.41, 83.10 -GPS, 3, 594562600, 8, 2.25, 44.0290187, -77.7367094, 13.91, 98.25, 0.14, 325.04 -NTUN, 0.25, 1.52, -23.280640, 12.248047, -23.280640, 12.248047, -13.077678, 3.694591, -0.854797, 43.340210, 0.33, -2.50 -CTUN, 998, 0.00, 14.11, 16.385923, 0, 0, 247, 295, 248 -ATT, 0.00, 0.58, 0.00, -1.83, 0.00, 83.41, 83.10 -NTUN, 0.25, 1.52, -23.222626, 13.234802, -23.222626, 13.234802, -13.443846, 3.311966, 1.580139, 44.867554, 0.21, -2.61 -ATT, 0.00, 0.08, 0.00, -1.97, 0.00, 83.38, 83.10 -GPS, 3, 594562800, 8, 2.25, 44.0290186, -77.7367099, 14.28, 98.76, 0.15, 325.04 -CTUN, 997, 0.00, 14.67, 16.757170, 0, 0, 246, 296, 248 -NTUN, 0.26, 1.50, -23.054871, 14.367920, -23.054871, 14.367920, -13.975677, 3.157032, 1.660942, 49.218987, 0.23, -2.86 -ATT, 0.00, 0.31, 0.00, -2.38, 0.00, 83.38, 83.10 -CTUN, 998, 0.00, 15.03, 17.155258, 0, 0, 245, 300, 248 -NTUN, 0.27, 1.47, -22.772888, 15.679810, -22.772888, 15.679810, -14.146167, 2.559610, 3.819824, 53.118896, 0.13, -3.10 -GPS, 3, 594563000, 8, 2.25, 44.0290185, -77.7367103, 14.76, 99.22, 0.13, 325.04 -CTUN, 998, 0.00, 15.02, 17.230333, 0, 0, 245, 301, 248 -NTUN, 0.27, 1.43, -22.416870, 17.025574, -22.416870, 17.025574, -14.495801, 3.313393, 4.560181, 54.457642, 0.10, -3.18 -ATT, 0.00, 0.40, 0.00, -2.87, 0.00, 83.38, 83.10 -CTUN, 998, 0.00, 15.27, 17.652885, 0, 0, 244, 299, 248 -NTUN, 0.27, 1.43, -21.981598, 18.351379, -21.981598, 18.351379, -14.882136, 3.577197, 5.309626, 56.126789, 0.07, -3.28 -GPS, 3, 594563200, 8, 2.25, 44.0290183, -77.7367105, 15.38, 99.68, 0.17, 325.04 -ATT, 0.00, 0.13, 0.00, -2.96, 0.00, 83.40, 83.10 -CTUN, 998, 0.00, 15.47, 17.952381, 0, 0, 243, 305, 248 -NTUN, 0.27, 1.43, -21.458038, 19.523376, -21.458038, 19.523376, -14.786576, 4.977973, 7.235596, 54.719971, -0.05, -3.22 -ATT, 0.00, -0.01, 0.00, -3.17, 0.00, 83.45, 83.10 -CTUN, 998, 0.00, 15.57, 18.198961, 0, 0, 244, 295, 248 -NTUN, 0.29, 1.36, -20.822174, 20.480591, -20.822174, 20.480591, -14.930474, 6.249374, 9.422871, 53.668831, -0.18, -3.17 -GPS, 3, 594563400, 8, 2.25, 44.0290181, -77.7367109, 15.89, 100.15, 0.14, 325.04 -CTUN, 998, 0.00, 15.76, 18.375368, 0, 0, 244, 315, 248 -NTUN, 0.29, 1.36, -20.156647, 21.426575, -20.156647, 21.426575, -14.588556, 6.738379, 8.655273, 54.459839, -0.14, -3.21 -ATT, 0.00, -0.15, 0.00, -2.66, 0.00, 83.51, 83.10 -CTUN, 997, 0.00, 16.09, 18.620918, 0, 0, 245, 294, 248 -NTUN, 0.29, 1.32, -19.446411, 22.287109, -19.446411, 22.287109, -14.009761, 8.684884, 9.032036, 53.520145, -0.17, -3.16 -ATT, 0.00, 0.00, 0.00, -3.27, 0.00, 83.52, 83.10 -GPS, 3, 594563600, 8, 2.25, 44.0290178, -77.7367111, 16.35, 100.63, 0.20, 325.04 -CTUN, 998, 0.00, 16.17, 18.945768, 0, 0, 248, 300, 248 -NTUN, 0.29, 1.32, -18.704376, 23.034607, -18.704376, 23.034607, -13.691458, 8.678890, 9.420349, 53.474976, -0.19, -3.16 -ATT, 0.00, -0.13, 0.00, -3.16, 0.00, 83.53, 83.10 -CTUN, 998, 0.00, 16.62, 19.192022, 0, 0, 249, 299, 248 -NTUN, 0.29, 1.28, -17.876678, 23.657227, -17.876678, 23.657227, -13.131404, 9.838223, 11.195027, 52.164551, -0.30, -3.09 -GPS, 3, 594563800, 8, 2.25, 44.0290174, -77.7367113, 16.73, 101.12, 0.23, 263.11 -CTUN, 998, 0.00, 16.85, 19.442768, 0, 0, 249, 301, 248 -NTUN, 0.29, 1.28, -16.919800, 24.237671, -16.919800, 24.237671, -12.998958, 10.360089, 12.568787, 52.804443, -0.38, -3.14 -ATT, 0.00, -0.04, 0.00, -2.85, 0.00, 83.53, 83.10 -CTUN, 998, 0.00, 17.19, 19.639473, 0, 0, 251, 290, 248 -NTUN, 0.29, 1.24, -15.831848, 24.755493, -15.831848, 24.755493, -12.967136, 10.665013, 14.989410, 53.230530, -0.52, -3.18 -ATT, 0.00, -0.16, 0.00, -2.78, 0.00, 83.60, 83.10 -GPS, 3, 594564000, 8, 2.25, 44.0290171, -77.7367113, 17.33, 101.58, 0.23, 263.11 -NTUN, 0.29, 1.24, -14.664368, 25.182373, -14.664368, 25.182373, -12.763027, 11.078400, 16.559212, 53.226532, -0.61, -3.19 -CTUN, 998, 0.00, 17.41, 19.839758, 0, 0, 251, 298, 248 -ATT, 0.00, -0.36, 0.00, -3.08, 0.00, 83.66, 83.10 -NTUN, 0.29, 1.19, -13.465271, 25.500305, -13.465271, 25.500305, -12.722155, 11.384247, 17.990967, 53.179321, -0.70, -3.20 -GPS, 3, 594564200, 8, 2.25, 44.0290168, -77.7367114, 17.70, 102.06, 0.18, 263.11 -CTUN, 998, 0.00, 17.89, 20.210537, 0, 0, 249, 298, 248 -NTUN, 0.28, 1.15, -12.221680, 25.808899, -12.221680, 25.808899, -11.721309, 12.014081, 18.435913, 52.085938, -0.73, -3.13 -ATT, 0.00, -0.72, 0.00, -3.27, 0.00, 83.69, 83.10 -CTUN, 995, 0.00, 18.05, 20.583420, 0, 0, 249, 301, 248 -NTUN, 0.28, 1.13, -11.038116, 26.048950, -11.038116, 26.048950, -11.570343, 12.149454, 17.835632, 52.400513, -0.69, -3.15 -ATT, 0.00, -0.62, 0.00, -3.13, 0.00, 83.70, 83.10 -GPS, 3, 594564400, 8, 2.25, 44.0290166, -77.7367114, 18.29, 102.53, 0.16, 263.11 -CTUN, 910, 0.00, 18.56, 20.798098, 0, 0, 249, 293, 226 -NTUN, 0.28, 1.13, -9.906525, 26.216858, -9.906525, 26.216858, -10.393891, 12.642130, 17.203878, 52.662453, -0.65, -3.16 -ATT, 0.00, -0.62, 0.00, -3.01, 0.00, 83.63, 83.10 -NTUN, 0.28, 1.10, -8.918091, 26.355713, -8.918091, 26.355713, -10.154467, 11.633619, 16.984180, 53.402576, -0.63, -3.20 -CTUN, 687, 0.00, 18.96, 21.022751, 0, 0, 247, 284, 124 -GPS, 3, 594564600, 8, 2.25, 44.0290163, -77.7367113, 18.64, 103.02, 0.18, 212.43 -ATT, 0.00, -0.60, 0.00, -2.10, 0.00, 83.61, 83.10 -NTUN, 0.27, 1.06, -7.844025, 26.561035, -7.844025, 26.561035, -10.100921, 10.717484, 18.634319, 56.032894, -0.71, -3.37 -CTUN, 615, 0.00, 19.04, 21.055010, 0, 0, 231, 272, 11 -ATT, 0.00, -0.11, 0.00, -3.10, 0.00, 83.52, 83.10 -NTUN, 0.27, 1.04, -6.701660, 26.688232, -6.701660, 26.688232, -10.376930, 11.093079, 21.423645, 56.271973, -0.87, -3.40 -CTUN, 616, 0.00, 19.05, 21.065590, 0, 0, 221, 143, 10 -GPS, 3, 594564800, 8, 2.25, 44.0290158, -77.7367110, 19.26, 103.49, 0.31, 171.53 -NTUN, 0.27, 1.01, -5.348389, 26.784668, -5.348389, 26.784668, -10.875407, 8.674450, 25.532715, 59.964355, -1.08, -3.64 -DU32, 7, 426225 -CURR, 616, 303120, 1404, 764, 5006, 491.805690 -ATT, 0.00, -0.44, 0.00, -3.00, 0.00, 83.67, 83.10 -CTUN, 617, 0.00, 19.16, 21.075596, 0, 0, 192, 141, 10 -NTUN, 0.27, 1.01, -3.747345, 26.954041, -3.747345, 26.954041, -11.298211, 5.335559, 29.851917, 64.676956, -1.32, -3.94 -GPS, 3, 594565000, 8, 2.25, 44.0290155, -77.7367108, 19.53, 103.90, 0.22, 165.62 -CTUN, 616, 0.00, 20.62, 21.079565, 0, 0, 177, 204, 10 -ATT, 0.00, -1.55, 0.00, 1.91, 0.00, 83.90, 83.10 -NTUN, 0.27, 0.96, -2.038239, 27.449585, -2.038239, 27.449585, -11.559524, 2.640985, 34.263702, 72.005501, -1.54, -4.38 -CTUN, 616, 0.00, 20.86, 21.098608, 0, 0, 106, 403, 10 -ATT, 0.00, -1.89, 0.00, -1.99, 0.00, 83.92, 83.10 -NTUN, 0.27, 0.93, -0.412231, 27.655884, -0.412231, 27.655884, -9.740337, 10.400590, 33.260071, 63.062988, -1.53, -3.86 -GPS, 3, 594565200, 8, 2.25, 44.0290152, -77.7367107, 19.92, 104.23, 0.22, 165.62 -CTUN, 616, 0.00, 18.82, 21.105671, 0, 0, 115, 130, 10 -NTUN, 0.27, 0.88, 1.159058, 27.183838, 1.159058, 27.183838, -10.002524, 13.978123, 35.557316, 52.326279, -1.70, -3.25 -ATT, 0.00, 0.28, 0.00, -13.98, 0.00, 84.20, 83.10 -NTUN, 0.27, 0.84, 2.652252, 25.946594, 2.652252, 25.946594, -8.926330, 23.095875, 34.931946, 34.627563, -1.78, -2.21 -GPS, 3, 594565400, 8, 2.25, 44.0290148, -77.7367104, 20.12, 104.41, 0.17, 165.62 -ATT, 0.00, -0.18, 0.00, -10.61, 0.00, 84.55, 83.10 -CTUN, 616, 0.00, 17.14, 21.126656, 0, 2, 98, 303, 10 -NTUN, 0.26, 0.81, 4.113068, 23.838379, 4.113068, 23.838379, -7.087343, 28.555670, 35.755711, 18.704895, -1.95, -1.28 -CTUN, 616, 0.00, 18.61, 21.138643, 0, 0, 80, 265, 10 -ATT, 0.00, -3.04, 0.00, -3.95, 0.00, 84.25, 83.10 -NTUN, 0.24, 0.76, 5.420898, 20.910645, 5.420898, 20.910645, -5.916484, 35.868748, 33.948818, 1.012531, -1.96, -0.26 -GPS, 3, 594565600, 8, 2.25, 44.0290144, -77.7367099, 20.12, 104.61, 0.19, 156.69 -CTUN, 616, 0.00, 19.62, 21.142651, 0, 0, 80, 301, 10 -NTUN, 0.21, 0.69, 6.775940, 17.655823, 6.775940, 17.655823, -4.271781, 35.957458, 35.550415, -7.548218, -2.10, 0.21 -ATT, 0.00, -1.82, 0.00, -2.30, 0.00, 83.91, 83.10 -PM, 0, 0, 51, 168, 1015, 11904, 10, 0 -CTUN, 619, 0.00, 20.35, 21.156687, 0, 0, 81, 281, 10 -NTUN, 0.18, 0.62, 7.922913, 14.416809, 7.922913, 14.416809, -2.650217, 33.960388, 32.469727, -9.390137, -1.94, 0.34 -ATT, 0.00, -1.25, 0.00, -3.11, 0.00, 83.90, 83.10 -GPS, 3, 594565800, 8, 2.25, 44.0290139, -77.7367090, 20.24, 104.75, 0.24, 150.66 -CTUN, 618, 0.00, 20.41, 21.166697, 0, 0, 84, 270, 11 -NTUN, 0.18, 0.62, 9.226959, 11.407715, 9.226959, 11.407715, -1.581537, 30.734232, 35.040466, -8.090942, -2.08, 0.24 -ATT, 0.00, -1.98, 0.00, -0.97, 0.00, 83.79, 83.10 -CTUN, 619, 0.00, 21.77, 21.180918, 0, 0, 83, 239, 11 -NTUN, 0.14, 0.48, 10.538330, 8.650024, 10.538330, 8.650024, -1.038846, 27.292252, 35.983871, -5.303865, -2.12, 0.08 -GPS, 3, 594566000, 8, 2.25, 44.0290135, -77.7367080, 20.39, 104.91, 0.40, 136.66 -CTUN, 619, 0.00, 22.22, 21.193125, 0, 0, 72, 268, 11 -ATT, 0.00, -2.51, 0.00, 0.29, 0.00, 83.88, 83.10 -NTUN, 0.13, 0.28, 11.896576, 6.217651, 11.896576, 6.217651, -0.638252, 22.923946, 38.719654, -1.569426, -2.25, -0.14 -CTUN, 618, 0.00, 22.23, 21.204058, 0, 0, 62, 225, 11 -NTUN, 0.13, 0.28, 13.282806, 4.122314, 13.282806, 4.122314, -0.124302, 18.801670, 40.725052, 3.254091, -2.34, -0.44 -ATT, 0.00, -1.24, 0.00, -1.02, 0.00, 83.93, 83.10 -GPS, 3, 594566200, 8, 2.25, 44.0290131, -77.7367070, 20.72, 105.04, 0.40, 126.75 -NTUN, 0.13, 0.28, 14.698395, 2.401978, 14.698395, 2.401978, 1.011932, 13.259786, 41.155884, 10.796631, -2.32, -0.88 -CTUN, 618, 0.00, 22.35, 21.212942, 0, 0, 43, 249, 11 -ATT, 0.00, -2.18, 0.00, -0.49, 0.00, 83.90, 83.10 -NTUN, 0.14, 0.07, 16.092957, 0.932373, 16.092957, 0.932373, 0.909881, 10.005781, 43.807541, 13.449461, -2.46, -1.04 -GPS, 3, 594566400, 8, 2.25, 44.0290127, -77.7367062, 20.85, 105.15, 0.32, 123.48 -CTUN, 618, 0.00, 22.12, 21.228300, 0, 0, 24, 283, 11 -NTUN, 0.16, 0.01, 17.660431, -0.324219, 17.660431, -0.324219, 0.373500, 6.871555, 48.674744, 17.434082, -2.72, -1.30 -ATT, 0.00, -1.58, 0.00, -1.39, 0.00, 84.06, 83.10 -CTUN, 616, 0.00, 21.37, 21.245928, 0, 0, 1, 305, 11 -NTUN, 0.17, 3.57, 19.244324, -1.385864, 19.244324, -1.385864, 1.278768, 4.250948, 49.838928, 21.383545, -2.76, -1.54 -GPS, 3, 594566600, 8, 2.25, 44.0290126, -77.7367054, 20.98, 105.17, 0.32, 123.48 -ATT, 0.00, -2.20, 0.00, -2.07, 0.00, 83.85, 83.10 -CTUN, 616, 0.00, 20.97, 21.259943, 0, 0, 10, 253, 10 -NTUN, 0.17, 3.57, 20.624420, -2.409363, 20.624420, -2.409363, 1.689610, 0.476342, 49.800964, 24.765015, -2.73, -1.75 -ATT, 0.00, -2.95, 0.00, -0.45, 0.00, 83.50, 83.10 -CTUN, 617, 0.00, 21.18, 21.268970, 0, 0, 10, 312, 10 -NTUN, 0.20, 3.52, 21.804993, -3.172119, 21.804993, -3.172119, 4.036016, -2.485523, 47.805725, 29.372437, -2.57, -2.02 -GPS, 3, 594566800, 8, 2.25, 44.0290124, -77.7367048, 21.00, 105.13, 0.22, 123.48 -CTUN, 617, 0.00, 20.89, 21.278976, 0, 0, 17, 255, 10 -NTUN, 0.22, 3.50, 22.672699, -3.940002, 22.672699, -3.940002, 6.283834, -5.103750, 43.677063, 30.321167, -2.32, -2.05 -ATT, 0.00, -3.20, 0.00, -2.06, 0.00, 83.30, 83.10 -DU32, 7, 426225 -CURR, 617, 307088, 1346, 2106, 4962, 498.470700 -CTUN, 617, 0.00, 20.39, 21.289934, 0, 0, 16, 284, 10 -NTUN, 0.22, 3.50, 23.392181, -4.410095, 23.392181, -4.410095, 8.267789, -8.500945, 42.194824, 36.299072, -2.19, -2.39 -ATT, 0.00, -1.67, 0.00, -2.01, 0.00, 83.17, 83.10 -GPS, 3, 594567000, 8, 2.25, 44.0290125, -77.7367042, 21.04, 105.09, 0.18, 123.48 -CTUN, 616, 0.00, 20.55, 21.299177, 0, 0, 16, 290, 10 -NTUN, 0.22, 3.50, 23.643036, -4.862366, 23.643036, -4.862366, 9.940618, -8.733376, 36.483707, 35.522076, -1.87, -2.30 -ATT, 0.00, -2.22, 0.00, -2.45, 0.00, 83.34, 83.10 -NTUN, 0.24, 3.47, 23.563904, -5.407288, 23.563904, -5.407288, 11.225256, -10.289824, 32.200687, 35.495739, -1.62, -2.27 -CTUN, 616, 0.00, 20.51, 21.307983, 0, 0, 18, 285, 10 -GPS, 3, 594567200, 8, 2.25, 44.0290127, -77.7367037, 21.03, 105.10, 0.18, 123.48 -ATT, 0.00, -2.52, 0.00, -2.04, 0.00, 83.39, 83.10 -NTUN, 0.24, 3.45, 23.171295, -6.027527, 23.171295, -6.027527, 12.832244, -10.529393, 28.112785, 35.859016, -1.38, -2.26 -CTUN, 616, 0.00, 20.48, 21.327059, 0, 0, 23, 273, 10 -ATT, 0.00, -2.22, 0.00, -2.13, 0.00, 83.46, 83.10 -NTUN, 0.24, 3.45, 22.514313, -6.757385, 22.514313, -6.757385, 13.652323, -11.270159, 23.430176, 34.701416, -1.12, -2.16 -GPS, 3, 594567400, 8, 2.25, 44.0290132, -77.7367034, 21.04, 105.12, 0.19, 123.48 -NTUN, 0.23, 3.40, 21.421997, -7.511841, 21.421997, -7.511841, 15.209981, -10.907910, 17.966507, 33.379238, -0.81, -2.05 -CTUN, 616, 0.00, 20.61, 21.333149, 0, 0, 21, 270, 10 -ATT, 0.00, -1.47, 0.00, -2.59, 0.00, 83.45, 83.10 -NTUN, 0.22, 3.37, 19.997833, -8.287048, 19.997833, -8.287048, 15.495069, -12.090894, 12.899368, 33.324677, -0.53, -2.01 -CTUN, 616, 0.00, 20.54, 21.348064, 0, 0, 25, 280, 10 -GPS, 3, 594567600, 8, 2.25, 44.0290136, -77.7367028, 21.04, 105.15, 0.24, 123.48 -ATT, 0.00, -1.32, 0.00, -1.60, 0.00, 83.58, 83.10 -NTUN, 0.22, 3.37, 18.350037, -9.237549, 18.350037, -9.237549, 16.396381, -11.846988, 7.522034, 30.494995, -0.23, -1.81 -CTUN, 589, 0.00, 20.79, 21.355894, 0, 0, 21, 274, 6 -ATT, 0.00, -1.32, 0.00, -1.98, 0.00, 83.56, 83.10 -NTUN, 0.20, 3.32, 16.568878, -10.343628, 16.568878, -10.343628, 16.760687, -12.452412, 5.188416, 28.939209, -0.11, -1.71 -GPS, 3, 594567800, 8, 2.25, 44.0290141, -77.7367024, 21.06, 105.17, 0.31, 84.51 -CTUN, 464, 0.00, 20.63, 21.355894, 0, 0, 22, 286, 0 -NTUN, 0.19, 3.22, 14.548187, -11.373352, 14.548187, -11.373352, 18.030216, -13.097498, -0.006840, 28.804712, 0.19, -1.67 -ATT, 0.00, -1.05, 0.00, -1.96, 0.00, 83.49, 83.10 -CTUN, 267, 0.00, 20.74, 21.322229, 0, 0, 22, 268, -55 -NTUN, 0.19, 3.22, 12.392792, -12.378723, 12.392792, -12.378723, 17.743410, -14.078476, -4.553955, 28.946289, 0.45, -1.64 -GPS, 3, 594568000, 8, 2.25, 44.0290145, -77.7367020, 21.07, 105.20, 0.31, 84.51 -ATT, 0.00, -0.31, 0.00, -1.55, 0.00, 83.38, 83.10 -CTUN, 180, 0.00, 20.85, 21.158445, 0, 0, 18, 279, -130 -NTUN, 0.17, 3.12, 10.165863, -13.324707, 10.165863, -13.324707, 18.613983, -15.417288, -8.494230, 30.444607, 0.69, -1.70 -ATT, 0.00, -0.37, 0.00, -1.46, 0.00, 83.43, 83.10 -CTUN, 143, 0.00, 20.85, 21.010479, 0, 0, 15, 195, -160 -NTUN, 0.16, 3.04, 7.916718, -14.290649, 7.916718, -14.290649, 17.664070, -15.962245, -9.268766, 30.436214, 0.74, -1.70 -GPS, 3, 594568200, 8, 2.25, 44.0290150, -77.7367017, 21.09, 105.24, 0.31, 32.07 -CTUN, 137, 0.00, 20.86, 20.846577, 0, 0, -2, 202, -164 -NTUN, 0.16, 3.04, 5.747681, -15.030701, 5.747681, -15.030701, 16.327925, -19.517061, -10.690369, 35.599487, 0.85, -1.99 -ATT, 0.00, 0.82, 0.00, -0.57, 0.00, 83.60, 83.10 -CTUN, 137, 0.00, 21.69, 20.699244, 0, 0, -28, 224, -163 -NTUN, 0.16, 2.89, 3.568726, -15.399963, 3.568726, -15.399963, 16.225607, -22.683050, -13.789551, 42.307373, 1.07, -2.36 -ATT, 0.00, 0.63, 0.00, 1.84, 0.00, 83.59, 83.10 -GPS, 3, 594568400, 8, 2.25, 44.0290156, -77.7367015, 21.06, 105.27, 0.39, 12.91 -CTUN, 136, 0.00, 22.30, 20.533714, 0, 0, -56, 213, -163 -NTUN, 0.15, 2.79, 1.291504, -15.685059, 1.291504, -15.685059, 15.472693, -21.407059, -16.546749, 41.177277, 1.22, -2.28 -ATT, 0.00, -0.18, 0.00, -1.12, 0.00, 83.76, 83.10 -NTUN, 0.15, 2.71, -0.960510, -16.071228, -0.960510, -16.071228, 13.224036, -21.099112, -17.747618, 41.099300, 1.28, -2.27 -CTUN, 132, 0.00, 20.52, 20.352179, 0, 0, -87, 286, -166 -ATT, 0.00, 1.22, 0.00, -5.17, 0.00, 83.82, 83.10 -GPS, 3, 594568600, 8, 2.25, 44.0290163, -77.7367015, 20.97, 105.20, 0.44, 1.46 -NTUN, 0.16, 2.60, -3.210876, -16.338623, -3.210876, -16.338623, 12.817677, -21.552645, -20.280853, 42.352524, 1.44, -2.33 -CTUN, 132, 0.00, 20.21, 20.132921, 0, 0, -109, 261, -167 -ATT, 0.00, 1.39, 0.00, -1.98, 0.00, 83.88, 83.10 -NTUN, 0.16, 2.52, -5.518036, -16.559875, -5.518036, -16.559875, 10.155126, -21.289011, -21.071594, 41.787476, 1.48, -2.29 -GPS, 3, 594568800, 8, 2.25, 44.0290169, -77.7367016, 20.79, 105.01, 0.44, 1.46 -CTUN, 132, 0.00, 20.55, 20.018360, 0, 0, -115, 265, -167 -ATT, 0.00, 1.27, 0.00, -1.37, 0.00, 83.64, 83.10 -NTUN, 0.17, 2.46, -7.623840, -16.998230, -7.623840, -16.998230, 6.096049, -17.270081, -17.058044, 35.616455, 1.22, -1.95 -CTUN, 132, 0.00, 20.15, 19.718260, 0, 0, -109, 259, -167 -ATT, 0.00, 2.28, 0.00, -3.49, 0.00, 83.57, 83.10 -NTUN, 0.18, 2.42, -9.389832, -17.463257, -9.389832, -17.463257, 1.447354, -18.873417, -11.485062, 36.395775, 0.90, -2.03 -GPS, 3, 594569000, 8, 2.25, 44.0290176, -77.7367020, 20.48, 104.80, 0.44, 345.86 -CTUN, 132, 0.00, 19.95, 19.616148, 0, 0, -112, 280, -167 -NTUN, 0.18, 2.42, -10.993591, -17.738525, -10.993591, -17.738525, 1.197218, -16.452995, -12.037598, 36.247314, 0.94, -2.02 -ATT, 0.00, 0.51, 0.00, -2.61, 0.00, 83.39, 83.10 -NTUN, 0.20, 2.37, -12.504852, -17.918823, -12.504852, -17.918823, -4.742730, -16.148346, -7.265263, 37.178810, 0.66, -2.10 -CTUN, 132, 0.00, 19.86, 19.400297, 0, 0, -105, 278, -167 -ATT, 0.00, 0.60, 0.00, -2.09, 0.00, 83.42, 83.10 -GPS, 3, 594569200, 8, 2.25, 44.0290181, -77.7367022, 20.25, 104.58, 0.44, 345.86 -NTUN, 0.21, 2.34, -13.722504, -18.054688, -13.722504, -18.054688, -5.386790, -15.133406, -5.055954, 36.654808, 0.54, -2.09 -CTUN, 132, 0.00, 19.84, 19.166466, 0, 0, -105, 247, -167 -ATT, 0.00, 0.79, 0.00, -1.81, 0.00, 83.26, 83.10 -NTUN, 0.22, 2.31, -14.932556, -18.117249, -14.932556, -18.117249, -8.995009, -15.854406, -2.100525, 37.374390, 0.37, -2.15 -GPS, 3, 594569400, 8, 2.25, 44.0290184, -77.7367026, 20.04, 104.38, 0.31, 343.33 -CTUN, 132, 0.00, 19.67, 19.015858, 0, 0, -107, 265, -167 -NTUN, 0.22, 2.31, -15.836456, -17.937561, -15.836456, -17.937561, -10.104530, -15.170947, -0.039001, 39.796875, 0.28, -2.30 -ATT, 0.00, 0.95, 0.00, -1.55, 0.00, 82.90, 83.10 -CTUN, 0, 0.00, 19.29, 18.631153, 0, 0, -117, 254, -250 -NTUN, 0.23, 2.28, -16.723755, -17.705200, -16.723755, -17.705200, -11.409387, -14.141360, 0.127014, 39.323608, 0.27, -2.27 -ATT, 0.00, -0.54, 0.00, -3.84, 0.00, 82.91, 83.10 -GPS, 3, 594569600, 8, 2.25, 44.0290187, -77.7367033, 19.76, 104.17, 0.26, 333.21 -CTUN, 0, 0.00, 18.95, 18.529163, 0, 0, -117, 240, -250 -NTUN, 0.24, 2.26, -17.341827, -17.106873, -17.341827, -17.106873, -16.681059, -15.913214, 7.880470, 43.924034, -0.13, -2.60 -DU32, 7, 426225 -CURR, 0, 313124, 1411, 1001, 4897, 507.391540 -ATT, 0.00, 2.91, 0.00, -1.13, 0.00, 82.52, 83.10 -CTUN, 0, 0.00, 19.30, 18.130344, 0, 0, -134, 279, -250 -NTUN, 0.24, 2.23, -17.783325, -16.183472, -17.783325, -16.183472, -15.607912, -14.752956, 7.585022, 47.234009, -0.07, -2.79 -GPS, 3, 594569800, 8, 2.25, 44.0290189, -77.7367038, 19.52, 103.93, 0.32, 322.17 -ATT, 0.00, 0.11, 0.00, -1.83, 0.00, 82.55, 83.10 -CTUN, 0, 0.00, 19.16, 17.854584, 0, 0, -139, 221, -250 -NTUN, 0.24, 2.20, -18.223206, -15.336487, -18.223206, -15.336487, -18.805082, -11.848777, 9.601196, 44.469849, -0.22, -2.64 -CTUN, 0, 0.00, 18.39, 17.605263, 0, 0, -150, 199, -250 -NTUN, 0.24, 2.20, -18.282593, -14.643921, -18.282593, -14.643921, -22.352388, -9.517776, 17.400129, 40.995617, -0.70, -2.50 -ATT, 0.00, 1.00, 0.00, -6.02, 0.00, 82.90, 83.10 -GPS, 3, 594570000, 8, 2.25, 44.0290191, -77.7367046, 19.10, 103.67, 0.32, 322.17 -NTUN, 0.23, 2.18, -18.152649, -14.107361, -18.152649, -14.107361, -23.327293, -7.645231, 21.286573, 38.312477, -0.95, -2.37 -CTUN, 0, 0.00, 18.24, 17.253613, 0, 0, -175, 247, -250 -ATT, 0.00, 2.21, 0.00, -2.21, 0.00, 82.78, 83.10 -NTUN, 0.22, 2.17, -18.355743, -13.342163, -18.355743, -13.342163, -20.404251, -7.423420, 14.969055, 40.651978, -0.56, -2.46 -CTUN, 0, 0.00, 18.72, 17.103842, 0, 0, -188, 325, -250 -GPS, 3, 594570200, 8, 2.25, 44.0290190, -77.7367053, 18.81, 103.37, 0.28, 322.17 -ATT, 0.00, -3.55, 0.00, 0.27, 0.00, 82.56, 83.10 -NTUN, 0.22, 2.14, -18.525757, -12.444397, -18.525757, -12.444397, -20.972946, -2.636118, 15.299866, 37.977661, -0.59, -2.31 -CTUN, 0, 0.00, 18.39, 16.776571, 0, 0, -197, 240, -250 -ATT, 0.00, -0.24, 0.00, -5.86, 0.00, 82.37, 83.10 -NTUN, 0.22, 2.12, -18.324646, -11.774475, -18.324646, -11.774475, -23.191816, -0.360334, 21.011108, 32.699219, -0.95, -2.05 -GPS, 3, 594570400, 8, 2.25, 44.0290191, -77.7367062, 18.32, 102.98, 0.28, 322.17 -CTUN, 0, 0.00, 17.87, 16.501690, 0, 1, -202, 288, -250 -NTUN, 0.21, 2.10, -18.360199, -10.852966, -18.360199, -10.852966, -20.734081, 1.885300, 16.647991, 34.123848, -0.65, -2.11 -ATT, 0.00, 2.55, 0.00, -7.04, 0.00, 81.12, 83.10 -CTUN, 0, 0.00, 17.96, 16.151461, 0, 0, -201, 279, -250 -NTUN, 0.21, 2.08, -18.573059, -10.025696, -18.573059, -10.025696, -20.167835, 4.277730, 13.849897, 30.356268, -0.50, -1.88 -ATT, 0.00, -1.87, 0.00, -2.75, 0.00, 80.49, 83.10 -GPS, 3, 594570600, 8, 2.25, 44.0290190, -77.7367068, 17.90, 102.62, 0.36, 302.47 -CTUN, 0, 0.00, 18.50, 15.999850, 0, 0, -206, 283, -250 -NTUN, 0.21, 2.07, -18.346344, -9.292908, -18.346344, -9.292908, -24.085434, 7.075456, 22.267151, 26.327881, -0.99, -1.74 -ATT, 0.00, 0.63, 0.00, -1.49, 0.00, 78.53, 83.10 -CTUN, 0, 0.00, 18.46, 15.676471, 0, 0, -197, 160, -250 -NTUN, 0.21, 2.07, -18.285431, -8.338501, -18.285431, -8.338501, -19.473434, 3.329467, 16.597187, 33.356930, -0.52, -2.11 -GPS, 3, 594570800, 8, 2.25, 44.0290191, -77.7367074, 17.54, 102.23, 0.25, 302.47 -CTUN, 0, 0.00, 16.25, 15.400271, 0, 0, -195, 168, -250 -ATT, 0.00, -1.64, 0.00, -4.14, 0.00, 76.15, 83.10 -NTUN, 0.20, 2.01, -18.767700, -7.155457, -18.767700, -7.155457, -14.619864, 6.206933, 6.128593, 32.949944, 0.12, -1.95 -DU32, 7, 426225 -CURR, 0, 315587, 1396, 902, 4876, 511.838230 -CTUN, 0, 0.00, 14.85, 15.175751, 0, 2, -209, 274, -250 -ATT, 0.00, -4.44, 0.00, -11.00, 0.00, 75.15, 83.10 -NTUN, 0.20, 1.97, -20.058685, -6.247681, -20.058685, -6.247681, -4.937679, 13.103361, -13.782030, 22.987881, 1.09, -1.09 -GPS, 3, 594571000, 8, 2.25, 44.0290187, -77.7367078, 17.05, 101.82, 0.23, 302.47 -CTUN, 0, 0.00, 14.39, 14.998871, 0, 3, -219, 234, -250 -NTUN, 0.20, 1.97, -21.721954, -6.030273, -21.721954, -6.030273, 1.978914, 18.178926, -26.632690, 10.174072, 1.60, -0.20 -ATT, 0.00, -3.04, 0.00, -11.03, 0.00, 76.40, 83.10 -CTUN, 0, 0.00, 13.99, 14.674150, 0, 0, -219, 291, -250 -NTUN, 0.22, 1.95, -23.795288, -6.239136, -23.795288, -6.239136, 4.531259, 25.324509, -36.942764, -3.109720, 2.05, 0.67 -GPS, 3, 594571200, 8, 2.25, 44.0290193, -77.7367080, 16.43, 101.44, 0.24, 302.47 -ATT, 0.00, 3.81, 0.00, -1.70, 0.00, 76.79, 83.10 -CTUN, 0, 0.00, 13.91, 14.349380, 0, 0, -201, 260, -250 -NTUN, 0.24, 1.94, -26.574768, -7.087463, -26.574768, -7.087463, 9.327388, 26.891958, -52.519604, -12.399283, 2.82, 1.38 -ATT, 0.00, 0.82, 0.00, -0.53, 0.00, 78.52, 83.10 -CTUN, 0, 0.00, 15.37, 14.123929, 0, 0, -198, 336, -250 -NTUN, 0.27, 1.94, -29.752014, -8.004578, -29.752014, -8.004578, 7.640864, 30.541483, -60.772461, -20.171143, 3.25, 1.83 -GPS, 3, 594571400, 8, 2.25, 44.0290192, -77.7367082, 15.83, 101.13, 0.10, 302.47 -ATT, 0.00, -0.23, 0.00, -5.77, 0.00, 79.97, 83.10 -NTUN, 0.30, 1.95, -32.255493, -9.070007, -32.255493, -9.070007, 7.993629, 30.264439, -59.034790, -24.654297, 3.12, 2.01 -CTUN, 0, 0.00, 15.20, 13.872560, 0, 0, -191, 262, -250 -ATT, 0.00, -0.65, 0.00, -2.69, 0.00, 81.40, 83.10 -NTUN, 0.33, 1.95, -34.528046, -9.757996, -34.528046, -9.757996, 6.694513, 24.817871, -59.500519, -17.811764, 3.28, 1.53 -CTUN, 0, 0.00, 15.45, 13.572619, 0, 0, -182, 236, -250 -GPS, 3, 594571600, 8, 2.25, 44.0290188, -77.7367076, 15.51, 100.71, 0.10, 302.47 -NTUN, 0.35, 1.95, -35.884338, -10.049744, -35.884338, -10.049744, 5.965924, 20.391649, -52.562927, -10.917480, 2.94, 1.02 -ATT, 0.00, 3.04, 0.00, 6.10, 0.00, 82.74, 83.10 -CTUN, 0, 0.00, 15.93, 13.271820, 0, 0, -185, 197, -250 -NTUN, 0.35, 1.95, -36.655640, -10.112427, -36.655640, -10.112427, 1.805504, 15.026944, -45.790924, -4.633162, 2.61, 0.59 -GPS, 3, 594571800, 8, 2.25, 44.0290189, -77.7367076, 15.10, 100.40, 0.19, 302.47 -ATT, 0.00, 3.67, 0.00, 0.72, 0.00, 83.19, 83.10 -CTUN, 0, 0.00, 15.56, 12.996120, 0, 0, -199, 246, -250 -NTUN, 0.38, 1.94, -36.875153, -9.315796, -36.875153, -9.315796, -2.548622, 8.109170, -36.173397, 10.887434, 2.17, -0.38 -ATT, 0.00, 2.90, 0.00, -2.50, 0.00, 83.42, 83.10 -CTUN, 0, 0.00, 14.98, 12.672280, 0, 0, -221, 237, -250 -NTUN, 0.38, 1.94, -36.613403, -7.897095, -36.613403, -7.897095, -6.107799, 2.830844, -29.382507, 23.187012, 1.85, -1.15 -GPS, 3, 594572000, 8, 2.25, 44.0290186, -77.7367073, 14.79, 100.02, 0.17, 302.47 -CTUN, 0, 0.00, 14.76, 12.597691, 0, 0, -226, 244, -250 -NTUN, 0.37, 1.90, -35.835205, -6.279297, -35.835205, -6.279297, -9.098549, 0.764386, -21.218018, 28.177979, 1.41, -1.50 -ATT, 0.00, 0.64, 0.00, -0.46, 0.00, 83.81, 83.10 -CTUN, 0, 0.00, 14.65, 12.145880, 0, 0, -245, 315, -250 -NTUN, 0.36, 1.88, -34.507294, -4.758850, -34.507294, -4.758850, -10.819257, -0.138218, -13.720886, 30.204468, 0.98, -1.66 -ATT, 0.00, 1.38, 0.00, -0.95, 0.00, 83.71, 83.10 -GPS, 3, 594572200, 8, 2.25, 44.0290186, -77.7367076, 14.33, 99.54, 0.17, 302.47 -NTUN, 0.34, 1.85, -33.217773, -3.184937, -33.217773, -3.184937, -11.603049, 0.383633, -13.104797, 30.739136, 0.96, -1.69 -CTUN, 0, 0.00, 14.15, 11.917881, 0, 0, -241, 276, -250 -ATT, 0.00, 1.87, 0.00, -3.58, 0.00, 83.40, 83.10 -NTUN, 0.34, 1.85, -31.946747, -1.415527, -31.946747, -1.415527, -12.952850, -3.621409, -11.289734, 38.694092, 0.90, -2.17 -ATT, 0.00, 0.96, 0.00, -1.22, 0.00, 83.68, 83.10 -GPS, 3, 594572400, 8, 2.25, 44.0290185, -77.7367081, 13.84, 99.08, 0.18, 302.47 -CTUN, 0, 0.00, 13.78, 11.570080, 0, 0, -237, 276, -250 -NTUN, 0.31, 1.82, -30.822937, 0.601746, -30.822937, 0.601746, -8.067605, -2.724360, -17.982258, 41.777184, 1.30, -2.31 -ATT, 0.00, -2.75, 0.00, -1.20, 0.00, 84.36, 83.10 -CTUN, 0, 0.00, 13.98, 11.144400, 0, 0, -235, 265, -250 -NTUN, 0.30, 1.77, -30.073730, 2.543030, -30.073730, 2.543030, -9.155942, -2.828126, -20.432257, 43.608932, 1.43, -2.42 -GPS, 3, 594572600, 8, 2.25, 44.0290183, -77.7367085, 13.40, 98.63, 0.21, 302.47 -CTUN, 0, 0.00, 13.42, 11.094560, 0, 0, -233, 302, -250 -NTUN, 0.30, 1.72, -29.316589, 4.585632, -29.316589, 4.585632, -7.058495, -4.715710, -24.352110, 48.632347, 1.69, -2.68 -ATT, 0.00, 2.55, 0.00, -3.81, 0.00, 84.23, 83.10 -CTUN, 0, 0.00, 13.22, 10.618839, 0, 0, -237, 245, -250 -NTUN, 0.29, 1.67, -28.789520, 6.604919, -28.789520, 6.604919, -4.475739, -3.015925, -29.781494, 48.992943, 2.03, -2.65 -ATT, 0.00, 1.99, 0.00, -3.21, 0.00, 83.82, 83.10 -GPS, 3, 594572800, 8, 2.25, 44.0290182, -77.7367091, 12.86, 98.17, 0.21, 302.47 -NTUN, 0.29, 1.67, -28.384125, 8.555359, -28.384125, 8.555359, -5.383762, -1.129026, -30.946045, 48.504395, 2.10, -2.61 -CTUN, 0, 0.00, 12.98, 10.392849, 0, 0, -241, 309, -250 -ATT, 0.00, 0.07, 0.00, -3.14, 0.00, 83.67, 83.10 -DU32, 7, 426225 -CURR, 0, 319919, 1384, 1132, 4940, 519.050600 -NTUN, 0.29, 1.62, -27.738892, 10.623779, -27.738892, 10.623779, -6.144796, 0.980976, -28.667496, 47.094383, 1.96, -2.54 -GPS, 3, 594573000, 8, 2.25, 44.0290181, -77.7367094, 12.49, 97.71, 0.20, 302.47 -CTUN, 0, 0.00, 12.82, 10.093088, 0, 0, -250, 279, -250 -ATT, 0.00, 2.18, 0.00, -2.78, 0.00, 83.85, 83.10 -NTUN, 0.29, 1.56, -27.196869, 12.009216, -27.196869, 12.009216, -6.265160, 2.986825, -28.525023, 43.994312, 1.92, -2.37 -CTUN, 0, 0.00, 12.71, 9.616838, 0, 0, -253, 299, -250 -NTUN, 0.29, 1.54, -26.745667, 13.025085, -26.745667, 13.025085, -5.441164, 6.728892, -31.532650, 38.058109, 2.04, -2.03 -GPS, 3, 594573200, 8, 2.25, 44.0290180, -77.7367096, 12.00, 97.22, 0.13, 302.47 -ATT, 0.00, 1.52, 0.00, -3.63, 0.00, 84.63, 83.10 -CTUN, 0, 0.00, 12.33, 9.366268, 0, 0, -253, 275, -250 -NTUN, 0.29, 1.54, -25.774414, 13.826599, -25.774414, 13.826599, -14.388857, 4.049404, -17.287476, 39.015137, 1.20, -2.18 -ATT, 0.00, 5.71, 0.00, -0.08, 0.00, 84.89, 83.10 -CTUN, 0, 0.00, 12.51, 9.116208, 0, 0, -254, 268, -250 -NTUN, 0.29, 1.51, -24.756195, 14.466980, -24.756195, 14.466980, -8.308825, 10.780684, -22.817810, 31.403809, 1.48, -1.70 -GPS, 3, 594573400, 8, 2.25, 44.0290179, -77.7367097, 11.54, 96.72, 0.10, 302.47 -CTUN, 0, 0.00, 13.19, 8.887519, 0, 0, -255, 271, -250 -ATT, 0.00, -1.55, 0.00, -4.83, 0.00, 85.76, 83.10 -NTUN, 0.28, 1.48, -23.728699, 14.389221, -23.728699, 14.389221, -13.152695, 15.399911, -16.826769, 20.230110, 1.05, -1.10 -CTUN, 0, 0.00, 11.12, 8.615619, 0, 0, -254, 247, -250 -NTUN, 0.27, 1.48, -22.492462, 13.876404, -22.492462, 13.876404, -12.695984, 18.680916, -14.637634, 12.871826, 0.88, -0.70 -GPS, 3, 594573600, 8, 2.25, 44.0290177, -77.7367098, 11.13, 96.23, 0.09, 302.47 -ATT, 0.00, 0.45, 0.00, -5.81, 0.00, 87.00, 83.10 -CTUN, 0, 0.00, 10.86, 8.389158, 0, 0, -259, 275, -250 -NTUN, 0.26, 1.48, -21.368073, 13.148682, -21.368073, 13.148682, -10.826488, 20.050615, -16.642529, 8.649271, 0.99, -0.45 -ATT, 0.00, 0.92, 0.00, -1.14, 0.00, 87.22, 83.10 -CTUN, 0, 0.00, 12.39, 8.164009, 0, 0, -266, 287, -250 -GPS, 3, 594573800, 8, 2.25, 44.0290173, -77.7367095, 10.61, 95.73, 0.11, 302.47 -NTUN, 0.26, 1.48, -20.066040, 11.537598, -20.066040, 11.537598, -11.903008, 23.675020, -17.830757, -2.345661, 1.03, 0.18 -CTUN, 0, 0.00, 12.32, 8.064909, 0, 0, -265, 256, -250 -ATT, 0.00, 1.55, 0.00, -0.36, 0.00, 87.43, 83.10 -NTUN, 0.23, 1.50, -18.557251, 10.416260, -18.557251, 10.416260, -13.643688, 20.947317, -7.759706, -1.326646, 0.44, 0.09 -CTUN, 0, 0.00, 10.70, 7.689209, 0, 0, -260, 269, -250 -GPS, 3, 594574000, 8, 2.25, 44.0290170, -77.7367092, 10.32, 95.19, 0.20, 190.98 -NTUN, 0.21, 1.50, -17.019470, 9.424988, -17.019470, 9.424988, -14.088085, 19.418152, -5.622192, 1.087280, 0.33, -0.04 -ATT, 0.00, 0.02, 0.00, -0.49, 0.00, 86.76, 83.10 -CTUN, 0, 0.00, 11.11, 7.188069, 0, 0, -265, 254, -250 -NTUN, 0.19, 1.50, -15.074219, 8.814575, -15.074219, 8.814575, -17.531971, 15.177488, 2.259914, 7.956311, -0.10, -0.47 -ATT, 0.00, -0.36, 0.00, 0.50, 0.00, 86.44, 83.10 -GPS, 3, 594574200, 8, 2.25, 44.0290167, -77.7367090, 9.72, 94.67, 0.20, 190.98 -NTUN, 0.17, 1.46, -12.836884, 8.628784, -12.836884, 8.628784, -16.844597, 9.768959, 5.526012, 17.295496, -0.25, -1.02 -CTUN, 0, 0.00, 10.34, 7.013619, 0, 0, -267, 260, -250 -ATT, 0.00, 0.10, 0.00, 1.34, 0.00, 86.00, 83.10 -NTUN, 0.17, 1.46, -10.800110, 9.034668, -10.800110, 9.034668, -17.459888, 4.614916, 7.968370, 27.979252, -0.34, -1.66 -CTUN, 0, 0.00, 9.61, 6.662800, 0, 0, -269, 253, -250 -GPS, 3, 594574400, 8, 2.25, 44.0290162, -77.7367089, 9.22, 94.16, 0.19, 174.19 -ATT, 0.00, 0.75, 0.00, 0.79, 0.00, 85.40, 83.10 -NTUN, 0.17, 1.46, -8.650024, 10.073975, -8.650024, 10.073975, -16.462393, -1.472237, 10.718035, 41.498047, -0.42, -2.46 -CTUN, 0, 0.00, 9.97, 6.385730, 0, 0, -274, 263, -250 -NTUN, 0.13, 1.28, -6.527771, 11.398499, -6.527771, 11.398499, -16.487499, -2.354691, 13.436903, 47.379028, -0.55, -2.82 -ATT, 0.00, -1.20, 0.00, -2.46, 0.00, 85.31, 83.10 -CTUN, 0, 0.00, 10.67, 6.085380, 0, 0, -278, 293, -250 -GPS, 3, 594574600, 8, 2.25, 44.0290162, -77.7367091, 8.73, 93.62, 0.24, 171.18 -NTUN, 0.13, 1.17, -4.603241, 12.835754, -4.603241, 12.835754, -14.119953, -4.663616, 11.054752, 53.230255, -0.36, -3.15 -CTUN, 0, 0.00, 8.50, 5.834020, 0, 0, -279, 257, -250 -ATT, 0.00, -1.31, 0.00, -3.54, 0.00, 84.64, 83.10 -NTUN, 0.13, 1.08, -3.359253, 14.536194, -3.359253, 14.536194, -11.558031, -5.147705, 3.439880, 59.004395, 0.12, -3.44 -CTUN, 0, 0.00, 8.25, 5.661610, 0, 0, -279, 287, -250 -GPS, 3, 594574800, 8, 2.25, 44.0290161, -77.7367094, 8.22, 93.08, 0.13, 171.18 -ATT, 0.00, -0.68, 0.00, -2.32, 0.00, 84.05, 83.10 -NTUN, 0.14, 0.99, -2.562866, 16.044250, -2.562866, 16.044250, -7.184408, -3.236530, -4.114983, 57.931252, 0.59, -3.33 -CTUN, 0, 0.00, 7.92, 5.309889, 0, 0, -281, 305, -250 -NTUN, 0.16, 0.97, -2.247314, 17.301636, -2.247314, 17.301636, -4.731183, -1.403634, -10.844482, 55.573853, 0.99, -3.15 -ATT, 0.00, 0.33, 0.00, -4.93, 0.00, 83.41, 83.10 -CTUN, 0, 0.00, 7.30, 5.083089, 0, 0, -279, 295, -250 -GPS, 3, 594575000, 8, 2.25, 44.0290160, -77.7367095, 7.76, 92.52, 0.08, 171.18 -NTUN, 0.16, 0.97, -2.291199, 18.323059, -2.291199, 18.323059, -1.509917, 0.276825, -16.438843, 53.214233, 1.30, -2.97 -CTUN, 0, 0.00, 6.94, 4.809089, 0, 0, -272, 299, -250 -ATT, 0.00, 0.08, 0.00, -3.23, 0.00, 83.59, 83.10 -NTUN, 0.18, 0.97, -2.540649, 18.934448, -2.540649, 18.934448, -1.460754, 2.031753, -19.519703, 48.175648, 1.43, -2.67 -CTUN, 0, 0.00, 7.25, 4.581860, 0, 0, -264, 264, -250 -ATT, 0.00, 1.13, 0.00, -1.56, 0.00, 83.93, 83.10 -GPS, 3, 594575200, 8, 2.25, 44.0290162, -77.7367096, 7.19, 91.99, 0.06, 171.18 -NTUN, 0.19, 0.97, -2.924225, 19.316101, -2.924225, 19.316101, 0.011600, 4.509418, -21.797777, 44.778740, 1.53, -2.46 -CTUN, 0, 0.00, 7.28, 4.307300, 0, 0, -259, 313, -250 -ATT, 0.00, 1.83, 0.00, -3.68, 0.00, 84.46, 83.10 -NTUN, 0.19, 0.99, -3.274933, 19.381042, -3.274933, 19.381042, -5.848159, 7.839381, -17.507080, 39.649414, 1.23, -2.20 -CTUN, 0, 0.00, 6.57, 4.057260, 0, 0, -253, 225, -250 -GPS, 3, 594575400, 8, 2.25, 44.0290162, -77.7367094, 6.56, 91.45, 0.09, 171.18 -ATT, 0.00, 4.37, 0.00, -4.21, 0.00, 85.09, 83.10 -NTUN, 0.19, 0.99, -3.144318, 19.121338, -3.144318, 19.121338, -7.977640, 8.284266, -10.706779, 35.428669, 0.79, -2.00 -CTUN, 0, 0.00, 6.72, 3.806750, 0, 0, -252, 294, -250 -NTUN, 0.19, 0.99, -2.790253, 18.609192, -2.790253, 18.609192, -9.568494, 9.834102, -6.459351, 30.878540, 0.50, -1.77 -ATT, 0.00, 0.27, 0.00, -0.43, 0.00, 85.98, 83.10 -GPS, 3, 594575600, 8, 2.25, 44.0290161, -77.7367089, 6.14, 90.93, 0.09, 171.18 -NTUN, 0.19, 0.99, -1.950226, 17.731506, -1.950226, 17.731506, -16.055666, 11.898994, 7.400269, 25.223145, -0.32, -1.50 -CTUN, 0, 0.00, 7.41, 3.530839, 0, 0, -259, 246, -250 -ATT, 0.00, 1.02, 0.00, -1.44, 0.00, 85.69, 83.10 -PM, 0, 0, 50, 160, 1004, 12100, 10, 0 -NTUN, 0.17, 0.94, -0.539307, 16.465271, -0.539307, 16.465271, -18.423027, 14.232555, 17.251709, 18.209743, -0.91, -1.14 -CTUN, 0, 0.00, 4.49, 3.079949, 0, 0, -261, 269, -250 -ATT, 0.00, 3.03, 0.00, -5.02, 0.00, 84.93, 83.10 -GPS, 3, 594575800, 8, 2.25, 44.0290161, -77.7367087, 5.62, 90.42, 0.22, 171.18 -NTUN, 0.16, 0.87, 0.938171, 14.979858, 0.938171, 14.979858, -20.209171, 13.821762, 22.628494, 15.292945, -1.22, -1.01 -CTUN, 0, 0.00, 5.01, 2.980370, 0, 0, -265, 292, -250 -DU32, 7, 426225 -CURR, 0, 326244, 1383, 1322, 4984, 529.276060 -ATT, 0.00, 0.08, 0.00, -2.21, 0.00, 84.29, 83.10 -NTUN, 0.16, 0.87, 2.545990, 13.654236, 2.545990, 13.654236, -23.371321, 14.639844, 29.078186, 15.743774, -1.59, -1.08 -GPS, 3, 594576000, 8, 2.25, 44.0290160, -77.7367086, 5.20, 89.90, 0.11, 171.18 -ATT, 0.00, -0.27, 0.00, -0.85, 0.00, 83.33, 83.10 -CTUN, 277, 0.00, 5.36, 2.666362, 0, 0, -271, 264, -155 -NTUN, 0.13, 0.78, 4.505737, 12.026672, 4.505737, 12.026672, -26.539253, 17.542860, 40.403439, 7.885511, -2.28, -0.73 -CTUN, 409, 0.00, 4.41, 2.597609, 0, 0, -256, 308, -2 -NTUN, 0.12, 0.66, 6.299225, 10.797119, 6.299225, 10.797119, -24.823620, 12.834940, 39.934875, 13.704468, -2.21, -1.08 -ATT, 0.00, -0.80, 0.00, -0.49, 0.00, 82.80, 83.10 -GPS, 3, 594576200, 8, 2.25, 44.0290156, -77.7367085, 4.57, 89.37, 0.22, 171.18 -CTUN, 464, 0.00, 4.67, 2.597609, 0, 0, -258, 418, 0 -NTUN, 0.12, 0.54, 8.170624, 9.721375, 8.170624, 9.721375, -24.979849, 17.946508, 44.713989, 9.242554, -2.51, -0.88 -ATT, 0.00, -0.71, 0.00, -4.09, 0.00, 81.81, 83.10 -NTUN, 0.12, 0.42, 9.894989, 8.103516, 9.894989, 8.103516, -22.629570, 23.139437, 43.243652, -4.178589, -2.50, -0.15 -CTUN, 522, 0.00, 3.55, 2.597609, 0, 2, -214, 389, 0 -GPS, 3, 594576400, 8, 2.25, 44.0290156, -77.7367086, 4.08, 88.87, 0.08, 171.18 -ATT, 0.00, -0.67, 0.00, -6.62, 0.00, 80.45, 83.10 -NTUN, 0.12, 0.29, 11.230225, 6.008118, 11.230225, 6.008118, -19.258116, 33.017281, 39.220154, -21.746513, -2.45, 0.86 -CTUN, 520, 0.00, 2.65, 2.597609, 0, 0, -156, 320, 0 -NTUN, 0.12, 0.29, 11.885284, 3.404358, 11.885284, 3.404358, -13.862689, 32.367786, 28.616766, -29.300604, -1.95, 1.37 -ATT, 0.00, -2.21, 0.00, -0.35, 0.00, 79.41, 83.10 -CTUN, 521, 0.00, 2.75, 2.597609, 0, 0, -104, 345, 0 -GPS, 3, 594576600, 8, 2.25, 44.0290149, -77.7367079, 3.83, 88.39, 0.08, 171.18 -NTUN, 0.12, 0.14, 12.471161, 0.843323, 12.471161, 0.843323, -12.620548, 31.773674, 28.858765, -32.610352, -2.00, 1.55 -ATT, 0.00, -2.62, 0.00, 1.53, 0.00, 79.18, 83.10 -CTUN, 520, 0.00, 2.98, 2.597609, 0, 0, -63, 222, 0 -NTUN, 0.12, 0.01, 12.975739, -1.264893, 12.975739, -1.264893, -5.924860, 20.462959, 22.045776, -20.082153, -1.48, 0.90 -ATT, 0.00, -3.16, 0.00, 1.89, 0.00, 78.83, 83.10 -GPS, 3, 594576800, 8, 2.25, 44.0290146, -77.7367072, 3.57, 88.04, 0.39, 171.18 -CTUN, 521, 0.00, 2.75, 2.597609, 0, 0, -53, 240, 0 -NTUN, 0.13, 3.53, 13.140015, -2.220520, 13.140015, -2.220520, -5.320071, 10.120633, 19.626495, -0.461658, -1.12, -0.19 -ATT, 0.00, -2.27, 1.42, 5.32, 0.00, 78.97, 83.10 -CTUN, 521, 0.00, 2.17, 2.597609, 0, 0, -73, 338, 0 -NTUN, 0.13, 3.49, 13.324463, -2.531555, 13.324463, -2.531555, -2.905678, 8.393860, 17.844482, 7.889648, -0.93, -0.64 -GPS, 3, 594577000, 8, 2.25, 44.0290138, -77.7367071, 3.43, 87.82, 0.35, 171.18 -CTUN, 521, 0.00, 1.01, 2.597609, 0, 0, -73, 257, 0 -NTUN, 0.13, 3.48, 13.556641, -2.389832, 13.556641, -2.389832, 1.874965, 1.640697, 14.321777, 18.417236, -0.62, -1.21 -ATT, -1.99, -2.56, 1.66, -4.13, 0.00, 79.29, 83.10 -CTUN, 521, 0.00, 0.46, 2.597609, 0, 0, -70, 308, 0 -NTUN, 0.13, 3.51, 14.113464, -1.542786, 14.539021, -1.542786, 0.701243, -1.835065, 23.823809, 29.470459, -1.05, -1.94 -ATT, -6.46, -1.21, 4.40, -1.44, 0.00, 79.72, 83.10 -GPS, 3, 594577200, 8, 2.25, 44.0290142, -77.7367063, 3.21, 87.81, 0.37, 171.18 -CTUN, 522, 0.00, 0.64, 2.597609, 0, 0, -72, 274, 0 -NTUN, 0.13, 3.51, 14.472321, -1.047974, 15.091043, -1.727815, 3.064470, 0.007114, 19.465565, 18.168022, -0.92, -1.24 -ATT, -1.05, -0.68, 5.95, -0.16, 0.00, 79.83, 83.10 -CTUN, 545, 0.00, 0.85, 2.597609, 0, 0, -70, 356, 0 -NTUN, 0.14, 3.55, 13.894714, -1.065247, 13.894714, -2.113830, 6.360458, -2.079838, -3.084132, 17.100866, 0.35, -0.95 -GPS, 3, 594577400, 8, 2.25, 44.0290142, -77.7367059, 2.77, 87.74, 0.19, 171.18 -CTUN, 574, 0.00, 1.27, 2.597609, 0, 0, -72, 355, 0 -NTUN, 0.13, 3.55, 13.259033, -1.285095, 13.259033, -1.987157, 5.420444, 1.811017, 4.273143, 18.141191, -0.07, -1.08 -ATT, 0.00, -0.39, 4.28, -4.48, 0.00, 80.40, 83.10 -NTUN, 0.13, 3.53, 12.534546, -1.812317, 12.534546, -2.408580, 8.419309, -1.123576, -0.244873, 14.785770, 0.15, -0.84 -CTUN, 585, 0.00, 1.13, 2.597609, 0, 0, -23, 233, 0 -GPS, 3, 594577600, 8, 2.25, 44.0290145, -77.7367053, 2.59, 87.62, 0.29, 171.18 -ATT, -2.81, -0.42, 4.28, 2.65, 0.00, 80.84, 83.10 -NTUN, 0.13, 3.53, 11.641510, -2.075500, 11.641510, -2.609975, 6.831430, -5.498320, -1.930359, 20.986050, 0.30, -1.19 -CTUN, 586, 0.00, 1.37, 2.597609, 0, 0, -26, 322, 0 -NTUN, 0.11, 3.49, 10.626465, -2.734924, 10.626465, -3.070440, 8.341487, -1.942448, -5.150452, 14.395357, 0.42, -0.78 -ATT, -4.93, -0.31, 3.92, -2.56, 0.00, 80.97, 83.10 -CTUN, 585, 0.00, 1.31, 2.597609, 0, 0, -15, 252, 0 -GPS, 3, 594577800, 8, 2.25, 44.0290146, -77.7367049, 2.43, 87.64, 0.24, 171.18 -NTUN, 0.10, 3.43, 9.592468, -3.516907, 10.227530, -4.024313, 8.647682, -3.392347, 0.010656, 10.461267, 0.09, -0.60 -CTUN, 585, 0.00, 0.77, 2.597609, 0, 1, -11, 363, 0 -ATT, -8.69, -0.14, 5.23, -6.39, 0.00, 81.24, 83.10 -NTUN, 0.10, 3.35, 8.906921, -4.636597, 11.511852, -6.285613, 7.725785, 1.369126, 18.843218, -9.613001, -1.16, 0.38 -GPS, 3, 594578000, 8, 2.25, 44.0290150, -77.7367042, 2.30, 87.62, 0.33, 171.18 -NTUN, 0.10, 3.35, 8.289978, -6.731140, 13.822554, -10.335196, 9.045046, 3.729002, 29.878231, -35.094883, -2.02, 1.76 -CTUN, 585, 0.00, 1.00, 2.597609, 0, 0, 8, 333, 0 -ATT, -12.21, -0.25, 7.61, 0.71, 0.00, 81.52, 83.10 -NTUN, 0.10, 3.15, 7.806976, -9.386902, 16.803543, -15.964814, 9.201041, 4.151483, 40.809895, -58.296177, -2.85, 3.01 -GPS, 3, 594578200, 8, 2.25, 44.0290155, -77.7367039, 2.25, 87.66, 0.33, 171.18 -NTUN, 0.10, 3.15, 7.419983, -12.112610, 20.190727, -22.340410, 10.893670, -2.653091, 46.871841, -65.755959, -3.26, 3.39 -CTUN, 584, 0.00, 0.60, 2.597609, 0, 0, 50, 310, 0 -ATT, -13.51, -2.01, 9.64, 1.41, 0.00, 81.60, 83.10 -NTUN, 0.14, 2.97, 6.921051, -14.326477, 22.610996, -27.398388, 13.345995, -8.184443, 38.202690, -52.579777, -2.64, 2.71 -CTUN, 584, 0.00, 0.54, 2.597609, 0, 0, 54, 255, 0 -GPS, 3, 594578400, 8, 2.25, 44.0290161, -77.7367031, 2.24, 87.79, 0.26, 171.18 -NTUN, 0.15, 2.88, 6.059845, -16.151855, 22.783121, -28.956619, 16.195541, -15.840976, 12.721249, -12.582314, -0.83, 0.62 -ATT, -7.40, -1.88, 3.57, 2.02, 0.00, 81.94, 83.10 -CTUN, 574, 0.00, 1.30, 2.597609, 0, 0, 53, 315, 0 -NTUN, 0.15, 2.88, 4.807190, -17.290283, 22.059372, -29.067745, 18.839970, -20.452328, 0.762508, 5.888741, 0.00, -0.34 -CTUN, 547, 0.00, 2.52, 2.597609, 0, 0, 52, 247, 0 -GPS, 3, 594578600, 8, 2.25, 44.0290166, -77.7367027, 2.24, 87.91, 0.48, 98.39 -ATT, -6.69, -1.11, 2.14, 1.01, 0.00, 82.12, 83.10 -NTUN, 0.17, 2.76, 3.435883, -17.980225, 21.241276, -28.537868, 19.462421, -26.170746, -2.099961, 18.246304, 0.26, -1.03 -CTUN, 539, 0.00, 3.44, 2.597609, 0, 0, 49, 275, 0 -ATT, -7.16, -0.20, 2.14, 0.51, 0.00, 82.26, 83.10 -NTUN, 0.17, 2.76, 2.081299, -18.126343, 21.379932, -27.640650, 20.408318, -28.781778, 6.400572, 25.062817, -0.17, -1.50 -GPS, 3, 594578800, 8, 2.25, 44.0290171, -77.7367025, 2.36, 88.04, 0.24, 98.39 -NTUN, 0.17, 2.76, 0.976624, -18.117981, 23.280350, -26.983021, 22.092861, -30.341961, 25.004173, 25.576290, -1.25, -1.67 -ATT, -12.10, -1.10, 2.38, -0.91, 0.00, 82.62, 83.10 -CTUN, 541, 0.00, 3.90, 2.597609, 0, 0, 35, 257, 0 -NTUN, 0.18, 2.70, 0.180603, -17.971130, 25.853926, -26.207956, 22.649561, -32.720882, 33.480949, 29.673904, -1.72, -1.96 -GPS, 3, 594579000, 8, 2.25, 44.0290180, -77.7367026, 2.53, 88.15, 0.41, 42.74 -NTUN, 0.17, 2.60, -0.971008, -17.560852, 25.423843, -24.262371, 25.738106, -32.590076, 0.699177, 43.455853, 0.26, -2.52 -ATT, -4.81, -1.66, 0.00, -0.57, 0.00, 83.14, 83.10 -CTUN, 541, 0.00, 4.40, 2.597609, 0, 0, 28, 224, 0 -NTUN, 0.17, 2.55, -2.894104, -16.966614, 20.375925, -20.990841, 26.899977, -33.225563, -50.979389, 61.391388, 3.36, -3.21 -CTUN, 541, 0.00, 4.09, 2.597609, 0, 0, 17, 246, 0 -GPS, 3, 594579200, 8, 2.25, 44.0290187, -77.7367029, 2.67, 88.24, 0.41, 42.74 -ATT, 0.00, -0.39, 0.00, -1.22, 0.00, 83.67, 83.10 -NTUN, 0.17, 2.48, -5.145203, -16.021484, 15.101252, -17.455166, 26.354866, -32.985622, -58.746735, 68.356750, 3.83, -3.59 -CTUN, 541, 0.00, 4.52, 2.597609, 0, 0, -5, 251, 0 -ATT, 0.00, 1.90, 0.00, -1.43, 0.00, 83.66, 83.10 -NTUN, 0.16, 2.40, -7.779907, -15.090881, 9.540556, -15.090881, 27.846958, -30.312803, -70.168640, 56.881660, 4.43, -2.84 -GPS, 3, 594579400, 8, 2.25, 44.0290199, -77.7367031, 2.78, 88.31, 0.55, 1.83 -CTUN, 541, 0.00, 3.97, 2.597609, 0, 0, -23, 281, 0 -ATT, 0.00, 1.50, 0.00, -3.43, 0.00, 83.71, 83.10 -NTUN, 0.16, 2.30, -10.883850, -14.440247, 3.518005, -14.440247, 24.314655, -28.401751, -76.629211, 38.441929, 4.67, -1.74 -DU32, 7, 426225 -CURR, 541, 333537, 1405, 1241, 4984, 543.635380 -CTUN, 542, 0.00, 3.64, 2.597609, 0, 0, -43, 283, 0 -ATT, 0.00, 2.82, 0.00, -2.92, 0.00, 83.72, 83.10 -NTUN, 0.18, 2.23, -14.189362, -14.055237, -2.611547, -14.055237, 21.597950, -25.064457, -84.295532, 34.850098, 5.09, -1.48 -GPS, 3, 594579600, 8, 2.25, 44.0290208, -77.7367032, 2.80, 88.26, 0.55, 1.83 -CTUN, 541, 0.00, 3.80, 2.597609, 0, 0, -48, 313, 0 -NTUN, 0.18, 2.23, -17.485840, -14.097656, -8.668527, -14.097656, 16.815680, -20.686464, -85.569794, 25.575806, 5.11, -0.94 -ATT, 0.00, 4.00, 0.00, -2.14, 0.00, 83.69, 83.10 -NTUN, 0.22, 2.17, -20.506271, -14.612122, -14.414331, -14.612122, 10.775496, -17.552870, -81.889153, 16.906284, 4.84, -0.44 -MODE, ALT_HOLD, 269 -CTUN, 541, 0.00, 3.77, 2.597609, 0, 0, -41, 299, 0 -GPS, 3, 594579800, 8, 2.25, 44.0290215, -77.7367034, 2.79, 88.20, 0.46, 358.62 -ATT, 0.00, 4.40, 0.00, -1.83, 0.00, 83.59, 83.10 -CTUN, 541, 0.00, 3.39, 2.597609, 0, 0, -28, 283, 0 -ATT, 0.00, 1.92, 0.00, -0.99, 0.00, 83.59, 83.10 -GPS, 3, 594580000, 8, 2.25, 44.0290222, -77.7367036, 2.79, 88.19, 0.34, 355.35 -CTUN, 541, 0.00, 3.51, 2.597609, 0, 0, -22, 298, 0 -ATT, 0.00, 0.97, 0.00, -0.30, 0.00, 83.78, 83.10 -CTUN, 542, 0.00, 3.45, 2.597609, 0, 0, -18, 275, 0 -ATT, 0.00, 0.95, 0.00, -0.60, 0.00, 83.73, 83.10 -GPS, 3, 594580200, 8, 2.25, 44.0290226, -77.7367042, 2.80, 88.16, 0.24, 352.13 -CTUN, 541, 0.00, 3.06, 2.597609, 0, 0, -17, 290, 0 -ATT, 0.00, 0.82, 0.00, 0.02, 0.00, 83.89, 83.10 -CTUN, 541, 0.00, 2.88, 2.597609, 0, 0, -21, 284, 0 -ATT, -5.63, -0.16, 5.59, -0.09, 0.00, 84.05, 83.10 -GPS, 3, 594580400, 8, 2.25, 44.0290229, -77.7367047, 2.79, 88.13, 0.24, 352.13 -CTUN, 541, 0.00, 2.75, 2.597609, 0, 0, -21, 284, 0 -ATT, -2.81, -2.92, 7.61, 2.68, 0.00, 84.18, 83.10 -CTUN, 540, 0.00, 2.22, 2.597609, 0, 0, -22, 299, 0 -GPS, 3, 594580600, 8, 2.25, 44.0290231, -77.7367053, 2.73, 88.13, 0.21, 352.13 -ATT, -1.99, -2.21, 10.00, 4.67, 0.00, 84.11, 83.10 -CTUN, 542, 0.00, 1.63, 2.597609, 0, 0, -19, 305, 0 -DU32, 7, 426229 -CURR, 541, 336731, 1373, 1836, 4962, 548.834230 -ATT, -5.99, -1.83, 10.11, 6.34, 0.00, 84.03, 83.10 -CTUN, 541, 0.00, 1.22, 2.597609, 0, 1, -15, 297, 0 -GPS, 3, 594580800, 8, 2.25, 44.0290232, -77.7367061, 2.64, 88.14, 0.21, 352.13 -CTUN, 541, 0.00, 1.01, 2.597609, 0, 1, -11, 306, 0 -ATT, -10.45, -4.42, 10.11, 7.64, 0.00, 84.05, 83.10 -CTUN, 541, 0.00, 0.81, 2.597609, 0, 2, 2, 302, 0 -ATT, -12.80, -7.09, 6.30, 7.92, 0.00, 84.17, 83.10 -GPS, 3, 594581000, 8, 2.25, 44.0290236, -77.7367071, 2.49, 88.13, 0.49, 305.23 -CTUN, 541, 0.00, 0.49, 2.597609, 0, 3, 10, 319, 0 -ATT, -12.57, -9.23, 2.38, 6.65, 0.00, 84.21, 83.10 -CTUN, 540, 0.00, 0.62, 2.597609, 0, 2, 20, 285, 0 -GPS, 3, 594581200, 8, 2.25, 44.0290246, -77.7367087, 2.42, 88.17, 0.49, 305.23 -ATT, -8.57, -9.76, 0.00, 3.58, 0.00, 84.20, 83.10 -CTUN, 542, 0.00, 0.72, 2.597609, 0, 1, 28, 276, 0 -ATT, -4.22, -8.02, 0.00, 3.06, 0.00, 83.79, 83.10 -GPS, 3, 594581400, 8, 2.25, 44.0290263, -77.7367105, 2.33, 88.29, 1.10, 319.10 -CTUN, 539, 0.00, 1.18, 2.597609, 0, 1, 27, 305, 0 -ATT, -4.69, -5.64, 0.00, 2.20, -0.36, 83.40, 83.02 -CTUN, 535, 0.00, 1.29, 2.597609, 0, 0, 26, 283, 0 -ATT, -5.75, -6.08, 0.00, 0.97, -2.31, 83.08, 82.19 -GPS, 3, 594581600, 8, 2.25, 44.0290285, -77.7367125, 2.28, 88.38, 1.44, 324.89 -CTUN, 533, 0.00, 1.20, 2.597609, 0, 1, 25, 310, 0 -ATT, -7.75, -6.71, 0.00, 1.21, -2.92, 81.43, 80.58 -CTUN, 525, 0.00, 1.12, 2.597609, 0, 1, 26, 294, 0 -ATT, -8.10, -6.62, 0.00, 0.50, -3.04, 79.83, 79.06 -GPS, 3, 594581800, 8, 2.25, 44.0290313, -77.7367144, 2.26, 88.50, 1.75, 330.97 -CTUN, 523, 0.00, 1.12, 2.597609, 0, 1, 29, 299, 0 -ATT, -8.81, -7.49, 0.00, 0.61, -3.17, 77.78, 77.14 -CTUN, 524, 0.00, 1.22, 2.597609, 0, 1, 31, 290, 0 -GPS, 3, 594582000, 8, 2.25, 44.0290341, -77.7367162, 2.24, 88.57, 1.69, 332.57 -ATT, -8.45, -7.62, 0.00, -0.06, -3.41, 75.85, 75.18 -CTUN, 524, 0.00, 1.24, 2.597609, 0, 1, 31, 290, 0 -ATT, -7.40, -8.12, 0.00, 0.42, -3.53, 74.15, 73.58 -GPS, 3, 594582200, 8, 2.25, 44.0290375, -77.7367179, 2.23, 88.70, 1.99, 337.56 -CTUN, 508, 0.00, 1.24, 2.597609, 0, 1, 35, 287, 0 -ATT, -2.46, -6.84, 0.00, 0.06, -3.53, 72.05, 71.40 -CTUN, 494, 0.00, 1.39, 2.597609, 0, 0, 32, 291, 0 -ATT, -1.05, -4.41, 0.00, 0.31, -3.65, 69.95, 69.61 -GPS, 3, 594582400, 8, 2.25, 44.0290410, -77.7367194, 2.22, 88.77, 1.99, 337.56 -CTUN, 461, 0.00, 1.59, 2.597609, 0, 0, 34, 289, 0 -ATT, 0.00, -3.04, 0.00, 0.22, -3.53, 68.04, 67.78 -CTUN, 430, 0.00, 1.60, 2.597609, 0, 0, 33, 288, 0 -GPS, 3, 594582600, 8, 2.25, 44.0290449, -77.7367208, 2.23, 88.90, 2.09, 340.28 -ATT, 0.00, -2.17, 2.02, 0.60, -3.78, 65.80, 65.61 -CTUN, 417, 0.00, 1.72, 2.597609, 0, 0, 33, 273, 0 -ATT, 0.00, -1.46, 4.16, 1.17, -3.53, 64.10, 64.00 -GPS, 3, 594582800, 8, 2.25, 44.0290489, -77.7367225, 2.25, 89.01, 2.31, 343.25 -CTUN, 407, 0.00, 1.66, 2.597609, 0, 0, 32, 293, 0 -ATT, 0.00, -1.23, 6.90, 3.16, -3.53, 62.04, 61.94 -DU32, 7, 426229 -CURR, 399, 342025, 1384, 1380, 4855, 557.343570 -CTUN, 388, 0.00, 1.69, 2.596700, 0, 0, 28, 291, -3 -ATT, 0.00, -0.82, 7.97, 4.33, -3.53, 60.39, 60.27 -GPS, 3, 594583000, 8, 2.25, 44.0290528, -77.7367243, 2.27, 89.14, 2.33, 342.98 -CTUN, 363, 0.00, 1.64, 2.587359, 0, 0, 28, 283, -20 -ATT, 0.00, -0.27, 7.14, 5.55, -3.41, 58.25, 58.16 -CTUN, 353, 0.00, 1.64, 2.551607, 0, 0, 26, 283, -25 -ATT, 0.00, -0.56, 4.88, 6.07, -3.41, 56.76, 56.56 -GPS, 3, 594583200, 8, 2.25, 44.0290563, -77.7367263, 2.28, 89.26, 2.21, 341.19 -CTUN, 335, 0.00, 2.31, 2.551607, 0, 0, 26, 291, -25 -ATT, 0.00, -0.61, 2.02, 5.04, -3.29, 55.17, 54.82 -CTUN, 320, 0.00, 4.66, 2.452305, 0, 0, 19, 264, -48 -GPS, 3, 594583400, 8, 2.25, 44.0290600, -77.7367291, 2.30, 89.40, 2.35, 336.66 -ATT, 0.00, -0.07, 0.00, 3.00, -3.29, 53.05, 52.67 -CTUN, 305, 0.00, 4.07, 2.382194, 0, 0, 12, 230, -56 -ATT, 0.00, 0.14, 0.00, 2.35, -3.29, 51.54, 51.17 -GPS, 3, 594583600, 8, 2.25, 44.0290635, -77.7367326, 2.45, 89.52, 2.35, 336.66 -CTUN, 285, 0.00, 2.63, 2.339545, 0, 0, 1, 266, -63 -ATT, 0.00, -0.30, 0.00, 2.81, -3.29, 49.54, 49.05 -CTUN, 268, 0.00, 3.26, 2.210331, 0, 0, -35, 256, -82 -ATT, 0.00, -0.60, 0.00, 1.05, -3.29, 47.89, 47.39 -GPS, 3, 594583800, 8, 2.25, 44.0290669, -77.7367359, 2.47, 89.63, 2.40, 328.29 -CTUN, 267, 0.00, 5.05, 2.127445, 0, 0, -53, 280, -82 -ATT, 0.00, 0.21, 0.00, -0.69, -3.29, 46.23, 45.70 -CTUN, 269, 0.00, 6.39, 2.029515, 0, 0, -61, 278, -81 -GPS, 3, 594584000, 8, 2.25, 44.0290704, -77.7367398, 2.51, 89.62, 2.40, 328.29 -ATT, 0.00, -0.25, 0.00, 0.77, -2.80, 44.34, 43.87 -CTUN, 269, 0.00, 9.30, 1.956628, 0, 0, -69, 241, -81 -ATT, 0.00, 0.09, 0.00, 1.46, -2.56, 42.95, 42.65 -GPS, 3, 594584200, 8, 2.25, 44.0290734, -77.7367442, 2.70, 89.64, 2.57, 322.91 -CTUN, 269, 0.00, 18.06, 1.867486, 0, 0, -77, 211, -81 -ATT, 0.00, 0.93, 0.00, 0.58, -2.31, 41.63, 41.25 -CTUN, 268, 0.00, 25.87, 1.737278, 0, 0, -109, 130, -82 -ATT, 0.00, 1.00, 0.00, 0.64, -2.31, 40.49, 40.18 -GPS, 3, 594584400, 8, 2.25, 44.0290763, -77.7367479, 3.59, 89.55, 2.46, 317.08 -CTUN, 269, 0.00, 46.28, 1.688516, 0, 0, -123, 130, -81 -ATT, 0.00, -0.19, 0.00, 0.87, -2.19, 38.84, 38.68 -CTUN, 269, 0.00, 68.21, 1.550296, 0, 0, -162, 130, -81 -ATT, 0.00, 1.07, 0.00, 1.88, -2.07, 37.52, 37.59 -GPS, 3, 594584600, 8, 2.25, 44.0290795, -77.7367518, 6.03, 89.32, 2.57, 315.82 -CTUN, 324, 0.00, 116.53, 1.472306, 0, 0, -169, 130, -47 -ATT, 0.00, 3.82, 0.00, -0.14, -1.82, 35.82, 36.55 -CTUN, 412, 0.00, 43.81, 2.670000, 0, 0, -158, 130, -18 -GPS, 3, 594584800, 8, 2.25, 44.0290819, -77.7367558, 12.34, 88.96, 2.54, 312.02 -ATT, 0.00, 7.41, 0.00, -6.24, -1.46, 33.79, 35.58 -CTUN, 445, 0.00, 1.00, 5.360000, 0, 0, -150, 130, 0 -ATT, 0.00, 10.87, 0.00, -9.03, -1.46, 32.10, 34.83 -GPS, 3, 594585000, 8, 2.25, 44.0290852, -77.7367603, 12.84, 88.66, 2.78, 312.50 -CTUN, 522, 0.00, 0.78, 5.710000, 0, 0, -171, 130, 0 -ATT, 0.00, 13.05, 0.00, -8.08, -1.09, 31.14, 34.15 -CTUN, 554, 0.00, -0.11, 5.710000, 0, 0, -212, 130, 0 -ATT, 0.00, 11.31, 0.00, -6.63, -0.73, 31.04, 33.75 -GPS, 3, 594585200, 8, 2.25, 44.0290875, -77.7367630, 11.42, 88.18, 2.18, 313.08 -CTUN, 553, 0.00, -2.11, 5.710000, 0, 0, -225, 130, 0 -ATT, 0.00, -7.67, 0.00, -2.03, 0.00, 31.40, 33.47 -CTUN, 552, 0.00, -1.89, 5.710000, 0, 0, -279, 130, 0 -ATT, 0.00, -17.24, 0.00, -1.47, 0.00, 32.89, 33.47 -GPS, 3, 594585400, 8, 2.25, 44.0290902, -77.7367652, 9.90, 87.83, 2.18, 313.08 -CTUN, 554, 0.00, -1.18, 5.710000, 0, 0, -349, 130, 0 -ATT, 0.00, -21.29, 0.00, -8.13, 0.00, 36.75, 33.47 -CTUN, 552, 0.00, -1.04, 5.710000, 0, 5, -396, 193, 0 -GPS, 3, 594585600, 8, 2.25, 44.0290913, -77.7367672, 8.34, 87.52, 1.91, 315.30 -ATT, 0.00, -16.98, 0.00, -15.23, 0.00, 40.35, 33.47 -DU32, 7, 426229 -CURR, 552, 346767, 1427, 701, 4793, 564.500790 -CTUN, 552, 0.00, -1.15, 5.710000, 0, 47, -434, 895, 0 -ATT, 0.00, -9.32, 0.59, -14.93, 0.00, 40.62, 33.47 -PM, 0, 0, 50, 109, 1003, 12024, 10, 0 -GPS, 3, 594585800, 8, 2.25, 44.0290915, -77.7367671, 7.11, 87.64, 1.42, 316.89 -CTUN, 553, 0.00, -1.13, 5.710000, 0, 0, -375, 496, 0 -ATT, 4.12, 2.04, 7.14, 0.06, 0.00, 41.74, 33.47 -CTUN, 492, 0.00, -1.30, 5.710000, 0, 0, -172, 130, 0 -ATT, 4.47, 7.36, 11.90, 11.58, 0.00, 44.11, 34.11 -GPS, 3, 594586000, 8, 2.25, 44.0290936, -77.7367678, 5.85, 87.73, 0.97, 349.84 -CTUN, 452, 0.00, -1.08, 5.710000, 0, 3, -156, 211, 0 -ATT, 4.35, 1.74, 0.00, 13.67, 0.00, 44.30, 34.76 -CTUN, 391, 0.00, -0.70, 5.709593, 0, 10, -153, 805, -1 -ATT, 0.00, -8.82, -2.36, 3.76, 0.00, 43.71, 34.76 -GPS, 3, 594586200, 8, 2.25, 44.0290948, -77.7367679, 5.01, 88.15, 0.97, 349.84 -CTUN, 393, 0.00, -0.32, 5.705237, 0, 13, -95, 543, -5 -ATT, 0.00, -14.20, -6.14, -11.23, 0.00, 46.58, 36.58 -CTUN, 394, 0.00, 0.28, 5.700876, 0, 11, -4, 393, -4 -ATT, 1.29, -2.97, -2.12, -11.22, 0.00, 45.86, 37.27 -GPS, 3, 594586400, 8, 2.25, 44.0290965, -77.7367692, 4.57, 88.85, 0.66, 353.67 -CTUN, 367, 0.00, 1.29, 5.695426, 0, 1, 56, 455, -6 -ATT, 7.06, 6.85, -2.36, 2.11, 0.00, 44.06, 37.27 -GPS, 3, 594586600, 8, 2.25, 44.0290991, -77.7367708, 4.42, 89.92, 0.66, 353.67 -CTUN, 227, 0.00, 55.46, 5.639901, 0, 2, 109, 297, -66 -ATT, 9.54, 8.44, -8.50, 3.56, 0.00, 42.34, 37.27 -CTUN, 227, 0.00, 85.57, 5.445190, 0, 0, 133, 130, -108 -ATT, 8.24, 5.94, -10.74, -0.77, 0.00, 40.98, 37.27 -GPS, 3, 594586800, 8, 2.25, 44.0291016, -77.7367724, 7.71, 90.85, 1.10, 359.24 -CTUN, 227, 0.00, 11.64, 5.390913, 0, 0, 132, 130, -108 -ATT, 7.18, 2.63, -9.33, -10.04, 0.00, 39.47, 37.27 -CTUN, 228, 0.00, 4.50, 5.250577, 0, 0, 92, 130, -108 -ATT, 6.95, 2.85, -7.20, -15.46, 0.00, 38.65, 37.27 -GPS, 3, 594587000, 8, 2.25, 44.0291029, -77.7367724, 9.74, 91.59, 1.10, 359.24 -CTUN, 229, 0.00, 4.35, 5.121953, 0, 0, 26, 130, -106 -ATT, 6.47, 5.09, -6.73, -14.32, 0.00, 38.47, 37.27 -CTUN, 229, 0.00, 4.87, 4.995184, 0, 0, -43, 130, -106 -GPS, 3, 594587200, 8, 2.25, 44.0291046, -77.7367729, 9.29, 92.36, 0.72, 2.51 -ATT, 5.41, 7.28, -5.78, -6.80, 0.00, 38.60, 37.27 -DU32, 7, 426229 -CURR, 228, 351820, 1426, 387, 4984, 578.078430 -CTUN, 229, 0.00, 19.56, 4.897755, 0, 0, -99, 130, -107 -ATT, 4.12, 6.46, -4.96, -1.46, 0.00, 38.37, 37.27 -GPS, 3, 594587400, 8, 2.25, 44.0291070, -77.7367734, 9.18, 92.97, 0.88, 359.50 -CTUN, 228, 0.00, 50.94, 4.781951, 0, 0, -153, 130, -106 -ATT, 3.65, 3.63, -4.84, -5.18, 0.00, 37.74, 37.27 -CTUN, 229, 0.00, 10.89, 4.622697, 0, 0, -215, 130, -106 -ATT, 2.94, 1.62, -4.72, -11.10, 0.00, 37.35, 37.27 -GPS, 3, 594587600, 8, 2.25, 44.0291090, -77.7367738, 10.57, 93.34, 1.41, 349.01 -CTUN, 228, 0.00, 6.08, 4.548018, 0, 0, -246, 130, -107 -ATT, 2.94, 2.40, -4.96, -11.22, 0.00, 37.31, 37.27 -CTUN, 227, 0.00, 11.19, 4.387097, 0, 0, -323, 130, -108 -MODE, STABILIZE, 269 -ATT, 2.35, 4.89, -4.13, -3.46, 0.00, 37.52, 37.27 -GPS, 3, 594587800, 8, 2.25, 44.0291111, -77.7367736, 9.77, 93.54, 1.49, 348.46 -CTUN, 227, 0.00, 123.86, 0.000000, 0, 0, -354, 174, 0 -ATT, 2.94, 5.02, -4.13, 1.06, 0.00, 37.48, 37.27 -CTUN, 227, 0.00, 143.18, 0.000000, 0, 0, -364, 174, 0 -ATT, 2.94, 3.52, -1.65, -5.89, 0.00, 37.16, 37.27 -GPS, 3, 594588000, 8, 2.25, 44.0291131, -77.7367730, 15.74, 93.38, 1.57, 347.46 -CTUN, 226, 0.00, 20.31, 0.000000, 0, 0, -347, 174, 0 -ATT, 3.88, 2.62, -0.59, -9.42, 0.00, 37.16, 37.27 -CTUN, 247, 0.00, 7.75, 0.000000, 0, 0, -371, 175, 0 -GPS, 3, 594588200, 8, 2.25, 44.0291154, -77.7367723, 17.43, 93.09, 1.57, 347.46 -ATT, 4.12, 3.23, 0.00, -0.67, 0.00, 37.53, 37.27 -CTUN, 247, 0.00, 126.37, 0.000000, 0, 0, -424, 183, 0 -DU32, 7, 426237 -CURR, 247, 353351, 1359, 1970, 5006, 580.387760 -ATT, 4.12, 3.23, 0.00, 7.42, 0.00, 37.85, 37.27 -CTUN, 282, 0.00, 200.71, 0.000000, 0, 0, -403, 191, 0 -GPS, 3, 594588400, 8, 2.25, 44.0291172, -77.7367711, 22.46, 92.57, 1.69, 348.21 -ATT, 2.94, 5.61, 0.00, 0.54, 0.00, 37.85, 37.27 -CTUN, 375, 0.00, 175.47, 0.000000, 0, 0, -353, 242, 0 -ATT, 2.94, 10.27, 0.00, -9.94, 0.00, 36.74, 37.27 -CTUN, 409, 0.00, 13.86, 0.000000, 0, 4, -293, 260, 0 -GPS, 3, 594588600, 8, 2.25, 44.0291196, -77.7367713, 31.92, 92.18, 1.49, 348.89 -ATT, 3.18, 9.60, 0.00, -13.24, 0.00, 35.84, 37.27 -CTUN, 432, 0.00, 4.55, 0.000000, 0, 6, -304, 274, 0 -ATT, 3.53, 1.72, 0.00, -6.13, 0.00, 37.09, 37.27 -CTUN, 437, 0.00, 7.68, 0.000000, 0, 1, -324, 272, 0 -GPS, 3, 594588800, 8, 2.25, 44.0291220, -77.7367706, 29.55, 91.73, 1.65, 345.46 -CTUN, 435, 0.00, 78.23, 0.000000, 0, 0, -336, 270, 0 -ATT, 0.00, 0.22, 5.00, -0.93, 0.00, 37.66, 37.27 -CTUN, 451, 0.00, 156.24, 0.000000, 0, 0, -319, 277, 0 -ATT, 0.00, 3.90, 9.76, 1.85, 0.00, 38.17, 37.27 -GPS, 3, 594589000, 8, 2.25, 44.0291236, -77.7367697, 31.61, 91.33, 1.56, 349.51 -CTUN, 481, 0.00, 210.34, 0.000000, 0, 0, -262, 291, 0 -ATT, 0.00, 3.71, 20.71, 0.91, 0.00, 37.80, 37.27 -CTUN, 508, 0.00, 71.43, 0.000000, 0, 0, -190, 311, 0 -GPS, 3, 594589200, 8, 2.25, 44.0291259, -77.7367689, 41.93, 90.90, 1.44, 0.79 -ATT, 0.00, 1.16, 21.90, 7.67, 0.00, 37.98, 37.27 -CTUN, 543, 0.00, 3.12, 0.000000, 0, 2, -173, 359, 0 -DU32, 7, 426237 -CURR, 552, 355817, 1334, 2564, 4962, 584.790590 -ATT, 0.00, 2.17, 21.30, 12.07, 0.00, 37.86, 37.27 -CTUN, 573, 0.00, 2.52, 0.000000, 0, 6, -173, 402, 0 -GPS, 3, 594589400, 8, 2.25, 44.0291266, -77.7367682, 40.70, 90.16, 0.87, 358.64 -ATT, 0.00, -1.63, 21.42, 12.58, 0.00, 37.82, 37.27 -CTUN, 581, 0.00, 1.32, 0.000000, 0, 6, -164, 419, 0 -ATT, 0.82, -1.88, 21.90, 13.04, 0.00, 38.52, 37.27 -CTUN, 582, 0.00, 1.23, 0.000000, 0, 8, -147, 422, 0 -GPS, 3, 594589600, 8, 2.25, 44.0291272, -77.7367680, 37.82, 89.43, 0.63, 352.91 -ATT, 0.58, -0.37, 21.19, 20.20, 0.00, 39.48, 37.27 -CTUN, 579, 0.00, 1.10, 0.000000, 0, 17, -117, 430, 0 -ATT, 0.70, -2.64, 5.23, 20.78, 0.00, 41.08, 37.27 -CTUN, 556, 0.00, 0.56, 0.000000, 0, 19, -78, 419, 0 -GPS, 3, 594589800, 8, 2.25, 44.0291276, -77.7367687, 35.04, 88.87, 0.63, 352.91 -CTUN, 469, 0.00, 0.21, 0.000000, 0, 3, -40, 288, 0 -ATT, 4.94, 4.23, 0.00, 10.59, 0.00, 40.56, 37.27 -CTUN, 349, 0.00, -0.02, 0.000000, 0, 1, -24, 235, 0 -GPS, 3, 594590000, 8, 2.25, 44.0291272, -77.7367717, 32.40, 88.57, 0.34, 352.91 -ATT, 8.01, 8.73, -5.43, 6.68, 0.00, 39.28, 37.27 -CTUN, 328, 0.00, -0.27, 0.000000, 0, 2, -28, 222, 0 -ATT, 8.12, 9.47, -8.74, 5.36, 0.00, 38.18, 37.27 -CTUN, 294, 0.00, -0.44, 0.000000, 0, 1, -39, 206, 0 -GPS, 3, 594590200, 8, 2.25, 44.0291261, -77.7367765, 29.69, 88.39, 0.90, 308.03 -ATT, 7.06, 3.72, -10.98, -5.44, 0.00, 36.79, 37.27 -CTUN, 272, 0.00, -0.11, 0.000000, 0, 1, -68, 200, 0 -ATT, 6.95, 6.18, -13.11, -16.22, 0.00, 35.99, 37.27 -GPS, 3, 594590400, 8, 2.25, 44.0291251, -77.7367810, 27.69, 88.05, 1.85, 254.26 -CTUN, 270, 0.00, 0.05, 0.000000, 0, 3, -86, 196, 0 -DU32, 7, 426237 -CURR, 270, 358966, 1397, 1033, 4897, 592.722840 -ATT, 6.36, 10.44, -14.76, -25.25, 0.00, 34.90, 37.27 -CTUN, 278, 0.00, -0.04, 0.000000, 0, 8, -129, 204, 0 -ATT, 5.18, 9.05, -14.76, -24.73, 0.00, 35.01, 37.27 -GPS, 3, 594590600, 8, 2.25, 44.0291245, -77.7367844, 24.95, 87.63, 1.50, 253.78 -CTUN, 280, 0.00, -0.80, 0.000000, 0, 6, -167, 204, 0 -ATT, 0.58, 4.10, -6.61, -8.72, 0.00, 37.33, 37.27 -CTUN, 295, 0.00, -2.45, 0.000000, 0, 0, -31, 205, 0 -ATT, 0.00, 0.90, 0.00, 4.95, 0.00, 37.40, 37.27 -GPS, 3, 594590800, 8, 2.25, 44.0291240, -77.7367859, 22.82, 87.23, 0.84, 253.78 -CTUN, 292, 0.00, -0.77, 0.000000, 0, 0, -10, 204, 0 -ATT, 0.00, 1.32, 0.00, -8.49, 0.00, 37.19, 37.27 -CTUN, 293, 0.00, -0.81, 0.000000, 0, 1, -37, 205, 0 -GPS, 3, 594591000, 8, 2.25, 44.0291231, -77.7367878, 20.99, 86.92, 0.79, 253.78 -ATT, 1.64, 1.88, 0.00, -19.86, 0.00, 37.24, 37.27 -CTUN, 293, 0.00, -0.82, 0.000000, 0, 4, -64, 208, 0 -ATT, 2.23, 2.04, 0.00, -16.01, 0.00, 37.37, 37.27 -CTUN, 294, 0.00, -1.00, 0.000000, 0, 3, -97, 207, 0 -GPS, 3, 594591200, 8, 2.25, 44.0291228, -77.7367875, 19.38, 87.01, 0.79, 253.78 -CTUN, 274, 0.00, -0.96, 0.000000, 0, 0, -141, 196, 0 -ATT, 0.00, 0.78, 6.07, -0.60, 0.00, 37.85, 37.27 -CTUN, 258, 0.00, -0.95, 0.000000, 0, 0, -173, 188, 0 -ATT, 0.00, -0.62, 13.09, 5.22, 0.00, 38.14, 37.27 -GPS, 3, 594591400, 8, 2.25, 44.0291232, -77.7367869, 17.57, 87.17, 0.51, 220.52 -CTUN, 210, 0.00, -1.05, 0.000000, 0, 0, -212, 168, 0 -DU32, 7, 426237 -CURR, 210, 360772, 1407, 734, 5006, 596.090390 -ATT, 0.00, 0.33, 12.73, 1.79, 0.00, 38.35, 37.27 -CTUN, 175, 0.00, -1.33, 0.000000, 0, 0, -243, 150, 0 -ATT, 0.00, 3.31, 8.33, 0.83, 0.00, 38.47, 37.27 -GPS, 3, 594591600, 8, 2.25, 44.0291237, -77.7367863, 15.75, 87.21, 0.51, 220.52 -CTUN, 134, 0.00, -2.05, 0.000000, 0, 0, -272, 132, 0 -ATT, 0.00, 3.68, 6.66, -1.62, 0.00, 38.75, 38.75 -CTUN, 0, 0.00, -2.53, 0.000000, 0, 0, -142, 0, 0 -ATT, 0.00, 3.08, 6.78, -8.15, 0.00, 38.56, 38.56 -GPS, 3, 594591800, 8, 2.25, 44.0291242, -77.7367854, 13.98, 87.05, 0.42, 220.52 -CTUN, 0, 0.00, -1.66, 0.000000, 0, 0, -197, 0, 0 -ATT, 0.00, 2.10, 6.54, -8.61, 0.00, 38.11, 38.11 -CTUN, 0, 0.00, -1.99, 0.000000, 0, 0, -182, 0, 0 -ATT, 0.00, 3.81, 5.71, -2.63, 0.00, 38.05, 38.05 -GPS, 3, 594592000, 7, 2.61, 44.0291241, -77.7367847, 12.43, 87.02, 0.42, 220.52 -CTUN, 0, 0.00, -1.82, 0.000000, 0, 0, -192, 0, 0 -ATT, 0.00, 3.50, 1.19, -2.88, 0.00, 38.35, 38.35 -CTUN, 0, 0.00, -1.87, 0.000000, 0, 0, -198, 0, 0 -ATT, 0.00, 3.26, 0.00, -3.63, 0.00, 38.57, 38.57 -GPS, 3, 594592200, 8, 2.25, 44.0291242, -77.7367846, 10.99, 87.00, 0.36, 220.52 -CTUN, 0, 0.00, -1.84, 0.000000, 0, 0, -204, 0, 0 -ATT, 0.00, 3.32, 0.00, -3.46, 0.00, 38.78, 38.78 -CTUN, 0, 0.00, -1.84, 0.000000, 0, 0, -208, 0, 0 -ATT, 0.00, 3.36, 0.00, -3.40, 0.00, 38.99, 38.99 -GPS, 3, 594592400, 7, 2.61, 44.0291246, -77.7367844, 9.63, 87.10, 0.24, 220.52 -CTUN, 0, 0.00, -1.56, 0.000000, 0, 0, -214, 0, 0 -DU32, 7, 426173 -CURR, 0, 361059, 1450, 4, 4940, 596.525270 -ATT, 0.00, 3.32, 0.00, -3.41, 0.00, 39.19, 39.19 -CTUN, 0, 0.00, -1.69, 0.000000, 0, 0, -218, 0, 0 -ATT, 0.00, 3.26, 0.00, -3.42, 0.00, 39.38, 39.38 -GPS, 3, 594592600, 8, 2.25, 44.0291248, -77.7367842, 8.37, 87.04, 0.10, 220.52 -CTUN, 0, 0.00, -1.62, 0.000000, 0, 0, -222, 0, 0 -ATT, 0.00, 3.21, 0.00, -3.43, 0.00, 39.58, 39.58 -CTUN, 0, 0.00, -1.61, 0.000000, 0, 0, -226, 0, 0 -ATT, 0.00, 3.16, 0.00, -3.42, -3.29, 39.78, 39.78 -GPS, 3, 594592800, 8, 2.25, 44.0291250, -77.7367844, 7.19, 87.15, 0.19, 220.52 -CTUN, 0, 0.00, -1.60, 0.000000, 0, 0, -230, 0, 0 -ATT, 0.00, 3.16, 0.00, -3.41, -41.46, 39.98, 39.98 -CTUN, 0, 0.00, -1.53, 0.000000, 0, 0, -234, 0, 0 -ATT, 0.00, 3.19, 0.00, -3.39, -44.51, 40.14, 40.14 -GPS, 3, 594593000, 8, 2.25, 44.0291257, -77.7367851, 6.09, 87.18, 0.19, 220.52 -CTUN, 0, 0.00, -1.61, 0.000000, 0, 0, -237, 0, 0 -ATT, 0.00, 3.18, 0.00, -3.38, -44.51, 40.33, 40.33 -CTUN, 0, 0.00, -1.47, 0.000000, 0, 0, -240, 0, 0 -ATT, 0.00, 3.15, 0.00, -3.39, -44.51, 40.53, 40.53 -GPS, 3, 594593200, 8, 2.25, 44.0291260, -77.7367859, 4.95, 87.27, 0.07, 220.52 -CTUN, 0, 0.00, -1.54, 0.000000, 0, 0, -243, 0, 0 -ATT, 0.00, 3.12, 0.00, -3.41, -44.51, 40.69, 40.69 -CTUN, 0, 0.00, -1.41, 0.000000, 0, 0, -245, 0, 0 -ATT, 0.00, 3.04, 0.00, -3.43, -44.51, 40.90, 40.90 -GPS, 3, 594593400, 8, 2.25, 44.0291260, -77.7367857, 3.99, 87.29, 0.04, 220.52 -CTUN, 0, 0.00, -1.51, 0.000000, 0, 0, -248, 0, 0 -DU32, 7, 426173 -CURR, 0, 361059, 1450, 3, 4918, 596.539980 -ATT, 0.00, 3.01, 0.00, -3.44, -44.51, 41.08, 41.08 -CTUN, 0, 0.00, -1.53, 0.000000, 0, 0, -249, 0, 0 -ATT, 0.00, 3.00, 0.00, -3.49, -44.51, 41.27, 41.27 -GPS, 3, 594593600, 8, 2.25, 44.0291264, -77.7367854, 3.19, 87.26, 0.04, 220.52 -CTUN, 0, 0.00, -1.56, 0.000000, 0, 0, -251, 0, 0 -ATT, 0.00, 2.99, 0.00, -3.51, -44.51, 41.46, 41.46 diff --git a/Tools/LogAnalyzer/examples/tradheli_brownout.log b/Tools/LogAnalyzer/examples/tradheli_brownout.log deleted file mode 100644 index 81de0bcf8c71c7..00000000000000 --- a/Tools/LogAnalyzer/examples/tradheli_brownout.log +++ /dev/null @@ -1,4197 +0,0 @@ -58 - -ArduCopter V3.0.1 -Free RAM: 1273 -APM 2 -FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format -FMT, 129, 23, PARM, Nf, Name,Value -FMT, 130, 35, GPS, BIBcLLeeEe, Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs -FMT, 131, 27, IMU, ffffff, GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 132, 67, MSG, Z, Message -FMT, 9, 19, CURR, hIhhhf, Thr,ThrInt,Volt,Curr,Vcc,CurrTot -FMT, 11, 13, MOT, hhhhh, Mot1,Mot2,Mot3,Mot4,GGain -FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch -FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit -FMT, 4, 25, CTUN, hcefhhhhh, ThrIn,SonAlt,BarAlt,WPAlt,NavThr,AngBst,CRate,ThrOut,DCRate -FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 6, 17, PM, BBBHHIhB, RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr -FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng -FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw -FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng -FMT, 3, 6, MODE, Mh, Mode,ThrCrs -FMT, 10, 3, STRT, , -FMT, 13, 4, EV, B, Id -FMT, 20, 6, D16, Bh, Id,Value -FMT, 21, 6, DU16, BH, Id,Value -FMT, 22, 8, D32, Bi, Id,Value -FMT, 23, 8, DU32, BI, Id,Value -FMT, 24, 8, DFLT, Bf, Id,Value -FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain -FMT, 16, 15, DMP, ccccCC, DCMRoll,DMPRoll,DCMPtch,DMPPtch,DCMYaw,DMPYaw -FMT, 18, 25, CAM, ILLeccC, GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw -FMT, 19, 5, ERR, BB, Subsys,ECode -PARM, SYSID_SW_MREV, 120.000000 -PARM, SYSID_SW_TYPE, 10.000000 -PARM, SYSID_THISMAV, 1.000000 -PARM, SYSID_MYGCS, 255.000000 -PARM, SERIAL3_BAUD, 57.000000 -PARM, TELEM_DELAY, 0.000000 -PARM, RTL_ALT, 0.000000 -PARM, SONAR_ENABLE, 1.000000 -PARM, SONAR_TYPE, 1.000000 -PARM, SONAR_GAIN, 0.200000 -PARM, BATT_MONITOR, 3.000000 -PARM, FS_BATT_ENABLE, 1.000000 -PARM, FS_GPS_ENABLE, 1.000000 -PARM, FS_GCS_ENABLE, 0.000000 -PARM, VOLT_DIVIDER, 10.495580 -PARM, AMP_PER_VOLT, 27.320000 -PARM, BATT_CAPACITY, 2250.000000 -PARM, MAG_ENABLE, 1.000000 -PARM, FLOW_ENABLE, 0.000000 -PARM, LOW_VOLT, 9.800000 -PARM, SUPER_SIMPLE, 0.000000 -PARM, RTL_ALT_FINAL, 0.000000 -PARM, BATT_VOLT_PIN, 13.000000 -PARM, BATT_CURR_PIN, 12.000000 -PARM, RSSI_PIN, -1.000000 -PARM, THR_ACC_ENABLE, 1.000000 -PARM, WP_YAW_BEHAVIOR, 1.000000 -PARM, WP_TOTAL, 8.000000 -PARM, WP_INDEX, 0.000000 -PARM, CIRCLE_RADIUS, 14.000000 -PARM, CIRCLE_RATE, 5.000000 -PARM, RTL_LOIT_TIME, 1000.000000 -PARM, LAND_SPEED, 100.000000 -PARM, PILOT_VELZ_MAX, 250.000000 -PARM, THR_MIN, 130.000000 -PARM, THR_MAX, 1000.000000 -PARM, FS_THR_ENABLE, 0.000000 -PARM, FS_THR_VALUE, 975.000000 -PARM, TRIM_THROTTLE, 474.000000 -PARM, THR_MID, 500.000000 -PARM, FLTMODE1, 6.000000 -PARM, FLTMODE2, 0.000000 -PARM, FLTMODE3, 9.000000 -PARM, FLTMODE4, 5.000000 -PARM, FLTMODE5, 6.000000 -PARM, FLTMODE6, 3.000000 -PARM, SIMPLE, 0.000000 -PARM, LOG_BITMASK, 830.000000 -PARM, TOY_RATE, 1.000000 -PARM, ESC, 0.000000 -PARM, TUNE, 0.000000 -PARM, TUNE_LOW, 10.000000 -PARM, TUNE_HIGH, 75.000000 -PARM, FRAME, 0.000000 -PARM, CH7_OPT, 5.000000 -PARM, CH8_OPT, 0.000000 -PARM, ARMING_CHECK, 1.000000 -PARM, HS1_MIN, 1000.000000 -PARM, HS1_TRIM, 1550.000000 -PARM, HS1_MAX, 2000.000000 -PARM, HS1_REV, 1.000000 -PARM, HS1_DZ, 0.000000 -PARM, HS2_MIN, 1000.000000 -PARM, HS2_TRIM, 1470.000000 -PARM, HS2_MAX, 2000.000000 -PARM, HS2_REV, -1.000000 -PARM, HS2_DZ, 0.000000 -PARM, HS3_MIN, 1000.000000 -PARM, HS3_TRIM, 1475.000000 -PARM, HS3_MAX, 2000.000000 -PARM, HS3_REV, 1.000000 -PARM, HS3_DZ, 0.000000 -PARM, HS4_MIN, 1239.000000 -PARM, HS4_TRIM, 1471.000000 -PARM, HS4_MAX, 1730.000000 -PARM, HS4_REV, 1.000000 -PARM, HS4_DZ, 0.000000 -PARM, RATE_PIT_FF, 0.020000 -PARM, RATE_RLL_FF, 0.020000 -PARM, RATE_YAW_FF, 0.050000 -PARM, RC1_MIN, 1102.000000 -PARM, RC1_TRIM, 1521.000000 -PARM, RC1_MAX, 1944.000000 -PARM, RC1_REV, 1.000000 -PARM, RC1_DZ, 30.000000 -PARM, RC2_MIN, 1102.000000 -PARM, RC2_TRIM, 1522.000000 -PARM, RC2_MAX, 1944.000000 -PARM, RC2_REV, 1.000000 -PARM, RC2_DZ, 30.000000 -PARM, RC3_MIN, 1101.000000 -PARM, RC3_TRIM, 1386.000000 -PARM, RC3_MAX, 1944.000000 -PARM, RC3_REV, 1.000000 -PARM, RC3_DZ, 10.000000 -PARM, RC4_MIN, 1102.000000 -PARM, RC4_TRIM, 1521.000000 -PARM, RC4_MAX, 1944.000000 -PARM, RC4_REV, 1.000000 -PARM, RC4_DZ, 15.000000 -PARM, RC5_MIN, 1161.000000 -PARM, RC5_TRIM, 1522.000000 -PARM, RC5_MAX, 1813.000000 -PARM, RC5_REV, 1.000000 -PARM, RC5_DZ, 0.000000 -PARM, RC5_FUNCTION, 0.000000 -PARM, RC6_MIN, 1101.000000 -PARM, RC6_TRIM, 1102.000000 -PARM, RC6_MAX, 1944.000000 -PARM, RC6_REV, 1.000000 -PARM, RC6_DZ, 0.000000 -PARM, RC6_FUNCTION, 0.000000 -PARM, RC7_MIN, 1101.000000 -PARM, RC7_TRIM, 1102.000000 -PARM, RC7_MAX, 1944.000000 -PARM, RC7_REV, 1.000000 -PARM, RC7_DZ, 0.000000 -PARM, RC7_FUNCTION, 0.000000 -PARM, RC8_MIN, 1102.000000 -PARM, RC8_TRIM, 1102.000000 -PARM, RC8_MAX, 1944.000000 -PARM, RC8_REV, 1.000000 -PARM, RC8_DZ, 0.000000 -PARM, RC8_FUNCTION, 0.000000 -PARM, RC10_MIN, 1100.000000 -PARM, RC10_TRIM, 1500.000000 -PARM, RC10_MAX, 1900.000000 -PARM, RC10_REV, 1.000000 -PARM, RC10_DZ, 0.000000 -PARM, RC10_FUNCTION, 0.000000 -PARM, RC11_MIN, 1100.000000 -PARM, RC11_TRIM, 1500.000000 -PARM, RC11_MAX, 1900.000000 -PARM, RC11_REV, 1.000000 -PARM, RC11_DZ, 0.000000 -PARM, RC11_FUNCTION, 0.000000 -PARM, RC_SPEED, 125.000000 -PARM, ACRO_P, 4.500000 -PARM, AXIS_ENABLE, 1.000000 -PARM, ACRO_BAL_ROLL, 50.000000 -PARM, ACRO_BAL_PITCH, 50.000000 -PARM, ACRO_TRAINER, 1.000000 -PARM, LED_MODE, 9.000000 -PARM, RATE_RLL_P, 0.060000 -PARM, RATE_RLL_I, 0.250000 -PARM, RATE_RLL_D, 0.000000 -PARM, RATE_RLL_IMAX, 500.000000 -PARM, RATE_PIT_P, 0.064000 -PARM, RATE_PIT_I, 0.150000 -PARM, RATE_PIT_D, 0.000000 -PARM, RATE_PIT_IMAX, 500.000000 -PARM, RATE_YAW_P, 0.100000 -PARM, RATE_YAW_I, 0.035000 -PARM, RATE_YAW_D, 0.001000 -PARM, RATE_YAW_IMAX, 2000.000000 -PARM, LOITER_LAT_P, 1.000000 -PARM, LOITER_LAT_I, 0.500000 -PARM, LOITER_LAT_D, 0.000000 -PARM, LOITER_LAT_IMAX, 400.000000 -PARM, LOITER_LON_P, 1.000000 -PARM, LOITER_LON_I, 0.500000 -PARM, LOITER_LON_D, 0.000000 -PARM, LOITER_LON_IMAX, 400.000000 -PARM, THR_RATE_P, 3.000000 -PARM, THR_RATE_I, 0.000000 -PARM, THR_RATE_D, 0.001000 -PARM, THR_RATE_IMAX, 300.000000 -PARM, THR_ACCEL_P, 0.250000 -PARM, THR_ACCEL_I, 0.600000 -PARM, THR_ACCEL_D, 0.001000 -PARM, THR_ACCEL_IMAX, 500.000000 -PARM, OF_RLL_P, 2.500000 -PARM, OF_RLL_I, 0.500000 -PARM, OF_RLL_D, 0.120000 -PARM, OF_RLL_IMAX, 100.000000 -PARM, OF_PIT_P, 2.500000 -PARM, OF_PIT_I, 0.500000 -PARM, OF_PIT_D, 0.120000 -PARM, OF_PIT_IMAX, 100.000000 -PARM, STB_RLL_P, 4.500000 -PARM, STB_RLL_I, 0.000000 -PARM, STB_RLL_IMAX, 800.000000 -PARM, STB_PIT_P, 3.500000 -PARM, STB_PIT_I, 0.000000 -PARM, STB_PIT_IMAX, 800.000000 -PARM, STB_YAW_P, 3.500000 -PARM, STB_YAW_I, 0.000000 -PARM, STB_YAW_IMAX, 800.000000 -PARM, THR_ALT_P, 0.250000 -PARM, THR_ALT_I, 0.020000 -PARM, THR_ALT_IMAX, 300.000000 -PARM, HLD_LAT_P, 1.000000 -PARM, HLD_LAT_I, 0.000000 -PARM, HLD_LAT_IMAX, 3000.000000 -PARM, HLD_LON_P, 1.000000 -PARM, HLD_LON_I, 0.000000 -PARM, HLD_LON_IMAX, 3000.000000 -PARM, CAM_TRIGG_TYPE, 0.000000 -PARM, CAM_DURATION, 10.000000 -PARM, CAM_SERVO_ON, 1300.000000 -PARM, CAM_SERVO_OFF, 1100.000000 -PARM, COMPASS_OFS_X, -73.707489 -PARM, COMPASS_OFS_Y, 23.727873 -PARM, COMPASS_OFS_Z, 76.562508 -PARM, COMPASS_DEC, 0.016268 -PARM, COMPASS_LEARN, 0.000000 -PARM, COMPASS_USE, 1.000000 -PARM, COMPASS_AUTODEC, 1.000000 -PARM, COMPASS_MOTCT, 0.000000 -PARM, COMPASS_MOT_X, 0.000000 -PARM, COMPASS_MOT_Y, 0.000000 -PARM, COMPASS_MOT_Z, 0.000000 -PARM, COMPASS_ORIENT, 8.000000 -PARM, INS_PRODUCT_ID, 88.000000 -PARM, INS_ACCSCAL_X, 1.000000 -PARM, INS_ACCSCAL_Y, 1.000000 -PARM, INS_ACCSCAL_Z, 1.000000 -PARM, INS_ACCOFFS_X, -0.048499 -PARM, INS_ACCOFFS_Y, 0.088398 -PARM, INS_ACCOFFS_Z, 0.353774 -PARM, INS_GYROFFS_X, -0.020699 -PARM, INS_GYROFFS_Y, 0.003874 -PARM, INS_GYROFFS_Z, 0.000502 -PARM, INS_MPU6K_FILTER, 10.000000 -PARM, INAV_TC_XY, 2.500000 -PARM, INAV_TC_Z, 5.000000 -PARM, WPNAV_SPEED, 1100.000000 -PARM, WPNAV_RADIUS, 274.320010 -PARM, WPNAV_SPEED_UP, 250.000000 -PARM, WPNAV_SPEED_DN, 150.000000 -PARM, WPNAV_LOIT_SPEED, 500.000000 -PARM, WPNAV_ACCEL, 150.000000 -PARM, SR0_RAW_SENS, 2.000000 -PARM, SR0_EXT_STAT, 2.000000 -PARM, SR0_RC_CHAN, 2.000000 -PARM, SR0_RAW_CTRL, 0.000000 -PARM, SR0_POSITION, 3.000000 -PARM, SR0_EXTRA1, 10.000000 -PARM, SR0_EXTRA2, 10.000000 -PARM, SR0_EXTRA3, 2.000000 -PARM, SR0_PARAMS, 0.000000 -PARM, SR3_RAW_SENS, 0.000000 -PARM, SR3_EXT_STAT, 0.000000 -PARM, SR3_RC_CHAN, 0.000000 -PARM, SR3_RAW_CTRL, 0.000000 -PARM, SR3_POSITION, 0.000000 -PARM, SR3_EXTRA1, 0.000000 -PARM, SR3_EXTRA2, 0.000000 -PARM, SR3_EXTRA3, 0.000000 -PARM, SR3_PARAMS, 0.000000 -PARM, AHRS_GPS_GAIN, 1.000000 -PARM, AHRS_GPS_USE, 1.000000 -PARM, AHRS_YAW_P, 0.100000 -PARM, AHRS_RP_P, 0.100000 -PARM, AHRS_WIND_MAX, 0.000000 -PARM, AHRS_TRIM_X, 0.000000 -PARM, AHRS_TRIM_Y, 0.000000 -PARM, AHRS_TRIM_Z, 0.000000 -PARM, AHRS_ORIENTATION, 0.000000 -PARM, AHRS_COMP_BETA, 0.100000 -PARM, AHRS_GPS_MINSATS, 6.000000 -PARM, MNT_MODE, 0.000000 -PARM, MNT_RETRACT_X, 0.000000 -PARM, MNT_RETRACT_Y, 0.000000 -PARM, MNT_RETRACT_Z, 0.000000 -PARM, MNT_NEUTRAL_X, 0.000000 -PARM, MNT_NEUTRAL_Y, 0.000000 -PARM, MNT_NEUTRAL_Z, 0.000000 -PARM, MNT_CONTROL_X, 0.000000 -PARM, MNT_CONTROL_Y, 0.000000 -PARM, MNT_CONTROL_Z, 0.000000 -PARM, MNT_STAB_ROLL, 0.000000 -PARM, MNT_STAB_TILT, 0.000000 -PARM, MNT_STAB_PAN, 0.000000 -PARM, MNT_RC_IN_ROLL, 0.000000 -PARM, MNT_ANGMIN_ROL, -4500.000000 -PARM, MNT_ANGMAX_ROL, 4500.000000 -PARM, MNT_RC_IN_TILT, 0.000000 -PARM, MNT_ANGMIN_TIL, -4500.000000 -PARM, MNT_ANGMAX_TIL, 4500.000000 -PARM, MNT_RC_IN_PAN, 0.000000 -PARM, MNT_ANGMIN_PAN, -4500.000000 -PARM, MNT_ANGMAX_PAN, 4500.000000 -PARM, MNT_JSTICK_SPD, 0.000000 -PARM, GND_ABS_PRESS, 101505.170000 -PARM, GND_TEMP, 29.660503 -PARM, SCHED_DEBUG, 0.000000 -PARM, FENCE_ENABLE, 1.000000 -PARM, FENCE_TYPE, 3.000000 -PARM, FENCE_ACTION, 1.000000 -PARM, FENCE_ALT_MAX, 25.908001 -PARM, FENCE_RADIUS, 91.440002 -PARM, H_SV1_POS, -60.000000 -PARM, H_SV2_POS, 60.000000 -PARM, H_SV3_POS, 180.000000 -PARM, H_ROL_MAX, 4500.000000 -PARM, H_PIT_MAX, 4500.000000 -PARM, H_COL_MIN, 1364.000000 -PARM, H_COL_MAX, 1678.000000 -PARM, H_COL_MID, 1558.000000 -PARM, H_GYR_ENABLE, 0.000000 -PARM, H_SWASH_TYPE, 0.000000 -PARM, H_GYR_GAIN, 1350.000000 -PARM, H_SV_MAN, 0.000000 -PARM, H_PHANG, 0.000000 -PARM, H_COLYAW, 5.000000 -PARM, H_GOV_SETPOINT, 1625.000000 -PARM, H_RSC_MODE, 2.000000 -PARM, H_RSC_RATE, 0.000000 -PARM, H_FLYBAR_MODE, 0.000000 -PARM, H_STAB_COL_MIN, 30.000000 -PARM, H_STAB_COL_MAX, 90.000000 -D32, 9, 21588 -CMD, 8, 0, 16, 0, 0, 0.00, 24.2398206, 54.5793101 -EV, 10 -EV, 15 -GPS, 3, 308900200, 10, 1.49, 24.2398205, 54.5793101, 0.19, 9.48, 0.01, 347.24 -CTUN, 336, 0.27, 0.03, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.23, 0.00, 0.75, 0.00, 215.88, 215.88 -GPS, 3, 308906400, 10, 1.49, 24.2398189, 54.5793105, 0.18, 9.42, 0.01, 347.24 -CTUN, 337, 0.27, 0.03, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.29, 0.00, 0.78, 0.00, 215.88, 215.88 -CTUN, 337, 0.27, 0.12, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.88, 215.88 -GPS, 3, 308906600, 10, 1.49, 24.2398189, 54.5793105, 0.17, 9.41, 0.01, 347.24 -CTUN, 336, 0.27, 0.11, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.87, 215.88 -CTUN, 337, 0.21, -0.01, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.88, 215.88 -GPS, 3, 308906800, 10, 1.49, 24.2398189, 54.5793105, 0.15, 9.41, 0.00, 347.24 -CTUN, 337, 0.26, 0.05, 0.000000, 0, 0, 0, 337, 0 -DU32, 7, 393469 -CURR, 337, 2021, 1232, 0, 4772, 0.000000 -ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 -CTUN, 336, 0.21, 0.04, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 -GPS, 3, 308907000, 10, 1.49, 24.2398188, 54.5793106, 0.14, 9.42, 0.01, 347.24 -CTUN, 337, 0.21, 0.01, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 -CTUN, 337, 0.21, 0.02, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.88, 215.88 -GPS, 3, 308907200, 10, 1.49, 24.2398187, 54.5793106, 0.12, 9.42, 0.01, 347.24 -CTUN, 336, 0.21, 0.03, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.88, 215.88 -CTUN, 337, 0.19, -0.02, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.89, 215.88 -GPS, 3, 308907400, 10, 1.49, 24.2398187, 54.5793106, 0.11, 9.42, 0.01, 347.24 -CTUN, 337, 0.19, 0.04, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.89, 215.88 -CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.89, 215.88 -GPS, 3, 308907600, 10, 1.49, 24.2398187, 54.5793106, 0.09, 9.43, 0.01, 347.24 -CTUN, 337, 0.19, 0.01, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.80, 0.00, 215.90, 215.88 -CTUN, 337, 0.15, -0.02, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -GPS, 3, 308907800, 10, 1.49, 24.2398186, 54.5793107, 0.08, 9.43, 0.01, 347.24 -CTUN, 336, 0.16, 0.07, 0.000000, 0, 0, -1, 337, 0 -DU32, 7, 393469 -CURR, 336, 5387, 1237, 0, 4772, 0.000000 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -CTUN, 336, 0.16, 0.02, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -GPS, 3, 308908000, 10, 1.49, 24.2398186, 54.5793107, 0.07, 9.44, 0.02, 347.24 -CTUN, 337, 0.16, 0.00, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -CTUN, 337, 0.15, -0.12, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -GPS, 3, 308908200, 10, 1.49, 24.2398185, 54.5793107, 0.05, 9.44, 0.01, 347.24 -CTUN, 336, 0.15, -0.02, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 -CTUN, 336, 0.15, 0.04, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 -PM, 0, 0, 50, 6, 1000, 6118488, 15, 0 -GPS, 3, 308908400, 10, 1.49, 24.2398184, 54.5793107, 0.04, 9.44, 0.01, 347.24 -CTUN, 337, 0.15, -0.04, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 -CTUN, 336, 0.15, -0.05, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 -GPS, 3, 308908600, 10, 1.49, 24.2398184, 54.5793108, 0.02, 9.45, 0.02, 347.24 -CTUN, 336, 0.16, 0.00, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 -CTUN, 337, 0.16, 0.06, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 -GPS, 3, 308908800, 10, 1.49, 24.2398184, 54.5793108, 0.02, 9.44, 0.02, 347.24 -CTUN, 337, 0.17, -0.01, 0.000000, 0, 0, -2, 337, 0 -DU32, 7, 393469 -CURR, 337, 8753, 1236, 0, 4752, 0.000000 -ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 -CTUN, 336, 0.16, -0.01, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.80, 0.00, 215.91, 215.88 -GPS, 3, 308909000, 10, 1.49, 24.2398183, 54.5793108, 0.01, 9.44, 0.02, 347.24 -CTUN, 336, 0.16, -0.06, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.81, 0.00, 215.91, 215.88 -CTUN, 337, 0.16, 0.05, 0.000000, 0, 0, -3, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 -MODE, LOITER, 494 -GPS, 3, 308909200, 10, 1.49, 24.2398183, 54.5793108, 0.00, 9.44, 0.01, 347.24 -NTUN, 0.00, 0.00, 0.024055, -0.020616, -3.706598, 0.999391, -3.688661, 1.017262, 0.000000, 0.000000, 0.00, 0.00 -CTUN, 337, 0.17, 0.00, 0.000000, 0, 0, -3, 337, 0 -ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 -NTUN, 0.00, 3.18, 0.025694, -0.125327, -1.037081, -0.125327, -3.474234, 1.032693, 28.695177, -12.247182, 1.56, 0.93 -CTUN, 336, 0.16, -0.01, -0.159600, 0, 0, -2, 335, -40 -ATT, 0.00, 0.28, 0.00, 0.81, 0.00, 215.91, 215.88 -GPS, 3, 308909400, 10, 1.49, 24.2398182, 54.5793109, 0.00, 9.44, 0.01, 347.24 -NTUN, 0.00, 2.90, 0.131245, -0.247736, 0.131245, -0.247736, -3.246917, 1.014269, 14.567575, -2.211969, 0.60, 0.61 -CTUN, 337, 0.16, -0.03, -0.181600, 0, 0, -2, 332, -40 -ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 -NTUN, 0.00, 3.01, 0.301338, -0.452011, 0.301338, -0.452011, -3.025889, 1.048491, 4.684094, -3.022526, 0.30, 0.11 -CTUN, 337, 0.16, 0.07, -0.221000, 0, 0, -2, 329, -39 -ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 -GPS, 3, 308909600, 10, 1.49, 24.2398181, 54.5793109, 0.00, 9.45, 0.01, 347.24 -NTUN, 0.00, 3.04, 0.469120, -0.641418, 0.469120, -0.641418, -2.853666, 0.977797, 4.677818, -2.894073, 0.29, 0.12 -CTUN, 337, 0.17, -0.06, -0.252200, 0, 0, -2, 326, -39 -ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 -NTUN, 0.00, 3.08, 0.685371, -0.787907, 0.685371, -0.787907, -2.664129, 0.955439, 5.162514, -2.464882, 0.29, 0.15 -CTUN, 336, 0.17, 0.05, -0.311600, 0, 0, -2, 325, -40 -ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 -GPS, 3, 308909800, 10, 1.49, 24.2398181, 54.5793109, -0.01, 9.45, 0.01, 347.24 -NTUN, 0.01, 3.12, 0.875168, -0.926881, 0.875168, -0.926881, -2.503617, 0.984931, 4.897964, -2.389742, 0.28, 0.14 -CTUN, 337, 0.17, 0.05, -0.343600, 0, 0, -3, 322, -40 -DU32, 7, 393457 -CURR, 337, 12072, 1232, 0, 4752, 0.000000 -ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 -NTUN, 0.01, 3.13, 0.993700, -1.035828, 0.993700, -1.035828, -2.198121, 0.921508, 5.185322, -2.089468, 0.27, 0.17 -CTUN, 337, 0.17, -0.03, -0.374800, 0, 0, -3, 319, -39 -ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.91, 215.88 -GPS, 3, 308910000, 10, 1.49, 24.2398180, 54.5793110, -0.01, 9.46, 0.01, 347.24 -NTUN, 0.01, 3.13, 1.101871, -1.160008, 1.101871, -1.160008, -1.963457, 0.927190, 5.071004, -3.229513, 0.32, 0.12 -MODE, STABILIZE, 494 -CTUN, 336, 0.19, 0.01, -0.406000, 0, 0, -3, 316, 0 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.92, 215.88 -CTUN, 336, 0.19, 0.02, 0.000000, 0, 0, -3, 336, 0 -GPS, 3, 308910200, 10, 1.49, 24.2398180, 54.5793110, -0.01, 9.46, 0.01, 347.24 -ATT, 0.00, 0.29, 0.00, 0.82, 0.00, 215.92, 215.88 -CTUN, 337, 0.19, -0.03, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.29, 0.00, 0.82, 0.00, 215.92, 215.88 -CTUN, 336, 0.19, -0.05, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308910400, 10, 1.49, 24.2398179, 54.5793110, -0.02, 9.46, 0.01, 347.24 -ATT, 0.00, 0.29, 0.00, 0.81, 0.00, 215.92, 215.88 -CTUN, 336, 0.19, 0.00, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.92, 215.88 -CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, -3, 337, 0 -GPS, 3, 308910600, 10, 1.49, 24.2398179, 54.5793110, -0.02, 9.46, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.93, 215.88 -CTUN, 336, 0.19, -0.07, 0.000000, 0, 0, -3, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.93, 215.88 -CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -3, 336, 0 -GPS, 3, 308910800, 10, 1.49, 24.2398178, 54.5793111, -0.03, 9.46, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.93, 215.88 -CTUN, 337, 0.19, 0.09, 0.000000, 0, 0, -3, 337, 0 -DU32, 7, 393469 -CURR, 336, 15400, 1231, 0, 4752, 0.000000 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.93, 215.88 -CTUN, 336, 0.19, 0.01, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308911000, 10, 1.49, 24.2398178, 54.5793111, -0.02, 9.46, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.93, 215.88 -CTUN, 336, 0.19, 0.01, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.94, 215.88 -CTUN, 337, 0.19, -0.02, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308911200, 10, 1.49, 24.2398177, 54.5793111, -0.03, 9.47, 0.00, 347.24 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 337, 0.19, 0.03, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, -2, 336, 0 -GPS, 3, 308911400, 10, 1.49, 24.2398177, 54.5793112, -0.02, 9.48, 0.02, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.95, 215.88 -CTUN, 337, 0.19, -0.05, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.95, 215.88 -CTUN, 337, 0.19, 0.02, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308911600, 10, 1.49, 24.2398176, 54.5793112, -0.03, 9.48, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.95, 215.88 -CTUN, 336, 0.19, -0.01, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.95, 215.88 -CTUN, 337, 0.16, 0.08, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308911800, 10, 1.49, 24.2398175, 54.5793112, -0.03, 9.48, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.96, 215.88 -CTUN, 337, 0.19, -0.01, 0.000000, 0, 0, -2, 337, 0 -DU32, 7, 393469 -CURR, 336, 18767, 1238, 0, 4772, 0.000000 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.96, 215.88 -CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -2, 336, 0 -GPS, 3, 308912000, 10, 1.49, 24.2398174, 54.5793113, -0.03, 9.49, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.96, 215.88 -CTUN, 336, 0.21, 0.10, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.96, 215.88 -CTUN, 337, 0.19, -0.01, 0.000000, 0, 0, -2, 337, 0 -GPS, 3, 308912200, 10, 1.49, 24.2398174, 54.5793113, -0.02, 9.49, 0.00, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.96, 215.88 -CTUN, 336, 0.19, 0.07, 0.000000, 0, 0, -2, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.97, 215.88 -CTUN, 336, 0.15, 0.03, 0.000000, 0, 0, -2, 336, 0 -GPS, 3, 308912400, 10, 1.49, 24.2398173, 54.5793113, -0.02, 9.49, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.97, 215.88 -CTUN, 337, 0.16, 0.09, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.97, 215.88 -CTUN, 336, 0.15, 0.05, 0.000000, 0, 0, -2, 336, 0 -GPS, 3, 308912600, 10, 1.49, 24.2398172, 54.5793114, -0.01, 9.49, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.98, 215.88 -CTUN, 336, 0.16, 0.06, 0.000000, 0, 0, -2, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 -CTUN, 337, 0.16, -0.01, 0.000000, 0, 0, -1, 337, 0 -GPS, 3, 308912800, 10, 1.49, 24.2398172, 54.5793114, -0.01, 9.49, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 -CTUN, 336, 0.16, -0.01, 0.000000, 0, 0, -1, 336, 0 -DU32, 7, 393469 -CURR, 337, 22132, 1240, 0, 4752, 0.000000 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 -CTUN, 337, 0.15, 0.05, 0.000000, 0, 0, -1, 337, 0 -GPS, 3, 308913000, 10, 1.49, 24.2398171, 54.5793114, -0.01, 9.50, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.99, 215.88 -CTUN, 337, 0.16, -0.03, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.99, 215.88 -CTUN, 336, 0.16, 0.01, 0.000000, 0, 0, -1, 336, 0 -GPS, 3, 308913200, 10, 1.49, 24.2398170, 54.5793114, -0.01, 9.50, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.99, 215.88 -CTUN, 337, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.99, 215.88 -CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, -1, 336, 0 -GPS, 3, 308913400, 10, 1.49, 24.2398170, 54.5793114, -0.01, 9.50, 0.00, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 216.00, 215.88 -CTUN, 336, 0.16, 0.03, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.00, 215.88 -CTUN, 337, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 -GPS, 3, 308913600, 10, 1.49, 24.2398169, 54.5793115, 0.00, 9.50, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.00, 215.88 -CTUN, 336, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 -CTUN, 336, 0.15, 0.06, 0.000000, 0, 0, -1, 336, 0 -GPS, 3, 308913800, 10, 1.49, 24.2398169, 54.5793115, 0.00, 9.51, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 -CTUN, 337, 0.16, 0.05, 0.000000, 0, 0, -1, 337, 0 -DU32, 7, 393469 -CURR, 336, 25498, 1232, 0, 4793, 0.000000 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 -CTUN, 336, 0.16, 0.11, 0.000000, 0, 0, -1, 336, 0 -GPS, 3, 308914000, 10, 1.49, 24.2398168, 54.5793115, 0.00, 9.50, 0.01, 347.24 -ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.02, 215.88 -CTUN, 337, 0.16, 0.10, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.02, 215.88 -CTUN, 337, 0.15, 0.03, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.03, 215.88 -GPS, 3, 308914200, 10, 1.49, 24.2398168, 54.5793116, 0.00, 9.51, 0.01, 347.24 -CTUN, 336, 0.15, 0.00, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.03, 215.88 -CTUN, 337, 0.15, 0.03, 0.000000, 0, 0, -1, 337, 0 -GPS, 3, 308914400, 10, 1.49, 24.2398167, 54.5793116, 0.00, 9.51, 0.01, 347.24 -ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.03, 215.88 -CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.04, 215.88 -CTUN, 336, 0.15, 0.05, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308914600, 10, 1.49, 24.2398167, 54.5793116, 0.01, 9.51, 0.01, 347.24 -ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.04, 215.88 -CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 216.04, 215.88 -CTUN, 336, 0.15, 0.02, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308914800, 10, 1.49, 24.2398166, 54.5793117, 0.01, 9.51, 0.01, 347.24 -ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 216.04, 215.88 -CTUN, 337, 0.15, 0.10, 0.000000, 0, 0, 0, 337, 0 -DU32, 7, 393469 -CURR, 337, 28863, 1238, 0, 4752, 0.000000 -ATT, 0.00, 0.25, 0.00, 0.83, 0.00, 216.04, 215.88 -CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308915000, 10, 1.49, 24.2398166, 54.5793117, 0.02, 9.51, 0.01, 347.24 -ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.04, 215.88 -CTUN, 336, 0.20, 0.12, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.05, 215.88 -CTUN, 337, 0.20, 0.12, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308915200, 10, 1.49, 24.2398165, 54.5793117, 0.03, 9.52, 0.02, 347.24 -ATT, 0.00, 0.25, 0.00, 0.85, 0.00, 215.97, 215.88 -CTUN, 336, 0.22, 0.03, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.96, 215.88 -CTUN, 336, 0.22, 0.03, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308915400, 10, 1.49, 24.2398165, 54.5793117, 0.03, 9.52, 0.01, 347.24 -ATT, 0.00, 0.30, 0.00, 0.79, 0.00, 215.97, 215.88 -CTUN, 337, 0.35, 0.01, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.76, 0.00, 215.98, 215.88 -CTUN, 337, 0.35, 0.17, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308915600, 10, 1.49, 24.2398164, 54.5793117, 0.03, 9.52, 0.02, 347.24 -ATT, 0.00, 0.24, 0.00, 0.80, 0.00, 215.96, 215.88 -CTUN, 337, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.23, 0.00, 0.82, 0.00, 215.95, 215.88 -CTUN, 337, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308915800, 10, 1.49, 24.2398164, 54.5793118, 0.04, 9.53, 0.02, 347.24 -ATT, 0.00, 0.22, 0.00, 0.82, 0.00, 215.95, 215.88 -CTUN, 336, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 -DU32, 7, 393469 -CURR, 337, 32229, 1235, 0, 4752, 0.000000 -ATT, 0.00, 0.23, 0.00, 0.81, 0.00, 215.95, 215.88 -CTUN, 336, 0.35, 0.14, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308916000, 10, 1.49, 24.2398164, 54.5793118, 0.04, 9.53, 0.02, 347.24 -ATT, 0.00, 0.22, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.24, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 337, 0.35, 0.11, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308916200, 10, 1.49, 24.2398163, 54.5793118, 0.05, 9.55, 0.02, 347.24 -ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 336, 0.35, -0.05, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.25, 0.00, 0.81, 0.00, 215.94, 215.88 -CTUN, 336, 0.35, 0.17, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308916400, 10, 1.49, 24.2398163, 54.5793118, 0.05, 9.55, 0.04, 347.24 -ATT, 0.00, 0.25, 0.00, 0.80, 0.00, 215.94, 215.88 -CTUN, 337, 0.35, 0.24, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.26, 0.00, 0.81, 0.00, 215.94, 215.88 -CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308916600, 10, 1.49, 24.2398163, 54.5793118, 0.06, 9.56, 0.03, 347.24 -ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.94, 215.88 -CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.25, 0.00, 0.84, 0.00, 215.93, 215.88 -CTUN, 337, 0.35, 0.04, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308916800, 10, 1.49, 24.2398163, 54.5793118, 0.07, 9.56, 0.00, 347.24 -ATT, 0.00, 0.20, 0.00, 0.85, 0.00, 215.91, 215.88 -CTUN, 336, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 -DU32, 7, 393469 -CURR, 337, 35594, 1230, 0, 4772, 0.000000 -ATT, 0.00, 0.24, 0.00, 0.84, 0.00, 215.92, 215.88 -CTUN, 336, 0.35, 0.07, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308917000, 10, 1.49, 24.2398162, 54.5793119, 0.07, 9.56, 0.02, 347.24 -ATT, 0.00, 0.23, 0.00, 0.84, 0.00, 215.91, 215.88 -CTUN, 337, 0.35, 0.05, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.21, 0.00, 0.82, 0.00, 215.91, 215.88 -CTUN, 337, 0.35, 0.16, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308917200, 10, 1.49, 24.2398160, 54.5793119, 0.07, 9.57, 0.05, 347.24 -ATT, 0.00, 0.26, 0.00, 0.81, 0.00, 215.91, 215.88 -CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.20, 0.00, 0.84, 0.00, 215.89, 215.88 -CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308917400, 10, 1.49, 24.2398160, 54.5793120, 0.08, 9.58, 0.03, 347.24 -ATT, 0.00, 0.23, 0.00, 0.80, 0.00, 215.91, 215.88 -CTUN, 337, 0.35, 0.04, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.21, 0.00, 0.85, 0.00, 215.89, 215.88 -CTUN, 336, 0.35, -0.03, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308917600, 10, 1.49, 24.2398159, 54.5793120, 0.07, 9.60, 0.02, 347.24 -ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.90, 215.88 -CTUN, 337, 0.35, 0.06, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.19, 0.00, 0.86, 0.00, 215.87, 215.88 -CTUN, 337, 0.35, 0.02, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308917800, 10, 1.49, 24.2398159, 54.5793120, 0.07, 9.62, 0.01, 347.24 -ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 215.89, 215.88 -CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 -DU32, 7, 393469 -CURR, 337, 38959, 1229, 0, 4772, 0.000000 -ATT, 0.00, 0.21, 0.00, 0.78, 0.00, 215.89, 215.88 -CTUN, 336, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308918000, 10, 1.49, 24.2398158, 54.5793121, 0.07, 9.64, 0.04, 347.24 -ATT, 0.00, 0.11, 0.00, 0.87, 0.00, 215.81, 215.88 -CTUN, 337, 0.35, 0.14, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.17, 0.00, 0.87, 0.00, 215.80, 215.88 -CTUN, 337, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308918200, 10, 1.49, 24.2398157, 54.5793121, 0.07, 9.66, 0.02, 347.24 -ATT, 0.00, 0.23, 0.00, 0.76, 0.00, 215.77, 215.88 -CTUN, 337, 0.35, 0.03, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.38, 0.00, 0.64, 0.00, 215.69, 215.88 -CTUN, 337, 0.35, 0.08, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308918400, 10, 1.49, 24.2398156, 54.5793121, 0.06, 9.67, 0.03, 347.24 -PM, 0, 0, 51, 5, 1000, 10908, 10, 0 -ATT, 0.00, 0.36, 0.00, 0.67, 0.00, 215.42, 215.88 -CTUN, 336, 0.35, 0.07, 0.000000, 0, 0, -1, 336, 0 -ATT, 0.00, 0.28, 0.00, 0.71, 0.00, 215.20, 215.88 -CTUN, 336, 0.34, 0.04, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308918600, 10, 1.49, 24.2398155, 54.5793121, 0.06, 9.68, 0.01, 347.24 -ATT, 0.00, 0.08, 0.00, 0.85, 0.00, 215.05, 215.88 -CTUN, 337, 0.35, 0.06, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.01, 0.00, 0.97, 0.00, 214.86, 215.88 -CTUN, 337, 0.35, 0.00, 0.000000, 0, 0, -1, 337, 0 -GPS, 3, 308918800, 10, 1.49, 24.2398154, 54.5793122, 0.06, 9.69, 0.01, 347.24 -ATT, 0.00, 0.25, 0.00, 0.89, 0.00, 214.92, 215.88 -CTUN, 336, 0.69, 0.14, 0.000000, 0, 0, 0, 337, 0 -DU32, 7, 393469 -CURR, 337, 42325, 1216, 0, 4752, 0.000000 -ATT, 0.00, 0.02, 0.00, 0.91, 0.00, 214.91, 215.88 -CTUN, 336, 0.69, -0.08, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308919000, 10, 1.49, 24.2398154, 54.5793122, 0.06, 9.69, 0.01, 347.24 -ATT, 0.00, 0.25, 0.00, 0.94, 0.00, 214.89, 215.88 -CTUN, 337, 0.69, -0.07, 0.000000, 0, 0, 0, 336, 0 -ATT, 0.00, 0.04, 0.00, 0.94, 0.00, 214.88, 215.88 -CTUN, 337, 0.69, -0.05, 0.000000, 0, 0, 0, 336, 0 -GPS, 3, 308919200, 10, 1.49, 24.2398153, 54.5793122, 0.04, 9.69, 0.02, 347.24 -ATT, 0.00, 0.12, 0.00, 0.90, 0.00, 214.91, 215.88 -CTUN, 337, 1.25, 0.00, 0.000000, 0, 0, 0, 337, 0 -ATT, 0.00, 0.20, 0.00, 0.92, 0.00, 214.89, 215.88 -CTUN, 337, 0.69, -0.03, 0.000000, 0, 0, 0, 337, 0 -GPS, 3, 308919400, 10, 1.49, 24.2398153, 54.5793122, 0.03, 9.70, 0.01, 347.24 -ATT, 0.00, 0.14, 0.00, 0.91, 0.00, 214.88, 215.88 -CTUN, 336, 0.69, -0.08, 0.000000, 0, 0, -1, 337, 0 -ATT, 0.00, 0.01, 0.00, 0.92, 0.00, 214.88, 215.88 -CTUN, 336, 0.69, -0.16, 0.000000, 0, 0, 2, 336, 0 -GPS, 3, 308919600, 10, 1.49, 24.2398152, 54.5793123, 0.02, 9.71, 0.01, 347.24 -ATT, 0.00, 0.03, 0.00, 0.87, 0.00, 214.99, 215.88 -CTUN, 337, 1.19, -0.05, 0.000000, 0, 0, 2, 336, 0 -ATT, 0.00, 0.02, 0.00, 0.88, 0.00, 215.15, 215.88 -CTUN, 337, 0.88, 0.00, 0.000000, 0, 0, 3, 337, 0 -GPS, 3, 308919800, 10, 1.49, 24.2398151, 54.5793123, 0.01, 9.71, 0.01, 347.24 -ATT, 0.00, 0.13, 0.00, 0.84, 0.00, 215.28, 215.88 -CTUN, 336, 0.88, -0.10, 0.000000, 0, 0, 3, 337, 0 -DU32, 7, 393469 -CURR, 337, 45691, 1220, 0, 4772, 0.000000 -ATT, 0.00, 0.00, 0.00, 0.82, 0.00, 215.37, 215.88 -CTUN, 337, 0.49, -0.06, 0.000000, 0, 0, 3, 337, 0 -GPS, 3, 308920000, 10, 1.49, 24.2398151, 54.5793123, 0.01, 9.72, 0.00, 347.24 -ATT, 0.00, 0.10, 0.00, 0.80, 0.00, 215.44, 215.88 -CTUN, 336, 0.64, -0.08, 0.000000, 0, 0, 5, 337, 0 -ATT, 0.00, 0.00, 0.00, 0.78, 0.00, 215.54, 215.88 -CTUN, 336, 0.49, -0.04, 0.000000, 0, 0, 3, 336, 0 -GPS, 3, 308920200, 10, 1.49, 24.2398150, 54.5793123, 0.01, 9.72, 0.00, 347.24 -ATT, 0.00, 0.20, 0.00, 0.71, 0.00, 215.97, 215.88 -CTUN, 337, 0.49, -0.09, 0.000000, 0, 0, 5, 336, 0 -ATT, 0.00, -0.10, 0.00, 0.66, 0.00, 216.60, 215.88 -CTUN, 337, 0.43, -0.09, 0.000000, 0, 0, 5, 337, 0 -GPS, 3, 308920400, 10, 1.49, 24.2398150, 54.5793124, 0.01, 9.73, 0.02, 347.24 -ATT, 0.00, -0.06, 0.00, 0.70, 0.00, 217.03, 215.88 -CTUN, 337, 0.43, -0.18, 0.000000, 0, 0, 2, 336, 0 -ATT, 0.00, -0.09, 0.00, 0.69, 0.00, 217.94, 215.88 -CTUN, 337, 0.41, -0.02, 0.000000, 0, 0, 6, 337, 0 -GPS, 3, 308920600, 10, 1.49, 24.2398149, 54.5793124, 0.00, 9.73, 0.01, 347.24 -ATT, 0.00, -0.06, 0.00, 0.65, 0.00, 218.82, 215.88 -CTUN, 336, 0.41, -0.16, 0.000000, 0, 0, 8, 336, 0 -ATT, 0.00, -0.13, 0.00, 0.64, 0.00, 219.48, 215.88 -CTUN, 336, 0.41, -0.11, 0.000000, 0, 0, 7, 337, 0 -GPS, 3, 308920800, 10, 1.49, 24.2398149, 54.5793125, 0.00, 9.74, 0.02, 347.24 -ATT, 0.00, -0.24, 0.00, 0.69, 0.00, 220.07, 215.88 -CTUN, 337, 0.68, -0.09, 0.000000, 0, 0, 6, 336, 0 -DU32, 7, 393469 -CURR, 336, 49056, 1201, 0, 4752, 0.000000 -ATT, 0.00, -0.17, 0.00, 0.66, 0.00, 220.69, 215.88 -CTUN, 337, 0.41, -0.20, 0.000000, 0, 0, 5, 336, 0 -GPS, 3, 308921000, 10, 1.49, 24.2398148, 54.5793126, 0.00, 9.74, 0.02, 347.24 -ATT, 0.00, 0.05, 0.00, 0.62, 0.00, 221.21, 215.88 -CTUN, 337, 0.41, -0.22, 0.000000, 0, 0, 10, 337, 0 -ATT, 0.00, 0.00, 0.00, 0.58, 0.00, 221.55, 215.88 -CTUN, 337, 0.22, -0.19, 0.000000, 0, 0, 13, 337, 0 -GPS, 3, 308921200, 10, 1.49, 24.2398147, 54.5793126, 0.00, 9.75, 0.01, 347.24 -ATT, 0.00, -0.22, 0.00, 0.61, 0.00, 222.01, 215.88 -CTUN, 336, 0.33, -0.08, 0.000000, 0, 0, 11, 337, 0 -ATT, 0.00, 0.08, 0.00, 0.58, 0.00, 222.34, 215.88 -CTUN, 336, 0.24, -0.23, 0.000000, 0, 0, 10, 336, 0 -GPS, 3, 308921400, 10, 1.49, 24.2398146, 54.5793126, 0.01, 9.75, 0.02, 347.24 -ATT, 0.00, -0.17, 0.00, 0.55, 0.00, 223.00, 215.88 -CTUN, 337, 0.33, -0.06, 0.000000, 0, 0, 13, 337, 0 -ATT, 0.00, -0.14, 0.00, 0.55, 0.00, 224.15, 215.88 -CTUN, 337, 0.29, -0.17, 0.000000, 0, 0, 14, 337, 0 -GPS, 3, 308921600, 10, 1.49, 24.2398145, 54.5793127, 0.02, 9.76, 0.02, 347.24 -ATT, 0.00, -0.12, 0.00, 0.48, 0.00, 225.74, 215.88 -CTUN, 336, 0.29, -0.39, 0.000000, 0, 0, 20, 337, 0 -ATT, 0.00, -0.42, 0.00, 0.48, 0.00, 227.00, 217.00 -CTUN, 336, 0.29, -0.12, 0.000000, 0, 0, 16, 337, 0 -GPS, 3, 308921800, 10, 1.49, 24.2398144, 54.5793128, 0.02, 9.77, 0.03, 347.24 -ATT, 0.00, -0.45, 0.00, 0.49, 0.00, 227.95, 217.95 -CTUN, 337, 0.36, -0.14, 0.000000, 0, 0, 16, 336, 0 -DU32, 7, 393469 -CURR, 337, 52423, 1180, 0, 4772, 0.000000 -ATT, 0.00, -0.38, 0.00, 0.45, 0.00, 228.77, 218.77 -CTUN, 337, 0.29, -0.20, 0.000000, 0, 0, 16, 336, 0 -GPS, 3, 308922000, 10, 1.49, 24.2398144, 54.5793129, 0.04, 9.79, 0.04, 347.24 -ATT, 0.00, -0.33, 0.00, 0.47, 0.00, 229.63, 219.63 -CTUN, 337, 0.33, -0.27, 0.000000, 0, 0, 18, 337, 0 -MODE, AUTO, 501 -ATT, 0.00, -0.35, 0.00, 0.47, 0.00, 230.26, 220.26 -CTUN, 336, 0.29, -0.25, 0.000000, 0, 0, 15, 337, 0 -CMD, 8, 1, 22, 1, 0, 7.62, 0.0000000, 0.0000000 -GPS, 3, 308922200, 10, 1.49, 24.2398143, 54.5793129, 0.03, 9.80, 0.03, 347.24 -ATT, -0.27, -0.38, 0.40, 0.46, 0.00, 230.74, 220.75 -NTUN, 0.00, 0.00, 11.218952, -3.977892, 11.218952, -3.977892, 10.711962, -2.335319, 0.000000, -1.000000, 0.03, -0.04 -CTUN, 336, 0.29, 0.25, 0.040093, 0, 0, 18, 475, 0 -ATT, 0.03, -0.69, -0.04, 0.71, 0.00, 229.13, 220.75 -NTUN, 0.00, 2.30, 10.713371, -4.404589, 10.713371, -4.404589, 13.511226, -0.950545, -7.055809, -7.266968, -0.03, -0.59 -CTUN, 337, 0.24, -0.39, 0.103789, 0, 0, 19, 475, 0 -GPS, 3, 308922400, 10, 1.49, 24.2398142, 54.5793129, 0.06, 9.80, 0.01, 347.24 -NTUN, 0.01, 2.23, 10.114662, -4.769110, 10.114662, -4.769110, 9.784394, 1.857668, -5.927813, -9.609119, 0.12, -0.64 -ATT, 0.12, -0.40, -0.64, 0.44, 0.00, 227.60, 220.75 -CTUN, 337, 0.29, -0.07, 0.219127, 0, 0, 21, 474, 0 -NTUN, 0.02, 2.61, 11.860283, -7.375818, 11.860283, -7.375818, -32.844906, 41.576733, 63.283371, -75.808990, 5.70, -0.72 -ATT, 5.70, -0.36, -0.72, 0.39, 0.00, 227.01, 220.75 -CTUN, 337, 0.25, -0.23, 0.385470, 0, 0, 22, 461, 0 -GPS, 3, 308922600, 10, 1.49, 24.2398142, 54.5793129, 0.07, 9.80, 0.03, 347.24 -NTUN, 0.10, 3.01, 17.227455, -13.677666, 17.227455, -13.677666, -57.575172, 73.119659, 132.671720, -156.018480, 11.72, -1.31 -CTUN, 337, 0.29, -0.22, 0.600166, 0, 0, 19, 448, 0 -ATT, 11.72, -0.14, -1.31, 0.30, 0.00, 226.57, 220.75 -NTUN, 0.20, 3.07, 24.158928, -21.701262, 24.158928, -21.701262, -63.983826, 77.550827, 167.314730, -191.235960, 14.47, -1.32 -CTUN, 337, 0.25, 0.00, 0.850166, 0, 0, 30, 465, 0 -ATT, 14.47, 0.05, -1.32, 0.17, 0.00, 226.15, 220.75 -GPS, 3, 308922800, 10, 1.49, 24.2398141, 54.5793129, 0.09, 9.79, 0.00, 347.24 -NTUN, 0.32, 3.08, 30.639336, -29.468784, 30.639336, -29.468784, -60.517593, 79.337593, 169.162450, -201.906160, 14.96, -1.53 -CTUN, 337, 0.25, -0.06, 1.102666, 0, 0, -5, 559, 0 -ATT, 14.96, 0.81, -1.53, -0.03, 0.00, 224.97, 220.75 -DU32, 7, 393457 -CURR, 337, 56271, 1193, 0, 4772, 0.000000 -NTUN, 0.32, 3.08, 36.171207, -36.663116, 36.171207, -36.663116, -55.220253, 79.798508, 165.318730, -210.943330, 15.20, -1.62 -CTUN, 336, 0.21, -0.34, 1.325662, 0, 0, -32, 584, 0 -ATT, 15.20, 3.82, -1.62, -0.91, 0.00, 223.10, 220.75 -GPS, 3, 308923000, 10, 1.49, 24.2398141, 54.5793129, 0.04, 9.79, 0.02, 347.24 -NTUN, 0.43, 3.08, 40.619099, -43.098080, 40.619099, -43.098080, -48.493973, 77.544411, 156.928190, -213.999630, 15.06, -1.62 -CTUN, 336, 0.22, -0.69, 1.495320, 0, 0, -80, 668, 0 -ATT, 15.06, 9.83, -1.62, -0.76, 0.00, 220.03, 220.75 -NTUN, 0.51, 3.08, 43.333050, -48.299927, 43.333050, -48.299927, -37.055912, 72.857292, 133.870800, -207.503430, 14.05, -1.51 -CTUN, 336, 0.22, -1.29, 1.629664, 0, 2, -123, 720, 0 -GPS, 3, 308923200, 10, 1.49, 24.2398141, 54.5793128, -0.23, 9.80, 0.08, 347.24 -ATT, 14.05, 12.60, -1.51, -0.55, 0.00, 215.68, 220.75 -NTUN, 0.58, 3.06, 44.808475, -52.193821, 44.808475, -52.193821, -35.111961, 69.787422, 124.754260, -200.938930, 13.54, -0.72 -CTUN, 337, 0.27, -1.39, 1.771228, 0, 2, -105, 704, 0 -ATT, 13.54, 13.52, -0.72, -0.37, 0.00, 211.73, 220.75 -NTUN, 0.62, 3.05, 46.255318, -55.617573, 46.255318, -55.617573, -45.501850, 79.744339, 141.468410, -217.237520, 14.80, 0.43 -CTUN, 337, 0.27, -0.77, 1.905869, 0, 4, -113, 772, 0 -GPS, 3, 308923400, 10, 1.49, 24.2398144, 54.5793123, -0.56, 9.85, 0.30, 319.33 -ATT, 14.80, 14.20, 0.43, -0.22, 0.00, 208.85, 218.85 -NTUN, 0.67, 3.05, 48.271881, -59.620163, 48.271881, -59.620163, -50.871349, 89.512306, 159.965970, -243.629610, 16.49, 1.40 -CTUN, 337, 0.27, -0.60, 2.068352, 0, 3, -89, 734, 0 -ATT, 16.49, 16.11, 1.40, -0.33, 0.00, 205.41, 215.41 -NTUN, 0.71, 3.04, 49.271904, -61.951389, 49.271904, -61.951389, -38.100204, 64.007118, 142.000230, -210.312260, 14.33, 2.32 -CTUN, 337, 0.21, -0.12, 2.252397, 0, 5, -70, 755, 0 -GPS, 3, 308923600, 10, 1.49, 24.2398150, 54.5793112, -0.72, 10.00, 0.73, 306.76 -NTUN, 0.72, 3.04, 48.655746, -60.892334, 48.655746, -60.892334, -28.088583, 37.604218, 118.838420, -153.409450, 10.67, 3.42 -ATT, 10.67, 17.76, 3.42, -0.88, 0.00, 199.71, 209.71 -CTUN, 336, 0.27, 0.30, 2.449948, 0, 6, -54, 767, 0 -NTUN, 0.68, 3.05, 46.551796, -55.633720, 46.551796, -55.633720, -19.507681, 5.990871, 97.168808, -77.934525, 5.94, 4.15 -ATT, 5.94, 16.97, 4.15, 0.10, 0.00, 195.99, 205.99 -CTUN, 337, 0.27, 0.59, 2.665683, 0, 6, -32, 777, 0 -GPS, 3, 308923800, 10, 1.49, 24.2398158, 54.5793091, -0.70, 10.25, 1.24, 300.06 -NTUN, 0.59, 3.08, 43.153175, -46.478767, 43.153175, -46.478767, -11.677929, -20.816683, 75.013794, -4.450470, 1.17, 4.22 -CTUN, 337, 0.43, 1.01, 2.904601, 0, 4, -7, 782, 0 -ATT, 1.17, 13.00, 4.22, 1.26, 0.00, 190.75, 200.75 -NTUN, 0.47, 3.13, 38.527103, -33.728680, 38.527103, -33.728680, -6.010324, -38.518227, 54.739281, 60.500877, -3.08, 3.62 -CTUN, 336, 0.43, 1.11, 3.154601, 0, 2, 17, 757, 0 -ATT, -3.08, 9.62, 3.62, 1.78, 0.00, 185.95, 195.95 -GPS, 3, 308924000, 10, 1.49, 24.2398171, 54.5793063, -0.51, 10.58, 1.69, 298.24 -NTUN, 0.32, 3.25, 32.901154, -19.003736, 32.901154, -19.003736, -1.999703, -49.658333, 37.297527, 106.791500, -6.12, 2.40 -CTUN, 336, 0.74, 1.29, 3.407101, 0, 1, 35, 774, 0 -ATT, -6.12, 5.27, 2.40, 1.47, 0.00, 179.42, 189.42 -DU32, 7, 393457 -CURR, 336, 64256, 1182, 0, 4772, 0.000000 -NTUN, 0.21, 3.52, 26.379150, -3.019579, 26.379150, -3.019579, 2.681522, -52.334209, 17.779968, 141.841570, -8.27, 0.58 -CTUN, 337, 0.74, 1.43, 3.657101, 0, 0, 53, 756, 0 -ATT, -8.27, 1.95, 0.58, 0.36, 0.00, 174.20, 184.20 -GPS, 3, 308924200, 10, 1.49, 24.2398184, 54.5793029, -0.22, 10.96, 1.98, 296.41 -NTUN, 0.19, 0.42, 19.461609, 13.211496, 19.461609, 13.211496, 2.641173, -49.726601, 8.509491, 159.703700, -9.22, -0.86 -CTUN, 337, 1.11, 1.51, 3.909601, 0, 0, 67, 764, 0 -ATT, -9.22, -0.57, -0.86, -1.05, 0.00, 168.40, 178.40 -NTUN, 0.30, 0.75, 12.316704, 29.346365, 12.316704, 29.346365, 2.225170, -42.407974, -0.449051, 172.348680, -9.71, -2.26 -CTUN, 336, 1.11, 1.72, 4.159601, 0, 0, 81, 747, 0 -GPS, 3, 308924400, 10, 1.49, 24.2398194, 54.5792996, 0.11, 11.43, 1.85, 294.24 -ATT, -9.71, -1.76, -2.26, -2.22, 0.00, 163.64, 173.64 -NTUN, 0.45, 0.88, 5.230618, 44.963272, 5.230618, 44.963272, 0.001821, -35.019409, -3.860863, 179.169070, -9.82, -3.31 -CTUN, 337, 1.48, 1.82, 4.409601, 0, 0, 91, 738, 0 -ATT, -9.82, -2.90, -3.31, -3.59, 0.00, 158.77, 168.77 -NTUN, 0.60, 0.95, -1.634468, 60.041031, -1.634468, 60.041031, -0.001427, -28.209909, -6.971146, 186.284730, -9.84, -4.38 -CTUN, 336, 1.48, 1.61, 4.662101, 0, 0, 99, 739, 0 -GPS, 3, 308924600, 10, 1.49, 24.2398205, 54.5792968, 0.48, 11.92, 1.62, 294.03 -NTUN, 0.74, 0.98, -8.212360, 73.966217, -8.212360, 73.966217, -3.756350, -18.413843, -8.778923, 184.251860, -9.30, -5.22 -ATT, -9.30, -3.57, -5.22, -4.75, 0.00, 153.21, 163.21 -CTUN, 337, 2.09, 1.77, 4.912101, 0, 0, 96, 743, 0 -NTUN, 0.88, 1.01, -14.399727, 86.876389, -14.399727, 86.876389, -5.825308, -9.867271, -8.873665, 183.101720, -8.80, -5.92 -ATT, -8.80, -4.30, -5.92, -5.27, 0.00, 148.58, 158.58 -CTUN, 337, 2.09, 1.97, 5.162101, 0, 1, 95, 755, 0 -GPS, 3, 308924800, 10, 1.49, 24.2398215, 54.5792945, 0.80, 12.47, 1.35, 295.04 -NTUN, 1.01, 1.03, -20.399529, 98.552238, -20.399529, 98.552238, -7.452480, 2.692262, -11.403973, 173.602480, -7.78, -6.38 -ATT, -7.78, -3.98, -6.38, -6.82, 0.00, 143.21, 153.21 -CTUN, 336, 2.60, 2.37, 5.414601, 0, 1, 90, 748, 0 -NTUN, 1.12, 1.04, -26.136154, 108.671780, -26.136154, 108.671780, -9.283962, 12.756130, -13.945713, 164.217620, -6.68, -6.80 -ATT, -6.68, -2.19, -6.80, -7.40, 0.00, 137.88, 147.88 -CTUN, 336, 2.60, 2.31, 5.662101, 0, 1, 95, 750, 0 -GPS, 3, 308925000, 10, 1.49, 24.2398222, 54.5792931, 1.16, 12.98, 0.86, 296.31 -NTUN, 1.21, 1.05, -31.199333, 117.238420, -31.199333, 117.238420, -14.625351, 20.909149, -7.130482, 152.818180, -5.79, -6.71 -CTUN, 336, 2.60, 2.40, 5.914601, 0, 1, 94, 745, 0 -ATT, -5.79, -1.57, -6.71, -7.17, 0.00, 130.78, 140.78 -DU32, 7, 393457 -CURR, 337, 70992, 1190, 0, 4793, 0.000000 -NTUN, 1.21, 1.05, -35.632408, 124.528680, -35.632408, 124.528680, -18.183670, 29.583235, -2.891830, 143.180790, -4.95, -6.67 -CTUN, 336, 2.60, 2.36, 6.167102, 0, 1, 96, 757, 0 -ATT, -4.95, -1.63, -6.67, -6.83, 0.00, 125.26, 135.26 -GPS, 3, 308925200, 9, 1.75, 24.2398225, 54.5792924, 1.49, 13.47, 0.39, 296.63 -NTUN, 1.31, 1.06, -39.379242, 130.261660, -39.379242, 130.261660, -19.753963, 39.608944, 0.531662, 128.329790, -4.03, -6.27 -CTUN, 336, 3.55, 2.62, 6.417102, 0, 0, 90, 757, 0 -ATT, -4.03, -0.47, -6.27, -6.37, 0.00, 119.93, 129.93 -NTUN, 1.37, 1.07, -42.720036, 134.703310, -42.720036, 134.703310, -21.511440, 44.773178, 1.592064, 119.416500, -3.25, -6.13 -CTUN, 337, 3.55, 2.74, 6.667102, 0, 0, 97, 754, 0 -ATT, -3.25, 0.73, -6.13, -5.58, 0.00, 114.31, 124.31 -GPS, 3, 308925400, 9, 1.75, 24.2398226, 54.5792924, 1.79, 13.94, 0.08, 296.63 -NTUN, 1.42, 1.08, -45.298603, 137.802640, -45.298603, 137.802640, -26.134127, 48.733604, 10.214325, 109.993350, -2.90, -5.73 -CTUN, 337, 3.98, 2.70, 6.917102, 0, 0, 93, 764, 0 -ATT, -2.90, 0.19, -5.73, -4.61, 0.00, 107.84, 117.84 -NTUN, 1.46, 1.08, -47.455734, 139.961940, -47.455734, 139.961940, -25.275766, 53.548508, 10.428688, 102.593020, -2.25, -5.56 -CTUN, 336, 3.98, 2.77, 7.167101, 0, 0, 100, 759, 0 -GPS, 3, 308925600, 9, 1.75, 24.2398227, 54.5792929, 2.10, 14.41, 0.28, 332.29 -ATT, -2.25, 1.29, -5.56, -3.70, 0.00, 102.13, 112.13 -NTUN, 1.48, 1.08, -49.309723, 140.972290, -49.309723, 140.972290, -28.058275, 57.373024, 13.643677, 92.003418, -1.80, -5.10 -CTUN, 336, 4.48, 2.89, 7.419602, 0, 0, 108, 741, 0 -ATT, -1.80, 0.60, -5.10, -2.00, 0.00, 95.91, 105.91 -NTUN, 1.49, 1.09, -50.613499, 141.347290, -50.613476, 141.347230, -30.500196, 55.526684, 18.962471, 90.749390, -1.59, -5.16 -CTUN, 337, 4.48, 2.99, 7.620000, 0, 0, 116, 750, 0 -GPS, 3, 308925800, 9, 1.75, 24.2398227, 54.5792940, 2.40, 14.92, 0.55, 70.72 -NTUN, 1.50, 1.09, -51.421017, 140.849030, -51.421017, 140.849030, -29.381805, 53.628754, 20.924591, 88.018005, -1.27, -5.11 -ATT, -1.27, 0.39, -5.11, -1.46, 0.00, 90.05, 100.05 -CTUN, 337, 4.95, 3.11, 7.620000, 0, 0, 115, 747, 0 -NTUN, 1.49, 1.10, -52.096004, 139.980100, -52.096004, 139.980100, -31.509203, 51.498936, 23.250122, 90.310730, -0.92, -5.35 -ATT, -0.92, 0.69, -5.35, -0.55, 0.00, 84.79, 94.79 -CTUN, 337, 4.95, 3.33, 7.620000, 0, 0, 118, 747, 0 -GPS, 3, 308926000, 9, 1.75, 24.2398225, 54.5792956, 2.71, 15.41, 0.78, 88.33 -NTUN, 1.49, 1.10, -52.243824, 138.460830, -52.243824, 138.460830, -32.563969, 47.538269, 28.536440, 89.957703, -0.74, -5.44 -ATT, -0.74, 0.14, -5.44, -0.04, 0.00, 78.57, 88.57 -CTUN, 337, 5.39, 3.45, 7.620000, 0, 0, 118, 745, 0 -DU32, 7, 393457 -CURR, 337, 78518, 1160, 0, 4793, 0.000000 -NTUN, 1.47, 1.10, -52.255611, 136.714970, -52.255611, 136.714970, -32.073730, 43.795528, 27.882126, 94.541351, -0.16, -5.73 -ATT, -0.16, 0.10, -5.73, -0.53, 0.00, 73.89, 83.89 -CTUN, 337, 5.39, 4.04, 7.620000, 0, 0, 114, 758, 0 -GPS, 3, 308926200, 9, 1.75, 24.2398222, 54.5792973, 3.03, 15.90, 0.90, 95.35 -NTUN, 1.46, 1.10, -52.129230, 134.307950, -52.129230, 134.307950, -30.638874, 40.429138, 27.251297, 94.168190, 0.27, -5.70 -CTUN, 337, 5.89, 4.20, 7.620000, 0, 0, 112, 752, 0 -ATT, 0.27, 0.03, -5.70, -0.13, 0.00, 69.34, 79.34 -NTUN, 1.43, 1.11, -52.000767, 131.609650, -52.000767, 131.609650, -29.517799, 38.308655, 25.271917, 95.284126, 0.74, -5.69 -CTUN, 336, 5.89, 4.27, 7.620000, 0, 0, 117, 742, 0 -ATT, 0.74, 0.38, -5.69, 0.62, 0.00, 66.11, 76.11 -GPS, 3, 308926400, 9, 1.75, 24.2398220, 54.5792992, 3.38, 16.38, 0.98, 96.46 -NTUN, 1.41, 1.11, -51.653019, 128.308790, -51.653019, 128.308790, -31.440739, 34.503742, 28.512604, 93.658005, 0.85, -5.63 -CTUN, 336, 6.37, 4.26, 7.620000, 0, 0, 119, 728, 0 -ATT, 0.85, 0.61, -5.63, 1.29, 0.00, 62.14, 72.14 -NTUN, 1.37, 1.12, -50.923923, 124.796460, -50.923923, 124.796460, -35.667393, 30.531456, 36.218765, 98.224464, 0.93, -6.02 -CTUN, 337, 6.36, 4.41, 7.620000, 0, 0, 122, 713, 0 -GPS, 3, 308926600, 9, 1.75, 24.2398219, 54.5793012, 3.72, 16.80, 1.05, 96.14 -ATT, 0.93, 0.84, -6.02, 0.72, 0.00, 58.49, 68.49 -NTUN, 1.33, 1.12, -49.743343, 120.744250, -49.743343, 120.744250, -40.779099, 26.487364, 46.805801, 96.477844, 0.67, -6.20 -CTUN, 336, 6.37, 4.65, 7.620000, 0, 0, 125, 705, 0 -ATT, 0.67, 1.27, -6.20, -0.29, 0.00, 55.75, 65.75 -NTUN, 1.28, 1.12, -48.143864, 116.237610, -48.143864, 116.237610, -43.524288, 27.768135, 54.994797, 90.933624, 0.34, -6.17 -CTUN, 336, 6.37, 4.90, 7.620000, 0, 0, 121, 700, 0 -GPS, 3, 308926800, 9, 1.75, 24.2398217, 54.5793032, 4.06, 17.27, 1.01, 95.51 -ATT, 0.34, 0.99, -6.17, -0.34, 0.00, 54.99, 64.97 -NTUN, 1.23, 1.12, -46.206898, 110.840710, -46.206898, 110.840710, -46.630077, 29.135546, 62.177879, 79.565384, -0.31, -5.87 -CTUN, 336, 6.40, 5.13, 7.620000, 0, 0, 120, 692, 0 -ATT, -0.31, 0.03, -5.87, 0.42, 0.00, 55.29, 64.97 -NTUN, 1.16, 1.12, -43.860149, 104.948150, -43.860149, 104.948150, -50.085506, 28.113409, 73.467484, 73.074371, -1.10, -5.93 -CTUN, 337, 6.37, 5.41, 7.620000, 0, 0, 108, 692, 0 -GPS, 3, 308927000, 9, 1.75, 24.2398214, 54.5793053, 4.40, 17.71, 1.10, 97.63 -NTUN, 1.10, 1.12, -41.227871, 98.620377, -41.227871, 98.620377, -55.015835, 22.805412, 83.322784, 71.722260, -1.74, -6.15 -ATT, -1.74, -0.15, -6.15, 0.87, 0.00, 56.51, 64.97 -CTUN, 336, 6.38, 5.46, 7.620000, 0, 0, 104, 694, 0 -NTUN, 1.02, 1.12, -38.109997, 92.186981, -38.109997, 92.186981, -58.721611, 20.467167, 96.178741, 69.666046, -2.47, -6.45 -ATT, -2.47, -0.48, -6.45, 0.64, 0.00, 56.90, 64.97 -CTUN, 337, 6.38, 6.00, 7.620000, 0, 0, 90, 689, 0 -GPS, 3, 308927200, 10, 1.49, 24.2398210, 54.5793073, 4.72, 18.15, 1.05, 100.52 -DU32, 7, 393457 -CURR, 337, 85641, 1159, 0, 4813, 0.000000 -NTUN, 0.95, 1.12, -34.733585, 85.588089, -34.733585, 85.588089, -60.522694, 18.144802, 104.429810, 67.664436, -2.92, -6.62 -ATT, -2.92, -0.64, -6.62, 0.36, 0.00, 56.78, 64.97 -CTUN, 337, 6.38, 5.98, 7.620000, 0, 0, 87, 696, 0 -NTUN, 0.87, 1.11, -31.123348, 78.877258, -31.123348, 78.877258, -63.045300, 16.728363, 115.102370, 64.891693, -3.53, -6.82 -ATT, -3.53, -1.14, -6.82, 0.32, 0.00, 56.76, 64.97 -CTUN, 336, 4.85, 6.34, 7.620000, 0, 0, 74, 699, 0 -GPS, 3, 308927400, 10, 1.49, 24.2398206, 54.5793095, 5.01, 18.53, 1.12, 102.55 -NTUN, 0.77, 1.10, -27.452015, 71.775650, -27.452015, 71.775650, -65.387444, 12.132516, 123.349840, 61.687050, -4.07, -6.91 -CTUN, 337, 5.82, 6.61, 7.620000, 0, 0, 69, 703, 0 -ATT, -4.07, -2.28, -6.91, -0.15, 0.00, 56.83, 64.97 -NTUN, 0.77, 1.10, -23.884335, 64.599396, -23.884335, 64.599396, -64.279190, 10.584182, 127.676800, 57.237457, -4.42, -6.83 -CTUN, 337, 5.82, 6.81, 7.620000, 0, 0, 58, 705, 0 -ATT, -4.42, -2.81, -6.83, -0.39, 0.00, 57.05, 64.97 -GPS, 3, 308927600, 10, 1.49, 24.2398199, 54.5793115, 5.33, 18.88, 1.12, 105.99 -NTUN, 0.67, 1.10, -20.357830, 57.300983, -20.357830, 57.300983, -62.516785, 7.539318, 131.265050, 54.015877, -4.68, -6.80 -CMD, 8, 2, 16, 1, 0, 7.62, 24.2398304, 54.5793472 -CTUN, 337, 6.31, 6.91, 7.620000, 0, 0, 54, 717, 0 -ATT, -3.09, -3.05, -0.55, -0.58, 0.00, 56.89, 66.77 -NTUN, 0.00, 0.69, -15.613808, 52.703514, -15.613808, 52.703514, -59.282318, 6.241214, 145.970520, 80.480499, -4.54, -8.54 -CTUN, 337, 6.31, 7.17, 7.620000, 0, 0, 46, 703, 0 -ATT, -4.54, -2.91, -8.54, -0.34, 0.00, 56.81, 69.72 -GPS, 3, 308927800, 9, 1.75, 24.2398194, 54.5793134, 5.60, 19.19, 1.05, 107.00 -NTUN, 4.30, 0.68, -10.121582, 50.594215, -10.121582, 50.594215, -57.730812, 4.638804, 160.477020, 105.693950, -4.54, -10.15 -CTUN, 336, 6.31, 7.37, 7.620000, 0, 0, 42, 727, 0 -ATT, -4.54, -4.49, -10.15, 0.71, 0.00, 58.72, 69.72 -NTUN, 4.24, 0.68, -3.537167, 51.296951, -3.537167, 51.296951, -54.789848, -2.309740, 177.844150, 145.027360, -4.64, -12.37 -CTUN, 336, 3.58, 7.44, 7.620000, 0, 0, 36, 714, 0 -GPS, 3, 308928000, 10, 1.49, 24.2398190, 54.5793154, 5.88, 19.47, 1.05, 105.62 -ATT, -4.64, -3.70, -12.37, -2.10, 0.00, 60.14, 69.72 -NTUN, 4.18, 0.67, 3.965332, 55.457954, 3.965332, 55.457954, -49.233303, -4.116338, 190.553910, 187.794140, -4.16, -14.72 -CTUN, 336, 4.63, 7.53, 7.620000, 0, 0, 41, 713, 0 -ATT, -4.16, -2.41, -14.72, -4.75, 0.00, 59.52, 69.72 -NTUN, 4.12, 0.66, 11.225163, 59.944443, 11.225163, 59.944443, -42.349426, 1.907382, 192.331620, 194.318070, -3.89, -15.12 -CTUN, 337, 4.63, 7.62, 7.620000, 0, 0, 34, 714, 0 -GPS, 3, 308928200, 10, 1.49, 24.2398186, 54.5793171, 6.16, 19.72, 0.89, 105.29 -DU32, 7, 393457 -CURR, 336, 92052, 1164, 0, 4752, 0.000000 -NTUN, 4.05, 0.66, 18.320229, 64.669800, 18.320229, 64.669800, -36.724842, 9.730409, 193.559480, 194.327030, -3.95, -15.15 -ATT, -3.95, -2.02, -15.15, -6.20, 0.00, 59.51, 69.72 -CTUN, 337, 6.05, 7.64, 7.620000, 0, 0, 32, 720, 0 -NTUN, 3.96, 0.65, 25.009930, 68.819839, 25.009930, 68.819839, -30.619263, 17.709455, 194.572740, 188.919590, -4.21, -14.91 -ATT, -4.21, -2.24, -14.91, -6.98, 0.00, 59.76, 69.72 -CTUN, 336, 6.05, 7.81, 7.620000, 0, 0, 25, 723, 0 -GPS, 3, 308928400, 10, 1.49, 24.2398184, 54.5793191, 6.39, 19.98, 1.02, 100.04 -PM, 0, 0, 50, 40, 1001, 11692, 7, 0 -NTUN, 3.87, 0.64, 31.593376, 73.129684, 31.593376, 73.129684, -22.604809, 27.677116, 194.834470, 186.098450, -4.29, -14.79 -ATT, -4.29, -2.15, -14.79, -7.78, 0.00, 59.75, 69.72 -CTUN, 337, 6.35, 7.91, 7.620000, 0, 1, 20, 734, 0 -NTUN, 3.76, 0.64, 38.097515, 77.597168, 38.097515, 77.597168, -14.265009, 38.502377, 193.397420, 183.232510, -4.33, -14.61 -ATT, -4.33, -2.08, -14.61, -8.12, 0.00, 59.77, 69.72 -CTUN, 337, 6.35, 7.82, 7.620000, 0, 1, 15, 725, 0 -GPS, 3, 308928600, 10, 1.49, 24.2398186, 54.5793212, 6.59, 20.20, 1.06, 91.04 -NTUN, 3.64, 0.63, 44.217991, 81.987923, 44.217991, 81.987923, -7.039289, 50.184177, 192.204760, 176.907550, -4.36, -14.30 -CTUN, 336, 6.38, 7.76, 7.620000, 0, 1, 16, 726, 0 -ATT, -4.36, -2.22, -14.30, -8.04, 0.00, 59.28, 69.72 -NTUN, 3.51, 0.63, 50.014851, 86.482742, 50.014851, 86.482742, 0.730065, 59.651535, 188.394650, 173.503160, -4.24, -14.04 -CTUN, 337, 6.38, 7.90, 7.620000, 0, 1, 11, 734, 0 -ATT, -4.24, -2.49, -14.04, -7.88, 0.00, 59.47, 69.72 -GPS, 3, 308928800, 10, 1.49, 24.2398189, 54.5793237, 6.76, 20.38, 1.30, 87.22 -NTUN, 3.36, 0.62, 55.584438, 91.010704, 55.584438, 91.010704, 9.358702, 71.236969, 186.695880, 168.279620, -4.38, -13.73 -CTUN, 337, 6.38, 7.91, 7.620000, 0, 1, 7, 735, 0 -ATT, -4.38, -2.56, -13.73, -7.51, 0.00, 59.40, 69.72 -NTUN, 3.20, 0.62, 60.955303, 95.611542, 60.955303, 95.611542, 18.277100, 81.382446, 182.708650, 165.008380, -4.22, -13.48 -CTUN, 336, 6.37, 7.74, 7.620000, 0, 1, 7, 730, 0 -GPS, 3, 308929000, 10, 1.49, 24.2398197, 54.5793265, 6.91, 20.51, 1.44, 79.50 -ATT, -4.22, -2.49, -13.48, -7.41, 0.00, 58.91, 69.72 -NTUN, 3.03, 0.61, 65.961838, 100.484850, 65.961838, 100.484850, 25.566374, 92.053909, 179.065340, 161.733060, -4.01, -13.26 -CTUN, 336, 6.38, 7.93, 7.620000, 0, 1, 3, 737, 0 -ATT, -4.01, -1.96, -13.26, -7.72, 0.00, 58.40, 69.72 -NTUN, 2.84, 0.60, 70.604034, 105.514630, 70.604034, 105.514630, 32.901661, 100.880840, 172.962340, 158.799850, -3.69, -12.97 -CTUN, 336, 6.37, 8.27, 7.620000, 0, 1, 2, 738, 0 -GPS, 3, 308929200, 10, 1.49, 24.2398206, 54.5793296, 7.03, 20.65, 1.68, 74.80 -NTUN, 2.65, 0.60, 75.120743, 110.933170, 75.120743, 110.933170, 41.976795, 113.830530, 170.167080, 157.185330, -3.57, -12.82 -ATT, -3.57, -2.18, -12.82, -7.86, 0.00, 58.20, 69.72 -CTUN, 337, 6.37, 8.18, 7.620000, 0, 1, 3, 727, 0 -DU32, 7, 393457 -CURR, 336, 99318, 1154, 0, 4752, 0.000000 -NTUN, 2.42, 0.59, 79.471603, 116.699040, 79.471603, 116.699040, 54.062313, 124.512560, 161.508610, 155.658690, -3.22, -12.49 -ATT, -3.22, -4.07, -12.49, -7.72, 0.00, 58.42, 69.72 -CTUN, 337, 6.37, 8.31, 7.620000, 0, 1, 12, 708, 0 -GPS, 3, 308929400, 10, 1.49, 24.2398219, 54.5793333, 7.18, 20.75, 1.96, 72.40 -NTUN, 2.17, 0.58, 83.586761, 124.314700, 83.586761, 124.314700, 73.631790, 134.633610, 143.744140, 169.402590, -2.31, -12.56 -ATT, -2.31, -4.26, -12.56, -6.88, 0.00, 60.83, 69.72 -CTUN, 337, 6.37, 8.04, 7.620000, 0, 0, 30, 672, 0 -NTUN, 1.90, 0.57, 87.237000, 133.331740, 87.087151, 133.102710, 80.975159, 141.036850, 135.003890, 184.880100, -2.01, -12.99 -ATT, -2.01, -2.97, -12.99, -5.41, 0.00, 63.27, 69.72 -CTUN, 337, 6.37, 8.06, 7.620000, 0, 0, 39, 682, 0 -GPS, 3, 308929600, 10, 1.49, 24.2398234, 54.5793373, 7.36, 20.88, 2.16, 69.40 -NTUN, 1.64, 0.57, 87.993027, 136.345060, 87.740974, 135.954500, 84.271759, 147.272370, 103.538240, 121.517910, -2.37, -8.94 -CTUN, 336, 6.37, 8.34, 7.620000, 0, 0, 37, 669, 0 -ATT, -2.37, -2.44, -8.94, -5.40, 0.00, 64.53, 69.72 -NTUN, 1.64, 0.57, 76.037827, 113.121060, 76.037827, 113.121060, 88.433815, 153.776950, -33.872749, -164.073610, -2.34, 9.41 -CTUN, 337, 6.37, 8.88, 7.620000, 0, 0, 37, 678, 0 -ATT, -2.34, -1.33, 9.41, -5.19, 0.00, 64.33, 69.72 -GPS, 3, 308929800, 10, 1.49, 24.2398255, 54.5793415, 7.54, 21.04, 2.43, 64.46 -NTUN, 1.33, 0.55, 63.812515, 89.206543, 63.812515, 89.206543, 89.953163, 164.993390, -56.253113, -216.145200, -2.45, 12.60 -CMD, 8, 6, 16, 1, 0, 7.62, 24.2398128, 54.5793536 -CTUN, 337, 6.40, 8.07, 7.620000, 0, 0, 29, 666, 0 -ATT, -1.27, -1.94, -3.87, 0.06, 0.00, 65.11, 66.12 -NTUN, 0.00, 1.31, 48.562218, 65.493164, 48.562218, 65.493164, 86.377777, 166.580000, -97.993042, -242.785920, -0.68, 14.93 -CTUN, 337, 6.37, 8.02, 7.620000, 0, 0, 32, 670, 0 -GPS, 3, 308930000, 10, 1.49, 24.2398277, 54.5793460, 7.70, 21.17, 2.56, 63.22 -ATT, -0.68, -5.29, 14.93, 5.91, 0.00, 65.88, 60.12 -NTUN, 1.93, 1.38, 31.086990, 43.820007, 31.086990, 43.820007, 87.398422, 144.648850, -144.517460, -230.920780, 2.19, 15.38 -CTUN, 336, 6.37, 9.37, 7.620000, 0, 0, 47, 629, 0 -ATT, 2.19, -2.32, 15.38, 6.52, 0.00, 64.14, 54.12 -NTUN, 1.88, 1.47, 10.479088, 24.978851, 10.479088, 24.978851, 83.557144, 135.620450, -195.079030, -216.411560, 4.28, 16.02 -CTUN, 337, 6.36, 9.75, 7.620000, 0, 0, 47, 636, 0 -GPS, 3, 308930200, 10, 1.49, 24.2398299, 54.5793504, 7.93, 21.28, 2.52, 62.57 -ATT, 4.28, -2.21, 16.02, 13.14, 0.00, 60.14, 48.12 -NTUN, 1.88, 1.54, -11.980812, 8.366272, -11.980812, 8.366272, 69.740768, 117.344190, -223.375240, -195.480970, 5.18, 16.05 -CTUN, 337, 6.36, 10.07, 7.620000, 0, 0, 47, 619, 0 -DU32, 7, 393457 -CURR, 336, 105315, 1172, 0, 4772, 0.000000 -ATT, 5.18, -3.59, 16.05, 16.37, 0.00, 57.15, 42.12 -NTUN, 1.91, 1.61, -33.380829, -5.255310, -33.380829, -5.255310, 57.101727, 85.864799, -229.000170, -155.215820, 5.84, 14.63 -CTUN, 337, 6.35, 10.36, 7.620000, 0, 0, 52, 587, 0 -GPS, 3, 308930400, 10, 1.49, 24.2398318, 54.5793546, 8.19, 21.45, 2.38, 62.71 -ATT, 5.84, -1.66, 14.63, 17.45, 0.00, 53.70, 36.12 -NTUN, 1.96, 1.68, -54.081150, -15.671112, -54.081150, -15.671112, 37.389668, 56.837921, -227.003200, -107.158020, 6.29, 12.85 -CTUN, 336, 6.36, 10.55, 7.620000, 0, 0, 57, 569, 0 -ATT, 6.29, -0.27, 12.85, 18.62, 0.00, 49.20, 30.12 -NTUN, 2.01, 1.72, -74.059990, -23.124451, -74.059990, -23.124451, 15.630918, 34.957474, -220.810290, -65.795433, 6.59, 11.34 -CTUN, 336, 6.36, 10.87, 7.620000, 0, 0, 54, 565, 0 -GPS, 3, 308930600, 10, 1.49, 24.2398332, 54.5793580, 8.55, 21.61, 1.91, 63.37 -ATT, 6.59, -0.21, 11.34, 19.58, 0.00, 45.13, 24.12 -NTUN, 2.06, 1.76, -92.830406, -28.438477, -92.830406, -28.438477, -5.757162, 14.400352, -212.704160, -31.140259, 6.92, 10.06 -CTUN, 337, 6.37, 10.98, 7.620000, 0, 0, 43, 561, 0 -ATT, 6.92, 1.03, 10.06, 18.64, 0.00, 42.10, 18.12 -NTUN, 2.07, 1.79, -110.903880, -31.204193, -110.903880, -31.204193, -30.422009, -4.934965, -202.734710, 8.342834, 7.65, 8.57 -CTUN, 337, 6.37, 11.07, 7.620000, 0, 0, 41, 535, 0 -GPS, 3, 308930800, 10, 1.49, 24.2398340, 54.5793602, 8.92, 21.78, 1.23, 64.51 -ATT, 7.65, 3.00, 8.57, 17.79, 0.00, 38.27, 12.12 -NTUN, 2.07, 1.81, -128.744720, -31.539124, -128.744720, -31.539124, -58.692818, -18.163364, -191.642000, 45.683857, 8.40, 7.27 -CTUN, 337, 6.38, 11.12, 7.620000, 0, 0, 35, 532, 0 -ATT, 8.40, 4.00, 7.27, 17.15, 0.00, 33.89, 6.12 -NTUN, 2.04, 1.82, -145.596950, -30.031494, -145.596950, -30.031494, -83.956619, -25.139088, -177.522340, 72.076294, 8.68, 6.42 -CTUN, 337, 6.38, 11.24, 7.620000, 0, 0, 22, 539, 0 -GPS, 3, 308931000, 10, 1.49, 24.2398341, 54.5793616, 9.25, 21.91, 0.70, 69.88 -ATT, 8.68, 5.41, 6.42, 15.86, 0.00, 30.11, 0.12 -NTUN, 1.98, 1.84, -162.174530, -27.363251, -161.545910, -27.257187, -107.806610, -29.126593, -163.489590, 89.743073, 8.78, 5.83 -CTUN, 337, 6.38, 11.28, 7.620000, 0, 0, 9, 541, 0 -ATT, 8.78, 5.90, 5.83, 14.90, 0.00, 25.69, 0.00 -NTUN, 1.90, 1.85, -178.638640, -23.845093, -176.108830, -23.507406, -128.553410, -26.891155, -145.187240, 102.126540, 8.60, 5.20 -CTUN, 337, 6.38, 11.19, 7.620000, 0, 0, 0, 543, 0 -GPS, 3, 308931200, 10, 1.49, 24.2398331, 54.5793623, 9.49, 22.00, 0.66, 103.42 -ATT, 8.60, 6.06, 5.20, 13.88, 0.00, 22.29, 0.00 -NTUN, 1.81, 1.87, -176.289000, -25.799622, -174.072040, -25.475174, -150.171250, -26.392176, 42.367889, 42.322323, 1.36, -3.20 -CTUN, 337, 6.40, 11.29, 7.620000, 0, 0, -19, 551, 0 -ATT, 1.36, 5.75, -3.20, 12.86, 0.00, 20.31, 0.00 -NTUN, 1.70, 1.89, -163.574740, -30.749634, -162.774860, -30.599264, -167.056750, -20.210482, 162.971800, -0.240902, -3.22, -8.85 -DU32, 7, 393457 -CURR, 336, 111454, 1167, 0, 4772, 0.000000 -CTUN, 336, 6.38, 11.30, 7.620000, 0, 0, -38, 565, 0 -GPS, 3, 308931400, 10, 1.49, 24.2398314, 54.5793629, 9.67, 22.01, 1.01, 145.69 -ATT, -3.22, 3.19, -8.85, 10.66, 0.00, 19.86, 0.00 -CMD, 8, 7, 16, 1, 0, 7.62, 24.2398000, 54.5793472 -NTUN, 0.00, 1.98, -167.815110, -44.318542, -166.260770, -43.908058, -183.294240, -21.215260, 28.485981, -93.770233, -5.61, 0.30 -CTUN, 337, 6.40, 11.34, 7.620000, 0, 0, -50, 577, 0 -ATT, -5.61, 1.84, 0.30, 7.88, 0.00, 20.17, 354.00 -NTUN, 2.99, 2.00, -173.453980, -58.942780, -170.582630, -57.967037, -190.984310, -18.184553, 23.781464, -121.589780, -7.04, 1.11 -CTUN, 337, 6.38, 11.09, 7.620000, 0, 0, -58, 591, 0 -GPS, 3, 308931600, 10, 1.49, 24.2398290, 54.5793631, 9.76, 21.96, 1.37, 162.38 -ATT, -7.04, -2.38, 1.11, 9.75, 0.00, 19.31, 348.00 -NTUN, 2.86, 2.02, -180.739150, -74.414978, -175.782970, -72.374390, -206.945450, -22.415274, 27.996521, -137.073520, -7.93, 1.07 -CTUN, 336, 6.38, 11.12, 7.620000, 0, 0, -70, 599, 0 -ATT, -7.93, -6.72, 1.07, 8.90, 0.00, 17.63, 342.00 -NTUN, 2.71, 2.04, -189.804350, -89.696442, -181.905560, -85.963684, -216.787050, -38.525570, 24.380306, -128.547470, -7.47, 0.76 -CTUN, 336, 6.38, 11.06, 7.620000, 0, 0, -80, 606, 0 -GPS, 3, 308931800, 10, 1.49, 24.2398261, 54.5793633, 9.79, 21.83, 1.70, 170.74 -ATT, -7.47, -8.16, 0.76, 8.80, 0.00, 13.52, 336.00 -NTUN, 2.55, 2.06, -200.380250, -104.190090, -188.741990, -98.138649, -227.904390, -53.881424, 23.635742, -114.749650, -6.73, 0.02 -CTUN, 336, 6.38, 10.89, 7.620000, 0, 0, -79, 617, 0 -ATT, -6.73, -10.85, 0.02, 8.62, 0.00, 6.83, 330.00 -NTUN, 2.38, 2.08, -202.978960, -113.658260, -189.741930, -106.246170, -238.361180, -71.817581, 93.099617, -65.272484, -4.19, -5.09 -CTUN, 336, 6.38, 10.74, 7.620000, 0, 0, -84, 621, 0 -GPS, 3, 308932000, 10, 1.49, 24.2398230, 54.5793629, 9.77, 21.58, 1.84, 179.72 -ATT, -4.19, -12.15, -5.09, 7.34, 0.00, 359.63, 324.00 -NTUN, 2.18, 2.10, -181.830180, -110.309780, -173.755230, -105.411010, -254.641270, -90.763802, 300.481750, 43.435951, 3.43, -16.88 -CTUN, 337, 6.38, 10.88, 7.620000, 0, 0, -85, 632, 0 -ATT, 3.43, -12.43, -16.88, 5.38, 0.00, 350.72, 318.00 -MODE, LAND, 500 -NTUN, 1.97, 2.12, 6.865845, 1.784973, -255.146000, -100.600240, -267.450870, -108.417140, 12.000000, 7.000000, 0.54, -0.60 -CTUN, 337, 6.37, 10.73, 0.000000, 0, 0, -87, 646, 0 -GPS, 3, 308932200, 10, 1.49, 24.2398193, 54.5793620, 9.73, 21.35, 2.15, 186.89 -ATT, 0.00, -10.79, 0.00, 0.91, 0.00, 342.17, 339.87 -NTUN, 0.07, 0.15, 5.278854, -0.743225, -242.299560, -95.950035, -269.809720, -126.400400, 155.192430, 77.041656, 7.20, -7.03 -CTUN, 336, 6.37, 10.62, 0.000000, 0, 0, -84, 645, 0 -ATT, 0.00, -9.01, 0.00, 1.61, 0.00, 339.79, 339.87 -NTUN, 0.05, 0.14, 5.244492, -0.045349, -228.692900, -88.467850, -271.216310, -143.849470, 181.066590, 133.821850, 10.81, -7.23 -CTUN, 336, 6.37, 10.64, 0.000000, 0, 0, -79, 641, 0 -GPS, 3, 308932400, 10, 1.49, 24.2398153, 54.5793604, 9.68, 21.13, 2.40, 192.95 -ATT, 0.00, -7.38, 0.00, 2.50, 0.00, 341.28, 339.87 -DU32, 7, 393457 -CURR, 337, 117547, 1180, 0, 4772, 0.000000 -NTUN, 0.05, 0.18, 7.314941, 2.483826, -213.595280, -79.459663, -284.514130, -151.675030, 226.976260, 169.081860, 13.25, -9.46 -CTUN, 336, 6.37, 10.49, 0.000000, 0, 0, -77, 631, 0 -ATT, 0.00, -3.69, 0.00, -0.40, 0.00, 343.29, 339.87 -NTUN, 0.07, 0.23, 11.000992, 6.615356, -197.343860, -69.078796, -283.198520, -158.640630, 256.905150, 203.780850, 15.28, -10.89 -CTUN, 336, 6.37, 10.26, 0.000000, 0, 0, -71, 631, 0 -GPS, 3, 308932600, 10, 1.49, 24.2398108, 54.5793576, 9.63, 20.89, 2.87, 202.45 -ATT, 0.00, -0.16, 0.00, -0.22, 0.00, 344.11, 339.87 -NTUN, 0.12, 0.28, 15.761566, 12.138824, -180.707760, -57.649094, -280.881040, -155.360000, 282.360930, 228.297030, 16.78, -12.12 -CTUN, 337, 6.37, 10.12, 0.000000, 0, 0, -73, 628, 0 -ATT, 0.00, 1.48, 0.00, -0.59, 0.00, 345.04, 339.87 -NTUN, 0.19, 0.32, 21.697449, 18.164276, -163.430760, -45.983185, -278.193180, -153.425980, 307.770080, 245.659090, 17.84, -13.49 -CTUN, 336, 6.37, 10.11, 0.000000, 0, 0, -67, 626, 0 -GPS, 3, 308932800, 9, 1.75, 24.2398061, 54.5793543, 9.56, 20.65, 3.09, 208.60 -ATT, 0.00, 4.00, 0.00, -2.81, 0.00, 345.94, 339.87 -NTUN, 0.28, 0.34, 28.414459, 25.049957, -145.774670, -33.657001, -271.690400, -146.692580, 327.812680, 263.041410, 18.78, -14.57 -CTUN, 336, 6.37, 9.99, 0.000000, 0, 0, -74, 626, 0 -ATT, 0.00, 6.41, 0.00, -3.87, 0.00, 346.40, 339.87 -NTUN, 0.37, 0.36, 35.487930, 31.974701, -128.362690, -21.590446, -261.400240, -136.131500, 341.119870, 267.665560, 19.05, -15.37 -GPS, 3, 308933000, 9, 1.75, 24.2398014, 54.5793507, 9.48, 20.41, 3.16, 211.17 -CTUN, 336, 6.37, 9.74, 0.000000, 0, 0, -69, 630, 0 -ATT, 0.00, 7.81, 0.00, -5.25, 0.00, 346.77, 339.87 -NTUN, 0.47, 0.38, 42.816177, 39.074921, -111.161160, -9.579796, -251.653370, -124.193830, 353.015230, 273.106510, 19.37, -16.00 -CTUN, 337, 6.37, 9.61, 0.000000, 0, 0, -78, 642, 0 -ATT, 0.00, 9.08, 0.00, -7.50, 0.00, 346.93, 339.87 -NTUN, 0.57, 0.39, 49.697113, 45.916412, -94.756958, 1.998055, -233.535320, -114.304320, 348.417850, 275.632170, 19.34, -15.77 -GPS, 3, 308933200, 10, 1.49, 24.2397969, 54.5793475, 9.35, 20.16, 3.00, 212.09 -CTUN, 336, 6.37, 9.38, 0.000000, 0, 0, -76, 644, 0 -NTUN, 0.67, 0.39, 56.098145, 52.584900, -79.355499, 13.142868, -214.462810, -101.377850, 344.014590, 276.448120, 19.27, -15.56 -ATT, 0.00, 9.93, 0.00, -8.47, 0.00, 347.05, 339.87 -CTUN, 336, 6.38, 9.18, 0.000000, 0, 0, -80, 640, 0 -NTUN, 0.76, 0.40, 61.610992, 58.665222, -65.247238, 23.498081, -195.747280, -88.610329, 333.082610, 271.552120, 18.78, -15.14 -ATT, 0.00, 10.67, 0.00, -9.47, 0.00, 347.39, 339.87 -GPS, 3, 308933400, 10, 1.49, 24.2397929, 54.5793444, 9.20, 19.90, 2.74, 213.54 -CTUN, 337, 6.37, 9.13, 0.000000, 0, 1, -81, 655, 0 -DU32, 7, 393457 -CURR, 336, 123949, 1199, 0, 4752, 0.000000 -NTUN, 0.85, 0.41, 66.097809, 64.531677, -52.469711, 33.487885, -176.021730, -73.919937, 317.510160, 267.908940, 18.24, -14.51 -ATT, 0.00, 11.47, 0.00, -10.58, 0.00, 347.87, 339.87 -CTUN, 336, 6.37, 8.83, 0.000000, 0, 0, -83, 641, 0 -NTUN, 0.92, 0.42, 69.365814, 69.639557, -41.366165, 42.492733, -151.981890, -59.308189, 294.035460, 258.048490, 17.36, -13.45 -ATT, 0.00, 11.67, 0.00, -11.69, 0.00, 348.16, 339.87 -GPS, 3, 308933600, 9, 1.75, 24.2397896, 54.5793418, 9.02, 19.63, 2.28, 213.97 -CTUN, 336, 6.37, 8.75, 0.000000, 0, 1, -76, 654, 0 -NTUN, 0.98, 0.43, 71.015961, 74.200226, -32.158249, 50.812225, -125.982610, -45.941948, 262.167480, 250.371220, 16.44, -12.04 -ATT, 0.00, 11.66, 0.00, -12.13, 0.00, 349.06, 339.87 -CTUN, 336, 6.37, 8.51, 0.000000, 0, 1, -77, 647, 0 -NTUN, 1.02, 0.44, 71.102661, 77.953064, -24.928711, 58.117523, -103.207430, -30.797054, 232.295380, 237.052980, 15.22, -10.91 -ATT, 0.00, 10.88, 0.00, -11.99, 0.00, 350.45, 340.45 -GPS, 3, 308933800, 9, 1.75, 24.2397869, 54.5793395, 8.83, 19.36, 1.87, 215.59 -CTUN, 336, 6.31, 8.39, 0.000000, 0, 1, -74, 663, 0 -NTUN, 1.05, 0.46, 70.009033, 81.320648, -19.200928, 64.877708, -82.247559, -18.192736, 205.277830, 230.601850, 14.39, -9.86 -ATT, 0.00, 9.86, 0.00, -12.12, 0.00, 352.00, 342.00 -CTUN, 337, 6.36, 8.31, 0.000000, 0, 1, -75, 651, 0 -NTUN, 1.07, 0.48, 67.424316, 84.177826, -15.206047, 71.007217, -61.032948, -6.837453, 171.553270, 221.688200, 13.47, -8.40 -ATT, 0.00, 9.32, 0.00, -11.56, 0.00, 353.57, 343.57 -GPS, 3, 308934000, 9, 1.75, 24.2397851, 54.5793377, 8.65, 19.07, 1.38, 217.18 -CTUN, 336, 6.36, 8.31, 0.000000, 0, 1, -71, 657, 0 -NTUN, 1.07, 0.50, 63.759369, 86.524658, -12.714813, 76.415802, -40.372002, 3.469611, 141.163970, 214.632170, 12.78, -7.05 -ATT, 0.00, 8.18, 0.00, -10.66, 0.00, 355.03, 345.03 -CTUN, 336, 6.36, 7.96, 0.000000, 0, 0, -65, 639, 0 -NTUN, 1.07, 0.53, 58.878906, 88.574432, -11.594521, 81.450020, -23.527332, 12.611626, 111.092000, 208.843730, 12.18, -5.73 -ATT, 0.00, 7.26, 0.00, -10.02, 0.00, 356.76, 346.76 -GPS, 3, 308934200, 9, 1.75, 24.2397840, 54.5793364, 8.46, 18.81, 0.88, 219.92 -CTUN, 336, 6.36, 8.02, 0.000000, 0, 0, -63, 641, 0 -NTUN, 1.06, 0.56, 53.121094, 90.519745, -11.624313, 86.244141, -7.828726, 21.051466, 85.705025, 206.466540, 11.87, -4.66 -ATT, 0.00, 6.49, 0.00, -8.93, 0.00, 358.60, 348.60 -CTUN, 337, 6.36, 7.99, 0.000000, 0, 0, -56, 638, 0 -NTUN, 1.04, 0.60, 46.675934, 92.180145, -12.655930, 90.596939, 1.618477, 28.938814, 63.683838, 201.527980, 11.51, -3.71 -ATT, 0.00, 6.03, 0.00, -7.46, 0.00, 0.12, 350.12 -GPS, 3, 308934400, 9, 1.75, 24.2397836, 54.5793354, 8.29, 18.55, 0.57, 231.55 -CTUN, 337, 5.51, 7.87, 0.000000, 0, 0, -60, 639, 0 -NTUN, 1.03, 0.64, 39.874176, 93.648529, -14.287754, 93.648529, 13.458117, 33.666645, 43.681755, 189.515900, 10.81, -2.77 -ATT, 0.00, 5.31, 0.00, -6.59, 0.00, 1.30, 351.30 -DU32, 7, 393457 -CURR, 337, 130402, 1189, 0, 4772, 0.000000 -CTUN, 337, 5.51, 7.75, 0.000000, 0, 0, -51, 627, 0 -NTUN, 1.01, 0.68, 32.636597, 94.837799, -16.538673, 94.837799, 21.639561, 38.231819, 24.713671, 170.774950, 9.75, -1.89 -ATT, 0.00, 5.08, 0.00, -5.45, 0.00, 2.76, 352.76 -GPS, 3, 308934600, 10, 1.49, 24.2397837, 54.5793346, 8.13, 18.28, 0.38, 248.64 -CTUN, 337, 5.51, 7.68, 0.000000, 0, 0, -51, 620, 0 -NTUN, 1.00, 0.72, 25.289978, 95.943085, -19.219536, 95.943085, 27.341030, 42.245224, 9.920582, 170.164510, 9.75, -1.31 -ATT, 0.00, 4.84, 0.00, -3.96, 0.00, 4.39, 354.39 -CTUN, 336, 5.82, 7.51, 0.000000, 0, 0, -45, 613, 0 -NTUN, 0.99, 0.77, 17.969055, 96.826263, -21.992500, 96.826263, 27.795399, 46.195755, 3.544907, 166.744340, 9.56, -1.21 -ATT, 0.00, 4.66, 0.00, -2.32, 0.00, 6.10, 356.10 -GPS, 3, 308934800, 10, 1.49, 24.2397841, 54.5793343, 7.98, 18.07, 0.27, 277.16 -CTUN, 337, 5.82, 7.44, 0.000000, 0, 0, -49, 609, 0 -NTUN, 0.98, 0.81, 11.092133, 97.333496, -24.571152, 97.333496, 28.234222, 49.305347, 0.213486, 164.072330, 9.41, -1.22 -ATT, 0.00, 4.81, 0.00, -0.87, 0.00, 7.40, 357.40 -CTUN, 337, 6.37, 7.24, 0.000000, 0, 0, -50, 620, 0 -NTUN, 0.97, 0.85, 4.970306, 97.436096, -26.588131, 97.436096, 24.313164, 53.603748, 4.830208, 157.026000, 8.96, -1.57 -ATT, 0.00, 4.80, 0.00, 0.17, 0.00, 8.12, 358.12 -GPS, 3, 308935000, 10, 1.49, 24.2397847, 54.5793341, 7.81, 17.80, 0.33, 311.43 -CTUN, 336, 6.37, 7.13, 0.000000, 0, 0, -54, 613, 0 -NTUN, 0.97, 0.88, -0.428253, 97.205231, -28.027359, 97.205231, 19.956686, 56.961964, 11.750217, 152.714200, 8.66, -1.95 -ATT, 0.00, 4.30, 0.00, 0.92, 0.00, 8.19, 358.23 -CTUN, 337, 6.40, 6.91, 0.000000, 0, 0, -53, 618, 0 -NTUN, 0.97, 0.91, -4.877777, 96.671753, -28.734922, 96.671753, 12.385397, 61.856934, 22.924366, 145.665220, 8.18, -2.48 -ATT, 0.00, 3.68, 0.00, 1.71, 0.00, 7.75, 358.23 -GPS, 3, 308935200, 10, 1.49, 24.2397854, 54.5793340, 7.62, 17.54, 0.38, 332.86 -CTUN, 336, 6.38, 6.91, 0.000000, 0, 0, -48, 587, 0 -NTUN, 0.96, 0.93, -8.548340, 95.905273, -28.831913, 95.905273, 5.545835, 62.362228, 34.030094, 143.335210, 8.01, -2.98 -ATT, 0.00, 2.53, 0.00, 1.72, 0.00, 6.84, 358.23 -CTUN, 336, 6.40, 6.74, 0.000000, 0, 0, -44, 601, 0 -NTUN, 0.96, 0.95, -11.390503, 95.243042, -28.261314, 95.243042, 3.248413, 61.916893, 42.705986, 146.377690, 8.16, -3.42 -ATT, 0.00, 3.24, 0.00, 1.03, 0.00, 6.33, 358.23 -GPS, 3, 308935400, 10, 1.49, 24.2397857, 54.5793343, 7.45, 17.28, 0.23, 345.08 -CTUN, 337, 6.40, 6.51, 0.000000, 0, 0, -41, 584, 0 -NTUN, 0.95, 0.97, -13.599121, 94.237396, -27.178154, 94.237396, 0.272123, 65.489029, 49.724361, 139.043110, 7.71, -3.75 -ATT, 0.00, 3.27, 0.00, 1.75, 0.00, 6.12, 358.23 -DU32, 7, 393457 -CURR, 337, 136511, 1173, 0, 4752, 0.000000 -CTUN, 337, 6.40, 6.48, 0.000000, 0, 0, -44, 599, 0 -NTUN, 0.95, 0.98, -14.917664, 92.849945, -25.385639, 92.849945, -6.976023, 67.602180, 64.925148, 134.125490, 7.32, -4.61 -ATT, 0.00, 2.89, 0.00, 2.20, 0.00, 6.27, 358.23 -GPS, 3, 308935600, 10, 1.49, 24.2397858, 54.5793345, 7.26, 17.07, 0.12, 345.08 -CTUN, 337, 6.40, 6.28, 0.000000, 0, 0, -39, 583, 0 -NTUN, 0.94, 0.99, -15.265991, 91.394714, -22.733198, 91.394714, -13.428787, 68.948967, 82.261795, 131.591780, 7.08, -5.58 -ATT, 0.00, 2.73, 0.00, 2.17, 0.00, 6.14, 358.23 -CTUN, 336, 6.40, 6.11, 0.000000, 0, 0, -44, 590, 0 -NTUN, 0.92, 0.99, -14.701508, 89.773895, -19.332689, 89.773895, -18.008480, 69.035248, 98.005089, 128.791810, 6.84, -6.46 -ATT, 0.00, 2.22, 0.00, 1.48, 0.00, 6.06, 358.23 -GPS, 3, 308935800, 10, 1.49, 24.2397860, 54.5793347, 7.06, 16.81, 0.13, 345.08 -CTUN, 336, 6.40, 6.03, 0.000000, 0, 0, -39, 579, 0 -NTUN, 0.90, 0.98, -13.698700, 88.212189, -15.621479, 88.212189, -19.382402, 69.336479, 105.112110, 128.382930, 6.76, -6.87 -ATT, 0.00, 2.01, 0.00, 1.16, 0.00, 6.19, 358.23 -CTUN, 336, 6.40, 5.81, 0.000000, 0, 0, -45, 594, 0 -NTUN, 0.89, 0.98, -12.332245, 86.655731, -12.332245, 86.655731, -22.826569, 69.345764, 108.566670, 127.589530, 6.65, -7.10 -ATT, 0.00, 1.70, 0.00, 1.10, 0.00, 6.51, 358.23 -GPS, 3, 308936000, 10, 1.49, 24.2397858, 54.5793353, 6.84, 16.55, 0.34, 84.93 -CTUN, 337, 6.36, 5.86, 0.000000, 0, 0, -41, 577, 0 -NTUN, 0.87, 0.97, -10.699188, 84.961853, -10.699188, 84.961853, -26.083317, 68.087486, 97.330566, 126.061220, 6.59, -6.50 -ATT, 0.00, 1.50, 0.00, 0.82, 0.00, 6.97, 358.23 -CTUN, 336, 6.36, 5.78, 0.000000, 0, 0, -45, 588, 0 -NTUN, 0.85, 0.96, -8.858917, 83.240479, -8.858917, 83.240479, -27.531891, 67.593369, 103.402710, 125.786250, 6.49, -6.89 -ATT, 0.00, 1.85, 0.00, 0.31, 0.00, 7.37, 358.23 -GPS, 3, 308936200, 9, 1.75, 24.2397855, 54.5793357, 6.64, 16.30, 0.25, 100.40 -CTUN, 336, 5.96, 5.54, 0.000000, 0, 0, -41, 571, 0 -NTUN, 0.83, 0.94, -6.848846, 81.440948, -6.848846, 81.440948, -27.918331, 68.914413, 109.100710, 123.004700, 6.26, -7.21 -ATT, 0.00, 2.02, 0.00, 0.70, 0.00, 7.47, 358.23 -CTUN, 337, 5.96, 5.47, 0.000000, 0, 0, -43, 582, 0 -NTUN, 0.81, 0.93, -4.607361, 79.389923, -4.607361, 79.389923, -31.404415, 70.774139, 118.192920, 116.692820, 5.89, -7.64 -ATT, 0.00, 1.23, 0.00, 1.34, 0.00, 6.96, 358.23 -GPS, 3, 308936400, 9, 1.75, 24.2397851, 54.5793361, 6.43, 16.05, 0.35, 124.20 -CTUN, 337, 5.84, 5.50, 0.000000, 0, 0, -38, 563, 0 -NTUN, 0.79, 0.91, -1.914215, 77.416412, -1.914215, 77.416412, -34.727791, 68.077415, 129.931460, 118.264890, 6.08, -8.19 -ATT, 0.00, 0.41, 0.00, 0.65, 0.00, 5.76, 358.23 -DU32, 7, 393457 -CURR, 337, 142348, 1192, 0, 4772, 0.000000 -CTUN, 337, 5.84, 5.22, 0.000000, 0, 0, -36, 563, 0 -NTUN, 0.77, 0.89, 0.804749, 75.797760, 0.804749, 75.797760, -35.649529, 63.985107, 135.920430, 124.973740, 6.46, -8.55 -ATT, 0.00, 1.50, 0.00, -0.21, 0.00, 5.55, 358.23 -GPS, 3, 308936600, 10, 1.49, 24.2397845, 54.5793367, 6.24, 15.80, 0.44, 132.28 -CTUN, 336, 5.62, 5.08, 0.000000, 0, 0, -39, 567, 0 -NTUN, 0.75, 0.87, 3.775482, 74.042847, 3.775482, 74.042847, -35.072098, 66.663742, 143.007420, 119.273610, 6.11, -8.90 -ATT, 0.00, 2.53, 0.00, -1.10, 0.00, 5.49, 358.23 -CTUN, 336, 5.62, 5.14, 0.000000, 0, 0, -49, 589, 0 -NTUN, 0.74, 0.84, 6.872345, 71.898071, 6.872345, 71.898071, -34.268810, 69.199142, 148.662000, 110.764600, 5.70, -9.11 -ATT, 0.00, 1.90, 0.00, -2.62, 0.00, 4.67, 358.23 -GPS, 3, 308936800, 9, 1.75, 24.2397839, 54.5793372, 6.01, 15.54, 0.46, 138.96 -CTUN, 336, 5.43, 4.99, 0.000000, 0, 0, -61, 596, 0 -NTUN, 0.72, 0.82, 9.712585, 69.573730, 9.712585, 69.573730, -29.920835, 68.384697, 146.121190, 107.986720, 5.57, -8.93 -ATT, 0.00, 0.84, 0.00, -4.12, 0.00, 4.52, 358.23 -CTUN, 337, 5.43, 4.90, 0.000000, 0, 0, -65, 591, 0 -NTUN, 0.70, 0.80, 11.938751, 67.355743, 11.938751, 67.355743, -22.952904, 66.251701, 137.261660, 109.820130, 5.78, -8.39 -ATT, 0.00, -0.59, 0.00, -4.76, 0.00, 4.12, 358.23 -GPS, 3, 308937000, 9, 1.75, 24.2397832, 54.5793379, 5.76, 15.27, 0.58, 140.12 -CTUN, 337, 5.16, 4.64, 0.000000, 0, 0, -63, 576, 0 -NTUN, 0.68, 0.78, 13.581512, 65.320587, 13.581512, 65.320587, -16.018938, 60.011101, 127.593550, 115.442860, 6.17, -7.84 -ATT, 0.00, -1.38, 0.00, -4.49, 0.00, 3.85, 358.23 -CTUN, 336, 5.16, 4.54, 0.000000, 0, 0, -57, 582, 0 -NTUN, 0.66, 0.77, 14.652527, 63.741150, 14.652527, 63.741150, -8.425225, 54.713730, 116.604100, 124.362010, 6.74, -7.23 -ATT, 0.00, -0.91, 0.00, -4.76, 0.00, 3.73, 358.23 -GPS, 3, 308937200, 9, 1.96, 24.2397827, 54.5793384, 5.51, 15.02, 0.40, 136.27 -CTUN, 336, 4.91, 4.38, 0.000000, 0, 0, -54, 571, 0 -NTUN, 0.65, 0.76, 15.140289, 62.522156, 15.140289, 62.522156, -0.145216, 52.151695, 103.877620, 129.810060, 7.19, -6.42 -ATT, 0.00, -0.10, 0.00, -5.09, 0.00, 2.92, 358.23 -CTUN, 337, 4.91, 4.26, 0.000000, 0, 0, -44, 562, 0 -NTUN, 0.64, 0.76, 14.660767, 61.578979, 14.660767, 61.578979, 7.529474, 50.221642, 86.298798, 133.753170, 7.52, -5.35 -ATT, 0.00, 0.47, 0.00, -4.43, 0.00, 2.37, 358.23 -GPS, 3, 308937400, 9, 1.75, 24.2397825, 54.5793389, 5.29, 14.72, 0.30, 130.30 -CTUN, 336, 4.49, 4.16, 0.000000, 0, 0, -40, 559, 0 -NTUN, 0.63, 0.77, 13.482819, 60.569397, 13.482819, 60.569397, 14.008894, 48.894077, 72.101532, 133.802200, 7.57, -4.53 -ATT, 0.00, 0.19, 0.00, -3.69, 0.00, 2.50, 358.23 -DU32, 7, 393457 -CURR, 337, 148075, 1201, 0, 4752, 0.000000 -CTUN, 336, 4.49, 4.06, 0.000000, 0, 0, -35, 557, 0 -NTUN, 0.62, 0.78, 11.819977, 59.742462, 11.819977, 59.742462, 20.045444, 45.371513, 59.371582, 139.730650, 7.89, -3.89 -ATT, 0.00, 0.70, 0.00, -3.96, 0.00, 3.14, 358.23 -GPS, 3, 308937600, 10, 1.49, 24.2397823, 54.5793394, 5.08, 14.50, 0.24, 122.35 -CTUN, 336, 4.39, 3.89, 0.000000, 0, 0, -37, 571, 0 -NTUN, 0.60, 0.80, 9.844604, 58.777740, 9.844604, 58.777740, 26.232363, 46.758007, 47.441856, 136.448300, 7.66, -3.39 -ATT, 0.00, 1.63, 0.00, -3.60, 0.00, 4.66, 358.23 -CTUN, 336, 4.39, 3.72, 0.000000, 0, 0, -39, 570, 0 -NTUN, 0.59, 0.82, 7.531525, 57.593140, 7.531525, 57.593140, 29.516319, 48.554981, 37.869202, 132.153990, 7.41, -2.95 -ATT, 0.00, 0.66, 0.00, -3.07, 0.00, 5.74, 358.23 -GPS, 3, 308937800, 10, 1.49, 24.2397826, 54.5793395, 4.85, 14.28, 0.15, 122.35 -CTUN, 337, 4.16, 3.65, 0.000000, 0, 0, -43, 574, 0 -NTUN, 0.58, 0.84, 4.802307, 56.572906, 4.802307, 56.572906, 33.333317, 44.252026, 25.707825, 136.797670, 7.69, -2.43 -ATT, 0.00, -0.16, 0.00, -3.69, 0.00, 6.82, 358.23 -CTUN, 336, 4.16, 3.53, 0.000000, 0, 0, -42, 565, 0 -NTUN, 0.56, 0.88, 1.516693, 55.984070, 1.516693, 55.984070, 40.628223, 42.229950, 7.469170, 143.169940, 8.16, -1.54 -ATT, 0.00, 0.11, 0.00, -3.16, 0.00, 7.76, 358.23 -GPS, 3, 308938000, 10, 1.49, 24.2397830, 54.5793400, 4.63, 14.05, 0.29, 77.94 -CTUN, 336, 3.94, 3.40, 0.000000, 0, 0, -43, 572, 0 -NTUN, 0.56, 0.91, -2.077026, 55.243713, -2.077026, 55.243713, 43.141460, 41.185658, -4.937195, 143.596440, 8.28, -0.89 -ATT, 0.00, 0.22, 0.00, -1.82, 0.00, 8.27, 358.27 -CTUN, 336, 3.94, 3.29, 0.000000, 0, 0, -38, 558, 0 -NTUN, 0.55, 0.95, -5.860077, 54.556335, -5.860077, 54.556335, 44.269722, 39.948460, -13.830505, 144.126220, 8.38, -0.47 -ATT, 0.00, 0.50, 0.00, -1.12, 0.00, 8.55, 358.68 -GPS, 3, 308938200, 10, 1.49, 24.2397834, 54.5793401, 4.40, 13.81, 0.27, 46.29 -CTUN, 337, 3.72, 3.08, 0.000000, 0, 0, -32, 553, 0 -NTUN, 0.55, 0.95, -9.548706, 54.129852, -9.548706, 54.129852, 44.182812, 37.278896, -18.521080, 149.777390, 8.74, -0.23 -ATT, 0.00, 1.32, 0.00, -0.51, 0.00, 8.74, 358.74 -CTUN, 337, 3.72, 3.14, 0.000000, 0, 0, -26, 546, 0 -NTUN, 0.54, 1.00, -13.086761, 53.888397, -13.086761, 53.888397, 43.559422, 36.528595, -23.030251, 153.609360, 9.00, 0.00 -GPS, 3, 308938400, 10, 1.49, 24.2397841, 54.5793403, 4.20, 13.56, 0.32, 27.98 -ATT, 0.00, 2.32, 0.00, 0.00, 0.00, 8.28, 358.74 -CTUN, 337, 3.50, 2.92, 0.000000, 0, 0, -28, 561, 0 -PM, 0, 0, 50, 37, 1000, 12000, 6, 0 -NTUN, 0.55, 1.04, -16.510620, 53.507690, -16.510620, 53.507690, 41.685608, 37.841629, -26.584431, 151.154480, 8.89, 0.25 -DU32, 7, 393457 -CURR, 336, 153699, 1204, 0, 4772, 0.000000 -ATT, 0.00, 3.16, 0.00, 0.61, 0.00, 8.13, 358.74 -CTUN, 336, 3.50, 2.83, 0.000000, 0, 0, -29, 556, 0 -NTUN, 0.55, 1.07, -19.629059, 52.912964, -19.629059, 52.912964, 38.479633, 40.651348, -25.875629, 146.111620, 8.59, 0.37 -GPS, 3, 308938600, 10, 1.49, 24.2397847, 54.5793405, 3.99, 13.35, 0.37, 21.69 -ATT, 0.00, 4.10, 0.00, 1.73, 0.00, 7.47, 358.74 -CTUN, 336, 3.30, 2.81, 0.000000, 0, 0, -36, 579, 0 -NTUN, 0.56, 1.10, -22.380035, 51.914703, -22.380035, 51.914703, 30.972786, 43.579845, -20.509766, 139.017400, 8.14, 0.15 -ATT, 0.00, 3.77, 0.00, 2.23, 0.00, 6.74, 358.74 -CTUN, 337, 3.30, 2.73, 0.000000, 0, 0, -47, 584, 0 -NTUN, 0.56, 1.13, -24.445404, 50.547791, -24.445404, 50.547791, 27.158907, 46.469486, -14.653687, 131.330870, 7.66, -0.02 -GPS, 3, 308938800, 10, 1.49, 24.2397852, 54.5793408, 3.76, 13.14, 0.33, 23.60 -ATT, 0.00, 2.66, 0.00, 2.04, 0.00, 6.61, 358.74 -CTUN, 336, 3.09, 2.62, 0.000000, 0, 0, -58, 594, 0 -NTUN, 0.56, 1.16, -26.009369, 48.984833, -26.009369, 48.984833, 21.122009, 45.795444, -7.484800, 128.525180, 7.46, -0.37 -ATT, 0.00, 1.76, 0.00, 2.36, 0.00, 5.84, 358.74 -CTUN, 337, 3.09, 2.58, 0.000000, 0, 0, -57, 592, 0 -NTUN, 0.55, 1.18, -26.998901, 47.322968, -26.998901, 47.322968, 16.864998, 46.322334, 0.104675, 125.381350, 7.24, -0.74 -GPS, 3, 308939000, 10, 1.49, 24.2397855, 54.5793412, 3.55, 12.86, 0.24, 35.61 -ATT, 0.00, 0.62, 0.00, 2.25, 0.00, 5.41, 358.74 -CTUN, 337, 2.88, 2.29, 0.000000, 0, 0, -53, 582, 0 -NTUN, 0.54, 1.20, -27.370239, 45.829224, -27.370239, 45.829224, 8.371254, 43.411045, 12.286621, 128.062560, 7.35, -1.34 -ATT, 0.00, 0.57, 0.00, 1.64, 0.00, 4.62, 358.74 -CTUN, 336, 2.88, 2.20, 0.000000, 0, 0, -50, 583, 0 -NTUN, 0.53, 1.20, -27.268860, 44.615692, -27.268860, 44.615692, 5.727310, 39.461590, 18.003756, 133.984830, 7.67, -1.63 -GPS, 3, 308939200, 10, 1.49, 24.2397857, 54.5793417, 3.27, 12.60, 0.23, 53.35 -ATT, 0.00, 1.51, 0.00, 1.08, 0.00, 3.79, 358.74 -CTUN, 337, 2.61, 2.03, 0.000000, 0, 0, -52, 588, 0 -NTUN, 0.52, 1.21, -26.954163, 43.449860, -26.954163, 43.449860, 3.767017, 38.894253, 21.178761, 134.223910, 7.69, -1.76 -ATT, 0.00, 1.35, 0.00, 1.43, 0.00, 3.73, 358.74 -CTUN, 337, 2.61, 1.92, 0.000000, 0, 0, -51, 593, 0 -NTUN, 0.51, 1.21, -26.317749, 42.166718, -26.317749, 42.166718, 0.403590, 38.446316, 27.239349, 132.420180, 7.57, -2.06 -GPS, 3, 308939400, 10, 1.49, 24.2397854, 54.5793422, 3.03, 12.39, 0.29, 86.22 -ATT, 0.00, 0.65, 0.00, 1.70, 0.00, 3.71, 358.74 -CTUN, 337, 2.36, 1.71, 0.000000, 0, 0, -50, 588, 0 -NTUN, 0.49, 1.21, -25.004639, 40.821198, -25.004639, 40.821198, -6.464251, 37.426674, 41.131104, 131.544800, 7.46, -2.91 -ATT, 0.00, -0.01, 0.00, 1.73, 0.00, 3.64, 358.74 -CTUN, 336, 2.36, 1.71, 0.000000, 0, 0, -44, 583, 0 -DU32, 7, 393457 -CURR, 337, 159566, 1176, 0, 4793, 0.000000 -NTUN, 0.47, 1.21, -23.049469, 39.589783, -23.049469, 39.589783, -10.855576, 34.284595, 52.551697, 134.685850, 7.60, -3.58 -GPS, 3, 308939600, 10, 1.49, 24.2397853, 54.5793425, 2.81, 12.12, 0.17, 106.40 -ATT, 0.00, -0.26, 0.00, 1.49, 0.00, 4.39, 358.74 -CTUN, 336, 2.15, 1.67, 0.000000, 0, 0, -36, 580, 0 -NTUN, 0.45, 1.19, -20.798431, 38.708038, -20.798431, 38.708038, -15.830733, 30.484425, 63.510376, 142.182560, 7.95, -4.31 -ATT, 0.00, 0.07, 0.00, 1.44, 0.00, 4.39, 358.74 -CTUN, 336, 2.15, 1.42, 0.000000, 0, 0, -36, 579, 0 -NTUN, 0.43, 1.16, -18.234680, 38.116364, -18.234680, 38.116364, -17.011360, 27.436670, 69.637512, 147.083250, 8.17, -4.74 -GPS, 3, 308939800, 10, 1.49, 24.2397849, 54.5793428, 2.60, 11.87, 0.24, 135.45 -CTUN, 336, 1.96, 1.38, 0.000000, 0, 0, -27, 578, 0 -ATT, 0.00, 0.69, 0.00, 1.18, 0.00, 4.13, 358.74 -NTUN, 0.42, 1.13, -15.189453, 37.732452, -15.189453, 37.732452, -23.002716, 26.413218, 82.452271, 151.160890, 8.40, -5.41 -CTUN, 337, 1.96, 1.34, 0.000000, 0, 0, -29, 575, 0 -ATT, 0.00, 1.54, 0.00, 0.94, 0.00, 4.08, 358.74 -NTUN, 0.40, 1.09, -11.869965, 37.414276, -11.869965, 37.414276, -26.902416, 25.487455, 93.866226, 151.849750, 8.40, -6.06 -GPS, 3, 308940000, 10, 1.49, 24.2397844, 54.5793429, 2.39, 11.66, 0.26, 150.86 -CTUN, 336, 1.75, 1.34, 0.000000, 0, 0, -28, 587, 0 -ATT, 0.00, 2.07, 0.00, 0.64, 0.00, 2.93, 358.74 -NTUN, 0.39, 1.03, -8.160583, 37.080750, -8.160583, 37.080750, -28.213224, 26.787987, 104.093810, 151.664730, 8.47, -6.50 -CTUN, 336, 1.75, 1.11, 0.000000, 0, 0, -36, 589, 0 -ATT, 0.00, 2.60, 0.00, 0.19, 0.00, 2.81, 358.74 -NTUN, 0.37, 0.97, -4.270325, 36.648102, -4.270325, 36.648102, -30.492025, 27.198334, 112.902590, 149.673520, 8.36, -6.96 -GPS, 3, 308940200, 10, 1.49, 24.2397838, 54.5793432, 2.19, 11.47, 0.35, 157.05 -CTUN, 336, 1.56, 0.88, 0.000000, 0, 0, -34, 597, 0 -ATT, 0.00, 2.45, 0.00, -0.37, 0.00, 2.31, 358.74 -NTUN, 0.36, 0.91, -0.234924, 35.880585, -0.234924, 35.880585, -29.992992, 28.788401, 118.954450, 144.400820, 8.09, -7.24 -CTUN, 340, 1.56, 1.12, 0.000000, 0, 0, -44, 603, 0 -ATT, 0.00, 2.35, 0.00, -0.94, 0.00, 1.66, 358.74 -NTUN, 0.35, 0.85, 3.774384, 34.958954, 3.774384, 34.958954, -31.335699, 30.099003, 127.093080, 140.783690, 7.95, -7.60 -GPS, 3, 308940400, 10, 1.49, 24.2397831, 54.5793433, 1.99, 11.31, 0.37, 164.18 -MODE, STABILIZE, 500 -CTUN, 474, 1.39, 0.95, 0.000000, 0, 0, -47, 617, 0 -ATT, 0.00, 1.67, 0.00, -1.32, 0.00, 1.64, 358.74 -EV, 16 -CTUN, 723, 1.39, 0.68, 0.000000, 0, 0, -53, 635, 0 -ATT, 0.00, -1.29, 0.00, -1.58, 0.00, 0.97, 358.74 -DU32, 7, 426237 -CURR, 723, 165522, 1191, 0, 4732, 0.000000 -GPS, 3, 308940600, 10, 1.49, 24.2397822, 54.5793436, 1.75, 11.07, 0.52, 161.97 -CTUN, 723, 1.18, 0.23, 0.000000, 0, 0, -34, 723, 0 -ATT, 0.00, -2.32, 0.00, 0.44, 0.00, 359.68, 358.74 -CTUN, 737, 1.18, 0.15, 0.000000, 0, 0, 6, 737, 0 -ATT, 0.00, -3.86, 0.00, 2.83, 0.00, 355.08, 358.74 -GPS, 3, 308940800, 10, 1.49, 24.2397815, 54.5793438, 1.60, 10.84, 0.47, 165.42 -CTUN, 746, 0.95, 0.22, 0.000000, 0, 0, 43, 741, 0 -ATT, 0.00, -5.25, 0.00, 2.86, 0.00, 349.60, 358.74 -CTUN, 749, 0.95, 0.21, 0.000000, 0, 0, 75, 749, 0 -ATT, 0.00, -4.92, 0.00, 1.51, 0.00, 345.39, 355.39 -GPS, 3, 308941000, 10, 1.49, 24.2397804, 54.5793439, 1.56, 10.76, 0.50, 172.01 -CTUN, 757, 0.95, 0.03, 0.000000, 0, 0, 112, 757, 0 -ATT, 0.00, -3.71, 0.00, 1.07, 0.00, 342.21, 352.21 -CTUN, 763, 0.96, 0.53, 0.000000, 0, 0, 145, 763, 0 -ATT, 0.00, -2.96, 0.00, 1.49, 0.00, 339.35, 349.35 -GPS, 3, 308941200, 10, 1.49, 24.2397791, 54.5793433, 1.66, 10.82, 0.76, 191.07 -CTUN, 764, 0.96, 0.35, 0.000000, 0, 0, 174, 764, 0 -ATT, 0.00, -2.51, 0.00, 1.86, 0.00, 336.23, 346.23 -CTUN, 763, 1.07, 0.62, 0.000000, 0, 0, 193, 764, 0 -ATT, 0.00, -2.25, 0.00, 1.87, 0.00, 333.17, 343.17 -GPS, 3, 308941400, 10, 1.49, 24.2397773, 54.5793422, 1.88, 11.04, 1.11, 209.43 -CTUN, 765, 1.07, 0.97, 0.000000, 0, 0, 208, 765, 0 -ATT, 0.00, -2.32, 0.00, 1.56, 0.00, 330.33, 340.33 -CTUN, 702, 1.29, 1.17, 0.000000, 0, 0, 225, 738, 0 -ATT, 0.00, -2.49, 0.00, 0.71, 4.96, 327.66, 337.66 -DU32, 7, 426237 -CURR, 657, 173025, 1152, 0, 4712, 0.000000 -GPS, 3, 308941600, 10, 1.49, 24.2397750, 54.5793408, 2.19, 11.32, 1.42, 210.61 -CTUN, 653, 1.29, 1.66, 0.000000, 0, 0, 237, 653, 0 -ATT, 2.63, -2.14, 0.00, -0.19, 9.48, 326.16, 336.16 -CTUN, 627, 1.67, 1.89, 0.000000, 0, 0, 227, 627, 0 -ATT, 7.21, -0.66, 0.00, -0.13, 15.77, 329.54, 339.54 -GPS, 3, 308941800, 9, 1.75, 24.2397723, 54.5793390, 2.58, 11.63, 1.73, 211.58 -CTUN, 614, 1.67, 1.73, 0.000000, 0, 0, 205, 625, 0 -ATT, 9.50, 1.25, 0.00, 1.51, 18.63, 337.74, 346.96 -CTUN, 606, 2.03, 1.52, 0.000000, 0, 0, 191, 605, 0 -ATT, 10.19, 3.38, 0.00, 2.41, 20.51, 348.93, 355.94 -GPS, 3, 308942000, 10, 1.49, 24.2397692, 54.5793366, 2.84, 11.95, 2.09, 214.41 -CTUN, 606, 2.03, 1.55, 0.000000, 0, 0, 171, 605, 0 -ATT, 9.16, 5.69, 0.00, 2.67, 20.73, 0.59, 5.35 -CTUN, 601, 2.37, 1.53, 0.000000, 0, 0, 155, 605, 0 -ATT, 6.41, 6.52, 0.00, 2.90, 19.30, 11.27, 14.42 -GPS, 3, 308942200, 9, 1.75, 24.2397658, 54.5793338, 3.01, 12.21, 2.30, 215.00 -CTUN, 624, 2.37, 1.53, 0.000000, 0, 0, 130, 624, 0 -ATT, 3.32, 6.15, -5.07, 3.19, 16.32, 20.74, 22.21 -CTUN, 650, 2.62, 1.46, 0.000000, 0, 0, 118, 641, 0 -ATT, 2.40, 5.29, -8.19, 3.70, 15.11, 27.58, 29.11 -GPS, 3, 308942400, 10, 1.49, 24.2397620, 54.5793315, 3.07, 12.41, 2.39, 211.88 -CTUN, 661, 2.62, 1.59, 0.000000, 0, 0, 104, 675, 0 -ATT, 3.54, 4.54, -8.76, 1.94, 13.67, 31.65, 35.33 -CTUN, 665, 2.78, 1.80, 0.000000, 0, 0, 105, 665, 0 -ATT, 3.66, 4.68, -10.03, -0.08, 15.66, 33.31, 41.89 -DU32, 7, 426237 -CURR, 665, 179353, 1191, 0, 4772, 0.000000 -GPS, 3, 308942600, 10, 1.49, 24.2397583, 54.5793293, 3.10, 12.56, 2.37, 209.44 -CTUN, 663, 2.78, 1.91, 0.000000, 0, 0, 95, 663, 0 -ATT, 0.22, 4.64, -9.23, -1.39, 17.20, 36.36, 46.36 -CTUN, 654, 2.89, 1.90, 0.000000, 0, 0, 90, 657, 0 -ATT, 1.03, 3.86, -7.38, -1.82, 21.28, 42.91, 52.91 -GPS, 3, 308942800, 10, 1.49, 24.2397541, 54.5793275, 3.14, 12.72, 2.49, 205.10 -CTUN, 643, 2.89, 1.84, 0.000000, 0, 0, 83, 654, 0 -ATT, 0.00, 2.92, -5.88, -1.81, 27.02, 52.10, 62.10 -CTUN, 631, 3.00, 1.86, 0.000000, 0, 0, 80, 631, 0 -ATT, 0.00, 2.66, -4.15, -1.75, 28.67, 64.10, 74.02 -GPS, 3, 308943000, 10, 1.49, 24.2397499, 54.5793257, 3.15, 12.85, 2.49, 203.53 -CTUN, 631, 2.95, 1.87, 0.000000, 0, 0, 69, 631, 0 -ATT, 0.00, 2.63, -4.96, -1.75, 23.71, 78.12, 86.09 -CTUN, 660, 2.95, 2.01, 0.000000, 0, 0, 61, 647, 0 -ATT, -5.89, 2.46, -7.73, -1.04, 15.33, 91.60, 94.60 -GPS, 3, 308943200, 10, 1.49, 24.2397458, 54.5793241, 3.13, 12.98, 2.39, 201.07 -CTUN, 669, 2.92, 2.01, 0.000000, 0, 0, 51, 669, 0 -ATT, -11.91, 1.23, -0.80, -1.09, 9.70, 100.19, 100.27 -CTUN, 671, 2.92, 2.23, 0.000000, 0, 0, 47, 671, 0 -ATT, -13.18, -2.27, 0.00, -2.84, 6.83, 102.17, 103.82 -GPS, 3, 308943400, 10, 1.49, 24.2397417, 54.5793229, 3.10, 13.02, 2.43, 197.46 -CTUN, 671, 2.88, 2.13, 0.000000, 0, 0, 40, 671, 0 -ATT, -12.37, -5.13, 0.00, -2.32, 0.00, 100.50, 104.72 -CTUN, 704, 2.88, 1.85, 0.000000, 0, 0, 29, 680, 0 -ATT, -13.76, -7.41, 0.00, -1.11, 0.00, 96.80, 104.72 -GPS, 3, 308943600, 10, 1.49, 24.2397374, 54.5793218, 3.05, 13.05, 2.52, 194.86 -DU32, 7, 426237 -CURR, 788, 186664, 1179, 0, 4772, 0.000000 -CTUN, 795, 2.78, 1.37, 0.000000, 0, 1, 23, 789, 0 -ATT, -18.04, -7.97, 0.00, -0.12, 0.00, 92.28, 102.28 -CTUN, 818, 2.78, 1.34, 0.000000, 0, 2, 30, 815, 0 -ATT, -16.54, -11.01, 0.00, -0.87, 0.00, 87.00, 97.00 -GPS, 3, 308943800, 10, 1.49, 24.2397331, 54.5793210, 2.93, 13.02, 2.45, 191.63 -CTUN, 822, 2.78, 1.19, 0.000000, 0, 4, 51, 826, 0 -ATT, -2.31, -10.75, -9.92, -2.65, 0.00, 80.16, 90.16 -CTUN, 822, 2.79, 0.93, 0.000000, 0, 2, 79, 824, 0 -ATT, 0.00, -7.75, -12.57, -1.99, 0.00, 70.73, 80.73 -GPS, 3, 308944000, 10, 1.49, 24.2397295, 54.5793204, 2.85, 13.02, 2.06, 190.65 -CTUN, 806, 2.79, 1.17, 0.000000, 0, 1, 104, 823, 0 -ATT, 0.00, -3.75, -9.69, -5.27, 0.55, 61.01, 71.01 -CTUN, 791, 2.97, 1.15, 0.000000, 0, 1, 138, 793, 0 -ATT, 0.00, -0.50, -7.73, -7.92, 2.64, 52.74, 62.74 -GPS, 3, 308944200, 10, 1.49, 24.2397265, 54.5793199, 2.89, 13.17, 1.60, 190.52 -CTUN, 789, 2.97, 1.41, 0.000000, 0, 1, 152, 790, 0 -ATT, 0.00, -1.02, -7.26, -4.33, 4.08, 48.32, 58.32 -CTUN, 789, 3.13, 1.48, 0.000000, 0, 0, 165, 789, 0 -ATT, 0.00, -1.09, -5.65, -2.59, 2.31, 47.38, 57.38 -GPS, 3, 308944400, 10, 1.49, 24.2397241, 54.5793198, 3.02, 13.42, 1.20, 188.26 -CTUN, 789, 3.13, 1.78, 0.000000, 0, 0, 178, 789, 0 -ATT, -2.77, 0.34, -2.88, -3.51, 0.00, 46.00, 56.00 -CTUN, 789, 3.40, 1.83, 0.000000, 0, 0, 191, 789, 0 -ATT, -8.56, -0.03, -2.19, -3.05, 0.00, 43.49, 53.49 -GPS, 3, 308944600, 10, 1.49, 24.2397223, 54.5793195, 3.23, 13.70, 0.98, 188.84 -DU32, 7, 426237 -CURR, 752, 194666, 1178, 0, 4772, 0.000000 -CTUN, 752, 3.40, 2.44, 0.000000, 0, 0, 191, 757, 0 -ATT, -9.71, -4.57, -3.00, -2.88, 0.00, 42.24, 52.24 -CTUN, 750, 3.68, 2.55, 0.000000, 0, 0, 183, 750, 0 -ATT, -1.96, -6.47, -11.53, -2.66, 0.00, 43.02, 52.21 -GPS, 3, 308944800, 10, 1.49, 24.2397206, 54.5793194, 3.49, 14.03, 0.88, 186.60 -CTUN, 750, 3.68, 2.71, 0.000000, 0, 0, 175, 750, 0 -ATT, 0.00, -4.80, -14.88, -0.75, 0.00, 43.49, 52.21 -CTUN, 745, 4.01, 2.95, 0.000000, 0, 0, 175, 747, 0 -ATT, 0.00, -3.37, -17.30, -3.58, 0.00, 42.24, 52.21 -GPS, 3, 308945000, 10, 1.49, 24.2397191, 54.5793191, 3.74, 14.37, 0.80, 187.43 -CTUN, 740, 4.01, 3.32, 0.000000, 0, 0, 176, 743, 0 -ATT, 0.00, -0.69, -18.57, -8.64, 0.00, 40.53, 50.53 -CTUN, 735, 4.30, 3.31, 0.000000, 0, 1, 171, 736, 0 -ATT, 0.00, 0.62, -19.50, -10.24, 0.00, 40.17, 50.13 -GPS, 3, 308945200, 10, 1.49, 24.2397180, 54.5793187, 4.01, 14.68, 0.65, 191.75 -CTUN, 732, 4.30, 3.44, 0.000000, 0, 1, 163, 735, 0 -ATT, 0.00, -0.11, -14.76, -9.91, 0.00, 40.84, 50.09 -CTUN, 709, 4.61, 3.48, 0.000000, 0, 1, 158, 710, 0 -ATT, 0.00, -0.46, -12.69, -9.64, 0.00, 42.42, 50.09 -GPS, 3, 308945400, 10, 1.49, 24.2397172, 54.5793183, 4.27, 15.03, 0.43, 196.14 -CTUN, 705, 4.61, 3.66, 0.000000, 0, 1, 143, 706, 0 -ATT, 0.00, 0.27, -10.15, -9.44, 0.00, 44.31, 50.09 -CTUN, 703, 4.90, 3.75, 0.000000, 0, 1, 130, 704, 0 -ATT, 0.00, 0.66, -7.73, -9.10, 0.00, 44.59, 50.09 -GPS, 3, 308945600, 10, 1.49, 24.2397169, 54.5793180, 4.45, 15.30, 0.21, 199.72 -DU32, 7, 426237 -CURR, 701, 201958, 1163, 0, 4813, 0.000000 -CTUN, 701, 4.90, 3.81, 0.000000, 0, 0, 120, 701, 0 -ATT, 0.00, -0.49, -5.19, -7.94, 2.31, 43.45, 50.26 -CTUN, 701, 5.11, 3.82, 0.000000, 0, 0, 119, 701, 0 -ATT, -1.15, -1.64, -4.15, -6.09, 7.27, 43.75, 52.49 -GPS, 3, 308945800, 10, 1.49, 24.2397169, 54.5793181, 4.61, 15.49, 0.06, 199.72 -CTUN, 701, 5.11, 3.90, 0.000000, 0, 0, 120, 701, 0 -ATT, -3.12, -1.68, -4.73, -3.25, 9.48, 48.26, 56.41 -CTUN, 701, 5.29, 3.59, 0.000000, 0, 0, 127, 701, 0 -ATT, -3.35, -2.19, -9.23, -0.92, 9.92, 55.08, 60.79 -GPS, 3, 308946000, 10, 1.49, 24.2397172, 54.5793183, 4.76, 15.71, 0.24, 82.92 -CTUN, 701, 5.29, 3.39, 0.000000, 0, 0, 135, 701, 0 -ATT, 0.00, -2.91, -14.65, -0.47, 9.37, 60.34, 65.11 -CTUN, 701, 5.53, 3.43, 0.000000, 0, 0, 146, 701, 0 -ATT, 0.00, -1.73, -19.61, -2.39, 4.63, 63.06, 68.26 -GPS, 3, 308946200, 10, 1.49, 24.2397179, 54.5793185, 4.88, 15.94, 0.41, 31.94 -CTUN, 701, 5.53, 3.52, 0.000000, 0, 0, 162, 701, 0 -ATT, 0.00, 0.06, -19.96, -5.89, 0.00, 62.26, 68.85 -CTUN, 701, 5.53, 3.81, 0.000000, 0, 0, 170, 701, 0 -ATT, 0.00, 2.35, -13.73, -8.94, 0.00, 59.22, 68.85 -GPS, 3, 308946400, 10, 1.49, 24.2397187, 54.5793186, 5.04, 16.18, 0.45, 15.96 -CTUN, 701, 5.20, 4.01, 0.000000, 0, 1, 171, 702, 0 -ATT, 0.00, 1.77, -6.57, -8.07, 0.00, 58.01, 67.94 -CTUN, 701, 5.20, 3.97, 0.000000, 0, 0, 169, 701, 0 -ATT, 0.00, -0.23, 0.00, -5.44, 0.00, 58.22, 67.94 -GPS, 3, 308946600, 10, 1.49, 24.2397195, 54.5793193, 5.25, 16.51, 0.57, 22.90 -DU32, 7, 426237 -CURR, 701, 208969, 1167, 0, 4752, 0.000000 -CTUN, 701, 3.27, 4.09, 0.000000, 0, 0, 174, 701, 0 -ATT, 0.00, -0.13, 0.00, -1.90, 0.00, 59.18, 67.94 -CTUN, 701, 5.20, 3.97, 0.000000, 0, 0, 179, 701, 0 -ATT, 0.00, -0.35, 0.00, 1.30, 0.00, 58.94, 67.94 -GPS, 3, 308946800, 10, 1.49, 24.2397206, 54.5793202, 5.45, 16.80, 0.71, 32.04 -CTUN, 701, 5.20, 4.23, 0.000000, 0, 0, 182, 701, 0 -ATT, 0.00, 1.02, 9.52, 1.15, 0.00, 58.04, 67.94 -CTUN, 656, 5.94, 4.72, 0.000000, 0, 0, 173, 666, 0 -ATT, 0.00, 1.03, 8.72, 2.73, 0.00, 57.53, 67.53 -GPS, 3, 308947000, 10, 1.49, 24.2397216, 54.5793211, 5.65, 17.11, 0.75, 34.04 -CTUN, 649, 5.20, 4.65, 0.000000, 0, 0, 164, 654, 0 -ATT, 0.00, -0.63, 0.57, 7.53, 0.00, 58.69, 67.52 -CTUN, 600, 5.49, 4.82, 0.000000, 0, 0, 144, 623, 0 -ATT, 0.00, -1.18, 0.00, 8.65, 0.22, 60.16, 67.52 -GPS, 3, 308947200, 10, 1.49, 24.2397223, 54.5793221, 5.84, 17.47, 0.70, 41.66 -CTUN, 589, 5.49, 5.22, 0.000000, 0, 0, 131, 589, 0 -ATT, 0.00, 0.38, 0.00, 5.17, 0.44, 60.52, 67.55 -CTUN, 565, 6.22, 5.58, 0.000000, 0, 0, 107, 565, 0 -ATT, -5.78, 1.33, 0.00, 4.36, 0.22, 60.86, 67.55 -GPS, 3, 308947400, 10, 1.49, 24.2397228, 54.5793228, 6.00, 17.71, 0.40, 44.23 -CTUN, 565, 6.22, 5.59, 0.000000, 0, 0, 85, 565, 0 -ATT, -10.75, -2.12, -1.03, 6.38, 0.99, 63.00, 67.63 -CTUN, 565, 6.22, 5.60, 0.000000, 0, 0, 52, 565, 0 -ATT, -12.26, -4.80, -1.61, 6.62, 1.43, 66.94, 68.13 -GPS, 3, 308947600, 10, 1.49, 24.2397230, 54.5793233, 6.08, 17.92, 0.25, 55.24 -CTUN, 578, 6.22, 6.07, 0.000000, 0, 0, 32, 567, 0 -DU32, 7, 426237 -CURR, 578, 215183, 1166, 0, 4732, 0.000000 -ATT, -15.26, -5.47, 0.00, 5.89, 3.30, 69.46, 69.25 -CTUN, 624, 6.35, 6.26, 0.000000, 0, 0, 14, 611, 0 -ATT, -17.35, -8.18, 0.00, 5.58, 2.64, 69.95, 70.59 -GPS, 3, 308947800, 10, 1.49, 24.2397233, 54.5793230, 6.11, 18.00, 0.13, 55.24 -CTUN, 641, 6.35, 5.64, 0.000000, 0, 0, 8, 641, 0 -ATT, -15.50, -10.88, -2.53, 6.10, 2.97, 70.15, 71.75 -CTUN, 641, 6.38, 5.25, 0.000000, 0, 0, 0, 641, 0 -ATT, -9.94, -12.58, -8.76, 7.05, 3.41, 69.66, 73.09 -GPS, 3, 308948000, 10, 1.49, 24.2397234, 54.5793225, 6.07, 18.01, 0.23, 337.25 -CTUN, 641, 6.37, 5.66, 0.000000, 0, 0, -4, 641, 0 -ATT, -5.43, -11.76, -13.03, 5.49, 2.42, 68.81, 74.45 -CTUN, 606, 6.38, 6.50, 0.000000, 0, 0, 12, 613, 0 -ATT, 0.00, -8.89, -20.07, 0.77, 2.86, 66.29, 75.54 -GPS, 3, 308948200, 10, 1.49, 24.2397239, 54.5793215, 6.04, 18.00, 0.54, 299.77 -CTUN, 603, 6.38, 6.39, 0.000000, 0, 0, 33, 603, 0 -ATT, 0.00, -4.84, -21.46, -2.69, 3.97, 64.50, 74.50 -CTUN, 603, 6.38, 6.36, 0.000000, 0, 0, 47, 603, 0 -ATT, 0.00, -3.16, -21.80, -5.04, 6.28, 65.85, 75.78 -GPS, 3, 308948400, 10, 1.49, 24.2397249, 54.5793199, 6.17, 18.01, 0.96, 301.57 -CTUN, 605, 6.38, 6.32, 0.000000, 0, 0, 55, 605, 0 -PM, 0, 0, 50, 8, 1000, 11104, 11, 0 -ATT, 0.00, -2.21, -19.38, -6.79, 6.50, 69.40, 78.71 -CTUN, 602, 6.38, 6.49, 0.000000, 0, 0, 69, 602, 0 -ATT, 0.00, -1.53, -12.46, -8.17, 4.30, 73.78, 80.99 -GPS, 3, 308948600, 10, 1.49, 24.2397263, 54.5793181, 6.32, 18.11, 1.26, 307.37 -CTUN, 583, 6.38, 6.37, 0.000000, 0, 0, 85, 593, 0 -DU32, 7, 426237 -CURR, 571, 221341, 1176, 0, 4772, 0.000000 -ATT, 0.00, -0.61, -1.15, -6.84, 3.63, 77.36, 82.73 -CTUN, 539, 6.38, 6.49, 0.000000, 0, 0, 95, 539, 0 -ATT, 0.00, -0.82, 0.00, -2.38, 3.86, 81.06, 84.46 -GPS, 3, 308948800, 10, 1.49, 24.2397283, 54.5793165, 6.51, 18.23, 1.39, 318.36 -CTUN, 436, 6.33, 6.64, 0.000000, 0, 0, 92, 511, 0 -ATT, 0.00, -1.30, 0.00, 2.26, 3.63, 85.93, 86.12 -CTUN, 429, 6.33, 7.03, 0.000000, 0, 0, 89, 428, 0 -ATT, -1.15, -1.19, 0.00, 4.02, 4.19, 90.68, 87.72 -GPS, 3, 308949000, 10, 1.49, 24.2397303, 54.5793155, 6.70, 18.37, 1.22, 323.49 -CTUN, 417, 6.33, 7.10, 0.000000, 0, 0, 76, 417, 0 -ATT, -9.37, 0.31, 0.00, 4.86, 4.74, 93.89, 89.69 -CTUN, 409, 6.38, 7.26, 0.000000, 0, 0, 61, 412, 0 -ATT, -13.30, -1.45, 0.00, 5.57, 4.41, 96.75, 91.70 -GPS, 3, 308949200, 10, 1.49, 24.2397325, 54.5793145, 6.88, 18.51, 1.30, 331.60 -CTUN, 399, 6.38, 7.43, 0.000000, 0, 0, 30, 400, 0 -ATT, -16.42, -3.26, 0.00, 4.86, 4.19, 99.89, 93.59 -CTUN, 380, 6.38, 7.49, 0.000000, 0, 0, 10, 382, 0 -ATT, -17.46, -4.90, -1.15, 3.99, 3.97, 102.54, 95.38 -GPS, 3, 308949400, 9, 1.96, 24.2397344, 54.5793134, 6.97, 18.62, 1.22, 332.09 -CTUN, 376, 6.37, 7.61, 0.000000, 0, 0, -23, 378, 0 -ATT, -17.58, -7.26, -3.34, 3.17, 2.75, 104.90, 96.87 -CTUN, 378, 6.37, 7.40, 0.000000, 0, 0, -51, 378, 0 -ATT, -18.74, -9.68, -3.80, 1.52, 1.54, 105.90, 97.64 -GPS, 3, 308949600, 10, 1.49, 24.2397364, 54.5793120, 6.95, 18.61, 1.28, 331.25 -CTUN, 387, 5.35, 7.03, 0.000000, 0, 0, -84, 384, 0 -DU32, 7, 426237 -CURR, 387, 225610, 1187, 0, 4793, 0.000000 -ATT, -19.78, -10.85, -6.34, 0.93, 1.43, 105.06, 98.22 -CTUN, 390, 6.22, 6.88, 0.000000, 0, 0, -106, 390, 0 -ATT, -20.24, -12.72, -6.57, 1.35, 1.21, 102.78, 98.72 -GPS, 3, 308949800, 9, 1.96, 24.2397387, 54.5793106, 6.79, 18.48, 1.36, 331.24 -CTUN, 456, 6.22, 6.55, 0.000000, 0, 0, -131, 456, 0 -ATT, -20.70, -14.28, -6.80, 0.96, 3.86, 100.93, 99.60 -CTUN, 527, 6.36, 6.40, 0.000000, 0, 0, -142, 527, 0 -ATT, -17.00, -14.49, -8.53, 0.02, 6.17, 100.34, 101.90 -GPS, 3, 308950000, 10, 1.49, 24.2397411, 54.5793093, 6.49, 18.26, 1.48, 332.48 -CTUN, 563, 6.36, 5.94, 0.000000, 0, 0, -140, 563, 0 -ATT, -4.62, -12.77, -13.73, 0.40, 8.16, 100.20, 105.20 -CTUN, 570, 6.36, 5.71, 0.000000, 0, 0, -111, 570, 0 -ATT, 0.00, -9.68, -15.46, 1.26, 9.04, 101.05, 109.21 -GPS, 3, 308950200, 10, 1.49, 24.2397443, 54.5793082, 6.20, 17.91, 1.80, 337.72 -CTUN, 570, 6.36, 5.44, 0.000000, 0, 0, -67, 570, 0 -ATT, 0.00, -6.54, -15.46, 0.17, 7.94, 103.34, 112.81 -CTUN, 570, 6.40, 5.23, 0.000000, 0, 0, -13, 570, 0 -ATT, 0.00, -2.51, -14.53, -2.23, 3.75, 105.60, 115.41 -GPS, 3, 308950400, 10, 1.49, 24.2397483, 54.5793073, 6.05, 17.65, 2.28, 342.85 -CTUN, 509, 6.40, 5.39, 0.000000, 0, 0, 35, 536, 0 -ATT, 0.00, 0.73, -15.00, -3.07, 1.98, 107.93, 116.62 -CTUN, 451, 6.40, 5.49, 0.000000, 0, 0, 62, 458, 0 -ATT, 0.00, 1.47, -14.65, -3.53, 0.77, 110.08, 117.28 -GPS, 3, 308950600, 10, 1.49, 24.2397529, 54.5793066, 6.07, 17.57, 2.67, 347.06 -CTUN, 399, 6.38, 5.42, 0.000000, 0, 0, 65, 409, 0 -DU32, 7, 426237 -CURR, 376, 230636, 1175, 0, 4732, 0.000000 -ATT, 0.00, 1.79, -10.61, -5.48, 0.00, 111.55, 117.31 -CTUN, 356, 6.38, 5.52, 0.000000, 0, 0, 63, 356, 0 -ATT, 0.00, 2.20, -8.19, -6.63, 0.00, 112.53, 117.31 -GPS, 3, 308950800, 9, 1.96, 24.2397573, 54.5793061, 6.12, 17.71, 2.56, 350.74 -CTUN, 350, 6.38, 5.53, 0.000000, 0, 0, 47, 355, 0 -ATT, 0.00, 2.02, -7.84, -6.39, 0.00, 114.39, 117.31 -CTUN, 348, 6.38, 5.55, 0.000000, 0, 0, 27, 348, 0 -GPS, 3, 308951000, 9, 1.96, 24.2397614, 54.5793061, 6.12, 17.81, 2.32, 355.08 -ATT, 0.00, 1.43, -6.34, -5.93, 0.00, 115.70, 117.31 -CTUN, 346, 6.38, 5.86, 0.000000, 0, 0, 6, 346, 0 -ATT, -3.23, 0.98, -1.61, -5.31, 0.00, 116.69, 117.31 -CTUN, 346, 6.38, 5.93, 0.000000, 0, 0, -13, 346, 0 -GPS, 3, 308951200, 10, 1.49, 24.2397650, 54.5793062, 6.07, 17.83, 1.96, 357.55 -ATT, -8.21, 0.23, 0.00, -3.84, 0.00, 117.09, 117.31 -CTUN, 343, 6.38, 5.85, 0.000000, 0, 0, -42, 343, 0 -ATT, -14.46, -0.69, 0.00, -1.76, 0.00, 117.57, 117.31 -CTUN, 435, 6.38, 5.63, 0.000000, 0, 0, -84, 426, 0 -GPS, 3, 308951400, 10, 1.49, 24.2397680, 54.5793065, 5.92, 17.76, 1.69, 1.23 -ATT, -16.19, -4.42, 0.00, -1.05, 0.00, 118.46, 117.31 -CTUN, 452, 6.38, 5.62, 0.000000, 0, 0, -113, 450, 0 -ATT, -15.73, -6.42, 0.00, -2.56, 0.00, 117.88, 117.31 -CTUN, 464, 6.38, 5.35, 0.000000, 0, 0, -127, 464, 0 -ATT, -12.26, -5.91, 0.00, -1.31, 0.00, 116.56, 117.31 -GPS, 3, 308951600, 10, 1.49, 24.2397708, 54.5793070, 5.63, 17.58, 1.49, 5.88 -CTUN, 480, 6.38, 5.29, 0.000000, 0, 0, -144, 465, 0 -DU32, 7, 426237 -CURR, 506, 234520, 1173, 0, 4793, 0.000000 -ATT, -9.60, -7.19, 0.00, 1.99, 0.00, 114.91, 117.31 -CTUN, 535, 6.38, 5.00, 0.000000, 0, 0, -160, 530, 0 -ATT, -5.20, -5.87, 0.00, 3.24, 0.00, 113.56, 117.31 -GPS, 3, 308951800, 10, 1.49, 24.2397735, 54.5793076, 5.29, 17.25, 1.44, 9.21 -CTUN, 547, 6.38, 4.98, 0.000000, 0, 0, -140, 547, 0 -ATT, 0.00, -3.75, 0.00, 4.21, 0.00, 111.82, 117.31 -CTUN, 553, 6.38, 4.81, 0.000000, 0, 0, -108, 553, 0 -ATT, 0.00, -0.65, 0.00, 6.23, 0.66, 110.32, 117.35 -GPS, 3, 308952000, 10, 1.49, 24.2397766, 54.5793084, 5.02, 16.88, 1.67, 11.07 -CTUN, 553, 6.27, 4.78, 0.000000, 0, 0, -75, 553, 0 -ATT, 0.00, 1.26, -8.42, 8.62, 2.86, 109.89, 118.12 -CTUN, 552, 6.27, 4.66, 0.000000, 0, 0, -39, 564, 0 -ATT, 0.00, 1.53, -12.11, 6.89, 4.63, 111.51, 119.73 -GPS, 3, 308952200, 10, 1.49, 24.2397797, 54.5793090, 4.89, 16.61, 1.75, 9.72 -CTUN, 495, 5.75, 4.76, 0.000000, 0, 0, -2, 531, 0 -ATT, 0.00, 1.79, -16.26, 1.89, 3.75, 113.17, 121.45 -CTUN, 463, 5.91, 4.75, 0.000000, 0, 0, 33, 478, 0 -GPS, 3, 308952400, 10, 1.49, 24.2397828, 54.5793093, 4.90, 16.54, 1.88, 4.04 -ATT, 0.00, 2.95, -16.73, -1.45, 3.19, 115.71, 122.96 -CTUN, 427, 5.90, 4.63, 0.000000, 0, 0, 50, 438, 0 -ATT, 0.00, 3.21, -15.34, -3.07, 1.54, 120.03, 123.90 -CTUN, 411, 5.90, 4.68, 0.000000, 0, 0, 62, 414, 0 -GPS, 3, 308952600, 10, 1.49, 24.2397858, 54.5793091, 4.99, 16.58, 1.79, 1.21 -ATT, 0.00, 2.73, -12.57, -4.54, 1.10, 124.27, 124.36 -CTUN, 388, 5.90, 4.87, 0.000000, 0, 0, 68, 388, 0 -DU32, 7, 426237 -CURR, 388, 239511, 1194, 0, 4772, 0.000000 -ATT, 0.00, 2.25, -8.07, -6.26, 0.00, 126.85, 124.52 -CTUN, 378, 5.94, 4.63, 0.000000, 0, 0, 66, 378, 0 -GPS, 3, 308952800, 9, 1.96, 24.2397885, 54.5793090, 5.09, 16.67, 1.59, 0.05 -ATT, 0.00, 1.85, -6.11, -6.54, 0.00, 127.71, 124.52 -CTUN, 375, 5.94, 4.91, 0.000000, 0, 0, 40, 376, 0 -ATT, 0.00, 1.82, -3.23, -5.65, 0.00, 127.79, 124.52 -CTUN, 369, 5.94, 4.81, 0.000000, 0, 0, 10, 369, 0 -GPS, 3, 308953000, 10, 1.49, 24.2397904, 54.5793091, 5.11, 16.77, 1.11, 1.03 -ATT, 0.00, 2.62, -0.80, -4.05, 0.00, 128.23, 124.52 -CTUN, 369, 4.30, 5.05, 0.000000, 0, 0, -13, 369, 0 -ATT, 0.00, 3.59, 0.00, -1.94, 0.00, 128.54, 124.52 -CTUN, 369, 4.30, 5.06, 0.000000, 0, 0, -37, 369, 0 -ATT, 0.00, 3.78, 0.00, -0.02, 0.00, 129.78, 124.52 -GPS, 3, 308953200, 10, 1.49, 24.2397920, 54.5793093, 5.03, 16.74, 0.86, 3.03 -CTUN, 428, 4.30, 5.04, 0.000000, 0, 0, -58, 385, 0 -ATT, 0.00, 3.73, 2.52, 0.73, 0.00, 130.70, 124.52 -CTUN, 447, 5.53, 4.91, 0.000000, 0, 0, -75, 441, 0 -ATT, -1.27, 4.20, 2.18, 1.46, 0.00, 131.40, 124.52 -GPS, 3, 308953400, 10, 1.49, 24.2397933, 54.5793095, 4.89, 16.59, 0.66, 4.09 -CTUN, 464, 5.53, 4.78, 0.000000, 0, 0, -74, 460, 0 -ATT, -6.94, 5.17, 0.00, 3.17, 0.00, 131.19, 124.52 -CTUN, 506, 5.68, 4.78, 0.000000, 0, 0, -79, 490, 0 -GPS, 3, 308953600, 10, 1.49, 24.2397943, 54.5793098, 4.74, 16.36, 0.49, 5.69 -ATT, -9.71, 3.23, 0.00, 4.14, 0.00, 130.40, 124.52 -CTUN, 523, 5.58, 4.68, 0.000000, 0, 0, -76, 523, 0 -DU32, 7, 426237 -CURR, 523, 243668, 1180, 0, 4752, 0.000000 -ATT, -12.03, 0.69, 0.00, 2.49, 0.00, 129.27, 124.52 -CTUN, 517, 5.58, 4.59, 0.000000, 0, 0, -70, 522, 0 -ATT, -14.46, 0.14, 0.00, 1.72, 0.00, 126.95, 124.52 -GPS, 3, 308953800, 10, 1.49, 24.2397951, 54.5793096, 4.59, 16.19, 0.43, 358.60 -CTUN, 515, 5.39, 4.34, 0.000000, 0, 0, -62, 518, 0 -ATT, -14.57, -2.38, -1.61, 2.83, 0.00, 125.42, 124.52 -CTUN, 496, 5.39, 4.29, 0.000000, 0, 0, -73, 512, 0 -ATT, -11.79, -5.10, -2.76, 2.53, 0.00, 124.96, 124.52 -GPS, 3, 308954000, 10, 1.49, 24.2397956, 54.5793093, 4.43, 16.00, 0.36, 347.89 -CTUN, 492, 5.29, 4.27, 0.000000, 0, 0, -69, 492, 0 -ATT, -7.98, -5.56, -1.84, 2.06, 0.00, 124.33, 124.52 -CTUN, 490, 5.29, 4.05, 0.000000, 0, 0, -68, 490, 0 -ATT, -3.47, -3.79, 0.00, 2.58, 0.00, 124.17, 124.52 -GPS, 3, 308954200, 10, 1.49, 24.2397963, 54.5793089, 4.26, 15.84, 0.46, 336.26 -CTUN, 490, 5.13, 4.04, 0.000000, 0, 0, -62, 487, 0 -ATT, 0.00, -1.80, 0.00, 4.75, 0.55, 124.17, 124.57 -CTUN, 493, 5.13, 3.92, 0.000000, 0, 0, -58, 492, 0 -GPS, 3, 308954400, 10, 1.49, 24.2397973, 54.5793087, 4.14, 15.66, 0.54, 344.04 -ATT, 0.00, 0.29, 0.00, 5.86, 0.22, 124.38, 124.63 -CTUN, 492, 4.91, 4.01, 0.000000, 0, 0, -51, 492, 0 -ATT, 0.00, 2.38, 2.64, 5.62, 0.22, 124.95, 124.64 -CTUN, 483, 4.91, 3.91, 0.000000, 0, 0, -40, 483, 0 -GPS, 3, 308954600, 10, 1.49, 24.2397985, 54.5793085, 4.02, 15.50, 0.70, 347.84 -ATT, 0.00, 4.32, 0.00, 5.96, 0.00, 124.79, 124.64 -CTUN, 478, 4.74, 3.62, 0.000000, 0, 0, -30, 478, 0 -DU32, 7, 426237 -CURR, 471, 248632, 1160, 0, 4752, 0.000000 -ATT, -1.38, 4.40, 0.00, 6.77, 0.00, 124.79, 124.64 -CTUN, 471, 4.74, 3.66, 0.000000, 0, 0, -17, 471, 0 -GPS, 3, 308954800, 10, 1.49, 24.2397996, 54.5793079, 3.94, 15.37, 0.73, 339.87 -ATT, -7.98, 3.52, 0.00, 5.76, 0.00, 125.75, 124.64 -CTUN, 471, 4.64, 3.94, 0.000000, 0, 0, -22, 471, 0 -ATT, -9.02, 0.37, 0.00, 2.83, 0.00, 126.03, 124.64 -CTUN, 458, 4.64, 3.96, 0.000000, 0, 0, -34, 466, 0 -GPS, 3, 308955000, 10, 1.49, 24.2398006, 54.5793070, 3.87, 15.27, 0.78, 328.05 -ATT, -10.64, -0.67, 0.00, 0.22, 0.00, 126.35, 124.64 -CTUN, 448, 4.57, 3.65, 0.000000, 0, 0, -41, 450, 0 -ATT, -8.56, -1.31, 0.00, 0.96, 0.00, 126.79, 124.64 -CTUN, 447, 4.57, 3.65, 0.000000, 0, 0, -56, 447, 0 -GPS, 3, 308955200, 10, 1.49, 24.2398016, 54.5793058, 3.77, 15.18, 0.84, 320.08 -ATT, -8.32, -2.34, 0.00, 2.89, 0.00, 127.61, 124.64 -CTUN, 477, 4.44, 3.53, 0.000000, 0, 0, -73, 477, 0 -ATT, -9.83, -2.80, 0.00, 3.66, 0.00, 129.31, 124.64 -CTUN, 489, 4.44, 3.54, 0.000000, 0, 0, -85, 489, 0 -GPS, 3, 308955400, 10, 1.49, 24.2398027, 54.5793045, 3.58, 15.00, 0.88, 315.92 -ATT, -9.71, -2.55, 0.00, 2.93, 0.00, 130.08, 124.64 -CTUN, 492, 4.25, 3.27, 0.000000, 0, 0, -91, 492, 0 -ATT, -6.70, -2.97, 0.00, 2.30, 0.22, 129.61, 124.64 -CTUN, 492, 4.25, 3.29, 0.000000, 0, 0, -89, 492, 0 -GPS, 3, 308955600, 10, 1.49, 24.2398039, 54.5793034, 3.38, 14.80, 0.83, 317.21 -ATT, -4.74, -2.61, 0.00, 1.84, 0.11, 128.89, 124.64 -CTUN, 490, 4.07, 3.10, 0.000000, 0, 0, -92, 490, 0 -DU32, 7, 426237 -CURR, 492, 253367, 1185, 0, 4772, 0.000000 -ATT, -4.51, -1.30, 0.00, 2.49, 0.11, 127.47, 124.64 -CTUN, 490, 4.07, 3.06, 0.000000, 0, 0, -97, 490, 0 -GPS, 3, 308955800, 10, 1.49, 24.2398051, 54.5793024, 3.17, 14.65, 0.88, 321.05 -ATT, -1.96, -0.50, 0.00, 3.18, 0.11, 126.44, 124.65 -CTUN, 490, 3.87, 2.82, 0.000000, 0, 0, -106, 492, 0 -ATT, 0.00, 0.30, 0.00, 3.75, 0.00, 125.65, 124.65 -CTUN, 498, 3.87, 2.65, 0.000000, 0, 0, -106, 498, 0 -GPS, 3, 308956000, 10, 1.49, 24.2398064, 54.5793012, 2.93, 14.39, 0.92, 320.32 -ATT, 0.00, 2.41, 0.00, 4.70, 0.00, 124.91, 124.65 -CTUN, 498, 3.63, 2.57, 0.000000, 0, 0, -102, 496, 0 -ATT, 0.00, 3.78, -0.57, 5.68, 0.00, 125.59, 124.65 -CTUN, 511, 3.63, 2.72, 0.000000, 0, 0, -89, 511, 0 -GPS, 3, 308956200, 10, 1.49, 24.2398077, 54.5793001, 2.72, 14.12, 0.92, 319.97 -ATT, 0.00, 4.50, -4.50, 4.98, 0.00, 126.59, 124.65 -CTUN, 511, 3.37, 2.58, 0.000000, 0, 0, -77, 511, 0 -ATT, -0.92, 4.69, -3.23, 3.73, 0.00, 126.89, 124.65 -CTUN, 511, 3.37, 2.42, 0.000000, 0, 0, -58, 511, 0 -GPS, 3, 308956400, 10, 1.49, 24.2398088, 54.5792988, 2.56, 13.90, 0.97, 315.97 -ATT, -3.47, 4.54, -2.19, 2.47, 0.00, 126.89, 124.65 -CTUN, 513, 3.08, 2.29, 0.000000, 0, 0, -48, 511, 0 -ATT, -4.97, 3.82, -2.19, 1.06, 0.00, 126.13, 124.65 -CTUN, 515, 3.08, 2.37, 0.000000, 0, 0, -40, 515, 0 -GPS, 3, 308956600, 10, 1.49, 24.2398099, 54.5792969, 2.45, 13.78, 1.19, 309.50 -ATT, -5.32, 3.12, -1.38, 0.38, 0.00, 125.79, 124.65 -CTUN, 511, 3.08, 2.21, 0.000000, 0, 0, -34, 512, 0 -DU32, 7, 426237 -CURR, 511, 258397, 1180, 0, 4772, 0.000000 -ATT, -6.01, 1.91, 0.00, 0.05, 0.00, 125.70, 124.65 -CTUN, 494, 3.08, 2.32, 0.000000, 0, 0, -31, 511, 0 -GPS, 3, 308956800, 10, 1.49, 24.2398108, 54.5792949, 2.37, 13.69, 1.18, 302.50 -ATT, -13.65, 0.91, 0.00, -0.20, 0.00, 125.12, 124.65 -CTUN, 492, 2.98, 2.20, 0.000000, 0, 0, -37, 492, 0 -ATT, -14.92, -2.31, 0.00, 0.12, 0.00, 124.90, 124.65 -CTUN, 492, 2.98, 2.21, 0.000000, 0, 0, -55, 492, 0 -GPS, 3, 308957000, 10, 1.49, 24.2398115, 54.5792928, 2.27, 13.60, 1.16, 298.74 -ATT, -13.99, -6.29, 0.00, -1.03, 0.00, 125.59, 124.65 -CTUN, 492, 2.89, 2.00, 0.000000, 0, 0, -60, 492, 0 -ATT, -7.40, -6.50, -6.23, -1.43, 0.00, 126.31, 124.65 -CTUN, 492, 2.89, 1.91, 0.000000, 0, 0, -70, 490, 0 -GPS, 3, 308957200, 10, 1.49, 24.2398121, 54.5792909, 2.11, 13.47, 1.02, 295.17 -ATT, -1.15, -4.76, -8.76, 0.56, 0.00, 126.32, 124.65 -CTUN, 498, 2.75, 1.84, 0.000000, 0, 0, -79, 492, 0 -ATT, 0.00, -2.04, -7.03, 0.00, 0.00, 126.07, 124.65 -CTUN, 530, 2.75, 1.81, 0.000000, 0, 0, -84, 524, 0 -GPS, 3, 308957400, 10, 1.49, 24.2398129, 54.5792893, 1.93, 13.29, 0.93, 294.87 -ATT, 0.00, 0.70, -6.92, -1.11, 0.00, 125.40, 124.65 -CTUN, 531, 2.57, 1.58, 0.000000, 0, 0, -76, 531, 0 -ATT, -3.47, 3.32, -7.96, -0.28, 0.00, 125.03, 124.65 -CTUN, 534, 2.57, 1.55, 0.000000, 0, 0, -62, 531, 0 -GPS, 3, 308957600, 10, 1.49, 24.2398135, 54.5792880, 1.76, 13.13, 0.73, 297.00 -ATT, -9.71, 3.54, -6.46, -0.27, 0.00, 125.22, 124.65 -CTUN, 549, 2.38, 1.46, 0.000000, 0, 0, -45, 549, 0 -DU32, 7, 426237 -CURR, 549, 263501, 1169, 0, 4752, 0.000000 -ATT, -11.68, 1.07, -4.96, -2.03, 0.00, 125.91, 124.65 -CTUN, 549, 2.38, 1.31, 0.000000, 0, 0, -29, 549, 0 -GPS, 3, 308957800, 10, 1.49, 24.2398142, 54.5792867, 1.65, 12.98, 0.81, 297.46 -ATT, -11.22, -0.71, -4.84, -3.14, 0.00, 126.75, 124.65 -CTUN, 530, 2.24, 1.46, 0.000000, 0, 0, -16, 539, 0 -ATT, -8.90, -1.71, -4.84, -2.62, 0.00, 126.64, 124.65 -CTUN, 511, 2.24, 1.36, 0.000000, 0, 0, -15, 511, 0 -GPS, 3, 308958000, 10, 1.49, 24.2398145, 54.5792855, 1.58, 12.92, 0.75, 296.41 -ATT, -4.62, -2.64, -2.76, -2.15, 0.00, 126.28, 124.65 -CTUN, 483, 2.18, 1.53, 0.000000, 0, 0, -21, 486, 0 -ATT, -9.37, -1.86, 0.00, -1.86, 0.00, 126.43, 124.65 -CTUN, 486, 2.18, 1.51, 0.000000, 0, 0, -32, 486, 0 -GPS, 3, 308958200, 10, 1.49, 24.2398148, 54.5792846, 1.52, 12.88, 0.51, 295.31 -ATT, -10.41, -1.71, 0.00, 0.02, 0.00, 126.84, 124.65 -CTUN, 499, 2.12, 1.50, 0.000000, 0, 0, -50, 481, 0 -ATT, -10.29, -3.83, 0.00, 0.81, 0.00, 128.17, 124.65 -CTUN, 521, 2.12, 1.28, 0.000000, 0, 0, -54, 521, 0 -GPS, 3, 308958400, 10, 1.49, 24.2398152, 54.5792840, 1.41, 12.77, 0.39, 297.65 -ATT, -11.68, -3.93, 0.00, 0.30, 0.00, 129.19, 124.65 -CTUN, 522, 2.01, 1.24, 0.000000, 0, 0, -60, 522, 0 -PM, 0, 0, 50, 1, 1000, 10504, 9, 0 -ATT, -12.03, -4.03, 0.00, 1.26, 0.00, 128.16, 124.65 -CTUN, 522, 2.01, 1.05, 0.000000, 0, 0, -61, 522, 0 -GPS, 3, 308958600, 10, 1.49, 24.2398156, 54.5792835, 1.28, 12.63, 0.30, 305.68 -ATT, -5.78, -4.42, 0.00, 2.45, 0.00, 126.66, 124.65 -CTUN, 522, 1.86, 1.07, 0.000000, 0, 0, -64, 522, 0 -DU32, 7, 426237 -CURR, 522, 268663, 1156, 0, 4752, 0.000000 -ATT, 0.00, -3.43, -1.03, 2.72, 0.00, 125.13, 124.65 -CTUN, 522, 1.86, 0.86, 0.000000, 0, 0, -52, 522, 0 -GPS, 3, 308958800, 10, 1.49, 24.2398161, 54.5792834, 1.13, 12.48, 0.29, 319.57 -ATT, 0.00, 0.30, -0.57, 3.90, 0.00, 124.04, 124.65 -CTUN, 522, 1.72, 0.89, 0.000000, 0, 0, -54, 522, 0 -ATT, 0.00, 1.82, 0.00, 5.37, 0.00, 124.11, 124.65 -CTUN, 522, 1.72, 0.77, 0.000000, 0, 0, -52, 522, 0 -GPS, 3, 308959000, 10, 1.49, 24.2398169, 54.5792832, 1.00, 12.34, 0.44, 337.97 -ATT, 0.00, 2.51, 0.00, 5.09, 0.00, 124.02, 124.65 -CTUN, 522, 1.60, 0.65, 0.000000, 0, 0, -50, 522, 0 -ATT, 0.00, 3.80, -0.34, 4.87, 0.00, 124.13, 124.65 -CTUN, 523, 1.60, 0.58, 0.000000, 0, 0, -41, 525, 0 -GPS, 3, 308959200, 10, 1.49, 24.2398176, 54.5792830, 0.88, 12.20, 0.45, 340.97 -ATT, 0.00, 4.78, 0.00, 4.70, 0.00, 124.40, 124.65 -CTUN, 523, 1.49, 0.61, 0.000000, 0, 0, -37, 523, 0 -ATT, -5.66, 5.11, 0.00, 4.17, 0.00, 124.09, 124.65 -CTUN, 523, 1.49, 0.49, 0.000000, 0, 0, -34, 523, 0 -GPS, 3, 308959400, 10, 1.49, 24.2398183, 54.5792823, 0.77, 12.11, 0.56, 324.86 -ATT, -7.05, 3.59, -0.80, 3.69, 0.00, 124.38, 124.65 -CTUN, 523, 1.30, 0.54, 0.000000, 0, 0, -38, 523, 0 -ATT, -5.43, 1.09, -4.26, 2.59, 0.00, 124.72, 124.65 -CTUN, 523, 1.30, 0.33, 0.000000, 0, 0, -33, 523, 0 -GPS, 3, 308959600, 10, 1.49, 24.2398189, 54.5792814, 0.67, 12.03, 0.60, 316.19 -ATT, -5.43, 0.96, -4.26, 1.54, 0.00, 124.99, 124.65 -CTUN, 523, 1.29, 0.53, 0.000000, 0, 0, -33, 523, 0 -DU32, 7, 426237 -CURR, 523, 273896, 1157, 0, 4752, 0.000000 -ATT, -3.23, 0.87, -6.46, 1.04, 0.00, 125.26, 124.65 -CTUN, 523, 1.29, 0.48, 0.000000, 0, 0, -36, 523, 0 -GPS, 3, 308959800, 10, 1.49, 24.2398196, 54.5792803, 0.58, 11.96, 0.72, 310.23 -ATT, -1.96, 0.98, -7.96, 0.26, 0.00, 125.17, 124.65 -CTUN, 523, 1.23, 0.39, 0.000000, 0, 0, -38, 523, 0 -ATT, -4.16, 1.76, -7.84, -0.33, 0.00, 125.30, 124.65 -CTUN, 523, 1.23, 0.29, 0.000000, 0, 0, -40, 523, 0 -GPS, 3, 308960000, 10, 1.49, 24.2398202, 54.5792790, 0.48, 11.89, 0.73, 303.57 -ATT, -6.94, 2.06, -5.65, -0.90, 0.00, 125.76, 124.65 -CTUN, 523, 1.14, 0.32, 0.000000, 0, 0, -41, 523, 0 -ATT, -8.79, 1.27, -5.53, -1.50, 0.00, 125.91, 124.65 -CTUN, 535, 1.14, 0.27, 0.000000, 0, 0, -41, 535, 0 -GPS, 3, 308960200, 10, 1.49, 24.2398209, 54.5792779, 0.38, 11.78, 0.67, 303.56 -ATT, -9.48, 0.09, -5.42, -2.59, 0.00, 126.10, 124.65 -CTUN, 548, 1.05, 0.27, 0.000000, 0, 0, -35, 548, 0 -ATT, -9.71, -0.80, -5.42, -3.09, 0.00, 125.78, 124.65 -CTUN, 548, 1.05, 0.07, 0.000000, 0, 0, -28, 548, 0 -GPS, 3, 308960400, 10, 1.49, 24.2398212, 54.5792768, 0.30, 11.70, 0.61, 299.83 -ATT, -9.02, -1.61, -5.42, -2.93, 0.00, 125.14, 124.65 -CTUN, 548, 0.96, 0.09, 0.000000, 0, 0, -27, 548, 0 -ATT, -6.59, -2.42, -5.19, -2.67, 0.00, 124.88, 124.65 -CTUN, 548, 0.96, 0.20, 0.000000, 0, 0, -29, 548, 0 -GPS, 3, 308960600, 10, 1.49, 24.2398215, 54.5792760, 0.22, 11.64, 0.50, 296.37 -ATT, -3.70, -2.32, -5.19, -2.38, 0.00, 124.49, 124.65 -CTUN, 537, 0.90, 0.11, 0.000000, 0, 0, -29, 537, 0 -DU32, 7, 426237 -CURR, 533, 279259, 1175, 0, 4752, 0.000000 -ATT, -2.77, -0.91, -4.96, -1.01, 0.00, 123.81, 124.65 -CTUN, 533, 0.90, 0.05, 0.000000, 0, 0, -29, 533, 0 -GPS, 3, 308960800, 10, 1.49, 24.2398217, 54.5792755, 0.15, 11.58, 0.31, 296.55 -ATT, -1.38, -0.08, -3.92, 0.13, 0.00, 123.62, 124.65 -CTUN, 533, 0.85, 0.04, 0.000000, 0, 0, -36, 533, 0 -ATT, -0.34, 0.65, -2.88, -0.06, 0.00, 124.03, 124.65 -CTUN, 533, 0.85, 0.01, 0.000000, 0, 0, -36, 533, 0 -GPS, 3, 308961000, 10, 1.49, 24.2398218, 54.5792752, 0.07, 11.50, 0.14, 296.55 -ATT, -4.16, 2.63, -2.76, 0.57, 0.00, 124.62, 124.65 -CTUN, 530, 0.74, 0.04, 0.000000, 0, 0, -46, 530, 0 -ATT, -3.12, 2.14, -4.73, 1.67, 0.00, 125.33, 124.65 -CTUN, 530, 0.74, 0.04, 0.000000, 0, 0, -44, 530, 0 -GPS, 3, 308961200, 10, 1.49, 24.2398220, 54.5792751, -0.01, 11.44, 0.16, 296.55 -ATT, -5.32, 1.83, -4.03, 1.21, 0.00, 125.76, 124.65 -CTUN, 531, 0.67, -0.04, 0.000000, 0, 0, -46, 531, 0 -ATT, -8.21, 2.36, -3.46, 0.60, 0.00, 126.07, 124.65 -CTUN, 531, 0.67, -0.09, 0.000000, 0, 0, -42, 531, 0 -GPS, 3, 308961400, 10, 1.49, 24.2398218, 54.5792749, -0.09, 11.35, 0.12, 296.55 -ATT, -8.79, 1.16, -3.34, 0.81, 0.00, 126.05, 124.65 -CTUN, 530, 0.57, -0.17, 0.000000, 0, 0, -49, 530, 0 -ATT, -9.37, -0.34, -3.34, 0.00, 0.00, 126.12, 124.65 -CTUN, 531, 0.57, -0.25, 0.000000, 0, 0, -49, 530, 0 -GPS, 3, 308961600, 10, 1.49, 24.2398219, 54.5792745, -0.19, 11.27, 0.18, 296.55 -ATT, -9.37, -1.19, -3.34, -0.64, 0.00, 126.24, 124.65 -CTUN, 531, 0.49, -0.35, 0.000000, 0, 0, -53, 531, 0 -DU32, 7, 426237 -CURR, 531, 284575, 1185, 0, 4752, 0.000000 -ATT, -7.63, -1.86, -3.69, -0.36, 0.00, 126.19, 124.65 -CTUN, 525, 0.49, -0.35, 0.000000, 0, 0, -56, 528, 0 -GPS, 3, 308961800, 10, 1.49, 24.2398220, 54.5792744, -0.32, 11.16, 0.10, 296.55 -ATT, -3.00, -2.34, -4.61, 0.00, 0.00, 125.98, 124.65 -CTUN, 512, 0.40, -0.56, 0.000000, 0, 0, -62, 517, 0 -ATT, 0.00, -0.71, -5.07, 0.22, 0.00, 126.02, 124.65 -CTUN, 511, 0.40, -0.47, 0.000000, 0, 0, -67, 511, 0 -GPS, 3, 308962000, 10, 1.49, 24.2398220, 54.5792744, -0.43, 11.06, 0.04, 296.55 -ATT, 0.00, 1.62, -6.11, 0.84, 0.00, 126.63, 124.65 -CTUN, 517, 0.27, -0.53, 0.000000, 0, 0, -78, 517, 0 -ATT, 0.00, 2.65, -6.92, 1.23, 0.00, 128.28, 124.65 -CTUN, 511, 0.27, -0.50, 0.000000, 0, 0, -78, 511, 0 -GPS, 3, 308962200, 10, 1.49, 24.2398221, 54.5792744, -0.61, 10.90, 0.05, 296.55 -ATT, 0.00, 3.65, -5.76, 1.02, 0.00, 130.21, 124.65 -CTUN, 494, 0.16, -0.74, 0.000000, 0, 0, -79, 494, 0 -ATT, 0.00, 4.20, -4.61, 1.05, 0.00, 131.39, 124.65 -CTUN, 471, 0.25, -0.67, 0.000000, 0, 0, 1, 474, 0 -GPS, 3, 308962400, 10, 1.49, 24.2398223, 54.5792746, -0.71, 10.68, 0.09, 296.55 -ATT, -0.11, 1.56, -4.03, -1.39, 0.00, 132.59, 124.65 -CTUN, 422, 0.19, -0.76, 0.000000, 0, 0, -4, 422, 0 -ATT, 0.00, 1.84, -3.23, -1.07, 0.00, 134.82, 124.82 -CTUN, 402, 0.19, -0.74, 0.000000, 0, 0, -8, 403, 0 -GPS, 3, 308962600, 10, 1.49, 24.2398223, 54.5792746, -0.72, 10.63, 0.13, 296.55 -ATT, -0.11, -1.97, -2.53, 0.18, 0.00, 137.03, 127.03 -CTUN, 369, 0.19, -0.55, 0.000000, 0, 0, 5, 369, 0 -DU32, 7, 426237 -CURR, 366, 289373, 1188, 0, 4752, 0.000000 -ATT, 0.00, -2.11, -0.80, 0.12, 0.00, 138.98, 128.98 -CTUN, 351, 0.20, -0.65, 0.000000, 0, 0, 6, 356, 0 -GPS, 3, 308962800, 10, 1.49, 24.2398225, 54.5792748, -0.71, 10.61, 0.13, 296.55 -ATT, 0.00, -2.89, 0.00, 0.31, 0.00, 139.90, 129.90 -CTUN, 346, 0.19, -0.71, 0.000000, 0, 0, 3, 346, 0 -ATT, 0.00, -2.98, 0.00, 0.50, 0.00, 141.06, 131.06 -CTUN, 314, 0.20, -0.75, 0.000000, 0, 0, -2, 314, 0 -GPS, 3, 308963000, 10, 1.49, 24.2398225, 54.5792749, -0.71, 10.59, 0.05, 296.55 -ATT, 0.00, -3.04, 0.00, 0.53, 0.00, 141.31, 131.31 -CTUN, 280, 0.19, -0.74, 0.000000, 0, 0, 1, 296, 0 -ATT, 0.00, -3.00, 0.00, 0.47, 0.00, 141.53, 131.53 -CTUN, 268, 0.20, -0.40, 0.000000, 0, 0, 1, 271, 0 -GPS, 3, 308963200, 10, 1.49, 24.2398224, 54.5792749, -0.71, 10.59, 0.01, 296.55 -ATT, 0.00, -3.07, 0.00, 0.49, 0.00, 141.98, 131.98 -CTUN, 267, 0.20, -0.39, 0.000000, 0, 0, 4, 268, 0 -ATT, 0.00, -3.02, 0.00, 0.46, 0.00, 142.20, 132.20 -CTUN, 268, 0.20, -0.20, 0.000000, 0, 0, -3, 268, 0 -GPS, 3, 308963400, 10, 1.49, 24.2398224, 54.5792750, -0.67, 10.58, 0.03, 296.55 -ATT, 0.00, -2.99, 0.00, 0.48, 0.00, 142.48, 132.48 -CTUN, 268, 0.19, -0.28, 0.000000, 0, 0, 1, 268, 0 -ATT, 0.00, -2.90, 0.00, 0.46, 0.00, 142.79, 132.79 -CTUN, 268, 0.19, -0.43, 0.000000, 0, 0, 2, 268, 0 -GPS, 3, 308963600, 10, 1.49, 24.2398224, 54.5792750, -0.62, 10.58, 0.00, 296.55 -ATT, 0.00, -2.90, 0.00, 0.46, 0.00, 142.91, 132.91 -CTUN, 267, 0.19, -0.50, 0.000000, 0, 0, 7, 268, 0 -DU32, 7, 426237 -CURR, 268, 292328, 1173, 0, 4712, 0.000000 -ATT, 0.00, -2.85, 0.00, 0.45, 0.00, 143.09, 133.12 -CTUN, 268, 0.19, -0.48, 0.000000, 0, 0, 1, 268, 0 -GPS, 3, 308963800, 10, 1.49, 24.2398223, 54.5792750, -0.59, 10.58, 0.01, 296.55 -ATT, 0.00, -2.84, 0.00, 0.54, 0.00, 143.33, 133.33 -CTUN, 268, 0.19, -0.49, 0.000000, 0, 0, 0, 268, 0 -ATT, 0.00, -2.76, 0.00, 0.50, 0.00, 143.58, 133.58 -CTUN, 268, 0.21, -0.48, 0.000000, 0, 0, 1, 268, 0 -GPS, 3, 308964000, 10, 1.49, 24.2398223, 54.5792750, -0.57, 10.58, 0.01, 296.55 -ATT, 0.00, -2.75, 0.00, 0.47, 0.00, 143.65, 133.65 -CTUN, 268, 0.20, -0.51, 0.000000, 0, 0, 7, 268, 0 -ATT, 0.00, -2.72, 0.00, 0.45, 0.00, 143.74, 133.76 -CTUN, 268, 0.20, -0.60, 0.000000, 0, 0, 7, 268, 0 -GPS, 3, 308964200, 10, 1.49, 24.2398223, 54.5792750, -0.54, 10.58, 0.01, 296.55 -ATT, 0.00, -2.70, 0.00, 0.42, 0.00, 143.71, 133.76 -CTUN, 212, 0.20, -0.67, 0.000000, 0, 0, 4, 211, 0 -ATT, 0.00, -2.73, 0.00, 0.41, 0.00, 143.82, 133.82 -CTUN, 211, 0.20, -0.33, 0.000000, 0, 0, 6, 211, 0 -GPS, 3, 308964400, 10, 1.49, 24.2398223, 54.5792750, -0.54, 10.57, 0.00, 296.55 -ATT, 0.00, -2.78, 0.00, 0.39, 0.00, 143.80, 133.82 -CTUN, 212, 0.20, -0.42, 0.000000, 0, 0, 9, 212, 0 -ATT, 0.00, -2.72, 0.00, 0.40, 0.00, 143.93, 133.94 -CTUN, 210, 0.20, -0.41, 0.000000, 0, 0, 13, 210, 0 -GPS, 3, 308964600, 10, 1.49, 24.2398223, 54.5792750, -0.50, 10.57, 0.01, 296.55 -ATT, 0.00, -2.64, 0.00, 0.35, 0.00, 143.76, 133.94 -CTUN, 210, 0.17, -0.31, 0.000000, 0, 0, 11, 210, 0 -DU32, 7, 426237 -CURR, 210, 294722, 1188, 0, 4772, 0.000000 -ATT, 0.00, -2.74, 0.00, 0.39, 0.00, 143.82, 133.94 -CTUN, 210, 0.19, -0.30, 0.000000, 0, 0, 13, 210, 0 -GPS, 3, 308964800, 10, 1.49, 24.2398223, 54.5792750, -0.47, 10.57, 0.01, 296.55 -ATT, 0.00, -2.78, 0.00, 0.39, 0.00, 143.76, 133.94 -CTUN, 210, 0.19, -0.24, 0.000000, 0, 0, 14, 210, 0 -ATT, 0.00, -2.77, 0.00, 0.42, 0.00, 143.77, 133.94 -CTUN, 210, 0.19, -0.35, 0.000000, 0, 0, 16, 210, 0 -GPS, 3, 308965000, 10, 1.49, 24.2398223, 54.5792750, -0.42, 10.56, 0.02, 296.55 -ATT, 0.00, -2.79, 0.00, 0.38, 0.00, 143.67, 133.94 -CTUN, 210, 0.19, -0.27, 0.000000, 0, 0, 16, 210, 0 -ATT, 0.00, -2.80, 0.00, 0.49, 0.00, 144.15, 134.15 -CTUN, 210, 0.19, -0.27, 0.000000, 0, 0, 19, 210, 0 -GPS, 3, 308965200, 10, 1.49, 24.2398223, 54.5792750, -0.37, 10.56, 0.01, 296.55 -ATT, 0.00, -2.66, 0.00, 0.51, 0.00, 144.82, 134.82 -CTUN, 210, 0.17, -0.41, 0.000000, 0, 0, 13, 210, 0 -ATT, 0.00, -2.62, 0.00, 0.42, 0.00, 145.27, 135.27 -CTUN, 210, 0.19, -0.45, 0.000000, 0, 0, 10, 210, 0 -GPS, 3, 308965400, 10, 1.49, 24.2398222, 54.5792750, -0.34, 10.57, 0.00, 296.55 -ATT, 0.00, -2.81, 0.00, 0.40, 0.00, 145.39, 135.39 -CTUN, 210, 0.19, -0.14, 0.000000, 0, 0, 13, 210, 0 -ATT, 0.00, -2.80, 0.00, 0.53, 0.00, 145.68, 135.68 -CTUN, 210, 0.24, -0.40, 0.000000, 0, 0, 14, 210, 0 -GPS, 3, 308965600, 10, 1.49, 24.2398222, 54.5792750, -0.32, 10.57, 0.01, 296.55 -ATT, 0.00, -2.64, 0.00, 0.42, 0.00, 145.77, 135.77 -CTUN, 210, 0.24, -0.19, 0.000000, 0, 0, 14, 210, 0 -ATT, 0.00, -2.77, 0.00, 0.46, 0.00, 145.75, 135.78 -DU32, 7, 426237 -CURR, 210, 296820, 1205, 0, 4793, 0.000000 -CTUN, 210, 0.24, -0.37, 0.000000, 0, 0, 15, 210, 0 -GPS, 3, 308965800, 10, 1.49, 24.2398222, 54.5792750, -0.28, 10.57, 0.01, 296.55 -ATT, 0.00, -2.79, 0.00, 0.42, 0.00, 145.76, 135.78 -CTUN, 0, 0.24, -0.20, 0.000000, 0, 0, 20, 0, 0 -ATT, 0.00, -2.59, 0.00, 0.44, 0.00, 145.97, 145.97 -CTUN, 0, 0.24, 0.06, 0.000000, 0, 0, 18, 0, 0 -GPS, 3, 308966000, 10, 1.49, 24.2398222, 54.5792750, -0.25, 10.57, 0.02, 296.55 -ATT, 0.00, -2.86, 0.00, 0.44, 0.00, 146.23, 146.23 -CTUN, 0, 0.24, -0.06, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -3.13, 0.00, 0.52, 0.00, 146.26, 146.26 -CTUN, 0, 0.25, -0.13, 0.000000, 0, 0, 15, 0, 0 -GPS, 3, 308966200, 10, 1.49, 24.2398221, 54.5792750, -0.18, 10.58, 0.02, 296.55 -ATT, 0.00, -2.94, 0.00, 0.53, 0.00, 146.44, 146.44 -CTUN, 0, 0.25, -0.07, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -2.88, 0.00, 0.49, 0.00, 146.87, 146.87 -CTUN, 0, 0.25, -0.12, 0.000000, 0, 0, 15, 0, 0 -GPS, 3, 308966400, 10, 1.49, 24.2398221, 54.5792750, -0.14, 10.59, 0.01, 296.55 -ATT, 0.00, -2.85, 0.00, 0.47, 0.00, 147.51, 147.51 -CTUN, 0, 0.20, 0.02, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -2.62, 0.00, 0.47, 0.00, 148.18, 148.18 -CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 17, 0, 0 -GPS, 3, 308966600, 10, 1.49, 24.2398222, 54.5792750, -0.10, 10.58, 0.02, 296.55 -ATT, 0.00, -2.50, 0.00, 0.43, 0.00, 148.83, 148.83 -CTUN, 0, 0.20, -0.02, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -2.70, 0.00, 0.48, 0.00, 149.44, 149.44 -DU32, 7, 426173 -CURR, 0, 297030, 1210, 0, 4772, 0.000000 -CTUN, 0, 0.24, 0.01, 0.000000, 0, 0, 16, 0, 0 -GPS, 3, 308966800, 10, 1.49, 24.2398222, 54.5792750, -0.05, 10.59, 0.01, 296.55 -ATT, 0.00, -2.82, 0.00, 0.42, 0.00, 150.17, 150.17 -CTUN, 0, 0.24, 0.01, 0.000000, 0, 0, 16, 0, 0 -ATT, 0.00, -2.44, 0.00, 0.48, 0.00, 150.97, 150.97 -CTUN, 0, 0.29, -0.01, 0.000000, 0, 0, 19, 0, 0 -GPS, 3, 308967000, 10, 1.49, 24.2398221, 54.5792751, -0.01, 10.60, 0.01, 296.55 -ATT, 0.00, -2.67, 0.00, 0.47, 0.00, 151.69, 151.69 -CTUN, 0, 0.27, -0.05, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -2.36, 0.00, 0.40, 0.00, 152.16, 152.16 -CTUN, 0, 0.29, -0.08, 0.000000, 0, 0, 19, 0, 0 -GPS, 3, 308967200, 10, 1.49, 24.2398221, 54.5792751, 0.02, 10.59, 0.03, 296.55 -ATT, 0.00, -2.64, 0.00, 0.47, 0.00, 152.68, 152.68 -CTUN, 0, 0.27, -0.02, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -2.15, 0.00, 0.48, 0.00, 152.97, 152.97 -CTUN, 0, 0.27, -0.04, 0.000000, 0, 0, 17, 0, 0 -GPS, 3, 308967400, 10, 1.49, 24.2398221, 54.5792752, 0.04, 10.60, 0.03, 296.55 -ATT, 0.00, -2.41, 0.00, 0.51, 0.00, 153.10, 153.10 -CTUN, 0, 0.25, 0.01, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -2.46, 0.00, 0.51, 0.00, 153.46, 153.46 -CTUN, 0, 0.25, -0.10, 0.000000, 0, 0, 17, 0, 0 -GPS, 3, 308967600, 10, 1.49, 24.2398221, 54.5792752, 0.07, 10.59, 0.00, 296.55 -ATT, 0.00, -2.19, 0.00, 0.45, 0.00, 153.61, 153.61 -CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -2.19, 0.00, 0.44, -1.11, 153.74, 153.74 -DU32, 7, 426173 -CURR, 0, 297030, 1207, 0, 4772, 0.000000 -CTUN, 0, 0.22, -0.02, 0.000000, 0, 0, 16, 0, 0 -GPS, 3, 308967800, 10, 1.49, 24.2398222, 54.5792752, 0.08, 10.59, 0.01, 296.55 -ATT, 0.00, -2.41, 0.00, 0.46, -17.26, 153.63, 153.63 -CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -2.50, 0.00, 0.43, -34.41, 153.33, 153.33 -CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 15, 0, 0 -GPS, 3, 308968000, 10, 1.49, 24.2398221, 54.5792752, 0.09, 10.59, 0.05, 296.55 -ATT, 0.00, -2.37, 0.00, 0.41, -45.00, 152.88, 152.88 -CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -2.33, 0.00, 0.34, -42.77, 152.10, 152.10 -CTUN, 0, 0.22, -0.03, 0.000000, 0, 0, 13, 0, 0 -GPS, 3, 308968200, 10, 1.49, 24.2398222, 54.5792752, 0.10, 10.58, 0.00, 296.55 -ATT, 0.00, -2.29, 0.00, 0.27, -38.65, 151.24, 151.24 -CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -2.23, 0.00, 0.33, -45.11, 150.89, 150.89 -CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, 12, 0, 0 -GPS, 3, 308968400, 10, 1.49, 24.2398221, 54.5792752, 0.11, 10.58, 0.03, 296.55 -ATT, 0.00, -2.27, 0.00, 0.32, -45.11, 150.32, 150.32 -CTUN, 0, 0.22, -0.17, 0.000000, 0, 0, 12, 0, 0 -PM, 0, 0, 50, 0, 1000, 10500, 9, 0 -ATT, 0.00, -2.31, 0.00, 0.32, -45.11, 149.78, 149.78 -CTUN, 0, 0.27, 0.03, 0.000000, 0, 0, 11, 0, 0 -GPS, 3, 308968600, 10, 1.49, 24.2398222, 54.5792751, 0.10, 10.59, 0.01, 296.55 -ATT, 0.00, -2.27, 0.00, 0.39, -45.00, 149.58, 149.58 -CTUN, 0, 0.26, -0.02, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -2.19, 0.00, 0.31, -45.11, 149.34, 149.34 -DU32, 7, 426173 -CURR, 0, 297030, 1212, 0, 4752, 0.000000 -CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 8, 0, 0 -GPS, 3, 308968800, 10, 1.49, 24.2398222, 54.5792751, 0.11, 10.59, 0.01, 296.55 -ATT, 0.00, -2.02, 0.00, 0.29, -45.11, 149.29, 149.29 -CTUN, 0, 0.27, -0.06, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -1.97, 0.00, 0.25, -45.00, 149.19, 149.19 -CTUN, 0, 0.27, -0.14, 0.000000, 0, 0, 8, 0, 0 -GPS, 3, 308969000, 10, 1.49, 24.2398222, 54.5792751, 0.11, 10.58, 0.01, 296.55 -ATT, 0.00, -2.21, 0.00, 0.29, -45.11, 149.13, 149.13 -CTUN, 0, 0.27, -0.05, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -2.24, 0.00, 0.31, -45.00, 149.02, 149.02 -CTUN, 0, 0.27, -0.03, 0.000000, 0, 0, 6, 0, 0 -GPS, 3, 308969200, 10, 1.49, 24.2398221, 54.5792751, 0.10, 10.59, 0.05, 296.55 -ATT, 0.00, -2.01, 0.00, 0.22, -45.00, 148.96, 148.96 -CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, -1.98, 0.00, 0.18, -45.11, 149.00, 149.00 -CTUN, 0, 0.27, -0.18, 0.000000, 0, 0, 6, 0, 0 -GPS, 3, 308969400, 10, 1.49, 24.2398221, 54.5792751, 0.09, 10.61, 0.02, 296.55 -ATT, 0.00, -2.25, 0.00, 0.24, -45.11, 148.94, 148.94 -CTUN, 0, 0.27, -0.02, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, -1.89, 0.00, 0.18, -45.00, 148.92, 148.92 -CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 4, 0, 0 -GPS, 3, 308969600, 10, 1.49, 24.2398221, 54.5792751, 0.08, 10.60, 0.01, 296.55 -ATT, 0.00, -2.09, 0.00, 0.18, -45.11, 148.95, 148.95 -CTUN, 0, 0.27, -0.06, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, -1.97, 0.00, 0.25, -45.00, 148.88, 148.88 -DU32, 7, 426173 -CURR, 0, 297030, 1214, 0, 4772, 0.000000 -CTUN, 0, 0.29, 0.04, 0.000000, 0, 0, 2, 0, 0 -GPS, 3, 308969800, 10, 1.49, 24.2398220, 54.5792751, 0.07, 10.58, 0.07, 296.55 -ATT, 0.00, -1.81, 0.00, 0.16, -45.00, 148.87, 148.87 -CTUN, 0, 0.27, -0.01, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, -1.90, 0.00, 0.21, -32.30, 148.87, 148.87 -CTUN, 0, 0.29, 0.01, 0.000000, 0, 0, 2, 0, 0 -GPS, 3, 308970000, 10, 1.49, 24.2398220, 54.5792752, 0.07, 10.58, 0.01, 296.55 -ATT, 0.00, -1.82, 0.00, 0.12, -0.77, 148.81, 148.81 -CTUN, 0, 0.29, -0.04, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -1.92, 0.00, 0.21, 0.00, 148.88, 148.88 -CTUN, 0, 0.29, -0.14, 0.000000, 0, 0, 1, 0, 0 -GPS, 3, 308970200, 10, 1.49, 24.2398220, 54.5792752, 0.06, 10.56, 0.01, 296.55 -ATT, 0.00, -1.92, 0.00, 0.15, 0.00, 148.82, 148.82 -CTUN, 0, 0.25, 0.03, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, -1.87, 0.00, 0.19, 0.00, 148.83, 148.83 -CTUN, 0, 0.25, -0.07, 0.000000, 0, 0, 1, 0, 0 -GPS, 3, 308970400, 10, 1.49, 24.2398220, 54.5792752, 0.05, 10.56, 0.03, 296.55 -ATT, 0.00, -1.96, 0.00, 0.17, 0.00, 148.81, 148.81 -CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -1.82, 0.00, 0.13, 0.00, 148.76, 148.76 -CTUN, 0, 0.24, -0.06, 0.000000, 0, 0, 0, 0, 0 -GPS, 3, 308970600, 10, 1.49, 24.2398220, 54.5792752, 0.04, 10.55, 0.02, 296.55 -ATT, 0.00, -1.89, 0.00, 0.20, 0.00, 148.80, 148.80 -CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -1.91, 0.00, 0.12, 0.00, 148.73, 148.73 -DU32, 7, 426173 -CURR, 0, 297030, 1219, 0, 4772, 0.000000 -CTUN, 0, 0.24, -0.01, 0.000000, 0, 0, -1, 0, 0 -GPS, 3, 308970800, 10, 1.49, 24.2398220, 54.5792752, 0.04, 10.55, 0.00, 296.55 -ATT, 0.00, -1.79, 0.00, 0.12, 0.00, 148.71, 148.71 -CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -1.86, 0.00, 0.17, 0.00, 148.74, 148.74 -CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, 0, 0, 0 -GPS, 3, 308971000, 10, 1.49, 24.2398220, 54.5792752, 0.03, 10.55, 0.01, 296.55 -ATT, 0.00, -1.92, 0.00, 0.13, 0.00, 148.71, 148.71 -CTUN, 0, 0.22, 0.06, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, -1.83, 0.00, 0.11, 0.00, 148.67, 148.67 -CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, -1, 0, 0 -GPS, 3, 308971200, 10, 1.49, 24.2398220, 54.5792752, 0.03, 10.54, 0.00, 296.55 -ATT, 0.00, -1.80, 0.00, 0.13, 0.00, 148.67, 148.67 -CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, -1.84, 0.00, 0.14, 0.00, 148.68, 148.68 -CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, -2, 0, 0 -GPS, 3, 308971400, 10, 1.49, 24.2398220, 54.5792752, 0.02, 10.55, 0.02, 296.55 -ATT, 0.00, -1.84, 0.00, 0.11, 0.00, 148.63, 148.63 -CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, -1.76, 0.00, 0.10, 0.00, 148.62, 148.62 -CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, -3, 0, 0 -GPS, 3, 308971600, 10, 1.49, 24.2398220, 54.5792752, 0.00, 10.54, 0.02, 296.55 -ATT, 0.00, -1.70, 0.00, 0.11, 0.00, 148.60, 148.60 -CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, -1.83, 0.00, 0.09, 0.00, 148.59, 148.59 -DU32, 7, 426173 -CURR, 0, 297030, 1215, 0, 4752, 0.000000 -CTUN, 0, 0.22, -0.06, 0.000000, 0, 0, -4, 0, 0 -GPS, 3, 308971800, 10, 1.49, 24.2398221, 54.5792753, 0.00, 10.52, 0.06, 296.55 -ATT, 0.00, -1.79, 0.00, 0.13, 0.00, 148.60, 148.60 -CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, -1.82, 0.00, 0.18, 0.00, 148.58, 148.58 -CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, -5, 0, 0 -GPS, 3, 308972000, 10, 1.49, 24.2398220, 54.5792753, -0.02, 10.53, 0.02, 296.55 -ATT, 0.00, -1.87, 0.00, 0.11, 0.00, 148.55, 148.55 -CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, -5, 0, 0 -ATT, 0.00, -1.83, 0.00, 0.11, 0.00, 148.54, 148.54 -CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -6, 0, 0 -GPS, 3, 308972200, 10, 1.49, 24.2398220, 54.5792753, -0.02, 10.53, 0.03, 296.55 -ATT, 0.00, -1.74, 0.00, 0.06, 0.00, 148.50, 148.50 -CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -6, 0, 0 -ATT, 0.00, -1.68, 0.00, 0.12, 0.00, 148.52, 148.52 -CTUN, 0, 0.22, -0.20, 0.000000, 0, 0, -6, 0, 0 -GPS, 3, 308972400, 10, 1.49, 24.2398220, 54.5792753, -0.05, 10.54, 0.00, 296.55 -ATT, 0.00, -1.67, 0.00, 0.30, 0.00, 148.44, 148.44 -CTUN, 0, 0.22, 0.03, 0.000000, 0, 0, -7, 0, 0 -ATT, 0.00, -1.74, 0.00, 0.05, 0.00, 148.48, 148.48 -CTUN, 0, 0.22, -0.03, 0.000000, 0, 0, -8, 0, 0 -GPS, 3, 308972600, 10, 1.49, 24.2398220, 54.5792753, -0.07, 10.54, 0.02, 296.55 -ATT, 0.00, -1.51, 0.00, 0.00, 0.00, 148.51, 148.51 -CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, -8, 0, 0 -ATT, 0.00, -1.43, 0.00, 0.01, 0.00, 148.49, 148.49 -DU32, 7, 426173 -CURR, 0, 297030, 1212, 0, 4752, 0.000000 -GPS, 3, 308972800, 10, 1.49, 24.2398220, 54.5792753, -0.08, 10.53, 0.02, 296.55 -CTUN, 0, 0.22, -0.07, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, -1.50, 0.00, 0.00, 0.00, 148.47, 148.47 -CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, -1.45, 0.00, -0.02, 0.00, 148.44, 148.44 -GPS, 3, 308973000, 10, 1.49, 24.2398220, 54.5792753, -0.10, 10.54, 0.03, 296.55 -CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, -1.52, 0.00, 0.03, 0.00, 148.43, 148.43 -CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, -1.34, 0.00, -0.07, 0.00, 148.36, 148.36 -GPS, 3, 308973200, 10, 1.49, 24.2398221, 54.5792753, -0.11, 10.51, 0.04, 296.55 -CTUN, 0, 0.22, -0.16, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, -1.24, 0.00, 0.27, 0.00, 148.40, 148.40 -CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, -10, 0, 0 -ATT, 0.00, -1.53, 0.00, 0.21, 0.00, 148.19, 148.19 -GPS, 3, 308973400, 10, 1.49, 24.2398221, 54.5792753, -0.13, 10.53, 0.02, 296.55 -CTUN, 0, 0.22, -0.16, 0.000000, 0, 0, -10, 0, 0 -ATT, 0.00, -1.33, 0.00, -0.08, 0.00, 148.27, 148.27 -CTUN, 0, 0.21, -0.09, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, -1.31, 0.00, 0.19, 0.00, 148.30, 148.30 -GPS, 3, 308973600, 10, 1.49, 24.2398221, 54.5792754, -0.15, 10.53, 0.02, 296.55 -CTUN, 0, 0.21, -0.12, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, -1.28, 0.00, 0.25, 0.00, 148.25, 148.25 -CTUN, 0, 0.15, -0.17, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, -1.36, 0.00, 0.29, 0.00, 148.22, 148.22 -DU32, 7, 426173 -CURR, 0, 297030, 1214, 0, 4752, 0.000000 -GPS, 3, 308973800, 10, 1.49, 24.2398221, 54.5792753, -0.17, 10.53, 0.03, 296.55 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, -1.55, 0.00, 0.18, 0.00, 148.13, 148.13 -CTUN, 0, 0.15, -0.14, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, -1.24, 0.00, -0.04, 0.00, 148.18, 148.18 -GPS, 3, 308974000, 10, 1.49, 24.2398221, 54.5792753, -0.19, 10.52, 0.01, 296.55 -CTUN, 0, 0.15, -0.18, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, -1.26, 0.00, 0.17, 0.00, 148.19, 148.19 -CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, -1.46, 0.00, 0.39, 0.00, 148.10, 148.10 -CTUN, 0, 0.15, -0.10, 0.000000, 0, 0, -13, 0, 0 -GPS, 3, 308974200, 10, 1.49, 24.2398222, 54.5792753, -0.22, 10.52, 0.03, 296.55 -ATT, 0.00, -1.40, 0.00, 0.02, 0.00, 148.10, 148.10 -CTUN, 0, 0.15, -0.07, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.30, 0.00, 0.04, 0.00, 148.15, 148.15 -GPS, 3, 308974400, 10, 1.49, 24.2398222, 54.5792754, -0.23, 10.53, 0.02, 296.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, -1.27, 0.00, 0.42, 0.00, 148.05, 148.05 -CTUN, 0, 0.15, -0.04, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.33, 0.00, 0.22, 0.00, 148.01, 148.01 -GPS, 3, 308974600, 10, 1.49, 24.2398222, 54.5792754, -0.24, 10.54, 0.02, 296.55 -CTUN, 0, 0.15, -0.01, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.24, 0.00, 0.15, 0.00, 148.03, 148.03 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.17, 0.00, 0.35, 0.00, 148.01, 148.01 -DU32, 7, 426173 -CURR, 0, 297030, 1216, 0, 4752, 0.000000 -GPS, 3, 308974800, 10, 1.49, 24.2398221, 54.5792754, -0.24, 10.55, 0.04, 296.55 -CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.27, 0.00, 0.14, 0.00, 147.97, 147.97 -CTUN, 0, 0.15, -0.14, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.14, 0.00, 0.00, 0.00, 148.03, 148.03 -GPS, 3, 308975000, 10, 1.49, 24.2398222, 54.5792754, -0.26, 10.56, 0.04, 296.55 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.38, 0.00, 147.95, 147.95 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.16, 0.00, 0.42, 0.00, 147.92, 147.92 -GPS, 3, 308975200, 10, 1.49, 24.2398221, 54.5792754, -0.27, 10.58, 0.05, 296.55 -CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.24, 0.00, 0.06, 0.00, 147.90, 147.90 -CTUN, 0, 0.15, -0.19, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.00, 0.00, 147.95, 147.95 -GPS, 3, 308975400, 10, 1.49, 24.2398224, 54.5792753, -0.29, 10.52, 0.02, 296.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.08, 0.00, 0.19, 0.00, 147.94, 147.94 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.43, 0.00, 147.85, 147.85 -GPS, 3, 308975600, 10, 1.49, 24.2398223, 54.5792753, -0.30, 10.54, 0.06, 296.55 -CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -1.18, 0.00, 0.27, 0.00, 147.82, 147.82 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -1.08, 0.00, 0.05, 0.00, 147.83, 147.83 -DU32, 7, 426173 -CURR, 0, 297030, 1217, 0, 4752, 0.000000 -GPS, 3, 308975800, 10, 1.49, 24.2398226, 54.5792754, -0.31, 10.50, 0.07, 296.55 -CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -1.01, 0.00, -0.02, 0.00, 147.85, 147.85 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -1.00, 0.00, 0.09, 0.00, 147.90, 147.90 -GPS, 3, 308976000, 10, 1.49, 24.2398224, 54.5792754, -0.32, 10.53, 0.10, 296.55 -CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -0.86, 0.00, 0.41, 0.00, 147.82, 147.82 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, -0.89, 0.00, 0.40, 0.00, 147.78, 147.78 -GPS, 3, 308976200, 10, 1.49, 24.2398225, 54.5792755, -0.33, 10.52, 0.04, 296.55 -CTUN, 0, 0.15, -0.15, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.97, 0.00, 0.21, 0.00, 147.73, 147.73 -CTUN, 0, 0.15, -0.06, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.99, 0.00, 0.00, 0.00, 147.76, 147.76 -GPS, 3, 308976400, 10, 1.49, 24.2398226, 54.5792756, -0.34, 10.51, 0.05, 296.55 -CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.99, 0.00, -0.03, 0.00, 147.74, 147.74 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.19, 0.00, 0.00, 0.00, 147.76, 147.76 -GPS, 3, 308976600, 10, 1.49, 24.2398225, 54.5792755, -0.34, 10.49, 0.05, 296.55 -CTUN, 0, 0.15, -0.20, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.26, 0.00, -0.02, 0.00, 147.74, 147.74 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.23, 0.00, -0.02, 0.00, 147.72, 147.72 -DU32, 7, 426173 -CURR, 0, 297030, 1213, 0, 4772, 0.000000 -GPS, 3, 308976800, 10, 1.49, 24.2398229, 54.5792756, -0.35, 10.44, 0.14, 296.55 -CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.23, 0.00, -0.01, 0.00, 147.71, 147.71 -CTUN, 0, 0.15, -0.20, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.25, 0.00, 0.01, 0.00, 147.69, 147.69 -GPS, 3, 308977000, 10, 1.49, 24.2398230, 54.5792756, -0.36, 10.42, 0.03, 296.55 -CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.27, 0.00, 0.02, 0.00, 147.67, 147.67 -CTUN, 0, 0.15, 0.02, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.16, 0.00, -0.01, 0.00, 147.64, 147.64 -GPS, 3, 308977200, 10, 1.49, 24.2398230, 54.5792757, -0.36, 10.42, 0.02, 296.55 -CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.12, 0.00, -0.05, 0.00, 147.61, 147.61 -CTUN, 0, 0.15, -0.10, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.09, 0.00, -0.06, 0.00, 147.59, 147.59 -GPS, 3, 308977400, 10, 1.49, 24.2398231, 54.5792757, -0.36, 10.39, 0.03, 296.55 -CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.03, 0.00, -0.05, 0.00, 147.57, 147.57 -CTUN, 0, 0.15, -0.01, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.02, 0.00, -0.03, 0.00, 147.57, 147.57 -GPS, 3, 308977600, 10, 1.49, 24.2398230, 54.5792757, -0.36, 10.39, 0.05, 296.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.96, 0.00, 0.04, 0.00, 147.59, 147.59 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.97, 0.00, 0.01, 0.00, 147.55, 147.55 -DU32, 7, 426173 -CURR, 0, 297030, 1213, 0, 4772, 0.000000 -GPS, 3, 308977800, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.33, 0.13, 296.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.97, 0.00, 0.09, 0.00, 147.55, 147.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.17, 0.00, 147.49, 147.49 -GPS, 3, 308978000, 10, 1.49, 24.2398233, 54.5792759, -0.36, 10.31, 0.07, 296.55 -CTUN, 0, 0.15, 0.00, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.18, 0.00, 147.47, 147.47 -CTUN, 0, 0.15, -0.13, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.07, 0.00, 0.03, 0.00, 147.42, 147.42 -GPS, 3, 308978200, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.32, 0.04, 296.55 -CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.03, 0.00, -0.04, 0.00, 147.43, 147.43 -CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.12, 0.00, -0.04, 0.00, 147.42, 147.42 -GPS, 3, 308978400, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.32, 0.03, 296.55 -CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.17, 0.00, -0.01, 0.00, 147.41, 147.41 -PM, 0, 0, 50, 0, 1000, 10500, 9, 0 -CTUN, 0, 0.15, -0.15, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -1.06, 0.00, -0.18, 0.00, 147.40, 147.40 -GPS, 3, 308978600, 10, 1.49, 24.2398236, 54.5792760, -0.37, 10.29, 0.07, 296.55 -CTUN, 0, 0.15, -0.19, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.61, 0.00, -0.23, 0.00, 147.34, 147.34 -CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, 23, 0, 0 -ATT, 0.00, -1.00, 0.00, 0.01, 0.00, 145.29, 145.29 -DU32, 7, 426173 -CURR, 0, 297030, 1214, 0, 4793, 0.000000 -GPS, 3, 308978800, 10, 1.49, 24.2398236, 54.5792761, -0.30, 10.28, 0.04, 296.55 -CTUN, 0, 0.16, 0.01, 0.000000, 0, 0, 47, 0, 0 -ATT, 0.00, -1.95, 0.00, -0.04, 0.00, 142.63, 142.63 -CTUN, 0, 0.15, 0.01, 0.000000, 0, 0, 70, 0, 0 -ATT, 0.00, -1.15, 0.00, -1.26, 0.00, 139.35, 139.35 -GPS, 3, 308979000, 10, 1.49, 24.2398239, 54.5792761, -0.15, 10.33, 0.12, 296.55 -CTUN, 0, 0.16, 0.08, 0.000000, 0, 0, 72, 0, 0 -ATT, 0.00, -0.03, 0.00, -2.25, 0.00, 135.23, 135.23 -CTUN, 0, 0.16, 0.29, 0.000000, 0, 0, 56, 0, 0 -ATT, 0.00, 0.48, 0.00, -2.76, 0.00, 130.68, 130.68 -GPS, 3, 308979200, 10, 1.49, 24.2398241, 54.5792763, 0.00, 10.46, 0.12, 296.55 -CTUN, 0, 0.26, 0.54, 0.000000, 0, 0, 42, 0, 0 -ATT, 0.00, 0.75, 0.00, -3.45, 0.00, 126.26, 126.26 -CTUN, 0, 0.26, 0.75, 0.000000, 0, 0, 36, 0, 0 -ATT, 0.00, -1.53, 0.00, -4.36, 0.00, 122.30, 122.30 -GPS, 3, 308979400, 10, 1.49, 24.2398241, 54.5792766, 0.14, 10.58, 0.13, 296.55 -CTUN, 0, 0.39, 0.79, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -1.44, 0.00, -6.41, 0.00, 118.11, 118.11 -CTUN, 0, 0.39, 0.76, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -0.27, 0.00, -7.35, 0.00, 114.46, 114.46 -GPS, 3, 308979600, 10, 1.49, 24.2398237, 54.5792777, 0.23, 10.65, 0.51, 16.51 -CTUN, 0, 0.49, 0.78, 0.000000, 0, 0, -7, 0, 0 -ATT, 0.00, 2.36, 0.00, -7.68, 0.00, 111.88, 111.88 -CTUN, 0, 0.49, 0.87, 0.000000, 0, 0, -18, 0, 0 -ATT, 0.00, 4.44, 0.00, -7.58, 0.00, 109.95, 109.95 -DU32, 7, 426173 -CURR, 0, 297030, 1210, 0, 4752, 0.000000 -GPS, 3, 308979800, 10, 1.49, 24.2398230, 54.5792792, 0.26, 10.67, 0.88, 98.67 -CTUN, 0, 0.50, 0.79, 0.000000, 0, 0, -26, 0, 0 -ATT, 0.00, 4.45, 0.00, -5.84, 0.00, 108.51, 108.51 -CTUN, 0, 0.49, 0.56, 0.000000, 0, 0, -9, 0, 0 -ATT, 0.00, 4.50, 0.00, -2.32, 0.00, 107.44, 107.44 -GPS, 3, 308980000, 10, 1.49, 24.2398219, 54.5792814, 0.29, 10.64, 1.33, 113.88 -CTUN, 0, 0.49, 0.80, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 4.32, 0.00, 0.89, 0.00, 106.66, 106.66 -CTUN, 0, 0.46, 0.59, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, 4.23, 0.00, 3.31, 0.00, 105.22, 105.22 -GPS, 3, 308980200, 10, 1.49, 24.2398206, 54.5792835, 0.34, 10.64, 1.34, 118.38 -CTUN, 0, 0.49, 0.78, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 3.56, 0.00, 5.08, 0.00, 103.94, 103.94 -CTUN, 0, 0.49, 1.04, 0.000000, 0, 0, -10, 0, 0 -ATT, 0.00, 3.21, 0.00, 6.28, 0.00, 103.04, 103.04 -GPS, 3, 308980400, 9, 1.75, 24.2398195, 54.5792856, 0.39, 10.66, 1.25, 122.12 -CTUN, 0, 0.54, 0.84, 0.000000, 0, 0, -6, 0, 0 -ATT, 0.00, 2.61, 0.00, 5.87, 0.00, 102.47, 102.47 -CTUN, 0, 0.54, 0.89, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, 1.49, 0.00, 4.41, 0.00, 102.44, 102.44 -GPS, 3, 308980600, 9, 1.75, 24.2398187, 54.5792873, 0.46, 10.63, 1.09, 122.11 -CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 1.22, 0.00, 3.91, 0.00, 103.11, 103.11 -CTUN, 0, 0.55, 0.70, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 2.55, 0.00, 4.65, 0.00, 103.50, 103.50 -DU32, 7, 426173 -CURR, 0, 297030, 1211, 0, 4772, 0.000000 -GPS, 3, 308980800, 9, 1.75, 24.2398176, 54.5792888, 0.49, 10.70, 0.93, 124.60 -CTUN, 0, 0.57, 0.68, 0.000000, 0, 0, -23, 0, 0 -ATT, 0.00, 3.63, 0.00, 5.71, 0.00, 103.80, 103.80 -CTUN, 0, 0.55, 0.75, 0.000000, 0, 0, -35, 0, 0 -ATT, 0.00, 3.84, 0.00, 6.11, 0.00, 104.06, 104.06 -GPS, 3, 308981000, 9, 1.75, 24.2398169, 54.5792898, 0.45, 10.63, 0.81, 127.13 -CTUN, 0, 0.55, 0.82, 0.000000, 0, 0, -33, 0, 0 -ATT, 0.00, 3.44, 0.00, 5.55, 0.00, 104.03, 104.03 -CTUN, 0, 0.54, 0.61, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, 2.55, 0.00, 4.47, 0.00, 103.61, 103.61 -GPS, 3, 308981200, 9, 1.75, 24.2398160, 54.5792908, 0.45, 10.54, 0.89, 131.80 -CTUN, 0, 0.54, 0.62, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 3.66, 0.00, 2.52, 0.00, 102.71, 102.71 -CTUN, 0, 0.49, 0.87, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 4.89, 0.00, 0.52, 0.00, 101.18, 101.18 -GPS, 3, 308981400, 9, 1.75, 24.2398148, 54.5792915, 0.47, 10.54, 0.75, 139.90 -CTUN, 0, 0.53, 0.91, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 4.60, 0.00, 0.07, 0.00, 99.46, 99.46 -CTUN, 0, 0.53, 1.03, 0.000000, 0, 0, -18, 0, 0 -ATT, 0.00, 3.49, 0.00, 0.85, 0.00, 98.69, 98.69 -GPS, 3, 308981600, 9, 1.75, 24.2398138, 54.5792925, 0.49, 10.55, 0.73, 142.17 -CTUN, 0, 0.55, 1.02, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 2.72, 0.00, 1.34, 0.00, 98.97, 98.97 -CTUN, 0, 0.55, 0.87, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 2.31, 0.00, 1.28, 0.00, 99.86, 99.86 -DU32, 7, 426173 -CURR, 0, 297030, 1211, 0, 4752, 0.000000 -GPS, 3, 308981800, 9, 1.75, 24.2398126, 54.5792935, 0.54, 10.53, 0.87, 142.38 -CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 1.52, 0.00, 0.48, 0.00, 101.15, 101.15 -CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 1.17, 0.00, 0.93, 0.00, 102.61, 102.61 -GPS, 3, 308982000, 9, 1.75, 24.2398114, 54.5792945, 0.58, 10.53, 0.86, 143.83 -CTUN, 0, 0.57, 0.85, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, 2.11, 0.00, 2.22, 0.00, 104.12, 104.12 -CTUN, 0, 0.55, 0.72, 0.000000, 0, 0, -32, 0, 0 -ATT, 0.00, 2.40, 0.00, 3.20, 0.00, 105.78, 105.78 -GPS, 3, 308982200, 9, 1.75, 24.2398102, 54.5792955, 0.55, 10.52, 0.88, 144.06 -CTUN, 0, 0.55, 0.63, 0.000000, 0, 0, -40, 0, 0 -ATT, 0.00, 2.21, 0.00, 3.51, 0.00, 107.22, 107.22 -CTUN, 0, 0.53, 0.67, 0.000000, 0, 0, -29, 0, 0 -ATT, 0.00, 1.90, 0.00, 3.76, 0.00, 107.76, 107.76 -GPS, 3, 308982400, 10, 1.49, 24.2398087, 54.5792966, 0.50, 10.47, 1.09, 143.33 -CTUN, 0, 0.53, 0.69, 0.000000, 0, 0, -24, 0, 0 -ATT, 0.00, 2.21, 0.00, 3.16, 0.00, 107.37, 107.37 -CTUN, 0, 0.44, 0.79, 0.000000, 0, 0, -21, 0, 0 -ATT, 0.00, 2.08, 0.00, 2.20, 0.00, 105.88, 105.88 -GPS, 3, 308982600, 10, 1.49, 24.2398074, 54.5792974, 0.48, 10.44, 0.92, 145.95 -CTUN, 0, 0.46, 0.74, 0.000000, 0, 0, -32, 0, 0 -ATT, 0.00, 1.67, 0.00, 1.51, 0.00, 103.73, 103.73 -CTUN, 0, 0.45, 0.88, 0.000000, 0, 0, -47, 0, 0 -ATT, 0.00, 0.64, 0.00, 1.12, 0.00, 102.04, 102.04 -DU32, 7, 426173 -CURR, 0, 297030, 1220, 0, 4752, 0.000000 -GPS, 3, 308982800, 10, 1.49, 24.2398061, 54.5792982, 0.43, 10.41, 0.84, 149.62 -CTUN, 0, 0.45, 0.64, 0.000000, 0, 0, -41, 0, 0 -ATT, 0.00, 1.36, 0.00, 0.38, 0.00, 100.90, 100.90 -CTUN, 0, 0.44, 0.69, 0.000000, 0, 0, -37, 0, 0 -ATT, 0.00, 2.07, 0.00, -1.15, 0.00, 100.38, 100.38 -GPS, 3, 308983000, 10, 1.49, 24.2398053, 54.5792990, 0.38, 10.30, 0.72, 145.42 -CTUN, 0, 0.44, 0.63, 0.000000, 0, 0, -55, 0, 0 -ATT, 0.00, 2.23, 0.00, -2.21, 0.00, 101.09, 101.09 -CTUN, 0, 0.39, 0.49, 0.000000, 0, 0, -69, 0, 0 -ATT, 0.00, 1.95, 0.00, -2.39, 0.00, 102.55, 102.55 -GPS, 3, 308983200, 10, 1.49, 24.2398043, 54.5792999, 0.27, 10.25, 0.69, 144.51 -CTUN, 0, 0.39, 0.34, 0.000000, 0, 0, -83, 0, 0 -ATT, 0.00, 2.33, 0.00, -1.19, 0.00, 103.20, 103.20 -CTUN, 0, 0.29, 0.28, 0.000000, 0, 0, -86, 0, 0 -ATT, 0.00, 1.40, 0.00, 1.02, 0.00, 103.32, 103.32 -GPS, 3, 308983400, 10, 1.49, 24.2398034, 54.5793010, 0.12, 10.10, 0.89, 137.08 -CTUN, 0, 0.29, 0.08, 0.000000, 0, 0, -71, 0, 0 -ATT, 0.00, 0.40, 0.00, 2.72, 0.00, 102.94, 102.94 -CTUN, 0, 0.17, 0.00, 0.000000, 0, 0, -57, 0, 0 -ATT, 0.00, 1.17, 0.00, 2.02, 0.00, 102.25, 102.25 -GPS, 3, 308983600, 10, 1.49, 24.2398027, 54.5793015, 0.00, 9.92, 0.61, 139.64 -CTUN, 0, 0.17, -0.07, 0.000000, 0, 0, -47, 0, 0 -ATT, 0.00, 0.78, 0.00, -0.67, 0.00, 101.02, 101.02 -CTUN, 0, 0.17, -0.09, 0.000000, 0, 0, -37, 0, 0 -ATT, 0.00, 0.73, 0.00, -1.93, 0.00, 99.80, 99.80 -DU32, 7, 426173 -CURR, 0, 297030, 1210, 0, 4772, 0.000000 -GPS, 3, 308983800, 10, 1.49, 24.2398025, 54.5793017, -0.08, 9.82, 0.22, 139.64 -CTUN, 0, 0.17, -0.20, 0.000000, 0, 0, -31, 0, 0 -ATT, 0.00, 0.74, 0.00, -2.06, 0.00, 98.52, 98.52 -CTUN, 0, 0.17, -0.13, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.90, 0.00, -0.44, 0.00, 98.26, 98.26 -GPS, 3, 308984000, 10, 1.49, 24.2398023, 54.5793016, -0.12, 9.78, 0.18, 139.64 -CTUN, 0, 0.20, -0.10, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.73, 0.00, -0.37, 0.00, 98.23, 98.23 -CTUN, 0, 0.20, -0.15, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.71, 0.00, -0.31, 0.00, 98.24, 98.24 -GPS, 3, 308984200, 10, 1.49, 24.2398023, 54.5793016, -0.14, 9.78, 0.12, 139.64 -CTUN, 0, 0.22, -0.22, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.68, 0.00, -0.26, 0.00, 98.24, 98.24 -CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.64, 0.00, -0.27, 0.00, 98.24, 98.24 -GPS, 3, 308984400, 9, 1.75, 24.2398026, 54.5793015, -0.17, 9.74, 0.11, 139.64 -CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.61, 0.00, -0.27, 0.00, 98.24, 98.24 -CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.59, 0.00, -0.28, 0.00, 98.25, 98.25 -GPS, 3, 308984600, 10, 1.49, 24.2398027, 54.5793016, -0.20, 9.75, 0.04, 139.64 -CTUN, 0, 0.22, -0.11, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.57, 0.00, -0.30, 0.00, 98.25, 98.25 -CTUN, 0, 0.22, -0.11, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.56, 0.00, -0.34, 0.00, 98.25, 98.25 -DU32, 7, 426173 -CURR, 0, 297030, 1215, 0, 4772, 0.000000 -GPS, 3, 308984800, 10, 1.49, 24.2398026, 54.5793017, -0.21, 9.77, 0.03, 139.64 -CTUN, 0, 0.22, 0.03, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.56, 0.00, -0.37, 0.00, 98.26, 98.26 -CTUN, 0, 0.22, -0.06, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.57, 0.00, -0.37, 0.00, 98.26, 98.26 -GPS, 3, 308985000, 10, 1.49, 24.2398029, 54.5793018, -0.21, 9.75, 0.08, 139.64 -CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.57, 0.00, -0.38, 0.00, 98.27, 98.27 -CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.53, 0.00, -0.38, 0.00, 98.27, 98.27 -GPS, 3, 308985200, 9, 1.75, 24.2398029, 54.5793020, -0.22, 9.78, 0.09, 139.64 -CTUN, 0, 0.22, -0.28, 0.000000, 0, 0, -11, 0, 0 -ATT, 0.00, 0.51, 0.00, -0.39, 0.00, 98.28, 98.28 -CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.52, 0.00, -0.42, 0.00, 98.28, 98.28 -GPS, 3, 308985400, 10, 1.49, 24.2398029, 54.5793019, -0.25, 9.78, 0.06, 139.64 -CTUN, 0, 0.22, -0.29, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.52, 0.00, -0.43, 0.00, 98.29, 98.29 -CTUN, 0, 0.22, -0.29, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.53, 0.00, -0.39, 0.00, 98.30, 98.30 -GPS, 3, 308985600, 10, 1.49, 24.2398028, 54.5793018, -0.28, 9.81, 0.04, 139.64 -CTUN, 0, 0.22, -0.23, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.53, 0.00, -0.37, 0.00, 98.30, 98.30 -CTUN, 0, 0.22, -0.37, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.51, 0.00, -0.38, 0.00, 98.31, 98.31 -DU32, 7, 426173 -CURR, 0, 297030, 1221, 0, 4752, 0.000000 -GPS, 3, 308985800, 10, 1.49, 24.2398028, 54.5793019, -0.31, 9.84, 0.08, 139.64 -CTUN, 0, 0.22, -0.41, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.50, 0.00, -0.40, 0.00, 98.31, 98.31 -CTUN, 0, 0.22, -0.39, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.48, 0.00, -0.44, 0.00, 98.32, 98.32 -GPS, 3, 308986000, 10, 1.49, 24.2398030, 54.5793019, -0.34, 9.82, 0.07, 139.64 -CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.46, 0.00, -0.46, 0.00, 98.32, 98.32 -CTUN, 0, 0.22, -0.22, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.45, 0.00, -0.42, 0.00, 98.33, 98.33 -GPS, 3, 308986200, 10, 1.49, 24.2398031, 54.5793020, -0.36, 9.85, 0.01, 139.64 -CTUN, 0, 0.22, -0.26, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.44, 0.00, -0.40, 0.00, 98.33, 98.33 -CTUN, 0, 0.22, -0.23, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.44, 0.00, -0.43, 0.00, 98.33, 98.33 -GPS, 3, 308986400, 10, 1.49, 24.2398030, 54.5793020, -0.37, 9.85, 0.02, 139.64 -CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.44, 0.00, -0.44, 0.00, 98.34, 98.34 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.44, 0.00, -0.45, 0.00, 98.35, 98.35 -GPS, 3, 308986600, 10, 1.49, 24.2398029, 54.5793021, -0.40, 9.88, 0.02, 139.64 -CTUN, 0, 0.22, -0.41, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.44, 0.00, -0.46, 0.00, 98.35, 98.35 -CTUN, 0, 0.22, -0.32, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.43, 0.00, -0.47, 0.00, 98.36, 98.36 -DU32, 7, 426173 -CURR, 0, 297030, 1219, 0, 4772, 0.000000 -GPS, 3, 308986800, 10, 1.49, 24.2398029, 54.5793022, -0.42, 9.92, 0.00, 139.64 -CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.42, 0.00, -0.48, 0.00, 98.36, 98.36 -CTUN, 0, 0.22, -0.39, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.41, 0.00, -0.48, 0.00, 98.37, 98.37 -GPS, 3, 308987000, 10, 1.49, 24.2398028, 54.5793020, -0.44, 9.92, 0.03, 139.64 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.40, 0.00, -0.48, 0.00, 98.37, 98.37 -CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.38, 0.00, -0.49, 0.00, 98.38, 98.38 -GPS, 3, 308987200, 10, 1.49, 24.2398027, 54.5793020, -0.45, 9.93, 0.01, 139.64 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.37, 0.00, -0.50, 0.00, 98.39, 98.39 -CTUN, 0, 0.22, -0.25, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.37, 0.00, -0.50, 0.00, 98.39, 98.39 -GPS, 3, 308987400, 10, 1.49, 24.2398026, 54.5793021, -0.46, 9.95, 0.01, 139.64 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.36, 0.00, -0.51, 0.00, 98.40, 98.40 -CTUN, 0, 0.22, -0.45, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.36, 0.00, -0.50, 0.00, 98.41, 98.41 -GPS, 3, 308987600, 10, 1.49, 24.2398026, 54.5793020, -0.48, 9.96, 0.02, 139.64 -CTUN, 0, 0.24, -0.59, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.35, 0.00, -0.50, 0.00, 98.41, 98.41 -CTUN, 0, 0.22, -0.50, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.34, 0.00, -0.50, 0.00, 98.42, 98.42 -DU32, 7, 426173 -CURR, 0, 297030, 1213, 0, 4793, 0.000000 -GPS, 3, 308987800, 10, 1.49, 24.2398026, 54.5793021, -0.52, 9.97, 0.02, 139.64 -CTUN, 0, 0.22, -0.42, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.34, 0.00, -0.51, 0.11, 98.42, 98.42 -CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.33, 0.00, -0.52, 0.00, 98.43, 98.43 -GPS, 3, 308988000, 9, 1.96, 24.2398025, 54.5793020, -0.53, 10.00, 0.01, 139.64 -CTUN, 0, 0.22, -0.40, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.32, 0.00, -0.53, 0.00, 98.43, 98.43 -CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.31, 0.00, -0.53, 0.00, 98.44, 98.44 -GPS, 3, 308988200, 9, 1.96, 24.2398024, 54.5793020, -0.55, 10.02, 0.02, 139.64 -CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.30, 0.00, -0.53, 0.00, 98.45, 98.45 -CTUN, 0, 0.22, -0.38, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.29, 0.00, -0.54, 0.00, 98.46, 98.46 -GPS, 3, 308988400, 10, 1.49, 24.2398023, 54.5793020, -0.56, 10.04, 0.00, 139.64 -CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.28, 0.00, -0.54, 0.00, 98.46, 98.46 -PM, 0, 0, 50, 0, 1000, 10500, 9, 0 -CTUN, 0, 0.22, -0.46, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.28, 0.00, -0.55, 0.00, 98.46, 98.46 -GPS, 3, 308988600, 10, 1.49, 24.2398022, 54.5793020, -0.58, 10.05, 0.00, 139.64 -CTUN, 0, 0.22, -0.54, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.27, 0.00, -0.55, 0.00, 98.47, 98.47 -CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.26, 0.00, -0.55, 0.00, 98.47, 98.47 -DU32, 7, 426173 -CURR, 0, 297030, 1216, 0, 4772, 0.000000 -GPS, 3, 308988800, 10, 1.49, 24.2398022, 54.5793019, -0.59, 10.05, 0.02, 139.64 -CTUN, 0, 0.24, -0.43, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.26, 0.00, -0.56, 0.00, 98.48, 98.48 -CTUN, 0, 0.22, -0.42, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.26, 0.00, -0.56, 0.00, 98.48, 98.48 -GPS, 3, 308989000, 10, 1.49, 24.2398021, 54.5793020, -0.61, 10.07, 0.01, 139.64 -CTUN, 0, 0.22, -0.46, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.25, 0.00, -0.57, 0.00, 98.49, 98.49 -CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.24, 0.00, -0.57, 0.00, 98.50, 98.50 -GPS, 3, 308989200, 10, 1.49, 24.2398021, 54.5793020, -0.62, 10.07, 0.02, 139.64 -CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.23, 0.00, -0.58, 0.00, 98.50, 98.50 -CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.23, 0.00, -0.58, 0.00, 98.51, 98.51 -GPS, 3, 308989400, 10, 1.49, 24.2398021, 54.5793019, -0.62, 10.07, 0.01, 139.64 -CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.23, 0.00, -0.59, 0.00, 98.51, 98.51 -CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.21, 0.00, -0.59, 0.00, 98.52, 98.52 -GPS, 3, 308989600, 10, 1.49, 24.2398020, 54.5793020, -0.62, 10.10, 0.01, 139.64 -CTUN, 0, 0.22, -0.45, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.21, 0.00, -0.59, 0.00, 98.53, 98.53 -CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.21, 0.00, -0.60, 0.00, 98.53, 98.53 -DU32, 7, 426173 -CURR, 0, 297030, 1216, 0, 4752, 0.000000 -GPS, 3, 308989800, 10, 1.49, 24.2398020, 54.5793021, -0.62, 10.12, 0.01, 139.64 -CTUN, 0, 0.22, -0.47, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.20, 0.00, -0.60, 0.00, 98.54, 98.54 -CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.18, 0.00, -0.61, 0.00, 98.55, 98.55 -GPS, 3, 308990000, 10, 1.49, 24.2398019, 54.5793021, -0.62, 10.14, 0.02, 139.64 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.16, 0.00, -0.61, 0.00, 98.56, 98.56 -CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.15, 0.00, -0.61, 0.00, 98.57, 98.57 -GPS, 3, 308990200, 10, 1.49, 24.2398019, 54.5793022, -0.61, 10.16, 0.01, 139.64 -CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.13, 0.00, -0.61, 0.00, 98.58, 98.58 -CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.12, 0.00, -0.62, 0.00, 98.59, 98.59 -GPS, 3, 308990400, 10, 1.49, 24.2398018, 54.5793022, -0.61, 10.18, 0.00, 139.64 -CTUN, 0, 0.22, -0.25, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.11, 0.00, -0.62, 0.00, 98.60, 98.60 -CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.10, 0.00, -0.62, 0.00, 98.61, 98.61 -GPS, 3, 308990600, 10, 1.49, 24.2398017, 54.5793022, -0.59, 10.19, 0.01, 139.64 -CTUN, 0, 0.22, -0.28, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.09, 0.00, -0.62, 0.00, 98.61, 98.61 -CTUN, 0, 0.22, -0.24, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.09, 0.00, -0.63, 0.00, 98.62, 98.62 -DU32, 7, 426173 -CURR, 0, 297030, 1217, 0, 4772, 0.000000 -EV, 11 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -PM, 0, 0, 51, 4, 1000, 115952, 11, 0 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -PM, 0, 0, 50, 5, 1000, 11076, 10, 0 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -PM, 0, 0, 50, 3, 1000, 11148, 10, 0 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -PM, 0, 0, 52, 13, 1000, 58732, 9, 0 -DU32, 7, 393405 -DU32, 7, 393405 -DU32, 7, 393405 -D32, 9, 10034 -CMD, 9, 0, 16, 0, 0, 0.00, 24.2397986, 54.5793039 -EV, 10 -GPS, 3, 309032600, 10, 1.49, 24.2397986, 54.5793039, -0.46, 12.10, 0.01, 139.64 -DU32, 7, 393405 -CURR, 0, 297030, 1212, 0, 4772, 0.000000 -GPS, 3, 309034600, 10, 1.49, 24.2397986, 54.5793039, -0.46, 12.13, 0.01, 139.64 -CTUN, 0, 0.22, 0.02, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.34, 100.34 -CTUN, 0, 0.22, 0.10, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, -0.60, 0.00, -0.59, 0.00, 100.34, 100.34 -GPS, 3, 309034800, 10, 1.49, 24.2397986, 54.5793038, -0.40, 12.13, 0.01, 139.64 -CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, -0.60, 0.00, -0.58, 0.00, 100.33, 100.33 -CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, -0.61, 0.00, -0.59, 0.00, 100.33, 100.33 -GPS, 3, 309035000, 10, 1.49, 24.2397986, 54.5793038, -0.35, 12.13, 0.01, 139.64 -CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -0.61, 0.00, -0.59, 0.00, 100.33, 100.33 -CTUN, 0, 0.22, 0.09, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -0.60, 0.00, -0.59, 0.11, 100.33, 100.33 -GPS, 3, 309035200, 10, 1.49, 24.2397986, 54.5793038, -0.30, 12.14, 0.01, 139.64 -CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 4, 0, 0 -EV, 15 -ATT, 0.00, -0.60, 0.00, -0.59, 0.00, 100.32, 100.32 -CTUN, 278, 0.22, -0.10, 0.000000, 0, 0, 4, 256, 0 -ATT, 0.00, -0.60, 0.00, -0.60, 0.00, 100.32, 100.32 -GPS, 3, 309035400, 10, 1.49, 24.2397986, 54.5793038, -0.27, 12.14, 0.00, 139.64 -CTUN, 285, 0.22, -0.04, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.60, 0.00, -0.61, 0.00, 100.32, 100.32 -CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.32, 100.32 -GPS, 3, 309035600, 10, 1.49, 24.2397985, 54.5793039, -0.23, 12.15, 0.02, 139.64 -CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 4, 285, 0 -DU32, 7, 393469 -CURR, 285, 298109, 1213, 0, 4772, 0.000000 -ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.32, 100.32 -CTUN, 285, 0.22, -0.13, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 -GPS, 3, 309035800, 10, 1.49, 24.2397985, 54.5793039, -0.21, 12.15, 0.01, 139.64 -CTUN, 286, 0.22, 0.06, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 -CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 -GPS, 3, 309036000, 10, 1.49, 24.2397985, 54.5793039, -0.17, 12.16, 0.01, 139.64 -CTUN, 285, 0.22, -0.03, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.61, 0.00, 100.32, 100.32 -CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.33, 100.32 -GPS, 3, 309036200, 10, 1.49, 24.2397985, 54.5793039, -0.13, 12.16, 0.00, 139.64 -CTUN, 285, 0.22, 0.11, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.62, 0.00, 100.33, 100.32 -CTUN, 285, 0.22, 0.21, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.62, 0.00, 100.33, 100.32 -GPS, 3, 309036400, 10, 1.49, 24.2397985, 54.5793039, -0.09, 12.16, 0.01, 139.64 -CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.32, 100.32 -CTUN, 285, 0.22, 0.13, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.32, 100.32 -GPS, 3, 309036600, 10, 1.49, 24.2397985, 54.5793039, -0.05, 12.17, 0.01, 139.64 -CTUN, 285, 0.22, 0.15, 0.000000, 0, 0, 8, 285, 0 -DU32, 7, 393469 -CURR, 286, 300963, 1214, 0, 4772, 0.000000 -ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.32, 100.32 -CTUN, 286, 0.22, 0.02, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.33, 100.32 -GPS, 3, 309036800, 10, 1.49, 24.2397985, 54.5793039, -0.02, 12.17, 0.00, 139.64 -CTUN, 285, 0.22, 0.06, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.33, 100.32 -CTUN, 285, 0.22, 0.09, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.33, 100.32 -GPS, 3, 309037000, 10, 1.49, 24.2397985, 54.5793039, 0.00, 12.18, 0.01, 139.64 -CTUN, 286, 0.22, 0.17, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.64, 0.00, 100.33, 100.32 -CTUN, 286, 0.22, 0.12, 0.000000, 0, 0, 9, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.64, 0.00, 100.33, 100.32 -GPS, 3, 309037200, 10, 1.49, 24.2397984, 54.5793040, 0.04, 12.18, 0.01, 139.64 -CTUN, 285, 0.22, -0.18, 0.000000, 0, 0, 9, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.64, 0.00, 100.33, 100.32 -CTUN, 286, 0.22, -0.23, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 -GPS, 3, 309037400, 10, 1.49, 24.2397984, 54.5793040, 0.03, 12.19, 0.00, 139.64 -CTUN, 285, 0.22, -0.21, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 -CTUN, 286, 0.22, -0.15, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 -GPS, 3, 309037600, 10, 1.49, 24.2397984, 54.5793040, 0.02, 12.20, 0.00, 139.64 -CTUN, 286, 0.22, -0.18, 0.000000, 0, 0, 8, 286, 0 -DU32, 7, 393469 -CURR, 285, 303819, 1219, 0, 4752, 0.000000 -ATT, 0.00, -0.63, 0.00, -0.65, 0.00, 100.33, 100.32 -CTUN, 285, 0.22, -0.08, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.33, 100.32 -GPS, 3, 309037800, 10, 1.49, 24.2397984, 54.5793040, 0.01, 12.20, 0.02, 139.64 -CTUN, 286, 0.22, -0.05, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.33, 100.32 -CTUN, 285, 0.22, -0.12, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 -GPS, 3, 309038000, 10, 1.49, 24.2397984, 54.5793040, 0.02, 12.21, 0.01, 139.64 -CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.67, 0.00, 100.34, 100.32 -CTUN, 286, 0.22, 0.11, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 -GPS, 3, 309038200, 10, 1.49, 24.2397984, 54.5793041, 0.04, 12.21, 0.01, 139.64 -CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 -CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.67, 0.00, 100.35, 100.32 -GPS, 3, 309038400, 10, 1.49, 24.2397984, 54.5793041, 0.04, 12.22, 0.01, 139.64 -CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.68, 0.00, -0.67, 0.00, 100.31, 100.32 -CTUN, 285, 0.24, -0.02, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.68, 0.00, 100.33, 100.32 -GPS, 3, 309038600, 10, 1.49, 24.2397984, 54.5793041, 0.05, 12.22, 0.01, 139.64 -CTUN, 286, 0.22, 0.16, 0.000000, 0, 0, 7, 286, 0 -DU32, 7, 393469 -CURR, 286, 306673, 1213, 0, 4752, 0.000000 -ATT, 0.00, -0.65, 0.00, -0.68, 0.00, 100.33, 100.32 -CTUN, 286, 0.24, 0.19, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.34, 100.32 -GPS, 3, 309038800, 10, 1.49, 24.2397983, 54.5793041, 0.08, 12.23, 0.02, 139.64 -CTUN, 286, 0.22, 0.24, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.64, 0.00, -0.69, 0.00, 100.35, 100.32 -CTUN, 285, 0.22, 0.06, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.64, 0.00, -0.68, 0.00, 100.35, 100.32 -GPS, 3, 309039000, 10, 1.49, 24.2397983, 54.5793041, 0.10, 12.23, 0.03, 139.64 -CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.64, 0.00, -0.67, 0.00, 100.35, 100.32 -CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 8, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.35, 100.32 -GPS, 3, 309039200, 10, 1.49, 24.2397984, 54.5793041, 0.11, 12.25, 0.04, 139.64 -CTUN, 286, 0.22, 0.00, 0.000000, 0, 0, 8, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.36, 100.32 -CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.36, 100.32 -GPS, 3, 309039400, 10, 1.49, 24.2397983, 54.5793041, 0.11, 12.26, 0.01, 139.64 -CTUN, 285, 0.22, 0.09, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.66, 0.00, -0.69, 0.00, 100.37, 100.32 -CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.37, 100.32 -GPS, 3, 309039600, 10, 1.49, 24.2397983, 54.5793041, 0.12, 12.26, 0.04, 139.64 -CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 7, 286, 0 -DU32, 7, 393469 -CURR, 286, 309529, 1216, 0, 4772, 0.000000 -ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.38, 100.32 -CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.70, 0.00, 100.38, 100.32 -GPS, 3, 309039800, 10, 1.49, 24.2397982, 54.5793042, 0.11, 12.26, 0.05, 139.64 -CTUN, 285, 0.22, -0.04, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.70, 0.00, 100.38, 100.32 -CTUN, 285, 0.22, 0.01, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.72, 0.00, 100.39, 100.32 -GPS, 3, 309040000, 10, 1.49, 24.2397983, 54.5793041, 0.11, 12.27, 0.01, 139.64 -CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.72, 0.00, 100.39, 100.32 -CTUN, 286, 0.22, -0.01, 0.000000, 0, 0, 6, 286, 0 -ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.39, 100.32 -GPS, 3, 309040200, 10, 1.49, 24.2397983, 54.5793041, 0.10, 12.29, 0.02, 139.64 -CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 6, 286, 0 -ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.40, 100.32 -CTUN, 285, 0.22, -0.01, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.40, 100.32 -GPS, 3, 309040400, 10, 1.49, 24.2397984, 54.5793040, 0.10, 12.30, 0.03, 139.64 -CTUN, 286, 0.22, -0.09, 0.000000, 0, 0, 5, 285, 0 -ATT, 0.00, -0.64, 0.00, -0.69, 0.00, 100.41, 100.32 -CTUN, 286, 0.22, -0.10, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.66, 0.00, -0.69, 0.00, 100.41, 100.32 -GPS, 3, 309040600, 10, 1.49, 24.2397984, 54.5793041, 0.09, 12.30, 0.01, 139.64 -CTUN, 286, 0.22, 0.00, 0.000000, 0, 0, 5, 286, 0 -DU32, 7, 393469 -CURR, 286, 312385, 1219, 0, 4772, 0.000000 -ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.41, 100.32 -CTUN, 285, 0.22, 0.05, 0.000000, 0, 0, 5, 285, 0 -ATT, 0.00, -0.65, 0.00, -0.70, 0.00, 100.41, 100.32 -GPS, 3, 309040800, 10, 1.49, 24.2397984, 54.5793041, 0.09, 12.30, 0.01, 139.64 -CTUN, 285, 0.22, -0.07, 0.000000, 0, 0, 5, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.71, 0.00, 100.42, 100.32 -CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 5, 285, 0 -ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.42, 100.32 -GPS, 3, 309041000, 10, 1.49, 24.2397984, 54.5793041, 0.08, 12.29, 0.01, 139.64 -CTUN, 286, 0.22, -0.10, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.70, 0.00, 100.42, 100.32 -CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.60, 0.00, -0.71, 0.00, 100.43, 100.32 -PM, 0, 0, 51, 4, 1001, 2106108, 11, 0 -GPS, 3, 309041200, 10, 1.49, 24.2397984, 54.5793041, 0.07, 12.30, 0.02, 139.64 -CTUN, 286, 0.22, 0.06, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.64, 0.00, -0.71, 0.00, 100.43, 100.32 -CTUN, 285, 0.22, -0.01, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.61, 0.00, -0.71, 0.00, 100.43, 100.32 -GPS, 3, 309041400, 10, 1.49, 24.2397984, 54.5793041, 0.08, 12.30, 0.01, 139.64 -CTUN, 285, 0.22, -0.03, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.61, 0.00, -0.70, 0.00, 100.41, 100.32 -CTUN, 286, 0.22, -0.20, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.39, 100.32 -GPS, 3, 309041600, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.29, 0.02, 139.64 -CTUN, 286, 0.22, -0.12, 0.000000, 0, 0, 4, 286, 0 -DU32, 7, 393469 -CURR, 286, 315239, 1209, 0, 4732, 0.000000 -ATT, 0.00, -0.58, 0.00, -0.73, 0.00, 100.39, 100.32 -CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 3, 286, 0 -ATT, 0.00, -0.46, 0.00, -0.83, 0.00, 100.20, 100.32 -GPS, 3, 309041800, 10, 1.49, 24.2397984, 54.5793041, 0.05, 12.29, 0.01, 139.64 -CTUN, 285, 0.22, -0.26, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.63, 0.00, -0.77, 0.00, 99.46, 100.32 -CTUN, 285, 0.24, -0.28, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.88, 0.00, -0.50, 0.00, 98.85, 100.32 -GPS, 3, 309042000, 10, 1.49, 24.2397984, 54.5793042, 0.02, 12.29, 0.01, 139.64 -CTUN, 285, 0.24, -0.17, 0.000000, 0, 0, 0, 285, 0 -ATT, 0.00, -0.45, 0.00, -0.59, 0.00, 97.84, 100.32 -CTUN, 286, 0.26, -0.22, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.72, 0.00, -0.44, 0.00, 97.00, 100.32 -GPS, 3, 309042200, 10, 1.49, 24.2397984, 54.5793041, 0.00, 12.29, 0.02, 139.64 -CTUN, 286, 0.26, -0.12, 0.000000, 0, 0, 3, 286, 0 -ATT, 0.00, -0.37, 0.00, -0.57, 0.00, 96.09, 100.32 -CTUN, 286, 0.30, -0.13, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.30, 0.00, -0.41, 0.00, 95.14, 100.32 -GPS, 3, 309042400, 10, 1.49, 24.2397983, 54.5793041, 0.00, 12.28, 0.02, 139.64 -CTUN, 285, 0.30, -0.30, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.44, 0.00, -0.35, 0.00, 94.10, 100.32 -CTUN, 285, 0.30, -0.17, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.57, 0.00, -0.41, 0.00, 93.16, 100.32 -GPS, 3, 309042600, 10, 1.49, 24.2397983, 54.5793041, -0.02, 12.28, 0.01, 139.64 -CTUN, 286, 0.26, -0.30, 0.000000, 0, 0, 3, 286, 0 -DU32, 7, 393469 -CURR, 286, 318093, 1202, 0, 4772, 0.000000 -ATT, 0.00, -0.56, 0.00, -0.46, 0.00, 92.29, 100.32 -CTUN, 286, 0.26, -0.29, 0.000000, 0, 0, 1, 286, 0 -ATT, 0.00, -0.44, 0.00, -0.44, 0.00, 91.80, 100.32 -GPS, 3, 309042800, 10, 1.49, 24.2397983, 54.5793041, -0.04, 12.28, 0.01, 139.64 -CTUN, 286, 0.26, -0.15, 0.000000, 0, 0, 4, 286, 0 -ATT, 0.00, -0.34, 0.00, -0.45, 0.00, 91.75, 100.32 -CTUN, 286, 0.55, -0.14, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.30, 0.00, -0.48, 0.00, 91.55, 100.32 -GPS, 3, 309043000, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 -CTUN, 285, 0.36, -0.12, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.28, 0.00, -0.51, 0.00, 91.46, 100.32 -CTUN, 285, 0.38, -0.19, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.43, 0.00, -0.51, 0.00, 91.47, 100.32 -GPS, 3, 309043200, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.02, 139.64 -CTUN, 286, 0.38, -0.16, 0.000000, 0, 0, 5, 285, 0 -ATT, 0.00, -0.29, 0.00, -0.51, 0.00, 91.50, 100.32 -CTUN, 286, 0.38, -0.14, 0.000000, 0, 0, 6, 286, 0 -ATT, 0.00, -0.45, 0.00, -0.50, 0.00, 91.57, 100.32 -GPS, 3, 309043400, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 -CTUN, 286, 0.38, -0.13, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.39, 0.00, -0.44, 0.00, 91.70, 100.32 -CTUN, 286, 0.38, -0.24, 0.000000, 0, 0, 5, 286, 0 -ATT, 0.00, -0.37, 0.00, -0.44, 0.00, 91.89, 100.32 -GPS, 3, 309043600, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.02, 139.64 -CTUN, 285, 0.38, -0.15, 0.000000, 0, 0, 6, 285, 0 -DU32, 7, 393469 -CURR, 285, 320949, 1174, 0, 4772, 0.000000 -ATT, 0.00, -0.48, 0.00, -0.44, 0.00, 92.11, 100.32 -CTUN, 285, 0.53, -0.07, 0.000000, 0, 0, 6, 285, 0 -ATT, 0.00, -0.49, 0.00, -0.37, 0.00, 92.36, 100.32 -GPS, 3, 309043800, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 -CTUN, 285, 0.39, -0.10, 0.000000, 0, 0, 7, 285, 0 -ATT, 0.00, -0.50, 0.00, -0.25, 0.00, 93.00, 100.32 -CTUN, 286, 0.53, -0.07, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.52, 0.00, -0.20, 0.00, 93.82, 100.32 -GPS, 3, 309044000, 10, 1.49, 24.2397983, 54.5793041, -0.04, 12.30, 0.00, 139.64 -CTUN, 286, 0.53, -0.07, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.52, 0.00, -0.11, 0.00, 94.96, 100.32 -CTUN, 286, 0.53, -0.28, 0.000000, 0, 0, 7, 286, 0 -ATT, 0.00, -0.49, 0.00, -0.21, 0.00, 96.44, 100.32 -GPS, 3, 309044200, 10, 1.49, 24.2397983, 54.5793041, -0.03, 12.30, 0.02, 139.64 -CTUN, 286, 0.34, -0.04, 0.000000, 0, 0, 10, 286, 0 -ATT, 0.00, -0.67, 0.00, -0.36, 0.00, 98.04, 100.32 -CTUN, 285, 0.34, 0.01, 0.000000, 0, 0, 9, 285, 0 -ATT, 0.00, -0.84, 0.00, -0.34, 0.00, 99.56, 100.32 -GPS, 3, 309044400, 10, 1.49, 24.2397983, 54.5793041, -0.02, 12.30, 0.01, 139.64 -CTUN, 285, 0.34, -0.06, 0.000000, 0, 0, 10, 285, 0 -ATT, 0.00, -0.66, 0.00, -0.17, 0.00, 101.29, 100.32 -CTUN, 285, 0.34, 0.09, 0.000000, 0, 0, 11, 285, 0 -ATT, 0.00, -0.72, 0.00, -0.33, 0.00, 102.89, 100.32 -GPS, 3, 309044600, 10, 1.49, 24.2397983, 54.5793041, 0.00, 12.31, 0.01, 139.64 -CTUN, 285, 0.26, -0.02, 0.000000, 0, 0, 13, 286, 0 -ATT, 0.00, -0.55, 0.00, -0.29, 0.00, 104.20, 100.32 -DU32, 7, 393469 -CURR, 286, 323804, 1192, 0, 4752, 0.000000 -CTUN, 286, 0.26, 0.00, 0.000000, 0, 0, 12, 286, 0 -ATT, 0.00, -0.66, 0.00, -0.39, 0.00, 105.22, 100.32 -GPS, 3, 309044800, 10, 1.49, 24.2397983, 54.5793041, 0.02, 12.31, 0.03, 139.64 -CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 11, 286, 0 -ATT, 0.00, -0.60, 0.00, -0.45, 0.00, 106.19, 100.32 -CTUN, 285, 0.26, -0.01, 0.000000, 0, 0, 15, 285, 0 -ATT, 0.00, -0.48, 0.00, -0.47, 0.00, 106.71, 100.32 -GPS, 3, 309045000, 10, 1.49, 24.2397983, 54.5793041, 0.04, 12.31, 0.01, 139.64 -CTUN, 285, 0.26, -0.02, 0.000000, 0, 0, 14, 285, 0 -ATT, 0.00, -0.48, 0.00, -0.45, 0.00, 107.28, 100.32 -CTUN, 286, 0.40, -0.18, 0.000000, 0, 0, 15, 285, 0 -ATT, 0.00, -0.54, 0.00, -0.45, 0.00, 107.80, 100.32 -GPS, 3, 309045200, 10, 1.49, 24.2397983, 54.5793042, 0.05, 12.31, 0.02, 139.64 -CTUN, 285, 0.40, -0.12, 0.000000, 0, 0, 14, 286, 0 -ATT, 0.00, -0.59, 0.00, -0.37, 0.00, 108.32, 100.32 -CTUN, 286, 0.40, -0.01, 0.000000, 0, 0, 11, 286, 0 -ATT, 0.00, -0.67, 0.00, -0.32, 0.00, 108.76, 100.32 -GPS, 3, 309045400, 10, 1.49, 24.2397984, 54.5793042, 0.06, 12.31, 0.02, 139.64 -CTUN, 285, 0.25, 0.02, 0.000000, 0, 0, 11, 285, 0 -ATT, 0.00, -0.62, 0.00, -0.28, 0.00, 109.21, 100.32 -CTUN, 285, 0.25, -0.09, 0.000000, 0, 0, 11, 285, 0 -ATT, 0.00, -0.51, 0.00, -0.29, 0.00, 109.87, 100.32 -GPS, 3, 309045600, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.02, 139.64 -CTUN, 286, 0.20, -0.24, 0.000000, 0, 0, 16, 286, 0 -ATT, 0.00, -0.55, 0.00, -0.32, 0.00, 110.26, 100.32 -DU32, 7, 393469 -CURR, 286, 326658, 1156, 0, 4793, 0.000000 -CTUN, 286, 0.20, -0.27, 0.000000, 0, 0, 16, 286, 0 -ATT, 0.00, -0.79, 0.00, -0.33, 0.00, 110.66, 100.66 -GPS, 3, 309045800, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.02, 139.64 -CTUN, 286, 0.15, -0.14, 0.000000, 0, 0, 10, 286, 0 -ATT, 0.00, -0.81, 0.00, -0.25, 0.00, 111.60, 101.60 -CTUN, 285, 0.16, 0.01, 0.000000, 0, 0, 15, 285, 0 -ATT, 0.00, -0.47, 0.00, -0.18, 0.00, 112.94, 102.94 -GPS, 3, 309046000, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.01, 139.64 -CTUN, 285, 0.16, 0.00, 0.000000, 0, 0, 20, 285, 0 -ATT, 0.00, -0.54, 0.00, -0.11, 0.00, 113.50, 103.50 -CTUN, 286, 0.29, -0.16, 0.000000, 0, 0, 20, 286, 0 -ATT, 0.00, -0.60, 0.00, 0.06, 0.00, 114.38, 104.38 -GPS, 3, 309046200, 10, 1.49, 24.2397984, 54.5793042, 0.09, 12.32, 0.01, 139.64 -CTUN, 286, 0.29, 0.00, 0.000000, 0, 0, 4, 285, 0 -ATT, 0.00, -0.49, 0.00, 0.09, 0.00, 115.92, 105.92 -CTUN, 285, 0.30, 0.08, 0.000000, 0, 0, -34, 286, 0 -ATT, 0.00, -0.53, 0.00, 0.06, 0.00, 117.79, 107.79 -MODE, AUTO, 470 -GPS, 3, 309046400, 10, 1.49, 24.2397984, 54.5793043, 0.03, 12.32, 0.01, 139.64 -CTUN, 285, 0.30, -0.07, 0.000000, 0, 0, -73, 286, 0 -CMD, 9, 1, 22, 1, 0, 7.62, 0.0000000, 0.0000000 -ATT, -0.43, -0.54, 0.12, 0.13, 0.00, 119.88, 109.88 -CTUN, 285, 0.30, 0.30, -0.025654, 0, 0, -109, 524, 0 -NTUN, 0.00, 0.00, 81.094238, 19.787561, 81.094238, 19.787561, 86.690399, 9.314609, -5.000000, 10.000000, -0.04, -0.65 -ATT, -0.04, 0.48, -0.65, -0.38, 0.00, 119.42, 110.88 -GPS, 3, 309046600, 10, 1.49, 24.2397984, 54.5793043, -0.16, 12.32, 0.04, 139.64 -CTUN, 286, 0.24, -0.98, -0.025654, 0, 0, -133, 620, 0 -NTUN, 0.04, 1.78, 76.497276, 20.741100, 76.497276, 20.741100, 87.782677, 1.019583, -56.514473, 28.440979, 2.28, -2.89 -DU32, 7, 393457 -CURR, 285, 330071, 1177, 0, 4752, 0.000000 -ATT, 2.28, 0.99, -2.89, 0.39, 0.00, 111.79, 110.88 -CTUN, 285, 0.30, -1.36, 0.025351, 0, 0, -169, 662, 0 -NTUN, 0.08, 1.71, 71.720436, 22.395283, 71.720436, 22.395283, 87.094124, -5.120653, -63.768402, 45.541824, 2.68, -3.69 -ATT, 2.68, 2.69, -3.69, 2.06, 0.00, 105.62, 110.88 -GPS, 3, 309046800, 10, 1.49, 24.2397983, 54.5793043, -0.57, 12.33, 0.07, 139.64 -CTUN, 285, 0.30, -1.50, 0.089945, 0, 0, -184, 702, 0 -NTUN, 0.13, 1.66, 68.257965, 24.653629, 68.257965, 24.653629, 82.325531, -10.859194, -49.974453, 61.811581, 2.01, -4.17 -ATT, 2.01, 3.07, -4.17, 1.13, 0.00, 99.77, 109.77 -CTUN, 285, 0.30, -1.38, 0.149017, 0, 0, -169, 684, 0 -NTUN, 0.16, 1.59, 64.907799, 27.517967, 64.907799, 27.517967, 91.781113, -16.360638, -62.169964, 77.359779, 2.93, -4.98 -GPS, 3, 309047000, 10, 1.49, 24.2397984, 54.5793041, -1.01, 12.34, 0.14, 139.64 -ATT, 2.93, 4.03, -4.98, 0.70, 0.00, 93.83, 103.83 -CTUN, 285, 0.26, -1.25, 0.224606, 0, 0, -165, 734, 0 -NTUN, 0.20, 1.53, 60.097557, 30.371601, 60.097557, 30.371601, 114.825450, -16.639885, -108.102420, 83.536339, 6.07, -5.13 -CTUN, 286, 0.26, -1.11, 0.313335, 0, 0, -128, 714, 0 -ATT, 6.07, 4.23, -5.13, 1.75, 0.00, 85.53, 95.53 -NTUN, 0.25, 1.51, 53.183434, 33.436726, 53.183434, 33.436726, 123.999930, -23.988001, -147.456670, 98.347763, 9.02, -4.91 -GPS, 3, 309047200, 10, 1.49, 24.2397985, 54.5793037, -1.30, 12.49, 0.21, 186.61 -CTUN, 285, 0.24, -1.23, 0.430059, 0, 0, -104, 717, 0 -NTUN, 0.32, 1.51, 45.900955, 37.252762, 45.900955, 37.252762, 125.704120, -34.892059, -164.824780, 125.160360, 11.03, -4.55 -ATT, 11.03, 5.54, -4.55, 3.96, 0.00, 74.10, 84.10 -CTUN, 286, 0.26, -1.32, 0.571672, 0, 1, -84, 734, 0 -NTUN, 0.39, 1.49, 38.896820, 42.060459, 38.896820, 42.060459, 120.331630, -48.998432, -168.041350, 158.076970, 12.46, -4.43 -ATT, 12.46, 6.34, -4.43, 5.43, 0.00, 65.05, 75.05 -GPS, 3, 309047400, 10, 1.49, 24.2397981, 54.5793033, -1.46, 12.77, 0.25, 208.02 -CTUN, 286, 0.26, -1.35, 0.738692, 0, 1, -58, 733, 0 -NTUN, 0.46, 1.46, 33.406029, 48.125500, 33.406029, 48.125500, 108.785800, -64.635132, -150.364270, 197.049900, 13.36, -4.73 -ATT, 13.36, 7.36, -4.73, 5.58, 0.00, 53.40, 63.40 -CTUN, 285, 0.53, -0.66, 0.939282, 0, 1, -29, 739, 0 -NTUN, 0.52, 1.42, 29.587189, 55.360962, 29.587189, 55.360962, 98.446404, -76.764160, -130.188400, 235.354610, 14.54, -4.90 -ATT, 14.54, 8.29, -4.90, 4.97, 0.00, 44.67, 54.67 -GPS, 3, 309047600, 10, 1.49, 24.2397975, 54.5793027, -1.49, 13.08, 0.48, 223.20 -CTUN, 285, 0.53, -0.32, 1.155007, 0, 1, -15, 736, 0 -NTUN, 0.58, 1.36, 27.689941, 63.225525, 27.689941, 63.225525, 86.188568, -84.438812, -103.972470, 264.645630, 15.33, -5.19 -DU32, 7, 393457 -CURR, 285, 336519, 1144, 0, 4752, 0.000000 -ATT, 15.33, 9.66, -5.19, 5.39, 0.00, 36.81, 46.81 -CTUN, 285, 0.90, 0.00, 1.384182, 0, 2, -7, 751, 0 -NTUN, 0.64, 1.30, 27.449661, 71.545242, 27.449661, 71.545242, 69.944626, -91.818504, -73.379013, 292.373440, 16.03, -6.00 -ATT, 16.03, 10.41, -6.00, 5.81, 0.00, 31.84, 41.84 -GPS, 3, 309047800, 10, 1.49, 24.2397961, 54.5793024, -1.35, 13.52, 0.72, 201.34 -CTUN, 285, 0.90, 0.48, 1.629918, 0, 3, 7, 763, 0 -NTUN, 0.69, 1.23, 30.077858, 79.550003, 30.077858, 79.550003, 51.432121, -98.459473, -24.718033, 314.047610, 16.20, -7.63 -ATT, 16.20, 11.36, -7.63, 4.13, 0.00, 25.66, 35.66 -CTUN, 286, 1.35, 1.10, 1.879918, 0, 3, 22, 767, 0 -NTUN, 0.74, 1.16, 35.114761, 87.650192, 35.114761, 87.650192, 36.534496, -104.780070, 19.369034, 338.001890, 16.98, -9.07 -GPS, 3, 309048000, 10, 1.49, 24.2397942, 54.5793020, -1.09, 14.07, 0.95, 192.75 -ATT, 16.98, 13.34, -9.07, 2.00, 0.00, 21.01, 31.01 -CTUN, 285, 1.35, 1.49, 2.129918, 0, 4, 23, 768, 0 -NTUN, 0.79, 1.08, 41.620590, 95.589722, 41.620590, 95.589722, 26.115559, -102.799740, 49.414146, 351.609190, 17.64, -9.79 -CTUN, 285, 1.61, 1.91, 2.382418, 0, 4, 29, 756, 0 -ATT, 17.64, 14.98, -9.79, 0.91, 0.00, 17.92, 27.92 -NTUN, 0.84, 1.00, 49.996918, 102.025510, 49.996918, 102.025510, 13.791585, -96.829689, 91.763275, 347.357850, 17.17, -11.13 -GPS, 3, 309048200, 10, 1.49, 24.2397921, 54.5793016, -0.71, 14.56, 1.21, 191.16 -CTUN, 286, 1.61, 2.05, 2.632418, 0, 4, 39, 764, 0 -NTUN, 0.90, 0.92, 59.942490, 107.232350, 59.942490, 107.232350, 2.932265, -91.686577, 131.455720, 345.068420, 16.81, -12.65 -ATT, 16.81, 14.86, -12.65, 0.10, 0.00, 15.58, 25.58 -CTUN, 285, 2.24, 2.43, 2.882418, 0, 5, 41, 790, 0 -NTUN, 0.96, 0.84, 71.164673, 111.675640, 71.164673, 111.675640, -3.660860, -91.860573, 164.110720, 351.993040, 17.05, -14.04 -ATT, 17.05, 15.08, -14.04, -1.65, 0.00, 14.01, 24.01 -GPS, 3, 309048400, 10, 1.49, 24.2397895, 54.5793018, -0.30, 15.09, 1.38, 181.95 -CTUN, 285, 2.24, 2.95, 3.134918, 0, 5, 44, 769, 0 -NTUN, 1.03, 0.76, 83.282387, 114.827000, 83.282387, 114.827000, -9.442659, -85.577728, 196.177140, 346.513520, 16.74, -15.22 -ATT, 16.74, 16.47, -15.22, -3.63, 0.00, 12.04, 22.04 -CTUN, 286, 2.62, 3.24, 3.384918, 0, 6, 58, 761, 0 -NTUN, 1.11, 0.69, 95.901382, 116.636470, 95.899284, 116.633920, -11.150739, -78.515327, 222.168980, 338.069210, 16.39, -16.07 -ATT, 16.39, 16.57, -16.07, -5.29, 0.00, 10.91, 20.91 -GPS, 3, 309048600, 10, 1.49, 24.2397869, 54.5793025, 0.19, 15.60, 1.47, 173.68 -CTUN, 285, 2.52, 3.53, 3.634918, 0, 8, 56, 794, 0 -NTUN, 1.19, 0.62, 108.592900, 116.586930, 108.406680, 116.387000, -12.061378, -69.933739, 238.835650, 318.555270, 15.24, -16.66 -ATT, 15.24, 17.02, -16.66, -7.41, 0.00, 10.48, 20.48 -DU32, 7, 393457 -CURR, 286, 343452, 1183, 0, 4772, 0.000000 -CTUN, 286, 2.55, 3.70, 3.887418, 0, 8, 49, 791, 0 -NTUN, 1.27, 0.56, 121.250660, 114.949410, 120.615560, 114.347330, -9.245070, -58.437130, 251.088780, 294.603270, 13.95, -16.95 -ATT, 13.95, 16.75, -16.95, -7.85, 0.00, 9.43, 19.43 -GPS, 3, 309048800, 9, 1.96, 24.2397845, 54.5793038, 0.68, 16.16, 1.50, 161.11 -CTUN, 285, 2.52, 4.15, 4.137418, 0, 7, 60, 784, 0 -NTUN, 1.35, 0.51, 133.293610, 111.337370, 132.049300, 110.298010, -6.110949, -49.670006, 259.337400, 269.506840, 12.82, -16.92 -ATT, 12.82, 15.01, -16.92, -9.42, 0.00, 9.00, 18.94 -CTUN, 286, 2.52, 4.47, 4.387418, 0, 8, 49, 806, 0 -NTUN, 1.42, 0.45, 144.720260, 106.683640, 142.719560, 105.208780, -1.748475, -50.415558, 263.646120, 263.611540, 12.36, -17.13 -GPS, 3, 309049000, 10, 1.49, 24.2397823, 54.5793060, 1.19, 16.70, 1.64, 146.37 -ATT, 12.36, 14.81, -17.13, -10.80, 0.00, 9.23, 18.94 -CTUN, 285, 1.87, 4.73, 4.639918, 0, 7, 52, 779, 0 -NTUN, 1.51, 0.40, 154.978990, 100.468230, 152.219960, 98.679634, 8.273634, -43.072510, 260.003970, 241.708560, 11.16, -16.75 -CTUN, 285, 2.52, 4.97, 4.889918, 0, 8, 62, 785, 0 -ATT, 11.16, 14.25, -16.75, -11.73, 0.00, 8.97, 18.94 -NTUN, 1.57, 0.35, 163.969390, 92.971588, 160.513900, 91.012306, 20.060749, -40.640942, 251.939450, 227.326720, 10.47, -16.17 -GPS, 3, 309049200, 9, 1.96, 24.2397805, 54.5793090, 1.73, 17.24, 1.84, 134.92 -CTUN, 285, 2.52, 5.37, 5.139918, 0, 9, 60, 813, 0 -NTUN, 1.64, 0.30, 171.508470, 83.943222, 167.518260, 81.990257, 29.737247, -39.001118, 242.043640, 208.779510, 9.22, -15.65 -ATT, 9.22, 12.68, -15.65, -12.74, 0.00, 10.15, 18.94 -CTUN, 286, 3.31, 5.76, 5.389918, 0, 7, 57, 788, 0 -NTUN, 1.68, 0.25, 177.794130, 73.822968, 173.405010, 72.000534, 40.376240, -36.411816, 233.867490, 192.102770, 8.18, -15.16 -ATT, 8.18, 11.38, -15.16, -12.61, 0.00, 10.88, 18.94 -GPS, 3, 309049400, 10, 1.49, 24.2397794, 54.5793125, 2.28, 17.80, 1.89, 121.71 -CTUN, 286, 3.31, 6.42, 5.639918, 0, 6, 62, 779, 0 -NTUN, 1.72, 0.21, 182.034240, 62.707367, 177.536940, 61.158138, 53.130020, -38.380424, 212.910170, 180.649550, 7.70, -13.96 -ATT, 7.70, 9.88, -13.96, -13.06, 0.00, 11.46, 18.94 -CTUN, 285, 3.79, 6.63, 5.892418, 0, 5, 72, 756, 0 -NTUN, 1.73, 0.17, 184.435670, 50.683601, 180.090710, 49.489594, 68.531563, -39.680088, 190.537720, 165.314540, 6.88, -12.69 -ATT, 6.88, 8.85, -12.69, -13.31, 0.00, 12.61, 18.94 -GPS, 3, 309049600, 10, 1.49, 24.2397790, 54.5793166, 2.89, 18.33, 2.06, 109.24 -CTUN, 286, 3.63, 6.99, 6.142417, 0, 6, 61, 813, 0 -NTUN, 1.74, 0.13, 184.956880, 37.782150, 181.012880, 36.976490, 81.721130, -48.648415, 167.221650, 157.868960, 6.34, -11.57 -ATT, 6.34, 7.53, -11.57, -12.55, 0.00, 14.81, 18.94 -CTUN, 286, 3.79, 7.25, 6.392417, 0, 4, 64, 783, 0 -NTUN, 1.74, 0.08, 183.641430, 24.731028, 180.278490, 24.278141, 91.713058, -51.257145, 143.728810, 150.273770, 5.96, -10.39 -DU32, 7, 393457 -CURR, 285, 351310, 1179, 0, 4752, 0.000000 -ATT, 5.96, 6.23, -10.39, -10.83, 0.00, 16.52, 18.94 -GPS, 3, 309049800, 10, 1.49, 24.2397793, 54.5793209, 3.50, 18.85, 2.21, 96.64 -CTUN, 285, 3.79, 7.63, 6.644917, 0, 3, 68, 775, 0 -NTUN, 1.73, 0.04, 180.705690, 10.470793, 178.034320, 10.316003, 99.046005, -52.487785, 122.558290, 127.378620, 4.85, -8.99 -ATT, 4.85, 4.82, -8.99, -9.81, 0.00, 18.47, 18.94 -CTUN, 285, 4.27, 7.83, 6.894917, 0, 2, 56, 778, 0 -NTUN, 1.71, 0.00, 176.326100, -3.759577, 174.344590, -3.717327, 109.876630, -67.122498, 97.468048, 132.056140, 5.28, -7.88 -ATT, 5.28, 4.00, -7.88, -9.38, 0.00, 20.47, 18.94 -GPS, 3, 309050000, 10, 1.49, 24.2397803, 54.5793254, 4.10, 19.44, 2.35, 86.15 -CTUN, 286, 3.79, 8.10, 7.147417, 0, 2, 56, 785, 0 -NTUN, 1.69, 3.55, 170.179900, -17.875822, 168.879170, -17.739191, 120.898000, -75.459068, 65.345764, 127.781360, 5.47, -6.25 -ATT, 5.47, 2.92, -6.25, -7.72, 0.00, 22.18, 18.94 -CTUN, 285, 4.27, 8.13, 7.397417, 0, 1, 66, 756, 0 -NTUN, 1.67, 3.50, 163.092900, -32.429482, 162.308820, -32.273575, 128.235030, -80.497658, 42.296570, 115.656160, 5.25, -4.84 -GPS, 3, 309050200, 10, 1.49, 24.2397820, 54.5793297, 4.69, 20.00, 2.40, 77.49 -ATT, 5.25, 3.23, -4.84, -5.64, 0.00, 21.90, 18.94 -CTUN, 285, 4.27, 8.56, 7.620000, 0, 0, 76, 752, 0 -NTUN, 1.64, 3.45, 156.880620, -46.324120, 156.339290, -46.164280, 130.711730, -90.719246, 41.304718, 120.092960, 5.57, -4.84 -CTUN, 286, 4.81, 8.11, 7.620000, 0, 0, 70, 743, 0 -ATT, 5.57, 4.45, -4.84, -4.62, 0.00, 21.26, 18.94 -NTUN, 1.62, 3.40, 149.998570, -60.341682, 149.606580, -60.183998, 131.077000, -97.067993, 28.339493, 114.190920, 5.59, -3.93 -GPS, 3, 309050400, 10, 1.49, 24.2397841, 54.5793340, 5.25, 20.58, 2.47, 70.13 -CTUN, 286, 4.81, 8.30, 7.620000, 0, 0, 63, 761, 0 -NTUN, 1.60, 3.34, 142.377200, -74.685249, 142.056990, -74.517281, 129.687030, -99.832222, 13.504089, 99.667175, 5.16, -2.74 -ATT, 5.16, 4.25, -2.74, -3.76, 0.00, 20.03, 18.94 -CTUN, 285, 5.52, 8.48, 7.620000, 0, 0, 76, 727, 0 -NTUN, 1.60, 3.28, 134.428440, -89.179955, 134.097080, -88.960129, 131.283400, -108.349800, -0.599152, 93.571518, 5.15, -1.74 -ATT, 5.15, 2.89, -1.74, -3.35, 0.00, 18.96, 18.94 -GPS, 3, 309050600, 10, 1.49, 24.2397866, 54.5793381, 5.75, 21.18, 2.51, 63.74 -CTUN, 286, 5.52, 9.28, 7.620000, 0, 0, 76, 750, 0 -NTUN, 1.62, 3.22, 125.551550, -103.545660, 125.166140, -103.227800, 130.496900, -117.798150, -17.309387, 91.323303, 5.35, -0.78 -ATT, 5.35, 4.43, -0.78, -2.51, 0.00, 19.53, 18.94 -CMD, 9, 2, 16, 1, 0, 7.62, 24.2398304, 54.5793472 -CTUN, 285, 5.52, 9.23, 7.620000, 0, 0, 60, 749, 0 -NTUN, 0.00, 0.35, 118.077210, -115.403990, 117.581910, -114.919900, 126.198590, -122.502140, -6.091370, 111.236630, 6.18, -1.95 -ATT, 6.18, 3.90, -1.95, -1.27, 0.00, 20.72, 23.14 -GPS, 3, 309050800, 10, 1.49, 24.2397892, 54.5793419, 6.28, 21.78, 2.44, 58.66 -CTUN, 285, 3.36, 9.36, 7.620000, 0, 0, 65, 716, 0 -NTUN, 5.11, 0.34, 111.996950, -124.590060, 111.382190, -123.906170, 123.931060, -133.739040, 2.616611, 141.027070, 7.58, -3.11 -DU32, 7, 393457 -CURR, 286, 358864, 1156, 0, 4772, 0.000000 -ATT, 7.58, 3.35, -3.11, 0.59, 0.00, 21.47, 30.34 -CTUN, 285, 4.73, 9.60, 7.620000, 0, 0, 70, 713, 0 -NTUN, 4.95, 0.34, 107.554310, -130.587540, 106.861050, -129.745800, 120.969550, -142.458040, 15.788666, 174.603620, 8.99, -4.75 -ATT, 8.99, 5.03, -4.75, 0.78, 0.00, 24.40, 35.51 -GPS, 3, 309051000, 10, 1.49, 24.2397920, 54.5793453, 6.78, 22.37, 2.32, 54.13 -CTUN, 286, 3.54, 9.85, 7.620000, 0, 0, 65, 720, 0 -NTUN, 4.80, 0.33, 103.475020, -135.680760, 102.715610, -134.684970, 114.861750, -145.972700, 21.545532, 183.608370, 8.93, -5.94 -ATT, 8.93, 7.06, -5.94, 0.67, 0.00, 30.23, 35.51 -CTUN, 285, 3.54, 9.62, 7.620000, 0, 0, 63, 692, 0 -NTUN, 4.64, 0.32, 99.447067, -141.089360, 98.589882, -139.873230, 105.202670, -141.619280, 27.151241, 171.631060, 7.69, -6.53 -GPS, 3, 309051200, 10, 1.49, 24.2397946, 54.5793484, 7.25, 22.96, 2.16, 50.83 -PM, 0, 0, 51, 30, 1000, 11596, 7, 0 -ATT, 7.69, 7.06, -6.53, 0.61, 0.00, 33.53, 35.51 -CTUN, 285, 2.37, 9.73, 7.620000, 0, 0, 58, 696, 0 -NTUN, 4.48, 0.32, 95.609100, -147.473510, 94.577042, -145.881590, 95.208153, -138.006180, 33.871597, 154.916380, 6.37, -6.66 -CTUN, 286, 2.37, 9.85, 7.620000, 0, 0, 34, 712, 0 -ATT, 6.37, 7.29, -6.66, -0.13, 0.00, 34.51, 35.51 -NTUN, 4.33, 0.31, 92.080536, -154.426800, 90.807335, -152.291530, 91.359589, -137.773420, 36.302933, 142.900570, 5.65, -6.45 -GPS, 3, 309051400, 10, 1.49, 24.2397970, 54.5793513, 7.62, 23.53, 2.00, 49.53 -CTUN, 286, 2.05, 10.36, 7.620000, 0, 0, 31, 698, 0 -NTUN, 4.18, 0.30, 88.783951, -161.621980, 87.225197, -158.784420, 85.650322, -130.321490, 40.178619, 126.071110, 4.79, -6.03 -ATT, 4.79, 6.08, -6.03, -0.75, 0.00, 33.69, 35.51 -CTUN, 285, 2.08, 10.66, 7.620000, 0, 0, 30, 698, 0 -NTUN, 4.02, 0.28, 85.384933, -169.494140, 83.487610, -165.727840, 84.039803, -131.738390, 37.624130, 115.565800, 4.45, -5.50 -ATT, 4.45, 5.02, -5.50, -0.25, 0.00, 32.99, 35.51 -GPS, 3, 309051600, 10, 1.49, 24.2397992, 54.5793542, 7.99, 24.09, 1.93, 50.63 -CTUN, 285, 2.08, 10.93, 7.620000, 0, 0, 13, 720, 0 -NTUN, 3.87, 0.27, 81.363876, -176.942380, 79.186539, -172.207320, 87.176407, -136.760180, 24.415138, 116.846760, 4.90, -4.93 -ATT, 4.90, 4.60, -4.93, -0.96, 0.00, 33.51, 35.51 -CTUN, 286, 2.14, 10.77, 7.620000, 0, 0, 1, 689, 0 -NTUN, 3.72, 0.26, 76.977051, -184.242400, 74.556793, -178.449580, 86.566475, -134.617750, 15.702545, 108.577360, 4.77, -4.25 -ATT, 4.77, 4.24, -4.25, -0.24, 0.00, 33.33, 35.51 -GPS, 3, 309051800, 10, 1.49, 24.2398011, 54.5793571, 8.34, 24.59, 1.83, 52.77 -CTUN, 285, 2.14, 10.85, 7.620000, 0, 0, 12, 679, 0 -NTUN, 3.56, 0.24, 72.722839, -191.810590, 70.046951, -184.752790, 83.196503, -133.308460, 14.901581, 96.967926, 4.27, -3.80 -DU32, 7, 393457 -CURR, 285, 365167, 1143, 0, 4752, 0.000000 -ATT, 4.27, 3.52, -3.80, 0.83, 0.00, 32.96, 35.51 -CTUN, 285, 2.78, 11.08, 7.620000, 0, 0, 4, 701, 0 -NTUN, 3.42, 0.23, 68.414055, -199.507510, 65.498856, -191.006260, 81.508934, -138.431960, 10.969353, 95.084518, 4.29, -3.56 -ATT, 4.29, 3.21, -3.56, 0.80, 0.00, 33.02, 35.51 -GPS, 3, 309052000, 10, 1.49, 24.2398029, 54.5793599, 8.65, 25.09, 1.73, 54.13 -CTUN, 286, 2.71, 11.38, 7.620000, 0, 0, -4, 692, 0 -NTUN, 3.27, 0.21, 64.098595, -207.008450, 60.986355, -196.957380, 77.385841, -137.106080, 9.874992, 87.488739, 3.96, -3.26 -ATT, 3.96, 3.42, -3.26, 1.16, 0.00, 32.66, 35.51 -CTUN, 286, 2.78, 11.31, 7.620000, 0, 0, -5, 669, 0 -NTUN, 3.14, 0.19, 59.885651, -214.622890, 56.597240, -202.837630, 76.654449, -140.135420, 6.108856, 82.197510, 3.84, -2.89 -GPS, 3, 309052200, 10, 1.49, 24.2398046, 54.5793624, 8.95, 25.59, 1.59, 54.47 -ATT, 3.84, 3.18, -2.89, 1.69, 0.00, 32.99, 35.51 -CTUN, 285, 2.71, 11.99, 7.620000, 0, 0, -6, 681, 0 -NTUN, 3.01, 0.17, 55.982849, -222.152270, 52.540356, -208.491710, 70.946762, -138.086120, 10.431152, 72.459167, 3.21, -2.80 -ATT, 3.21, 2.64, -2.80, 1.92, 0.00, 32.65, 35.51 -CTUN, 285, 2.71, 12.02, 7.620000, 0, 0, -19, 701, 0 -NTUN, 2.89, 0.15, 52.624634, -229.783870, 49.020973, -214.048600, 64.603691, -135.155760, 19.154629, 61.981342, 2.45, -2.88 -GPS, 3, 309052400, 10, 1.49, 24.2398061, 54.5793647, 9.24, 26.06, 1.43, 54.99 -ATT, 2.45, 2.26, -2.88, 2.63, 0.00, 31.54, 35.51 -CTUN, 286, 2.66, 12.29, 7.620000, 0, 0, -20, 672, 0 -NTUN, 2.78, 0.13, 49.464218, -237.521120, 45.718250, -219.533430, 61.778397, -139.410310, 18.972771, 56.151672, 2.21, -2.65 -CTUN, 286, 2.66, 12.64, 7.620000, 0, 0, -28, 683, 0 -ATT, 2.21, 1.60, -2.65, 2.86, 0.00, 32.18, 35.51 -NTUN, 2.67, 0.10, 46.370911, -245.006520, 42.530926, -224.717470, 56.825630, -141.534590, 21.126755, 52.159637, 1.91, -2.67 -GPS, 3, 309052600, 10, 1.49, 24.2398073, 54.5793668, 9.55, 26.54, 1.24, 56.60 -CTUN, 286, 2.26, 12.49, 7.620000, 0, 0, -30, 685, 0 -NTUN, 2.59, 0.08, 43.495590, -252.015320, 39.603512, -229.464460, 55.287273, -147.105680, 22.015705, 54.000061, 1.94, -2.79 -ATT, 1.94, 1.66, -2.79, 2.40, 0.00, 32.96, 35.51 -CTUN, 285, 2.66, 12.54, 7.620000, 0, 0, -34, 677, 0 -NTUN, 2.51, 0.05, 40.533081, -258.967410, 36.637856, -234.080660, 52.808136, -154.102140, 20.343437, 53.838043, 2.01, -2.68 -ATT, 2.01, 1.66, -2.68, 3.73, 0.00, 32.24, 35.51 -GPS, 3, 309052800, 10, 1.49, 24.2398084, 54.5793684, 9.86, 27.03, 1.06, 54.41 -CTUN, 286, 2.66, 12.63, 7.620000, 0, 0, -34, 670, 0 -NTUN, 2.44, 0.03, 37.745117, -265.253690, 33.892376, -238.178570, 43.375248, -158.213530, 28.817036, 55.426579, 1.85, -3.13 -DU32, 7, 393457 -CURR, 285, 371308, 1139, 0, 4712, 0.000000 -ATT, 1.85, 0.76, -3.13, 3.89, 0.00, 31.97, 35.51 -CTUN, 286, 2.66, 13.20, 7.620000, 0, 0, -44, 691, 0 -NTUN, 2.38, 0.01, 35.552399, -271.281740, 31.717749, -242.021530, 36.449539, -158.014860, 39.253727, 48.570435, 1.20, -3.44 -ATT, 1.20, 1.71, -3.44, 2.52, 0.00, 31.66, 35.51 -GPS, 3, 309053000, 10, 1.49, 24.2398093, 54.5793696, 10.12, 27.52, 0.77, 52.84 -CTUN, 286, 2.66, 13.39, 7.620000, 0, 0, -57, 683, 0 -NTUN, 2.34, 3.58, 33.372986, -276.989560, 29.591713, -245.605710, 35.341824, -166.483810, 38.739643, 52.158173, 1.44, -3.50 -ATT, 1.44, 1.37, -3.50, 3.39, 0.00, 30.40, 35.51 -CTUN, 285, 2.66, 13.56, 7.620000, 0, 0, -62, 694, 0 -NTUN, 2.30, 3.56, 31.230484, -282.149960, 27.539520, -248.804170, 31.475275, -170.937770, 41.681259, 54.332123, 1.50, -3.70 -ATT, 1.50, 0.53, -3.70, 3.68, 0.00, 30.41, 35.51 -GPS, 3, 309053200, 10, 1.49, 24.2398100, 54.5793704, 10.39, 27.97, 0.57, 51.96 -CTUN, 285, 2.43, 13.68, 7.620000, 0, 0, -64, 703, 0 -NTUN, 2.27, 3.55, 29.348816, -286.875670, 25.749353, -251.692020, 23.832811, -176.349590, 48.098331, 55.121521, 1.34, -4.04 -ATT, 1.34, 1.72, -4.04, 2.37, 0.00, 30.45, 35.51 -CTUN, 286, 2.54, 13.92, 7.620000, 0, 0, -78, 714, 0 -NTUN, 2.24, 3.53, 27.589935, -291.222660, 24.093622, -254.317700, 19.442347, -181.306290, 52.442688, 56.743134, 1.32, -4.30 -GPS, 3, 309053400, 10, 1.49, 24.2398103, 54.5793708, 10.64, 28.42, 0.27, 50.34 -ATT, 1.32, 1.27, -4.30, 1.51, 0.00, 29.41, 35.51 -CTUN, 286, 2.43, 14.99, 7.620000, 0, 0, -81, 706, 0 -NTUN, 2.23, 3.52, 26.289154, -294.891570, 22.867151, -256.506160, 17.337414, -183.764140, 57.856724, 58.332069, 1.31, -4.60 -CTUN, 286, 2.43, 15.37, 7.620000, 0, 0, -96, 728, 0 -ATT, 1.31, 1.38, -4.60, 1.56, 0.00, 29.58, 35.51 -NTUN, 2.22, 3.51, 25.201599, -298.123900, 21.844954, -258.416260, 14.001935, -184.039470, 61.778023, 54.899048, 1.00, -4.71 -GPS, 3, 309053600, 10, 1.49, 24.2398106, 54.5793707, 10.96, 28.81, 0.09, 50.34 -CTUN, 286, 1.80, 15.37, 7.620000, 0, 0, -107, 768, 0 -NTUN, 2.21, 3.49, 24.276550, -301.004210, 20.977922, -260.104610, 12.868859, -190.502780, 65.329689, 59.116455, 1.12, -5.00 -ATT, 1.12, 1.03, -5.00, 1.32, 0.00, 29.37, 35.51 -CTUN, 285, 2.43, 15.25, 7.620000, 0, 0, -98, 720, 0 -NTUN, 2.20, 3.49, 23.248505, -302.966250, 20.047884, -261.256900, 9.118357, -196.911390, 66.791702, 66.591263, 1.62, -5.24 -ATT, 1.62, 0.52, -5.24, 1.62, 0.00, 27.48, 35.51 -GPS, 3, 309053800, 10, 1.49, 24.2398107, 54.5793702, 11.27, 29.24, 0.28, 339.99 -CTUN, 285, 2.43, 15.76, 7.620000, 0, 0, -98, 727, 0 -NTUN, 2.20, 3.48, 22.476013, -303.479680, 19.372015, -261.568330, 7.287034, -200.387310, 72.173042, 74.854225, 2.01, -5.71 -DU32, 7, 393457 -CURR, 286, 377689, 1174, 0, 4772, 0.000000 -ATT, 2.01, 0.77, -5.71, 0.14, 0.00, 26.52, 35.51 -CTUN, 286, 4.05, 16.22, 7.620000, 0, 0, -107, 730, 0 -NTUN, 2.19, 3.49, 21.631378, -302.910830, 18.656994, -261.259610, 11.586437, -205.900300, 66.849792, 84.087158, 2.64, -5.67 -ATT, 2.64, 1.88, -5.67, -0.79, 0.00, 26.51, 35.51 -GPS, 3, 309054000, 10, 1.49, 24.2398107, 54.5793693, 11.61, 29.64, 0.49, 287.78 -CTUN, 286, 3.53, 16.34, 7.620000, 0, 0, -104, 743, 0 -NTUN, 2.18, 3.49, 20.759460, -301.518070, 17.933746, -260.476350, 13.129594, -207.173140, 63.839134, 87.755089, 2.92, -5.60 -ATT, 2.92, 1.90, -5.60, 0.24, 0.00, 26.88, 35.51 -CTUN, 286, 3.53, 16.42, 7.620000, 0, 0, -97, 732, 0 -NTUN, 2.17, 3.49, 19.996368, -299.394840, 17.316172, -259.265720, 10.551203, -212.283420, 67.885399, 96.986458, 3.23, -6.08 -ATT, 3.23, 1.83, -6.08, 0.72, 0.00, 27.59, 35.51 -GPS, 3, 309054200, 10, 1.49, 24.2398109, 54.5793678, 11.96, 30.09, 0.75, 281.50 -CTUN, 286, 3.02, 16.69, 7.620000, 0, 0, -109, 743, 0 -NTUN, 2.15, 3.50, 19.380493, -296.125180, 16.844664, -257.378850, 7.282642, -212.158310, 72.237289, 103.059310, 3.33, -6.52 -ATT, 3.33, 2.74, -6.52, -0.17, 0.00, 27.57, 35.51 -CTUN, 286, 3.53, 16.80, 7.620000, 0, 0, -110, 727, 0 -NTUN, 2.14, 3.51, 18.980225, -292.257260, 16.568546, -255.122270, 5.566997, -212.008590, 77.292969, 105.123300, 3.37, -6.80 -GPS, 3, 309054400, 10, 1.49, 24.2398110, 54.5793659, 12.27, 30.52, 0.97, 277.03 -ATT, 3.37, 3.62, -6.80, -1.07, 0.00, 26.61, 35.51 -CTUN, 285, 3.53, 17.36, 7.620000, 0, 0, -101, 737, 0 -NTUN, 2.13, 3.52, 18.691498, -287.556460, 16.402964, -252.348830, 8.734666, -213.659070, 74.327446, 115.014520, 4.07, -6.84 -CTUN, 285, 3.75, 17.57, 7.620000, 0, 0, -118, 758, 0 -ATT, 4.07, 3.70, -6.84, -1.74, 0.00, 26.76, 35.51 -NTUN, 2.12, 3.53, 18.338257, -282.400390, 16.186998, -249.272020, 8.029769, -211.866460, 74.840347, 116.768130, 4.11, -6.94 -GPS, 3, 309054600, 10, 1.49, 24.2398112, 54.5793638, 12.63, 30.98, 1.06, 276.01 -CTUN, 286, 3.75, 17.34, 7.620000, 0, 0, -118, 729, 0 -NTUN, 2.11, 3.55, 17.605804, -276.282780, 15.649113, -245.576970, 9.509535, -213.880130, 70.674400, 126.584690, 4.67, -7.01 -ATT, 4.67, 3.64, -7.01, -1.14, 0.00, 27.21, 35.51 -CTUN, 286, 5.38, 17.86, 7.620000, 0, 0, -115, 742, 0 -NTUN, 2.10, 3.57, 16.749176, -269.348210, 15.006269, -241.320020, 9.682804, -218.364720, 68.571556, 140.569430, 5.39, -7.32 -ATT, 5.39, 3.34, -7.32, -1.20, 0.00, 27.85, 35.51 -GPS, 3, 309054800, 10, 1.49, 24.2398114, 54.5793614, 12.98, 31.43, 1.20, 276.02 -CTUN, 286, 5.38, 18.12, 7.620000, 0, 0, -117, 734, 0 -NTUN, 2.09, 3.59, 15.729584, -261.101620, 14.226836, -236.156940, 12.387700, -222.340330, 63.282848, 157.119660, 6.16, -7.67 -DU32, 7, 393457 -CURR, 285, 384332, 1130, 0, 4752, 0.000000 -ATT, 6.16, 4.23, -7.67, -1.84, 0.00, 29.95, 35.51 -CTUN, 286, 5.52, 18.22, 7.620000, 0, 0, -114, 721, 0 -NTUN, 2.08, 0.01, 14.564667, -252.272580, 13.307709, -230.500990, 13.826535, -223.153120, 60.808723, 168.559450, 6.58, -8.06 -ATT, 6.58, 4.48, -8.06, -1.48, 0.00, 31.29, 35.51 -GPS, 3, 309055000, 10, 1.49, 24.2398116, 54.5793588, 13.35, 31.88, 1.36, 275.71 -CTUN, 286, 5.38, 18.07, 7.620000, 0, 0, -118, 720, 0 -NTUN, 2.07, 0.04, 13.444611, -242.597840, 12.421443, -224.135530, 10.638435, -224.001620, 62.137344, 182.654630, 7.06, -8.68 -ATT, 7.06, 5.08, -8.68, -1.28, 0.00, 32.11, 35.51 -CTUN, 285, 5.38, 18.30, 7.620000, 0, 0, -109, 698, 0 -NTUN, 2.07, 0.06, 12.457886, -232.465640, 11.643294, -217.265270, 6.692154, -220.026090, 66.295555, 189.022310, 7.26, -9.06 -ATT, 7.26, 5.23, -9.06, -1.45, 0.00, 31.71, 35.51 -GPS, 3, 309055200, 10, 1.49, 24.2398119, 54.5793559, 13.73, 32.35, 1.45, 276.07 -CTUN, 285, 5.20, 18.54, 7.620000, 0, 0, -103, 689, 0 -NTUN, 2.08, 0.09, 11.718170, -221.904540, 11.082142, -209.860200, 7.914550, -221.911560, 67.388474, 206.050750, 8.13, -9.56 -ATT, 8.13, 6.57, -9.56, -3.33, 0.00, 32.17, 35.51 -CTUN, 285, 5.20, 18.97, 7.620000, 0, 0, -119, 711, 0 -NTUN, 2.09, 0.12, 10.786407, -210.829530, 10.324662, -201.804320, 9.698957, -219.539170, 62.425201, 218.558780, 8.79, -9.77 -GPS, 3, 309055400, 10, 1.49, 24.2398121, 54.5793528, 14.05, 32.82, 1.54, 274.83 -ATT, 8.79, 7.53, -9.77, -3.37, 0.00, 31.75, 35.51 -CTUN, 285, 3.08, 19.29, 7.620000, 0, 1, -130, 715, 0 -NTUN, 2.11, 0.15, 9.754669, -199.735660, 9.445167, -193.398300, 8.383429, -210.777730, 63.292122, 221.227940, 8.98, -9.82 -CTUN, 285, 3.47, 19.18, 7.620000, 0, 0, -124, 694, 0 -ATT, 8.98, 7.46, -9.82, -1.81, 0.00, 31.08, 35.51 -NTUN, 2.13, 0.18, 8.872437, -188.833070, 8.681162, -184.762150, 5.561554, -207.254230, 66.359955, 230.361540, 9.42, -10.16 -GPS, 3, 309055600, 10, 1.49, 24.2398123, 54.5793497, 14.39, 33.25, 1.57, 274.38 -CTUN, 286, 3.47, 19.10, 7.620000, 0, 0, -132, 707, 0 -NTUN, 2.16, 0.21, 8.101959, -177.468690, 8.003202, -175.305470, 5.962768, -208.387160, 66.220406, 251.566800, 10.47, -10.76 -ATT, 10.47, 8.42, -10.76, -2.50, 0.00, 31.05, 35.51 -CTUN, 286, 3.47, 19.67, 7.620000, 0, 1, -147, 704, 0 -NTUN, 2.20, 0.24, 7.497406, -166.243100, 7.460855, -165.432650, 4.624718, -198.128660, 67.630226, 255.750670, 10.69, -10.87 -ATT, 10.69, 9.45, -10.87, -3.56, 0.00, 30.52, 35.51 -GPS, 3, 309055800, 10, 1.49, 24.2398123, 54.5793468, 14.69, 33.70, 1.48, 273.09 -CTUN, 286, 2.09, 19.92, 7.620000, 0, 1, -144, 692, 0 -NTUN, 2.25, 0.27, 7.099579, -155.417540, 7.095012, -155.317570, 5.585473, -191.759980, 68.341568, 265.150820, 11.13, -11.17 -ATT, 11.13, 9.67, -11.17, -4.14, 0.00, 30.61, 35.51 -DU32, 7, 393457 -CURR, 285, 390717, 1156, 0, 4752, 0.000000 -CTUN, 285, 2.09, 19.90, 7.620000, 0, 1, -144, 706, 0 -NTUN, 2.29, 0.29, 6.858521, -144.573820, 6.858521, -144.573820, 4.294928, -184.300640, 70.635086, 276.437440, 11.47, -11.74 -ATT, 11.47, 9.85, -11.74, -3.88, 0.00, 31.45, 35.51 -GPS, 3, 309056000, 10, 1.49, 24.2398124, 54.5793439, 15.00, 34.10, 1.45, 271.61 -CTUN, 285, 2.07, 19.99, 7.620000, 0, 2, -167, 733, 0 -NTUN, 2.34, 0.31, 7.217346, -133.716370, 7.217346, -133.716370, 0.300463, -174.760060, 80.552727, 280.499510, 11.23, -12.47 -ATT, 11.23, 10.72, -12.47, -3.74, 0.00, 32.05, 35.51 -CTUN, 285, 2.09, 20.20, 7.620000, 0, 1, -165, 684, 0 -NTUN, 2.41, 0.34, 8.130524, -123.025280, 8.130524, -123.025280, -1.742319, -167.083830, 90.131775, 284.910860, 11.26, -12.96 -ATT, 11.26, 10.91, -12.96, -3.96, 0.00, 31.15, 35.51 -GPS, 3, 309056200, 10, 1.49, 24.2398125, 54.5793412, 15.30, 34.47, 1.38, 271.32 -CTUN, 285, 2.09, 20.70, 7.620000, 0, 1, -161, 710, 0 -NTUN, 2.41, 0.34, 9.996674, -112.028790, 9.996674, -112.028790, -4.695375, -150.007420, 104.850000, 284.075650, 10.81, -13.60 -ATT, 10.81, 11.24, -13.60, -6.22, 0.00, 31.33, 35.51 -CTUN, 285, 3.47, 21.09, 7.620000, 0, 3, -175, 748, 0 -NTUN, 2.47, 0.36, 12.936432, -101.556900, 12.936432, -101.556900, -8.041158, -134.583250, 122.821160, 272.665620, 9.66, -14.15 -GPS, 3, 309056400, 10, 1.49, 24.2398123, 54.5793390, 15.57, 34.88, 1.15, 269.40 -ATT, 9.66, 11.28, -14.15, -6.72, 0.00, 31.64, 35.51 -CTUN, 285, 3.39, 20.89, 7.620000, 0, 2, -180, 725, 0 -NTUN, 2.52, 0.37, 16.266876, -91.462692, 16.266876, -91.462692, -4.136828, -126.055270, 127.640850, 274.961700, 9.66, -14.43 -ATT, 9.66, 10.30, -14.43, -5.39, 0.00, 31.51, 35.51 -CTUN, 285, 3.47, 21.06, 7.620000, 0, 1, -170, 704, 0 -NTUN, 2.57, 0.38, 20.035263, -81.251907, 20.035263, -81.251907, -3.731271, -115.181720, 135.944980, 274.105740, 9.36, -14.80 -GPS, 3, 309056600, 10, 1.49, 24.2398123, 54.5793369, 15.87, 35.23, 1.03, 268.13 -ATT, 9.36, 10.01, -14.80, -6.44, 0.00, 32.03, 35.51 -CTUN, 286, 3.39, 21.50, 7.620000, 0, 2, -168, 736, 0 -NTUN, 2.61, 0.39, 24.254395, -71.096939, 24.254395, -71.096939, -3.908225, -104.318140, 147.617490, 277.575440, 8.93, -15.57 -ATT, 8.93, 10.49, -15.57, -8.16, 0.00, 32.51, 35.51 -CTUN, 286, 3.39, 21.63, 7.620000, 0, 2, -175, 720, 0 -NTUN, 2.64, 0.40, 28.840485, -60.465714, 28.840485, -60.465714, 4.230619, -95.851440, 147.860900, 285.312260, 9.27, -15.80 -GPS, 3, 309056800, 10, 1.49, 24.2398122, 54.5793352, 16.18, 35.62, 0.85, 267.69 -ATT, 9.27, 9.80, -15.80, -7.77, 0.00, 31.54, 35.51 -CTUN, 285, 3.39, 21.74, 7.620000, 0, 2, -171, 721, 0 -NTUN, 2.67, 0.40, 33.298798, -49.660263, 33.298798, -49.660263, 8.148936, -87.901588, 149.141710, 290.984650, 9.75, -15.89 -DU32, 7, 393457 -CURR, 285, 397928, 1130, 0, 4712, 0.000000 -CTUN, 286, 3.39, 22.04, 7.620000, 0, 3, -173, 742, 0 -ATT, 9.75, 9.47, -15.89, -8.86, 0.00, 32.48, 35.51 -NTUN, 2.69, 0.41, 38.170624, -38.674988, 38.170624, -38.674988, 10.086967, -72.040222, 157.235900, 289.765110, 9.13, -16.38 -GPS, 3, 309057000, 10, 1.49, 24.2398122, 54.5793339, 16.50, 35.98, 0.66, 268.29 -CTUN, 286, 3.39, 21.99, 7.620000, 0, 3, -183, 756, 0 -NTUN, 2.70, 0.42, 43.239929, -27.657623, 43.239929, -27.657623, 19.550074, -63.516689, 156.205110, 295.286500, 9.22, -16.61 -ATT, 9.22, 10.12, -16.61, -9.12, 0.00, 33.30, 35.51 -CTUN, 286, 3.73, 22.46, 7.620000, 0, 2, -166, 716, 0 -NTUN, 2.70, 0.42, 48.557648, -16.095779, 48.557648, -16.095779, 26.370752, -51.132133, 157.650680, 300.473690, 9.67, -16.68 -ATT, 9.67, 9.30, -16.68, -9.19, 0.00, 32.32, 35.51 -GPS, 3, 309057200, 10, 1.49, 24.2398124, 54.5793328, 16.85, 36.35, 0.56, 274.69 -CTUN, 286, 3.73, 22.85, 7.620000, 0, 3, -166, 728, 0 -NTUN, 2.69, 0.43, 54.153687, -4.620117, 54.153687, -4.620117, 30.789837, -36.915760, 162.960390, 299.756620, 9.38, -16.93 -ATT, 9.38, 9.46, -16.93, -11.14, 0.00, 32.81, 35.51 -CTUN, 285, 3.73, 22.81, 7.620000, 0, 4, -164, 745, 0 -NTUN, 2.66, 0.43, 59.858124, 6.876129, 59.858124, 6.876129, 37.745670, -22.970087, 164.044370, 297.962460, 8.92, -17.10 -ATT, 8.92, 9.62, -17.10, -10.96, 0.00, 33.93, 35.51 -GPS, 3, 309057400, 10, 1.49, 24.2398129, 54.5793322, 17.19, 36.71, 0.45, 291.05 -CTUN, 286, 2.84, 22.83, 7.620000, 0, 3, -165, 731, 0 -NTUN, 2.62, 0.44, 65.872375, 18.765533, 65.872375, 18.765533, 44.370476, -7.856487, 166.547040, 298.716860, 8.64, -17.35 -ATT, 8.64, 8.79, -17.35, -10.54, 0.00, 34.58, 35.51 -CTUN, 286, 3.73, 23.17, 7.620000, 0, 2, -160, 725, 0 -NTUN, 2.57, 0.44, 72.318542, 30.590271, 72.318542, 30.590271, 53.478165, 5.216713, 168.823430, 299.076600, 8.54, -17.48 -GPS, 3, 309057600, 10, 1.49, 24.2398136, 54.5793317, 17.54, 37.09, 0.43, 314.28 -ATT, 8.54, 8.31, -17.48, -11.33, 0.00, 35.02, 35.51 -CTUN, 286, 3.73, 23.33, 7.620000, 0, 4, -173, 763, 0 -NTUN, 2.51, 0.44, 77.596893, 42.027222, 77.596893, 42.027222, 62.161522, 9.051478, 156.316680, 305.524750, 9.06, -17.21 -ATT, 9.06, 8.82, -17.21, -11.46, 0.00, 35.12, 35.51 -CTUN, 286, 3.73, 23.45, 7.620000, 0, 3, -165, 736, 0 -NTUN, 2.44, 0.45, 82.242859, 53.002472, 82.242859, 53.002472, 67.590981, 23.638344, 148.999660, 297.665830, 9.03, -16.60 -GPS, 3, 309057800, 10, 1.49, 24.2398146, 54.5793317, 17.88, 37.45, 0.58, 340.68 -ATT, 9.03, 8.33, -16.60, -11.10, 0.00, 34.34, 35.51 -CTUN, 286, 3.73, 23.49, 7.620000, 0, 3, -157, 726, 0 -NTUN, 2.36, 0.45, 85.999908, 62.740967, 85.999908, 62.740967, 76.126434, 37.820072, 135.570500, 282.384950, 8.89, -15.46 -DU32, 7, 393457 -CURR, 286, 404541, 1135, 0, 4732, 0.000000 -CTUN, 285, 3.73, 23.89, 7.620000, 0, 4, -169, 752, 0 -ATT, 8.89, 8.82, -15.46, -11.96, 0.00, 34.91, 35.51 -NTUN, 2.26, 0.45, 89.146088, 71.409668, 89.146088, 71.409668, 83.388702, 50.284351, 126.461790, 269.687010, 8.41, -14.75 -GPS, 3, 309058000, 10, 1.49, 24.2398160, 54.5793320, 18.23, 37.81, 0.76, 358.87 -CTUN, 285, 3.73, 23.88, 7.620000, 0, 3, -164, 737, 0 -NTUN, 2.16, 0.46, 91.648743, 79.350464, 91.648743, 79.350464, 90.045456, 64.622253, 115.778760, 255.621730, 8.04, -13.88 -ATT, 8.04, 9.35, -13.88, -11.18, 0.00, 35.38, 35.51 -CTUN, 285, 3.73, 24.14, 7.620000, 0, 3, -164, 745, 0 -NTUN, 2.04, 0.46, 93.212494, 86.200043, 93.212494, 86.200043, 95.459412, 70.074265, 103.795470, 249.187670, 8.12, -13.15 -ATT, 8.12, 7.67, -13.15, -10.67, 0.00, 35.48, 35.51 -GPS, 3, 309058200, 10, 1.49, 24.2398177, 54.5793326, 18.61, 38.18, 0.98, 10.85 -CTUN, 286, 3.73, 24.19, 7.620000, 0, 2, -162, 733, 0 -NTUN, 1.91, 0.47, 93.864197, 93.210052, 93.864197, 93.210052, 106.531650, 75.954666, 83.452507, 250.406040, 8.87, -12.26 -ATT, 8.87, 7.66, -12.26, -9.49, 0.00, 35.34, 35.51 -CTUN, 285, 3.73, 24.29, 7.620000, 0, 1, -152, 715, 0 -NTUN, 1.77, 0.47, 93.612518, 99.832977, 93.612518, 99.832977, 113.347910, 83.737297, 66.508133, 246.573520, 9.31, -11.35 -ATT, 9.31, 7.50, -11.35, -8.43, 0.00, 35.52, 35.51 -GPS, 3, 309058400, 10, 1.49, 24.2398196, 54.5793335, 18.93, 38.53, 1.19, 17.83 -CTUN, 285, 3.70, 24.65, 7.620000, 0, 2, -160, 747, 0 -NTUN, 1.63, 0.48, 92.708893, 106.533170, 92.708893, 106.533170, 117.176610, 87.704521, 53.963745, 251.001950, 9.82, -11.02 -ATT, 9.82, 8.11, -11.02, -8.06, 0.00, 36.22, 35.51 -CTUN, 285, 3.73, 24.70, 7.620000, 0, 1, -148, 712, 0 -NTUN, 1.49, 0.50, 90.292328, 111.429200, 90.292328, 111.429200, 122.632230, 92.738571, 29.308186, 233.000260, 9.78, -9.34 -GPS, 3, 309058600, 10, 1.49, 24.2398218, 54.5793346, 19.29, 38.89, 1.32, 21.78 -ATT, 9.78, 8.32, -9.34, -6.68, 0.00, 36.10, 35.51 -CTUN, 285, 3.73, 24.58, 7.620000, 0, 1, -146, 719, 0 -NTUN, 1.34, 0.52, 77.396515, 102.509280, 77.396515, 102.509280, 122.146510, 98.274826, -91.260742, 80.899780, 6.88, 1.49 -CMD, 9, 6, 16, 1, 0, 7.62, 24.2398128, 54.5793536 -ATT, 8.23, 8.46, -6.26, -6.21, 0.00, 36.49, 34.91 -CTUN, 286, 5.08, 24.85, 7.620000, 0, 1, -148, 719, 0 -NTUN, 0.00, 1.27, 61.229309, 94.656097, 61.229309, 94.656097, 127.905170, 97.855171, -147.672060, 85.468201, 9.02, 3.96 -GPS, 3, 309058800, 10, 1.49, 24.2398242, 54.5793357, 19.64, 39.26, 1.45, 22.85 -ATT, 9.02, 7.54, 3.96, -3.51, 0.00, 36.62, 28.31 -CTUN, 286, 3.73, 24.92, 7.620000, 0, 0, -144, 709, 0 -NTUN, 2.07, 1.32, 41.996246, 88.061279, 41.996246, 88.061279, 130.342090, 100.416480, -205.330630, 88.051819, 11.12, 6.54 -CTUN, 285, 3.73, 25.29, 7.620000, 0, 0, -130, 688, 0 -ATT, 11.12, 6.63, 6.54, 1.62, 0.00, 35.28, 21.71 -NTUN, 2.11, 1.36, 22.541473, 82.054199, 22.541473, 82.054199, 120.880460, 92.070541, -220.621510, 96.523956, 11.84, 7.26 -DU32, 7, 393457 -CURR, 285, 411047, 1155, 0, 4772, 0.000000 -GPS, 3, 309059000, 10, 1.49, 24.2398266, 54.5793370, 19.99, 39.63, 1.45, 24.27 -CTUN, 285, 2.75, 25.53, 7.620000, 0, 0, -132, 688, 0 -NTUN, 2.16, 1.40, 4.185822, 77.253143, 4.185822, 77.253143, 108.934910, 83.712914, -224.410630, 111.504490, 12.30, 7.51 -ATT, 12.30, 7.48, 7.51, 4.92, 0.00, 32.15, 14.51 -CTUN, 286, 3.22, 26.34, 7.620000, 0, 0, -129, 674, 0 -NTUN, 2.21, 1.43, -12.878906, 73.122620, -12.878906, 73.122620, 90.860191, 80.984550, -210.301250, 117.504670, 11.68, 7.40 -ATT, 11.68, 7.80, 7.40, 7.29, 0.00, 28.50, 8.51 -GPS, 3, 309059200, 10, 1.49, 24.2398288, 54.5793382, 20.41, 40.03, 1.36, 25.37 -CTUN, 285, 3.22, 26.69, 7.620000, 0, 0, -108, 640, 0 -NTUN, 2.26, 1.46, -27.612366, 69.673645, -27.612366, 69.673645, 71.749290, 70.089066, -192.822830, 130.161870, 11.39, 6.93 -ATT, 11.39, 8.15, 6.93, 8.28, 0.00, 24.78, 2.51 -CTUN, 285, 5.04, 27.52, 7.620000, 0, 0, -110, 653, 0 -NTUN, 2.30, 1.48, -40.823486, 67.586853, -40.823486, 67.586853, 57.444344, 58.876450, -178.803180, 153.338700, 11.90, 6.33 -ATT, 11.90, 8.74, 6.33, 8.31, 0.00, 21.51, 0.00 -GPS, 3, 309059400, 10, 1.49, 24.2398305, 54.5793392, 20.94, 40.46, 1.09, 25.80 -CTUN, 285, 3.88, 27.64, 7.620000, 0, 1, -125, 669, 0 -NTUN, 2.33, 1.49, -52.237885, 66.165161, -52.237885, 66.165161, 36.351078, 59.121655, -156.143980, 158.783080, 11.38, 5.71 -ATT, 11.38, 9.30, 5.71, 9.05, 0.00, 17.46, 0.00 -CTUN, 285, 3.88, 27.71, 7.620000, 0, 1, -121, 661, 0 -NTUN, 2.35, 1.51, -61.562897, 64.853455, -61.562897, 64.853455, 15.689597, 54.747616, -128.250120, 163.882930, 10.91, 4.69 -ATT, 10.91, 9.11, 4.69, 9.73, 0.00, 14.58, 0.00 -GPS, 3, 309059600, 10, 1.49, 24.2398317, 54.5793397, 21.48, 40.90, 0.71, 24.95 -CTUN, 286, 3.56, 27.77, 7.620000, 0, 1, -123, 659, 0 -NTUN, 2.35, 1.51, -68.967468, 64.182343, -68.967468, 64.182343, -3.800247, 50.819443, -100.045720, 173.288880, 10.92, 3.32 -ATT, 10.92, 9.41, 3.32, 8.76, 0.00, 12.56, 0.00 -CTUN, 285, 3.56, 28.17, 7.620000, 0, 1, -149, 696, 0 -NTUN, 2.33, 1.52, -74.793549, 63.983307, -74.793549, 63.983307, -20.404596, 51.267303, -74.563889, 178.067610, 10.83, 2.08 -GPS, 3, 309059800, 10, 1.49, 24.2398323, 54.5793399, 21.96, 41.31, 0.36, 22.80 -ATT, 10.83, 9.63, 2.08, 7.81, 0.00, 11.50, 0.00 -CTUN, 286, 1.95, 28.60, 7.620000, 0, 1, -151, 667, 0 -NTUN, 2.31, 1.52, -78.698517, 64.246399, -78.698517, 64.246399, -40.267986, 43.815380, -43.846615, 191.684620, 11.23, 0.38 -ATT, 11.23, 9.14, 0.38, 7.56, 0.00, 10.78, 0.00 -CTUN, 286, 3.56, 28.89, 7.620000, 0, 1, -146, 671, 0 -NTUN, 2.27, 1.52, -80.825897, 64.804169, -80.825897, 64.804169, -61.132538, 47.506470, -7.273804, 192.577700, 10.91, -1.67 -DU32, 7, 393457 -CURR, 285, 417774, 1156, 0, 4752, 0.000000 -GPS, 3, 309060000, 10, 1.49, 24.2398325, 54.5793398, 22.49, 41.71, 0.08, 22.80 -ATT, 10.91, 9.56, -1.67, 5.83, 0.00, 10.34, 0.00 -CTUN, 285, 3.56, 28.97, 7.620000, 0, 1, -163, 716, 0 -NTUN, 2.21, 1.52, -81.490631, 65.530548, -81.490631, 65.530548, -73.744667, 46.502697, 19.352661, 197.263790, 10.95, -3.18 -ATT, 10.95, 10.14, -3.18, 4.17, 0.00, 10.14, 0.00 -CTUN, 286, 3.56, 28.96, 7.620000, 0, 1, -165, 692, 0 -NTUN, 2.15, 1.51, -81.204041, 66.815979, -81.204041, 66.815979, -85.106285, 41.125175, 38.837532, 209.727040, 11.49, -4.32 -GPS, 3, 309060200, 10, 1.49, 24.2398322, 54.5793396, 22.89, 42.10, 0.21, 329.75 -ATT, 11.49, 9.88, -4.32, 3.55, 0.00, 9.50, 0.00 -CTUN, 285, 2.15, 29.32, 7.620000, 0, 1, -162, 685, 0 -NTUN, 2.09, 1.50, -79.964966, 68.636322, -79.964966, 68.636322, -100.181310, 42.995987, 66.390747, 216.203430, 11.65, -5.85 -CTUN, 285, 3.56, 29.60, 7.620000, 0, 1, -162, 708, 0 -ATT, 11.65, 10.10, -5.85, 1.64, 0.00, 8.35, 0.00 -NTUN, 2.09, 1.50, -77.827682, 70.369568, -77.827682, 70.369568, -111.679560, 45.350922, 88.953758, 215.992610, 11.57, -6.92 -GPS, 3, 309060400, 10, 1.49, 24.2398315, 54.5793392, 23.32, 42.44, 0.48, 230.20 -CTUN, 286, 3.21, 29.73, 7.620000, 0, 1, -174, 713, 0 -NTUN, 2.00, 1.49, -75.262207, 72.576111, -75.262207, 72.576111, -116.633220, 41.095802, 103.913890, 229.288310, 12.37, -7.58 -ATT, 12.37, 10.55, -7.58, -0.20, 0.00, 6.71, 0.00 -CTUN, 285, 3.21, 29.90, 7.620000, 0, 1, -171, 702, 0 -NTUN, 1.93, 1.48, -72.442566, 75.225769, -72.442566, 75.225769, -121.906090, 42.171803, 116.917240, 237.234240, 12.89, -8.10 -ATT, 12.89, 10.33, -8.10, -0.59, 0.00, 5.52, 0.00 -GPS, 3, 309060600, 10, 1.49, 24.2398307, 54.5793387, 23.73, 42.77, 0.53, 216.08 -CTUN, 286, 2.31, 30.04, 7.620000, 0, 1, -173, 738, 0 -NTUN, 1.86, 1.46, -69.688171, 78.146729, -69.688171, 78.146729, -125.415000, 42.915031, 125.543950, 243.209590, 13.26, -8.48 -ATT, 13.26, 10.41, -8.48, -2.37, 0.00, 4.90, 0.00 -CTUN, 285, 3.17, 29.96, 7.620000, 0, 2, -180, 719, 0 -NTUN, 1.79, 1.44, -66.878143, 81.214050, -66.878143, 81.214050, -128.202960, 44.292957, 135.100280, 247.673220, 13.55, -8.89 -ATT, 13.55, 11.72, -8.89, -2.59, 0.00, 4.03, 0.00 -GPS, 3, 309060800, 10, 1.49, 24.2398299, 54.5793382, 24.11, 43.08, 0.56, 211.93 -CTUN, 286, 3.17, 30.33, 7.620000, 0, 2, -179, 733, 0 -NTUN, 1.72, 1.42, -64.658051, 83.979370, -64.658051, 83.979370, -131.136800, 50.835560, 137.200930, 243.653200, 13.53, -8.67 -ATT, 13.53, 11.31, -8.67, -3.60, 0.00, 2.60, 0.00 -CTUN, 286, 5.77, 30.63, 7.620000, 0, 2, -177, 727, 0 -NTUN, 1.66, 1.40, -62.646545, 86.223206, -62.646545, 86.223206, -129.445470, 56.498627, 137.720640, 234.998380, 13.12, -8.53 -GPS, 3, 309061000, 10, 1.49, 24.2398293, 54.5793375, 24.50, 43.36, 0.50, 216.98 -DU32, 7, 393457 -CURR, 286, 424188, 1132, 0, 4752, 0.000000 -ATT, 13.12, 11.58, -8.53, -4.59, 0.00, 2.07, 0.00 -CTUN, 286, 5.77, 30.87, 7.620000, 0, 3, -178, 758, 0 -NTUN, 1.59, 1.38, -61.451233, 88.951965, -61.451233, 88.951965, -127.707660, 51.428867, 134.073870, 250.563230, 14.00, -8.30 -ATT, 14.00, 11.75, -8.30, -4.56, 0.00, 1.95, 0.00 -CTUN, 286, 5.77, 30.75, 7.620000, 0, 2, -180, 739, 0 -NTUN, 1.55, 1.36, -60.707458, 92.117493, -60.707458, 92.117493, -127.047690, 53.482979, 132.364110, 257.341860, 14.43, -8.13 -GPS, 3, 309061200, 10, 1.49, 24.2398289, 54.5793368, 24.87, 43.66, 0.43, 224.30 -ATT, 14.43, 11.82, -8.13, -4.52, 0.00, 1.34, 0.00 -PM, 0, 0, 50, 66, 1000, 12400, 8, 0 -CTUN, 286, 5.70, 30.97, 7.620000, 0, 3, -183, 750, 0 -NTUN, 1.51, 1.34, -60.548523, 94.934509, -60.548523, 94.934509, -127.628040, 58.725327, 130.605410, 254.454710, 14.36, -7.85 -ATT, 14.36, 12.17, -7.85, -4.66, 0.00, 1.01, 3.00 -CTUN, 286, 5.70, 31.12, 7.620000, 0, 4, -188, 788, 0 -NTUN, 1.47, 1.32, -61.078476, 97.883728, -61.078476, 97.883728, -125.913880, 56.087589, 124.752940, 262.200200, 14.81, -7.48 -GPS, 3, 309061400, 10, 1.49, 24.2398288, 54.5793360, 25.23, 43.94, 0.41, 242.99 -ATT, 14.81, 12.52, -7.48, -4.55, 0.00, 1.14, 9.60 -CTUN, 286, 4.11, 31.45, 7.620000, 0, 3, -181, 760, 0 -NTUN, 1.44, 1.30, -62.905167, 101.729490, -62.905167, 101.729490, -120.153190, 56.559616, 106.733090, 277.457640, 15.60, -6.59 -CTUN, 285, 4.11, 31.41, 7.620000, 0, 3, -171, 741, 0 -ATT, 15.60, 12.78, -6.59, -4.31, 0.00, 3.32, 16.20 -NTUN, 1.43, 1.28, -65.524002, 105.725950, -65.524002, 105.725950, -116.297000, 60.898849, 95.070938, 279.568910, 15.50, -6.57 -GPS, 3, 309061600, 10, 1.49, 24.2398290, 54.5793353, 25.60, 44.26, 0.37, 266.37 -CTUN, 286, 3.37, 31.33, 7.620000, 0, 3, -166, 754, 0 -NTUN, 1.43, 1.27, -69.429855, 109.759400, -69.429855, 109.759400, -114.970630, 58.493195, 78.546936, 290.741880, 15.64, -7.09 -ATT, 15.64, 13.65, -7.09, -3.87, 0.00, 9.35, 23.40 -CTUN, 286, 4.11, 31.25, 7.620000, 0, 4, -165, 761, 0 -NTUN, 1.43, 1.26, -73.846603, 113.582610, -73.846603, 113.582610, -115.653020, 63.089626, 72.698547, 288.482480, 14.83, -8.36 -ATT, 14.83, 13.97, -8.36, -3.48, 0.00, 15.40, 29.40 -GPS, 3, 309061800, 10, 1.49, 24.2398295, 54.5793344, 25.95, 44.62, 0.53, 296.11 -MODE, RTL, 470 -ERR, 9, 1 -CTUN, 285, 4.11, 31.17, 7.620000, 0, 3, -153, 744, 0 -NTUN, 1.44, 2.38, -116.561460, 68.828918, -116.561460, 68.828918, -117.939540, 74.361435, -355.463230, -256.057500, -6.76, 23.29 -ATT, -6.76, 14.00, 23.29, -3.55, 0.00, 20.86, 29.40 -CTUN, 285, 4.11, 31.28, 26.007353, 0, 3, -155, 754, 0 -NTUN, 4.54, 2.38, -116.751720, 63.516907, -116.751720, 63.516907, -123.076180, 87.439728, 80.097458, 123.879880, 4.59, -7.24 -ATT, 4.59, 10.59, -7.24, -2.59, 0.00, 25.03, 23.40 -GPS, 3, 309062000, 10, 1.49, 24.2398304, 54.5793337, 26.26, 44.95, 0.59, 309.40 -CTUN, 286, 3.60, 31.31, 26.007261, 0, 0, -158, 722, 0 -NTUN, 4.53, 2.38, -118.601910, 55.516479, -118.601910, 55.516479, -128.416720, 65.827538, 66.681221, 110.787850, 4.12, -6.28 -DU32, 7, 393457 -CURR, 285, 431717, 1136, 0, 4772, 0.000000 -ATT, 4.12, 1.26, -6.28, 7.50, 0.00, 24.79, 16.20 -CTUN, 286, 4.11, 31.97, 26.007118, 0, 0, -135, 722, 0 -NTUN, 4.51, 2.38, -120.092270, 47.768860, -120.092270, 47.768860, -146.515870, 39.743057, 88.096436, 130.523800, 5.00, -7.66 -ATT, 5.00, 2.72, -7.66, 1.17, 0.00, 21.74, 10.20 -GPS, 3, 309062200, 10, 1.49, 24.2398311, 54.5793332, 26.60, 45.35, 0.49, 316.48 -CTUN, 285, 4.11, 32.18, 26.006931, 0, 0, -122, 714, 0 -NTUN, 4.46, 2.38, -122.387440, 38.706909, -122.387440, 38.706909, -137.244780, 31.979101, 69.275589, 116.277720, 5.27, -5.85 -ATT, 5.27, 7.49, -5.85, -1.90, 0.00, 14.76, 3.00 -CTUN, 286, 4.54, 32.55, 26.006695, 0, 0, -134, 733, 0 -NTUN, 4.41, 2.37, -125.742720, 29.505463, -125.742720, 29.505463, -134.736130, 36.504013, 52.779350, 102.896580, 5.17, -4.31 -GPS, 3, 309062400, 10, 1.49, 24.2398314, 54.5793323, 27.00, 45.78, 0.50, 306.77 -ATT, 5.17, 2.62, -4.31, 0.95, 0.00, 10.09, 356.40 -CTUN, 286, 4.11, 32.97, 26.006458, 0, 0, -147, 741, 0 -NTUN, 4.36, 2.37, -130.049560, 19.816406, -130.049560, 19.816406, -139.243870, 18.892578, 44.496574, 102.130740, 5.48, -3.47 -ATT, 5.48, 3.80, -3.47, -0.30, 0.00, 5.36, 349.80 -CTUN, 286, 4.11, 33.28, 26.006199, 0, 0, -131, 712, 0 -NTUN, 4.30, 2.36, -134.726350, 10.172516, -134.726350, 10.172516, -141.681260, 4.429316, 38.695168, 109.515940, 6.21, -2.65 -GPS, 3, 309062600, 10, 1.49, 24.2398318, 54.5793311, 27.42, 46.23, 0.60, 296.27 -ATT, 6.21, 4.44, -2.65, 0.25, 0.00, 359.45, 343.20 -CTUN, 285, 3.36, 33.57, 26.005909, 0, 0, -135, 734, 0 -NTUN, 4.22, 2.36, -139.962950, 0.800690, -139.962950, 0.800690, -143.129820, -4.244016, 29.633972, 111.281740, 6.51, -1.55 -CTUN, 286, 4.11, 34.07, 26.005610, 0, 0, -146, 750, 0 -ATT, 6.51, 4.45, -1.55, 0.91, 0.00, 354.48, 336.60 -NTUN, 4.15, 2.35, -145.331500, -8.914001, -145.331500, -8.914001, -147.048900, -21.910736, 26.314545, 115.853090, 6.85, -0.83 -GPS, 3, 309062800, 10, 1.49, 24.2398320, 54.5793295, 27.87, 46.64, 0.81, 288.06 -CTUN, 285, 4.11, 34.06, 26.005281, 0, 0, -159, 752, 0 -NTUN, 4.03, 2.34, -150.556500, -18.371948, -150.547350, -18.370831, -153.596500, -29.832338, 30.841492, 118.431710, 7.08, -0.60 -ATT, 7.08, 4.70, -0.60, 1.04, 0.00, 349.85, 329.40 -CTUN, 285, 4.11, 34.45, 26.004938, 0, 0, -143, 723, 0 -NTUN, 3.93, 2.33, -155.494190, -28.565094, -155.290160, -28.527613, -163.858870, -40.860458, 41.041454, 113.437810, 6.97, -0.68 -ATT, 6.97, 4.73, -0.68, 1.28, 0.00, 345.23, 323.40 -GPS, 3, 309063000, 10, 1.49, 24.2398324, 54.5793274, 28.31, 47.00, 1.06, 280.76 -CTUN, 285, 3.37, 35.14, 26.004572, 0, 0, -147, 762, 0 -NTUN, 3.81, 2.32, -160.361360, -38.716278, -159.699860, -38.556572, -171.781740, -54.282124, 48.903015, 117.710410, 7.38, -0.55 -DU32, 7, 393457 -CURR, 285, 438326, 1133, 0, 4752, 0.000000 -ATT, 7.38, 4.42, -0.55, 0.61, 0.00, 340.58, 316.20 -CTUN, 285, 4.11, 35.34, 26.004187, 0, 0, -158, 765, 0 -NTUN, 3.69, 2.31, -164.892960, -48.848343, -163.541110, -48.447865, -177.320240, -61.187126, 55.967846, 118.066410, 7.57, -0.46 -ATT, 7.57, 5.08, -0.46, 0.36, 0.00, 336.87, 310.20 -GPS, 3, 309063200, 10, 1.49, 24.2398325, 54.5793248, 28.80, 47.38, 1.32, 276.68 -CTUN, 286, 4.11, 35.75, 26.003784, 0, 0, -140, 727, 0 -NTUN, 3.55, 2.30, -169.144740, -58.958740, -166.893780, -58.174122, -186.540390, -70.662247, 67.134583, 117.754970, 7.85, -0.46 -ATT, 7.85, 4.66, -0.46, 1.26, 0.00, 331.78, 303.00 -CTUN, 286, 4.11, 36.22, 26.003368, 0, 0, -135, 733, 0 -NTUN, 3.41, 2.29, -172.793150, -69.594574, -169.484040, -68.261787, -197.717390, -76.447701, 86.353905, 113.122120, 8.18, -1.06 -GPS, 3, 309063400, 10, 1.49, 24.2398326, 54.5793216, 29.34, 47.77, 1.59, 274.16 -ATT, 8.18, 5.70, -1.06, 0.35, 0.00, 328.23, 296.40 -CTUN, 286, 2.69, 36.46, 26.002935, 0, 0, -165, 774, 0 -NTUN, 3.26, 2.27, -176.287640, -79.719635, -171.779390, -77.680939, -205.958070, -81.114418, 96.046509, 113.808490, 8.57, -1.05 -ATT, 8.57, 6.20, -1.05, 0.64, 0.00, 323.05, 289.80 -CTUN, 286, 4.11, 36.81, 26.002495, 0, 0, -146, 745, 0 -NTUN, 3.10, 2.26, -179.325650, -90.650391, -173.468380, -87.689507, -217.809300, -89.582626, 114.277280, 106.905270, 8.97, -1.29 -GPS, 3, 309063600, 10, 1.49, 24.2398327, 54.5793179, 29.89, 48.15, 1.88, 272.12 -ATT, 8.97, 5.94, -1.29, 0.11, 0.00, 317.29, 283.80 -CTUN, 286, 3.60, 37.20, 26.002031, 0, 0, -145, 747, 0 -NTUN, 2.93, 2.24, -182.462310, -102.810180, -174.961040, -98.583519, -227.430860, -94.845734, 126.922620, 91.959473, 8.94, -1.57 -ATT, 8.94, 6.70, -1.57, -1.04, 0.00, 312.31, 277.80 -CTUN, 285, 3.60, 37.26, 26.001532, 0, 1, -168, 800, 0 -NTUN, 2.76, 2.22, -186.141480, -118.401520, -176.350010, -112.173330, -234.282230, -98.348686, 136.382720, 57.766541, 8.18, -2.62 -GPS, 3, 309063800, 10, 1.49, 24.2398328, 54.5793137, 30.40, 48.54, 2.10, 271.18 -ATT, 8.18, 6.75, -2.62, -0.97, 0.00, 305.41, 271.20 -CTUN, 286, 1.54, 37.31, 26.000967, 0, 0, -160, 740, 0 -NTUN, 2.59, 2.19, -190.490780, -134.934480, -177.906540, -126.020410, -247.138310, -100.944930, 149.277440, 38.130539, 8.42, -2.98 -CTUN, 285, 3.60, 38.07, 26.000374, 0, 0, -149, 754, 0 -ATT, 8.42, 5.73, -2.98, -1.81, 0.00, 296.57, 264.60 -NTUN, 2.41, 2.17, -190.022130, -137.284910, -177.271360, -128.072910, -256.946810, -104.684620, 185.288880, 158.678240, 13.52, 3.60 -GPS, 3, 309064000, 10, 1.49, 24.2398328, 54.5793090, 30.95, 48.90, 2.37, 270.33 -CTUN, 285, 3.60, 38.26, 26.000000, 0, 1, -148, 788, 0 -NTUN, 2.23, 2.13, -183.254240, -115.529790, -174.370450, -109.929150, -268.978910, -113.215060, 228.009090, 386.437620, 19.12, 16.58 -ATT, 19.12, 8.22, 16.58, -3.46, 0.00, 288.19, 257.40 -DU32, 7, 393457 -CURR, 285, 445135, 1142, 0, 4732, 0.000000 -CTUN, 285, 3.60, 38.16, 26.000000, 0, 1, -151, 747, 0 -NTUN, 2.05, 2.09, -175.365540, -92.855225, -170.061950, -90.046989, -283.180210, -113.512470, 266.658450, 422.853030, 19.41, 20.21 -ATT, 19.41, 10.38, 20.21, 1.20, 0.00, 280.61, 251.40 -GPS, 3, 309064200, 10, 1.49, 24.2398329, 54.5793035, 31.51, 49.26, 2.76, 270.49 -CTUN, 286, 2.18, 38.31, 26.000000, 0, 3, -136, 732, 0 -NTUN, 1.86, 2.04, -167.545260, -69.886597, -164.997730, -68.823975, -290.040250, -96.994690, 292.642240, 444.230160, 17.38, 23.80 -ATT, 17.38, 12.48, 23.80, 8.83, 0.00, 269.40, 244.20 -CTUN, 286, 2.18, 38.46, 26.000000, 0, 7, -149, 797, 0 -NTUN, 1.68, 1.97, -159.898650, -48.467285, -159.060710, -48.213299, -288.339660, -76.990486, 311.782290, 438.066100, 14.47, 25.69 -ATT, 14.47, 13.05, 25.69, 11.69, 0.00, 260.65, 238.20 -GPS, 3, 309064400, 10, 1.49, 24.2398331, 54.5792975, 32.02, 49.59, 3.05, 270.68 -CTUN, 286, 1.56, 38.46, 26.000000, 0, 7, -156, 778, 0 -NTUN, 1.68, 1.97, -154.215550, -27.979004, -154.073200, -27.953176, -281.586980, -51.104553, 307.378970, 434.647710, 9.82, 27.15 -ATT, 9.82, 12.12, 27.15, 14.44, 0.00, 249.20, 238.02 -CTUN, 286, 2.18, 38.90, 26.000000, 0, 7, -145, 759, 0 -NTUN, 1.55, 1.89, -149.428530, -8.360474, -149.428530, -8.360474, -272.383640, -18.991434, 300.843870, 393.510830, 5.55, 26.33 -GPS, 3, 309064600, 10, 1.49, 24.2398335, 54.5792913, 32.49, 49.90, 3.15, 272.18 -ATT, 5.55, 8.59, 26.33, 17.58, 0.00, 240.18, 238.02 -CTUN, 285, 2.10, 39.10, 26.000000, 0, 7, -148, 762, 0 -NTUN, 1.48, 1.81, -147.574370, 8.431274, -147.574370, 8.431274, -264.438140, 11.551234, 276.541560, 371.917480, 2.45, 25.19 -ATT, 2.45, 6.33, 25.19, 18.54, 0.00, 236.73, 238.02 -CTUN, 285, 2.10, 39.10, 26.000000, 0, 9, -157, 783, 0 -NTUN, 1.47, 1.75, -146.593410, 22.129761, -146.593410, 22.129761, -257.983610, 47.775482, 268.712430, 316.628570, 2.65, 22.81 -GPS, 3, 309064800, 10, 1.49, 24.2398343, 54.5792853, 32.97, 50.22, 3.07, 274.31 -ATT, 2.65, 4.12, 22.81, 18.18, 0.00, 235.45, 238.02 -CTUN, 286, 1.81, 39.39, 26.000000, 0, 7, -145, 769, 0 -NTUN, 1.49, 1.69, -147.643250, 34.301758, -147.635280, 34.299904, -252.150130, 89.431076, 246.476060, 270.930730, 2.72, 20.31 -ATT, 2.72, 3.59, 20.31, 17.48, 0.00, 236.49, 238.02 -CTUN, 285, 2.10, 39.78, 26.000000, 0, 7, -146, 774, 0 -NTUN, 1.52, 1.65, -149.446260, 43.215942, -149.350460, 43.188244, -246.228990, 124.668880, 237.018020, 206.003360, 4.84, 17.10 -GPS, 3, 309065000, 10, 1.49, 24.2398354, 54.5792800, 33.43, 50.56, 2.80, 277.22 -CTUN, 285, 2.10, 39.93, 26.000000, 0, 6, -149, 769, 0 -ATT, 4.84, 4.08, 17.10, 16.51, 0.00, 240.03, 238.02 -NTUN, 1.57, 1.63, -152.812500, 51.274780, -152.444110, 51.151173, -242.990570, 158.569440, 221.063570, 166.629290, 6.12, 14.53 -DU32, 7, 393457 -CURR, 285, 452043, 1157, 0, 4712, 0.000000 -CTUN, 286, 2.10, 40.06, 26.000000, 0, 5, -152, 764, 0 -ATT, 6.12, 5.58, 14.53, 15.30, 0.00, 243.29, 238.02 -NTUN, 1.63, 1.60, -156.649690, 56.311157, -155.881680, 56.035080, -237.681820, 187.539760, 213.624240, 104.839070, 8.11, 10.89 -GPS, 3, 309065200, 10, 1.49, 24.2398369, 54.5792755, 33.88, 50.91, 2.46, 283.26 -CTUN, 286, 1.19, 40.31, 26.000000, 0, 4, -139, 752, 0 -ATT, 8.11, 6.68, 10.89, 13.50, 0.00, 245.78, 238.02 -NTUN, 1.69, 1.59, -162.472810, 61.180969, -160.963330, 60.612556, -227.246800, 214.581890, 185.183500, 72.774765, 7.88, 8.22 -CTUN, 286, 2.10, 40.57, 26.000000, 0, 3, -134, 757, 0 -ATT, 7.88, 7.70, 8.22, 10.80, 0.00, 247.90, 238.02 -NTUN, 1.78, 1.59, -169.239750, 64.218750, -166.737150, 63.269131, -222.786790, 235.284640, 171.833480, 25.302715, 8.55, 5.10 -GPS, 3, 309065400, 10, 1.49, 24.2398386, 54.5792718, 34.36, 51.30, 2.13, 289.80 -CTUN, 285, 2.10, 40.82, 26.000000, 0, 2, -130, 749, 0 -ATT, 8.55, 8.52, 5.10, 8.01, 0.00, 250.41, 238.02 -NTUN, 1.86, 1.59, -177.170990, 68.241821, -173.222600, 66.720993, -218.397250, 246.771670, 155.145570, 16.518623, 8.10, 3.91 -CTUN, 285, 3.41, 41.05, 26.000000, 0, 2, -139, 743, 0 -ATT, 8.10, 8.45, 3.91, 5.25, 0.00, 252.10, 238.02 -NTUN, 1.95, 1.58, -185.768740, 71.570374, -180.035030, 69.361374, -213.415130, 254.058690, 142.550110, -4.857616, 7.94, 2.25 -GPS, 3, 309065600, 10, 1.49, 24.2398405, 54.5792684, 34.88, 51.71, 2.02, 295.56 -CTUN, 285, 2.42, 41.24, 26.000000, 0, 1, -140, 763, 0 -NTUN, 2.05, 1.58, -194.828740, 76.809143, -186.821200, 73.652260, -218.035460, 258.277560, 141.138370, 1.908859, 7.81, 2.47 -ATT, 7.81, 8.41, 2.47, 1.65, 0.00, 253.37, 238.02 -CTUN, 286, 2.42, 41.39, 26.000000, 0, 1, -133, 753, 0 -NTUN, 2.15, 1.58, -203.692410, 82.278564, -193.173740, 78.029701, -220.331010, 259.197170, 142.474610, -3.225586, 7.99, 2.15 -ATT, 7.99, 8.13, 2.15, 0.12, 0.00, 253.66, 238.02 -GPS, 3, 309065800, 10, 1.49, 24.2398424, 54.5792650, 35.33, 52.07, 2.01, 299.62 -CTUN, 286, 2.42, 41.54, 26.000000, 0, 1, -134, 749, 0 -NTUN, 2.26, 1.57, -212.400180, 90.248108, -198.963810, 84.539040, -225.180210, 257.134310, 149.099300, 19.093384, 7.96, 3.57 -ATT, 7.96, 7.34, 3.57, -0.55, 0.00, 253.15, 238.02 -CTUN, 286, 2.88, 41.78, 26.000000, 0, 0, -131, 723, 0 -NTUN, 2.37, 1.56, -220.827610, 98.719604, -204.273300, 91.319115, -228.497760, 253.717090, 153.430760, 23.129456, 8.05, 4.04 -ATT, 8.05, 6.82, 4.04, -1.05, 0.00, 251.89, 238.02 -GPS, 3, 309066000, 10, 1.49, 24.2398441, 54.5792614, 35.80, 52.45, 2.05, 298.60 -CTUN, 286, 2.88, 41.81, 26.000000, 0, 0, -124, 720, 0 -NTUN, 2.48, 1.55, -228.623320, 108.689390, -208.784850, 99.258026, -229.901860, 250.132970, 158.884490, 39.389114, 7.96, 5.19 -ATT, 7.96, 7.07, 5.19, -1.15, 0.00, 250.80, 238.02 -DU32, 7, 393457 -CURR, 285, 459544, 1131, 0, 4752, 0.000000 -CTUN, 286, 2.88, 42.07, 26.000000, 0, 1, -132, 755, 0 -NTUN, 2.60, 1.53, -236.090270, 119.646360, -212.779560, 107.832910, -231.388610, 246.257710, 162.052950, 50.748825, 7.87, 5.94 -ATT, 7.87, 6.91, 5.94, -0.81, 0.00, 250.32, 238.02 -GPS, 3, 309066200, 10, 1.49, 24.2398456, 54.5792575, 36.26, 52.83, 2.18, 294.88 -CTUN, 286, 2.88, 42.14, 26.000000, 0, 0, -134, 735, 0 -NTUN, 2.72, 1.52, -244.176570, 133.745360, -216.654540, 118.670430, -231.830000, 241.656200, 161.633820, 82.302216, 7.11, 7.77 -ATT, 7.11, 6.48, 7.77, -0.76, 0.00, 249.35, 238.02 -CTUN, 286, 4.30, 42.44, 26.000000, 0, 0, -128, 720, 0 -NTUN, 2.87, 1.50, -252.236820, 148.599730, -220.216080, 129.735410, -236.044460, 238.654130, 164.384610, 94.649796, 6.82, 8.64 -ATT, 6.82, 6.50, 8.64, -0.35, 0.00, 248.03, 238.02 -GPS, 3, 309066400, 10, 1.49, 24.2398467, 54.5792533, 36.69, 53.17, 2.20, 290.63 -CTUN, 285, 4.30, 42.56, 26.000000, 0, 0, -148, 758, 0 -NTUN, 3.01, 1.48, -259.336700, 165.191650, -222.741260, 141.881180, -238.312520, 235.606540, 175.748230, 115.457670, 6.85, 10.07 -ATT, 6.85, 6.12, 10.07, 0.74, 0.00, 247.29, 238.02 -CTUN, 285, 5.91, 42.60, 26.000000, 0, 0, -150, 744, 0 -NTUN, 3.16, 1.46, -266.229800, 182.074710, -224.935620, 153.833600, -238.632400, 236.594700, 178.273610, 119.340820, 6.61, 10.50 -ATT, 6.61, 5.50, 10.50, 1.50, 0.00, 245.59, 238.02 -GPS, 3, 309066600, 10, 1.49, 24.2398476, 54.5792486, 37.11, 53.50, 2.40, 285.41 -CTUN, 285, 4.77, 42.84, 26.000000, 0, 0, -130, 714, 0 -NTUN, 3.31, 1.44, -272.541990, 200.444400, -226.417820, 166.521790, -240.757480, 238.017440, 187.178070, 134.881870, 6.18, 11.79 -ATT, 6.18, 6.27, 11.79, 2.60, 0.00, 243.05, 238.02 -CTUN, 286, 4.77, 43.09, 26.000000, 0, 1, -141, 772, 0 -NTUN, 3.48, 1.42, -278.764100, 219.112640, -227.688350, 178.966350, -241.147780, 235.744340, 188.420410, 143.213500, 5.79, 12.34 -ATT, 5.79, 5.49, 12.34, 4.21, 0.00, 242.19, 238.02 -GPS, 3, 309066800, 10, 1.49, 24.2398480, 54.5792439, 37.49, 53.86, 2.43, 281.34 -CTUN, 286, 4.77, 43.16, 26.000000, 0, 0, -163, 742, 0 -NTUN, 3.64, 1.40, -284.308900, 238.629910, -228.319850, 191.636440, -237.336350, 242.023010, 191.685000, 150.700900, 5.55, 12.88 -ATT, 5.55, 4.77, 12.88, 4.64, 0.00, 241.03, 238.02 -CTUN, 286, 4.77, 43.36, 26.000000, 0, 0, -140, 717, 0 -NTUN, 3.81, 1.38, -289.677920, 257.531490, -228.868290, 203.470090, -240.097790, 247.618930, 194.515690, 146.336490, 5.44, 12.89 -ATT, 5.44, 5.29, 12.89, 5.28, 0.00, 239.60, 238.02 -GPS, 3, 309067000, 10, 1.49, 24.2398484, 54.5792391, 37.86, 54.17, 2.46, 277.46 -CTUN, 286, 4.34, 43.59, 26.000000, 0, 1, -139, 771, 0 -NTUN, 3.97, 1.37, -294.554810, 277.193570, -228.953310, 215.458660, -235.956020, 249.197020, 196.149780, 156.885710, 5.27, 13.42 -ATT, 5.27, 4.80, 13.42, 6.52, 0.00, 240.01, 238.02 -DU32, 7, 393457 -CURR, 285, 466966, 1137, 0, 4793, 0.000000 -CTUN, 285, 4.34, 43.65, 26.000000, 0, 1, -153, 757, 0 -NTUN, 4.14, 1.35, -299.765200, 296.654720, -229.244920, 226.866200, -229.527570, 256.105260, 187.083890, 154.075320, 5.02, 12.99 -ATT, 5.02, 4.32, 12.99, 7.04, 0.00, 240.45, 238.02 -GPS, 3, 309067200, 10, 1.49, 24.2398484, 54.5792342, 38.24, 54.55, 2.49, 274.48 -CTUN, 286, 2.00, 43.99, 26.000000, 0, 0, -136, 709, 0 -NTUN, 4.32, 1.34, -304.450500, 316.436550, -229.149150, 238.170620, -228.783450, 263.824070, 190.948170, 153.925020, 5.18, 13.10 -ATT, 5.18, 4.56, 13.10, 6.97, 0.00, 240.34, 238.02 -CTUN, 286, 3.35, 44.09, 26.000000, 0, 1, -133, 713, 0 -NTUN, 4.49, 1.33, -309.388240, 335.666470, -229.282330, 248.756670, -221.861450, 266.254060, 180.681400, 154.812320, 4.66, 12.85 -ATT, 4.66, 4.11, 12.85, 7.13, 0.00, 240.49, 238.02 -GPS, 3, 309067400, 10, 1.49, 24.2398483, 54.5792297, 38.66, 54.89, 2.30, 271.91 -CTUN, 286, 3.35, 44.18, 26.000000, 0, 1, -142, 766, 0 -NTUN, 4.66, 1.31, -313.481450, 355.186550, -228.864230, 259.311980, -224.392590, 272.394350, 189.223300, 159.619320, 5.20, 13.23 -ATT, 5.20, 4.12, 13.23, 6.76, 0.00, 241.52, 238.02 -CTUN, 285, 3.35, 44.25, 26.000000, 0, 0, -127, 709, 0 -NTUN, 4.83, 1.30, -317.383790, 374.029140, -228.442600, 269.214110, -224.009370, 282.307400, 189.216310, 151.021300, 5.46, 12.80 -GPS, 3, 309067600, 10, 1.49, 24.2398481, 54.5792254, 38.97, 55.24, 2.20, 269.50 -ATT, 5.46, 4.75, 12.80, 7.44, 0.00, 241.45, 238.02 -CTUN, 285, 2.76, 44.63, 26.000000, 0, 1, -119, 709, 0 -NTUN, 5.00, 1.29, -320.219600, 392.585600, -227.445270, 278.845310, -221.923890, 282.860320, 193.874560, 156.358370, 5.52, 13.19 -ATT, 5.52, 5.46, 13.19, 8.55, 0.00, 241.63, 238.02 -CTUN, 285, 2.76, 44.83, 26.000000, 0, 2, -157, 778, 0 -NTUN, 5.16, 1.28, -323.410400, 411.284390, -226.662260, 288.248780, -216.251570, 284.852260, 185.830050, 162.034730, 4.97, 13.24 -GPS, 3, 309067800, 10, 1.49, 24.2398476, 54.5792215, 39.36, 55.62, 2.05, 267.02 -ATT, 4.97, 4.31, 13.24, 9.04, 0.00, 241.41, 238.02 -CTUN, 285, 2.76, 45.03, 26.000000, 0, 1, -146, 721, 0 -NTUN, 5.32, 1.27, -325.875850, 429.234250, -225.584530, 297.133420, -211.913300, 295.677830, 184.777280, 154.846440, 4.76, 13.00 -ATT, 4.76, 4.78, 13.00, 8.08, 0.00, 239.33, 238.02 -CTUN, 285, 2.76, 45.17, 26.000000, 0, 1, -140, 748, 0 -NTUN, 5.48, 1.26, -328.854370, 446.915440, -224.872020, 305.602660, -203.314590, 294.953090, 172.054550, 159.853850, 3.63, 12.99 -GPS, 3, 309068000, 10, 1.49, 24.2398471, 54.5792180, 39.73, 55.97, 1.83, 264.15 -ATT, 3.63, 4.95, 12.99, 7.92, 0.00, 238.20, 238.02 -CTUN, 285, 2.64, 45.14, 26.000000, 0, 1, -139, 744, 0 -NTUN, 5.64, 1.25, -331.271120, 464.268340, -223.904400, 313.796510, -200.947130, 296.623600, 172.676210, 165.938480, 3.27, 13.34 -DU32, 7, 393457 -CURR, 286, 474348, 1129, 0, 4732, 0.000000 -ATT, 3.27, 4.53, 13.34, 8.98, 0.00, 237.48, 238.02 -CTUN, 286, 2.76, 45.28, 26.000000, 0, 1, -153, 731, 0 -NTUN, 5.79, 1.25, -334.365480, 481.406370, -223.384340, 321.620060, -190.680440, 303.535250, 157.200650, 163.235470, 2.44, 12.78 -GPS, 3, 309068200, 10, 1.49, 24.2398465, 54.5792146, 40.08, 56.33, 1.77, 262.32 -ATT, 2.44, 3.41, 12.78, 8.65, 0.00, 236.28, 238.02 -CTUN, 285, 2.76, 45.60, 26.000000, 0, 1, -144, 728, 0 -NTUN, 5.95, 1.24, -337.077090, 497.785710, -222.768600, 328.978240, -182.719440, 304.815950, 148.096420, 165.853300, 1.66, 12.67 -ATT, 1.66, 2.98, 12.67, 7.92, 0.00, 235.17, 238.02 -CTUN, 285, 4.14, 45.91, 26.000000, 0, 1, -144, 755, 0 -NTUN, 6.10, 1.23, -339.982240, 513.778630, -222.336140, 335.992680, -177.899670, 307.291810, 139.324650, 168.144350, 0.98, 12.51 -GPS, 3, 309068400, 10, 1.49, 24.2398459, 54.5792117, 40.43, 56.68, 1.53, 260.03 -ATT, 0.98, 2.31, 12.51, 7.32, 0.00, 234.52, 238.02 -CTUN, 286, 3.86, 45.88, 26.000000, 0, 1, -143, 746, 0 -NTUN, 6.22, 1.23, -340.298650, 526.687380, -220.853970, 341.820370, -181.631590, 315.307860, 152.674880, 154.699980, 1.98, 12.34 -ATT, 1.98, 1.80, 12.34, 8.06, 0.00, 234.18, 238.02 -CTUN, 286, 4.14, 45.95, 26.000000, 0, 1, -151, 747, 0 -NTUN, 6.33, 1.22, -340.457520, 539.036130, -219.376270, 347.331820, -178.508940, 317.733760, 149.777070, 157.114440, 1.69, 12.36 -GPS, 3, 309068600, 10, 1.49, 24.2398452, 54.5792091, 40.78, 57.02, 1.38, 258.36 -CTUN, 286, 3.86, 46.21, 26.000000, 0, 1, -149, 717, 0 -ATT, 1.69, 1.13, 12.36, 8.20, 0.00, 233.22, 238.02 -NTUN, 6.45, 1.21, -342.000000, 553.154170, -218.478270, 353.368900, -171.318020, 324.885350, 134.979950, 162.370790, 0.60, 12.13 -CTUN, 286, 4.14, 46.61, 26.000000, 0, 1, -135, 741, 0 -ATT, 0.60, 1.77, 12.13, 7.13, 0.00, 232.44, 238.02 -NTUN, 6.58, 1.21, -343.853210, 566.919860, -217.818600, 359.123320, -171.582990, 329.468900, 131.531370, 161.974500, 0.29, 12.00 -GPS, 3, 309068800, 10, 1.49, 24.2398444, 54.5792071, 41.13, 57.38, 1.17, 253.36 -CTUN, 286, 4.14, 46.66, 26.000000, 0, 1, -143, 757, 0 -ATT, 0.29, 1.62, 12.00, 7.09, 0.00, 232.38, 238.02 -NTUN, 6.69, 1.20, -344.575500, 579.631960, -216.675000, 364.482540, -167.625170, 327.395450, 130.436000, 168.592220, 0.03, 12.26 -CTUN, 286, 4.14, 46.60, 26.000000, 0, 0, -141, 729, 0 -ATT, 0.03, 0.43, 12.26, 7.66, 0.00, 232.48, 238.02 -NTUN, 6.81, 1.20, -345.836300, 592.352970, -215.849080, 369.709140, -161.233540, 329.416750, 120.259280, 172.265930, -0.54, 12.07 -GPS, 3, 309069000, 9, 1.75, 24.2398434, 54.5792053, 41.49, 57.75, 1.07, 248.54 -CTUN, 286, 2.22, 47.10, 26.000000, 0, 0, -129, 691, 0 -ATT, -0.54, 0.32, 12.07, 6.83, 0.00, 232.73, 238.02 -NTUN, 6.92, 1.20, -345.988460, 603.685850, -214.591400, 374.422270, -164.382980, 338.283110, 125.452220, 163.664700, 0.04, 11.87 -DU32, 7, 393457 -CURR, 285, 480980, 1156, 0, 4793, 0.000000 -CTUN, 286, 2.22, 47.37, 26.000000, 0, 0, -125, 720, 0 -ATT, 0.04, 0.82, 11.87, 5.93, 0.00, 233.63, 238.02 -NTUN, 7.01, 1.19, -345.945370, 614.583370, -213.294130, 378.924070, -159.338410, 333.882230, 119.972720, 174.018010, -0.36, 12.15 -GPS, 3, 309069200, 10, 1.49, 24.2398423, 54.5792041, 41.87, 58.09, 0.87, 240.90 -CTUN, 285, 2.22, 47.39, 26.000000, 0, 0, -128, 725, 0 -NTUN, 7.10, 1.19, -344.909910, 624.684200, -211.559200, 383.165800, -158.106540, 334.174160, 122.349240, 176.417300, -0.07, 12.34 -ATT, -0.07, 0.52, 12.34, 6.07, 0.00, 235.06, 238.02 -CTUN, 285, 2.22, 47.54, 26.000000, 0, 0, -119, 698, 0 -NTUN, 7.18, 1.18, -343.665410, 634.397710, -209.770130, 387.230350, -163.395100, 339.155430, 127.890780, 176.645450, 0.32, 12.53 -GPS, 3, 309069400, 10, 1.49, 24.2398408, 54.5792035, 42.27, 58.49, 0.87, 221.69 -ATT, 0.32, 0.15, 12.53, 6.25, 0.00, 235.62, 238.02 -CTUN, 286, 2.22, 47.69, 26.000000, 0, 0, -116, 692, 0 -NTUN, 7.24, 1.18, -340.431760, 642.187190, -207.120000, 390.709200, -165.259080, 341.705870, 138.238920, 174.444080, 0.96, 12.75 -ATT, 0.96, 0.44, 12.75, 6.60, 0.00, 235.85, 238.02 -CTUN, 285, 2.90, 47.92, 26.000000, 0, 0, -126, 706, 0 -NTUN, 7.29, 1.17, -337.037350, 649.741460, -204.419390, 394.080200, -163.412050, 340.868930, 137.006070, 180.710020, 0.65, 13.00 -GPS, 3, 309069600, 10, 1.49, 24.2398391, 54.5792031, 42.65, 58.85, 0.98, 202.97 -ATT, 0.65, 0.13, 13.00, 6.53, 0.00, 235.69, 238.02 -CTUN, 286, 2.33, 48.12, 26.000000, 0, 0, -121, 704, 0 -NTUN, 7.34, 1.17, -332.289920, 655.960080, -201.130450, 397.043460, -163.437290, 341.678560, 145.889400, 180.632570, 0.97, 13.28 -ATT, 0.97, 0.67, 13.28, 6.72, 0.00, 235.22, 238.02 -CTUN, 285, 2.90, 48.29, 26.000000, 0, 0, -118, 711, 0 -NTUN, 7.37, 1.16, -327.215330, 661.725460, -197.715420, 399.838590, -162.341710, 340.264430, 146.812120, 185.674610, 0.89, 13.54 -GPS, 3, 309069800, 9, 1.75, 24.2398371, 54.5792032, 43.06, 59.17, 1.10, 188.06 -ATT, 0.89, 1.13, 13.54, 7.49, 0.00, 235.41, 238.02 -CTUN, 285, 2.90, 48.23, 26.000000, 0, 1, -141, 731, 0 -NTUN, 7.36, 1.15, -319.032960, 663.208740, -193.032840, 401.278500, -166.234760, 341.683810, 167.298860, 175.544560, 2.34, 13.70 -ATT, 2.34, 0.80, 13.70, 8.14, 0.00, 236.02, 238.02 -CTUN, 285, 2.90, 48.54, 26.000000, 0, 0, -151, 710, 0 -NTUN, 7.34, 1.15, -310.989750, 664.372130, -188.438520, 402.564090, -162.191270, 345.688840, 164.488270, 173.728550, 2.16, 13.54 -GPS, 3, 309070000, 10, 1.49, 24.2398348, 54.5792036, 43.39, 59.50, 1.29, 176.07 -ATT, 2.16, 0.86, 13.54, 8.40, 0.00, 235.51, 238.02 -CTUN, 285, 2.90, 48.75, 26.000000, 0, 1, -142, 720, 0 -NTUN, 7.33, 1.14, -303.699710, 667.282470, -184.067140, 404.428380, -159.892940, 347.619260, 163.713840, 182.642880, 1.53, 13.96 -ATT, 1.53, 2.02, 13.96, 8.56, 0.00, 234.22, 238.02 -DU32, 7, 393457 -CURR, 286, 488087, 1144, 0, 4732, 0.000000 -CTUN, 285, 4.41, 48.89, 26.000000, 0, 1, -153, 756, 0 -NTUN, 7.33, 1.14, -296.641850, 670.349910, -179.799440, 406.309970, -158.075380, 349.018740, 164.677000, 186.815920, 1.18, 14.20 -GPS, 3, 309070200, 10, 1.49, 24.2398321, 54.5792048, 43.72, 59.81, 1.58, 164.32 -ATT, 1.18, 2.04, 14.20, 8.32, 0.00, 233.25, 238.02 -CTUN, 285, 4.41, 48.79, 26.000000, 0, 0, -154, 721, 0 -NTUN, 7.31, 1.13, -288.256590, 671.208250, -174.988390, 407.462160, -157.362610, 352.735320, 172.634160, 178.407840, 1.54, 14.12 -ATT, 1.54, 1.78, 14.12, 7.49, 0.00, 232.00, 238.02 -CTUN, 285, 4.41, 49.25, 26.000000, 0, 0, -142, 701, 0 -NTUN, 7.28, 1.12, -279.346920, 670.934690, -169.963590, 408.218110, -156.925190, 354.027070, 178.247960, 177.559510, 1.67, 14.29 -GPS, 3, 309070400, 10, 1.49, 24.2398292, 54.5792066, 44.03, 60.13, 1.83, 156.03 -ATT, 1.67, 1.74, 14.29, 7.99, 0.00, 231.50, 238.02 -CTUN, 286, 1.95, 49.41, 26.000000, 0, 1, -158, 756, 0 -NTUN, 7.21, 1.12, -267.432370, 665.615970, -163.656890, 407.327790, -153.527920, 352.970280, 193.442600, 164.184950, 3.05, 14.19 -ATT, 3.05, 1.66, 14.19, 9.29, 0.00, 232.53, 238.02 -CTUN, 286, 2.05, 49.48, 26.000000, 0, 1, -163, 750, 0 -NTUN, 7.11, 1.11, -255.686280, 659.693790, -157.423290, 406.166350, -152.492430, 364.750890, 199.335970, 150.385620, 3.93, 13.76 -GPS, 3, 309070600, 9, 1.75, 24.2398264, 54.5792085, 44.34, 60.43, 1.83, 151.97 -ATT, 3.93, 2.21, 13.76, 8.79, 0.00, 232.86, 238.02 -CTUN, 286, 2.05, 49.55, 26.000000, 0, 1, -140, 712, 0 -NTUN, 7.02, 1.10, -244.875730, 655.042480, -151.542620, 405.376430, -150.823330, 367.755220, 199.806760, 152.100830, 3.70, 13.90 -ATT, 3.70, 3.65, 13.90, 8.19, 0.00, 232.04, 238.02 -CTUN, 286, 4.17, 49.66, 26.000000, 0, 1, -142, 739, 0 -NTUN, 6.94, 1.10, -234.145390, 650.135250, -145.664840, 404.457490, -149.149860, 367.624660, 202.195820, 151.901540, 3.81, 13.97 -GPS, 3, 309070800, 10, 1.49, 24.2398236, 54.5792108, 44.66, 60.70, 1.98, 146.74 -ATT, 3.81, 3.76, 13.97, 8.75, 0.00, 232.21, 238.02 -CTUN, 286, 4.17, 49.91, 26.000000, 0, 1, -149, 723, 0 -NTUN, 6.82, 1.09, -221.158570, 640.106990, -138.805860, 401.750700, -145.323870, 372.152500, 215.589780, 127.932130, 5.30, 13.37 -ATT, 5.30, 3.64, 13.37, 9.32, 0.00, 232.18, 238.02 -CTUN, 286, 5.86, 50.13, 26.000000, 0, 1, -141, 725, 0 -NTUN, 6.68, 1.08, -208.390260, 629.280760, -132.021640, 398.668700, -140.127750, 379.006010, 217.842250, 115.179990, 5.74, 12.93 -GPS, 3, 309071000, 10, 1.49, 24.2398207, 54.5792136, 44.98, 60.97, 2.16, 142.20 -ATT, 5.74, 4.05, 12.93, 9.73, 0.00, 231.63, 238.02 -CTUN, 286, 4.99, 50.13, 26.000000, 0, 1, -122, 715, 0 -NTUN, 6.53, 1.07, -195.790410, 617.031310, -125.326770, 394.965910, -132.318540, 382.060460, 214.285840, 103.338720, 5.87, 12.35 -DU32, 7, 393457 -CURR, 285, 495358, 1124, 0, 4772, 0.000000 -ATT, 5.87, 5.00, 12.35, 8.99, 0.00, 231.32, 238.02 -CTUN, 286, 5.86, 50.16, 26.000000, 0, 1, -130, 731, 0 -NTUN, 6.38, 1.07, -183.728030, 604.778750, -118.829840, 391.152980, -130.263210, 381.731990, 217.969250, 98.870728, 6.31, 12.23 -GPS, 3, 309071200, 9, 1.75, 24.2398177, 54.5792168, 45.28, 61.26, 2.30, 138.88 -ATT, 6.31, 6.07, 12.23, 8.35, 0.00, 231.91, 238.02 -PM, 0, 0, 50, 85, 1000, 11940, 10, 0 -CTUN, 286, 4.99, 50.44, 26.000000, 0, 1, -129, 711, 0 -NTUN, 6.24, 1.06, -172.782350, 594.940670, -112.722560, 388.137050, -122.122720, 380.562560, 213.689740, 104.536060, 6.06, 12.26 -ATT, 6.06, 6.60, 12.26, 9.02, 0.00, 232.59, 238.02 -CTUN, 285, 4.99, 50.57, 26.000000, 0, 1, -123, 694, 0 -NTUN, 6.12, 1.05, -162.874390, 585.215880, -107.161740, 385.037510, -107.915980, 374.831390, 197.517850, 108.612270, 5.38, 11.81 -GPS, 3, 309071400, 9, 1.75, 24.2398146, 54.5792205, 45.61, 61.53, 2.52, 135.23 -ATT, 5.38, 6.01, 11.81, 8.36, 0.00, 233.70, 238.02 -CTUN, 286, 4.36, 50.68, 26.000000, 0, 1, -132, 711, 0 -NTUN, 5.96, 1.05, -150.899290, 570.087460, -100.551220, 379.875820, -108.613270, 376.188480, 217.105190, 80.383179, 7.52, 11.02 -ATT, 7.52, 6.58, 11.02, 7.50, 0.00, 235.12, 238.02 -CTUN, 286, 4.36, 50.68, 26.000000, 0, 1, -129, 708, 0 -NTUN, 5.79, 1.04, -138.810790, 554.754520, -93.715622, 374.532590, -106.699210, 377.483860, 224.355940, 73.567688, 8.27, 10.80 -GPS, 3, 309071600, 9, 1.75, 24.2398117, 54.5792243, 45.94, 61.79, 2.55, 132.22 -ATT, 8.27, 7.99, 10.80, 7.83, 0.00, 235.85, 238.02 -CTUN, 285, 4.05, 50.77, 26.000000, 0, 1, -128, 719, 0 -NTUN, 5.63, 1.03, -128.352050, 542.695010, -87.581497, 370.309970, -93.047081, 369.845950, 209.733900, 87.191826, 7.20, 10.93 -ATT, 7.20, 7.73, 10.93, 7.68, 0.00, 236.03, 238.02 -CTUN, 285, 4.05, 51.05, 26.000000, 0, 1, -135, 710, 0 -NTUN, 5.49, 1.02, -118.590080, 530.822270, -81.776291, 366.039640, -87.997704, 366.642910, 208.052060, 86.296753, 7.17, 10.83 -GPS, 3, 309071800, 9, 1.75, 24.2398088, 54.5792285, 46.30, 62.01, 2.68, 129.66 -ATT, 7.17, 8.17, 10.83, 6.78, 0.00, 236.02, 238.02 -ERR, 9, 1 -CTUN, 285, 2.87, 51.20, 26.000000, 0, 1, -131, 689, 0 -NTUN, 5.32, 1.02, -106.992790, 513.796630, -74.890152, 359.634550, -83.157837, 362.458770, 222.556960, 62.302116, 8.57, 10.21 -ATT, 8.57, 8.82, 10.21, 6.70, 0.00, 235.72, 238.02 -CTUN, 285, 3.56, 51.31, 26.000000, 0, 1, -134, 711, 0 -NTUN, 5.13, 1.01, -95.990349, 497.293760, -68.188095, 353.259640, -76.990067, 356.633180, 219.356990, 62.882095, 8.37, 10.17 -GPS, 3, 309072000, 9, 1.75, 24.2398060, 54.5792328, 46.55, 62.21, 2.69, 127.65 -ATT, 8.37, 8.52, 10.17, 6.16, 0.00, 235.51, 238.02 -CTUN, 285, 3.56, 51.15, 26.000000, 0, 1, -128, 710, 0 -NTUN, 4.97, 1.00, -86.074089, 483.981450, -61.899845, 348.053410, -69.844109, 348.790800, 215.882510, 76.937622, 7.75, 10.72 -DU32, 7, 393457 -CURR, 285, 502439, 1140, 0, 4793, 0.000000 -ATT, 7.75, 10.03, 10.72, 6.03, 0.00, 235.41, 238.02 -CTUN, 285, 4.96, 51.34, 26.000000, 0, 2, -141, 723, 0 -NTUN, 4.83, 0.99, -76.682487, 471.793090, -55.781124, 343.196350, -65.359337, 341.990110, 216.187210, 81.429443, 7.61, 10.94 -GPS, 3, 309072200, 9, 1.75, 24.2398034, 54.5792372, 46.84, 62.43, 2.73, 125.27 -ATT, 7.61, 10.08, 10.94, 6.31, 0.00, 235.46, 238.02 -CTUN, 286, 4.44, 51.48, 26.000000, 0, 2, -149, 720, 0 -NTUN, 4.69, 0.98, -67.031364, 458.354980, -49.384010, 337.683810, -56.940434, 335.141940, 216.337750, 76.420372, 7.69, 10.77 -ATT, 7.69, 9.78, 10.77, 6.12, 0.00, 234.75, 238.02 -CTUN, 286, 4.80, 51.33, 26.000000, 0, 1, -136, 674, 0 -NTUN, 4.54, 0.97, -58.179192, 444.868290, -43.416084, 331.981900, -45.458557, 328.545140, 207.679260, 74.980957, 7.13, 10.57 -GPS, 3, 309072400, 9, 1.75, 24.2398008, 54.5792417, 47.11, 62.61, 2.71, 123.67 -ATT, 7.13, 9.99, 10.57, 5.34, 0.00, 233.45, 238.02 -CTUN, 285, 4.80, 51.31, 26.000000, 0, 1, -118, 687, 0 -NTUN, 4.37, 0.96, -48.362175, 426.742070, -36.721622, 324.027220, -41.282887, 320.414730, 217.281800, 53.240784, 8.22, 9.97 -ATT, 8.22, 10.23, 9.97, 5.71, 0.00, 233.62, 238.02 -CTUN, 286, 5.67, 51.50, 26.000000, 0, 2, -135, 724, 0 -NTUN, 4.18, 0.95, -38.931145, 409.327640, -30.068645, 316.146060, -36.100544, 315.724150, 218.871060, 50.968674, 8.59, 9.72 -GPS, 3, 309072600, 9, 1.75, 24.2397984, 54.5792462, 47.38, 62.81, 2.65, 121.90 -ATT, 8.59, 9.11, 9.72, 6.00, 0.00, 235.10, 238.02 -CTUN, 286, 4.80, 51.88, 26.000000, 0, 1, -138, 702, 0 -NTUN, 4.00, 0.94, -29.619865, 391.596190, -23.285477, 307.850980, -29.666311, 311.005220, 221.516850, 42.211372, 9.20, 9.22 -ATT, 9.20, 9.30, 9.22, 5.98, 0.00, 236.19, 238.02 -CTUN, 286, 4.80, 52.21, 26.000000, 0, 1, -136, 675, 0 -NTUN, 3.81, 0.93, -20.735466, 374.033690, -16.594879, 299.344300, -25.818489, 309.435420, 223.243530, 33.775414, 9.67, 8.74 -GPS, 3, 309072800, 10, 1.49, 24.2397960, 54.5792508, 47.62, 63.00, 2.70, 120.69 -ATT, 9.67, 10.20, 8.74, 5.52, 0.00, 236.84, 238.02 -CTUN, 286, 3.69, 52.21, 26.000000, 0, 1, -133, 695, 0 -NTUN, 3.63, 0.92, -11.606926, 355.792480, -9.466495, 290.180850, -19.643200, 303.147130, 229.283840, 24.365479, 10.32, 8.41 -ATT, 10.32, 10.34, 8.41, 4.23, 0.00, 237.14, 238.02 -CTUN, 285, 3.69, 52.03, 26.000000, 0, 1, -136, 695, 0 -NTUN, 3.45, 0.91, -3.034904, 338.230590, -2.521475, 281.010530, -13.778031, 294.234920, 229.450200, 22.296814, 10.43, 8.28 -GPS, 3, 309073000, 10, 1.49, 24.2397938, 54.5792554, 47.85, 63.21, 2.63, 119.38 -ATT, 10.43, 10.98, 8.28, 3.53, 0.00, 237.18, 238.02 -CTUN, 285, 2.43, 52.27, 26.000000, 0, 1, -123, 670, 0 -NTUN, 3.27, 0.89, 5.349739, 320.591550, 4.529256, 271.422820, -6.153962, 284.912350, 228.809220, 19.072205, 10.46, 8.15 -DU32, 7, 393457 -CURR, 286, 509386, 1134, 0, 4752, 0.000000 -ATT, 10.46, 11.86, 8.15, 3.77, 0.00, 237.06, 238.02 -CTUN, 285, 2.54, 52.44, 26.000000, 0, 1, -128, 701, 0 -NTUN, 3.10, 0.88, 13.168953, 303.886470, 11.352031, 261.959230, -1.071572, 276.136410, 230.227750, 17.364075, 10.60, 8.09 -GPS, 3, 309073200, 10, 1.49, 24.2397916, 54.5792600, 48.10, 63.41, 2.64, 118.20 -ATT, 10.60, 11.95, 8.09, 3.61, 0.00, 237.27, 238.02 -CTUN, 285, 2.54, 52.43, 26.000000, 0, 1, -143, 692, 0 -NTUN, 2.95, 0.86, 20.533577, 290.117310, 17.965347, 253.830980, 7.739331, 263.991150, 226.133160, 33.717499, 9.93, 8.72 -ATT, 9.93, 12.01, 8.72, 2.96, 0.00, 237.17, 238.02 -CTUN, 285, 3.96, 52.57, 26.000000, 0, 1, -127, 666, 0 -NTUN, 2.83, 0.85, 27.293098, 277.118530, 24.215338, 245.868700, 13.517757, 253.555160, 222.881090, 39.165543, 9.57, 8.93 -GPS, 3, 309073400, 10, 1.49, 24.2397895, 54.5792647, 48.33, 63.61, 2.63, 117.24 -ATT, 9.57, 12.62, 8.93, 2.87, 0.00, 237.18, 238.02 -CTUN, 285, 2.54, 52.68, 26.000000, 0, 2, -130, 709, 0 -NTUN, 2.68, 0.83, 34.460945, 260.539920, 31.124741, 235.316740, 19.215595, 243.002460, 231.094020, 12.480438, 10.92, 7.71 -ATT, 10.92, 11.82, 7.71, 2.77, 0.00, 238.55, 238.02 -CTUN, 286, 3.96, 52.79, 26.000000, 0, 1, -145, 694, 0 -NTUN, 2.53, 0.81, 41.224495, 244.788330, 37.859127, 224.805010, 25.212904, 234.121870, 231.343870, 9.882660, 11.20, 7.30 -GPS, 3, 309073600, 10, 1.49, 24.2397875, 54.5792691, 48.57, 63.83, 2.50, 116.93 -ATT, 11.20, 11.94, 7.30, 2.00, 0.00, 239.97, 238.02 -CTUN, 286, 3.96, 52.95, 26.000000, 0, 0, -129, 656, 0 -NTUN, 2.39, 0.79, 47.936653, 229.169920, 44.734993, 213.863800, 32.439617, 223.245450, 233.077880, 6.671211, 11.50, 7.00 diff --git a/Tools/LogAnalyzer/examples/underpowered.log b/Tools/LogAnalyzer/examples/underpowered.log deleted file mode 100644 index 7c3cf667682c22..00000000000000 --- a/Tools/LogAnalyzer/examples/underpowered.log +++ /dev/null @@ -1,9888 +0,0 @@ -1 - -ArduCopter V3.0.1 -Free RAM: 1696 -APM 2 -FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format -FMT, 129, 23, PARM, Nf, Name,Value -FMT, 130, 35, GPS, BIBcLLeeEe, Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs -FMT, 131, 27, IMU, ffffff, GyrX,GyrY,GyrZ,AccX,AccY,AccZ -FMT, 132, 67, MSG, Z, Message -FMT, 9, 19, CURR, hIhhhf, Thr,ThrInt,Volt,Curr,Vcc,CurrTot -FMT, 11, 11, MOT, hhhh, Mot1,Mot2,Mot3,Mot4 -FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch -FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit -FMT, 4, 25, CTUN, hcefhhhhh, ThrIn,SonAlt,BarAlt,WPAlt,NavThr,AngBst,CRate,ThrOut,DCRate -FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ -FMT, 6, 17, PM, BBBHHIhB, RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr -FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng -FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw -FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng -FMT, 3, 6, MODE, Mh, Mode,ThrCrs -FMT, 10, 3, STRT, , -FMT, 13, 4, EV, B, Id -FMT, 20, 6, D16, Bh, Id,Value -FMT, 21, 6, DU16, BH, Id,Value -FMT, 22, 8, D32, Bi, Id,Value -FMT, 23, 8, DU32, BI, Id,Value -FMT, 24, 8, DFLT, Bf, Id,Value -FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain -FMT, 16, 15, DMP, ccccCC, DCMRoll,DMPRoll,DCMPtch,DMPPtch,DCMYaw,DMPYaw -FMT, 18, 25, CAM, ILLeccC, GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw -FMT, 19, 5, ERR, BB, Subsys,ECode -PARM, SYSID_SW_MREV, 120.000000 -PARM, SYSID_SW_TYPE, 10.000000 -PARM, SYSID_THISMAV, 1.000000 -PARM, SYSID_MYGCS, 253.000000 -PARM, SERIAL3_BAUD, 57.000000 -PARM, TELEM_DELAY, 0.000000 -PARM, RTL_ALT, 1500.000000 -PARM, SONAR_ENABLE, 1.000000 -PARM, SONAR_TYPE, 0.000000 -PARM, SONAR_GAIN, 0.200000 -PARM, BATT_MONITOR, 4.000000 -PARM, FS_BATT_ENABLE, 0.000000 -PARM, FS_GPS_ENABLE, 1.000000 -PARM, FS_GCS_ENABLE, 0.000000 -PARM, VOLT_DIVIDER, 15.701050 -PARM, AMP_PER_VOLT, 27.320000 -PARM, BATT_CAPACITY, 4000.000000 -PARM, MAG_ENABLE, 1.000000 -PARM, FLOW_ENABLE, 0.000000 -PARM, LOW_VOLT, 9.400000 -PARM, SUPER_SIMPLE, 0.000000 -PARM, RTL_ALT_FINAL, 200.000000 -PARM, BATT_VOLT_PIN, 1.000000 -PARM, BATT_CURR_PIN, 2.000000 -PARM, RSSI_PIN, -1.000000 -PARM, THR_ACC_ENABLE, 1.000000 -PARM, WP_YAW_BEHAVIOR, 2.000000 -PARM, WP_TOTAL, 2.000000 -PARM, WP_INDEX, 0.000000 -PARM, CIRCLE_RADIUS, 10.000000 -PARM, CIRCLE_RATE, 5.000000 -PARM, RTL_LOIT_TIME, 5000.000000 -PARM, LAND_SPEED, 50.000000 -PARM, PILOT_VELZ_MAX, 250.000000 -PARM, THR_MIN, 130.000000 -PARM, THR_MAX, 1000.000000 -PARM, FS_THR_ENABLE, 0.000000 -PARM, FS_THR_VALUE, 975.000000 -PARM, TRIM_THROTTLE, 782.000000 -PARM, THR_MID, 500.000000 -PARM, FLTMODE1, 0.000000 -PARM, FLTMODE2, 5.000000 -PARM, FLTMODE3, 2.000000 -PARM, FLTMODE4, 7.000000 -PARM, FLTMODE5, 6.000000 -PARM, FLTMODE6, 8.000000 -PARM, SIMPLE, 0.000000 -PARM, LOG_BITMASK, 830.000000 -PARM, TOY_RATE, 1.000000 -PARM, ESC, 0.000000 -PARM, TUNE, 0.000000 -PARM, TUNE_LOW, 0.000000 -PARM, TUNE_HIGH, 1000.000000 -PARM, FRAME, 2.000000 -PARM, CH7_OPT, 7.000000 -PARM, CH8_OPT, 0.000000 -PARM, ARMING_CHECK, 0.000000 -PARM, RC1_MIN, 988.000000 -PARM, RC1_TRIM, 1498.000000 -PARM, RC1_MAX, 2003.000000 -PARM, RC1_REV, -1.000000 -PARM, RC1_DZ, 30.000000 -PARM, RC2_MIN, 986.000000 -PARM, RC2_TRIM, 1498.000000 -PARM, RC2_MAX, 2010.000000 -PARM, RC2_REV, -1.000000 -PARM, RC2_DZ, 30.000000 -PARM, RC3_MIN, 986.000000 -PARM, RC3_TRIM, 989.000000 -PARM, RC3_MAX, 2014.000000 -PARM, RC3_REV, 1.000000 -PARM, RC3_DZ, 30.000000 -PARM, RC4_MIN, 985.000000 -PARM, RC4_TRIM, 1502.000000 -PARM, RC4_MAX, 2010.000000 -PARM, RC4_REV, 1.000000 -PARM, RC4_DZ, 40.000000 -PARM, RC5_MIN, 1175.000000 -PARM, RC5_TRIM, 1179.000000 -PARM, RC5_MAX, 1839.000000 -PARM, RC5_REV, 1.000000 -PARM, RC5_DZ, 0.000000 -PARM, RC5_FUNCTION, 0.000000 -PARM, RC6_MIN, 985.000000 -PARM, RC6_TRIM, 990.000000 -PARM, RC6_MAX, 2014.000000 -PARM, RC6_REV, 1.000000 -PARM, RC6_DZ, 0.000000 -PARM, RC6_FUNCTION, 0.000000 -PARM, RC7_MIN, 985.000000 -PARM, RC7_TRIM, 989.000000 -PARM, RC7_MAX, 2014.000000 -PARM, RC7_REV, 1.000000 -PARM, RC7_DZ, 0.000000 -PARM, RC7_FUNCTION, 0.000000 -PARM, RC8_MIN, 1498.000000 -PARM, RC8_TRIM, 1498.000000 -PARM, RC8_MAX, 1499.000000 -PARM, RC8_REV, 1.000000 -PARM, RC8_DZ, 0.000000 -PARM, RC8_FUNCTION, 0.000000 -PARM, RC10_MIN, 1100.000000 -PARM, RC10_TRIM, 1500.000000 -PARM, RC10_MAX, 1900.000000 -PARM, RC10_REV, 1.000000 -PARM, RC10_DZ, 0.000000 -PARM, RC10_FUNCTION, 0.000000 -PARM, RC11_MIN, 1100.000000 -PARM, RC11_TRIM, 1500.000000 -PARM, RC11_MAX, 1900.000000 -PARM, RC11_REV, 1.000000 -PARM, RC11_DZ, 0.000000 -PARM, RC11_FUNCTION, 0.000000 -PARM, RC_SPEED, 490.000000 -PARM, ACRO_P, 4.500000 -PARM, AXIS_ENABLE, 1.000000 -PARM, ACRO_BAL_ROLL, 200.000000 -PARM, ACRO_BAL_PITCH, 200.000000 -PARM, ACRO_TRAINER, 1.000000 -PARM, LED_MODE, 9.000000 -PARM, RATE_RLL_P, 0.150000 -PARM, RATE_RLL_I, 0.100000 -PARM, RATE_RLL_D, 0.004000 -PARM, RATE_RLL_IMAX, 500.000000 -PARM, RATE_PIT_P, 0.150000 -PARM, RATE_PIT_I, 0.100000 -PARM, RATE_PIT_D, 0.004000 -PARM, RATE_PIT_IMAX, 500.000000 -PARM, RATE_YAW_P, 0.200000 -PARM, RATE_YAW_I, 0.020000 -PARM, RATE_YAW_D, 0.000000 -PARM, RATE_YAW_IMAX, 800.000000 -PARM, LOITER_LAT_P, 1.000000 -PARM, LOITER_LAT_I, 0.500000 -PARM, LOITER_LAT_D, 0.000000 -PARM, LOITER_LAT_IMAX, 400.000000 -PARM, LOITER_LON_P, 1.000000 -PARM, LOITER_LON_I, 0.500000 -PARM, LOITER_LON_D, 0.000000 -PARM, LOITER_LON_IMAX, 400.000000 -PARM, THR_RATE_P, 6.000000 -PARM, THR_RATE_I, 0.000000 -PARM, THR_RATE_D, 0.000000 -PARM, THR_RATE_IMAX, 300.000000 -PARM, THR_ACCEL_P, 0.750000 -PARM, THR_ACCEL_I, 1.500000 -PARM, THR_ACCEL_D, 0.000000 -PARM, THR_ACCEL_IMAX, 500.000000 -PARM, OF_RLL_P, 2.500000 -PARM, OF_RLL_I, 0.500000 -PARM, OF_RLL_D, 0.120000 -PARM, OF_RLL_IMAX, 100.000000 -PARM, OF_PIT_P, 2.500000 -PARM, OF_PIT_I, 0.500000 -PARM, OF_PIT_D, 0.120000 -PARM, OF_PIT_IMAX, 100.000000 -PARM, STB_RLL_P, 4.500000 -PARM, STB_RLL_I, 0.000000 -PARM, STB_RLL_IMAX, 800.000000 -PARM, STB_PIT_P, 4.500000 -PARM, STB_PIT_I, 0.000000 -PARM, STB_PIT_IMAX, 800.000000 -PARM, STB_YAW_P, 4.500000 -PARM, STB_YAW_I, 0.000000 -PARM, STB_YAW_IMAX, 800.000000 -PARM, THR_ALT_P, 1.000000 -PARM, THR_ALT_I, 0.000000 -PARM, THR_ALT_IMAX, 300.000000 -PARM, HLD_LAT_P, 1.000000 -PARM, HLD_LAT_I, 0.000000 -PARM, HLD_LAT_IMAX, 3000.000000 -PARM, HLD_LON_P, 1.000000 -PARM, HLD_LON_I, 0.000000 -PARM, HLD_LON_IMAX, 3000.000000 -PARM, CAM_TRIGG_TYPE, 0.000000 -PARM, CAM_DURATION, 10.000000 -PARM, CAM_SERVO_ON, 1300.000000 -PARM, CAM_SERVO_OFF, 1100.000000 -PARM, COMPASS_OFS_X, 0.000000 -PARM, COMPASS_OFS_Y, 0.000000 -PARM, COMPASS_OFS_Z, 0.000000 -PARM, COMPASS_DEC, 0.000000 -PARM, COMPASS_LEARN, 0.000000 -PARM, COMPASS_USE, 1.000000 -PARM, COMPASS_AUTODEC, 1.000000 -PARM, COMPASS_MOTCT, 0.000000 -PARM, COMPASS_MOT_X, 0.000000 -PARM, COMPASS_MOT_Y, 0.000000 -PARM, COMPASS_MOT_Z, 0.000000 -PARM, COMPASS_ORIENT, 0.000000 -PARM, INS_PRODUCT_ID, 88.000000 -PARM, INS_ACCSCAL_X, 1.002061 -PARM, INS_ACCSCAL_Y, 1.000603 -PARM, INS_ACCSCAL_Z, 0.988811 -PARM, INS_ACCOFFS_X, -0.071901 -PARM, INS_ACCOFFS_Y, 0.362812 -PARM, INS_ACCOFFS_Z, 0.146283 -PARM, INS_GYROFFS_X, -0.000372 -PARM, INS_GYROFFS_Y, -0.027095 -PARM, INS_GYROFFS_Z, -0.009971 -PARM, INS_MPU6K_FILTER, 0.000000 -PARM, INAV_TC_XY, 2.500000 -PARM, INAV_TC_Z, 5.000000 -PARM, WPNAV_SPEED, 500.000000 -PARM, WPNAV_RADIUS, 200.000000 -PARM, WPNAV_SPEED_UP, 250.000000 -PARM, WPNAV_SPEED_DN, 150.000000 -PARM, WPNAV_LOIT_SPEED, 500.000000 -PARM, WPNAV_ACCEL, 100.000000 -PARM, SR0_RAW_SENS, 0.000000 -PARM, SR0_EXT_STAT, 0.000000 -PARM, SR0_RC_CHAN, 0.000000 -PARM, SR0_RAW_CTRL, 0.000000 -PARM, SR0_POSITION, 0.000000 -PARM, SR0_EXTRA1, 0.000000 -PARM, SR0_EXTRA2, 0.000000 -PARM, SR0_EXTRA3, 0.000000 -PARM, SR0_PARAMS, 0.000000 -PARM, SR3_RAW_SENS, 0.000000 -PARM, SR3_EXT_STAT, 0.000000 -PARM, SR3_RC_CHAN, 0.000000 -PARM, SR3_RAW_CTRL, 0.000000 -PARM, SR3_POSITION, 0.000000 -PARM, SR3_EXTRA1, 0.000000 -PARM, SR3_EXTRA2, 0.000000 -PARM, SR3_EXTRA3, 0.000000 -PARM, SR3_PARAMS, 0.000000 -PARM, AHRS_GPS_GAIN, 1.000000 -PARM, AHRS_GPS_USE, 1.000000 -PARM, AHRS_YAW_P, 0.100000 -PARM, AHRS_RP_P, 0.100000 -PARM, AHRS_WIND_MAX, 0.000000 -PARM, AHRS_TRIM_X, 0.002719 -PARM, AHRS_TRIM_Y, 0.013084 -PARM, AHRS_TRIM_Z, 0.000000 -PARM, AHRS_ORIENTATION, 0.000000 -PARM, AHRS_COMP_BETA, 0.100000 -PARM, AHRS_GPS_MINSATS, 6.000000 -PARM, MNT_MODE, 0.000000 -PARM, MNT_RETRACT_X, 0.000000 -PARM, MNT_RETRACT_Y, 0.000000 -PARM, MNT_RETRACT_Z, 0.000000 -PARM, MNT_NEUTRAL_X, 0.000000 -PARM, MNT_NEUTRAL_Y, 0.000000 -PARM, MNT_NEUTRAL_Z, 0.000000 -PARM, MNT_CONTROL_X, 0.000000 -PARM, MNT_CONTROL_Y, 0.000000 -PARM, MNT_CONTROL_Z, 0.000000 -PARM, MNT_STAB_ROLL, 0.000000 -PARM, MNT_STAB_TILT, 0.000000 -PARM, MNT_STAB_PAN, 0.000000 -PARM, MNT_RC_IN_ROLL, 0.000000 -PARM, MNT_ANGMIN_ROL, -4500.000000 -PARM, MNT_ANGMAX_ROL, 4500.000000 -PARM, MNT_RC_IN_TILT, 0.000000 -PARM, MNT_ANGMIN_TIL, -4500.000000 -PARM, MNT_ANGMAX_TIL, 4500.000000 -PARM, MNT_RC_IN_PAN, 0.000000 -PARM, MNT_ANGMIN_PAN, -4500.000000 -PARM, MNT_ANGMAX_PAN, 4500.000000 -PARM, MNT_JSTICK_SPD, 0.000000 -PARM, GND_ABS_PRESS, 99088.188000 -PARM, GND_TEMP, 27.673569 -PARM, SCHED_DEBUG, 0.000000 -PARM, FENCE_ENABLE, 0.000000 -PARM, FENCE_TYPE, 3.000000 -PARM, FENCE_ACTION, 1.000000 -PARM, FENCE_ALT_MAX, 100.000000 -PARM, FENCE_RADIUS, 150.000000 -PARM, MOT_TCRV_ENABLE, 1.000000 -PARM, MOT_TCRV_MIDPCT, 52.000000 -PARM, MOT_TCRV_MAXPCT, 93.000000 -D32, 9, 6794 -EV, 10 -EV, 15 -ERR, 7, 1 -CTUN, 164, 1.98, -0.01, 0.000000, 0, 0, 14, 165, 0 -ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.94, 67.94 -CTUN, 165, 1.98, 0.03, 0.000000, 0, 0, 13, 164, 0 -ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.91, 67.94 -CTUN, 165, 1.98, -0.11, 0.000000, 0, 0, 12, 165, 0 -ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.87, 67.94 -CTUN, 164, 1.98, -0.26, 0.000000, 0, 0, 11, 165, 0 -ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.82, 67.94 -CTUN, 165, 1.98, -0.52, 0.000000, 0, 0, 10, 165, 0 -ATT, 0.00, 0.01, -2.24, 0.04, 0.00, 67.78, 67.94 -CTUN, 165, 1.98, -0.65, 0.000000, 0, 0, 9, 165, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.74, 67.94 -CTUN, 164, 1.99, -0.66, 0.000000, 0, 0, 7, 164, 0 -DU32, 7, 133372 -CURR, 164, 1153, 1198, 297, 5028, 0.654078 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.71, 67.94 -CTUN, 165, 1.98, -0.80, 0.000000, 0, 0, 6, 165, 0 -ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.69, 67.94 -CTUN, 165, 1.98, -0.76, 0.000000, 0, 0, 5, 164, 0 -ATT, 0.00, 0.02, -2.24, 0.03, 0.00, 67.66, 67.94 -CTUN, 164, 1.98, -0.71, 0.000000, 0, 0, 3, 164, 0 -ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.63, 67.94 -CTUN, 158, 1.99, -0.70, 0.000000, 0, 0, 2, 165, 0 -ATT, 0.00, 0.01, -2.14, 0.03, 0.00, 67.60, 67.60 -CTUN, 0, 1.99, -0.94, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.58, 67.58 -CTUN, 0, 1.99, -0.71, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.99, -0.51, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.02, -2.14, 0.03, 0.00, 67.59, 67.59 -CTUN, 0, 1.99, -0.42, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.57, 67.57 -CTUN, 0, 1.99, -0.23, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 -PM, 0, 0, 0, 2, 1000, 6014860, 0, 0 -CTUN, 0, 1.99, -0.15, 0.000000, 0, 0, -3, 0, 0 -DU32, 7, 133308 -CURR, 0, 1811, 1210, 0, 5028, 1.030283 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 -CTUN, 0, 1.99, -0.22, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.99, -0.24, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 -CTUN, 0, 1.99, -0.09, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.99, -0.13, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.99, -0.10, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.14, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.99, -0.08, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.98, -0.14, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.07, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.07, 0.000000, 0, 0, -4, 0, 0 -DU32, 7, 133308 -CURR, 0, 1811, 1212, 0, 5051, 1.031275 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.13, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.12, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.17, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, -0.11, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.15, 0.000000, 0, 0, -4, 0, 0 -DU32, 7, 133308 -CURR, 0, 1811, 1213, 0, 5051, 1.031928 -ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.42, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.15, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.00, -2.33, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 -CTUN, 133, 1.98, -0.06, 0.000000, 0, 0, -3, 0, 0 -EV, 15 -ATT, 0.00, 0.00, -2.33, 0.03, 0.00, 67.57, 67.57 -CTUN, 160, 1.98, 0.00, 0.000000, 0, 0, -3, 152, 0 -DU32, 7, 133372 -CURR, 163, 1963, 1195, 281, 5051, 1.110572 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.57 -CTUN, 176, 1.98, -0.07, 0.000000, 0, 0, -3, 170, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.53, 67.57 -CTUN, 194, 1.98, -0.07, 0.000000, 0, 0, -3, 191, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.50, 67.57 -CTUN, 212, 1.98, -0.09, 0.000000, 0, 0, -2, 210, 0 -ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.48, 67.57 -CTUN, 235, 1.98, -0.26, 0.000000, 0, 0, -2, 232, 0 -ATT, 0.00, -0.01, -2.24, 0.03, 0.00, 67.46, 67.57 -CTUN, 245, 1.98, -0.46, 0.000000, 0, 0, -2, 244, 0 -ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.44, 67.57 -CTUN, 276, 1.98, -0.43, 0.000000, 0, 0, -3, 261, 0 -ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.40, 67.57 -CTUN, 298, 1.98, -0.58, 0.000000, 0, 0, -3, 298, 0 -ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.37, 67.57 -CTUN, 324, 1.98, -0.65, 0.000000, 0, 0, -4, 320, 0 -ATT, 0.00, -0.01, -2.24, 0.02, 0.00, 67.33, 67.57 -CTUN, 351, 1.98, -0.68, 0.000000, 0, 0, -4, 345, 0 -ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.29, 67.57 -CTUN, 372, 1.98, -1.01, 0.000000, 0, 0, -4, 372, 0 -DU32, 7, 133372 -CURR, 381, 4606, 1179, 619, 5051, 2.136434 -ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.24, 67.57 -CTUN, 395, 1.98, -1.06, 0.000000, 0, 0, -5, 395, 0 -ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.18, 67.57 -CTUN, 406, 1.98, -1.30, 0.000000, 0, 0, -7, 406, 0 -ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 67.12, 67.57 -EV, 16 -CTUN, 422, 1.98, -1.34, 0.000000, 0, 0, -7, 422, 0 -ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 67.05, 67.57 -CTUN, 434, 1.99, -1.49, 0.000000, 0, 0, -8, 432, 0 -ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 66.98, 67.57 -CTUN, 439, 1.99, -1.52, 0.000000, 0, 0, -10, 438, 0 -ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 66.92, 67.57 -CTUN, 442, 1.99, -1.61, 0.000000, 0, 0, -11, 439, 0 -ATT, 0.00, -0.04, -2.24, 0.00, 0.00, 66.84, 67.57 -CTUN, 453, 1.99, -1.75, 0.000000, 0, 0, -12, 453, 0 -ATT, 0.00, -0.04, -2.24, 0.00, 0.00, 66.77, 67.57 -CTUN, 469, 2.00, -1.81, 0.000000, 0, 0, -13, 468, 0 -ATT, 0.00, -0.05, -2.33, 0.00, 0.00, 66.68, 67.57 -CTUN, 488, 2.00, -1.98, 0.000000, 0, 0, -14, 488, 0 -ATT, 0.00, -0.07, -2.33, 0.00, 0.00, 66.60, 67.57 -CTUN, 508, 3.83, -1.99, 0.000000, 0, 0, -15, 504, 0 -DU32, 7, 166140 -CURR, 510, 9051, 1149, 1139, 5028, 4.570772 -ATT, 0.00, -0.07, -2.24, -0.01, 0.00, 66.51, 67.57 -CTUN, 510, 2.03, -2.03, 0.000000, 0, 0, -16, 510, 0 -ATT, 0.00, -0.08, -2.24, -0.02, 0.00, 66.40, 67.57 -CTUN, 519, 2.03, -2.20, 0.000000, 0, 0, -16, 517, 0 -ATT, 0.00, -0.09, -2.24, -0.02, 0.00, 66.31, 67.57 -CTUN, 535, 1.99, -2.46, 0.000000, 0, 0, -18, 535, 0 -ATT, 0.00, -0.10, -2.24, -0.01, 0.00, 66.21, 67.57 -CTUN, 543, 1.99, -2.24, 0.000000, 0, 0, -20, 541, 0 -ATT, 0.00, -0.12, -2.24, -0.02, 0.00, 66.10, 67.57 -CTUN, 545, 1.99, -2.40, 0.000000, 0, 0, -19, 545, 0 -ATT, 0.00, -0.14, -2.24, -0.03, 0.00, 65.99, 67.57 -CTUN, 571, 1.99, -2.24, 0.000000, 0, 0, -25, 565, 0 -ATT, 0.00, -0.20, -2.24, -0.04, 0.00, 65.88, 67.57 -CTUN, 588, 1.99, -2.37, 0.000000, 0, 0, -26, 588, 0 -ATT, 0.00, -0.38, -2.14, -0.03, 0.00, 65.79, 67.57 -CTUN, 597, 1.99, -2.22, 0.000000, 0, 0, -28, 597, 0 -ATT, 0.00, -0.60, -2.24, -0.01, 0.00, 65.72, 67.57 -CTUN, 621, 1.99, -2.71, 0.000000, 0, 0, -28, 621, 0 -ATT, 0.00, -1.44, -2.24, 0.04, 0.00, 65.68, 67.57 -CTUN, 636, 3.00, -2.47, 0.000000, 0, 0, -25, 636, 0 -DU32, 7, 166140 -CURR, 636, 14706, 1111, 1700, 5051, 8.368493 -ATT, 0.00, -2.69, -2.24, -0.44, 0.00, 65.88, 67.57 -CTUN, 639, 3.00, -2.12, 0.000000, 0, 0, -25, 639, 0 -ATT, 0.00, -3.88, -2.05, -2.01, 0.00, 66.52, 67.57 -CTUN, 639, 3.00, -1.85, 0.000000, 0, 1, -21, 638, 0 -ATT, 0.00, -5.46, -2.05, -3.96, 0.00, 67.51, 67.57 -CTUN, 639, 3.00, -1.11, 0.000000, 0, 4, -23, 643, 0 -ATT, 1.96, -7.33, -1.86, -5.06, 0.00, 68.76, 67.57 -CTUN, 639, 3.00, -0.93, 0.000000, 0, 7, -25, 646, 0 -ATT, 2.53, -8.21, -1.21, -6.58, 0.00, 70.50, 67.57 -CTUN, 639, 2.59, -1.00, 0.000000, 0, 9, -29, 648, 0 -ATT, 2.90, -8.33, 0.00, -7.53, 0.00, 72.38, 67.57 -CTUN, 639, 2.59, -0.78, 0.000000, 0, 9, -31, 648, 0 -ATT, 5.06, -8.06, 0.00, -7.18, 0.00, 73.85, 67.57 -CTUN, 639, 0.21, -0.72, 0.000000, 0, 8, -35, 647, 0 -ATT, 6.28, -6.97, 0.00, -6.10, 0.00, 75.00, 67.57 -CTUN, 638, 0.21, -1.16, 0.000000, 0, 5, -38, 643, 0 -ATT, 7.40, -4.56, 0.00, -5.31, 0.00, 76.14, 67.57 -CTUN, 639, 0.20, -1.86, 0.000000, 0, 2, -39, 641, 0 -ATT, 7.78, -2.30, 0.00, -3.88, 0.00, 76.58, 67.57 -CTUN, 641, 0.21, -1.72, 0.000000, 0, 1, -37, 643, 0 -DU32, 7, 166140 -CURR, 641, 21139, 1119, 1700, 5051, 13.092842 -ATT, 7.87, -0.48, 0.00, -2.13, 0.00, 76.59, 67.57 -CTUN, 655, 0.21, -2.22, 0.000000, 0, 0, -34, 653, 0 -ATT, 8.53, -0.11, 0.37, -0.19, 0.00, 76.29, 67.57 -CTUN, 662, 2.57, -2.02, 0.000000, 0, 0, -23, 661, 0 -ATT, 10.03, -0.78, 4.01, -0.78, 0.00, 76.19, 67.57 -CTUN, 663, 2.57, -1.90, 0.000000, 0, 0, -22, 663, 0 -ATT, 12.37, -1.41, 5.60, -0.77, 0.00, 76.10, 67.57 -CTUN, 666, 5.86, -2.13, 0.000000, 0, 0, -26, 666, 0 -ATT, 15.46, -0.51, 6.53, -1.91, 0.00, 76.35, 67.57 -CTUN, 666, 5.86, -2.17, 0.000000, 0, 0, -29, 666, 0 -ATT, 18.09, -0.18, 8.02, -1.83, 0.00, 76.12, 67.57 -CTUN, 666, 7.61, -1.94, 0.000000, 0, 0, -29, 666, 0 -ATT, 18.65, -0.01, 8.21, -0.67, 0.00, 75.66, 67.57 -CTUN, 680, 7.61, -2.30, 0.000000, 0, 0, -27, 678, 0 -ATT, 19.87, -0.07, 12.04, -0.72, 0.00, 75.50, 67.57 -CTUN, 711, 7.61, -2.32, 0.000000, 0, 0, -25, 702, 0 -ATT, 18.75, -0.20, 13.25, -1.65, 0.00, 75.27, 67.57 -CTUN, 711, 7.51, -2.44, 0.000000, 0, 0, -25, 711, 0 -ATT, 16.40, -0.60, 16.24, -1.70, 0.00, 74.87, 67.57 -CTUN, 713, 7.51, -2.31, 0.000000, 0, 0, -25, 711, 0 -DU32, 7, 166140 -CURR, 713, 27907, 1086, 2084, 5051, 18.359875 -ATT, 14.53, -1.87, 20.16, -0.42, 0.00, 74.30, 67.57 -CTUN, 711, 2.11, -2.13, 0.000000, 0, 0, -24, 711, 0 -ATT, 15.00, -2.86, 21.56, 0.01, 0.00, 74.29, 67.57 -CTUN, 711, 2.11, -1.97, 0.000000, 0, 0, -25, 711, 0 -ATT, 15.37, -3.63, 21.56, 0.16, 0.00, 74.57, 67.57 -CTUN, 711, 2.11, -1.83, 0.000000, 0, 1, -30, 711, 0 -ATT, 15.56, -3.58, 23.52, 0.17, 0.00, 74.74, 67.57 -CTUN, 713, 6.65, -1.50, 0.000000, 0, 1, -30, 713, 0 -ATT, 15.56, -2.99, 25.02, 0.11, 0.00, 74.67, 67.57 -CTUN, 723, 6.65, -1.92, 0.000000, 0, 0, -30, 723, 0 -ATT, 15.46, -2.17, 26.14, 0.03, 0.00, 74.46, 67.57 -CTUN, 750, 7.57, -1.99, 0.000000, 0, 0, -27, 748, 0 -ATT, 15.56, -2.01, 26.42, 0.00, 0.00, 74.29, 67.57 -CTUN, 765, 6.65, -1.75, 0.000000, 0, 0, -27, 765, 0 -ATT, 15.65, -2.04, 28.66, 0.00, 0.00, 74.07, 67.57 -CTUN, 771, 7.51, -1.74, 0.000000, 0, 0, -27, 770, 0 -ATT, 15.56, -1.79, 28.66, -0.04, 0.00, 73.89, 67.57 -CTUN, 796, 7.51, -1.44, 0.000000, 0, 0, -26, 796, 0 -ATT, 15.56, -1.43, 29.12, -0.09, 0.00, 73.72, 67.57 -CTUN, 835, 7.65, -1.41, 0.000000, 0, 0, -28, 821, 0 -DU32, 7, 166140 -CURR, 842, 35358, 1077, 2047, 5051, 24.099819 -ATT, 15.56, -1.17, 29.03, -0.13, 0.00, 73.53, 67.57 -CTUN, 868, 7.65, -1.84, 0.000000, 0, 0, -25, 868, 0 -ATT, 15.75, -1.19, 28.47, -0.13, 0.00, 73.37, 67.57 -CTUN, 867, 7.65, -1.42, 0.000000, 0, 0, -27, 871, 0 -ATT, 15.75, -1.25, 19.51, -0.15, 0.00, 73.21, 67.57 -CTUN, 522, 7.65, -1.10, 0.000000, 0, 0, -25, 606, 0 -ATT, 0.00, -1.65, 0.00, -0.18, 0.00, 73.04, 67.57 -CTUN, 133, 7.65, -2.46, 0.000000, 0, 0, -23, 294, 0 -ATT, 0.00, -1.05, -2.24, -0.28, 0.00, 73.14, 73.14 -CTUN, 0, 3.93, -1.91, 0.000000, 0, 0, -24, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.34, 0.00, 73.33, 73.33 -CTUN, 0, 3.93, -1.17, 0.000000, 0, 0, -26, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.33, 0.00, 73.43, 73.43 -CTUN, 0, 1.99, -0.77, 0.000000, 0, 0, -24, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.32, 0.00, 73.56, 73.56 -CTUN, 0, 1.99, -0.42, 0.000000, 0, 0, -23, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.32, 0.00, 73.69, 73.69 -CTUN, 0, 1.99, -0.35, 0.000000, 0, 0, -21, 0, 0 -ATT, 0.00, -0.08, -2.24, -0.31, 0.00, 73.81, 73.81 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 0, 1.99, -0.32, 0.000000, 0, 0, -19, 0, 0 -DU32, 7, 166076 -CURR, 0, 38117, 1193, 0, 5051, 26.202591 -ATT, 0.00, -0.09, -2.24, -0.31, 0.00, 73.95, 73.95 -CTUN, 0, 1.98, -0.16, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.31, 0.00, 74.07, 74.07 -CTUN, 0, 1.98, -0.21, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.31, 0.00, 74.21, 74.21 -CTUN, 0, 1.98, -0.14, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.34, 74.34 -CTUN, 0, 1.98, -0.17, 0.000000, 0, 0, -10, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.46, 74.46 -CTUN, 0, 1.98, -0.10, 0.000000, 0, 0, -8, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.58, 74.58 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -6, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.71, 74.71 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.83, 74.83 -CTUN, 0, 1.98, -0.05, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.95, 74.95 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 75.08, 75.08 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 0, 0, 0 -DU32, 7, 166076 -CURR, 0, 38117, 1198, 0, 5028, 26.203243 -ATT, 0.00, -0.12, -2.24, -0.30, 0.00, 75.19, 75.19 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.29, 0.00, 75.31, 75.31 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.29, 0.00, 75.42, 75.42 -CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.28, 0.00, 75.53, 75.53 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.28, 0.00, 75.64, 75.64 -CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.75, 75.75 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.86, 75.86 -CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.96, 75.96 -CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.13, -2.24, -0.27, 0.00, 76.07, 76.07 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.17, 76.17 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 14, 0, 0 -DU32, 7, 166076 -CURR, 0, 38117, 1200, 0, 5051, 26.203243 -ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.28, 76.28 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.38, 76.38 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 16, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.26, 0.00, 76.48, 76.48 -CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 17, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.26, 0.00, 76.58, 76.58 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 18, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.68, 76.68 -CTUN, 0, 1.98, 0.12, 0.000000, 0, 0, 18, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.78, 76.78 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.88, 76.88 -CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 20, 0, 0 -ATT, 0.00, -0.15, -2.14, -0.26, 0.00, 76.97, 76.97 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 21, 0, 0 -ATT, 0.00, -0.16, -2.24, -0.26, 0.00, 77.07, 77.07 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 21, 0, 0 -ATT, 0.00, -0.16, -2.24, -0.26, 0.00, 77.16, 77.16 -EV, 15 -CTUN, 191, 1.98, 0.05, 0.000000, 0, 0, 22, 147, 0 -DU32, 7, 166140 -CURR, 244, 38117, 1200, 0, 5051, 26.203583 -ATT, 0.00, -0.16, -2.33, -0.25, 0.00, 77.25, 77.20 -CTUN, 304, 1.98, 0.06, 0.000000, 0, 0, 23, 304, 0 -ATT, 0.00, -0.16, -2.24, -0.25, 0.00, 77.33, 77.20 -CTUN, 171, 1.98, -0.05, 0.000000, 0, 0, 23, 216, 0 -ATT, 0.00, -0.16, -2.24, -0.25, 0.00, 77.38, 77.38 -CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.17, -2.24, -0.25, 0.00, 77.42, 77.42 -CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.16, -2.24, -0.24, 0.00, 77.53, 77.53 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.17, -2.24, -0.24, 0.00, 77.62, 77.62 -CTUN, 0, 1.98, -0.08, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.17, -2.24, -0.24, 0.00, 77.70, 77.70 -CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.24, 0.00, 77.80, 77.80 -CTUN, 0, 1.98, -0.05, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.23, 0.00, 77.89, 77.89 -CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.18, -2.14, -0.23, 0.00, 77.98, 77.98 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 26, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1201, 0, 5051, 26.528595 -ATT, 0.00, -0.18, -2.24, -0.23, 0.00, 78.06, 78.06 -CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.15, 78.15 -CTUN, 0, 1.98, -0.08, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.23, 78.23 -CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.32, 78.32 -CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.41, 78.41 -CTUN, 0, 1.98, 0.11, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.49, 78.49 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.57, 78.57 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.65, 78.65 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.74, 78.74 -CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.82, 78.82 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1202, 0, 5028, 26.529558 -ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 78.90, 78.90 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 78.98, 78.98 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 79.06, 79.06 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 79.14, 79.14 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.22, 79.22 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.30, 79.30 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.39, 79.39 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.20, 0.00, 79.46, 79.46 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.20, 0.00, 79.53, 79.53 -CTUN, 0, 1.98, 0.11, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.61, 79.61 -CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 28, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1203, 0, 5051, 26.530550 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.69, 79.69 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.76, 79.76 -CTUN, 0, 1.98, 0.13, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.84, 79.84 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.92, 79.92 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.99, 79.99 -CTUN, 0, 1.98, 0.09, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.06, 80.06 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.14, 80.14 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.21, 80.21 -CTUN, 0, 1.99, 0.18, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.28, 80.28 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.35, 80.35 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 27, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1206, 0, 5028, 26.530890 -ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.42, 80.42 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.49, 80.49 -CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.56, 80.56 -CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 27, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.63, 80.63 -CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.70, 80.70 -CTUN, 0, 1.98, 0.09, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.77, 80.77 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.84, 80.84 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 80.90, 80.90 -CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 26, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 80.97, 80.97 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.04, 81.04 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 25, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1206, 0, 5051, 26.531910 -ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.10, 81.10 -CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.17, 81.17 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 25, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.23, 81.23 -CTUN, 0, 1.98, 0.12, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.33, -0.15, 0.00, 81.29, 81.29 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.36, 81.36 -CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.42, 81.42 -CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.48, 81.48 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.54, 81.54 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.60, 81.60 -CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 24, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.66, 81.66 -CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 23, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1206, 0, 5028, 26.531910 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.72, 81.72 -CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 23, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.77, 81.77 -CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 23, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.83, 81.83 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 23, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.89, 81.89 -CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 81.95, 81.95 -CTUN, 0, 1.99, 0.04, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.01, 82.01 -CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.06, 82.06 -CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.11, 82.11 -CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 22, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.17, 82.17 -CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 21, 0, 0 -PM, 0, 0, 0, 0, 1000, 10460, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.23, 82.23 -CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 21, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1206, 0, 5051, 26.532589 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.28, 82.28 -CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 21, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.34, 82.34 -CTUN, 0, 1.99, 0.15, 0.000000, 0, 0, 20, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.39, 82.39 -CTUN, 0, 1.99, 0.06, 0.000000, 0, 0, 20, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.45, 82.45 -CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 20, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.50, 82.50 -CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.55, 82.55 -CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.60, 82.60 -CTUN, 0, 1.99, 0.01, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.13, 0.00, 82.65, 82.65 -CTUN, 0, 1.99, 0.06, 0.000000, 0, 0, 19, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.70, 82.70 -CTUN, 0, 1.99, 0.05, 0.000000, 0, 0, 18, 0, 0 -ATT, 0.00, -0.20, -2.14, -0.12, 0.00, 82.75, 82.75 -CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 18, 0, 0 -DU32, 7, 166076 -CURR, 0, 38626, 1206, 1, 5028, 26.533581 -ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.80, 82.80 -CTUN, 0, 1.99, 0.07, 0.000000, 0, 0, 18, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.86, 82.86 -CTUN, 0, 1.99, 0.03, 0.000000, 0, 0, 18, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.91, 82.91 -CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 17, 0, 0 -EV, 15 -ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.96, 82.93 -CTUN, 163, 1.98, 0.05, 0.000000, 0, 0, 17, 163, 0 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.00, 82.93 -CTUN, 181, 1.98, 0.04, 0.000000, 0, 0, 17, 181, 0 -ATT, 0.00, -0.20, -2.24, -0.11, 0.00, 83.03, 82.93 -CTUN, 181, 1.98, -0.07, 0.000000, 0, 0, 16, 180, 0 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.04, 82.93 -CTUN, 181, 1.98, -0.12, 0.000000, 0, 0, 16, 180, 0 -ATT, 0.00, -0.19, -2.24, -0.12, 0.00, 83.07, 82.93 -CTUN, 180, 1.98, -0.13, 0.000000, 0, 0, 16, 181, 0 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.11, 82.93 -CTUN, 181, 1.98, -0.24, 0.000000, 0, 0, 15, 180, 0 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.15, 82.93 -CTUN, 180, 1.98, -0.16, 0.000000, 0, 0, 15, 181, 0 -DU32, 7, 166140 -CURR, 181, 39870, 1193, 181, 5028, 26.998184 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.18, 82.93 -CTUN, 181, 1.98, -0.26, 0.000000, 0, 0, 14, 181, 0 -ATT, 0.00, -0.19, -2.24, -0.12, 0.00, 83.20, 82.93 -CTUN, 181, 1.98, -0.32, 0.000000, 0, 0, 13, 181, 0 -ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.25, 82.93 -CTUN, 180, 1.98, -0.33, 0.000000, 0, 0, 13, 181, 0 -ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.28, 82.93 -CTUN, 177, 1.98, -0.42, 0.000000, 0, 0, 12, 178, 0 -ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.31, 82.93 -CTUN, 171, 1.98, -0.38, 0.000000, 0, 0, 12, 171, 0 -ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.34, 82.93 -CTUN, 172, 1.99, -0.37, 0.000000, 0, 0, 10, 171, 0 -ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.37, 82.93 -CTUN, 172, 1.99, -0.39, 0.000000, 0, 0, 10, 171, 0 -ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.41, 82.93 -CTUN, 176, 1.99, -0.37, 0.000000, 0, 0, 9, 171, 0 -ATT, 0.00, -0.18, -2.24, -0.10, 0.00, 83.44, 82.93 -CTUN, 226, 1.99, -0.39, 0.000000, 0, 0, 9, 226, 0 -ATT, 0.00, -0.18, -2.24, -0.09, 0.00, 83.47, 82.93 -CTUN, 268, 1.99, -0.29, 0.000000, 0, 0, 9, 263, 0 -DU32, 7, 166140 -CURR, 273, 41732, 1190, 276, 5028, 27.512407 -ATT, 0.00, -0.18, -2.24, -0.09, 0.00, 83.50, 82.93 -CTUN, 279, 1.98, -0.52, 0.000000, 0, 0, 8, 279, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.52, 82.93 -CTUN, 279, 1.98, -0.60, 0.000000, 0, 0, 7, 279, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.53, 82.93 -CTUN, 279, 1.98, -0.76, 0.000000, 0, 0, 7, 279, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.55, 82.93 -CTUN, 284, 1.98, -0.69, 0.000000, 0, 0, 6, 281, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.57, 82.93 -CTUN, 302, 1.98, -0.74, 0.000000, 0, 0, 5, 302, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.59, 82.93 -CTUN, 327, 1.98, -0.65, 0.000000, 0, 0, 5, 324, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 -CTUN, 357, 1.98, -0.77, 0.000000, 0, 0, 4, 355, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 -CTUN, 376, 1.99, -0.91, 0.000000, 0, 0, 4, 374, 0 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 -CTUN, 396, 1.99, -1.04, 0.000000, 0, 0, 2, 396, 0 -ATT, 0.00, -0.20, -2.24, -0.09, 0.00, 83.59, 82.93 -CTUN, 411, 1.99, -1.16, 0.000000, 0, 0, 1, 402, 0 -DU32, 7, 166140 -CURR, 420, 44988, 1164, 716, 5028, 28.847597 -ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.58, 82.93 -CTUN, 434, 1.98, -1.35, 0.000000, 0, 0, 0, 434, 0 -ATT, 0.00, -0.20, -2.24, -0.09, 0.00, 83.56, 82.93 -CTUN, 458, 1.99, -1.29, 0.000000, 0, 0, 0, 449, 0 -ATT, 0.00, -0.21, -2.24, -0.10, 0.00, 83.52, 82.93 -CTUN, 499, 1.99, -1.50, 0.000000, 0, 0, 0, 490, 0 -ATT, 0.00, -0.22, -2.24, -0.10, 0.00, 83.49, 82.93 -CTUN, 510, 1.99, -1.61, 0.000000, 0, 0, 4, 510, 0 -ATT, 0.00, -0.23, -2.24, -0.11, 0.00, 83.43, 82.93 -CTUN, 530, 1.99, -2.04, 0.000000, 0, 0, 2, 530, 0 -ATT, 0.00, -0.23, -2.05, -0.11, 0.00, 83.37, 82.93 -CTUN, 544, 3.36, -1.93, 0.000000, 0, 0, 4, 542, 0 -ATT, 0.00, -0.25, -2.05, -0.14, 0.00, 83.31, 82.93 -CTUN, 577, 3.36, -1.95, 0.000000, 0, 0, 8, 571, 0 -ATT, 0.00, -0.30, -1.30, -0.17, 0.00, 83.22, 82.93 -CTUN, 596, 3.45, -2.23, 0.000000, 0, 0, 4, 592, 0 -ATT, 0.00, -0.31, -2.14, -0.18, 0.00, 83.16, 82.93 -CTUN, 622, 3.45, -2.37, 0.000000, 0, 0, 5, 597, 0 -ATT, 0.00, -0.64, -2.24, -0.22, 0.00, 83.08, 82.93 -CTUN, 639, 3.80, -2.34, 0.000000, 0, 0, 6, 639, 0 -DU32, 7, 166140 -CURR, 640, 50327, 1097, 1659, 5051, 32.284740 -ATT, 0.00, -1.69, -2.05, -0.20, 0.00, 83.10, 82.93 -CTUN, 663, 3.45, -2.20, 0.000000, 0, 0, 7, 660, 0 -ATT, 0.00, -3.27, -2.05, -0.59, 0.00, 83.38, 82.93 -CTUN, 681, 3.69, -2.01, 0.000000, 0, 1, 6, 680, 0 -ATT, 0.00, -4.80, -2.05, -1.97, 0.00, 84.18, 82.93 -CTUN, 680, 3.69, -1.75, 0.000000, 0, 3, 8, 682, 0 -ATT, 0.00, -6.70, -2.05, -4.07, 0.00, 85.36, 82.93 -CTUN, 680, 4.25, -1.42, 0.000000, 0, 6, 10, 686, 0 -ATT, 0.00, -9.28, -2.05, -6.55, 0.00, 87.02, 82.93 -CTUN, 680, 3.69, -0.89, 0.000000, 0, 14, 12, 694, 0 -ATT, 0.00, -11.94, -1.40, -8.88, 0.00, 89.02, 82.93 -CTUN, 680, 3.69, -0.12, 0.000000, 0, 22, 9, 702, 0 -ATT, 0.09, -14.27, 8.12, -10.52, 0.00, 91.04, 82.93 -CTUN, 623, 0.21, 0.31, 0.000000, 0, 27, 6, 650, 0 -ATT, 6.28, -16.64, 20.35, -10.29, 0.00, 92.42, 82.93 -CTUN, 330, 0.21, 0.23, 0.000000, 0, 14, 2, 372, 0 -ATT, 6.28, -17.34, 25.20, -7.79, 0.00, 93.22, 83.22 -CTUN, 171, 0.20, 0.24, 0.000000, 0, 3, -20, 197, 0 -ATT, 6.37, -13.62, 26.70, -2.14, 0.00, 94.19, 84.19 -CTUN, 133, 0.21, -0.11, 0.000000, 0, 0, -50, 134, 0 -DU32, 7, 166140 -CURR, 0, 55792, 1171, 295, 5051, 36.564842 -ATT, 6.18, -0.31, 25.76, -0.47, 0.00, 96.72, 96.72 -CTUN, 0, 0.21, -0.92, 0.000000, 0, 0, 13, 0, 0 -ATT, 3.37, -1.54, 23.71, -0.59, 0.00, 96.61, 96.61 -CTUN, 0, 1.79, -0.73, 0.000000, 0, 0, 6, 0, 0 -ATT, 2.25, -0.37, 20.07, -0.75, 0.00, 96.81, 96.81 -CTUN, 0, 1.79, -0.60, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -0.33, 10.54, -0.74, 0.00, 96.83, 96.83 -CTUN, 0, 7.18, -0.31, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, -0.33, -1.12, -0.73, 0.00, 96.86, 96.86 -CTUN, 0, 7.18, -0.24, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, -0.33, -2.14, -0.73, 0.00, 96.89, 96.89 -CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, -0.32, -2.14, -0.71, 0.00, 96.93, 96.93 -CTUN, 0, 7.65, -0.17, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, -0.33, -2.14, -0.72, 0.00, 96.95, 96.95 -CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, -0.32, -2.24, -0.71, 0.00, 96.99, 96.99 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, -0.32, -2.14, -0.69, 0.00, 97.03, 97.03 -CTUN, 0, 7.65, -0.14, 0.000000, 0, 0, 5, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1198, 0, 5051, 36.645130 -ATT, 0.00, -0.31, -2.14, -0.69, 0.00, 97.07, 97.07 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, -0.30, -2.14, -0.69, 0.00, 97.10, 97.10 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.30, -2.14, -0.69, 0.00, 97.13, 97.13 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, -0.30, -2.14, -0.68, 0.00, 97.17, 97.17 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, -0.29, -2.05, -0.67, 0.00, 97.20, 97.20 -CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.29, -2.14, -0.67, 0.00, 97.23, 97.23 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.29, -2.14, -0.66, 0.00, 97.27, 97.27 -CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.28, -2.05, -0.66, 0.00, 97.30, 97.30 -CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.28, -2.05, -0.66, 0.00, 97.33, 97.33 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.28, -2.14, -0.65, 0.00, 97.36, 97.36 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 11, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1199, 0, 5051, 36.645130 -ATT, 0.00, -0.27, -2.14, -0.65, 0.00, 97.40, 97.40 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.27, -2.14, -0.64, 0.00, 97.43, 97.43 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.27, -2.05, -0.64, 0.00, 97.46, 97.46 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.26, -2.14, -0.63, 0.00, 97.49, 97.49 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.26, -2.05, -0.63, 0.00, 97.52, 97.52 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.26, -2.05, -0.62, 0.00, 97.54, 97.54 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.26, -2.05, -0.62, 0.00, 97.57, 97.57 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.25, -2.14, -0.61, 0.00, 97.61, 97.61 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.25, -2.14, -0.61, 0.00, 97.63, 97.63 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.25, -2.05, -0.61, 0.00, 97.66, 97.66 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 14, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1200, 0, 5028, 36.645130 -ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.69, 97.69 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.72, 97.72 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.74, 97.74 -CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.24, -2.14, -0.60, 0.00, 97.77, 97.77 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.24, -2.14, -0.59, 0.00, 97.80, 97.80 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.24, -2.14, -0.59, 0.00, 97.82, 97.82 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.23, -2.14, -0.58, 0.00, 97.85, 97.85 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.23, -2.14, -0.58, 0.00, 97.88, 97.88 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.23, -2.14, -0.57, 0.00, 97.90, 97.90 -CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, 15, 0, 0 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -ATT, 0.00, -0.22, -2.05, -0.57, 0.00, 97.93, 97.93 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1201, 0, 5028, 36.645470 -ATT, 0.00, -0.22, -2.14, -0.57, 0.00, 97.95, 97.95 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.22, -2.14, -0.56, 0.00, 97.98, 97.98 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.22, -2.14, -0.56, 0.00, 98.00, 98.00 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.21, -2.14, -0.55, 0.00, 98.03, 98.03 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.21, -2.14, -0.55, 0.00, 98.06, 98.06 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.21, -2.14, -0.54, 0.00, 98.08, 98.08 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.21, -2.14, -0.54, 0.00, 98.10, 98.10 -CTUN, 0, 3.67, 0.06, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.20, -2.14, -0.54, 0.00, 98.12, 98.12 -CTUN, 0, 3.67, 0.07, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.20, -2.14, -0.53, 0.00, 98.14, 98.14 -CTUN, 0, 3.26, 0.05, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.20, -2.24, -0.53, 0.00, 98.17, 98.17 -CTUN, 0, 3.67, 0.04, 0.000000, 0, 0, 15, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1201, 0, 5028, 36.646122 -ATT, 0.00, -0.19, -2.24, -0.53, 0.00, 98.20, 98.20 -CTUN, 0, 3.67, 0.12, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.19, -2.14, -0.53, 0.00, 98.22, 98.22 -CTUN, 0, 7.55, 0.11, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.19, -2.24, -0.52, 0.00, 98.24, 98.24 -CTUN, 0, 7.55, 0.08, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.26, 98.26 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.28, 98.28 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.30, 98.30 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.32, 98.32 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.17, -2.24, -0.52, 0.00, 98.34, 98.34 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.17, -2.24, -0.51, 0.00, 98.37, 98.37 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.17, -2.14, -0.51, 0.00, 98.39, 98.39 -CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 14, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1203, 2, 5028, 36.646748 -ATT, 0.00, -0.17, -2.14, -0.50, 0.00, 98.42, 98.42 -CTUN, 0, 2.41, -0.02, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.16, -2.05, -0.50, 0.00, 98.44, 98.44 -CTUN, 0, 3.17, 0.05, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.16, -2.24, -0.49, 0.00, 98.46, 98.46 -CTUN, 0, 2.41, 0.04, 0.000000, 0, 0, 14, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.49, 0.00, 98.49, 98.49 -CTUN, 0, 2.41, 0.06, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.48, 0.00, 98.51, 98.51 -CTUN, 0, 0.73, 0.12, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.15, -2.24, -0.48, 0.00, 98.53, 98.53 -CTUN, 0, 2.41, 0.09, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.48, 0.00, 98.55, 98.55 -CTUN, 0, 2.41, 0.09, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.47, 0.00, 98.58, 98.58 -CTUN, 0, 7.12, 0.06, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.14, -2.24, -0.47, 0.00, 98.60, 98.60 -CTUN, 0, 7.12, 0.02, 0.000000, 0, 0, 13, 0, 0 -ATT, 0.00, -0.13, -2.24, -0.47, 0.00, 98.62, 98.62 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 13, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1203, 0, 5028, 36.646748 -ATT, 0.00, -0.13, -2.24, -0.46, 0.00, 98.64, 98.64 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.46, 0.00, 98.67, 98.67 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.46, 0.00, 98.69, 98.69 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.12, -2.24, -0.45, 0.00, 98.71, 98.71 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.45, 0.00, 98.73, 98.73 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.11, -2.24, -0.45, 0.00, 98.75, 98.75 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.77, 98.77 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 12, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.79, 98.79 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.81, 98.81 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.83, 98.83 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 11, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1204, 0, 5028, 36.647427 -ATT, 0.00, -0.09, -2.24, -0.44, 0.00, 98.85, 98.85 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.87, 98.87 -CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.89, 98.89 -CTUN, 0, 7.65, 0.14, 0.000000, 0, 0, 11, 0, 0 -ATT, 0.00, -0.08, -2.24, -0.43, 0.00, 98.91, 98.91 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.08, -2.24, -0.42, 0.00, 98.92, 98.92 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.08, -2.24, -0.42, 0.00, 98.94, 98.94 -CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.07, -2.24, -0.42, 0.00, 98.96, 98.96 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.07, -2.24, -0.41, 0.00, 98.97, 98.97 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 10, 0, 0 -ATT, 0.00, -0.07, -2.24, -0.41, 0.00, 98.99, 98.99 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.06, -2.24, -0.41, 0.00, 99.01, 99.01 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 9, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1204, 0, 5051, 36.648075 -ATT, 0.00, -0.06, -2.24, -0.40, 0.00, 99.03, 99.03 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.06, -2.24, -0.40, 0.00, 99.04, 99.04 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 9, 0, 0 -ATT, 0.00, -0.05, -2.24, -0.40, 0.00, 99.06, 99.06 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.05, -2.24, -0.40, 0.00, 99.07, 99.07 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.05, -2.24, -0.39, 0.00, 99.09, 99.09 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.11, 99.11 -CTUN, 0, 7.65, 0.13, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.12, 99.12 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 8, 0, 0 -ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.14, 99.14 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.16, 99.16 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.17, 99.17 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 7, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1204, 0, 5028, 36.648415 -ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.19, 99.19 -CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 7, 0, 0 -ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.20, 99.20 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.02, -2.24, -0.37, 0.00, 99.22, 99.22 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.02, -2.24, -0.37, 0.00, 99.24, 99.24 -CTUN, 0, 7.65, 0.11, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.02, -2.14, -0.37, 0.00, 99.25, 99.25 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.01, -2.24, -0.37, 0.00, 99.27, 99.27 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.01, -2.24, -0.37, 0.00, 99.28, 99.28 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 6, 0, 0 -ATT, 0.00, -0.01, -2.24, -0.36, 0.00, 99.30, 99.30 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.32, 99.32 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.34, 99.34 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1203, 0, 5028, 36.648415 -ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.36, 99.36 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.38, 99.38 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.40, 99.40 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.42, 99.42 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.44, 99.44 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 5, 0, 0 -ATT, 0.00, 0.01, -2.24, -0.35, 0.00, 99.45, 99.45 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.47, 99.47 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.48, 99.48 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.50, 99.50 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.02, -2.24, -0.34, 0.00, 99.52, 99.52 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 4, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1204, 0, 5051, 36.648754 -ATT, 0.00, 0.02, -2.24, -0.33, 0.00, 99.54, 99.54 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.02, -2.24, -0.33, 0.00, 99.56, 99.56 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.03, -2.24, -0.33, 0.00, 99.57, 99.57 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.03, -2.24, -0.32, 0.00, 99.59, 99.59 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 4, 0, 0 -ATT, 0.00, 0.03, -2.24, -0.32, 0.00, 99.61, 99.61 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 99.62, 99.62 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 99.64, 99.64 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.04, -2.24, -0.31, 0.00, 99.66, 99.66 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.67, 99.67 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.69, 99.69 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 3, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5028, 36.649067 -ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.70, 99.70 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.05, -2.24, -0.30, 0.00, 99.72, 99.72 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 3, 0, 0 -ATT, 0.00, 0.05, -2.24, -0.30, 0.00, 99.73, 99.73 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.06, -2.24, -0.30, 0.00, 99.75, 99.75 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.06, -2.24, -0.29, 0.00, 99.76, 99.76 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.06, -2.24, -0.29, 0.00, 99.78, 99.78 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.07, -2.24, -0.29, 0.00, 99.79, 99.79 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.07, -2.24, -0.29, 0.00, 99.80, 99.80 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 2, 0, 0 -ATT, 0.00, 0.07, -2.61, -0.29, 0.00, 99.82, 99.82 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 1, 0, 0 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -ATT, 0.00, 0.07, -2.24, -0.28, 0.00, 99.83, 99.83 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 1, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5028, 36.649406 -ATT, 0.00, 0.07, -2.24, -0.28, 0.00, 99.84, 99.84 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.08, -2.24, -0.28, 0.00, 99.85, 99.85 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.08, -2.24, -0.28, 0.00, 99.87, 99.87 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.08, -2.24, -0.27, 0.00, 99.89, 99.89 -CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.90, 99.90 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.91, 99.91 -CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 1, 0, 0 -ATT, 0.00, 0.09, -2.61, -0.27, 0.00, 99.92, 99.92 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.94, 99.94 -CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.10, -2.24, -0.27, 0.00, 99.95, 99.95 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.96, 99.96 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5028, 36.649406 -ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.97, 99.97 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.99, 99.99 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 100.00, 100.00 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.11, -2.24, -0.25, 0.00, 100.01, 100.01 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.11, -2.24, -0.25, 0.00, 100.02, 100.02 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.03, 100.03 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.05, 100.05 -CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.06, 100.06 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.24, 0.00, 100.07, 100.07 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.08, 100.08 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 0, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1207, 0, 5028, 36.649746 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.10, 100.10 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.11, 100.11 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.12, 100.12 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.13, 100.13 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.14, 100.14 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.15, 100.15 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.16, 100.16 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.17, 100.17 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.23, 0.00, 100.19, 100.19 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.23, 0.00, 100.20, 100.20 -CTUN, 0, 7.65, 0.12, 0.000000, 0, 0, -1, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1208, 0, 5028, 36.649746 -ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.22, 100.22 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.23, 100.23 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.22, 0.00, 100.23, 100.23 -CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.22, 0.00, 100.24, 100.24 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.25, 100.25 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.27, 100.27 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.21, 0.00, 100.27, 100.27 -CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.21, 0.00, 100.28, 100.28 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.29, 100.29 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.29, 100.29 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5051, 36.650372 -ATT, 0.00, 0.18, -2.24, -0.20, 0.00, 100.31, 100.31 -CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.21, 0.00, 100.31, 100.31 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.32, 100.32 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.22, 0.00, 100.31, 100.31 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.36, 100.36 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.37, 100.37 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.09, -2.33, -0.29, 0.00, 100.40, 100.40 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.08, -2.24, -0.30, 0.00, 100.44, 100.44 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.07, -2.24, -0.32, 0.00, 100.45, 100.45 -CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.06, -2.24, -0.34, 0.00, 100.45, 100.45 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -1, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5028, 36.650372 -ATT, 0.00, 0.04, -2.24, -0.35, 0.00, 100.35, 100.35 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 100.32, 100.32 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.07, -2.24, -0.26, 0.00, 100.45, 100.45 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -1, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.22, 0.00, 100.44, 100.44 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.21, 0.00, 100.44, 100.44 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.14, -2.24, -0.21, 0.00, 100.46, 100.46 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.21, 0.00, 100.45, 100.45 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.20, 0.00, 100.44, 100.44 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.20, 0.00, 100.47, 100.47 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.46, 100.46 -CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 1, 5028, 36.651051 -ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.47, 100.47 -CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.15, -2.24, -0.19, 0.00, 100.46, 100.46 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.18, 0.00, 100.49, 100.49 -CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.44, 100.44 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.50, 100.50 -CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.51, 100.51 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.54, 100.54 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.53, 100.53 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.53, 100.53 -CTUN, 0, 7.65, -0.17, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.54, 100.54 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1205, 0, 5051, 36.651390 -ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.54, 100.54 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.56, 100.56 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.16, -2.24, -0.17, 0.00, 100.58, 100.58 -CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.58, 100.58 -CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.58, 100.58 -CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.18, -2.24, -0.16, 0.00, 100.60, 100.60 -CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.18, -2.24, -0.16, 0.00, 100.60, 100.60 -CTUN, 0, 7.33, -0.06, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.17, -2.14, -0.16, 0.00, 100.61, 100.61 -CTUN, 0, 7.33, 0.02, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.17, -2.24, -0.16, 0.00, 100.61, 100.61 -CTUN, 0, 7.24, 0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.18, -2.24, -0.15, 0.00, 100.61, 100.61 -CTUN, 0, 7.33, 0.03, 0.000000, 0, 0, -3, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5028, 36.651703 -ATT, 0.00, 0.18, -2.24, -0.15, 0.00, 100.62, 100.62 -CTUN, 0, 7.33, -0.07, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.63, 100.63 -CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.63, 100.63 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.64, 100.64 -CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.14, -0.13, 0.00, 100.65, 100.65 -CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -2, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.63, 100.63 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.64, 100.64 -CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.65, 100.65 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.21, -2.33, -0.14, 0.00, 100.63, 100.63 -CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.66, 100.66 -CTUN, 0, 7.65, -0.09, 0.000000, 0, 0, -3, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1205, 0, 5028, 36.652355 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.21, -2.24, -0.11, 0.00, 100.67, 100.67 -CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.22, -2.24, -0.10, 0.00, 100.68, 100.68 -CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.19, -2.24, -0.13, 0.00, 100.69, 100.69 -CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 -ATT, 0.00, 0.22, -2.24, -0.09, 0.00, 100.69, 100.69 -CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, -4, 0, 0 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -ATT, 0.00, 0.21, -2.24, -0.11, 0.00, 100.69, 100.69 -CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -3, 0, 0 -DU32, 7, 166076 -CURR, 0, 55792, 1206, 0, 5051, 36.652695 -EV, 11 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -PM, 0, 0, 0, 1, 1000, 113444, 0, 0 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -PM, 0, 0, 0, 0, 1000, 10480, 0, 0 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -PM, 0, 0, 0, 0, 1000, 10484, 0, 0 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -DU32, 7, 133308 -D32, 9, 10058 -EV, 10 -CTUN, 154, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 -EV, 15 -ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.59, 100.58 -CTUN, 244, 7.65, 0.10, 0.000000, 0, 0, -1, 241, 0 -ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.55, 100.58 -CTUN, 244, 7.65, -0.12, 0.000000, 0, 0, 0, 243, 0 -ATT, 0.00, 0.08, -2.24, -0.30, 0.00, 100.52, 100.58 -CTUN, 244, 7.65, -0.31, 0.000000, 0, 0, -1, 244, 0 -ATT, 0.00, 0.09, -2.24, -0.29, 0.00, 100.46, 100.58 -CTUN, 244, 7.65, -0.86, 0.000000, 0, 0, -1, 244, 0 -ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.43, 100.58 -CTUN, 243, 7.65, -0.93, 0.000000, 0, 0, -2, 243, 0 -ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.41, 100.58 -CTUN, 144, 7.65, -1.07, 0.000000, 0, 0, -3, 181, 0 -ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.37, 100.37 -DU32, 7, 133308 -CURR, 0, 57309, 1189, 246, 5028, 37.295242 -CTUN, 0, 7.65, -1.07, 0.000000, 0, 0, -4, 0, 0 -ATT, 0.00, 0.11, -2.24, -0.29, 0.00, 100.36, 100.36 -CTUN, 0, 7.65, -0.64, 0.000000, 0, 0, -5, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.28, 0.00, 100.36, 100.36 -CTUN, 0, 7.65, -0.61, 0.000000, 0, 0, -6, 0, 0 -ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.41, 100.41 -CTUN, 0, 7.65, -0.59, 0.000000, 0, 0, -6, 0, 0 -ATT, 0.00, 0.12, -2.24, -0.28, 0.00, 100.38, 100.38 -CTUN, 0, 7.65, -0.34, 0.000000, 0, 0, -7, 0, 0 -ATT, 0.00, 0.11, -2.24, -0.28, 0.00, 100.37, 100.37 -CTUN, 0, 7.65, -0.27, 0.000000, 0, 0, -6, 0, 0 -EV, 15 -ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.38, 100.39 -CTUN, 200, 7.65, -0.22, 0.000000, 0, 0, -6, 191, 0 -ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.39, 100.39 -CTUN, 205, 7.65, -0.39, 0.000000, 0, 0, -6, 205, 0 -ATT, 0.00, 0.13, -2.24, -0.27, 0.00, 100.33, 100.39 -CTUN, 205, 7.65, -0.55, 0.000000, 0, 0, -7, 205, 0 -ATT, 0.00, 0.12, -2.33, -0.27, 0.00, 100.34, 100.39 -CTUN, 226, 7.65, -0.66, 0.000000, 0, 0, -7, 226, 0 -ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.34, 100.39 -DU32, 7, 133372 -CURR, 248, 58281, 1191, 233, 5028, 37.561947 -CTUN, 252, 7.65, -0.80, 0.000000, 0, 0, -7, 248, 0 -ATT, 0.00, 0.12, -2.24, -0.26, 0.00, 100.29, 100.39 -CTUN, 287, 7.65, -0.93, 0.000000, 0, 0, -8, 287, 0 -ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.27, 100.39 -CTUN, 328, 7.65, -1.14, 0.000000, 0, 0, -8, 328, 0 -EV, 16 -ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.23, 100.39 -CTUN, 361, 7.65, -1.73, 0.000000, 0, 0, -9, 357, 0 -ATT, 0.00, 0.13, -2.24, -0.26, 0.00, 100.16, 100.39 -CTUN, 378, 7.65, -1.88, 0.000000, 0, 0, -10, 378, 0 -ATT, 0.00, 0.13, -2.24, -0.25, 0.00, 100.09, 100.39 -CTUN, 403, 7.65, -2.38, 0.000000, 0, 0, -12, 403, 0 -ATT, 0.00, 0.14, -2.24, -0.25, 0.00, 100.03, 100.39 -CTUN, 441, 7.65, -2.51, 0.000000, 0, 0, -14, 438, 0 -ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 99.96, 100.39 -CTUN, 468, 7.65, -3.13, 0.000000, 0, 0, -17, 468, 0 -ATT, 0.00, 0.13, -2.24, -0.23, 0.00, 99.87, 100.39 -CTUN, 501, 7.65, -3.45, 0.000000, 0, 0, -19, 501, 0 -ATT, 0.00, 0.13, -2.24, -0.20, 0.00, 99.76, 100.39 -CTUN, 524, 7.65, -4.07, 0.000000, 0, 0, -20, 524, 0 -ATT, 0.37, 0.14, -2.05, -0.20, 0.00, 99.63, 100.39 -DU32, 7, 166140 -CURR, 544, 62282, 1134, 1271, 5051, 39.683720 -CTUN, 545, 7.65, -4.64, 0.000000, 0, 0, -20, 545, 0 -ATT, 0.65, 0.14, -2.05, -0.06, 0.00, 99.50, 100.39 -CTUN, 563, 6.46, -4.67, 0.000000, 0, 0, -21, 563, 0 -ATT, 1.40, 0.13, -1.30, 0.43, 0.00, 99.38, 100.39 -CTUN, 588, 7.55, -4.72, 0.000000, 0, 0, -24, 588, 0 -ATT, 1.40, 0.00, -1.49, 1.88, 0.00, 99.43, 100.39 -CTUN, 593, 6.46, -4.56, 0.000000, 0, 0, -25, 593, 0 -ATT, 1.68, 0.17, -1.77, 3.78, 0.00, 99.90, 100.39 -CTUN, 595, 6.46, -4.22, 0.000000, 0, 1, -25, 593, 0 -ATT, 2.90, 0.65, -2.24, 4.90, 0.00, 100.69, 100.39 -CTUN, 597, 5.28, -4.40, 0.000000, 0, 1, -29, 598, 0 -ATT, 5.34, 0.84, -5.60, 4.35, 0.00, 101.54, 100.39 -CTUN, 602, 6.46, -3.51, 0.000000, 0, 1, -34, 603, 0 -ATT, 6.00, 2.67, -13.53, 2.88, 0.00, 102.39, 100.39 -CTUN, 602, 5.28, -3.56, 0.000000, 0, 1, -35, 603, 0 -ATT, 6.18, 4.66, -14.28, -0.82, 0.00, 102.90, 100.39 -CTUN, 602, 5.28, -2.79, 0.000000, 0, 1, -41, 603, 0 -ATT, 6.18, 4.93, -14.28, -6.62, 0.00, 103.28, 100.39 -CTUN, 602, 1.94, -2.79, 0.000000, 0, 5, -44, 607, 0 -ATT, 6.09, 5.52, -12.88, -9.87, 0.00, 103.74, 100.39 -DU32, 7, 166140 -CURR, 608, 68184, 1106, 1533, 5051, 43.800499 -CTUN, 616, 1.94, -2.53, 0.000000, 0, 9, -43, 617, 0 -ATT, 3.93, 5.93, -9.33, -9.88, 0.00, 104.59, 100.39 -CTUN, 626, 0.28, -1.99, 0.000000, 0, 9, -47, 635, 0 -ATT, 0.28, 4.22, -2.05, -8.51, 0.00, 105.50, 100.39 -CTUN, 639, 0.29, -2.01, 0.000000, 0, 6, -46, 642, 0 -ATT, 0.00, 1.31, -1.40, -5.40, 0.00, 106.51, 100.39 -CTUN, 639, 0.28, -2.25, 0.000000, 0, 2, -42, 641, 0 -ATT, 0.00, -1.19, -0.56, -2.04, 0.00, 107.45, 100.39 -CTUN, 640, 0.28, -1.64, 0.000000, 0, 0, -42, 640, 0 -ATT, 0.00, -2.80, -0.84, 0.32, 0.00, 108.33, 100.39 -CTUN, 639, 0.22, -1.67, 0.000000, 0, 0, -37, 639, 0 -ATT, 0.00, -2.60, -2.24, 1.51, 0.00, 109.31, 100.39 -CTUN, 642, 0.22, -1.95, 0.000000, 0, 0, -34, 642, 0 -ATT, 0.00, -2.05, -2.24, 1.92, 0.00, 110.12, 100.39 -CTUN, 646, 0.20, -1.13, 0.000000, 0, 0, -32, 645, 0 -ATT, 0.00, -2.01, -2.24, 1.61, 0.00, 110.59, 100.59 -CTUN, 646, 0.20, -0.80, 0.000000, 0, 0, -29, 646, 0 -ATT, 0.00, -1.98, -2.05, 1.03, -0.09, 110.62, 100.62 -CTUN, 646, 0.20, -0.57, 0.000000, 0, 0, -27, 646, 0 -ATT, 0.00, -1.83, -2.05, 0.38, -3.20, 110.25, 100.25 -DU32, 7, 166140 -CURR, 644, 74588, 1101, 1738, 5028, 48.557549 -CTUN, 645, 0.20, -0.11, 0.000000, 0, 0, -26, 645, 0 -ATT, 0.00, -1.46, -2.05, 0.10, -3.30, 109.36, 99.36 -CTUN, 645, 0.20, 0.03, 0.000000, 0, 0, -25, 644, 0 -ATT, 0.00, -0.83, -2.05, 0.22, -4.24, 108.04, 98.04 -CTUN, 644, 0.20, 0.09, 0.000000, 0, 0, -25, 644, 0 -ATT, 0.00, -0.63, -1.58, -0.19, -8.01, 106.37, 96.37 -CTUN, 644, 0.20, 0.08, 0.000000, 0, 0, -28, 644, 0 -ATT, 0.00, -0.41, -1.68, -0.54, -9.71, 104.09, 94.09 -CTUN, 645, 0.20, 0.10, 0.000000, 0, 0, -29, 645, 0 -ATT, 0.00, -0.44, -1.58, -0.50, -11.03, 101.19, 91.19 -CTUN, 645, 0.20, 0.00, 0.000000, 0, 0, -28, 645, 0 -ATT, 0.00, -0.52, -1.40, -0.16, -11.88, 97.51, 87.51 -CTUN, 645, 0.20, 0.14, 0.000000, 0, 0, -28, 645, 0 -ATT, 0.00, -0.44, -0.93, -0.15, -11.88, 93.63, 83.63 -CTUN, 653, 0.20, 0.10, 0.000000, 0, 0, -29, 653, 0 -ATT, 0.00, -0.03, -0.84, -0.21, -11.88, 89.40, 79.40 -CTUN, 656, 0.20, 0.20, 0.000000, 0, 0, -29, 656, 0 -ATT, 0.00, 0.07, 0.00, -0.42, -11.88, 84.87, 74.87 -CTUN, 660, 0.20, 0.13, 0.000000, 0, 0, -26, 660, 0 -ATT, 0.00, -0.34, 0.00, 0.05, -11.79, 80.00, 70.00 -DU32, 7, 166140 -CURR, 666, 81069, 1075, 1811, 5051, 53.439949 -CTUN, 666, 0.20, 0.15, 0.000000, 0, 0, -23, 666, 0 -ATT, 0.00, -0.78, 0.00, 0.64, -8.67, 74.95, 65.29 -CTUN, 666, 0.20, -0.08, 0.000000, 0, 0, -19, 666, 0 -ATT, 0.00, -0.34, 0.28, 1.36, -3.67, 69.96, 62.72 -CTUN, 666, 0.20, -0.30, 0.000000, 0, 0, -14, 666, 0 -ATT, 0.00, 0.06, 0.00, 1.43, 0.00, 65.55, 62.38 -CTUN, 666, 0.20, -0.45, 0.000000, 0, 0, -11, 666, 0 -ATT, 0.00, 0.36, 0.00, 1.13, 0.00, 62.44, 62.38 -CTUN, 665, 0.20, -0.40, 0.000000, 0, 0, -9, 665, 0 -ATT, 0.00, 0.15, 0.00, 1.18, 0.00, 60.46, 62.38 -CTUN, 665, 0.20, -0.20, 0.000000, 0, 0, -4, 665, 0 -ATT, 0.00, 0.18, 0.00, 1.41, 0.00, 59.28, 62.38 -CTUN, 665, 0.20, -0.20, 0.000000, 0, 0, -3, 665, 0 -ATT, 0.00, 0.16, -0.74, 1.67, 0.00, 58.82, 62.38 -CTUN, 665, 0.20, -0.44, 0.000000, 0, 0, -2, 665, 0 -ATT, 0.00, 0.29, -2.05, 1.67, 0.00, 58.92, 62.38 -CTUN, 666, 0.20, -0.35, 0.000000, 0, 0, 0, 665, 0 -ATT, 0.00, 0.75, -2.24, 0.89, 0.00, 59.51, 62.38 -PM, 0, 0, 0, 1, 1000, 2055856, 0, 0 -CTUN, 665, 0.20, -0.16, 0.000000, 0, 0, -3, 665, 0 -ATT, 0.00, 0.51, -1.96, 0.14, 0.00, 60.46, 62.38 -DU32, 7, 166140 -CURR, 666, 87723, 1094, 1780, 5028, 58.453716 -CTUN, 666, 0.20, -0.11, 0.000000, 0, 0, -3, 666, 0 -ATT, 0.00, -0.65, -2.14, -0.69, 0.00, 61.81, 62.38 -CTUN, 666, 0.20, 0.01, 0.000000, 0, 0, -2, 666, 0 -ATT, 0.00, -1.18, -2.24, -1.59, 0.00, 63.35, 62.38 -CTUN, 666, 0.20, 0.23, 0.000000, 0, 0, -1, 666, 0 -ATT, 0.00, -1.20, -2.24, -2.01, 0.00, 64.98, 62.38 -CTUN, 666, 0.20, 0.17, 0.000000, 0, 0, 0, 665, 0 -ATT, 0.00, -1.02, -2.24, -1.38, 0.00, 66.50, 62.38 -CTUN, 665, 0.20, 0.09, 0.000000, 0, 0, 0, 664, 0 -ATT, 0.00, -0.43, -2.24, -0.97, 0.00, 67.95, 62.38 -CTUN, 665, 0.20, 0.16, 0.000000, 0, 0, 0, 665, 0 -ATT, 0.00, -0.12, -2.24, -1.39, 0.00, 69.04, 62.38 -CTUN, 666, 0.20, 0.26, 0.000000, 0, 0, -1, 666, 0 -ATT, 0.00, 0.00, -2.14, -2.15, 0.00, 69.78, 62.38 -CTUN, 666, 0.20, 0.42, 0.000000, 0, 0, 0, 666, 0 -ATT, 0.00, 0.26, -2.24, -1.39, 0.00, 70.20, 62.38 -CTUN, 665, 0.20, 0.32, 0.000000, 0, 0, 3, 665, 0 -ATT, 0.00, -0.42, -2.24, -0.56, 0.00, 70.42, 62.38 -CTUN, 665, 0.20, 0.39, 0.000000, 0, 0, 0, 666, 0 -ATT, 0.00, -0.33, -2.14, -0.73, 0.00, 70.56, 62.38 -DU32, 7, 166140 -CURR, 665, 94378, 1093, 1827, 5051, 63.492470 -CTUN, 665, 0.20, 0.31, 0.000000, 0, 0, 0, 665, 0 -ATT, 0.00, -0.03, -2.24, -1.22, 0.00, 70.46, 62.38 -CTUN, 665, 0.20, 0.42, 0.000000, 0, 0, 1, 665, 0 -ATT, 0.00, -0.26, -2.14, -1.07, 0.00, 70.10, 62.38 -CTUN, 665, 0.20, 0.26, 0.000000, 0, 0, 0, 665, 0 -ATT, 0.00, -0.48, -2.24, -1.22, 0.00, 69.59, 62.38 -CTUN, 665, 0.20, 0.28, 0.000000, 0, 0, -1, 665, 0 -MODE, ALT_HOLD, 634 -ATT, 0.00, -0.54, -2.24, -1.36, 0.00, 68.92, 62.38 -CTUN, 665, 0.20, -0.13, -0.282000, 0, 0, -2, 653, 40 -ATT, 0.00, 0.26, -2.24, -1.30, 0.00, 68.15, 62.38 -CTUN, 665, 0.20, 0.19, -0.221400, 0, 0, -3, 675, 41 -ATT, 0.00, 1.09, -2.24, -1.30, 0.00, 67.41, 62.38 -CTUN, 669, 0.20, 0.00, -0.161200, 0, 0, -1, 705, 40 -ATT, 0.00, 1.64, -2.14, -1.07, 0.00, 66.68, 62.38 -CTUN, 665, 0.20, -0.36, -0.100400, 0, 0, 4, 701, 40 -ATT, 0.00, 0.87, -2.05, -0.59, 0.00, 66.10, 62.38 -CTUN, 666, 0.20, -0.02, -0.059800, 0, 0, 10, 704, 41 -ATT, 0.00, -0.34, -2.24, -0.08, 0.00, 65.50, 62.38 -CTUN, 666, 0.20, 0.15, 0.001000, 0, 0, 15, 696, 41 -ATT, 0.00, -0.91, -2.24, 0.15, 0.00, 64.99, 62.38 -DU32, 7, 166132 -CURR, 666, 101172, 1073, 1933, 5028, 68.649132 -CTUN, 665, 0.20, 0.17, 0.081600, 0, 0, 19, 693, 41 -ATT, 0.00, -0.48, -2.24, 0.40, 0.00, 64.69, 62.38 -CTUN, 666, 0.20, 0.22, 0.161800, 0, 0, 24, 703, 41 -ATT, 0.00, 0.02, -2.24, 0.32, 0.00, 64.53, 62.38 -CTUN, 666, 0.20, 0.35, 0.234200, 0, 0, 24, 715, 40 -ATT, 0.00, 0.10, -2.24, -0.03, 0.00, 64.44, 62.38 -CTUN, 665, 0.20, 0.35, 0.334800, 0, 0, 31, 708, 40 -ATT, 0.00, -0.20, -2.24, -0.19, 0.00, 64.35, 62.38 -CTUN, 665, 0.20, 0.48, 0.397400, 0, 0, 34, 720, 41 -ATT, 0.00, -0.47, -2.24, -0.36, 0.00, 64.15, 62.38 -CTUN, 665, 0.20, 0.38, 0.507600, 0, 0, 37, 736, 40 -ATT, 0.00, 0.31, -2.24, -0.79, 0.00, 63.89, 62.38 -CTUN, 666, 0.23, 0.33, 0.608000, 0, 0, 41, 718, 40 -ATT, 0.46, 0.63, -2.05, -0.90, 0.00, 63.75, 62.38 -CTUN, 665, 0.23, 0.49, 0.678200, 0, 0, 42, 737, 40 -ATT, 3.00, 0.48, -2.05, -1.02, 0.00, 63.85, 62.38 -CTUN, 666, 0.27, 0.46, 0.750200, 0, 0, 43, 728, 40 -ATT, 5.34, 1.38, -2.05, -0.79, 0.00, 64.10, 62.38 -CTUN, 666, 0.27, 0.56, 0.812600, 0, 0, 46, 726, 40 -ATT, 5.06, 3.00, -2.05, -0.02, 0.00, 64.37, 62.38 -CTUN, 666, 0.34, 0.53, 0.913200, 0, 1, 47, 743, 40 -DU32, 7, 166132 -CURR, 665, 109100, 1072, 2158, 5028, 74.936569 -ATT, 5.43, 4.44, -2.05, 0.19, 0.00, 64.60, 62.38 -CTUN, 666, 0.34, 0.61, 0.935800, 0, 2, 46, 729, 41 -ATT, 4.50, 4.97, -2.05, -0.11, 0.00, 64.80, 62.38 -CTUN, 665, 0.41, 0.86, 1.028200, 0, 2, 46, 758, 41 -ATT, 3.18, 4.73, -2.05, -0.58, 0.00, 65.06, 62.38 -CTUN, 666, 0.41, 0.89, 1.068400, 0, 1, 48, 732, 40 -ATT, 3.00, 3.93, -2.24, -0.59, 0.00, 65.34, 62.38 -CTUN, 666, 0.48, 1.05, 1.160800, 0, 1, 49, 750, 41 -ATT, 1.87, 2.59, -2.24, -1.01, 0.00, 65.65, 62.38 -CTUN, 666, 0.48, 0.94, 1.211401, 0, 0, 49, 738, 41 -ATT, 0.84, 1.43, -2.05, -1.56, 0.00, 65.91, 62.38 -CTUN, 665, 0.55, 0.98, 1.303800, 0, 0, 48, 753, 41 -ATT, 0.46, 0.70, -2.24, -1.73, 0.00, 66.09, 62.38 -CTUN, 665, 0.55, 0.90, 1.344601, 0, 0, 48, 740, 41 -ATT, 0.46, -0.25, -2.24, -2.00, 0.00, 66.12, 62.38 -CTUN, 666, 0.62, 0.83, 1.417001, 0, 0, 50, 753, 41 -ATT, 0.37, -0.95, -2.24, -2.39, 0.00, 66.07, 62.38 -CTUN, 665, 0.62, 0.91, 1.447201, 0, 0, 50, 727, 40 -ATT, 0.46, -1.03, -2.24, -2.43, 0.00, 65.97, 62.38 -CTUN, 666, 0.69, 1.03, 1.527401, 0, 0, 51, 745, 40 -DU32, 7, 166132 -CURR, 666, 116510, 1059, 2112, 5051, 80.906990 -ATT, 0.46, -1.21, -2.24, -2.27, 0.00, 65.94, 62.38 -CTUN, 665, 0.69, 0.91, 1.558201, 0, 0, 52, 729, 40 -ATT, 0.46, -1.14, -2.24, -1.94, 0.00, 65.94, 62.38 -CTUN, 662, 0.76, 1.06, 1.638001, 0, 0, 52, 739, 39 -ATT, 0.46, -0.73, -2.24, -1.49, 0.00, 65.86, 62.38 -CTUN, 657, 0.76, 1.05, 1.655201, 0, 0, 53, 729, 35 -ATT, 0.46, -0.16, -2.24, -1.34, 0.00, 65.73, 62.38 -CTUN, 645, 0.82, 1.09, 1.719001, 0, 0, 50, 742, 28 -ATT, 0.84, 0.21, -2.24, -1.62, 0.00, 65.68, 62.38 -CTUN, 644, 0.82, 1.15, 1.736601, 0, 0, 51, 725, 27 -ATT, 1.03, 0.63, -2.24, -1.92, 0.00, 65.64, 62.38 -CTUN, 630, 0.89, 1.23, 1.796000, 0, 0, 51, 735, 22 -ATT, 1.59, 1.17, -2.24, -2.01, 0.00, 65.67, 62.38 -CTUN, 615, 0.89, 1.23, 1.799200, 0, 0, 50, 718, 9 -ATT, 1.78, 1.62, -2.24, -1.67, 0.00, 65.80, 62.38 -CTUN, 588, 0.96, 1.28, 1.839200, 0, 0, 49, 721, 0 -ATT, 1.78, 1.92, -2.24, -1.31, 0.00, 65.87, 62.38 -CTUN, 575, 0.96, 1.24, 1.819200, 0, 0, 46, 694, 0 -ATT, 1.78, 2.09, -2.05, -0.80, 0.00, 66.01, 62.38 -CTUN, 575, 1.03, 1.26, 1.849200, 0, 0, 42, 709, 0 -DU32, 7, 166132 -CURR, 575, 123751, 1073, 1922, 5028, 86.622047 -ATT, 1.21, 2.50, -2.05, -0.75, 0.00, 66.23, 62.38 -CTUN, 575, 1.03, 1.36, 1.809200, 0, 0, 37, 688, 0 -ATT, 0.46, 2.69, -2.05, -0.72, 0.00, 66.45, 62.38 -CTUN, 575, 1.09, 1.23, 1.839200, 0, 0, 31, 710, 0 -ATT, 0.00, 2.32, -2.05, -0.48, 0.00, 66.66, 62.38 -CTUN, 575, 1.09, 1.35, 1.789200, 0, 0, 27, 707, 0 -ATT, 0.00, 1.36, -0.18, -0.18, 0.00, 66.89, 62.38 -CTUN, 578, 1.13, 1.43, 1.809200, 0, 0, 24, 712, 0 -ATT, 0.00, 0.78, 0.00, 0.37, 0.00, 67.13, 62.38 -CTUN, 584, 1.13, 1.38, 1.789200, 0, 0, 21, 706, 0 -ATT, 0.00, 0.61, 0.00, 1.28, 0.00, 67.38, 62.38 -CTUN, 585, 1.17, 1.39, 1.799200, 0, 0, 19, 716, 0 -ATT, 0.00, 0.56, 0.00, 1.68, 0.00, 67.65, 62.38 -CTUN, 584, 1.17, 1.37, 1.769200, 0, 0, 17, 701, 0 -ATT, 0.00, 0.64, 0.00, 1.53, 0.00, 67.91, 62.38 -CTUN, 585, 1.17, 1.41, 1.769200, 0, 0, 15, 718, 0 -ATT, 0.00, 0.95, 0.00, 1.30, 0.00, 68.21, 62.38 -CTUN, 585, 1.09, 1.41, 1.779200, 0, 0, 14, 714, 0 -ATT, 0.00, 0.63, 0.00, 1.14, 0.00, 68.42, 62.38 -CTUN, 584, 1.09, 1.54, 1.859200, 0, 0, 15, 745, 0 -DU32, 7, 166132 -CURR, 584, 130868, 1061, 2233, 5051, 92.162010 -ATT, 0.00, -0.13, 0.00, 0.88, 0.00, 68.62, 62.38 -CTUN, 587, 1.09, 1.39, 1.869200, 0, 0, 19, 746, 0 -ATT, 0.00, -0.41, 0.00, 0.62, 0.00, 68.81, 62.38 -CTUN, 590, 1.12, 1.37, 1.879200, 0, 0, 23, 741, 0 -ATT, 0.00, -0.42, 0.00, 0.52, 0.00, 68.94, 62.38 -CTUN, 591, 1.12, 1.31, 1.869200, 0, 0, 27, 701, 0 -ATT, 0.00, -0.25, 0.00, 0.67, 0.00, 68.93, 62.38 -CTUN, 589, 1.20, 1.37, 1.879200, 0, 0, 25, 713, 0 -ATT, 0.00, -0.06, 0.00, 0.85, 0.00, 68.79, 62.38 -CTUN, 585, 1.15, 1.49, 1.799200, 0, 0, 23, 686, 0 -ATT, 0.00, 0.42, 0.00, 0.79, 0.00, 68.66, 62.38 -CTUN, 567, 1.15, 1.45, 1.869200, 0, 0, 19, 717, 0 -ATT, 0.00, 0.94, 0.00, 0.70, 0.00, 68.46, 62.38 -CTUN, 554, 1.15, 1.49, 1.869200, 0, 0, 16, 737, 0 -ATT, 0.00, 1.17, -0.09, 0.61, 0.00, 68.39, 62.38 -CTUN, 558, 1.23, 1.44, 1.879200, 0, 0, 17, 722, 0 -ATT, 0.00, 1.23, 0.00, 0.50, 0.00, 68.26, 62.38 -CTUN, 549, 1.23, 1.48, 1.809200, 0, 0, 18, 677, 0 -ATT, 0.00, 1.32, 0.00, 0.59, 0.00, 68.09, 62.38 -CTUN, 565, 1.27, 1.46, 1.809200, 0, 0, 13, 696, 0 -DU32, 7, 166132 -CURR, 575, 138004, 1066, 1895, 5028, 97.808418 -ATT, 0.00, 0.90, 0.00, 0.87, 0.00, 67.92, 62.38 -CTUN, 578, 1.27, 1.49, 1.769200, 0, 0, 9, 707, 0 -ATT, 0.00, -0.03, 0.00, 0.99, 0.00, 67.94, 62.38 -CTUN, 575, 1.28, 1.48, 1.769200, 0, 0, 5, 721, 0 -ATT, -2.27, -0.80, -2.24, 0.65, 0.00, 67.99, 62.38 -CTUN, 575, 1.28, 1.54, 1.749200, 0, 0, 1, 734, 0 -ATT, -2.36, -1.97, -2.33, -0.26, 0.00, 68.18, 62.38 -CTUN, 574, 1.28, 1.48, 1.739200, 0, 0, 1, 732, 0 -ATT, -4.26, -3.01, -2.52, -1.49, 0.00, 68.29, 62.38 -CTUN, 577, 1.22, 1.47, 1.729200, 0, 1, 1, 728, 0 -ATT, -4.26, -3.74, -2.52, -2.28, 0.00, 68.26, 62.38 -CTUN, 575, 1.22, 1.52, 1.789200, 0, 2, 1, 767, 0 -ATT, -2.93, -4.38, -2.89, -2.81, 0.00, 67.98, 62.38 -CTUN, 576, 1.22, 1.43, 1.779200, 0, 2, 8, 757, 0 -ATT, -0.18, -4.13, -2.80, -3.24, 0.00, 67.37, 62.38 -CTUN, 578, 1.22, 1.40, 1.779200, 0, 2, 11, 736, 0 -ATT, -0.09, -3.15, -2.42, -3.18, 0.00, 66.63, 62.38 -CTUN, 578, 1.22, 1.56, 1.779200, 0, 1, 14, 733, 0 -ATT, 0.00, -2.05, -2.42, -2.79, 0.00, 65.83, 62.38 -CTUN, 576, 1.25, 1.54, 1.789200, 0, 0, 13, 731, 0 -DU32, 7, 166132 -CURR, 577, 145350, 1063, 2069, 5051, 103.655980 -ATT, 0.00, -1.61, -2.61, -2.74, 0.00, 65.08, 62.38 -CTUN, 562, 1.22, 1.55, 1.769200, 0, 0, 13, 726, 0 -ATT, -0.09, -1.44, -2.61, -2.68, 0.00, 64.37, 62.38 -CTUN, 560, 1.25, 1.43, 1.799200, 0, 0, 11, 738, 0 -ATT, 0.00, -0.95, -2.70, -2.62, 0.00, 63.69, 62.38 -CTUN, 562, 1.25, 1.67, 1.769200, 0, 0, 11, 724, 0 -ATT, 0.00, -0.38, -2.42, -2.76, 0.00, 63.20, 62.38 -CTUN, 562, 1.29, 1.68, 1.779200, 0, 0, 11, 713, 0 -ATT, 0.00, 0.15, -2.52, -2.65, 0.00, 62.82, 62.38 -CTUN, 562, 1.29, 1.63, 1.759200, 0, 0, 11, 715, 0 -ATT, 0.00, 0.78, -2.42, -2.24, 0.00, 62.51, 62.38 -CTUN, 560, 1.30, 1.58, 1.759200, 0, 0, 9, 720, 0 -ATT, 0.00, 1.25, -2.52, -2.01, 0.00, 62.16, 62.38 -CTUN, 560, 1.30, 1.59, 1.749200, 0, 0, 5, 719, 0 -ATT, 0.00, 1.61, -2.52, -1.91, 0.00, 61.75, 62.38 -CTUN, 560, 1.32, 1.59, 1.759200, 0, 0, 6, 713, 0 -ATT, 0.00, 1.39, -2.42, -1.72, 0.00, 61.26, 62.38 -CTUN, 560, 1.32, 1.55, 1.739200, 0, 0, 7, 708, 0 -ATT, 0.00, 0.88, -2.52, -1.41, 0.00, 60.65, 62.38 -CTUN, 561, 1.32, 1.57, 1.729200, 0, 0, 5, 731, 0 -DU32, 7, 166132 -CURR, 562, 152557, 1065, 1969, 5051, 109.220810 -ATT, 0.00, 0.56, -2.24, -1.50, 0.00, 59.98, 62.38 -CTUN, 556, 1.32, 1.60, 1.729200, 0, 0, 2, 719, 0 -ATT, 0.00, 1.14, -2.52, -1.77, 0.00, 59.55, 62.38 -CTUN, 558, 1.33, 1.61, 1.729200, 0, 0, 2, 720, 0 -ATT, 0.00, 1.59, -2.52, -1.93, 0.00, 59.27, 62.38 -CTUN, 561, 1.33, 1.73, 1.719200, 0, 0, 1, 714, 0 -ATT, 0.00, 1.37, -2.52, -1.79, 0.00, 59.08, 62.38 -CTUN, 560, 1.33, 1.66, 1.719200, 0, 0, 0, 711, 0 -ATT, 0.00, 1.23, -2.42, -1.40, 0.00, 59.00, 62.38 -CTUN, 561, 1.33, 1.63, 1.719200, 0, 0, 0, 735, 0 -ATT, 0.00, 1.39, -2.52, -0.88, 0.00, 59.15, 62.38 -CTUN, 561, 1.33, 1.62, 1.719200, 0, 0, -3, 729, 0 -ATT, 0.00, 1.10, -2.52, -0.82, 0.00, 59.54, 62.38 -CTUN, 555, 1.32, 1.71, 1.709200, 0, 0, -1, 729, 0 -ATT, 0.00, 0.86, -2.42, -1.14, 0.00, 60.01, 62.38 -CTUN, 555, 1.32, 1.75, 1.719200, 0, 0, 0, 742, 0 -ATT, 0.00, 1.17, -2.52, -1.51, 0.00, 60.34, 62.38 -PM, 0, 0, 0, 0, 1000, 10484, 0, 0 -CTUN, 552, 1.31, 1.85, 1.729200, 0, 0, 1, 741, 0 -ATT, 0.00, 1.24, -2.42, -1.58, 0.00, 60.42, 62.38 -CTUN, 553, 1.31, 1.66, 1.749200, 0, 0, 1, 742, 0 -DU32, 7, 166132 -CURR, 553, 159835, 1063, 2079, 5051, 114.962650 -ATT, 0.00, 0.82, -2.42, -1.28, 0.00, 60.33, 62.38 -CTUN, 551, 1.31, 1.70, 1.749200, 0, 0, 4, 729, 0 -ATT, 0.00, 0.20, -2.52, -1.01, 0.00, 60.16, 62.38 -CTUN, 553, 1.31, 1.70, 1.759200, 0, 0, 5, 729, 0 -ATT, 0.00, -0.14, -2.52, -1.02, 0.00, 59.76, 62.38 -CTUN, 599, 1.31, 1.65, 1.759200, 0, 0, 7, 731, 0 -ATT, 0.00, -0.29, -2.42, -1.07, 0.00, 59.19, 62.38 -CTUN, 551, 1.31, 1.70, 1.769200, 0, 0, 4, 731, 0 -ATT, 0.00, -0.18, -2.52, -1.28, 0.00, 58.54, 62.38 -CTUN, 551, 1.31, 1.66, 1.769200, 0, 0, 5, 730, 0 -ATT, 0.00, -0.51, -2.24, -1.59, 0.00, 57.82, 62.38 -CTUN, 597, 1.31, 1.70, 1.769200, 0, 0, 2, 741, 0 -ATT, 0.00, -1.11, -2.24, -2.18, 0.00, 57.13, 62.38 -CTUN, 551, 1.30, 1.81, 1.769200, 0, 0, 1, 740, 0 -ATT, 0.00, -1.49, -2.42, -2.80, 0.00, 56.64, 62.38 -CTUN, 551, 1.31, 1.74, 1.789200, 0, 1, 2, 748, 0 -ATT, 0.00, -1.80, -2.24, -2.70, 0.00, 56.51, 62.38 -CTUN, 551, 1.31, 1.67, 1.779200, 0, 0, 2, 748, 0 -ATT, 0.00, -1.71, -2.05, -2.12, 0.00, 56.63, 62.38 -CTUN, 551, 1.33, 1.74, 1.779200, 0, 0, 3, 741, 0 -DU32, 7, 166132 -CURR, 595, 167190, 1055, 2103, 5051, 120.729560 -ATT, 0.00, -1.21, -1.96, -1.48, 0.00, 57.05, 62.38 -CTUN, 564, 1.31, 1.74, 1.769200, 0, 0, 1, 736, 0 -ATT, 0.00, -0.87, -0.93, -0.95, 0.00, 57.72, 62.38 -CTUN, 563, 1.31, 1.65, 1.789200, 0, 0, 3, 748, 0 -ATT, 0.00, -0.95, -0.93, -0.49, 0.00, 58.72, 62.38 -CTUN, 562, 1.31, 1.66, 1.789200, 0, 0, 2, 751, 0 -ATT, 0.00, -0.98, 0.00, -0.41, 0.00, 59.59, 62.38 -CTUN, 562, 1.34, 1.67, 1.789200, 0, 0, 4, 735, 0 -ATT, 0.00, -0.97, 0.00, -0.07, 0.00, 60.35, 62.38 -CTUN, 562, 1.34, 1.55, 1.759200, 0, 0, 4, 725, 0 -ATT, 0.00, -0.89, 0.00, 0.61, 0.00, 61.07, 62.38 -CTUN, 558, 1.34, 1.74, 1.749200, 0, 0, 4, 737, 0 -ATT, 0.28, -0.73, 0.00, 1.32, 0.00, 61.71, 62.38 -CTUN, 558, 1.34, 1.65, 1.759200, 0, 0, 2, 729, 0 -ATT, 0.65, -0.31, 0.00, 1.82, 0.00, 62.24, 62.38 -CTUN, 558, 1.35, 1.63, 1.749200, 0, 0, 1, 728, 0 -ATT, 1.96, 0.17, 0.00, 1.77, 0.00, 62.74, 62.38 -CTUN, 557, 1.35, 1.68, 1.739200, 0, 0, 1, 725, 0 -ATT, 3.18, 1.04, 0.00, 1.46, 0.00, 63.28, 62.38 -CTUN, 557, 1.36, 1.67, 1.739200, 0, 0, 1, 722, 0 -DU32, 7, 166132 -CURR, 557, 174538, 1055, 2045, 5051, 126.465110 -ATT, 4.40, 2.16, 0.00, 1.06, 0.00, 63.90, 62.38 -CTUN, 556, 1.36, 1.64, 1.729200, 0, 0, 2, 734, 0 -ATT, 6.00, 3.14, 0.00, 0.88, 0.00, 64.46, 62.38 -CTUN, 555, 1.36, 1.54, 1.719200, 0, 1, 1, 734, 0 -ATT, 5.25, 4.71, 0.00, 0.64, 0.00, 64.85, 62.38 -CTUN, 555, 1.36, 1.72, 1.719200, 0, 2, 2, 732, 0 -ATT, 3.46, 5.50, -0.93, 0.67, 0.00, 64.91, 62.38 -CTUN, 557, 1.36, 1.54, 1.719200, 0, 2, 1, 739, 0 -ATT, 3.18, 4.43, -1.49, 0.46, 0.00, 64.72, 62.38 -CTUN, 556, 1.36, 1.60, 1.709200, 0, 1, 0, 749, 0 -ATT, 2.43, 3.07, -2.24, -0.17, 0.00, 64.39, 62.38 -CTUN, 556, 1.36, 1.62, 1.699200, 0, 0, -1, 745, 0 -ATT, 0.46, 2.32, -2.52, -0.66, 0.00, 63.95, 62.38 -CTUN, 556, 1.35, 1.63, 1.699200, 0, 0, 0, 746, 0 -ATT, 0.28, 1.36, -2.52, -0.91, 0.00, 63.35, 62.38 -CTUN, 555, 1.36, 1.62, 1.699200, 0, 0, -1, 738, 0 -ATT, 0.09, 0.84, -2.52, -1.34, 0.00, 62.79, 62.38 -CTUN, 554, 1.35, 1.58, 1.689200, 0, 0, 0, 736, 0 -ATT, 0.28, 0.63, -2.52, -1.79, 0.00, 62.18, 62.38 -CTUN, 555, 1.36, 1.58, 1.699200, 0, 0, 0, 742, 0 -DU32, 7, 166132 -CURR, 555, 181912, 1051, 2088, 5051, 132.255620 -ATT, 0.28, 0.39, -2.24, -2.40, 0.00, 61.72, 62.38 -CTUN, 555, 1.36, 1.71, 1.679200, 0, 0, 1, 750, 0 -ATT, 0.37, 0.43, -2.52, -2.72, 0.00, 61.31, 62.38 -CTUN, 555, 1.36, 1.62, 1.679200, 0, 0, 1, 736, 0 -ATT, 0.28, 0.29, -2.42, -2.59, 0.00, 61.03, 62.38 -CTUN, 555, 1.36, 1.67, 1.679200, 0, 0, 1, 741, 0 -ATT, 0.09, -0.03, -2.42, -2.85, 0.00, 60.92, 62.38 -CTUN, 553, 1.38, 1.62, 1.679200, 0, 0, 3, 736, 0 -ATT, 0.28, -0.49, -2.52, -3.18, 0.00, 60.99, 62.38 -CTUN, 553, 1.38, 1.61, 1.659200, 0, 1, 2, 725, 0 -ATT, 0.28, -0.62, -2.52, -3.51, 0.00, 61.19, 62.38 -CTUN, 552, 1.38, 1.64, 1.659200, 0, 1, 4, 720, 0 -ATT, 0.18, -0.41, -2.42, -3.37, 0.00, 61.42, 62.38 -CTUN, 553, 1.38, 1.64, 1.669200, 0, 0, 2, 725, 0 -ATT, 0.28, 0.06, -2.33, -2.92, 0.00, 61.57, 62.38 -CTUN, 550, 1.39, 1.60, 1.669200, 0, 0, 1, 727, 0 -ATT, 0.93, 0.33, -2.14, -2.44, 0.00, 61.68, 62.38 -CTUN, 544, 1.39, 1.56, 1.649200, 0, 0, 0, 729, 0 -ATT, 1.03, 0.46, -2.24, -2.53, 0.00, 61.85, 62.38 -CTUN, 546, 1.40, 1.53, 1.639200, 0, 0, -3, 723, 0 -DU32, 7, 166132 -CURR, 546, 189240, 1060, 2009, 5051, 137.897920 -ATT, 0.46, 0.84, -2.24, -2.73, 0.00, 62.07, 62.38 -CTUN, 547, 1.40, 1.61, 1.619200, 0, 0, -3, 724, 0 -ATT, 0.37, 0.73, -2.33, -2.57, 0.00, 62.34, 62.38 -CTUN, 546, 1.41, 1.64, 1.609200, 0, 0, -6, 735, 0 -ATT, 0.46, 0.31, -2.24, -2.44, 0.00, 62.83, 62.38 -CTUN, 546, 1.40, 1.63, 1.599200, 0, 0, -7, 732, 0 -ATT, 0.46, 0.18, -2.24, -2.44, 0.00, 63.38, 62.38 -CTUN, 547, 1.40, 1.65, 1.599200, 0, 0, -8, 735, 0 -ATT, 0.46, 0.31, -2.24, -2.39, 0.00, 64.14, 62.38 -CTUN, 546, 1.40, 1.66, 1.589200, 0, 0, -7, 733, 0 -ATT, 0.46, 0.39, -2.24, -2.41, 0.00, 65.11, 62.38 -CTUN, 546, 1.40, 1.64, 1.589200, 0, 0, -6, 732, 0 -ATT, 0.46, 0.55, -2.24, -2.53, 0.00, 66.29, 62.38 -CTUN, 546, 1.39, 1.55, 1.579200, 0, 0, -7, 734, 0 -ATT, 0.18, 0.58, -2.24, -2.52, 0.00, 67.61, 62.38 -CTUN, 597, 1.39, 1.66, 1.579200, 0, 0, -6, 735, 0 -ATT, 0.00, 0.37, -2.14, -2.45, 0.00, 68.78, 62.38 -CTUN, 544, 1.38, 1.60, 1.579200, 0, 0, -4, 734, 0 -ATT, 0.00, -0.02, -2.24, -2.21, 0.00, 69.81, 62.38 -CTUN, 547, 1.38, 1.57, 1.589200, 0, 0, -2, 729, 0 -ATT, 0.00, -0.02, -2.24, -1.67, 0.00, 70.71, 62.38 -DU32, 7, 166132 -CURR, 546, 196582, 1056, 2093, 5051, 143.629650 -CTUN, 546, 1.38, 1.72, 1.579200, 0, 0, -4, 737, 0 -ATT, 0.00, 0.08, -2.24, -1.25, 0.00, 71.56, 62.38 -CTUN, 546, 1.38, 1.61, 1.579200, 0, 0, -2, 724, 0 -ATT, 0.00, 0.32, -2.24, -1.07, 0.00, 72.27, 62.38 -CTUN, 546, 1.38, 1.59, 1.579200, 0, 0, -3, 726, 0 -ATT, 0.00, 0.23, -2.24, -1.23, 0.00, 72.82, 62.82 -CTUN, 547, 1.38, 1.62, 1.579200, 0, 0, -3, 729, 0 -ATT, 0.00, -0.13, -2.52, -1.35, 0.00, 73.31, 63.31 -CTUN, 547, 1.38, 1.66, 1.579200, 0, 0, -5, 736, 0 -ATT, 0.00, -0.80, -2.42, -1.52, 0.00, 73.63, 63.63 -CTUN, 547, 1.38, 1.65, 1.569200, 0, 0, -6, 738, 0 -ATT, 0.00, -0.97, -2.42, -1.83, 0.00, 73.98, 63.98 -CTUN, 546, 1.38, 1.76, 1.569200, 0, 0, -4, 751, 0 -ATT, 0.00, -0.40, -2.24, -1.97, 0.00, 74.22, 64.22 -CTUN, 547, 1.38, 1.63, 1.579200, 0, 0, -4, 735, 0 -ATT, 0.00, 0.17, -2.33, -2.01, 0.00, 74.32, 64.32 -CTUN, 546, 1.36, 1.73, 1.579200, 0, 0, 0, 714, 0 -ATT, 0.00, 0.87, -2.42, -2.20, 0.00, 74.31, 64.32 -CTUN, 547, 1.37, 1.73, 1.599200, 0, 0, -2, 747, 0 -ATT, 0.00, 1.56, -2.42, -2.27, 0.00, 74.24, 64.32 -DU32, 7, 166132 -CURR, 546, 203936, 1056, 2049, 5028, 149.429180 -CTUN, 546, 1.36, 1.64, 1.599200, 0, 0, -2, 737, 0 -ATT, 0.00, 2.07, -2.24, -1.77, 0.00, 73.99, 64.32 -CTUN, 546, 1.36, 1.71, 1.609200, 0, 0, -1, 735, 0 -ATT, 0.00, 2.28, -2.24, -0.88, 0.00, 73.43, 64.32 -CTUN, 546, 1.36, 1.76, 1.619200, 0, 0, 0, 739, 0 -ATT, 0.00, 1.93, -2.24, 0.11, 0.00, 72.55, 64.32 -CTUN, 546, 1.36, 1.61, 1.619200, 0, 0, 0, 736, 0 -ATT, 0.00, 1.71, -2.24, 1.00, 0.00, 71.43, 64.32 -CTUN, 546, 1.32, 1.61, 1.629200, 0, 0, 0, 752, 0 -ATT, 0.00, 1.94, -2.24, 1.36, 0.00, 70.08, 64.32 -CTUN, 546, 1.36, 1.67, 1.669200, 0, 0, -1, 754, 0 -ATT, 0.00, 1.79, -2.24, 1.26, 0.00, 68.80, 64.32 -CTUN, 546, 1.36, 1.72, 1.629200, 0, 0, 0, 745, 0 -ATT, 0.00, 1.27, -2.24, 0.52, 0.00, 67.67, 64.32 -CTUN, 546, 1.37, 1.69, 1.639200, 0, 0, 4, 731, 0 -ATT, 0.00, 0.47, -2.24, -0.42, 0.00, 66.68, 64.32 -CTUN, 546, 1.36, 1.81, 1.639200, 0, 0, 3, 734, 0 -ATT, 0.00, 0.03, -2.33, -0.94, 0.00, 65.82, 64.32 -CTUN, 537, 1.36, 1.68, 1.659200, 0, 0, 3, 735, 0 -ATT, 0.00, 0.37, -2.33, -1.12, 0.00, 65.11, 64.32 -DU32, 7, 166132 -CURR, 537, 211302, 1064, 1979, 5028, 155.222180 -CTUN, 537, 1.36, 1.72, 1.659200, 0, 0, 2, 729, 0 -ATT, 0.00, 1.06, -2.42, -1.17, 0.00, 64.57, 64.32 -CTUN, 535, 1.36, 1.70, 1.669200, 0, 0, 1, 732, 0 -ATT, 0.00, 1.04, -2.42, -0.95, 0.00, 64.29, 64.32 -CTUN, 535, 1.36, 1.71, 1.679200, 0, 0, 0, 739, 0 -ATT, 0.00, 0.56, -2.42, -1.02, 0.00, 64.21, 64.32 -CTUN, 536, 1.37, 1.84, 1.679200, 0, 0, 0, 737, 0 -ATT, 0.00, 0.10, -2.42, -1.31, 0.00, 64.32, 64.32 -CTUN, 537, 1.37, 1.70, 1.679200, 0, 0, 0, 723, 0 -ATT, 0.00, -0.27, -2.52, -1.69, 0.00, 64.63, 64.32 -CTUN, 535, 1.38, 1.68, 1.679200, 0, 0, 1, 726, 0 -ATT, 0.00, -0.60, -2.52, -1.78, 0.00, 64.98, 64.32 -CTUN, 535, 1.38, 1.70, 1.669200, 0, 0, 0, 716, 0 -ATT, 0.00, -1.19, -2.33, -1.83, 0.00, 65.49, 64.32 -CTUN, 533, 1.44, 1.65, 1.669200, 0, 0, 0, 720, 0 -ATT, -2.46, -1.94, -2.42, -1.83, 0.00, 66.11, 64.32 -CTUN, 535, 1.44, 1.74, 1.609200, 0, 0, -3, 701, 0 -ATT, 0.00, -1.90, -2.42, -2.25, 0.00, 66.73, 64.32 -CTUN, 535, 1.44, 1.62, 1.609200, 0, 0, -6, 716, 0 -ATT, -2.55, -1.84, -2.42, -2.38, 0.00, 67.18, 64.32 -DU32, 7, 166132 -CURR, 534, 218592, 1063, 1893, 5051, 160.758710 -CTUN, 533, 1.44, 1.70, 1.599200, 0, 0, -10, 735, 0 -ATT, 0.00, -2.50, -2.33, -2.34, 0.00, 67.50, 64.32 -CTUN, 535, 1.44, 1.68, 1.589200, 0, 1, -13, 727, 0 -ATT, 0.00, -2.75, -2.33, -2.19, 0.00, 67.69, 64.32 -CTUN, 535, 1.43, 1.70, 1.569200, 0, 0, -13, 734, 0 -ATT, 0.00, -2.05, -2.52, -1.85, 0.00, 67.60, 64.32 -CTUN, 535, 1.43, 1.74, 1.569200, 0, 0, -14, 752, 0 -ATT, 0.00, -1.44, -2.33, -1.54, 0.00, 67.09, 64.32 -CTUN, 535, 1.40, 1.70, 1.559200, 0, 0, -13, 752, 0 -ATT, 0.00, -1.17, -2.52, -1.21, 0.00, 66.32, 64.32 -CTUN, 535, 1.40, 1.67, 1.589200, 0, 0, -10, 757, 0 -ATT, 0.00, -1.41, -2.42, -0.90, 0.00, 65.44, 64.32 -CTUN, 535, 1.39, 1.63, 1.579200, 0, 0, -7, 749, 0 -ATT, 0.00, -1.13, -2.52, -0.74, 0.00, 64.55, 64.32 -CTUN, 535, 1.39, 1.70, 1.589200, 0, 0, -5, 739, 0 -ATT, 0.00, -0.53, -2.52, -0.67, 0.00, 63.65, 64.32 -CTUN, 535, 1.39, 1.59, 1.589200, 0, 0, -3, 741, 0 -ATT, 0.00, -0.30, -2.52, -0.77, 0.00, 62.73, 64.32 -CTUN, 535, 1.39, 1.62, 1.589200, 0, 0, -1, 727, 0 -ATT, 0.00, -0.19, -2.52, -0.90, 0.00, 61.83, 64.32 -DU32, 7, 166132 -CURR, 535, 226032, 1056, 2017, 5051, 166.545200 -CTUN, 529, 1.39, 1.77, 1.589200, 0, 0, -1, 741, 0 -ATT, 0.00, -0.39, -2.24, -1.17, 0.00, 61.03, 64.32 -CTUN, 519, 1.39, 1.58, 1.589200, 0, 0, -3, 724, 0 -ATT, 0.00, -0.48, -2.42, -1.24, 0.00, 60.32, 64.32 -CTUN, 513, 1.39, 1.60, 1.589200, 0, 0, -2, 733, 0 -ATT, 0.00, -0.47, -2.42, -1.02, 0.00, 59.78, 64.32 -CTUN, 510, 1.39, 1.70, 1.589200, 0, 0, -2, 735, 0 -ATT, 0.00, -0.28, -2.42, -0.93, 0.00, 59.60, 64.32 -CTUN, 510, 1.39, 1.72, 1.589200, 0, 0, -3, 746, 0 -ATT, 0.00, -0.34, -2.42, -1.01, 0.00, 59.81, 64.32 -CTUN, 503, 1.39, 1.62, 1.589200, 0, 0, -4, 732, 0 -ATT, 0.00, -0.17, -2.52, -1.44, 0.00, 60.15, 64.32 -CTUN, 502, 1.39, 1.67, 1.589200, 0, 0, -4, 727, 0 -ATT, 0.00, -0.20, -2.24, -1.77, 0.00, 60.56, 64.32 -CTUN, 504, 1.40, 1.60, 1.589200, 0, 0, -4, 733, 0 -ATT, 0.00, -0.65, -2.05, -1.91, 0.00, 60.86, 64.32 -PM, 0, 0, 0, 1, 1000, 10508, 0, 0 -CTUN, 503, 1.40, 1.64, 1.569200, 0, 0, -4, 730, 0 -ATT, 0.28, -1.07, -2.24, -2.30, 0.00, 61.06, 64.32 -CTUN, 503, 1.40, 1.68, 1.569200, 0, 0, -6, 735, 0 -ATT, 0.28, -1.04, -2.24, -2.81, 0.00, 61.28, 64.32 -DU32, 7, 166132 -CURR, 503, 233339, 1044, 2026, 5051, 172.191180 -CTUN, 504, 1.40, 1.67, 1.569200, 0, 0, -7, 740, 0 -ATT, 2.15, -1.04, -2.24, -3.11, 0.00, 61.71, 64.32 -CTUN, 504, 1.40, 1.68, 1.559200, 0, 1, -7, 739, 0 -ATT, 2.15, -0.54, -2.24, -3.34, 0.00, 62.34, 64.32 -CTUN, 500, 1.40, 1.73, 1.559200, 0, 0, -6, 743, 0 -ATT, 3.18, 0.54, -2.14, -2.98, 0.00, 63.27, 64.32 -CTUN, 495, 1.40, 1.63, 1.559200, 0, 0, -7, 745, 0 -ATT, 3.46, 1.56, -2.24, -2.39, 0.00, 64.48, 64.32 -CTUN, 503, 1.39, 1.63, 1.559200, 0, 0, -8, 757, 0 -ATT, 6.00, 2.32, -2.05, -2.08, 0.00, 65.91, 64.32 -CTUN, 503, 1.39, 1.71, 1.559200, 0, 1, -7, 754, 0 -ATT, 5.90, 3.93, -2.05, -1.98, 0.00, 67.38, 64.32 -CTUN, 503, 1.39, 1.77, 1.559200, 0, 2, -4, 742, 0 -ATT, 6.09, 5.64, -2.05, -1.93, 0.00, 68.74, 64.32 -CTUN, 503, 1.39, 1.73, 1.569200, 0, 3, -2, 729, 0 -ATT, 6.28, 5.97, -2.05, -1.83, 0.00, 70.00, 64.32 -CTUN, 503, 1.33, 1.80, 1.579200, 0, 3, -2, 741, 0 -ATT, 6.00, 5.64, -2.05, -1.94, 0.00, 70.80, 64.32 -CTUN, 503, 1.33, 1.79, 1.649200, 0, 3, 0, 759, 0 -ATT, 2.81, 5.78, -2.24, -2.17, 0.00, 71.20, 64.32 -DU32, 7, 166132 -CURR, 503, 240746, 1046, 2093, 5051, 177.979870 -CTUN, 503, 1.30, 1.71, 1.659200, 0, 3, 4, 725, 0 -ATT, 0.18, 5.35, -2.24, -2.53, 0.00, 71.15, 64.32 -CTUN, 503, 1.32, 1.76, 1.699200, 0, 2, 5, 734, 0 -ATT, 0.00, 4.09, -2.24, -2.81, 0.00, 70.85, 64.32 -CTUN, 503, 1.32, 1.69, 1.689200, 0, 1, 8, 730, 0 -ATT, 0.00, 3.19, -2.14, -2.92, 0.00, 70.33, 64.32 -CTUN, 503, 1.34, 1.77, 1.699200, 0, 1, 9, 724, 0 -ATT, 0.00, 2.62, -2.24, -2.50, 0.00, 69.63, 64.32 -CTUN, 503, 1.34, 1.73, 1.699200, 0, 0, 9, 705, 0 -ATT, 0.00, 2.15, -2.24, -1.86, 0.00, 68.76, 64.32 -CTUN, 502, 1.43, 1.67, 1.709200, 0, 0, 5, 700, 0 -ATT, 0.00, 1.70, -2.24, -1.69, 0.00, 67.71, 64.32 -CTUN, 499, 1.43, 1.69, 1.629200, 0, 0, 1, 684, 0 -ATT, 0.00, 1.09, -2.24, -1.62, 0.00, 66.78, 64.32 -CTUN, 495, 1.45, 1.69, 1.619200, 0, 0, -1, 708, 0 -ATT, 0.00, 0.46, -2.24, -1.33, 0.00, 65.83, 64.32 -CTUN, 490, 1.45, 1.79, 1.599200, 0, 0, -10, 712, 0 -ATT, 0.00, -0.03, -2.24, -0.80, 0.00, 64.97, 64.32 -CTUN, 488, 1.45, 1.64, 1.589200, 0, 0, -12, 725, 0 -ATT, 0.00, -0.14, -2.24, -0.30, 0.00, 64.19, 64.32 -DU32, 7, 166132 -CURR, 488, 247874, 1055, 2014, 5051, 183.449490 -CTUN, 486, 1.45, 1.76, 1.569200, 0, 0, -16, 738, 0 -ATT, 0.00, -0.07, -2.24, -0.33, 0.00, 63.70, 64.32 -MODE, STABILIZE, 700 -CTUN, 486, 1.45, 1.71, 0.000000, 0, 0, -15, 486, 0 -ATT, 0.00, -0.16, -2.24, -0.77, 0.00, 63.45, 64.32 -CTUN, 489, 1.42, 1.52, 0.000000, 0, 0, -26, 489, 0 -ATT, 0.00, -0.49, -2.14, -1.01, 0.00, 63.54, 64.32 -CTUN, 495, 1.42, 1.59, 0.000000, 0, 0, -61, 493, 0 -ATT, 0.00, -0.56, -2.05, -1.51, 0.00, 63.64, 64.32 -CTUN, 507, 1.39, 1.65, 0.000000, 0, 0, -96, 501, 0 -ATT, 0.00, -0.20, -2.42, -2.36, 0.00, 63.62, 64.32 -CTUN, 553, 1.39, 1.45, 0.000000, 0, 0, -139, 553, 0 -ATT, 0.00, 0.02, -2.24, -3.18, 0.00, 63.60, 64.32 -CTUN, 680, 1.25, 1.26, 0.000000, 0, 0, -166, 654, 0 -ATT, 0.00, 0.05, -2.52, -3.22, 0.00, 63.53, 64.32 -CTUN, 804, 1.25, 1.27, 0.000000, 0, 0, -185, 779, 0 -ATT, 0.00, -0.10, -2.33, -2.30, 0.00, 63.18, 64.32 -CTUN, 900, 0.97, 1.01, 0.000000, 0, 0, -192, 879, 0 -ATT, 0.00, -0.54, -2.14, -0.97, 0.00, 62.48, 64.32 -CTUN, 924, 0.97, 0.77, 0.000000, 0, 0, -176, 924, 0 -ATT, 0.00, -0.48, -2.52, -0.12, 0.00, 61.39, 64.32 -DU32, 7, 166140 -CURR, 985, 254361, 989, 3240, 5051, 188.248660 -CTUN, 1000, 0.97, 0.72, 0.000000, 0, 0, -148, 1000, 0 -ATT, 0.00, -0.54, -2.24, 1.57, 0.00, 60.12, 64.32 -CTUN, 1000, 0.97, 0.48, 0.000000, 0, 0, -104, 1000, 0 -ATT, 0.00, -0.51, -2.52, 2.43, 0.00, 59.27, 64.32 -CTUN, 999, 0.29, -1.73, 0.000000, 0, 0, -61, 1000, 0 -ATT, 0.00, -0.30, -2.33, 2.23, 0.00, 58.88, 64.32 -CTUN, 1000, 0.29, -3.65, 0.000000, 0, 0, 0, 1000, 0 -ATT, -6.63, 0.46, -2.52, 1.63, 0.00, 58.58, 64.32 -CTUN, 991, 0.21, -2.49, 0.000000, 0, 0, 41, 999, 0 -ATT, -8.14, -2.07, -4.76, 1.13, 0.00, 58.58, 64.32 -CTUN, 768, 0.21, -0.25, 0.000000, 0, 1, 83, 856, 0 -ATT, -10.13, -5.99, -8.12, 0.95, 0.00, 59.21, 64.32 -CTUN, 653, 0.21, 0.38, 0.000000, 0, 3, 101, 694, 0 -ATT, -12.60, -7.79, -9.14, -1.78, 0.00, 60.33, 64.32 -CTUN, 632, 0.22, 0.42, 0.000000, 0, 5, 96, 637, 0 -ATT, -13.64, -8.93, -10.92, -6.39, 0.00, 61.53, 64.32 -CTUN, 636, 0.22, 0.83, 0.000000, 0, 11, 78, 645, 0 -ATT, -14.87, -11.22, -10.73, -10.17, 0.00, 62.38, 64.32 -CTUN, 636, 0.40, 1.05, 0.000000, 0, 20, 53, 656, 0 -ATT, -10.70, -12.92, -8.02, -12.03, 0.00, 62.63, 64.32 -DU32, 7, 166140 -CURR, 634, 262848, 1066, 1595, 5051, 195.187640 -CTUN, 628, 0.40, 0.80, 0.000000, 0, 25, 32, 658, 0 -ATT, 0.00, -12.73, -2.05, -11.29, 0.00, 62.09, 64.32 -CTUN, 633, 0.56, 1.02, 0.000000, 0, 20, 11, 653, 0 -ATT, 0.00, -8.42, 0.00, -8.04, 0.00, 61.07, 64.32 -CTUN, 637, 0.56, 0.95, 0.000000, 0, 6, -7, 642, 0 -ATT, 0.00, -2.12, 2.05, -3.23, 0.00, 60.35, 64.32 -CTUN, 674, 0.62, 0.92, 0.000000, 0, 0, -25, 665, 0 -ATT, 2.62, 1.35, 2.52, 1.05, 0.00, 60.14, 64.32 -CTUN, 681, 0.60, 0.78, 0.000000, 0, 0, -43, 681, 0 -ATT, 6.18, 2.30, 2.52, 3.68, 0.00, 60.02, 64.32 -CTUN, 683, 0.60, 0.91, 0.000000, 0, 2, -55, 683, 0 -ATT, 6.93, 3.80, 2.33, 4.80, 0.00, 59.98, 64.32 -CTUN, 694, 0.57, 0.86, 0.000000, 0, 3, -67, 697, 0 -ATT, 6.09, 5.79, 0.93, 4.80, 0.00, 60.02, 64.32 -CTUN, 765, 0.57, 0.66, 0.000000, 0, 5, -77, 759, 0 -ATT, 4.87, 6.66, 0.00, 4.39, 0.00, 60.07, 64.32 -CTUN, 821, 0.45, 0.68, 0.000000, 0, 6, -79, 822, 0 -ATT, 4.87, 6.34, 0.00, 3.55, 0.00, 60.16, 64.32 -CTUN, 856, 0.45, 0.53, 0.000000, 0, 5, -69, 847, 0 -ATT, 4.40, 5.80, -2.24, 2.95, 0.00, 60.36, 64.32 -DU32, 7, 166140 -CURR, 857, 269908, 1008, 2652, 5028, 200.430210 -CTUN, 861, 0.32, 0.42, 0.000000, 0, 4, -50, 863, 0 -ATT, 2.53, 5.27, -2.24, 2.29, 0.00, 60.64, 64.32 -CTUN, 859, 0.32, 0.28, 0.000000, 0, 2, -28, 863, 0 -ATT, 1.87, 2.98, -2.24, 1.18, 0.00, 61.14, 64.32 -CTUN, 835, 0.20, 0.36, 0.000000, 0, 0, -4, 850, 0 -ATT, 0.00, 1.01, -3.45, -0.06, 0.00, 61.88, 64.32 -CTUN, 789, 0.21, 0.16, 0.000000, 0, 0, 21, 800, 0 -ATT, 0.00, -0.25, -6.16, -0.38, 0.00, 62.57, 64.32 -CTUN, 743, 0.20, 0.32, 0.000000, 0, 0, 36, 752, 0 -ATT, 0.00, -0.72, -8.86, -1.46, 0.00, 63.01, 64.32 -CTUN, 716, 0.21, 0.61, 0.000000, 0, 0, 42, 720, 0 -ATT, 0.00, -0.62, -8.86, -3.74, 0.00, 63.29, 64.32 -CTUN, 715, 0.21, 0.65, 0.000000, 0, 2, 43, 718, 0 -ATT, 0.00, 0.36, -6.81, -5.90, 0.00, 63.23, 64.32 -CTUN, 709, 0.28, 0.61, 0.000000, 0, 3, 37, 716, 0 -ATT, 0.00, 1.01, -2.05, -6.09, 0.00, 62.78, 64.32 -CTUN, 675, 0.28, 0.50, 0.000000, 0, 2, 28, 682, 0 -ATT, 0.00, 1.16, -2.05, -4.30, 0.00, 62.19, 64.32 -CTUN, 661, 0.35, 0.53, 0.000000, 0, 0, 14, 660, 0 -ATT, 0.00, 0.87, -2.52, -2.00, 0.00, 61.64, 64.32 -DU32, 7, 166140 -CURR, 665, 277560, 1066, 1618, 5051, 206.555770 -CTUN, 675, 0.35, 0.69, 0.000000, 0, 0, 0, 675, 0 -ATT, 0.00, 0.91, -3.73, -0.59, 0.00, 61.12, 64.32 -CTUN, 719, 0.40, 0.70, 0.000000, 0, 0, -14, 717, 0 -ATT, 0.00, 1.27, -4.38, -0.99, 0.00, 60.64, 64.32 -CTUN, 735, 0.39, 0.66, 0.000000, 0, 0, -21, 731, 0 -ATT, 0.00, 1.18, -6.53, -2.27, 0.00, 60.31, 64.32 -CTUN, 743, 0.39, 0.62, 0.000000, 0, 0, -26, 741, 0 -ATT, 0.00, 0.50, -6.81, -3.69, 0.00, 60.00, 64.32 -CTUN, 747, 0.38, 0.86, 0.000000, 0, 1, -28, 747, 0 -ATT, 0.00, 0.33, -7.56, -5.09, 0.00, 59.59, 64.32 -CTUN, 746, 0.38, 0.56, 0.000000, 0, 2, -23, 748, 0 -ATT, 0.00, 0.07, -7.56, -5.72, 0.00, 59.30, 64.32 -CTUN, 746, 0.32, 0.64, 0.000000, 0, 3, -20, 750, 0 -ATT, 0.00, -0.33, -7.46, -5.80, 0.00, 59.06, 64.32 -CTUN, 746, 0.32, 0.61, 0.000000, 0, 3, -15, 749, 0 -ATT, 0.00, -0.03, -5.41, -5.10, 0.00, 58.99, 64.32 -CTUN, 746, 0.28, 0.65, 0.000000, 0, 1, -10, 747, 0 -ATT, 0.00, 0.55, -2.42, -3.35, 0.00, 59.12, 64.32 -CTUN, 746, 0.28, 0.37, 0.000000, 0, 0, -4, 745, 0 -ATT, -0.56, 0.50, -2.33, -1.06, 0.00, 59.41, 64.32 -DU32, 7, 166140 -CURR, 746, 284901, 1046, 2086, 5051, 212.131620 -CTUN, 746, 0.25, 0.52, 0.000000, 0, 0, -2, 745, 0 -ATT, -2.27, 0.08, -2.24, 0.30, 0.00, 59.64, 64.32 -CTUN, 746, 0.25, 0.53, 0.000000, 0, 0, 0, 746, 0 -ATT, -3.88, -0.50, -1.77, 0.97, 0.00, 60.00, 64.32 -CTUN, 741, 0.23, 0.64, 0.000000, 0, 0, 4, 741, 0 -ATT, -5.21, -1.15, -1.68, 1.66, 0.00, 60.74, 64.32 -CTUN, 742, 0.23, 0.57, 0.000000, 0, 0, 7, 741, 0 -ATT, -6.25, -2.59, -1.40, 1.75, 0.00, 61.80, 64.32 -CTUN, 742, 0.23, 0.47, 0.000000, 0, 1, 6, 743, 0 -ATT, -6.63, -4.13, -1.40, 1.67, 0.00, 62.92, 64.32 -CTUN, 742, 0.23, 0.63, 0.000000, 0, 2, 8, 743, 0 -ATT, -6.72, -5.19, -1.96, 1.78, 0.00, 63.87, 64.32 -CTUN, 741, 0.23, 0.58, 0.000000, 0, 2, 9, 742, 0 -ATT, -6.72, -5.30, -2.52, 1.43, 0.00, 64.63, 64.32 -CTUN, 737, 0.24, 0.61, 0.000000, 0, 2, 12, 741, 0 -ATT, -2.27, -5.56, -2.24, 0.71, 0.00, 65.11, 64.32 -CTUN, 737, 0.24, 0.57, 0.000000, 0, 2, 10, 739, 0 -ATT, 0.00, -4.20, -2.42, 0.53, 0.00, 65.10, 64.32 -CTUN, 739, 0.25, 0.51, 0.000000, 0, 0, 6, 738, 0 -ATT, 0.00, -0.44, -2.42, 0.39, 0.00, 64.58, 64.32 -DU32, 7, 166140 -CURR, 739, 292325, 1034, 2020, 5051, 217.817120 -CTUN, 739, 0.25, 0.61, 0.000000, 0, 0, 6, 738, 0 -ATT, 0.00, 1.48, -2.24, 0.56, 0.00, 63.61, 64.32 -CTUN, 738, 0.26, 0.43, 0.000000, 0, 0, 6, 738, 0 -ATT, 0.00, 1.30, -2.24, 0.87, 0.00, 62.42, 64.32 -CTUN, 737, 0.25, 0.55, 0.000000, 0, 0, 7, 738, 0 -ATT, 0.00, 1.77, -2.24, 0.72, 0.00, 61.14, 64.32 -CTUN, 740, 0.25, 0.56, 0.000000, 0, 0, 6, 739, 0 -ATT, 0.00, 1.68, -2.52, 0.49, 0.00, 60.01, 64.32 -CTUN, 740, 0.25, 0.59, 0.000000, 0, 0, 5, 740, 0 -ATT, 0.00, 1.32, -2.24, -0.26, 0.00, 59.18, 64.32 -CTUN, 741, 0.26, 0.53, 0.000000, 0, 0, 5, 740, 0 -ATT, 0.00, 0.68, -2.24, -0.85, 0.00, 58.56, 64.32 -CTUN, 741, 0.26, 0.39, 0.000000, 0, 0, 6, 741, 0 -ATT, 0.00, -0.17, -4.76, -0.92, 0.00, 58.13, 64.32 -CTUN, 741, 0.27, 0.52, 0.000000, 0, 0, 9, 741, 0 -ATT, 0.00, -0.11, -6.44, -1.62, 0.00, 58.08, 64.32 -CTUN, 740, 0.26, 0.55, 0.000000, 0, 0, 7, 743, 0 -ATT, 0.00, 0.99, -6.53, -3.24, 0.00, 58.37, 64.32 -CTUN, 740, 0.27, 0.56, 0.000000, 0, 1, 7, 741, 0 -ATT, 0.00, 1.56, -6.81, -4.76, 0.00, 58.98, 64.32 -DU32, 7, 166140 -CURR, 740, 299722, 1051, 2061, 5028, 223.470660 -CTUN, 740, 0.27, 0.37, 0.000000, 0, 2, 9, 740, 0 -ATT, -0.37, 1.34, -7.18, -5.67, 0.00, 59.78, 64.32 -CTUN, 738, 0.27, 0.60, 0.000000, 0, 3, 8, 744, 0 -ATT, -0.56, 0.51, -6.62, -5.35, 0.00, 60.62, 64.32 -CTUN, 739, 0.27, 0.55, 0.000000, 0, 2, 8, 741, 0 -ATT, -0.75, -0.13, -5.69, -4.40, 0.00, 61.29, 64.32 -CTUN, 739, 0.28, 0.65, 0.000000, 0, 1, 8, 740, 0 -ATT, -3.22, -0.34, -3.17, -3.42, 0.00, 61.81, 64.32 -CTUN, 738, 0.28, 0.59, 0.000000, 0, 0, 4, 738, 0 -ATT, -5.87, -1.24, -2.70, -2.12, 0.00, 62.05, 64.32 -CTUN, 739, 0.28, 0.48, 0.000000, 0, 0, 3, 739, 0 -ATT, -6.63, -2.61, -2.70, -0.48, 0.00, 62.00, 64.32 -CTUN, 738, 0.28, 0.51, 0.000000, 0, 1, 5, 739, 0 -ATT, -6.72, -5.26, -3.08, 1.07, 0.00, 61.78, 64.32 -CTUN, 738, 0.28, 0.48, 0.000000, 0, 3, 3, 742, 0 -PM, 0, 0, 0, 0, 1000, 10468, 0, 0 -ATT, -6.91, -6.71, -4.10, 1.04, 0.00, 61.51, 64.32 -CTUN, 738, 0.28, 0.56, 0.000000, 0, 4, 1, 742, 0 -ATT, -6.72, -6.04, -4.29, 0.28, 0.00, 61.29, 64.32 -CTUN, 737, 0.28, 0.60, 0.000000, 0, 3, 1, 741, 0 -ATT, -3.22, -5.48, -3.17, -0.73, 0.00, 61.08, 64.32 -DU32, 7, 166140 -CURR, 737, 307130, 1054, 2037, 5028, 229.168010 -CTUN, 738, 0.28, 0.44, 0.000000, 0, 2, 0, 740, 0 -ATT, 0.00, -4.92, -2.52, -1.50, 0.00, 61.16, 64.32 -CTUN, 738, 0.28, 0.49, 0.000000, 0, 1, 0, 738, 0 -ATT, 0.00, -3.01, -2.52, -1.47, 0.00, 61.41, 64.32 -CTUN, 737, 0.28, 0.45, 0.000000, 0, 0, -1, 738, 0 -ATT, 0.00, -1.03, -2.42, -1.02, 0.00, 61.77, 64.32 -CTUN, 737, 0.28, 0.37, 0.000000, 0, 0, 0, 737, 0 -ATT, 0.00, 0.38, -2.24, -0.66, 0.00, 62.25, 64.32 -CTUN, 738, 0.26, 0.44, 0.000000, 0, 0, 0, 737, 0 -ATT, 0.00, 0.00, -2.33, -0.08, 0.00, 62.85, 64.32 -CTUN, 737, 0.26, 0.57, 0.000000, 0, 0, -1, 738, 0 -ATT, 0.00, -0.40, -2.24, 0.40, 0.00, 63.53, 64.32 -CTUN, 738, 0.25, 0.58, 0.000000, 0, 0, -1, 738, 0 -ATT, 0.09, -0.07, -2.52, 0.19, 0.00, 64.25, 64.32 -CTUN, 738, 0.25, 0.55, 0.000000, 0, 0, 1, 738, 0 -ATT, 2.15, -0.60, -2.05, -0.31, 0.00, 64.98, 64.32 -CTUN, 737, 0.24, 0.48, 0.000000, 0, 0, 2, 738, 0 -ATT, 3.18, -0.39, -2.24, -0.98, 0.00, 65.72, 64.32 -CTUN, 738, 0.24, 0.42, 0.000000, 0, 0, 2, 738, 0 -ATT, 3.09, 1.19, -2.24, -1.05, 0.00, 66.27, 64.32 -DU32, 7, 166140 -CURR, 738, 314512, 1042, 1993, 5028, 234.735640 -CTUN, 738, 0.23, 0.52, 0.000000, 0, 0, 5, 738, 0 -ATT, 3.18, 2.77, -2.24, -0.29, 0.00, 66.71, 64.32 -CTUN, 738, 0.23, 0.40, 0.000000, 0, 0, 6, 739, 0 -ATT, 3.28, 3.24, -2.24, 0.32, 0.00, 67.07, 64.32 -CTUN, 738, 0.23, 0.51, 0.000000, 0, 0, 6, 738, 0 -ATT, 3.18, 3.15, -2.24, 0.17, 0.00, 67.40, 64.32 -CTUN, 738, 0.23, 0.52, 0.000000, 0, 0, 8, 738, 0 -ATT, 1.78, 2.59, -2.52, -0.48, 0.00, 67.75, 64.32 -CTUN, 739, 0.23, 0.49, 0.000000, 0, 0, 9, 741, 0 -ATT, 0.00, 1.70, -2.61, -0.54, 0.00, 68.12, 64.32 -CTUN, 740, 0.23, 0.49, 0.000000, 0, 0, 11, 741, 0 -ATT, 0.00, 0.61, -3.26, -1.08, 0.00, 68.63, 64.32 -CTUN, 741, 0.23, 0.41, 0.000000, 0, 0, 12, 741, 0 -ATT, 0.00, -1.24, -3.26, -1.80, 0.00, 69.04, 64.32 -CTUN, 742, 0.24, 0.49, 0.000000, 0, 0, 11, 742, 0 -ATT, 0.00, -2.62, -3.17, -2.10, -0.28, 69.20, 64.22 -CTUN, 743, 0.24, 0.51, 0.000000, 0, 1, 11, 744, 0 -ATT, 0.00, -2.41, -3.26, -1.89, -2.26, 69.11, 63.54 -CTUN, 743, 0.26, 0.67, 0.000000, 0, 0, 13, 744, 0 -ATT, 0.00, -1.83, -3.26, -1.46, -3.20, 68.62, 62.19 -DU32, 7, 166140 -CURR, 743, 321912, 1045, 2077, 5051, 240.392430 -CTUN, 744, 0.26, 0.47, 0.000000, 0, 0, 11, 744, 0 -ATT, 0.00, -1.42, -3.26, -1.58, -3.58, 67.64, 60.63 -CTUN, 744, 0.28, 0.58, 0.000000, 0, 0, 9, 744, 0 -ATT, 0.28, -1.39, -3.26, -2.02, -4.15, 66.14, 58.91 -CTUN, 744, 0.28, 0.59, 0.000000, 0, 0, 10, 744, 0 -ATT, 1.03, -1.25, -2.98, -2.40, -4.24, 64.03, 57.01 -CTUN, 742, 0.29, 0.65, 0.000000, 0, 0, 11, 742, 0 -ATT, 1.68, 0.05, -2.70, -2.37, -4.15, 61.49, 55.09 -CTUN, 741, 0.29, 0.66, 0.000000, 0, 0, 11, 741, 0 -ATT, 1.78, 1.62, -2.52, -1.84, -4.15, 58.79, 53.19 -CTUN, 742, 0.31, 0.63, 0.000000, 0, 0, 11, 742, 0 -ATT, 2.90, 2.37, -2.24, -0.75, -4.15, 56.20, 51.28 -CTUN, 741, 0.31, 0.56, 0.000000, 0, 0, 9, 742, 0 -ATT, 2.90, 3.28, -2.52, -0.11, -4.24, 53.64, 49.37 -CTUN, 742, 0.31, 0.55, 0.000000, 0, 1, 10, 742, 0 -ATT, 2.53, 4.27, -2.52, 0.11, -3.77, 51.03, 47.50 -CTUN, 741, 0.31, 0.70, 0.000000, 0, 1, 6, 742, 0 -ATT, 1.78, 4.60, -2.42, 0.00, -3.77, 48.40, 45.75 -CTUN, 742, 0.32, 0.48, 0.000000, 0, 1, 7, 742, 0 -ATT, 1.78, 3.30, -3.54, -0.20, -3.77, 45.95, 44.04 -DU32, 7, 166140 -CURR, 741, 329336, 1049, 2063, 5051, 246.147740 -CTUN, 741, 0.32, 0.56, 0.000000, 0, 0, 7, 741, 0 -ATT, 0.00, 1.94, -4.76, -1.03, -3.39, 43.98, 42.38 -CTUN, 742, 0.34, 0.58, 0.000000, 0, 0, 6, 741, 0 -ATT, 0.00, 0.91, -6.25, -2.11, -2.26, 42.43, 40.97 -CTUN, 742, 0.34, 0.64, 0.000000, 0, 0, 4, 741, 0 -ATT, 0.00, 0.18, -6.90, -3.22, -1.98, 41.23, 40.03 -CTUN, 743, 0.36, 0.68, 0.000000, 0, 1, 5, 743, 0 -ATT, 0.00, -0.08, -7.93, -4.36, -1.79, 40.28, 39.14 -CTUN, 741, 0.35, 0.68, 0.000000, 0, 2, 5, 744, 0 -ATT, 0.00, -0.10, -8.12, -5.56, -1.79, 39.33, 38.27 -CTUN, 743, 0.36, 0.62, 0.000000, 0, 3, 2, 746, 0 -ATT, 0.00, -0.78, -3.54, -6.41, -1.60, 38.26, 37.44 -CTUN, 742, 0.36, 0.56, 0.000000, 0, 3, 2, 745, 0 -ATT, 0.00, -1.19, -2.24, -5.50, -1.41, 37.05, 36.66 -CTUN, 742, 0.36, 0.62, 0.000000, 0, 2, 2, 746, 0 -ATT, 0.00, -1.03, -2.24, -2.87, -0.84, 35.91, 36.12 -CTUN, 741, 0.36, 0.77, 0.000000, 0, 0, 0, 741, 0 -ATT, 0.00, -0.98, -2.24, -0.45, -0.18, 34.80, 35.91 -CTUN, 742, 0.36, 0.79, 0.000000, 0, 0, -2, 742, 0 -ATT, 0.00, -1.50, -2.24, 0.79, 0.00, 34.00, 35.83 -DU32, 7, 166140 -CURR, 742, 336762, 1047, 2018, 5028, 251.847320 -CTUN, 741, 0.36, 0.66, 0.000000, 0, 0, -2, 741, 0 -ATT, 0.00, -1.35, -2.61, 1.43, 0.00, 33.59, 35.83 -CTUN, 743, 0.36, 0.77, 0.000000, 0, 0, -4, 745, 0 -ATT, 0.00, -1.02, -4.20, 1.48, 0.00, 33.68, 35.83 -CTUN, 743, 0.35, 0.73, 0.000000, 0, 0, -8, 743, 0 -ATT, 0.00, -1.49, -4.76, 1.05, 0.00, 34.14, 35.83 -CTUN, 742, 0.35, 0.60, 0.000000, 0, 0, -10, 742, 0 -ATT, 0.00, -1.78, -5.32, 0.26, 0.00, 34.76, 35.83 -CTUN, 741, 0.32, 0.60, 0.000000, 0, 0, -10, 742, 0 -ATT, 0.00, -1.66, -6.72, -1.13, 0.00, 35.55, 35.83 -CTUN, 741, 0.32, 0.60, 0.000000, 0, 0, -11, 741, 0 -ATT, 0.00, -1.00, -10.73, -2.41, 0.00, 36.34, 35.83 -CTUN, 742, 0.30, 0.62, 0.000000, 0, 0, -11, 741, 0 -ATT, 0.00, 0.09, -10.64, -3.36, 0.00, 37.15, 35.83 -CTUN, 746, 0.30, 0.56, 0.000000, 0, 1, -10, 743, 0 -ATT, 0.00, 0.17, -9.05, -4.95, 0.00, 37.81, 35.83 -CTUN, 741, 0.27, 0.66, 0.000000, 0, 2, -10, 744, 0 -ATT, 0.00, 0.38, -7.84, -5.92, 0.00, 38.21, 35.83 -CTUN, 741, 0.27, 0.50, 0.000000, 0, 3, -12, 744, 0 -ATT, 0.00, 0.59, -8.12, -4.95, 0.00, 38.46, 35.83 -DU32, 7, 166140 -CURR, 742, 344187, 1049, 2063, 5051, 257.498930 -CTUN, 742, 0.24, 0.49, 0.000000, 0, 1, -8, 742, 0 -ATT, 0.00, 0.02, -8.02, -3.43, 0.00, 38.75, 35.83 -CTUN, 741, 0.24, 0.46, 0.000000, 0, 0, -3, 742, 0 -ATT, 0.00, -0.19, -7.84, -2.53, 0.00, 39.02, 35.83 -CTUN, 741, 0.23, 0.48, 0.000000, 0, 0, -3, 742, 0 -ATT, 0.00, 0.40, -7.74, -2.41, 0.00, 39.29, 35.83 -CTUN, 743, 0.23, 0.56, 0.000000, 0, 0, -4, 743, 0 -ATT, 0.00, 0.02, -7.84, -2.32, 0.00, 39.58, 35.83 -CTUN, 741, 0.22, 0.53, 0.000000, 0, 0, -2, 741, 0 -ATT, 0.00, -0.53, -7.37, -2.47, 0.00, 39.73, 35.83 -CTUN, 741, 0.22, 0.39, 0.000000, 0, 0, 1, 742, 0 -ATT, 0.00, 0.09, -6.81, -3.12, 0.00, 39.74, 35.83 -CTUN, 743, 0.21, 0.50, 0.000000, 0, 1, 4, 744, 0 -ATT, -0.56, 0.98, -4.57, -3.49, 0.00, 39.45, 35.83 -CTUN, 743, 0.21, 0.36, 0.000000, 0, 1, 9, 743, 0 -ATT, 0.00, -0.11, -2.52, -3.22, 0.00, 38.88, 35.83 -CTUN, 743, 0.21, 0.43, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, -1.34, -2.42, -1.61, 0.00, 37.97, 35.83 -CTUN, 742, 0.21, 0.46, 0.000000, 0, 0, 9, 743, 0 -ATT, 0.00, -0.13, -2.05, 0.18, 0.00, 36.93, 35.83 -DU32, 7, 166140 -CURR, 743, 351610, 1041, 2014, 5028, 263.169430 -CTUN, 743, 0.21, 0.65, 0.000000, 0, 0, 10, 743, 0 -ATT, 0.00, 0.84, 0.00, 1.07, 0.00, 35.96, 35.83 -CTUN, 743, 0.24, 0.56, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, 0.76, 0.00, 1.78, 0.00, 35.15, 35.83 -CTUN, 743, 0.24, 0.59, 0.000000, 0, 0, 14, 743, 0 -ATT, 0.00, 0.39, 0.00, 2.62, 0.00, 34.47, 35.83 -CTUN, 743, 0.26, 0.65, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, 0.60, 0.00, 2.20, 0.00, 34.13, 35.83 -CTUN, 743, 0.26, 0.61, 0.000000, 0, 0, 12, 742, 0 -ATT, 0.00, 0.45, -2.52, 1.29, 0.00, 33.95, 35.83 -CTUN, 743, 0.28, 0.54, 0.000000, 0, 0, 11, 743, 0 -ATT, -0.18, 0.10, -2.70, 0.30, 0.00, 33.92, 35.83 -CTUN, 743, 0.28, 0.56, 0.000000, 0, 0, 10, 743, 0 -ATT, -0.66, -0.34, -2.61, -0.38, 0.00, 34.07, 35.83 -CTUN, 743, 0.30, 0.65, 0.000000, 0, 0, 7, 742, 0 -ATT, -0.56, -0.51, -2.70, -0.48, 0.00, 34.21, 35.83 -CTUN, 742, 0.30, 0.61, 0.000000, 0, 0, 4, 742, 0 -ATT, -0.75, -0.36, -2.70, -0.43, 0.00, 34.35, 35.83 -CTUN, 743, 0.32, 0.64, 0.000000, 0, 0, 2, 743, 0 -ATT, -0.94, 0.19, -2.70, 0.20, 0.00, 34.36, 35.83 -DU32, 7, 166140 -CURR, 742, 359035, 1037, 2016, 5051, 268.811770 -CTUN, 743, 0.32, 0.75, 0.000000, 0, 0, -2, 743, 0 -ATT, -1.23, -0.15, -2.89, 0.58, 0.00, 34.45, 35.83 -CTUN, 742, 0.33, 0.81, 0.000000, 0, 0, -6, 743, 0 -ATT, -2.36, -0.69, -2.33, -0.06, 0.00, 34.84, 35.83 -CTUN, 742, 0.32, 0.71, 0.000000, 0, 0, -6, 742, 0 -ATT, -2.65, -0.59, -4.38, -0.99, 0.00, 35.45, 35.83 -CTUN, 742, 0.32, 0.59, 0.000000, 0, 0, -6, 742, 0 -ATT, -3.03, -1.52, -4.76, -1.97, 0.00, 36.19, 35.83 -CTUN, 742, 0.32, 0.73, 0.000000, 0, 0, -7, 741, 0 -ATT, -3.88, -2.44, -3.82, -2.99, 0.00, 36.84, 35.83 -CTUN, 741, 0.32, 0.84, 0.000000, 0, 1, -10, 743, 0 -ATT, -4.16, -3.09, -4.20, -3.47, 0.00, 37.19, 35.83 -CTUN, 742, 0.31, 0.73, 0.000000, 0, 2, -8, 744, 0 -ATT, -4.45, -4.32, -4.38, -3.29, 0.00, 37.49, 35.83 -CTUN, 742, 0.31, 0.45, 0.000000, 0, 2, -8, 744, 0 -ATT, -3.78, -4.83, -3.73, -3.45, 0.00, 37.93, 35.83 -CTUN, 741, 0.29, 0.53, 0.000000, 0, 3, -5, 745, 0 -ATT, -0.85, -3.86, -2.61, -3.09, 0.00, 38.31, 35.83 -CTUN, 743, 0.29, 0.62, 0.000000, 0, 1, -5, 744, 0 -ATT, 0.00, -2.70, -2.89, -2.22, 0.00, 38.69, 35.83 -DU32, 7, 166140 -CURR, 743, 366458, 1038, 2048, 5028, 274.440160 -CTUN, 743, 0.27, 0.65, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.00, -1.92, -2.61, -1.50, 0.00, 39.11, 35.83 -CTUN, 742, 0.27, 0.62, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -1.11, -2.70, -1.23, 0.00, 39.44, 35.83 -CTUN, 743, 0.26, 0.72, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.33, -2.80, -1.17, 0.00, 39.75, 35.83 -CTUN, 743, 0.26, 0.40, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.43, -2.61, -0.69, 0.00, 40.00, 35.83 -CTUN, 743, 0.26, 0.64, 0.000000, 0, 0, 1, 743, 0 -ATT, 0.00, -1.02, -2.70, -0.02, 0.00, 40.17, 35.83 -CTUN, 743, 0.26, 0.47, 0.000000, 0, 0, 1, 743, 0 -ATT, 0.00, -0.94, -2.70, 0.51, 0.00, 40.11, 35.83 -CTUN, 743, 0.26, 0.74, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.49, -2.70, 0.40, 0.00, 39.90, 35.83 -CTUN, 743, 0.27, 0.45, 0.000000, 0, 0, 0, 742, 0 -ATT, 0.00, -0.71, -2.61, -0.25, 0.00, 39.60, 35.83 -CTUN, 743, 0.27, 0.58, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.28, -2.70, -0.81, 0.00, 39.17, 35.83 -CTUN, 743, 0.27, 0.54, 0.000000, 0, 0, 0, 742, 0 -ATT, 0.00, -0.21, -2.70, -0.84, 0.00, 38.52, 35.83 -DU32, 7, 166140 -CURR, 742, 373887, 1041, 2050, 5051, 280.111720 -CTUN, 742, 0.27, 0.60, 0.000000, 0, 0, 2, 743, 0 -ATT, 0.00, -0.99, -2.61, -0.56, 0.00, 37.69, 35.83 -CTUN, 743, 0.28, 0.47, 0.000000, 0, 0, 1, 742, 0 -ATT, 0.00, -1.60, -2.70, -0.44, 0.00, 36.88, 35.83 -CTUN, 743, 0.28, 0.60, 0.000000, 0, 0, 1, 743, 0 -ATT, 0.09, -1.06, -2.61, -0.25, 0.00, 35.99, 35.83 -CTUN, 743, 0.28, 0.46, 0.000000, 0, 0, 1, 743, 0 -ATT, 0.46, -0.32, -2.70, 0.08, 0.00, 34.87, 35.83 -CTUN, 744, 0.28, 0.53, 0.000000, 0, 0, 0, 744, 0 -ATT, 0.46, 0.07, -2.70, -0.23, 0.00, 33.60, 35.83 -CTUN, 743, 0.28, 0.66, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.84, 0.30, -2.70, -0.80, 0.00, 32.29, 35.83 -CTUN, 742, 0.28, 0.48, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.93, 1.26, -3.08, -0.19, 0.00, 31.07, 35.83 -CTUN, 743, 0.29, 0.55, 0.000000, 0, 0, 1, 742, 0 -PM, 0, 0, 0, 0, 1000, 10484, 0, 0 -ATT, 1.03, 2.00, -3.45, 0.27, 0.00, 30.13, 35.83 -CTUN, 744, 0.28, 0.51, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.84, 2.57, -4.38, 0.01, 0.00, 29.45, 35.83 -CTUN, 742, 0.29, 0.53, 0.000000, 0, 0, 0, 742, 0 -ATT, 0.84, 2.34, -4.29, -1.14, 0.00, 29.04, 35.83 -DU32, 7, 166140 -CURR, 741, 381316, 1039, 2060, 5051, 285.776730 -CTUN, 743, 0.28, 0.60, 0.000000, 0, 0, 1, 742, 0 -ATT, 0.84, 1.64, -4.48, -2.11, 0.00, 28.93, 35.83 -CTUN, 742, 0.28, 0.55, 0.000000, 0, 0, 2, 743, 0 -ATT, 0.56, 1.03, -4.57, -2.73, 0.00, 29.18, 35.83 -CTUN, 742, 0.28, 0.50, 0.000000, 0, 0, 4, 741, 0 -ATT, 0.46, 0.92, -4.38, -2.65, 0.00, 29.80, 35.83 -CTUN, 742, 0.29, 0.57, 0.000000, 0, 0, 1, 742, 0 -ATT, 0.37, 0.75, -4.38, -2.60, 0.00, 30.60, 35.83 -CTUN, 741, 0.29, 0.63, 0.000000, 0, 0, 0, 742, 0 -ATT, 0.46, 0.17, -4.38, -2.41, 0.00, 31.55, 35.83 -CTUN, 742, 0.30, 0.53, 0.000000, 0, 0, -1, 741, 0 -ATT, 0.46, -0.61, -4.38, -1.91, 0.00, 32.58, 35.83 -CTUN, 742, 0.29, 0.60, 0.000000, 0, 0, -3, 741, 0 -ATT, 0.46, -0.94, -4.38, -1.23, 0.00, 33.76, 35.83 -CTUN, 742, 0.29, 0.50, 0.000000, 0, 0, -9, 743, 0 -ATT, 0.46, -1.41, -4.38, -0.79, 0.00, 35.05, 35.83 -CTUN, 743, 0.29, 0.56, 0.000000, 0, 0, -8, 743, 0 -ATT, 0.46, -1.60, -4.38, -1.11, 0.00, 36.46, 35.83 -CTUN, 743, 0.29, 0.61, 0.000000, 0, 0, -8, 743, 0 -ATT, 0.46, -1.69, -4.38, -1.78, 0.00, 37.86, 35.83 -DU32, 7, 166140 -CURR, 742, 388741, 1019, 2014, 5028, 291.425510 -CTUN, 742, 0.28, 0.57, 0.000000, 0, 0, -8, 742, 0 -ATT, 0.46, -1.17, -4.38, -1.80, 0.00, 39.20, 35.83 -CTUN, 743, 0.28, 0.56, 0.000000, 0, 0, -6, 742, 0 -ATT, 0.46, -0.82, -4.29, -2.09, 0.00, 40.59, 35.83 -CTUN, 743, 0.26, 0.45, 0.000000, 0, 0, -9, 742, 0 -ATT, 0.46, -0.15, -4.38, -2.20, 0.00, 41.81, 35.83 -CTUN, 743, 0.26, 0.56, 0.000000, 0, 0, -4, 742, 0 -ATT, 0.37, 0.90, -4.38, -1.39, 0.00, 42.55, 35.83 -CTUN, 743, 0.24, 0.44, 0.000000, 0, 0, -5, 743, 0 -ATT, 0.65, 0.44, -4.38, -0.99, 0.00, 43.12, 35.83 -CTUN, 743, 0.24, 0.47, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.84, -0.49, -3.82, -0.85, 0.00, 43.50, 35.83 -CTUN, 741, 0.24, 0.51, 0.000000, 0, 0, -2, 743, 0 -ATT, 1.40, -1.19, -3.45, -1.27, 0.00, 43.73, 35.83 -CTUN, 742, 0.24, 0.37, 0.000000, 0, 0, -2, 742, 0 -ATT, 1.59, -1.38, -4.01, -1.74, 0.00, 43.92, 35.83 -CTUN, 741, 0.24, 0.58, 0.000000, 0, 0, -2, 741, 0 -ATT, 1.59, -0.40, -4.38, -1.49, 0.00, 44.13, 35.83 -CTUN, 742, 0.24, 0.46, 0.000000, 0, 0, -4, 741, 0 -ATT, 1.40, -0.11, -4.48, -1.75, 0.00, 44.37, 35.83 -DU32, 7, 166140 -CURR, 741, 396164, 1039, 2042, 5028, 297.111020 -CTUN, 741, 0.23, 0.60, 0.000000, 0, 0, -4, 741, 0 -ATT, 1.40, -0.15, -4.85, -2.08, 0.00, 44.51, 35.83 -CTUN, 742, 0.23, 0.49, 0.000000, 0, 0, -2, 741, 0 -ATT, 1.40, -0.23, -4.85, -1.99, 0.00, 44.51, 35.83 -CTUN, 742, 0.23, 0.43, 0.000000, 0, 0, -2, 743, 0 -ATT, 2.25, -0.76, -4.85, -2.24, 0.00, 44.40, 35.83 -CTUN, 742, 0.23, 0.51, 0.000000, 0, 0, -1, 742, 0 -ATT, 2.62, -0.11, -4.85, -2.46, 0.00, 44.08, 35.83 -CTUN, 741, 0.22, 0.49, 0.000000, 0, 0, 0, 741, 0 -ATT, 4.50, 0.28, -4.76, -3.02, 0.00, 43.71, 35.83 -CTUN, 742, 0.23, 0.43, 0.000000, 0, 0, 0, 741, 0 -ATT, 6.37, 1.26, -4.76, -3.29, 0.00, 43.33, 35.83 -CTUN, 741, 0.22, 0.41, 0.000000, 0, 1, 0, 742, 0 -ATT, 7.68, 3.02, -4.85, -3.15, 0.00, 42.97, 35.83 -CTUN, 742, 0.23, 0.47, 0.000000, 0, 1, 0, 742, 0 -ATT, 9.18, 4.61, -4.10, -1.98, 0.00, 42.88, 35.83 -CTUN, 741, 0.22, 0.57, 0.000000, 0, 2, 0, 743, 0 -ATT, 9.09, 6.54, -2.14, -1.11, 0.00, 42.93, 35.83 -CTUN, 742, 0.22, 0.67, 0.000000, 0, 5, -2, 747, 0 -ATT, 7.59, 8.02, -2.24, -0.21, 0.00, 42.96, 35.83 -DU32, 7, 166140 -CURR, 742, 403587, 1040, 2048, 5051, 302.763280 -CTUN, 742, 0.22, 0.53, 0.000000, 0, 6, -4, 748, 0 -ATT, 1.96, 7.72, -2.24, 0.06, 0.00, 42.84, 35.83 -CTUN, 742, 0.22, 0.49, 0.000000, 0, 4, -7, 746, 0 -ATT, 0.00, 5.08, -4.76, -0.45, 0.00, 42.61, 35.83 -CTUN, 743, 0.22, 0.67, 0.000000, 0, 0, -7, 743, 0 -ATT, 0.00, 1.14, -6.06, -1.88, 0.00, 42.32, 35.83 -CTUN, 743, 0.22, 0.56, 0.000000, 0, 0, -7, 743, 0 -ATT, 0.00, -0.47, -7.74, -3.50, 0.00, 42.05, 35.83 -CTUN, 743, 0.22, 0.57, 0.000000, 0, 1, -4, 744, 0 -ATT, 0.00, 0.30, -8.21, -4.01, 0.00, 41.68, 35.83 -CTUN, 743, 0.22, 0.46, 0.000000, 0, 1, -3, 744, 0 -ATT, 0.00, 0.29, -8.21, -4.35, 0.00, 41.16, 35.83 -CTUN, 743, 0.22, 0.56, 0.000000, 0, 1, -2, 744, 0 -ATT, 0.00, -0.07, -7.56, -4.79, 0.00, 40.58, 35.83 -CTUN, 742, 0.22, 0.48, 0.000000, 0, 2, 0, 744, 0 -ATT, -0.37, -0.19, -6.62, -4.63, 0.00, 39.99, 35.83 -CTUN, 741, 0.21, 0.50, 0.000000, 0, 1, 1, 744, 0 -ATT, -1.32, -0.43, -5.50, -4.16, 0.00, 39.45, 35.83 -CTUN, 743, 0.21, 0.59, 0.000000, 0, 1, 3, 742, 0 -ATT, -1.98, -0.59, -4.76, -2.88, 0.00, 38.92, 35.83 -DU32, 7, 166140 -CURR, 742, 411032, 1044, 2028, 5051, 308.419560 -CTUN, 743, 0.21, 0.46, 0.000000, 0, 0, 5, 742, 0 -ATT, -2.55, -0.94, -4.57, -1.57, 0.00, 38.45, 35.83 -CTUN, 743, 0.22, 0.65, 0.000000, 0, 0, 8, 743, 0 -ATT, -2.84, -1.52, -4.57, -0.57, 0.00, 37.91, 35.83 -CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 5, 742, 0 -ATT, -2.84, -1.78, -4.57, -0.74, 0.00, 37.42, 35.83 -CTUN, 742, 0.23, 0.62, 0.000000, 0, 0, 7, 743, 0 -ATT, -2.84, -2.47, -4.57, -1.43, 0.00, 36.87, 35.83 -CTUN, 742, 0.23, 0.48, 0.000000, 0, 0, 9, 742, 0 -ATT, -2.93, -3.10, -4.66, -1.45, 0.00, 36.33, 35.83 -CTUN, 743, 0.24, 0.50, 0.000000, 0, 1, 10, 743, 0 -ATT, -2.08, -2.94, -4.38, -1.07, 0.00, 35.93, 35.83 -CTUN, 743, 0.24, 0.67, 0.000000, 0, 0, 10, 743, 0 -ATT, -0.75, -2.24, -4.38, -0.58, 0.00, 35.65, 35.83 -CTUN, 743, 0.27, 0.73, 0.000000, 0, 0, 10, 743, 0 -ATT, -0.75, -1.07, -4.38, -0.79, 0.00, 35.61, 35.83 -CTUN, 742, 0.27, 0.70, 0.000000, 0, 0, 8, 742, 0 -ATT, 0.00, -0.75, -3.73, -1.75, 0.00, 35.72, 35.83 -CTUN, 742, 0.28, 0.71, 0.000000, 0, 0, 5, 743, 0 -DU32, 7, 166140 -CURR, 743, 418460, 1022, 2010, 5051, 314.043850 -ATT, 0.00, -0.27, -2.80, -2.32, 0.00, 35.88, 35.83 -CTUN, 742, 0.28, 0.78, 0.000000, 0, 0, 7, 743, 0 -ATT, -0.85, 0.71, -2.70, -2.14, 0.00, 36.05, 35.83 -CTUN, 742, 0.30, 0.56, 0.000000, 0, 0, 7, 742, 0 -ATT, -0.66, 1.22, -2.42, -1.83, 0.00, 36.02, 35.83 -CTUN, 742, 0.30, 0.88, 0.000000, 0, 0, 4, 742, 0 -ATT, -1.80, 1.40, -1.77, -1.54, 0.00, 35.87, 35.83 -CTUN, 742, 0.31, 0.63, 0.000000, 0, 0, 1, 742, 0 -ATT, -3.88, 1.42, 0.00, -0.94, 0.00, 35.63, 35.83 -CTUN, 741, 0.31, 0.63, 0.000000, 0, 0, 0, 741, 0 -ATT, -5.68, 0.30, 0.00, -0.03, 0.00, 35.41, 35.83 -CTUN, 741, 0.31, 0.76, 0.000000, 0, 0, -4, 742, 0 -ATT, -6.06, -1.66, 0.00, 0.84, 0.00, 35.25, 35.83 -CTUN, 743, 0.31, 0.67, 0.000000, 0, 0, -7, 743, 0 -ATT, -6.63, -3.96, 0.00, 1.16, 0.00, 35.32, 35.83 -CTUN, 741, 0.31, 0.60, 0.000000, 0, 2, -9, 743, 0 -ATT, -6.63, -4.62, 0.00, 1.26, 0.00, 35.53, 35.83 -CTUN, 743, 0.30, 0.68, 0.000000, 0, 2, -9, 745, 0 -ATT, -6.25, -4.62, -0.56, 1.29, 0.00, 35.84, 35.83 -CTUN, 742, 0.30, 0.85, 0.000000, 0, 2, -10, 744, 0 -DU32, 7, 166140 -CURR, 743, 425886, 1046, 2031, 5028, 319.663240 -ATT, -5.87, -4.33, -1.02, 1.49, 0.00, 36.20, 35.83 -CTUN, 743, 0.29, 0.57, 0.000000, 0, 1, -10, 743, 0 -ATT, -5.68, -4.13, -1.02, 1.23, 0.00, 36.59, 35.83 -CTUN, 743, 0.29, 0.60, 0.000000, 0, 1, -8, 744, 0 -ATT, -5.30, -4.37, -1.12, 0.90, 0.00, 36.85, 35.83 -CTUN, 743, 0.26, 0.45, 0.000000, 0, 1, -10, 743, 0 -ATT, -3.88, -4.34, -2.05, 0.69, 0.00, 36.97, 35.83 -CTUN, 742, 0.26, 0.55, 0.000000, 0, 1, -10, 743, 0 -ATT, -2.27, -3.98, -2.24, -0.03, 0.00, 37.15, 35.83 -CTUN, 742, 0.24, 0.57, 0.000000, 0, 1, -8, 743, 0 -ATT, -0.66, -3.67, -2.52, -0.58, 0.00, 37.38, 35.83 -CTUN, 743, 0.24, 0.54, 0.000000, 0, 1, -6, 744, 0 -ATT, 0.00, -2.35, -4.10, -0.64, 0.00, 37.72, 35.83 -CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.00, -0.32, -3.92, -0.92, 0.00, 38.01, 35.83 -CTUN, 742, 0.22, 0.55, 0.000000, 0, 0, 1, 743, 0 -ATT, 0.00, 0.90, -3.26, -1.15, 0.00, 38.20, 35.83 -CTUN, 743, 0.20, 0.61, 0.000000, 0, 0, 7, 743, 0 -ATT, 0.09, 0.81, -2.52, -0.98, 0.00, 38.23, 35.83 -CTUN, 743, 0.20, 0.49, 0.000000, 0, 0, 8, 743, 0 -DU32, 7, 166140 -CURR, 742, 433320, 1046, 1996, 5051, 325.250460 -ATT, 0.00, 0.50, -2.52, -1.18, 0.00, 38.26, 35.83 -CTUN, 742, 0.20, 0.58, 0.000000, 0, 0, 10, 742, 0 -ATT, 0.00, -0.06, -2.52, -1.35, 0.00, 38.37, 35.83 -CTUN, 743, 0.20, 0.47, 0.000000, 0, 0, 11, 744, 0 -ATT, 0.18, -0.13, -2.52, -1.24, 0.00, 38.43, 35.83 -CTUN, 743, 0.20, 0.47, 0.000000, 0, 0, 14, 742, 0 -ATT, 1.12, 0.59, -2.52, -0.94, 0.00, 38.32, 35.83 -CTUN, 742, 0.20, 0.48, 0.000000, 0, 0, 16, 742, 0 -ATT, 1.40, 0.54, -2.42, -0.44, 0.00, 38.04, 35.83 -CTUN, 743, 0.20, 0.64, 0.000000, 0, 0, 19, 743, 0 -ATT, 1.59, 0.49, -2.42, -0.34, 0.00, 37.64, 35.83 -CTUN, 743, 0.20, 0.57, 0.000000, 0, 0, 21, 743, 0 -ATT, 2.43, 1.22, -2.42, -0.39, 0.00, 37.13, 35.83 -CTUN, 742, 0.20, 0.69, 0.000000, 0, 0, 19, 743, 0 -ATT, 2.71, 1.81, -2.52, -0.68, 0.00, 36.66, 35.83 -CTUN, 741, 0.23, 0.57, 0.000000, 0, 0, 21, 741, 0 -ATT, 3.00, 2.69, -2.52, -1.08, 0.00, 36.30, 35.83 -CTUN, 742, 0.23, 0.62, 0.000000, 0, 0, 20, 742, 0 -ATT, 2.62, 3.00, -2.52, -1.38, 0.00, 36.09, 35.83 -CTUN, 743, 0.25, 0.74, 0.000000, 0, 0, 16, 743, 0 -DU32, 7, 166140 -CURR, 741, 440747, 1042, 2029, 5051, 330.838960 -ATT, 1.59, 2.40, -2.42, -1.66, 0.00, 36.13, 35.83 -CTUN, 743, 0.25, 0.61, 0.000000, 0, 0, 14, 743, 0 -ATT, 0.00, 2.06, -2.42, -1.51, 0.00, 36.19, 35.83 -CTUN, 741, 0.27, 0.66, 0.000000, 0, 0, 10, 743, 0 -ATT, 0.00, 1.97, -2.52, -1.11, 0.00, 36.16, 35.83 -CTUN, 742, 0.27, 0.65, 0.000000, 0, 0, 6, 742, 0 -ATT, 0.00, 1.09, -2.52, -1.15, 0.00, 36.13, 35.83 -CTUN, 743, 0.29, 0.74, 0.000000, 0, 0, 4, 743, 0 -ATT, 0.00, 0.62, -2.52, -1.32, 0.00, 36.07, 35.83 -CTUN, 743, 0.28, 0.63, 0.000000, 0, 0, 2, 742, 0 -ATT, 0.00, -0.04, -2.42, -1.22, 0.00, 35.97, 35.83 -CTUN, 743, 0.28, 0.68, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.53, -2.52, -0.73, 0.00, 35.90, 35.83 -CTUN, 742, 0.28, 0.53, 0.000000, 0, 0, 0, 742, 0 -ATT, 0.00, -0.59, -2.42, -0.40, 0.00, 35.77, 35.83 -CTUN, 743, 0.28, 0.74, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, -0.96, -2.42, -0.43, 0.00, 35.72, 35.83 -CTUN, 742, 0.28, 0.68, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.00, -0.89, -2.52, -0.59, 0.00, 35.71, 35.83 -CTUN, 742, 0.28, 0.55, 0.000000, 0, 0, -2, 743, 0 -DU32, 7, 166140 -CURR, 743, 448172, 1037, 1999, 5051, 336.392610 -ATT, 0.00, -0.70, -2.42, -0.32, 0.00, 35.67, 35.83 -CTUN, 743, 0.26, 0.65, 0.000000, 0, 0, -4, 743, 0 -ATT, 0.00, -1.37, -2.52, -0.14, 0.00, 35.51, 35.83 -CTUN, 743, 0.26, 0.60, 0.000000, 0, 0, -7, 742, 0 -ATT, 0.00, -1.74, -2.52, -0.39, 0.00, 35.42, 35.83 -CTUN, 743, 0.25, 0.63, 0.000000, 0, 0, -6, 743, 0 -ATT, 0.00, -1.66, -2.52, -0.70, 0.00, 35.32, 35.83 -CTUN, 743, 0.25, 0.62, 0.000000, 0, 0, -6, 743, 0 -ATT, 0.00, -1.71, -2.52, -0.77, 0.00, 35.22, 35.83 -CTUN, 742, 0.23, 0.46, 0.000000, 0, 0, -3, 742, 0 -ATT, 0.00, -1.67, -2.52, -0.43, 0.00, 35.00, 35.83 -CTUN, 742, 0.23, 0.56, 0.000000, 0, 0, -4, 742, 0 -ATT, 0.00, -1.86, -2.42, -0.38, 0.00, 34.69, 35.83 -CTUN, 743, 0.22, 0.69, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.00, -1.83, -2.42, -0.69, 0.00, 34.42, 35.83 -CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 2, 743, 0 -PM, 0, 0, 0, 0, 1000, 10484, 0, 0 -ATT, 0.00, -1.57, -2.52, -1.09, 0.00, 34.18, 35.83 -CTUN, 742, 0.20, 0.73, 0.000000, 0, 0, 3, 742, 0 -ATT, 0.00, -0.88, -2.52, -1.19, 0.00, 33.99, 35.83 -CTUN, 743, 0.20, 0.52, 0.000000, 0, 0, 7, 742, 0 -DU32, 7, 166140 -CURR, 743, 455601, 1032, 2004, 5051, 341.938870 -ATT, 0.00, 0.01, -2.52, -0.81, 0.00, 33.89, 35.83 -CTUN, 742, 0.20, 0.65, 0.000000, 0, 0, 13, 743, 0 -ATT, 0.00, 0.20, -2.52, 0.01, 0.00, 33.97, 35.83 -CTUN, 742, 0.20, 0.58, 0.000000, 0, 0, 13, 742, 0 -ATT, 0.00, 0.14, -2.52, 0.39, 0.00, 34.06, 35.83 -CTUN, 743, 0.20, 0.60, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, 0.73, -2.52, 0.58, 0.00, 34.10, 35.83 -CTUN, 743, 0.20, 0.64, 0.000000, 0, 0, 16, 744, 0 -ATT, 0.00, 0.95, -2.52, 0.34, 0.00, 34.31, 35.83 -CTUN, 743, 0.20, 0.71, 0.000000, 0, 0, 19, 743, 0 -ATT, 0.00, 0.55, -2.52, -0.83, 0.00, 34.42, 35.83 -CTUN, 743, 0.22, 0.62, 0.000000, 0, 0, 17, 743, 0 -ATT, 0.00, 0.67, -2.42, -2.16, 0.00, 34.17, 35.83 -CTUN, 743, 0.22, 0.63, 0.000000, 0, 0, 16, 743, 0 -ATT, 0.00, 0.51, -2.42, -2.06, 0.00, 33.78, 35.83 -CTUN, 743, 0.24, 0.64, 0.000000, 0, 0, 17, 742, 0 -ATT, 0.00, -0.35, -2.52, -1.04, 0.00, 33.26, 35.83 -CTUN, 744, 0.24, 0.61, 0.000000, 0, 0, 13, 743, 0 -ATT, 0.00, 0.47, -2.42, 0.03, 0.00, 32.51, 35.83 -CTUN, 743, 0.27, 0.70, 0.000000, 0, 0, 10, 743, 0 -DU32, 7, 166140 -CURR, 743, 463030, 1023, 2000, 5051, 347.506040 -ATT, 0.00, 2.40, -2.42, 0.69, 0.00, 31.97, 35.83 -CTUN, 743, 0.27, 0.70, 0.000000, 0, 0, 5, 743, 0 -ATT, 0.00, 2.36, -4.01, 1.23, 0.00, 31.63, 35.83 -CTUN, 742, 0.28, 0.66, 0.000000, 0, 0, 2, 742, 0 -ATT, 0.00, 1.76, -6.34, 1.06, 0.00, 31.52, 35.83 -CTUN, 743, 0.28, 0.76, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, 1.20, -8.02, -0.41, 0.00, 31.68, 35.83 -CTUN, 743, 0.28, 0.72, 0.000000, 0, 0, -5, 743, 0 -ATT, 0.00, 0.84, -10.82, -3.05, 0.00, 31.85, 35.83 -CTUN, 743, 0.27, 0.73, 0.000000, 0, 1, -7, 744, 0 -ATT, 0.00, 0.65, -10.92, -5.85, 0.00, 32.12, 35.83 -CTUN, 743, 0.27, 0.70, 0.000000, 0, 3, -8, 745, 0 -ATT, 0.00, 0.82, -10.92, -7.78, 0.00, 32.38, 35.83 -CTUN, 743, 0.26, 0.64, 0.000000, 0, 6, -12, 749, 0 -ATT, 0.00, 0.42, -10.92, -8.08, 0.00, 32.76, 35.83 -CTUN, 743, 0.26, 0.57, 0.000000, 0, 5, -10, 748, 0 -ATT, 0.00, 0.25, -10.64, -6.52, 0.00, 33.19, 35.83 -CTUN, 743, 0.24, 0.65, 0.000000, 0, 3, -12, 746, 0 -ATT, 0.00, 0.49, -8.30, -4.93, 0.00, 33.64, 35.83 -CTUN, 743, 0.24, 0.45, 0.000000, 0, 2, -9, 744, 0 -DU32, 7, 166140 -CURR, 743, 470477, 1037, 2004, 5028, 353.057680 -ATT, 0.00, -0.35, -7.84, -3.71, 0.00, 34.08, 35.83 -CTUN, 743, 0.21, 0.29, 0.000000, 0, 1, -8, 744, 0 -ATT, 0.00, -0.65, -8.02, -2.69, 0.00, 34.62, 35.83 -CTUN, 743, 0.21, 0.50, 0.000000, 0, 0, -6, 743, 0 -ATT, 0.00, 0.30, -8.12, -2.10, 0.00, 35.21, 35.83 -CTUN, 742, 0.20, 0.60, 0.000000, 0, 0, -4, 742, 0 -ATT, 0.00, 0.56, -8.12, -2.70, 0.00, 35.73, 35.83 -CTUN, 743, 0.20, 0.58, 0.000000, 0, 0, -2, 742, 0 -ATT, 0.00, -0.40, -7.00, -4.03, 0.00, 36.26, 35.83 -CTUN, 742, 0.20, 0.51, 0.000000, 0, 1, 1, 743, 0 -ATT, 0.00, -1.38, -6.16, -4.70, 0.00, 36.75, 35.83 -CTUN, 743, 0.20, 0.65, 0.000000, 0, 2, 5, 745, 0 -ATT, 0.46, -1.50, -4.66, -3.93, 0.00, 37.07, 35.83 -CTUN, 743, 0.20, 0.46, 0.000000, 0, 1, 10, 744, 0 -ATT, 0.84, -1.05, -2.89, -1.73, 0.00, 37.35, 35.83 -CTUN, 743, 0.20, 0.23, 0.000000, 0, 0, 14, 743, 0 -ATT, 3.46, -0.68, -2.24, 0.80, 0.00, 37.45, 35.83 -CTUN, 742, 0.20, 0.69, 0.000000, 0, 0, 15, 742, 0 -ATT, 6.09, 0.76, -2.24, 2.09, 0.00, 37.50, 35.83 -CTUN, 743, 0.20, 0.68, 0.000000, 0, 0, 16, 743, 0 -DU32, 7, 166140 -CURR, 743, 477908, 1049, 2003, 5028, 358.618740 -ATT, 7.03, 2.86, -2.24, 1.69, 0.00, 37.42, 35.83 -CTUN, 742, 0.20, 0.61, 0.000000, 0, 1, 12, 743, 0 -ATT, 7.31, 5.20, -2.24, 1.26, 0.00, 37.41, 35.83 -CTUN, 742, 0.20, 0.63, 0.000000, 0, 3, 12, 745, 0 -ATT, 7.87, 6.98, -2.24, 1.43, 0.00, 37.65, 35.83 -CTUN, 744, 0.20, 0.61, 0.000000, 0, 5, 10, 748, 0 -ATT, 7.59, 8.03, -2.24, 1.36, 0.00, 38.07, 35.83 -CTUN, 742, 0.22, 0.66, 0.000000, 0, 6, 6, 748, 0 -ATT, 6.28, 7.70, -2.24, 1.36, 0.00, 38.51, 35.83 -CTUN, 743, 0.22, 0.62, 0.000000, 0, 5, 3, 750, 0 -ATT, 0.84, 6.81, -3.54, 1.23, 0.00, 38.83, 35.83 -CTUN, 743, 0.23, 0.66, 0.000000, 0, 4, 0, 748, 0 -ATT, 0.00, 4.64, -4.57, 0.42, 0.00, 38.89, 35.83 -CTUN, 743, 0.23, 0.65, 0.000000, 0, 1, -2, 743, 0 -ATT, 0.00, 1.15, -6.34, -1.43, 0.00, 38.85, 35.83 -CTUN, 742, 0.23, 0.50, 0.000000, 0, 0, -2, 742, 0 -ATT, 0.00, -1.04, -7.00, -2.87, 0.00, 38.70, 35.83 -CTUN, 743, 0.23, 0.59, 0.000000, 0, 1, -2, 744, 0 -ATT, 0.00, -1.49, -7.46, -3.31, 0.00, 38.47, 35.83 -CTUN, 743, 0.24, 0.70, 0.000000, 0, 1, -4, 743, 0 -DU32, 7, 166140 -CURR, 742, 485362, 1036, 1998, 5028, 364.193660 -ATT, 0.00, -1.28, -6.81, -3.20, 0.00, 38.06, 35.83 -CTUN, 743, 0.23, 0.65, 0.000000, 0, 0, -2, 743, 0 -ATT, 0.00, -0.39, -6.81, -2.47, 0.00, 37.54, 35.83 -CTUN, 743, 0.23, 0.52, 0.000000, 0, 0, -3, 743, 0 -ATT, 0.00, 0.07, -6.53, -1.75, 0.00, 37.14, 35.83 -CTUN, 743, 0.23, 0.59, 0.000000, 0, 0, -1, 743, 0 -ATT, 0.00, 0.40, -6.06, -1.31, 0.00, 36.84, 35.83 -CTUN, 743, 0.23, 0.65, 0.000000, 0, 0, 0, 743, 0 -ATT, -0.75, -0.06, -5.88, -1.38, 0.00, 36.58, 35.83 -CTUN, 743, 0.22, 0.47, 0.000000, 0, 0, 1, 743, 0 -ATT, -3.31, -0.30, -5.60, -0.96, 0.00, 36.37, 35.83 -CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 3, 743, 0 -ATT, -3.78, -0.66, -5.50, -0.42, 0.00, 36.12, 35.83 -CTUN, 743, 0.21, 0.42, 0.000000, 0, 0, 3, 742, 0 -ATT, -3.88, -1.80, -5.60, -0.87, 0.00, 35.83, 35.83 -CTUN, 742, 0.22, 0.63, 0.000000, 0, 0, 4, 742, 0 -ATT, -4.07, -2.73, -4.01, -2.03, 0.00, 35.50, 35.83 -CTUN, 743, 0.21, 0.63, 0.000000, 0, 1, 4, 744, 0 -ATT, -4.83, -2.96, -4.76, -2.16, 0.00, 35.03, 35.83 -CTUN, 742, 0.21, 0.60, 0.000000, 0, 1, 6, 744, 0 -DU32, 7, 166140 -CURR, 743, 492792, 1031, 2009, 5028, 369.755000 -ATT, -4.83, -3.24, -4.76, -1.64, 0.00, 34.46, 35.83 -CTUN, 743, 0.21, 0.55, 0.000000, 0, 1, 7, 744, 0 -ATT, -0.28, -3.91, -4.85, -1.37, 0.00, 34.00, 35.83 -CTUN, 742, 0.22, 0.69, 0.000000, 0, 1, 9, 744, 0 -ATT, 0.00, -3.09, -2.98, -1.60, 0.00, 33.57, 35.83 -CTUN, 742, 0.22, 0.49, 0.000000, 0, 0, 9, 742, 0 -ATT, 0.00, -0.84, -2.80, -1.78, 0.00, 33.13, 35.83 -CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, 10, 743, 0 -ATT, 0.00, 1.25, -2.33, -1.51, 0.00, 32.64, 35.83 -CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, 1.65, -2.42, -0.93, 0.00, 32.26, 35.83 -CTUN, 743, 0.22, 0.66, 0.000000, 0, 0, 12, 743, 0 -ATT, 0.00, 0.52, -2.42, -0.45, 0.00, 31.91, 35.83 -CTUN, 743, 0.22, 0.69, 0.000000, 0, 0, 13, 743, 0 -ATT, 0.00, -0.04, -2.52, -0.28, 0.00, 31.59, 35.83 -CTUN, 743, 0.24, 0.58, 0.000000, 0, 0, 14, 742, 0 -ATT, 0.00, 0.14, -2.52, -0.39, 0.00, 31.51, 35.83 -CTUN, 743, 0.24, 0.70, 0.000000, 0, 0, 11, 743, 0 -ATT, 0.00, 0.68, -2.52, -0.47, 0.00, 31.78, 35.83 -CTUN, 742, 0.26, 0.62, 0.000000, 0, 0, 9, 743, 0 -DU32, 7, 166140 -CURR, 744, 500222, 1041, 2010, 5051, 375.335140 -ATT, 0.00, 0.95, -2.52, -0.59, 0.00, 32.16, 35.83 -CTUN, 743, 0.26, 0.63, 0.000000, 0, 0, 8, 743, 0 -ATT, 0.00, 0.01, -2.42, -0.70, 0.00, 32.62, 35.83 -CTUN, 742, 0.27, 0.83, 0.000000, 0, 0, 4, 743, 0 -ATT, 0.00, -0.24, -2.52, -0.74, 0.00, 33.04, 35.83 -CTUN, 743, 0.27, 0.84, 0.000000, 0, 0, 2, 742, 0 -ATT, 0.00, 0.40, -2.52, -0.20, 0.00, 33.58, 35.83 -CTUN, 743, 0.27, 0.79, 0.000000, 0, 0, 3, 743, 0 -ATT, 0.00, 0.77, -2.42, 0.20, 0.00, 34.13, 35.83 -CTUN, 743, 0.27, 0.81, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, 1.22, -2.52, 0.50, 0.00, 34.66, 35.83 -CTUN, 743, 0.27, 0.62, 0.000000, 0, 0, -1, 743, 0 -ATT, 0.00, 1.17, -2.42, 0.53, 0.00, 35.02, 35.83 -CTUN, 742, 0.26, 0.66, 0.000000, 0, 0, -1, 742, 0 -ATT, 0.00, 0.84, -2.52, 0.40, 0.00, 35.18, 35.83 -CTUN, 743, 0.26, 0.68, 0.000000, 0, 0, 0, 743, 0 -ATT, 0.00, 1.08, -2.52, 0.26, 0.00, 35.31, 35.83 -CTUN, 743, 0.25, 0.73, 0.000000, 0, 0, 3, 743, 0 -MODE, ALT_HOLD, 742 -ATT, 0.00, 0.77, -2.52, 0.35, 0.00, 35.48, 35.83 -CTUN, 743, 0.25, 0.70, 0.775600, 0, 0, 1, 743, 89 -ATT, 0.00, 0.06, -2.42, 0.40, 0.00, 35.67, 35.83 -DU32, 7, 166132 -CURR, 743, 507650, 1036, 2029, 5028, 380.935730 -CTUN, 743, 0.23, 0.79, 0.874400, 0, 0, 4, 764, 89 -ATT, 0.00, -0.15, -2.52, 0.36, 0.00, 35.95, 35.83 -CTUN, 743, 0.24, 0.73, 0.965400, 0, 0, 7, 807, 89 -ATT, 0.00, -0.31, -2.52, 0.24, 0.00, 36.33, 35.83 -CTUN, 743, 0.24, 0.66, 1.064200, 0, 0, 16, 816, 89 -ATT, 0.00, -0.81, -2.42, 0.35, 0.00, 36.73, 35.83 -CTUN, 743, 0.24, 0.64, 1.145400, 0, 0, 24, 826, 89 -ATT, 0.00, -0.67, -2.42, 0.55, 0.00, 37.15, 35.83 -CTUN, 742, 0.24, 0.64, 1.264400, 0, 0, 37, 830, 89 -ATT, 0.00, -0.31, -2.52, 0.81, 0.00, 37.37, 35.83 -CTUN, 743, 0.27, 0.65, 1.365000, 0, 0, 45, 835, 89 -ATT, 0.00, -0.22, -2.52, 1.04, 0.00, 37.36, 35.83 -CTUN, 743, 0.27, 0.79, 1.463800, 0, 0, 52, 841, 89 -ATT, 0.00, 0.11, -2.52, 0.92, 0.00, 37.12, 35.83 -CTUN, 743, 0.33, 0.80, 1.584800, 0, 0, 59, 839, 88 -ATT, 0.00, 0.57, -2.52, 0.79, 0.00, 36.54, 35.83 -CTUN, 743, 0.33, 0.97, 1.673800, 0, 0, 66, 820, 89 -ATT, 0.00, 0.41, -2.52, 1.04, 0.00, 35.52, 35.83 -CTUN, 743, 0.42, 0.93, 1.804800, 0, 0, 74, 838, 88 -MODE, STABILIZE, 742 -ATT, 0.00, 0.24, -2.52, 0.86, 0.00, 34.22, 35.83 -DU32, 7, 166140 -CURR, 744, 515857, 1018, 2397, 5028, 387.614870 -CTUN, 743, 0.42, 1.08, 0.000000, 0, 0, 77, 743, 0 -ATT, 0.00, 0.31, -2.52, 0.11, 0.00, 32.88, 35.83 -CTUN, 743, 0.55, 1.22, 0.000000, 0, 0, 72, 743, 0 -ATT, 0.00, 0.35, -2.42, -0.97, 0.00, 31.49, 35.83 -CTUN, 744, 0.55, 1.19, 0.000000, 0, 0, 67, 744, 0 -ATT, 0.00, 0.72, -3.73, -1.54, 0.00, 30.13, 35.83 -CTUN, 743, 0.68, 1.22, 0.000000, 0, 0, 60, 743, 0 -ATT, 0.00, 1.53, -6.34, -1.77, 0.00, 28.90, 35.83 -CTUN, 743, 0.68, 1.25, 0.000000, 0, 0, 52, 743, 0 -ATT, 0.00, 1.50, -8.40, -2.65, 0.00, 27.97, 35.83 -CTUN, 742, 0.80, 1.26, 0.000000, 0, 1, 48, 743, 0 -ATT, 0.00, 1.19, -11.01, -4.79, 0.00, 27.41, 35.83 -CTUN, 743, 0.80, 1.26, 0.000000, 0, 3, 40, 745, 0 -ATT, 0.00, 1.18, -12.23, -7.72, 0.00, 27.10, 35.83 -CTUN, 743, 0.90, 1.35, 0.000000, 0, 7, 34, 750, 0 -ATT, 0.00, 1.43, -12.60, -9.93, 0.00, 26.94, 35.83 -CTUN, 743, 0.90, 1.40, 0.000000, 0, 10, 28, 753, 0 -ATT, 0.00, 1.99, -12.60, -10.90, 0.00, 27.06, 35.83 -CTUN, 744, 0.97, 1.37, 0.000000, 0, 11, 24, 755, 0 -ATT, 1.03, 2.45, -10.64, -10.94, 0.00, 27.51, 35.83 -DU32, 7, 166140 -CURR, 743, 523318, 1028, 2078, 5051, 393.222560 -CTUN, 742, 0.97, 1.55, 0.000000, 0, 11, 20, 754, 0 -ATT, 2.81, 2.17, -4.01, -10.22, 0.00, 28.13, 35.83 -CTUN, 743, 1.02, 1.55, 0.000000, 0, 9, 17, 752, 0 -ATT, 2.71, 3.04, -1.58, -7.71, 0.00, 28.92, 35.83 -CTUN, 743, 1.02, 1.52, 0.000000, 0, 4, 15, 747, 0 -ATT, 0.46, 4.00, -0.37, -3.41, 0.00, 30.00, 35.83 -CTUN, 744, 1.06, 1.58, 0.000000, 0, 2, 8, 746, 0 -ATT, 0.00, 2.70, 0.00, 0.50, 0.00, 31.21, 35.83 -CTUN, 744, 1.06, 1.57, 0.000000, 0, 0, 6, 744, 0 -ATT, 0.09, 0.85, 0.00, 2.67, 0.00, 32.42, 35.83 -CTUN, 744, 1.08, 1.67, 0.000000, 0, 0, 3, 744, 0 -ATT, 0.00, 0.80, 0.00, 3.78, 0.00, 33.67, 35.83 -CTUN, 743, 1.08, 1.76, 0.000000, 0, 1, -2, 744, 0 -ATT, 0.28, 0.87, 0.00, 3.83, 0.00, 34.97, 35.83 -CTUN, 744, 1.08, 1.65, 0.000000, 0, 1, -7, 745, 0 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -ATT, 1.59, 0.51, 0.00, 3.24, 0.00, 36.18, 35.83 -CTUN, 743, 1.08, 1.57, 0.000000, 0, 0, -11, 743, 0 -ATT, 0.84, 1.04, 0.00, 3.16, 0.00, 37.08, 35.83 -CTUN, 745, 1.08, 1.50, 0.000000, 0, 1, -17, 745, 0 -ATT, 0.84, 1.54, 0.00, 3.33, 0.00, 37.82, 35.83 -DU32, 7, 166140 -CURR, 743, 530782, 1031, 1989, 5028, 398.800230 -CTUN, 744, 1.07, 1.73, 0.000000, 0, 1, -22, 745, 0 -ATT, 0.46, 0.51, 0.00, 3.21, 0.00, 38.43, 35.83 -CTUN, 745, 1.07, 1.67, 0.000000, 0, 0, -26, 745, 0 -ATT, 0.65, -0.87, 0.00, 3.04, 0.00, 38.94, 35.83 -CTUN, 744, 1.02, 1.58, 0.000000, 0, 0, -31, 744, 0 -ATT, 0.65, -1.04, 0.00, 2.58, 0.00, 39.41, 35.83 -CTUN, 744, 1.02, 1.48, 0.000000, 0, 0, -32, 744, 0 -ATT, 0.84, -0.99, -0.37, 2.12, 0.00, 39.92, 35.83 -CTUN, 743, 0.96, 1.57, 0.000000, 0, 0, -36, 744, 0 -ATT, 0.46, -0.20, -1.21, 1.70, 0.00, 40.55, 35.83 -CTUN, 744, 0.96, 1.38, 0.000000, 0, 0, -41, 744, 0 -ATT, 0.09, 0.87, -1.30, 1.11, 0.00, 41.11, 35.83 -CTUN, 743, 0.90, 1.37, 0.000000, 0, 0, -44, 743, 0 -ATT, 0.00, 1.35, -2.05, 0.32, 0.00, 41.36, 35.83 -CTUN, 743, 0.90, 1.53, 0.000000, 0, 0, -45, 743, 0 -ATT, 0.00, 0.88, -2.05, -0.24, 0.00, 41.22, 35.83 -CTUN, 744, 0.80, 1.52, 0.000000, 0, 0, -49, 743, 0 -ATT, 0.00, 0.80, -2.52, -0.57, 0.00, 40.78, 35.83 -CTUN, 743, 0.80, 1.31, 0.000000, 0, 0, -50, 743, 0 -ATT, 0.00, 0.83, -6.81, -0.53, 0.00, 39.98, 35.83 -DU32, 7, 166140 -CURR, 742, 538215, 1041, 2013, 5051, 404.352230 -CTUN, 741, 0.70, 1.31, 0.000000, 0, 0, -55, 742, 0 -ATT, 0.00, 0.52, -8.30, -0.99, 0.00, 38.94, 35.83 -CTUN, 743, 0.70, 1.30, 0.000000, 0, 0, -61, 743, 0 -ATT, 0.00, 0.42, -10.82, -2.29, 0.00, 37.92, 35.83 -CTUN, 742, 0.59, 1.22, 0.000000, 0, 0, -66, 742, 0 -ATT, 0.28, 0.58, -11.76, -4.05, 0.00, 37.03, 35.83 -CTUN, 742, 0.59, 1.11, 0.000000, 0, 2, -70, 744, 0 -ATT, 0.46, 0.62, -11.76, -5.21, 0.00, 36.44, 35.83 -CTUN, 741, 0.46, 1.14, 0.000000, 0, 2, -69, 743, 0 -ATT, 1.78, 1.05, -10.92, -4.92, 0.00, 36.09, 35.83 -CTUN, 741, 0.46, 0.93, 0.000000, 0, 2, -70, 745, 0 -ATT, 2.90, 1.49, -9.14, -4.48, 0.00, 35.65, 35.83 -CTUN, 741, 0.32, 0.67, 0.000000, 0, 2, -68, 743, 0 -ATT, 2.81, 1.15, -7.84, -5.19, 0.00, 35.32, 35.83 -CTUN, 741, 0.32, 0.45, 0.000000, 0, 2, -58, 744, 0 -ATT, 2.43, 0.87, -6.62, -4.87, 0.00, 35.24, 35.83 -CTUN, 741, 0.20, -1.47, 0.000000, 0, 1, -43, 742, 0 -ATT, 1.59, 0.45, -6.53, -3.49, 0.00, 35.46, 35.83 -CTUN, 741, 0.27, -3.39, 0.000000, 0, 0, -24, 742, 0 -ATT, 1.40, -0.83, -6.81, 1.20, 0.00, 35.96, 35.83 -DU32, 7, 166140 -CURR, 742, 545643, 1031, 1993, 5051, 409.884770 -CTUN, 742, 0.21, -5.11, 0.000000, 0, 0, 15, 742, 0 -ATT, 0.84, 1.67, -6.25, 2.58, 0.00, 36.24, 35.83 -CTUN, 742, 0.21, -4.21, 0.000000, 0, 0, 27, 743, 0 -ATT, 0.65, 0.76, -5.32, -0.02, 0.00, 36.75, 35.83 -CTUN, 742, 0.21, -2.88, 0.000000, 0, 0, 34, 742, 0 -ATT, 0.37, 0.11, -5.22, -1.34, 0.00, 37.28, 35.83 -CTUN, 743, 0.21, -1.12, 0.000000, 0, 0, 37, 743, 0 -ATT, 0.00, 0.25, -5.88, -1.76, 0.00, 37.53, 35.83 -CTUN, 750, 0.20, -0.11, 0.000000, 0, 0, 38, 750, 0 -ATT, 0.00, 0.37, -4.76, -1.75, 0.00, 37.75, 35.83 -CTUN, 750, 0.21, 0.67, 0.000000, 0, 0, 38, 750, 0 -ATT, 0.00, -0.35, -2.52, -1.64, 0.00, 37.83, 35.83 -CTUN, 750, 0.21, 0.75, 0.000000, 0, 0, 36, 750, 0 -ATT, 0.00, -0.30, -2.52, -1.31, 0.00, 37.66, 35.83 -CTUN, 750, 0.23, 0.80, 0.000000, 0, 0, 33, 750, 0 -ATT, 0.93, 0.07, -2.61, -0.59, 0.00, 37.43, 35.83 -CTUN, 751, 0.23, 0.92, 0.000000, 0, 0, 30, 750, 0 -ATT, 2.81, 0.18, -2.24, -0.07, 0.00, 37.09, 35.83 -CTUN, 751, 0.32, 0.86, 0.000000, 0, 0, 27, 751, 0 -ATT, 3.09, 1.21, -2.24, 0.03, 0.00, 36.63, 35.83 -DU32, 7, 166140 -CURR, 750, 553114, 1036, 2033, 5051, 415.498600 -CTUN, 751, 0.32, 0.98, 0.000000, 0, 0, 22, 751, 0 -ATT, 5.62, 2.42, -2.24, 0.05, 0.00, 36.08, 35.83 -CTUN, 750, 0.40, 0.98, 0.000000, 0, 0, 16, 750, 0 -ATT, 6.93, 3.44, -2.24, 0.27, 0.00, 35.59, 35.83 -CTUN, 750, 0.40, 1.01, 0.000000, 0, 1, 12, 751, 0 -ATT, 6.93, 4.91, -2.14, 0.50, 0.00, 35.11, 35.83 -CTUN, 750, 0.47, 1.07, 0.000000, 0, 2, 12, 752, 0 -ATT, 5.71, 5.79, -2.24, 0.92, 0.00, 34.72, 35.83 -CTUN, 751, 0.47, 1.17, 0.000000, 0, 3, 10, 754, 0 -ATT, 1.03, 5.48, -2.42, 1.27, 0.00, 34.36, 35.83 -CTUN, 750, 0.50, 1.15, 0.000000, 0, 2, 4, 752, 0 -ATT, 0.00, 3.24, -2.24, 1.16, 0.00, 33.97, 35.83 -CTUN, 752, 0.50, 1.12, 0.000000, 0, 0, 2, 752, 0 -ATT, 0.00, -0.04, -3.92, 0.60, 0.00, 33.49, 35.83 -CTUN, 751, 0.52, 1.20, 0.000000, 0, 0, 0, 750, 0 -ATT, 0.00, -1.21, -5.04, 0.06, 0.00, 32.87, 35.83 -CTUN, 750, 0.52, 1.15, 0.000000, 0, 0, -4, 750, 0 -ATT, -0.75, -0.49, -6.90, -0.57, 0.00, 31.95, 35.83 -CTUN, 751, 0.53, 0.89, 0.000000, 0, 0, -6, 751, 0 -ATT, -3.97, -0.23, -7.09, -1.65, 0.00, 30.92, 35.83 -DU32, 7, 166140 -CURR, 750, 560627, 1029, 2038, 5028, 421.153990 -CTUN, 751, 0.52, 1.16, 0.000000, 0, 0, -9, 751, 0 -ATT, -6.06, -1.70, -5.88, -2.74, 0.00, 30.09, 35.83 -CTUN, 751, 0.52, 1.11, 0.000000, 0, 1, -12, 751, 0 -ATT, -5.96, -3.51, -5.88, -3.22, 0.00, 29.35, 35.83 -CTUN, 750, 0.51, 0.96, 0.000000, 0, 2, -14, 752, 0 -ATT, -5.49, -4.79, -5.41, -3.37, 0.00, 28.63, 35.83 -CTUN, 751, 0.51, 1.03, 0.000000, 0, 3, -17, 753, 0 -ATT, -3.50, -5.20, -5.60, -3.29, 0.00, 27.99, 35.83 -CTUN, 750, 0.49, 0.88, 0.000000, 0, 3, -21, 753, 0 -ATT, -0.66, -4.72, -5.69, -3.02, 0.00, 27.42, 35.83 -CTUN, 750, 0.49, 1.01, 0.000000, 0, 2, -22, 752, 0 -ATT, 0.00, -2.60, -6.06, -2.83, 0.00, 27.00, 35.83 -CTUN, 754, 0.44, 0.87, 0.000000, 0, 0, -26, 752, 0 -ATT, 0.00, -0.23, -6.53, -2.68, 0.00, 26.81, 35.83 -CTUN, 769, 0.44, 0.94, 0.000000, 0, 0, -28, 769, 0 -ATT, 0.00, 0.73, -6.53, -2.56, 0.00, 26.92, 35.83 -CTUN, 780, 0.38, 0.91, 0.000000, 0, 0, -25, 780, 0 -ATT, 0.00, 0.88, -6.53, -2.54, 0.19, 27.20, 35.83 -CTUN, 779, 0.38, 0.81, 0.000000, 0, 0, -26, 779, 0 -ATT, 0.00, 1.12, -5.69, -3.00, 1.63, 27.65, 36.17 -DU32, 7, 166140 -CURR, 780, 568214, 1018, 2205, 5051, 426.923520 -CTUN, 783, 0.31, 0.79, 0.000000, 0, 1, -20, 782, 0 -ATT, 0.00, 0.94, -4.85, -2.81, 2.59, 28.49, 37.15 -CTUN, 785, 0.31, 0.80, 0.000000, 0, 0, -13, 785, 0 -ATT, 0.00, 0.34, -3.73, -1.89, 3.36, 29.94, 38.44 -CTUN, 785, 0.26, 0.84, 0.000000, 0, 0, -5, 787, 0 -ATT, 0.00, -0.10, -2.24, -0.56, 3.75, 31.87, 40.02 -CTUN, 784, 0.26, 0.81, 0.000000, 0, 0, 2, 784, 0 -ATT, 0.00, 0.02, -2.24, 1.23, 4.23, 34.33, 41.82 -CTUN, 784, 0.22, 0.75, 0.000000, 0, 0, 8, 784, 0 -ATT, 0.00, -0.06, -2.24, 2.34, 4.23, 37.29, 43.70 -CTUN, 783, 0.22, 0.65, 0.000000, 0, 0, 14, 783, 0 -ATT, 0.00, 0.25, -2.42, 1.83, 4.13, 40.50, 45.49 -CTUN, 782, 0.22, 0.69, 0.000000, 0, 0, 17, 782, 0 -ATT, 0.00, 0.09, -3.26, 1.02, 0.38, 43.77, 46.50 -CTUN, 778, 0.23, 0.71, 0.000000, 0, 0, 17, 782, 0 -ATT, 0.00, -0.09, -4.76, 0.82, 0.00, 46.74, 46.50 -CTUN, 766, 0.23, 0.66, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.00, -0.08, -6.81, 0.81, 0.00, 48.76, 46.50 -CTUN, 758, 0.25, 0.73, 0.000000, 0, 0, 24, 758, 0 -ATT, 0.00, -0.22, -7.37, -0.37, 0.00, 49.97, 46.50 -DU32, 7, 166140 -CURR, 758, 576011, 1026, 2088, 5051, 433.009460 -CTUN, 758, 0.25, 0.87, 0.000000, 0, 0, 21, 758, 0 -ATT, 0.00, -0.42, -8.12, -3.05, 0.00, 50.54, 46.50 -CTUN, 759, 0.29, 0.89, 0.000000, 0, 1, 19, 760, 0 -ATT, 0.00, -0.39, -8.21, -4.99, 0.00, 50.49, 46.50 -CTUN, 759, 0.29, 0.90, 0.000000, 0, 2, 16, 761, 0 -ATT, 0.00, -0.70, -8.02, -5.74, 0.00, 50.07, 46.50 -CTUN, 759, 0.32, 0.96, 0.000000, 0, 3, 14, 762, 0 -ATT, 0.00, -0.69, -7.74, -5.56, 0.00, 49.27, 46.50 -CTUN, 757, 0.32, 1.00, 0.000000, 0, 2, 10, 758, 0 -ATT, 0.84, -0.24, -6.06, -5.08, 0.00, 48.27, 46.50 -CTUN, 756, 0.35, 1.02, 0.000000, 0, 2, 9, 758, 0 -ATT, 1.78, 0.26, -4.38, -4.20, 0.00, 47.27, 46.50 -CTUN, 756, 0.35, 1.01, 0.000000, 0, 1, 7, 757, 0 -ATT, 2.43, 0.96, -2.24, -3.19, 0.00, 46.37, 46.50 -CTUN, 756, 0.37, 0.91, 0.000000, 0, 0, 4, 756, 0 -ATT, 2.62, 1.52, -2.24, -1.92, 0.00, 45.63, 46.50 -CTUN, 756, 0.37, 0.94, 0.000000, 0, 0, 2, 756, 0 -ATT, 2.34, 2.29, -2.24, -1.24, 0.00, 45.12, 46.50 -CTUN, 756, 0.37, 0.89, 0.000000, 0, 0, 0, 756, 0 -ATT, 2.34, 3.25, -2.24, -0.77, 0.00, 44.90, 46.50 -DU32, 7, 166140 -CURR, 755, 583594, 1027, 2070, 5028, 438.766970 -CTUN, 756, 0.37, 0.88, 0.000000, 0, 1, -1, 757, 0 -ATT, 0.84, 3.87, -2.24, -0.27, 0.00, 44.89, 46.50 -CTUN, 756, 0.37, 0.89, 0.000000, 0, 1, -6, 757, 0 -ATT, 0.00, 2.87, -2.33, -0.17, 0.00, 44.87, 46.50 -CTUN, 756, 0.36, 0.86, 0.000000, 0, 0, -8, 756, 0 -ATT, 0.00, 1.34, -2.52, -0.32, 0.00, 44.99, 46.50 -CTUN, 756, 0.36, 0.99, 0.000000, 0, 0, -11, 756, 0 -ATT, 0.00, 0.65, -3.26, -0.38, 0.00, 45.23, 46.50 -CTUN, 756, 0.35, 0.79, 0.000000, 0, 0, -12, 756, 0 -ATT, 0.00, 0.63, -3.26, -0.83, 0.00, 45.62, 46.50 -CTUN, 756, 0.35, 0.95, 0.000000, 0, 0, -15, 756, 0 -ATT, 0.00, 0.95, -3.45, -1.23, 0.00, 46.08, 46.50 -CTUN, 756, 0.32, 0.89, 0.000000, 0, 0, -14, 756, 0 -ATT, 0.00, 1.17, -3.17, -1.19, 0.00, 46.51, 46.50 -CTUN, 756, 0.32, 0.67, 0.000000, 0, 0, -14, 756, 0 -ATT, 0.00, 0.54, -2.24, -1.43, 0.00, 46.95, 46.50 -CTUN, 755, 0.29, 0.73, 0.000000, 0, 0, -13, 755, 0 -ATT, 0.00, 0.21, -2.05, -1.70, 0.00, 47.34, 46.50 -CTUN, 756, 0.29, 0.72, 0.000000, 0, 0, -13, 756, 0 -ATT, 0.00, -0.24, -2.24, -1.64, 0.00, 47.66, 46.50 -DU32, 7, 166140 -CURR, 756, 591155, 1037, 2054, 5051, 444.483760 -CTUN, 756, 0.26, 0.70, 0.000000, 0, 0, -12, 756, 0 -ATT, 0.00, -0.48, -2.24, -1.35, 0.00, 47.83, 46.50 -CTUN, 756, 0.26, 0.62, 0.000000, 0, 0, -5, 756, 0 -ATT, 0.00, -0.65, -2.24, -0.53, 0.00, 47.86, 46.50 -CTUN, 756, 0.24, 0.77, 0.000000, 0, 0, -3, 756, 0 -ATT, 0.00, -0.59, -2.24, -0.44, 0.00, 47.88, 46.50 -CTUN, 756, 0.24, 0.60, 0.000000, 0, 0, 0, 756, 0 -ATT, 0.00, -0.44, -2.24, -0.49, 0.00, 47.81, 46.50 -CTUN, 755, 0.22, 0.63, 0.000000, 0, 0, 4, 756, 0 -ATT, 0.00, -0.12, -2.33, -0.09, 0.00, 47.67, 46.50 -CTUN, 756, 0.22, 0.78, 0.000000, 0, 0, 8, 756, 0 -ATT, 0.00, -0.13, -3.08, 0.20, 0.00, 47.54, 46.50 -CTUN, 757, 0.21, 0.53, 0.000000, 0, 0, 10, 757, 0 -ATT, 0.00, -0.04, -3.73, -0.22, 0.00, 47.44, 46.50 -CTUN, 755, 0.22, 0.28, 0.000000, 0, 0, 10, 756, 0 -ATT, 0.00, 0.00, -4.38, -0.33, 0.00, 47.26, 46.50 -CTUN, 758, 0.22, 0.30, 0.000000, 0, 0, 11, 756, 0 -ATT, 0.00, 0.03, -4.29, -0.61, 0.00, 46.88, 46.50 -CTUN, 757, 0.23, 0.71, 0.000000, 0, 0, 11, 756, 0 -ATT, 0.00, -0.18, -4.57, -1.55, 0.00, 46.40, 46.50 -DU32, 7, 166140 -CURR, 757, 598715, 1025, 2063, 5051, 450.197110 -CTUN, 757, 0.23, 0.78, 0.000000, 0, 0, 12, 756, 0 -ATT, 0.00, -0.14, -4.76, -1.84, 0.00, 45.85, 46.50 -CTUN, 756, 0.25, 0.78, 0.000000, 0, 0, 10, 756, 0 -ATT, 0.00, -0.23, -3.92, -2.14, 0.00, 45.32, 46.50 -CTUN, 756, 0.25, 0.66, 0.000000, 0, 0, 12, 756, 0 -ATT, 0.00, -0.64, -2.05, -2.77, 0.00, 44.85, 46.50 -CTUN, 756, 0.27, 0.78, 0.000000, 0, 0, 10, 756, 0 -ATT, 0.00, -0.40, -2.24, -2.55, 0.00, 44.48, 46.50 -CTUN, 756, 0.27, 0.86, 0.000000, 0, 0, 13, 756, 0 -ATT, 0.00, -0.28, -2.24, -1.27, 0.00, 44.19, 46.50 -CTUN, 756, 0.28, 0.73, 0.000000, 0, 0, 9, 756, 0 -ATT, 0.00, -0.48, -2.52, -0.43, 0.00, 43.89, 46.50 -CTUN, 762, 0.28, 0.92, 0.000000, 0, 0, 8, 758, 0 -ATT, 0.00, -0.37, -2.52, -0.11, 0.00, 43.68, 46.50 -CTUN, 765, 0.29, 0.92, 0.000000, 0, 0, 8, 765, 0 -PM, 0, 0, 0, 0, 1000, 10492, 0, 0 -ATT, 0.00, -0.81, -2.52, -0.28, 0.00, 43.56, 46.50 -CTUN, 767, 0.29, 0.82, 0.000000, 0, 0, 6, 767, 0 -ATT, 0.00, -1.03, -2.52, -0.69, 0.00, 43.54, 46.50 -CTUN, 768, 0.31, 0.82, 0.000000, 0, 0, 4, 769, 0 -ATT, 0.00, -1.02, -2.42, -0.30, 0.00, 43.52, 46.50 -DU32, 7, 166140 -CURR, 771, 606310, 1025, 2109, 5051, 455.943150 -CTUN, 771, 0.31, 0.75, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, -1.50, -2.42, 0.58, 0.00, 43.41, 46.50 -CTUN, 771, 0.31, 0.77, 0.000000, 0, 0, 7, 770, 0 -ATT, 0.00, -2.21, -2.52, 0.86, 0.00, 43.43, 46.50 -CTUN, 771, 0.31, 0.88, 0.000000, 0, 0, 5, 770, 0 -ATT, 0.46, -2.59, -2.52, 0.38, 0.00, 43.49, 46.50 -CTUN, 771, 0.33, 0.82, 0.000000, 0, 0, 6, 770, 0 -ATT, 1.78, -1.88, -2.42, 0.71, 0.00, 43.37, 46.50 -CTUN, 771, 0.33, 0.80, 0.000000, 0, 0, 4, 771, 0 -ATT, 1.78, -0.49, -2.42, 1.18, 0.00, 43.10, 46.50 -CTUN, 770, 0.34, 0.74, 0.000000, 0, 0, 3, 770, 0 -ATT, 2.34, 0.43, -2.52, 1.32, 0.00, 42.72, 46.50 -CTUN, 771, 0.34, 0.88, 0.000000, 0, 0, 1, 771, 0 -ATT, 2.90, 1.22, -2.52, 1.26, 0.00, 42.26, 46.50 -CTUN, 771, 0.34, 0.90, 0.000000, 0, 0, 0, 771, 0 -ATT, 2.90, 2.80, -2.42, 1.26, 0.00, 41.74, 46.50 -CTUN, 771, 0.34, 0.94, 0.000000, 0, 1, -1, 771, 0 -ATT, 2.90, 4.08, -3.45, 0.94, 0.00, 41.26, 46.50 -CTUN, 770, 0.34, 0.94, 0.000000, 0, 1, -5, 772, 0 -ATT, 1.78, 4.44, -7.56, 0.43, 0.00, 40.83, 46.50 -DU32, 7, 166140 -CURR, 770, 614016, 1023, 2116, 5051, 461.851560 -CTUN, 770, 0.32, 0.95, 0.000000, 0, 1, -6, 772, 0 -ATT, 0.65, 4.16, -10.73, -1.10, 0.00, 40.50, 46.50 -CTUN, 771, 0.32, 0.82, 0.000000, 0, 1, -8, 772, 0 -ATT, 0.46, 3.62, -11.20, -3.47, 0.00, 40.23, 46.50 -CTUN, 771, 0.32, 0.85, 0.000000, 0, 3, -9, 773, 0 -ATT, 0.18, 3.65, -11.01, -5.72, 0.00, 40.10, 46.50 -CTUN, 771, 0.32, 0.91, 0.000000, 0, 5, -11, 776, 0 -ATT, 0.28, 4.08, -10.92, -6.48, 0.00, 40.17, 46.50 -CTUN, 771, 0.29, 0.83, 0.000000, 0, 5, -10, 776, 0 -ATT, 0.28, 3.57, -10.92, -6.45, 0.00, 40.64, 46.50 -CTUN, 771, 0.29, 0.78, 0.000000, 0, 5, -8, 776, 0 -ATT, 0.00, 2.67, -10.54, -6.04, 0.00, 41.36, 46.50 -CTUN, 770, 0.27, 0.94, 0.000000, 0, 3, -3, 774, 0 -ATT, 0.00, 1.55, -9.52, -5.78, 0.00, 42.15, 46.50 -CTUN, 771, 0.27, 0.64, 0.000000, 0, 3, -3, 774, 0 -ATT, 0.00, 0.94, -8.21, -4.80, 0.00, 42.96, 46.50 -CTUN, 770, 0.25, 0.68, 0.000000, 0, 1, 2, 773, 0 -ATT, 0.00, 0.29, -6.44, -2.86, 0.00, 43.89, 46.50 -CTUN, 771, 0.25, 0.70, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 0.35, -4.85, -1.35, 0.00, 44.90, 46.50 -DU32, 7, 166140 -CURR, 771, 621752, 1023, 2130, 5028, 467.780700 -CTUN, 771, 0.25, 0.57, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, 1.01, -4.38, -0.02, 0.00, 45.83, 46.50 -CTUN, 771, 0.25, 0.86, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, 0.63, -3.08, 0.68, 0.00, 46.67, 46.50 -CTUN, 771, 0.25, 0.77, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, 0.54, -2.52, 0.45, 0.00, 47.47, 46.50 -CTUN, 771, 0.25, 0.84, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.00, 0.45, -2.42, 0.32, 0.00, 48.01, 46.50 -CTUN, 770, 0.25, 0.80, 0.000000, 0, 0, 19, 770, 0 -ATT, 0.00, 0.06, -2.52, 0.75, 0.00, 48.27, 46.50 -CTUN, 771, 0.27, 0.87, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.00, -0.39, -2.52, 1.47, 0.00, 48.34, 46.50 -CTUN, 770, 0.27, 0.85, 0.000000, 0, 0, 21, 771, 0 -ATT, 0.00, -0.59, -3.26, 1.93, 0.00, 48.20, 46.50 -CTUN, 771, 0.30, 0.85, 0.000000, 0, 0, 18, 770, 0 -ATT, 0.00, -0.45, -4.57, 1.70, 0.00, 47.85, 46.50 -CTUN, 771, 0.30, 0.95, 0.000000, 0, 0, 16, 770, 0 -ATT, 0.00, -0.76, -6.16, 0.71, 0.00, 47.36, 46.50 -CTUN, 770, 0.32, 0.78, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -1.12, -6.53, -0.22, 0.00, 46.74, 46.50 -DU32, 7, 166140 -CURR, 771, 629460, 1020, 2119, 5028, 473.708370 -CTUN, 770, 0.32, 0.81, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.00, -0.83, -6.53, -1.30, 0.00, 45.98, 46.50 -CTUN, 770, 0.36, 0.99, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, -0.50, -6.53, -2.08, 0.00, 45.26, 46.50 -CTUN, 770, 0.36, 1.05, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.93, -6.53, -2.19, 0.00, 44.67, 46.50 -CTUN, 770, 0.37, 1.01, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, -1.31, -6.53, -2.03, 0.00, 44.18, 46.50 -CTUN, 771, 0.37, 1.13, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.83, -6.53, -2.19, 0.00, 43.72, 46.50 -CTUN, 770, 0.37, 1.07, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.44, -6.53, -2.77, 0.00, 43.34, 46.50 -CTUN, 771, 0.37, 0.96, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.93, -6.53, -3.26, 0.00, 43.08, 46.50 -CTUN, 771, 0.37, 1.15, 0.000000, 0, 1, -1, 772, 0 -ATT, 0.00, 1.28, -6.53, -3.37, 0.00, 42.84, 46.50 -CTUN, 771, 0.37, 0.92, 0.000000, 0, 1, -3, 771, 0 -ATT, 0.00, 0.78, -6.06, -3.30, 0.00, 42.62, 46.50 -CTUN, 771, 0.37, 1.01, 0.000000, 0, 1, -5, 771, 0 -ATT, 0.00, -0.19, -5.04, -3.11, 0.00, 42.45, 46.50 -DU32, 7, 166140 -CURR, 771, 637171, 1028, 2094, 5051, 479.558870 -CTUN, 771, 0.35, 0.94, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.38, -4.85, -2.20, 0.00, 42.34, 46.50 -CTUN, 770, 0.35, 1.07, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -0.34, -4.85, -0.79, 0.00, 42.34, 46.50 -CTUN, 771, 0.33, 1.06, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.19, -4.48, -0.79, 0.00, 42.65, 46.50 -CTUN, 771, 0.33, 0.87, 0.000000, 0, 0, -7, 771, 0 -ATT, 0.00, 0.25, -4.38, -1.50, 0.00, 43.15, 46.50 -CTUN, 771, 0.31, 0.88, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, 0.32, -4.48, -1.76, 0.00, 43.81, 46.50 -CTUN, 771, 0.31, 0.84, 0.000000, 0, 0, -4, 770, 0 -ATT, 0.00, 0.18, -4.20, -1.52, 0.00, 44.68, 46.50 -CTUN, 770, 0.29, 0.94, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, 0.18, -3.92, -1.33, 0.00, 45.66, 46.50 -CTUN, 771, 0.29, 0.83, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.20, -3.17, -1.71, 0.00, 46.81, 46.50 -CTUN, 771, 0.27, 0.79, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.19, -3.08, -2.18, 0.00, 47.99, 46.50 -CTUN, 770, 0.27, 0.77, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.11, -3.17, -1.48, 0.00, 48.88, 46.50 -DU32, 7, 166140 -CURR, 771, 644880, 1027, 2114, 5051, 485.402770 -CTUN, 771, 0.26, 0.82, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.01, -3.08, -0.24, 0.00, 49.56, 46.50 -CTUN, 771, 0.26, 0.76, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, -0.38, -2.80, 0.57, 0.00, 50.10, 46.50 -CTUN, 771, 0.26, 0.70, 0.000000, 0, 0, 9, 770, 0 -ATT, 0.00, 0.15, -2.61, 1.27, 0.00, 50.43, 46.50 -CTUN, 770, 0.27, 0.78, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, 0.66, -2.52, 1.80, 0.00, 50.67, 46.50 -CTUN, 770, 0.26, 0.87, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, 0.82, -2.61, 1.44, 0.00, 50.88, 46.50 -CTUN, 771, 0.26, 0.84, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, 1.26, -2.61, 0.48, 0.00, 50.94, 46.50 -CTUN, 771, 0.26, 0.81, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, 1.58, -2.70, 0.37, 0.00, 50.89, 46.50 -CTUN, 771, 0.28, 0.82, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, 1.01, -2.70, 1.20, 0.00, 50.88, 46.50 -CTUN, 771, 0.28, 0.86, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, -0.12, -2.80, 1.09, 0.00, 50.88, 46.50 -CTUN, 771, 0.29, 0.74, 0.000000, 0, 0, 9, 770, 0 -ATT, 0.00, -0.04, -2.61, 0.22, 0.00, 50.80, 46.50 -DU32, 7, 166140 -CURR, 770, 652588, 1019, 2116, 5051, 491.281890 -CTUN, 770, 0.29, 0.79, 0.000000, 0, 0, 9, 771, 0 -ATT, -0.37, 0.92, -2.70, -0.24, 0.00, 50.53, 46.50 -CTUN, 770, 0.29, 0.85, 0.000000, 0, 0, 8, 771, 0 -ATT, -2.17, 0.76, -1.49, -0.65, 0.00, 50.17, 46.50 -CTUN, 771, 0.29, 0.81, 0.000000, 0, 0, 9, 770, 0 -ATT, -2.36, -0.81, -2.33, -1.04, 0.00, 49.71, 46.50 -CTUN, 771, 0.30, 0.85, 0.000000, 0, 0, 9, 771, 0 -ATT, -0.94, -2.02, -2.61, -1.15, 0.00, 49.16, 46.50 -CTUN, 771, 0.30, 0.99, 0.000000, 0, 0, 11, 771, 0 -ATT, -0.75, -2.06, -2.70, -1.01, 0.00, 48.44, 46.50 -CTUN, 771, 0.33, 0.92, 0.000000, 0, 0, 7, 770, 0 -ATT, -0.37, -0.78, -2.89, -1.39, 0.00, 47.96, 46.50 -CTUN, 771, 0.33, 0.86, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -0.24, -2.89, -1.40, 0.00, 47.65, 46.50 -CTUN, 770, 0.33, 0.92, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.25, -3.08, -1.20, 0.00, 47.57, 46.50 -CTUN, 771, 0.33, 0.91, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.00, -3.08, -1.21, 0.00, 47.69, 46.50 -CTUN, 771, 0.34, 0.97, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.27, -2.98, -1.56, 0.00, 47.97, 46.50 -DU32, 7, 166140 -CURR, 770, 660297, 1015, 2097, 5051, 497.135040 -CTUN, 771, 0.34, 1.00, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, 0.44, -3.08, -2.27, 0.00, 48.32, 46.50 -CTUN, 771, 0.34, 0.87, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, 0.23, -2.80, -2.64, 0.00, 48.66, 46.50 -CTUN, 771, 0.34, 0.80, 0.000000, 0, 0, -2, 770, 0 -ATT, 0.00, -0.41, -2.61, -2.57, 0.00, 49.05, 46.50 -CTUN, 771, 0.34, 1.06, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -0.40, -2.52, -1.61, 0.00, 49.32, 46.50 -CTUN, 771, 0.33, 0.86, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.45, -1.77, -0.48, 0.00, 49.40, 46.50 -CTUN, 771, 0.33, 0.90, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 0.74, 0.00, 0.11, 0.00, 49.14, 46.50 -CTUN, 771, 0.32, 0.82, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.92, 0.00, 0.99, 0.00, 48.73, 46.50 -CTUN, 771, 0.32, 1.02, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, 1.84, 0.00, 2.28, 0.00, 48.23, 46.50 -CTUN, 771, 0.32, 0.89, 0.000000, 0, 1, 9, 772, 0 -ATT, 0.00, 2.41, 0.00, 3.41, 0.00, 47.62, 46.50 -CTUN, 771, 0.32, 0.97, 0.000000, 0, 1, 5, 772, 0 -ATT, 0.00, 2.19, 0.00, 2.59, 0.00, 47.10, 46.50 -DU32, 7, 166140 -CURR, 771, 668007, 1020, 2123, 5051, 503.020450 -CTUN, 770, 0.32, 1.03, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.00, 1.51, 0.00, 0.63, 0.00, 46.94, 46.50 -CTUN, 771, 0.32, 0.95, 0.000000, 0, 0, 4, 770, 0 -ATT, -2.93, 0.95, 0.00, -0.05, 0.00, 47.37, 46.50 -CTUN, 771, 0.32, 0.89, 0.000000, 0, 0, 6, 771, 0 -ATT, -3.78, -0.94, -0.93, 1.83, 0.00, 47.99, 46.50 -CTUN, 771, 0.32, 1.00, 0.000000, 0, 1, 9, 772, 0 -ATT, -4.45, -4.10, -1.02, 4.62, 0.00, 48.63, 46.50 -CTUN, 771, 0.32, 0.90, 0.000000, 0, 4, 6, 775, 0 -ATT, -5.21, -5.10, -1.02, 4.79, 0.00, 49.40, 46.50 -CTUN, 771, 0.34, 1.09, 0.000000, 0, 4, 3, 774, 0 -ATT, -4.35, -4.14, -0.93, 2.73, 0.00, 50.20, 46.50 -CTUN, 771, 0.34, 0.96, 0.000000, 0, 1, 1, 772, 0 -ATT, -2.55, -3.94, -2.42, -0.01, 0.00, 50.83, 46.50 -CTUN, 771, 0.34, 0.88, 0.000000, 0, 1, -1, 772, 0 -ATT, -2.74, -3.82, -2.61, -2.57, 0.00, 51.33, 46.50 -CTUN, 771, 0.34, 0.91, 0.000000, 0, 2, -1, 773, 0 -ATT, -0.85, -3.13, -2.61, -3.65, 0.00, 51.59, 46.50 -CTUN, 770, 0.34, 0.91, 0.000000, 0, 2, 0, 773, 0 -ATT, 0.00, -2.77, -2.61, -3.44, 0.00, 51.55, 46.50 -DU32, 7, 166140 -CURR, 770, 675728, 1019, 2109, 5051, 508.902500 -CTUN, 770, 0.33, 0.89, 0.000000, 0, 1, 0, 772, 0 -ATT, 0.00, -2.10, -2.89, -2.36, 0.00, 51.46, 46.50 -CTUN, 770, 0.33, 0.77, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -1.32, -2.80, -1.72, 0.00, 51.27, 46.50 -CTUN, 771, 0.31, 0.92, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -1.30, -2.89, -1.42, 0.00, 50.96, 46.50 -CTUN, 770, 0.31, 0.99, 0.000000, 0, 0, -9, 771, 0 -ATT, 0.00, -1.43, -3.08, -1.85, 0.00, 50.73, 46.50 -CTUN, 771, 0.30, 0.90, 0.000000, 0, 0, -9, 771, 0 -ATT, 0.00, -1.38, -3.08, -2.12, 0.00, 50.61, 46.50 -CTUN, 770, 0.30, 0.90, 0.000000, 0, 0, -7, 770, 0 -ATT, 0.00, -0.10, -3.08, -2.63, 0.00, 50.43, 46.50 -CTUN, 771, 0.28, 0.80, 0.000000, 0, 0, -7, 770, 0 -ATT, 0.00, 1.54, -2.80, -2.40, 0.00, 50.44, 46.50 -CTUN, 771, 0.28, 0.76, 0.000000, 0, 0, -5, 770, 0 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -ATT, 0.00, 2.17, -2.70, -1.93, 0.00, 50.69, 46.50 -CTUN, 770, 0.26, 0.79, 0.000000, 0, 0, -1, 770, 0 -ATT, 0.00, 0.70, -2.42, -1.55, 0.00, 51.12, 46.50 -CTUN, 771, 0.26, 0.82, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.30, -2.52, -1.61, 0.00, 51.61, 46.50 -DU32, 7, 166140 -CURR, 771, 683435, 1022, 2126, 5051, 514.773070 -CTUN, 771, 0.24, 0.80, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 1.92, -2.05, -1.83, 0.00, 52.19, 46.50 -CTUN, 771, 0.24, 0.73, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 2.58, -1.40, -1.53, 0.00, 52.84, 46.50 -CTUN, 770, 0.24, 0.93, 0.000000, 0, 0, 10, 770, 0 -ATT, 0.00, 1.46, 0.00, -0.38, 0.00, 53.64, 46.50 -CTUN, 771, 0.24, 0.98, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, 0.66, 0.00, 1.03, 0.00, 54.43, 46.50 -CTUN, 771, 0.24, 0.92, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, 1.15, 0.00, 1.86, 0.00, 54.99, 46.50 -CTUN, 771, 0.26, 0.91, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, 3.02, 0.00, 1.63, 0.00, 55.16, 46.50 -CTUN, 770, 0.26, 0.83, 0.000000, 0, 1, 7, 772, 0 -ATT, 0.00, 2.65, 0.00, 0.64, 0.00, 55.06, 46.50 -CTUN, 771, 0.27, 0.88, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.00, 2.17, -0.93, 0.02, 0.00, 54.66, 46.50 -CTUN, 771, 0.27, 0.78, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 1.00, -0.93, 0.06, 0.00, 54.47, 46.50 -CTUN, 771, 0.27, 0.81, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -0.45, 0.00, 0.13, 0.00, 54.25, 46.50 -DU32, 7, 166140 -CURR, 770, 691143, 1023, 2092, 5051, 520.668400 -CTUN, 771, 0.26, 0.93, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.15, 0.00, -0.54, 0.00, 54.06, 46.50 -CTUN, 770, 0.26, 0.87, 0.000000, 0, 0, 1, 770, 0 -ATT, -0.37, 1.32, -0.37, -1.61, 0.00, 53.98, 46.50 -CTUN, 771, 0.26, 0.78, 0.000000, 0, 0, 2, 770, 0 -ATT, -0.37, -0.35, -0.37, -1.59, 0.00, 54.20, 46.50 -CTUN, 770, 0.26, 0.84, 0.000000, 0, 0, 2, 770, 0 -ATT, -1.70, -3.10, 0.00, -1.15, 0.00, 54.50, 46.50 -CTUN, 771, 0.25, 0.80, 0.000000, 0, 1, 6, 772, 0 -ATT, -2.46, -4.37, 0.00, -1.46, 0.00, 54.88, 46.50 -CTUN, 770, 0.26, 0.71, 0.000000, 0, 1, 9, 772, 0 -ATT, -3.12, -3.58, 0.00, -1.30, 0.00, 55.20, 46.50 -CTUN, 771, 0.26, 0.80, 0.000000, 0, 1, 13, 772, 0 -ATT, -3.22, -3.67, 0.00, -0.70, 0.00, 55.42, 46.50 -CTUN, 770, 0.26, 0.93, 0.000000, 0, 1, 16, 772, 0 -ATT, -1.23, -4.55, 0.00, -0.40, 0.00, 55.45, 46.50 -CTUN, 770, 0.26, 0.76, 0.000000, 0, 2, 17, 773, 0 -ATT, -0.75, -3.67, 0.00, 0.28, 0.00, 55.12, 46.50 -CTUN, 771, 0.28, 0.88, 0.000000, 0, 1, 19, 772, 0 -ATT, 0.00, -1.25, 0.00, 1.46, 0.00, 54.30, 46.50 -DU32, 7, 166140 -CURR, 770, 698857, 1013, 2175, 5028, 526.637940 -CTUN, 771, 0.28, 0.73, 0.000000, 0, 0, 24, 771, 0 -ATT, 0.00, -0.40, 0.00, 2.81, 0.00, 52.85, 46.50 -CTUN, 771, 0.30, 1.05, 0.000000, 0, 0, 21, 771, 0 -ATT, 0.00, -0.83, 0.00, 2.37, 0.00, 51.53, 46.50 -CTUN, 771, 0.30, 1.02, 0.000000, 0, 0, 21, 771, 0 -ATT, 0.00, -1.36, 0.00, 1.59, 0.00, 50.65, 46.50 -CTUN, 771, 0.34, 1.07, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.00, -0.07, 0.00, 1.86, 0.00, 50.08, 46.50 -CTUN, 771, 0.34, 1.03, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.00, 0.38, -1.21, 2.70, 0.00, 49.65, 46.50 -CTUN, 771, 0.37, 1.25, 0.000000, 0, 0, 10, 770, 0 -ATT, 0.00, 1.20, -1.40, 1.60, 0.00, 49.57, 46.50 -CTUN, 771, 0.37, 1.05, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 1.34, -2.14, -0.39, 0.00, 49.68, 46.50 -CTUN, 770, 0.37, 1.27, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -0.94, -2.33, -2.44, 0.00, 50.21, 46.50 -CTUN, 771, 0.37, 1.11, 0.000000, 0, 1, 4, 772, 0 -ATT, 0.00, -2.05, -2.52, -4.00, 0.00, 50.77, 46.50 -CTUN, 771, 0.39, 1.06, 0.000000, 0, 2, 2, 773, 0 -ATT, 0.00, -1.12, -2.52, -4.20, 0.00, 51.15, 46.50 -DU32, 7, 166140 -CURR, 771, 706570, 1024, 2127, 5051, 532.557250 -CTUN, 771, 0.39, 1.16, 0.000000, 0, 1, 1, 772, 0 -ATT, 0.00, -0.10, -2.52, -2.87, 0.00, 51.48, 46.50 -CTUN, 771, 0.39, 1.05, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, -0.16, -2.52, -2.25, 0.00, 51.78, 46.50 -CTUN, 770, 0.39, 0.98, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, -0.99, -2.52, -2.01, 0.00, 52.13, 46.50 -CTUN, 771, 0.39, 0.91, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.29, -2.52, -1.16, 0.00, 52.59, 46.50 -CTUN, 771, 0.39, 0.93, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, -0.54, -2.52, -0.35, 0.00, 53.13, 46.50 -CTUN, 771, 0.39, 1.00, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 0.62, -2.52, -0.32, 0.00, 53.58, 46.50 -CTUN, 770, 0.39, 0.97, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.76, -2.42, -0.91, 0.00, 53.82, 46.50 -CTUN, 770, 0.39, 1.05, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.68, -2.52, -1.47, 0.00, 54.05, 46.50 -CTUN, 771, 0.39, 0.91, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, 0.58, -2.42, -1.98, 0.00, 54.11, 46.50 -CTUN, 771, 0.39, 1.13, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, 0.16, -2.52, -2.04, 0.00, 53.86, 46.50 -DU32, 7, 166140 -CURR, 771, 714279, 1012, 2156, 5051, 538.535710 -CTUN, 771, 0.37, 1.02, 0.000000, 0, 0, -4, 774, 0 -ATT, 0.00, -0.13, -2.42, -1.73, 0.00, 53.39, 46.50 -CTUN, 771, 0.37, 1.05, 0.000000, 0, 0, -8, 770, 0 -ATT, 0.00, -0.06, -2.42, -2.10, 0.00, 52.89, 46.50 -CTUN, 770, 0.36, 0.92, 0.000000, 0, 0, -9, 770, 0 -ATT, 0.00, -0.49, -2.05, -2.58, 0.00, 52.28, 46.50 -CTUN, 771, 0.36, 0.92, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, -1.11, -0.74, -2.34, 0.00, 51.53, 46.50 -CTUN, 770, 0.34, 0.99, 0.000000, 0, 0, -10, 770, 0 -ATT, 0.00, -1.12, 0.00, -1.43, 0.00, 50.79, 46.50 -CTUN, 771, 0.34, 0.92, 0.000000, 0, 0, -11, 771, 0 -ATT, 0.00, -1.01, 0.00, -0.09, 0.00, 50.05, 46.50 -CTUN, 771, 0.32, 0.98, 0.000000, 0, 0, -14, 770, 0 -ATT, 0.00, -0.37, 0.00, 0.83, 0.00, 49.32, 46.50 -CTUN, 771, 0.32, 1.00, 0.000000, 0, 0, -16, 771, 0 -ATT, 0.00, 1.49, 0.00, 0.77, 0.00, 48.64, 46.50 -CTUN, 771, 0.29, 0.92, 0.000000, 0, 0, -18, 770, 0 -ATT, 0.00, 2.09, 0.00, 0.47, 0.00, 48.20, 46.50 -CTUN, 771, 0.29, 0.88, 0.000000, 0, 0, -17, 770, 0 -ATT, 0.00, 1.15, 0.00, 0.26, 0.00, 47.93, 46.50 -DU32, 7, 166140 -CURR, 771, 721989, 1023, 2096, 5028, 544.432920 -CTUN, 771, 0.26, 0.90, 0.000000, 0, 0, -14, 771, 0 -ATT, 0.00, 0.78, 0.00, 0.06, 0.00, 47.80, 46.50 -CTUN, 770, 0.26, 0.89, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 1.00, 0.00, 0.41, 0.00, 48.03, 46.50 -CTUN, 771, 0.22, 0.75, 0.000000, 0, 0, -7, 771, 0 -ATT, -0.37, 1.22, 0.00, 0.92, 0.00, 48.49, 46.50 -CTUN, 771, 0.22, 0.79, 0.000000, 0, 0, -3, 771, 0 -ATT, -0.75, 0.80, 0.00, 1.06, 0.00, 49.05, 46.50 -CTUN, 771, 0.21, 0.80, 0.000000, 0, 0, -1, 771, 0 -ATT, -0.75, -0.40, 0.00, 0.83, 0.00, 49.71, 46.50 -CTUN, 771, 0.21, 0.94, 0.000000, 0, 0, -1, 771, 0 -ATT, -0.75, -0.19, 0.00, -0.29, 0.00, 50.46, 46.50 -CTUN, 771, 0.21, 0.88, 0.000000, 0, 0, 3, 770, 0 -ATT, -0.75, -0.14, 0.00, -1.15, 0.00, 51.20, 46.50 -CTUN, 770, 0.21, 1.02, 0.000000, 0, 0, 5, 771, 0 -ATT, -0.85, -0.63, 0.00, -1.00, 0.00, 52.06, 46.50 -CTUN, 770, 0.21, 0.87, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, -1.12, 0.00, -0.03, 0.00, 52.93, 46.50 -CTUN, 771, 0.21, 0.89, 0.000000, 0, 0, 14, 771, 0 -ATT, -1.32, -2.14, 0.00, 0.37, 0.00, 53.81, 46.50 -DU32, 7, 166140 -CURR, 771, 729699, 1031, 2039, 5051, 550.314940 -CTUN, 771, 0.21, 0.97, 0.000000, 0, 0, 13, 771, 0 -ATT, -2.17, -1.95, 0.00, 0.00, 0.00, 54.67, 46.50 -CTUN, 771, 0.24, 0.73, 0.000000, 0, 0, 14, 771, 0 -ATT, -0.94, -1.92, 0.00, -0.57, 0.00, 55.39, 46.50 -CTUN, 771, 0.24, 0.93, 0.000000, 0, 0, 13, 771, 0 -ATT, -0.66, -2.39, 0.00, -1.01, 0.00, 55.85, 46.50 -CTUN, 771, 0.26, 0.97, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -2.18, 0.00, -0.87, 0.00, 55.97, 46.50 -CTUN, 770, 0.26, 0.95, 0.000000, 0, 0, 15, 770, 0 -ATT, 0.00, -1.87, -0.93, -0.70, 0.00, 55.85, 46.50 -CTUN, 770, 0.29, 0.86, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, -1.54, -1.58, -0.86, 0.00, 55.30, 46.50 -CTUN, 771, 0.29, 0.96, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, -1.33, -2.24, -0.86, 0.00, 54.18, 46.50 -CTUN, 771, 0.33, 1.01, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, -1.18, -2.52, -1.01, 0.00, 52.88, 46.50 -CTUN, 771, 0.33, 0.98, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -1.64, -2.52, -1.08, 0.00, 51.60, 46.50 -CTUN, 771, 0.37, 0.92, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -2.00, -2.52, -1.09, 0.00, 50.24, 46.50 -DU32, 7, 166140 -CURR, 771, 737407, 1012, 2134, 5051, 556.350650 -CTUN, 771, 0.37, 0.93, 0.000000, 0, 0, 9, 770, 0 -ATT, 0.00, -1.84, -2.42, -0.16, 0.00, 48.65, 46.50 -CTUN, 771, 0.40, 1.11, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -1.31, -2.42, 0.24, 0.00, 47.19, 46.50 -CTUN, 771, 0.40, 1.10, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.70, -2.42, 0.13, 0.00, 46.08, 46.50 -CTUN, 771, 0.41, 1.10, 0.000000, 0, 0, -1, 771, 0 -ATT, 1.78, -0.32, -2.42, 0.42, 0.00, 45.36, 46.50 -CTUN, 771, 0.41, 0.93, 0.000000, 0, 0, -3, 770, 0 -ATT, 2.06, -0.07, -2.52, 0.97, 0.00, 44.84, 46.50 -CTUN, 770, 0.41, 1.14, 0.000000, 0, 0, -5, 770, 0 -ATT, 2.34, 0.13, -2.42, 0.90, 0.00, 44.34, 46.50 -CTUN, 770, 0.41, 1.05, 0.000000, 0, 0, -9, 770, 0 -ATT, 3.28, 0.85, -2.52, 0.16, 0.00, 43.77, 46.50 -CTUN, 770, 0.42, 1.13, 0.000000, 0, 0, -8, 770, 0 -ATT, 3.37, 1.94, -2.52, -0.37, 0.00, 43.32, 46.50 -CTUN, 771, 0.41, 1.07, 0.000000, 0, 0, -12, 771, 0 -ATT, 3.65, 2.72, -2.52, -0.57, 0.00, 43.17, 46.50 -CTUN, 770, 0.41, 1.13, 0.000000, 0, 0, -13, 771, 0 -ATT, 3.84, 3.25, -2.52, -0.93, 0.00, 43.31, 46.50 -DU32, 7, 166140 -CURR, 771, 745114, 1016, 2106, 5051, 562.206670 -CTUN, 770, 0.40, 1.09, 0.000000, 0, 1, -13, 771, 0 -ATT, 3.84, 3.22, -2.52, -1.06, 0.00, 43.44, 46.50 -CTUN, 771, 0.40, 1.09, 0.000000, 0, 1, -14, 772, 0 -ATT, 3.93, 3.46, -2.52, -0.99, 0.00, 43.36, 46.50 -CTUN, 770, 0.38, 1.05, 0.000000, 0, 1, -15, 772, 0 -ATT, 3.75, 4.07, -2.52, -0.57, 0.00, 43.02, 46.50 -CTUN, 770, 0.38, 1.06, 0.000000, 0, 1, -15, 772, 0 -ATT, 3.37, 4.71, -2.42, 0.07, 0.00, 42.57, 46.50 -CTUN, 771, 0.35, 0.90, 0.000000, 0, 2, -16, 772, 0 -ATT, 3.18, 4.37, -2.42, -0.02, 0.00, 41.80, 46.50 -CTUN, 771, 0.35, 1.01, 0.000000, 0, 1, -18, 772, 0 -ATT, 2.15, 3.42, -4.10, -0.86, 0.00, 41.04, 46.50 -CTUN, 771, 0.32, 0.88, 0.000000, 0, 1, -17, 771, 0 -ATT, 0.28, 3.67, -4.76, -2.21, 0.00, 40.58, 46.50 -CTUN, 771, 0.32, 1.02, 0.000000, 0, 1, -13, 772, 0 -ATT, 0.00, 2.27, -5.60, -3.04, 0.00, 40.44, 46.50 -CTUN, 771, 0.30, 0.99, 0.000000, 0, 1, -13, 772, 0 -ATT, 0.00, -0.46, -5.32, -3.51, 0.00, 40.34, 46.50 -CTUN, 771, 0.30, 0.82, 0.000000, 0, 1, -10, 772, 0 -ATT, 0.00, -1.45, -4.76, -3.91, 0.00, 40.27, 46.50 -DU32, 7, 166140 -CURR, 771, 752833, 1013, 2106, 5051, 568.069640 -CTUN, 771, 0.28, 0.81, 0.000000, 0, 1, -8, 771, 0 -ATT, 0.00, -0.45, -4.85, -2.98, 0.00, 40.16, 46.50 -CTUN, 771, 0.28, 0.96, 0.000000, 0, 0, -9, 771, 0 -ATT, 0.00, -0.27, -4.76, -1.64, 0.00, 40.12, 46.50 -CTUN, 770, 0.26, 0.75, 0.000000, 0, 0, -6, 770, 0 -ATT, 0.00, -0.58, -5.22, -1.17, 0.00, 40.22, 46.50 -CTUN, 771, 0.26, 0.85, 0.000000, 0, 0, -7, 770, 0 -ATT, 0.00, -0.76, -5.41, -1.60, 0.00, 40.53, 46.50 -CTUN, 771, 0.24, 0.87, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.42, -5.50, -1.82, 0.00, 41.06, 46.50 -CTUN, 770, 0.24, 0.96, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.46, -5.69, -1.48, 0.00, 41.77, 46.50 -CTUN, 770, 0.24, 0.85, 0.000000, 0, 0, -5, 770, 0 -ATT, 0.00, -0.84, -5.69, -0.90, 0.00, 42.63, 46.50 -CTUN, 771, 0.24, 0.81, 0.000000, 0, 0, -2, 770, 0 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -ATT, 0.00, -1.53, -5.69, -0.32, 0.00, 43.67, 46.50 -CTUN, 771, 0.24, 0.83, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -1.79, -5.69, 0.57, 0.00, 44.77, 46.50 -CTUN, 770, 0.24, 0.94, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.69, -7.74, 1.09, 0.00, 45.70, 46.50 -DU32, 7, 166140 -CURR, 771, 760540, 1021, 2094, 5051, 573.887210 -CTUN, 771, 0.23, 0.89, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.54, -10.26, 0.79, 0.00, 46.34, 46.50 -CTUN, 771, 0.23, 0.89, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -1.28, -14.09, -0.07, 0.00, 46.61, 46.50 -CTUN, 771, 0.23, 0.96, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.35, -16.24, -2.49, 0.00, 46.30, 46.50 -CTUN, 771, 0.23, 0.77, 0.000000, 0, 1, 0, 771, 0 -ATT, 0.00, -0.55, -17.36, -8.30, 0.00, 45.84, 46.50 -CTUN, 771, 0.23, 1.03, 0.000000, 0, 10, 4, 781, 0 -ATT, 0.00, 0.59, -17.64, -14.09, 0.00, 45.06, 46.50 -CTUN, 771, 0.23, 1.03, 0.000000, 0, 22, 7, 793, 0 -ATT, 0.00, 0.52, -17.17, -16.35, 0.00, 44.07, 46.50 -CTUN, 771, 0.23, 0.84, 0.000000, 0, 27, 13, 798, 0 -ATT, 0.00, 0.63, -14.84, -16.29, 0.00, 43.10, 46.50 -CTUN, 771, 0.24, 0.89, 0.000000, 0, 26, 17, 797, 0 -ATT, 0.00, 1.24, -7.46, -14.21, 0.00, 42.84, 46.50 -CTUN, 771, 0.24, 0.94, 0.000000, 0, 15, 23, 786, 0 -ATT, 0.00, 1.78, -1.68, -9.37, 0.00, 43.16, 46.50 -CTUN, 771, 0.26, 0.92, 0.000000, 0, 5, 26, 776, 0 -ATT, 0.00, 2.35, 0.00, -3.12, 0.00, 44.00, 46.50 -DU32, 7, 166140 -CURR, 770, 768358, 1015, 2143, 5051, 579.855900 -CTUN, 770, 0.26, 0.97, 0.000000, 0, 0, 28, 770, 0 -ATT, 0.00, 2.79, 0.00, 2.30, 0.00, 45.06, 46.50 -CTUN, 771, 0.29, 1.14, 0.000000, 0, 1, 29, 771, 0 -ATT, 0.00, 2.94, 0.00, 5.08, 0.00, 46.03, 46.50 -CTUN, 770, 0.29, 1.20, 0.000000, 0, 3, 25, 774, 0 -ATT, 0.00, 3.12, -1.96, 5.68, 0.00, 46.78, 46.50 -CTUN, 770, 0.34, 1.07, 0.000000, 0, 3, 21, 774, 0 -ATT, 0.00, 3.14, -2.52, 4.69, 0.00, 47.13, 46.50 -CTUN, 770, 0.34, 1.07, 0.000000, 0, 2, 18, 773, 0 -ATT, 0.00, 2.48, -3.26, 3.41, 0.00, 47.12, 46.50 -CTUN, 771, 0.39, 1.23, 0.000000, 0, 1, 18, 772, 0 -ATT, 0.00, 1.19, -4.10, 2.65, 0.00, 46.80, 46.50 -CTUN, 771, 0.39, 1.24, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, -0.33, -3.26, 2.19, 0.00, 46.22, 46.50 -CTUN, 770, 0.42, 1.29, 0.000000, 0, 0, 12, 770, 0 -ATT, 0.00, -0.90, -2.70, 1.94, 0.00, 45.61, 46.50 -CTUN, 771, 0.42, 1.33, 0.000000, 0, 0, 9, 771, 0 -ATT, -0.37, -0.33, -2.61, 2.15, 0.00, 45.18, 46.50 -CTUN, 770, 0.46, 1.17, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.26, -2.61, 2.32, 0.00, 44.89, 46.50 -DU32, 7, 166140 -CURR, 770, 776075, 1023, 2104, 5051, 585.731320 -CTUN, 771, 0.46, 1.22, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.31, -2.61, 2.12, 0.00, 44.70, 46.50 -CTUN, 771, 0.48, 1.34, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.15, -2.52, 1.67, 0.00, 44.54, 46.50 -CTUN, 771, 0.48, 1.42, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, 0.19, -2.42, 1.17, 0.00, 44.52, 46.50 -CTUN, 771, 0.49, 1.32, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, 0.56, -2.52, 0.98, 0.00, 44.56, 46.50 -CTUN, 770, 0.48, 1.27, 0.000000, 0, 0, -12, 770, 0 -ATT, 0.00, 0.55, -2.52, 0.92, 0.00, 44.58, 46.50 -CTUN, 770, 0.48, 1.35, 0.000000, 0, 0, -13, 771, 0 -ATT, 0.00, 0.35, -2.42, 0.70, 0.00, 44.73, 46.50 -CTUN, 771, 0.47, 1.27, 0.000000, 0, 0, -17, 771, 0 -ATT, 0.00, 0.22, -2.52, 0.21, 0.00, 44.96, 46.50 -CTUN, 770, 0.47, 1.36, 0.000000, 0, 0, -22, 771, 0 -ATT, 0.00, 0.10, -3.26, -0.17, 0.00, 45.30, 46.50 -CTUN, 771, 0.44, 1.21, 0.000000, 0, 0, -24, 770, 0 -ATT, 0.00, 0.02, -6.16, -0.56, 0.00, 45.83, 46.50 -CTUN, 771, 0.44, 1.18, 0.000000, 0, 0, -29, 770, 0 -ATT, 0.00, -0.40, -6.81, -1.96, 0.00, 46.40, 46.50 -DU32, 7, 166140 -CURR, 771, 783784, 1010, 2063, 5028, 591.523440 -CTUN, 771, 0.40, 1.08, 0.000000, 0, 0, -32, 771, 0 -ATT, -1.42, -1.00, -6.53, -3.66, 0.00, 47.06, 46.50 -CTUN, 771, 0.40, 0.98, 0.000000, 0, 1, -33, 771, 0 -ATT, -3.69, -1.42, -5.32, -4.58, 0.00, 47.83, 46.50 -CTUN, 771, 0.35, 1.00, 0.000000, 0, 2, -33, 773, 0 -ATT, -3.88, -2.92, -3.82, -4.56, 0.00, 48.74, 46.50 -CTUN, 771, 0.35, 0.92, 0.000000, 0, 2, -31, 773, 0 -ATT, -2.36, -4.30, -20.91, -3.43, 0.00, 49.61, 46.50 -CTUN, 771, 0.28, 0.91, 0.000000, 0, 2, -27, 773, 0 -ATT, -1.61, -4.22, -3.73, -2.43, 0.00, 50.43, 46.50 -CTUN, 771, 0.28, 1.00, 0.000000, 0, 2, -25, 773, 0 -ATT, -1.23, -2.73, -4.10, -2.52, 0.00, 51.12, 46.50 -CTUN, 770, 0.22, 0.80, 0.000000, 0, 0, -18, 770, 0 -ATT, -0.47, -1.57, -4.10, -2.11, 0.00, 51.38, 46.50 -CTUN, 770, 0.22, 0.71, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, -1.22, -4.20, -2.30, 0.00, 51.40, 46.50 -CTUN, 771, 0.20, 0.71, 0.000000, 0, 0, -7, 771, 0 -ATT, 0.00, -0.53, -3.17, -2.50, 0.00, 51.22, 46.50 -CTUN, 771, 0.20, 0.58, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.29, -3.08, -1.92, 0.00, 50.55, 46.50 -DU32, 7, 166140 -CURR, 771, 791502, 1020, 2082, 5028, 597.355040 -CTUN, 770, 0.20, 0.63, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, -0.67, -2.61, -0.40, 0.00, 49.67, 46.50 -CTUN, 771, 0.20, 0.62, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -1.36, -2.42, 0.87, 0.00, 48.79, 46.50 -CTUN, 771, 0.20, 0.69, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -1.39, -2.42, 1.25, 0.00, 47.96, 46.50 -CTUN, 771, 0.20, 0.68, 0.000000, 0, 0, 19, 770, 0 -ATT, 0.00, -1.12, -2.52, 0.69, 0.00, 47.20, 46.50 -CTUN, 771, 0.20, 0.89, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.00, -1.00, -2.52, 0.15, 0.00, 46.44, 46.50 -CTUN, 771, 0.20, 0.93, 0.000000, 0, 0, 19, 771, 0 -ATT, 0.00, -0.94, -3.17, -0.03, 0.00, 45.73, 46.50 -CTUN, 771, 0.20, 0.91, 0.000000, 0, 0, 23, 771, 0 -ATT, 0.00, -0.30, -3.92, -0.03, 0.00, 45.20, 46.50 -CTUN, 771, 0.23, 0.93, 0.000000, 0, 0, 23, 770, 0 -ATT, 0.00, 0.04, -4.20, -0.47, 0.00, 44.92, 46.50 -CTUN, 771, 0.23, 0.92, 0.000000, 0, 0, 21, 771, 0 -ATT, 0.00, -0.19, -4.20, -1.39, 0.00, 44.75, 46.50 -CTUN, 770, 0.27, 0.99, 0.000000, 0, 0, 17, 770, 0 -ATT, 0.00, 0.33, -4.10, -2.10, 0.00, 44.59, 46.50 -DU32, 7, 166140 -CURR, 770, 799209, 1015, 2088, 5051, 603.138430 -CTUN, 771, 0.27, 0.98, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.46, 0.76, -4.20, -2.21, 0.00, 44.29, 46.50 -CTUN, 771, 0.31, 1.05, 0.000000, 0, 0, 15, 771, 0 -ATT, 1.59, 0.41, -3.92, -1.45, 0.00, 43.78, 46.50 -CTUN, 771, 0.31, 0.99, 0.000000, 0, 0, 10, 771, 0 -ATT, 1.50, 0.98, -3.73, -0.81, 0.00, 43.29, 46.50 -CTUN, 771, 0.35, 0.94, 0.000000, 0, 0, 7, 771, 0 -ATT, 1.59, 1.73, -3.64, -0.31, 0.00, 42.94, 46.50 -CTUN, 770, 0.35, 0.99, 0.000000, 0, 0, 0, 770, 0 -ATT, 1.59, 2.08, -3.92, 0.35, 0.00, 42.60, 46.50 -CTUN, 770, 0.37, 1.19, 0.000000, 0, 0, -3, 771, 0 -ATT, 1.59, 2.41, -4.01, 0.18, 0.00, 42.26, 46.50 -CTUN, 771, 0.37, 1.00, 0.000000, 0, 0, -4, 771, 0 -ATT, 1.59, 1.90, -4.85, -0.40, 0.00, 41.86, 46.50 -CTUN, 771, 0.37, 1.04, 0.000000, 0, 0, -10, 771, 0 -ATT, 1.59, 1.59, -6.34, -1.29, 0.00, 41.46, 46.50 -CTUN, 771, 0.37, 0.93, 0.000000, 0, 0, -12, 770, 0 -ATT, 1.50, 1.84, -6.72, -1.63, 0.00, 41.07, 46.50 -CTUN, 770, 0.37, 1.17, 0.000000, 0, 0, -13, 771, 0 -ATT, 1.59, 2.70, -6.72, -1.41, 0.00, 40.60, 46.50 -DU32, 7, 166140 -CURR, 771, 806918, 1015, 2102, 5051, 608.950930 -CTUN, 771, 0.37, 1.08, 0.000000, 0, 1, -15, 771, 0 -ATT, 1.50, 3.49, -6.81, -1.24, 0.00, 40.25, 46.50 -CTUN, 770, 0.37, 1.10, 0.000000, 0, 1, -17, 772, 0 -ATT, 1.59, 3.91, -6.72, -1.40, 0.00, 40.19, 46.50 -CTUN, 770, 0.34, 1.09, 0.000000, 0, 1, -19, 771, 0 -ATT, 1.59, 3.75, -6.81, -2.34, 0.00, 40.48, 46.50 -CTUN, 771, 0.34, 0.99, 0.000000, 0, 1, -17, 772, 0 -ATT, 1.50, 3.14, -6.81, -3.70, 0.00, 41.26, 46.50 -CTUN, 771, 0.31, 0.99, 0.000000, 0, 2, -19, 773, 0 -ATT, 0.00, 2.40, -6.72, -4.51, 0.00, 42.26, 46.50 -CTUN, 771, 0.31, 0.95, 0.000000, 0, 2, -16, 773, 0 -ATT, 0.00, 0.96, -6.06, -4.26, 0.00, 43.29, 46.50 -CTUN, 770, 0.29, 0.83, 0.000000, 0, 1, -15, 772, 0 -ATT, 0.00, -0.49, -4.38, -3.55, 0.00, 44.03, 46.50 -CTUN, 771, 0.29, 0.96, 0.000000, 0, 1, -10, 771, 0 -ATT, 0.00, -0.63, -3.08, -1.72, 0.00, 44.62, 46.50 -CTUN, 771, 0.27, 0.89, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, -1.08, -3.17, 0.18, 0.00, 45.07, 46.50 -CTUN, 770, 0.27, 1.05, 0.000000, 0, 0, -7, 771, 0 -ATT, 0.00, -1.72, -4.10, 1.55, 0.00, 45.35, 46.50 -DU32, 7, 166140 -CURR, 770, 814635, 1023, 2096, 5051, 614.819150 -CTUN, 771, 0.26, 0.93, 0.000000, 0, 0, -4, 770, 0 -ATT, 0.00, -1.13, -4.85, 1.93, 0.00, 45.60, 46.50 -CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, -0.78, -5.50, 1.05, 0.00, 45.80, 46.50 -CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.66, -6.16, -0.35, 0.00, 45.95, 46.50 -CTUN, 770, 0.26, 0.97, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -0.30, -6.81, -1.66, 0.00, 46.03, 46.50 -CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -0.03, -6.81, -1.76, 0.00, 45.98, 46.50 -CTUN, 770, 0.26, 0.84, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.08, -6.62, -1.65, 0.00, 45.96, 46.50 -CTUN, 771, 0.26, 1.02, 0.000000, 0, 0, 2, 770, 0 -ATT, 0.00, -0.01, -6.53, -2.02, 0.00, 46.04, 46.50 -CTUN, 771, 0.27, 0.94, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -0.17, -6.53, -2.35, 0.00, 46.05, 46.50 -CTUN, 771, 0.27, 1.01, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.18, -6.62, -2.00, 0.00, 45.98, 46.50 -CTUN, 771, 0.27, 1.03, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.00, 0.46, -6.72, -1.96, 0.00, 45.82, 46.50 -DU32, 7, 166140 -CURR, 771, 822341, 1012, 2104, 5028, 620.679630 -CTUN, 771, 0.27, 1.04, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, 0.87, -6.72, -2.28, 0.00, 45.44, 46.50 -CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, 1.52, -6.72, -2.82, 0.00, 44.88, 46.50 -CTUN, 771, 0.28, 0.98, 0.000000, 0, 1, -6, 772, 0 -ATT, 0.00, 1.56, -6.81, -3.03, 0.00, 44.25, 46.50 -CTUN, 771, 0.29, 0.96, 0.000000, 0, 1, -5, 772, 0 -ATT, 0.00, 1.32, -6.81, -2.71, 0.00, 43.57, 46.50 -CTUN, 771, 0.29, 1.02, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 1.46, -6.72, -2.67, 0.00, 42.75, 46.50 -CTUN, 770, 0.29, 0.88, 0.000000, 0, 0, -11, 770, 0 -ATT, 0.00, 1.33, -6.62, -2.16, 0.00, 41.89, 46.50 -CTUN, 771, 0.29, 1.07, 0.000000, 0, 0, -13, 771, 0 -ATT, 0.00, 1.21, -6.53, -1.96, 0.00, 41.25, 46.50 -CTUN, 770, 0.29, 0.82, 0.000000, 0, 0, -11, 770, 0 -ATT, 0.00, 1.70, -6.53, -2.62, 0.00, 40.86, 46.50 -CTUN, 770, 0.28, 0.99, 0.000000, 0, 1, -13, 772, 0 -ATT, 0.00, 1.62, -6.53, -3.03, 0.00, 40.68, 46.50 -CTUN, 771, 0.28, 0.95, 0.000000, 0, 1, -13, 772, 0 -ATT, -1.04, -0.13, -6.53, -3.60, 0.00, 40.79, 46.50 -DU32, 7, 166140 -CURR, 770, 830055, 1015, 2110, 5028, 626.495730 -CTUN, 771, 0.28, 0.98, 0.000000, 0, 1, -11, 772, 0 -ATT, -2.17, -1.90, -5.69, -3.86, 0.00, 41.05, 46.50 -CTUN, 771, 0.28, 1.02, 0.000000, 0, 1, -7, 771, 0 -ATT, -3.22, -2.20, -3.17, -3.59, 0.00, 41.24, 46.50 -CTUN, 771, 0.27, 1.07, 0.000000, 0, 1, -5, 772, 0 -ATT, -3.78, -2.67, -3.73, -2.08, 0.00, 41.38, 46.50 -CTUN, 771, 0.27, 0.95, 0.000000, 0, 1, -3, 771, 0 -ATT, -2.93, -3.84, -2.89, -0.79, 0.00, 41.54, 46.50 -CTUN, 771, 0.27, 1.01, 0.000000, 0, 1, 0, 772, 0 -ATT, -2.65, -4.48, -2.61, -0.06, 0.00, 41.82, 46.50 -CTUN, 771, 0.27, 0.99, 0.000000, 0, 1, -1, 772, 0 -ATT, -2.27, -3.33, -2.24, -0.03, 0.00, 42.07, 46.50 -CTUN, 771, 0.27, 1.05, 0.000000, 0, 0, 0, 770, 0 -ATT, -0.75, -1.44, -2.70, 0.30, 0.00, 42.35, 46.50 -CTUN, 771, 0.27, 0.99, 0.000000, 0, 0, -1, 771, 0 -PM, 0, 0, 0, 0, 1001, 10488, 0, 0 -ATT, 0.00, -1.05, -2.52, 0.77, 0.00, 42.76, 46.50 -CTUN, 771, 0.27, 1.18, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.01, -2.24, 1.03, 0.00, 43.20, 46.50 -CTUN, 770, 0.27, 0.88, 0.000000, 0, 0, -5, 770, 0 -ATT, 0.00, 1.43, -2.52, 1.13, 0.00, 43.61, 46.50 -DU32, 7, 166140 -CURR, 771, 837768, 1013, 2075, 5028, 632.331120 -CTUN, 771, 0.26, 0.90, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, 1.11, -2.52, 1.22, 0.00, 44.06, 46.50 -CTUN, 771, 0.26, 1.03, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, 0.13, -2.52, 0.89, 0.00, 44.51, 46.50 -CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.46, -2.61, -0.39, 0.00, 45.15, 46.50 -CTUN, 770, 0.26, 1.01, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.57, -2.52, -1.18, 0.00, 45.67, 46.50 -CTUN, 770, 0.25, 1.12, 0.000000, 0, 0, 2, 771, 0 -ATT, -1.13, -0.51, -20.91, -1.14, 0.00, 46.09, 46.50 -CTUN, 771, 0.25, 1.10, 0.000000, 0, 0, 3, 771, 0 -ATT, -0.66, -0.68, -2.61, -1.21, 0.00, 46.31, 46.50 -CTUN, 771, 0.25, 0.94, 0.000000, 0, 0, 3, 771, 0 -ATT, -0.75, -1.10, -2.70, -1.37, 0.00, 46.38, 46.50 -CTUN, 771, 0.25, 1.04, 0.000000, 0, 0, 4, 771, 0 -ATT, -0.75, -1.73, -2.61, -1.79, 0.00, 46.42, 46.50 -CTUN, 770, 0.25, 0.87, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -2.42, -2.70, -2.04, 0.00, 46.53, 46.50 -CTUN, 771, 0.26, 1.13, 0.000000, 0, 1, 5, 772, 0 -ATT, 0.00, -2.47, -2.70, -1.63, 0.00, 46.65, 46.50 -DU32, 7, 166140 -CURR, 770, 845478, 1020, 2076, 5051, 638.134460 -CTUN, 770, 0.26, 1.05, 0.000000, 0, 0, 8, 770, 0 -ATT, 0.00, -1.16, -2.70, -0.29, 0.00, 46.82, 46.50 -CTUN, 770, 0.27, 1.05, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.00, -0.11, -2.61, 0.78, 0.00, 47.15, 46.50 -CTUN, 770, 0.27, 0.98, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.37, -2.70, 0.66, 0.00, 47.54, 46.50 -CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.28, -2.70, -0.13, 0.00, 47.84, 46.50 -CTUN, 771, 0.28, 1.07, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -0.01, -2.70, -0.52, 0.00, 48.13, 46.50 -CTUN, 771, 0.29, 1.02, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.12, -2.70, -1.11, 0.00, 48.42, 46.50 -CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -0.52, -2.70, -1.91, 0.00, 48.50, 46.50 -CTUN, 771, 0.28, 0.96, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -0.64, -2.52, -1.97, 0.00, 48.25, 46.50 -CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.48, -2.61, -1.26, 0.00, 47.98, 46.50 -CTUN, 770, 0.28, 1.04, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.33, -2.70, -0.59, 0.00, 47.59, 46.50 -DU32, 7, 166140 -CURR, 770, 853185, 1018, 2086, 5051, 643.938420 -CTUN, 770, 0.28, 1.08, 0.000000, 0, 0, 2, 770, 0 -ATT, 0.00, -0.24, -2.70, -0.61, 0.00, 47.15, 46.50 -CTUN, 771, 0.28, 0.94, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -1.04, -2.70, -0.50, 0.00, 46.79, 46.50 -CTUN, 771, 0.28, 1.12, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -0.95, -2.61, -0.18, 0.00, 46.42, 46.50 -CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.54, -2.70, -0.15, 0.00, 46.08, 46.50 -CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.00, 1.12, -2.70, -0.83, 0.00, 45.98, 46.50 -CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.58, -2.70, -1.30, 0.00, 46.12, 46.50 -CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, 0.65, -2.80, -1.77, 0.00, 46.43, 46.50 -CTUN, 771, 0.28, 1.06, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 1.39, -2.70, -1.79, 0.00, 46.59, 46.50 -CTUN, 771, 0.28, 1.14, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 1.21, -2.61, -1.31, 0.00, 46.77, 46.50 -CTUN, 771, 0.28, 1.26, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.43, -2.70, -0.62, 0.00, 47.28, 46.50 -DU32, 7, 166140 -CURR, 770, 860891, 1016, 2102, 5051, 649.724790 -CTUN, 770, 0.28, 1.17, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, -0.20, -2.61, -0.24, 0.00, 48.04, 46.50 -CTUN, 771, 0.28, 1.12, 0.000000, 0, 0, -1, 770, 0 -ATT, 0.00, -0.11, -2.70, -0.71, 0.00, 48.95, 46.50 -CTUN, 770, 0.28, 0.96, 0.000000, 0, 0, -2, 770, 0 -ATT, 0.00, 0.13, -2.61, -1.50, 0.00, 49.80, 46.50 -CTUN, 771, 0.28, 1.00, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.02, -2.61, -1.72, 0.00, 50.39, 46.50 -CTUN, 771, 0.28, 1.13, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.51, -2.70, -1.59, 0.00, 50.57, 46.50 -CTUN, 771, 0.29, 1.09, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.53, -2.70, -1.18, 0.00, 50.38, 46.50 -CTUN, 771, 0.29, 1.18, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, 0.06, -2.70, -0.41, 0.00, 49.81, 46.50 -CTUN, 771, 0.29, 1.09, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.39, -2.61, 0.13, 0.00, 49.05, 46.50 -CTUN, 770, 0.28, 1.05, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, -0.67, -2.89, -0.34, 0.00, 48.14, 46.50 -CTUN, 771, 0.28, 0.94, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, -1.94, -2.70, -1.10, 0.00, 47.16, 46.50 -DU32, 7, 166140 -CURR, 770, 868600, 1011, 2058, 5051, 655.494930 -CTUN, 771, 0.28, 1.06, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, -1.99, -2.61, -1.26, 0.00, 46.24, 46.50 -CTUN, 771, 0.28, 1.08, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -2.09, -2.89, -0.64, 0.00, 45.42, 46.50 -CTUN, 771, 0.27, 1.08, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, -1.23, -2.70, -0.37, 0.00, 44.96, 46.50 -CTUN, 771, 0.27, 1.09, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.84, -2.70, -0.50, 0.00, 44.88, 46.50 -CTUN, 771, 0.26, 1.04, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.15, -3.08, -0.94, 0.00, 44.99, 46.50 -CTUN, 770, 0.26, 1.00, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, 0.94, -3.64, -0.94, 0.00, 45.21, 46.50 -CTUN, 771, 0.26, 1.15, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, 1.12, -3.92, -1.12, 0.00, 45.54, 46.50 -CTUN, 771, 0.26, 1.15, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.53, -4.76, -1.64, 0.00, 45.94, 46.50 -CTUN, 770, 0.26, 1.10, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, 0.28, -4.76, -2.70, 0.00, 46.38, 46.50 -CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 5, 770, 0 -ATT, 0.00, 0.42, -4.76, -3.30, 0.00, 46.89, 46.50 -DU32, 7, 166140 -CURR, 770, 876308, 1008, 2093, 5051, 661.290470 -CTUN, 771, 0.26, 1.07, 0.000000, 0, 1, 7, 772, 0 -ATT, 0.00, 0.84, -4.76, -2.96, 0.00, 47.44, 46.50 -CTUN, 770, 0.27, 1.07, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, 0.26, -4.57, -2.58, 0.00, 47.98, 46.50 -CTUN, 770, 0.27, 1.07, 0.000000, 0, 0, 8, 770, 0 -ATT, 0.00, -0.67, -4.85, -2.31, 0.00, 48.51, 46.50 -CTUN, 771, 0.29, 1.14, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, -1.63, -4.76, -2.06, 0.00, 48.84, 46.50 -CTUN, 770, 0.29, 1.03, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, -1.79, -4.76, -2.06, 0.00, 48.92, 46.50 -CTUN, 770, 0.31, 1.13, 0.000000, 0, 0, 5, 770, 0 -ATT, 0.00, -1.13, -4.85, -2.42, 0.00, 48.88, 46.50 -CTUN, 770, 0.31, 1.09, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.00, -0.40, -4.76, -2.37, 0.00, 48.76, 46.50 -CTUN, 771, 0.32, 1.07, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 0.30, -4.57, -2.24, 0.00, 48.81, 46.50 -CTUN, 771, 0.32, 1.10, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.11, -4.85, -1.82, 0.00, 48.95, 46.50 -CTUN, 771, 0.33, 1.22, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.78, -4.57, -1.07, 0.00, 49.19, 46.50 -DU32, 7, 166140 -CURR, 770, 884015, 1020, 2108, 5051, 667.150390 -CTUN, 770, 0.33, 1.13, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, -0.88, -4.57, -1.26, 0.00, 49.48, 46.50 -CTUN, 770, 0.34, 1.13, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.14, -4.48, -2.18, 0.00, 49.92, 46.50 -CTUN, 770, 0.34, 1.29, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, 0.35, -4.57, -2.08, 0.00, 50.23, 46.50 -CTUN, 771, 0.35, 1.25, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, 0.15, -4.57, -1.46, 0.00, 50.36, 46.50 -CTUN, 771, 0.35, 1.19, 0.000000, 0, 0, -5, 771, 0 -ATT, 0.00, -0.21, -4.57, -0.73, 0.00, 50.21, 46.50 -CTUN, 771, 0.36, 1.23, 0.000000, 0, 0, -5, 771, 0 -ATT, 0.00, -0.45, -4.57, -0.13, 0.00, 49.79, 46.50 -CTUN, 771, 0.36, 1.36, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, -0.81, -4.48, -0.19, 0.00, 49.22, 46.50 -CTUN, 770, 0.36, 1.31, 0.000000, 0, 0, -8, 770, 0 -ATT, 0.00, -1.24, -4.57, -0.52, 0.00, 48.56, 46.50 -CTUN, 771, 0.35, 1.20, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, -0.99, -4.57, -0.74, 0.00, 47.81, 46.50 -CTUN, 770, 0.35, 1.25, 0.000000, 0, 0, -10, 770, 0 -ATT, 0.00, -0.51, -4.57, -0.64, 0.00, 47.16, 46.50 -DU32, 7, 166140 -CURR, 771, 891724, 1019, 2092, 5028, 672.946110 -CTUN, 771, 0.33, 1.18, 0.000000, 0, 0, -11, 771, 0 -ATT, 0.00, -0.56, -4.57, -0.73, 0.00, 46.92, 46.50 -CTUN, 771, 0.33, 1.19, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, -0.83, -4.57, -1.09, 0.00, 46.97, 46.50 -CTUN, 771, 0.32, 1.26, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.28, -0.92, -4.57, -1.51, 0.00, 47.13, 46.50 -CTUN, 771, 0.32, 1.17, 0.000000, 0, 0, -11, 771, 0 -ATT, 0.37, -0.41, -4.48, -1.53, 0.00, 47.31, 46.50 -CTUN, 771, 0.30, 1.18, 0.000000, 0, 0, -11, 771, 0 -ATT, 0.84, 0.56, -4.57, -1.27, 0.00, 47.54, 46.50 -CTUN, 771, 0.30, 1.09, 0.000000, 0, 0, -8, 771, 0 -ATT, 1.78, 1.39, -4.48, -0.93, 0.00, 47.64, 46.50 -CTUN, 770, 0.28, 1.13, 0.000000, 0, 0, -7, 770, 0 -ATT, 1.87, 2.06, -4.38, -0.86, 0.00, 47.67, 46.50 -CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, -6, 771, 0 -ATT, 1.96, 2.75, -4.38, -1.15, 0.00, 47.75, 46.50 -CTUN, 771, 0.26, 1.01, 0.000000, 0, 1, -5, 772, 0 -ATT, 1.96, 2.52, -4.38, -2.24, 0.00, 47.78, 46.50 -CTUN, 770, 0.26, 0.99, 0.000000, 0, 1, -6, 771, 0 -ATT, 1.96, 1.71, -4.38, -3.36, 0.00, 47.65, 46.50 -DU32, 7, 166140 -CURR, 770, 899431, 1009, 2092, 5051, 678.761660 -CTUN, 770, 0.25, 1.00, 0.000000, 0, 1, -1, 772, 0 -ATT, 1.96, 1.44, -4.38, -3.41, 0.00, 47.48, 46.50 -CTUN, 771, 0.25, 0.96, 0.000000, 0, 1, 0, 772, 0 -ATT, 1.78, 1.30, -4.38, -2.47, 0.00, 47.40, 46.50 -CTUN, 771, 0.24, 1.07, 0.000000, 0, 0, 1, 770, 0 -ATT, 1.78, 0.95, -4.48, -1.28, 0.00, 47.32, 46.50 -CTUN, 771, 0.25, 0.97, 0.000000, 0, 0, 2, 771, 0 -ATT, 1.31, 0.56, -4.57, -0.68, 0.00, 47.31, 46.50 -CTUN, 771, 0.25, 0.98, 0.000000, 0, 0, 0, 771, 0 -ATT, 1.03, 1.01, -4.57, -0.59, 0.00, 47.32, 46.50 -CTUN, 770, 0.25, 1.08, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.65, 0.77, -4.48, -0.98, 0.00, 47.38, 46.50 -CTUN, 770, 0.24, 1.01, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.09, 0.65, -4.57, -1.50, 0.00, 47.43, 46.50 -CTUN, 771, 0.25, 1.10, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 1.05, -4.38, -1.41, 0.00, 47.52, 46.50 -CTUN, 771, 0.25, 1.05, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, 1.28, -4.85, -0.74, 0.00, 47.66, 46.50 -CTUN, 771, 0.26, 1.20, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 1.19, -4.76, -0.12, 0.00, 47.75, 46.50 -DU32, 7, 166140 -CURR, 771, 907141, 1006, 2123, 5051, 684.602050 -CTUN, 771, 0.26, 1.14, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.00, 0.82, -4.76, -0.94, 0.00, 47.74, 46.50 -CTUN, 771, 0.27, 1.10, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.40, -5.69, -1.52, 0.00, 47.68, 46.50 -CTUN, 771, 0.27, 1.08, 0.000000, 0, 0, 5, 770, 0 -ATT, 0.00, -0.51, -6.25, -1.76, 0.00, 47.59, 46.50 -CTUN, 771, 0.28, 1.22, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -1.17, -6.06, -1.86, 0.00, 47.61, 46.50 -CTUN, 770, 0.28, 1.12, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -1.53, -6.06, -1.97, 0.00, 47.53, 46.50 -CTUN, 771, 0.30, 1.22, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.22, -6.06, -2.16, 0.00, 47.15, 46.50 -CTUN, 770, 0.30, 1.08, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -1.18, -6.06, -2.48, 0.00, 46.63, 46.50 -CTUN, 771, 0.30, 1.09, 0.000000, 0, 0, -3, 771, 0 -PM, 0, 0, 0, 0, 1000, 10484, 0, 0 -ATT, 0.00, -1.21, -6.16, -2.52, 0.00, 46.08, 46.50 -CTUN, 771, 0.30, 1.21, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, -0.77, -5.04, -2.21, 0.00, 45.48, 46.50 -CTUN, 771, 0.30, 1.17, 0.000000, 0, 0, -6, 771, 0 -ATT, -0.09, -0.29, -4.85, -2.16, 0.00, 45.05, 46.50 -DU32, 7, 166140 -CURR, 771, 914848, 1018, 2088, 5051, 690.416750 -CTUN, 771, 0.29, 1.17, 0.000000, 0, 0, -6, 770, 0 -ATT, -0.18, -0.25, -5.04, -2.13, 0.00, 44.61, 46.50 -CTUN, 771, 0.29, 1.00, 0.000000, 0, 0, -8, 770, 0 -ATT, -0.18, -0.44, -5.04, -2.25, 0.00, 44.33, 46.50 -CTUN, 771, 0.28, 1.04, 0.000000, 0, 0, -11, 771, 0 -ATT, -0.18, -0.60, -5.04, -2.31, 0.00, 44.14, 46.50 -CTUN, 771, 0.28, 1.01, 0.000000, 0, 0, -11, 770, 0 -ATT, -0.18, -1.08, -5.04, -2.78, 0.00, 44.07, 46.50 -CTUN, 770, 0.26, 1.10, 0.000000, 0, 0, -13, 771, 0 -ATT, -0.18, -0.55, -4.76, -2.54, 0.00, 44.02, 46.50 -CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -8, 771, 0 -ATT, -0.18, 0.35, -4.85, -1.63, 0.00, 43.92, 46.50 -CTUN, 770, 0.25, 1.08, 0.000000, 0, 0, -7, 771, 0 -ATT, 0.00, 0.64, -4.85, -1.05, 0.00, 44.04, 46.50 -CTUN, 771, 0.25, 1.00, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.07, -4.76, -1.23, 0.00, 44.39, 46.50 -CTUN, 770, 0.23, 1.05, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, -0.60, -4.85, -1.87, 0.00, 44.86, 46.50 -CTUN, 771, 0.23, 1.04, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, -0.22, -4.85, -1.94, 0.00, 45.44, 46.50 -DU32, 7, 166140 -CURR, 771, 922554, 1013, 2060, 5028, 696.159300 -CTUN, 770, 0.22, 1.11, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, -0.17, -4.76, -1.44, 0.00, 46.20, 46.50 -CTUN, 771, 0.22, 1.07, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.00, -0.30, -4.76, -1.28, 0.00, 47.03, 46.50 -CTUN, 771, 0.21, 0.99, 0.000000, 0, 0, 2, 771, 0 -ATT, -0.75, -0.13, -2.52, -1.18, 0.00, 47.87, 46.50 -CTUN, 771, 0.21, 1.01, 0.000000, 0, 0, 5, 771, 0 -ATT, -0.75, -0.16, -2.61, -0.63, 0.00, 48.59, 46.50 -CTUN, 771, 0.21, 1.13, 0.000000, 0, 0, 8, 770, 0 -ATT, -0.75, -0.43, -2.70, 0.07, 0.00, 49.09, 46.50 -CTUN, 770, 0.22, 1.07, 0.000000, 0, 0, 8, 771, 0 -ATT, -0.75, -0.26, -2.61, 0.24, 0.00, 49.48, 46.50 -CTUN, 771, 0.22, 0.94, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, 0.06, -2.61, 0.41, 0.00, 49.67, 46.50 -CTUN, 771, 0.23, 1.15, 0.000000, 0, 0, 11, 770, 0 -ATT, 0.00, -0.21, -2.61, 0.29, 0.00, 49.79, 46.50 -CTUN, 771, 0.23, 1.23, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, -0.03, -3.08, -0.10, 0.00, 49.88, 46.50 -CTUN, 770, 0.23, 1.25, 0.000000, 0, 0, 11, 771, 0 -ATT, -0.75, 0.88, -3.08, -0.47, 0.00, 50.00, 46.50 -DU32, 7, 166140 -CURR, 771, 930261, 1010, 2098, 5051, 701.952940 -CTUN, 771, 0.23, 1.11, 0.000000, 0, 0, 11, 771, 0 -ATT, -0.85, 1.22, -3.26, -0.94, 0.00, 50.06, 46.50 -CTUN, 770, 0.25, 1.16, 0.000000, 0, 0, 11, 771, 0 -ATT, -2.17, 0.50, -3.92, -1.96, 0.00, 50.08, 46.50 -CTUN, 771, 0.25, 1.19, 0.000000, 0, 0, 9, 770, 0 -ATT, -2.36, -0.88, -4.10, -2.55, 0.00, 50.03, 46.50 -CTUN, 771, 0.27, 1.11, 0.000000, 0, 0, 9, 771, 0 -ATT, -2.17, -1.81, -4.10, -2.33, 0.00, 49.68, 46.50 -CTUN, 771, 0.27, 1.15, 0.000000, 0, 0, 6, 771, 0 -ATT, -2.27, -1.90, -4.01, -1.68, 0.00, 49.18, 46.50 -CTUN, 770, 0.28, 1.20, 0.000000, 0, 0, 6, 770, 0 -ATT, -2.36, -2.01, -2.33, -0.74, 0.00, 48.58, 46.50 -CTUN, 770, 0.28, 1.21, 0.000000, 0, 0, 6, 771, 0 -ATT, -2.36, -1.94, -2.33, 0.02, 0.00, 47.97, 46.50 -CTUN, 771, 0.28, 1.15, 0.000000, 0, 0, 3, 770, 0 -ATT, -2.36, -1.86, -2.33, 0.19, 0.00, 47.46, 46.50 -CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 1, 771, 0 -ATT, -2.36, -1.23, -2.33, -0.40, 0.00, 47.11, 46.50 -CTUN, 771, 0.28, 1.14, 0.000000, 0, 0, 2, 771, 0 -ATT, -1.98, -1.10, -1.96, -0.69, 0.00, 46.89, 46.50 -DU32, 7, 166140 -CURR, 771, 937968, 1013, 2056, 5051, 707.722410 -CTUN, 771, 0.28, 1.24, 0.000000, 0, 0, 4, 771, 0 -ATT, -1.13, -1.33, -3.26, -0.52, 0.00, 46.77, 46.50 -CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 3, 771, 0 -ATT, -0.75, -1.52, -3.64, -0.61, 0.00, 46.83, 46.50 -CTUN, 771, 0.27, 1.22, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -1.10, -3.73, -1.05, 0.00, 47.09, 46.50 -CTUN, 770, 0.27, 1.09, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -0.27, -3.73, -1.61, 0.00, 47.65, 46.50 -CTUN, 771, 0.27, 1.09, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.37, -3.82, -2.01, 0.00, 48.51, 46.50 -CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, 0.69, -3.26, -1.63, 0.00, 49.43, 46.50 -CTUN, 770, 0.28, 1.20, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 0.32, -3.26, -1.22, 0.00, 50.46, 46.50 -CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -0.11, -3.17, -0.89, 0.00, 51.43, 46.50 -CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -0.51, -3.08, -0.79, 0.00, 52.33, 46.50 -CTUN, 771, 0.28, 1.21, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.50, -3.17, -1.23, 0.00, 52.97, 46.50 -DU32, 7, 166140 -CURR, 771, 945675, 1013, 2123, 5051, 713.567750 -CTUN, 771, 0.28, 1.13, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, 0.75, -3.17, -1.73, 0.00, 53.32, 46.50 -CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, 1.14, -3.26, -1.16, 0.00, 53.58, 46.50 -CTUN, 771, 0.27, 1.23, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.32, -2.70, -0.56, 0.00, 53.62, 46.50 -CTUN, 771, 0.27, 1.15, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, -0.33, -2.70, -0.70, 0.00, 53.43, 46.50 -CTUN, 771, 0.27, 1.30, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, -0.79, -2.61, -0.79, 0.00, 53.05, 46.50 -CTUN, 771, 0.27, 1.23, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -1.29, -2.70, -0.60, 0.00, 52.49, 46.50 -CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.50, -2.70, -0.81, 0.00, 51.93, 46.50 -CTUN, 771, 0.26, 1.21, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.19, -2.61, -0.24, 0.00, 51.33, 46.50 -CTUN, 771, 0.25, 1.24, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.61, -2.61, -0.02, 0.00, 50.56, 46.50 -CTUN, 770, 0.25, 1.18, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -1.19, -2.70, -0.72, 0.00, 49.72, 46.50 -DU32, 7, 166140 -CURR, 770, 953383, 1018, 2094, 5051, 719.391720 -CTUN, 771, 0.25, 1.05, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -1.61, -2.70, -1.89, 0.00, 48.97, 46.50 -CTUN, 770, 0.25, 1.16, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -1.58, -2.89, -2.20, 0.00, 48.46, 46.50 -CTUN, 770, 0.24, 1.08, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -0.59, -2.70, -1.74, 0.00, 48.04, 46.50 -CTUN, 770, 0.25, 0.97, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -0.04, -2.80, -1.16, 0.00, 47.74, 46.50 -CTUN, 771, 0.24, 1.12, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -0.52, -2.80, -1.19, 0.00, 47.54, 46.50 -CTUN, 771, 0.24, 1.25, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.75, -2.80, -1.48, 0.00, 47.45, 46.50 -CTUN, 771, 0.24, 1.21, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -1.42, -2.89, -1.70, 0.00, 47.36, 46.50 -CTUN, 770, 0.25, 1.24, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -2.16, -2.80, -1.46, 0.00, 47.11, 46.50 -CTUN, 771, 0.25, 1.25, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.28, -1.64, -2.80, -0.50, 0.00, 46.60, 46.50 -CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 5, 770, 0 -ATT, 0.46, -0.56, -2.80, 0.15, 0.00, 46.23, 46.50 -DU32, 7, 166140 -CURR, 770, 961091, 1018, 2084, 5051, 725.147890 -CTUN, 771, 0.26, 1.26, 0.000000, 0, 0, 5, 771, 0 -ATT, 2.34, -0.40, -2.80, 0.07, 0.00, 46.23, 46.50 -CTUN, 771, 0.26, 1.13, 0.000000, 0, 0, 3, 771, 0 -ATT, 2.90, -0.02, -2.80, -0.57, 0.00, 46.55, 46.50 -CTUN, 771, 0.26, 1.11, 0.000000, 0, 0, 3, 771, 0 -ATT, 3.28, 1.09, -2.89, -0.66, 0.00, 46.85, 46.50 -CTUN, 770, 0.27, 1.28, 0.000000, 0, 0, 5, 771, 0 -ATT, 3.56, 2.16, -2.80, -0.21, 0.00, 47.03, 46.50 -CTUN, 771, 0.27, 1.17, 0.000000, 0, 0, 3, 771, 0 -ATT, 3.56, 3.67, -2.89, -0.10, 0.00, 47.14, 46.50 -CTUN, 771, 0.27, 1.15, 0.000000, 0, 1, 1, 772, 0 -ATT, 3.65, 4.57, -2.70, -0.32, 0.00, 47.24, 46.50 -CTUN, 771, 0.27, 1.20, 0.000000, 0, 1, 0, 771, 0 -ATT, 3.84, 4.29, -2.70, -0.22, 0.00, 47.28, 46.50 -CTUN, 771, 0.28, 1.16, 0.000000, 0, 1, 0, 772, 0 -ATT, 3.93, 4.07, -2.61, 0.21, 0.00, 47.20, 46.50 -CTUN, 771, 0.28, 1.06, 0.000000, 0, 1, -1, 772, 0 -ATT, 3.93, 4.24, -2.89, 0.46, 0.00, 46.99, 46.50 -CTUN, 771, 0.29, 1.22, 0.000000, 0, 1, -2, 772, 0 -ATT, 3.46, 4.58, -2.89, 0.61, 0.00, 46.77, 46.50 -DU32, 7, 166140 -CURR, 771, 968805, 1008, 2097, 5051, 730.960750 -CTUN, 771, 0.29, 1.17, 0.000000, 0, 2, -5, 773, 0 -ATT, 3.09, 4.54, -3.17, 0.56, 0.00, 46.55, 46.50 -CTUN, 770, 0.29, 1.12, 0.000000, 0, 1, -5, 772, 0 -ATT, 1.40, 4.31, -3.26, 0.44, 0.00, 46.34, 46.50 -CTUN, 771, 0.29, 1.10, 0.000000, 0, 1, -10, 772, 0 -ATT, 0.00, 3.75, -3.26, 0.00, 0.00, 46.09, 46.50 -CTUN, 771, 0.29, 1.01, 0.000000, 0, 0, -14, 771, 0 -ATT, 0.00, 2.31, -3.26, -0.44, 0.00, 45.90, 46.50 -CTUN, 771, 0.29, 1.23, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, 1.33, -4.48, -0.94, 0.00, 45.77, 46.50 -CTUN, 771, 0.29, 1.13, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 0.75, -4.85, -1.66, 0.00, 45.77, 46.50 -CTUN, 771, 0.28, 1.23, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 0.04, -4.66, -2.34, 0.00, 45.90, 46.50 -CTUN, 771, 0.28, 1.10, 0.000000, 0, 0, -15, 771, 0 -ATT, -1.13, -0.75, -4.57, -2.72, 0.00, 46.26, 46.50 -CTUN, 771, 0.26, 1.13, 0.000000, 0, 0, -12, 771, 0 -ATT, -3.69, -1.37, -3.64, -2.88, 0.00, 46.69, 46.50 -CTUN, 771, 0.26, 1.10, 0.000000, 0, 1, -11, 772, 0 -ATT, -4.16, -3.06, -4.10, -2.99, 0.00, 47.29, 46.50 -DU32, 7, 166140 -CURR, 771, 976521, 1013, 2069, 5028, 736.742430 -CTUN, 771, 0.23, 1.00, 0.000000, 0, 2, -11, 772, 0 -ATT, -4.16, -4.87, -4.10, -2.61, 0.00, 47.76, 46.50 -CTUN, 770, 0.23, 1.01, 0.000000, 0, 3, -9, 773, 0 -ATT, -3.97, -5.34, -3.92, -2.10, 0.00, 48.08, 46.50 -CTUN, 771, 0.23, 1.23, 0.000000, 0, 2, -6, 773, 0 -ATT, -3.78, -4.56, -3.92, -1.93, 0.00, 48.23, 46.50 -CTUN, 770, 0.23, 1.27, 0.000000, 0, 1, -1, 772, 0 -ATT, -1.61, -3.52, -3.92, -1.36, 0.00, 48.13, 46.50 -CTUN, 770, 0.21, 1.10, 0.000000, 0, 1, 1, 772, 0 -ATT, 0.00, -2.55, -4.01, -0.86, 0.00, 47.91, 46.50 -CTUN, 771, 0.22, 1.12, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -0.93, -4.10, -0.69, 0.00, 47.50, 46.50 -CTUN, 771, 0.22, 1.28, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, -0.04, -3.92, -1.04, 0.00, 47.05, 46.50 -CTUN, 770, 0.22, 1.03, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, 0.30, -4.01, -1.36, 0.00, 46.47, 46.50 -CTUN, 771, 0.22, 1.09, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, -0.02, -3.92, -1.75, 0.00, 45.91, 46.50 -CTUN, 771, 0.24, 1.15, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, -0.47, -3.92, -2.08, 0.00, 45.34, 46.50 -DU32, 7, 166140 -CURR, 771, 984240, 1019, 2083, 5051, 742.546080 -CTUN, 770, 0.24, 1.24, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.00, -0.14, -4.10, -2.28, 0.00, 44.78, 46.50 -CTUN, 771, 0.27, 1.11, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 1.03, -4.20, -2.77, 0.00, 44.27, 46.50 -CTUN, 770, 0.27, 1.14, 0.000000, 0, 1, 6, 772, 0 -ATT, 0.00, 1.57, -4.20, -3.05, 0.00, 43.83, 46.50 -CTUN, 770, 0.29, 1.18, 0.000000, 0, 1, 5, 772, 0 -ATT, 0.00, 1.30, -4.20, -2.77, 0.00, 43.48, 46.50 -CTUN, 770, 0.29, 1.31, 0.000000, 0, 0, 2, 770, 0 -ATT, 0.00, 0.98, -4.20, -1.94, 0.00, 43.13, 46.50 -CTUN, 771, 0.31, 1.30, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.00, 0.42, -3.92, -1.35, 0.00, 42.85, 46.50 -CTUN, 770, 0.31, 1.26, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, 0.49, -4.20, -0.88, 0.00, 42.61, 46.50 -CTUN, 770, 0.31, 1.34, 0.000000, 0, 0, -5, 771, 0 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -ATT, 0.00, 0.88, -3.73, -0.36, 0.00, 42.34, 46.50 -CTUN, 771, 0.31, 1.34, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, 1.05, -3.17, 0.25, 0.00, 42.08, 46.50 -CTUN, 771, 0.31, 1.24, 0.000000, 0, 0, -9, 771, 0 -ATT, 0.00, 0.87, -3.08, 0.76, 0.00, 41.74, 46.50 -DU32, 7, 166140 -CURR, 770, 991949, 1013, 2063, 5028, 748.299620 -CTUN, 771, 0.31, 1.29, 0.000000, 0, 0, -11, 771, 0 -ATT, 0.00, 0.35, -3.26, 1.31, 0.00, 41.43, 46.50 -CTUN, 770, 0.31, 1.21, 0.000000, 0, 0, -13, 771, 0 -ATT, 0.00, 0.16, -3.26, 1.57, 0.00, 41.21, 46.50 -CTUN, 770, 0.31, 1.26, 0.000000, 0, 0, -14, 771, 0 -ATT, 0.00, 0.51, -3.26, 1.62, 0.00, 41.18, 46.50 -CTUN, 771, 0.31, 1.10, 0.000000, 0, 0, -16, 771, 0 -ATT, 0.00, 0.72, -4.38, 0.94, 0.00, 41.52, 46.50 -CTUN, 769, 0.29, 1.18, 0.000000, 0, 0, -18, 769, 0 -ATT, 0.00, 0.16, -4.48, -0.36, 0.00, 42.05, 46.50 -CTUN, 771, 0.29, 1.13, 0.000000, 0, 0, -20, 770, 0 -ATT, 0.00, -0.29, -4.85, -1.54, 0.00, 42.67, 46.50 -CTUN, 770, 0.26, 1.09, 0.000000, 0, 0, -20, 770, 0 -ATT, 0.00, -0.58, -4.85, -1.94, 0.00, 43.24, 46.50 -CTUN, 770, 0.26, 1.25, 0.000000, 0, 0, -19, 770, 0 -ATT, 0.00, -0.67, -4.85, -2.29, 0.00, 43.70, 46.50 -CTUN, 770, 0.24, 1.09, 0.000000, 0, 0, -17, 770, 0 -ATT, 0.00, -0.23, -4.85, -2.31, 0.00, 44.13, 46.50 -CTUN, 770, 0.24, 1.00, 0.000000, 0, 0, -15, 770, 0 -ATT, 0.00, 0.30, -4.85, -2.24, 0.00, 44.50, 46.50 -DU32, 7, 166140 -CURR, 770, 999651, 1015, 2058, 5051, 754.029660 -CTUN, 770, 0.22, 0.73, 0.000000, 0, 0, -14, 769, 0 -ATT, 0.00, 0.20, -4.76, -1.75, 0.00, 44.82, 46.50 -CTUN, 770, 0.22, 1.04, 0.000000, 0, 0, -12, 770, 0 -ATT, 0.00, 0.30, -4.76, -1.23, 0.00, 45.02, 46.50 -CTUN, 770, 0.20, 1.10, 0.000000, 0, 0, -14, 770, 0 -ATT, 0.00, 0.53, -4.76, -1.01, 0.00, 45.11, 46.50 -CTUN, 770, 0.20, 1.18, 0.000000, 0, 0, -12, 769, 0 -ATT, 0.00, 0.53, -4.76, -1.40, 0.00, 45.15, 46.50 -CTUN, 770, 0.20, 0.72, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.55, -4.85, -1.58, 0.00, 45.17, 46.50 -CTUN, 770, 0.20, 0.72, 0.000000, 0, 0, -3, 770, 0 -ATT, 0.00, 0.31, -4.85, -1.41, 0.00, 45.21, 46.50 -CTUN, 770, 0.20, 1.13, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, 0.45, -4.76, -1.26, 0.00, 45.38, 46.50 -CTUN, 769, 0.20, 1.13, 0.000000, 0, 0, 2, 770, 0 -ATT, -0.37, 0.79, -4.57, -1.62, 0.00, 45.77, 46.50 -CTUN, 771, 0.20, 1.06, 0.000000, 0, 0, 4, 771, 0 -ATT, -0.75, 0.85, -4.57, -1.91, 0.00, 46.21, 46.50 -CTUN, 770, 0.20, 1.08, 0.000000, 0, 0, 3, 770, 0 -ATT, -0.94, 0.16, -4.48, -2.49, 0.00, 46.61, 46.50 -DU32, 7, 166140 -CURR, 771, 1007352, 1013, 2070, 5051, 759.753540 -CTUN, 770, 0.20, 1.10, 0.000000, 0, 0, 2, 771, 0 -ATT, -2.17, -0.25, -4.48, -3.37, 0.00, 47.10, 46.50 -CTUN, 770, 0.21, 1.18, 0.000000, 0, 1, 4, 771, 0 -ATT, -3.31, -1.31, -3.26, -3.36, 0.00, 47.45, 46.50 -CTUN, 769, 0.21, 1.27, 0.000000, 0, 1, 4, 771, 0 -ATT, -3.12, -2.60, -3.08, -2.21, 0.00, 47.58, 46.50 -CTUN, 770, 0.22, 1.23, 0.000000, 0, 1, 0, 771, 0 -ATT, -2.84, -2.84, -2.89, -0.87, 0.00, 47.32, 46.50 -CTUN, 771, 0.22, 1.32, 0.000000, 0, 0, 2, 771, 0 -ATT, -2.65, -2.33, -2.61, 0.01, 0.00, 46.89, 46.50 -CTUN, 769, 0.24, 1.25, 0.000000, 0, 0, -1, 770, 0 -ATT, -2.65, -1.74, -2.61, -0.19, 0.00, 46.43, 46.50 -CTUN, 771, 0.24, 1.32, 0.000000, 0, 0, -1, 771, 0 -ATT, -2.65, -1.64, -2.52, -0.81, 0.00, 46.17, 46.50 -CTUN, 770, 0.25, 1.38, 0.000000, 0, 0, 0, 770, 0 -ATT, -2.08, -2.17, -2.05, -1.14, 0.00, 46.08, 46.50 -CTUN, 771, 0.25, 1.36, 0.000000, 0, 0, -1, 770, 0 -ATT, -3.12, -1.71, -1.58, -1.02, 0.00, 46.09, 46.50 -CTUN, 770, 0.25, 1.35, 0.000000, 0, 0, -4, 771, 0 -ATT, -3.69, -0.61, -1.21, -0.22, 0.00, 46.15, 46.50 -DU32, 7, 166140 -CURR, 769, 1015058, 1015, 2034, 5051, 765.463130 -CTUN, 770, 0.25, 1.15, 0.000000, 0, 0, -7, 770, 0 -ATT, -3.03, -1.82, -1.21, 0.37, 0.00, 46.31, 46.50 -CTUN, 770, 0.26, 1.32, 0.000000, 0, 0, -9, 770, 0 -ATT, -1.23, -3.71, -1.30, 0.03, 0.00, 46.45, 46.50 -CTUN, 769, 0.26, 1.26, 0.000000, 0, 2, -9, 772, 0 -ATT, -0.75, -5.07, -0.74, -0.54, 0.00, 46.49, 46.50 -CTUN, 770, 0.26, 1.30, 0.000000, 0, 1, -10, 771, 0 -ATT, 0.00, -3.26, -1.40, -0.72, 0.00, 46.65, 46.50 -CTUN, 771, 0.26, 1.19, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, -1.93, -1.49, 0.00, 0.00, 46.74, 46.50 -CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -4, 770, 0 -ATT, 0.00, -1.01, -1.68, 0.59, 0.00, 46.79, 46.50 -CTUN, 769, 0.24, 1.35, 0.000000, 0, 0, -3, 770, 0 -ATT, 0.00, -0.92, -2.24, 0.92, 0.00, 46.77, 46.50 -CTUN, 771, 0.24, 1.17, 0.000000, 0, 0, -5, 771, 0 -ATT, 0.00, -0.32, -2.24, 1.13, 0.00, 46.57, 46.50 -CTUN, 771, 0.23, 1.24, 0.000000, 0, 0, -5, 771, 0 -ATT, 0.00, 0.26, -2.52, 0.73, 0.00, 46.28, 46.50 -CTUN, 770, 0.23, 1.33, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.50, -2.70, 0.33, 0.00, 45.97, 46.50 -DU32, 7, 166140 -CURR, 771, 1022765, 1013, 2049, 5028, 771.203310 -CTUN, 771, 0.23, 1.18, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -1.50, -2.52, 0.14, 0.00, 45.69, 46.50 -CTUN, 771, 0.23, 1.19, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -1.16, -2.70, -0.09, 0.00, 45.48, 46.50 -CTUN, 771, 0.23, 1.25, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, -0.14, -2.70, -0.55, 0.00, 45.39, 46.50 -CTUN, 771, 0.23, 1.23, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.03, -2.70, -0.39, 0.00, 45.45, 46.50 -CTUN, 771, 0.23, 1.18, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.28, -0.54, -3.17, -0.18, 0.00, 45.64, 46.50 -CTUN, 770, 0.23, 1.32, 0.000000, 0, 0, 5, 769, 0 -ATT, 1.40, -0.45, -3.26, -0.38, 0.00, 45.96, 46.50 -CTUN, 771, 0.23, 1.30, 0.000000, 0, 0, 4, 771, 0 -ATT, 1.78, 0.39, -3.26, -0.48, 0.00, 46.40, 46.50 -CTUN, 771, 0.24, 1.35, 0.000000, 0, 0, 4, 771, 0 -ATT, 1.96, 0.76, -3.26, -0.46, 0.00, 46.98, 46.50 -CTUN, 771, 0.24, 1.21, 0.000000, 0, 0, 5, 771, 0 -ATT, 2.71, 0.89, -3.26, -0.88, 0.00, 47.41, 46.50 -CTUN, 770, 0.25, 1.26, 0.000000, 0, 0, 5, 771, 0 -ATT, 3.18, 0.87, -3.26, -1.14, 0.00, 47.62, 46.50 -DU32, 7, 166140 -CURR, 770, 1030473, 1015, 2082, 5051, 776.955080 -CTUN, 771, 0.25, 1.32, 0.000000, 0, 0, 5, 771, 0 -ATT, 3.56, 1.24, -3.73, -0.48, 0.00, 47.48, 46.50 -CTUN, 770, 0.26, 1.37, 0.000000, 0, 0, 5, 771, 0 -ATT, 4.31, 2.09, -3.73, 0.20, 0.00, 47.08, 46.50 -CTUN, 771, 0.26, 1.27, 0.000000, 0, 0, 4, 771, 0 -ATT, 4.68, 2.78, -3.82, 0.16, 0.00, 46.53, 46.50 -CTUN, 771, 0.26, 1.43, 0.000000, 0, 1, 2, 772, 0 -ATT, 4.59, 3.36, -4.20, -0.13, 0.00, 45.95, 46.50 -CTUN, 771, 0.26, 1.36, 0.000000, 0, 0, 0, 770, 0 -ATT, 4.59, 2.80, -4.57, -0.22, 0.00, 45.20, 46.50 -CTUN, 771, 0.28, 1.43, 0.000000, 0, 0, 0, 771, 0 -ATT, 3.28, 3.60, -4.85, -0.01, 0.00, 44.44, 46.50 -CTUN, 771, 0.28, 1.31, 0.000000, 0, 2, -3, 773, 0 -ATT, 3.18, 5.02, -5.69, 0.35, 0.00, 43.84, 46.50 -CTUN, 771, 0.28, 1.30, 0.000000, 0, 2, -4, 773, 0 -ATT, 2.53, 4.76, -6.90, 0.02, 0.00, 43.36, 46.50 -CTUN, 771, 0.27, 1.46, 0.000000, 0, 1, -10, 771, 0 -ATT, 1.40, 4.18, -8.21, -1.32, 0.00, 42.96, 46.50 -CTUN, 770, 0.27, 1.24, 0.000000, 0, 2, -12, 773, 0 -ATT, 0.46, 3.38, -8.30, -3.59, 0.00, 42.52, 46.50 -DU32, 7, 166140 -CURR, 771, 1038187, 1013, 2085, 5051, 782.765140 -CTUN, 771, 0.26, 1.39, 0.000000, 0, 2, -12, 773, 0 -ATT, 0.00, 1.37, -8.21, -5.82, 0.00, 42.30, 46.50 -CTUN, 771, 0.26, 1.26, 0.000000, 0, 4, -9, 775, 0 -ATT, 0.00, 1.07, -8.02, -6.66, 0.00, 42.17, 46.50 -CTUN, 770, 0.24, 1.18, 0.000000, 0, 4, -8, 775, 0 -ATT, 0.00, 1.25, -7.46, -6.16, 0.00, 42.18, 46.50 -CTUN, 771, 0.24, 1.16, 0.000000, 0, 3, -7, 774, 0 -ATT, 0.00, 0.84, -6.81, -5.08, 0.00, 42.56, 46.50 -CTUN, 771, 0.23, 1.04, 0.000000, 0, 1, -4, 771, 0 -ATT, 0.00, 1.37, -6.06, -3.40, 0.00, 43.25, 46.50 -CTUN, 771, 0.23, 1.34, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 1.30, -5.78, -1.95, 0.00, 44.08, 46.50 -CTUN, 771, 0.21, 1.16, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.75, -5.88, -1.45, 0.00, 44.79, 46.50 -CTUN, 770, 0.21, 1.32, 0.000000, 0, 0, 2, 770, 0 -ATT, 0.00, 0.03, -5.69, -2.04, 0.00, 45.45, 46.50 -CTUN, 771, 0.21, 1.20, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -1.10, -4.76, -2.77, 0.00, 46.04, 46.50 -CTUN, 771, 0.21, 1.06, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -1.28, -4.57, -2.68, 0.00, 46.47, 46.50 -DU32, 7, 166140 -CURR, 771, 1045909, 1008, 2048, 5051, 788.542110 -CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.50, -3.73, -1.40, 0.00, 46.78, 46.50 -CTUN, 771, 0.20, 1.23, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.56, -3.17, -0.50, 0.00, 46.93, 46.50 -CTUN, 770, 0.20, 1.32, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.00, -1.44, -3.08, -0.57, 0.00, 46.92, 46.50 -CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 13, 770, 0 -ATT, 0.00, -2.28, -3.26, -1.63, 0.00, 46.74, 46.50 -CTUN, 771, 0.20, 1.25, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.00, -1.30, -3.08, -1.86, 0.00, 46.41, 46.50 -CTUN, 771, 0.23, 1.21, 0.000000, 0, 0, 18, 770, 0 -ATT, 0.00, 0.29, -3.26, -1.06, 0.00, 45.89, 46.50 -CTUN, 771, 0.23, 1.38, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, 0.49, -3.17, -0.03, 0.00, 45.34, 46.50 -CTUN, 771, 0.25, 1.34, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, 0.02, -3.26, -0.05, 0.00, 45.07, 46.50 -CTUN, 771, 0.25, 1.31, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.00, -0.33, -3.26, -0.50, 0.00, 45.05, 46.50 -CTUN, 771, 0.27, 1.35, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.00, -0.13, -3.17, -1.13, 0.00, 45.19, 46.50 -DU32, 7, 166140 -CURR, 770, 1053619, 1002, 2075, 5051, 794.314510 -CTUN, 771, 0.27, 1.34, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.01, -3.26, -1.32, 0.00, 45.28, 46.50 -CTUN, 771, 0.30, 1.35, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, -0.35, -3.26, -1.39, 0.00, 45.46, 46.50 -CTUN, 770, 0.30, 1.29, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.59, -3.26, -1.46, 0.00, 45.68, 46.50 -CTUN, 771, 0.30, 1.39, 0.000000, 0, 0, 4, 768, 0 -ATT, 0.00, -0.57, -3.08, -1.17, 0.00, 45.85, 46.50 -CTUN, 771, 0.30, 1.51, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -0.37, -3.26, -0.61, 0.00, 45.99, 46.50 -CTUN, 771, 0.30, 1.45, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.00, -0.49, -3.08, 0.04, 0.00, 46.06, 46.50 -CTUN, 771, 0.30, 1.31, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.00, -1.15, -3.08, -0.17, 0.00, 46.05, 46.50 -CTUN, 771, 0.30, 1.42, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.00, -0.70, -3.17, -0.02, 0.00, 45.92, 46.50 -CTUN, 771, 0.30, 1.42, 0.000000, 0, 0, -5, 771, 0 -ATT, 0.00, 0.63, -2.98, 0.20, 0.00, 45.61, 46.50 -CTUN, 770, 0.30, 1.34, 0.000000, 0, 0, -7, 771, 0 -ATT, 0.00, 1.01, -3.26, 0.40, 0.00, 45.28, 46.50 -DU32, 7, 166140 -CURR, 771, 1061326, 1008, 2033, 5051, 800.036680 -CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.92, -3.26, -0.15, 0.00, 44.89, 46.50 -CTUN, 771, 0.28, 1.29, 0.000000, 0, 0, -12, 770, 0 -ATT, 0.00, 0.56, -3.26, -1.10, 0.00, 44.40, 46.50 -CTUN, 771, 0.26, 1.21, 0.000000, 0, 0, -12, 770, 0 -ATT, 0.00, 0.09, -3.26, -1.18, 0.00, 44.01, 46.50 -CTUN, 771, 0.26, 1.19, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 0.22, -3.17, -0.41, 0.00, 43.77, 46.50 -CTUN, 770, 0.22, 1.16, 0.000000, 0, 0, -10, 770, 0 -ATT, 0.00, 0.11, -3.26, -0.51, 0.00, 43.66, 46.50 -CTUN, 771, 0.22, 1.23, 0.000000, 0, 0, -11, 770, 0 -ATT, 0.00, 0.33, -3.26, -1.02, 0.00, 43.75, 46.50 -CTUN, 771, 0.20, 1.11, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.00, 0.46, -3.17, -1.56, 0.00, 43.99, 46.50 -CTUN, 771, 0.20, 1.10, 0.000000, 0, 0, -1, 771, 0 -PM, 0, 0, 0, 0, 1001, 10480, 0, 0 -ATT, 0.00, 0.43, -3.26, -1.46, 0.00, 44.29, 46.50 -CTUN, 771, 0.20, 0.75, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 0.67, -3.26, -0.83, 0.00, 44.61, 46.50 -CTUN, 771, 0.20, 1.00, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, 0.65, -3.26, -0.31, 0.00, 45.04, 46.50 -DU32, 7, 166140 -CURR, 770, 1069032, 1008, 2046, 5051, 805.722960 -CTUN, 771, 0.20, 0.87, 0.000000, 0, 0, 5, 768, 0 -ATT, 0.00, 0.21, -3.17, -0.08, 0.00, 45.55, 46.50 -CTUN, 771, 0.20, 0.91, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.41, -3.26, 0.01, 0.00, 46.12, 46.50 -CTUN, 770, 0.20, 1.00, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -0.60, -3.26, -0.11, 0.00, 46.70, 46.50 -CTUN, 771, 0.20, 0.81, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, -0.54, -3.26, -1.00, 0.00, 47.25, 46.50 -CTUN, 771, 0.20, 0.92, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, -0.29, -3.26, -1.75, 0.00, 47.55, 46.50 -CTUN, 770, 0.20, 1.32, 0.000000, 0, 0, 18, 771, 0 -ATT, 0.00, -0.18, -4.20, -1.79, 0.00, 47.61, 46.50 -CTUN, 771, 0.20, 1.21, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.00, -0.48, -4.76, -1.67, 0.00, 47.35, 46.50 -CTUN, 771, 0.20, 1.22, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.00, 0.41, -4.76, -1.74, 0.00, 46.99, 46.50 -CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, 1.16, -4.94, -1.70, 0.00, 46.44, 46.50 -CTUN, 771, 0.24, 1.35, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, 0.84, -5.04, -2.14, 0.00, 45.75, 46.50 -DU32, 7, 166140 -CURR, 770, 1076738, 1012, 2045, 5051, 811.423100 -CTUN, 770, 0.24, 1.28, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, 0.22, -5.04, -2.55, 0.00, 44.94, 46.50 -CTUN, 770, 0.27, 1.43, 0.000000, 0, 0, 9, 770, 0 -ATT, 0.00, -0.31, -5.04, -2.39, 0.00, 44.27, 46.50 -CTUN, 771, 0.27, 1.37, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.10, -5.04, -2.11, 0.00, 43.71, 46.50 -CTUN, 770, 0.28, 1.31, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, 0.86, -5.04, -1.75, 0.00, 43.34, 46.50 -CTUN, 771, 0.28, 1.30, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.99, -4.76, -1.43, 0.00, 43.14, 46.50 -CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, -7, 770, 0 -ATT, 0.00, 0.44, -4.85, -0.80, 0.00, 43.07, 46.50 -CTUN, 771, 0.28, 1.45, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.23, -4.76, -0.46, 0.00, 43.03, 46.50 -CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, 0.15, -4.76, -0.82, 0.00, 43.04, 46.50 -CTUN, 770, 0.27, 1.29, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, -0.35, -4.76, -1.10, 0.00, 43.16, 46.50 -CTUN, 771, 0.27, 1.29, 0.000000, 0, 0, -13, 770, 0 -ATT, 0.00, -0.36, -4.76, -1.26, 0.00, 43.31, 46.50 -DU32, 7, 166140 -CURR, 770, 1084445, 1007, 2053, 5051, 817.112060 -CTUN, 771, 0.25, 1.24, 0.000000, 0, 0, -13, 771, 0 -ATT, 0.00, 0.37, -4.76, -1.02, 0.00, 43.38, 46.50 -CTUN, 770, 0.25, 1.27, 0.000000, 0, 0, -13, 771, 0 -ATT, 0.00, 0.36, -4.76, -1.26, 0.00, 43.54, 46.50 -CTUN, 771, 0.23, 1.37, 0.000000, 0, 0, -8, 771, 0 -ATT, 0.00, 0.08, -4.76, -1.66, 0.00, 43.75, 46.50 -CTUN, 771, 0.23, 1.28, 0.000000, 0, 0, -13, 770, 0 -ATT, 0.00, 0.39, -4.76, -2.30, 0.00, 44.02, 46.50 -CTUN, 771, 0.21, 1.29, 0.000000, 0, 0, -12, 771, 0 -ATT, 0.00, 0.61, -4.85, -2.83, 0.00, 44.33, 46.50 -CTUN, 770, 0.21, 1.27, 0.000000, 0, 0, -10, 771, 0 -ATT, 0.00, 0.96, -4.76, -3.05, 0.00, 44.55, 46.50 -CTUN, 771, 0.20, 1.29, 0.000000, 0, 1, -5, 771, 0 -ATT, 0.00, 1.04, -4.76, -2.97, 0.00, 44.86, 46.50 -CTUN, 770, 0.20, 1.25, 0.000000, 0, 0, -6, 771, 0 -ATT, 0.00, 0.59, -4.76, -2.42, 0.00, 45.22, 46.50 -CTUN, 771, 0.20, 1.27, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.00, -0.23, -4.76, -1.39, 0.00, 45.72, 46.50 -CTUN, 771, 0.20, 1.18, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.78, -4.57, -1.20, 0.00, 46.26, 46.50 -DU32, 7, 166140 -CURR, 771, 1092151, 1017, 2067, 5051, 822.834530 -CTUN, 771, 0.20, 1.26, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -0.78, -4.57, -1.25, 0.00, 46.79, 46.50 -CTUN, 771, 0.20, 1.19, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, -0.64, -4.57, -1.11, 0.00, 47.35, 46.50 -CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, -0.80, -4.76, -0.68, 0.00, 47.94, 46.50 -CTUN, 771, 0.20, 1.34, 0.000000, 0, 0, 4, 770, 0 -ATT, 0.00, -0.18, -4.66, -0.58, 0.00, 48.38, 46.50 -CTUN, 771, 0.20, 1.44, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.19, -4.57, -1.04, 0.00, 48.73, 46.50 -CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 0.35, -4.48, -1.50, 0.00, 49.03, 46.50 -CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, 0.95, -4.48, -1.56, 0.00, 49.19, 46.50 -CTUN, 771, 0.22, 1.36, 0.000000, 0, 0, 7, 771, 0 -ATT, 0.00, 1.05, -4.48, -1.38, 0.00, 49.08, 46.50 -CTUN, 771, 0.22, 1.32, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.67, -4.57, -0.98, 0.00, 48.81, 46.50 -CTUN, 771, 0.25, 1.28, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.09, 0.07, -4.38, -0.41, 0.00, 48.50, 46.50 -DU32, 7, 166140 -CURR, 770, 1099860, 1016, 2070, 5051, 828.593200 -CTUN, 771, 0.25, 1.38, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.18, 0.11, -4.38, -0.91, 0.00, 48.18, 46.50 -CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.09, -0.04, -4.38, -1.85, 0.00, 47.91, 46.50 -CTUN, 771, 0.26, 1.26, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.09, -0.50, -4.29, -2.58, 0.00, 47.88, 46.50 -CTUN, 771, 0.27, 1.33, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.09, -0.92, -4.38, -2.92, 0.00, 48.08, 46.50 -CTUN, 771, 0.27, 1.46, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.09, -0.42, -4.38, -2.51, 0.00, 48.35, 46.50 -CTUN, 771, 0.27, 1.36, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.09, -0.14, -4.38, -1.72, 0.00, 48.67, 46.50 -CTUN, 770, 0.27, 1.30, 0.000000, 0, 0, -1, 771, 0 -ATT, 0.09, -0.42, -4.38, -1.21, 0.00, 48.92, 46.50 -CTUN, 770, 0.28, 1.46, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.28, -0.27, -4.29, -1.03, 0.00, 49.06, 46.50 -CTUN, 771, 0.28, 1.48, 0.000000, 0, 0, -2, 771, 0 -ATT, 1.59, 0.30, -2.89, -1.10, 0.00, 49.19, 46.50 -CTUN, 771, 0.28, 1.41, 0.000000, 0, 0, -2, 770, 0 -ATT, 2.34, 0.88, -2.42, -0.61, 0.00, 49.37, 46.50 -DU32, 7, 166140 -CURR, 771, 1107567, 1004, 2063, 5051, 834.336240 -CTUN, 770, 0.28, 1.43, 0.000000, 0, 0, -4, 771, 0 -ATT, 3.00, 1.30, -2.52, 0.49, 0.00, 49.64, 46.50 -CTUN, 771, 0.28, 1.41, 0.000000, 0, 0, -7, 766, 0 -ATT, 3.18, 1.97, -2.42, 0.85, 0.00, 49.91, 46.50 -CTUN, 770, 0.27, 1.48, 0.000000, 0, 0, -9, 771, 0 -ATT, 3.28, 2.17, -2.52, 0.72, 0.00, 50.13, 46.50 -CTUN, 770, 0.27, 1.40, 0.000000, 0, 0, -12, 770, 0 -ATT, 3.09, 2.51, -2.42, 0.95, 0.00, 50.34, 46.50 -CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -13, 771, 0 -ATT, 3.28, 2.75, -2.42, 1.24, 0.00, 50.47, 46.50 -CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -13, 770, 0 -ATT, 3.18, 2.36, -2.42, 1.32, 0.00, 50.63, 46.50 -CTUN, 771, 0.24, 1.28, 0.000000, 0, 0, -14, 771, 0 -ATT, 3.09, 1.85, -2.42, 1.00, 0.00, 50.78, 46.50 -CTUN, 770, 0.24, 1.18, 0.000000, 0, 0, -11, 770, 0 -ATT, 3.18, 1.89, -2.42, 0.60, 0.00, 50.84, 46.50 -CTUN, 771, 0.22, 1.22, 0.000000, 0, 0, -11, 771, 0 -ATT, 2.90, 1.68, -2.61, 0.41, 0.00, 50.87, 46.50 -CTUN, 771, 0.22, 1.16, 0.000000, 0, 0, -10, 770, 0 -ATT, 2.81, 0.76, -2.70, 0.24, 0.00, 50.90, 46.50 -DU32, 7, 166140 -CURR, 771, 1115275, 1002, 2065, 5051, 840.063660 -CTUN, 770, 0.20, 1.13, 0.000000, 0, 0, -11, 771, 0 -ATT, 2.90, 0.46, -2.89, -0.24, 0.00, 50.90, 46.50 -CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, -6, 770, 0 -ATT, 2.90, 0.81, -3.08, -0.55, 0.00, 50.75, 46.50 -CTUN, 770, 0.20, 1.11, 0.000000, 0, 0, -2, 771, 0 -ATT, 2.62, 1.42, -3.26, -0.91, 0.00, 50.45, 46.50 -CTUN, 771, 0.20, 1.11, 0.000000, 0, 0, 0, 770, 0 -ATT, 2.71, 2.28, -3.26, -2.07, 0.00, 50.08, 46.50 -CTUN, 771, 0.20, 1.14, 0.000000, 0, 1, 2, 771, 0 -ATT, 2.81, 2.57, -3.17, -2.93, 0.00, 49.46, 46.50 -CTUN, 771, 0.20, 1.08, 0.000000, 0, 1, 4, 772, 0 -ATT, 2.62, 2.21, -3.26, -2.85, 0.00, 48.88, 46.50 -CTUN, 771, 0.20, 1.13, 0.000000, 0, 0, 9, 770, 0 -ATT, 2.53, 1.51, -3.26, -2.09, 0.00, 48.29, 46.50 -CTUN, 770, 0.20, 0.93, 0.000000, 0, 0, 7, 771, 0 -ATT, 2.53, 1.47, -2.70, -1.59, 0.00, 47.75, 46.50 -CTUN, 771, 0.20, 1.25, 0.000000, 0, 0, 9, 770, 0 -ATT, 1.87, 1.68, -2.61, -1.44, 0.00, 47.30, 46.50 -CTUN, 771, 0.20, 1.24, 0.000000, 0, 0, 8, 770, 0 -ATT, 1.03, 1.58, -2.61, -1.38, 0.00, 46.97, 46.50 -DU32, 7, 166140 -CURR, 771, 1122988, 1004, 2056, 5028, 845.803220 -CTUN, 771, 0.20, 1.23, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.00, 1.15, -2.61, -1.05, 0.00, 46.71, 46.50 -CTUN, 770, 0.21, 1.29, 0.000000, 0, 0, 8, 770, 0 -ATT, 0.00, 0.43, -2.70, -0.52, 0.00, 46.42, 46.50 -CTUN, 770, 0.21, 1.35, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.22, -2.61, -0.31, 0.00, 46.13, 46.50 -CTUN, 771, 0.23, 1.27, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 0.50, -2.70, -0.62, 0.00, 45.98, 46.50 -CTUN, 771, 0.23, 1.40, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.00, 0.97, -2.70, -0.84, 0.00, 45.97, 46.50 -CTUN, 771, 0.25, 1.33, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.99, -2.70, -1.06, 0.00, 46.04, 46.50 -CTUN, 771, 0.25, 1.35, 0.000000, 0, 0, 2, 770, 0 -ATT, 0.00, 0.74, -2.70, -1.25, 0.00, 46.27, 46.50 -CTUN, 771, 0.25, 1.42, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.00, 1.29, -2.52, -1.27, 0.00, 46.60, 46.50 -CTUN, 770, 0.25, 1.32, 0.000000, 0, 0, -1, 770, 0 -ATT, -2.55, 1.67, -2.52, -1.37, 0.00, 46.89, 46.50 -CTUN, 771, 0.26, 1.23, 0.000000, 0, 0, 1, 770, 0 -ATT, -4.54, 0.61, -2.33, -1.04, 0.00, 47.08, 46.50 -DU32, 7, 166140 -CURR, 771, 1130697, 999, 2070, 5028, 851.504210 -CTUN, 771, 0.25, 1.50, 0.000000, 0, 0, 0, 771, 0 -ATT, -6.25, -1.41, -2.14, -0.79, 0.00, 47.25, 46.50 -CTUN, 771, 0.25, 1.47, 0.000000, 0, 0, -4, 771, 0 -ATT, -6.06, -3.70, -2.05, -1.55, 0.00, 47.54, 46.50 -CTUN, 770, 0.25, 1.47, 0.000000, 0, 2, -5, 772, 0 -ATT, -6.53, -4.95, -2.05, -2.92, 0.00, 47.91, 46.50 -CTUN, 770, 0.26, 1.48, 0.000000, 0, 3, -4, 773, 0 -ATT, -6.72, -4.84, -2.05, -2.81, 0.00, 48.10, 46.50 -CTUN, 771, 0.26, 1.51, 0.000000, 0, 2, -6, 773, 0 -ATT, -6.72, -4.61, -1.86, -0.91, 0.00, 47.94, 46.50 -CTUN, 770, 0.26, 1.38, 0.000000, 0, 1, -7, 772, 0 -ATT, -5.77, -4.30, -1.58, 0.74, 0.00, 47.58, 46.50 -CTUN, 771, 0.25, 1.31, 0.000000, 0, 1, -8, 772, 0 -ATT, -5.49, -4.22, -1.40, 0.87, 0.00, 47.16, 46.50 -CTUN, 771, 0.25, 1.44, 0.000000, 0, 1, -10, 772, 0 -ATT, -5.30, -4.12, -1.40, 0.21, 0.00, 46.67, 46.50 -CTUN, 771, 0.25, 1.43, 0.000000, 0, 1, -7, 772, 0 -ATT, -4.45, -4.12, -1.40, 0.17, 0.00, 46.00, 46.50 -CTUN, 771, 0.25, 1.42, 0.000000, 0, 1, -4, 772, 0 -ATT, -3.69, -3.75, -1.40, 0.94, 0.00, 45.13, 46.50 -DU32, 7, 166140 -CURR, 769, 1138417, 1015, 2039, 5051, 857.233220 -CTUN, 770, 0.23, 1.30, 0.000000, 0, 1, 0, 772, 0 -ATT, -3.88, -3.06, -1.21, 1.33, 0.00, 44.35, 46.50 -CTUN, 771, 0.24, 1.34, 0.000000, 0, 1, 1, 772, 0 -ATT, -0.85, -2.75, -2.52, 1.66, 0.00, 43.60, 46.50 -CTUN, 771, 0.23, 1.34, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, -2.00, -2.52, 1.16, 0.00, 43.11, 46.50 -CTUN, 771, 0.23, 1.41, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.22, -3.92, 0.13, 0.00, 42.81, 46.50 -CTUN, 770, 0.20, 1.23, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 1.83, -4.20, -0.76, 0.00, 42.75, 46.50 -CTUN, 771, 0.20, 1.37, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.00, 2.22, -4.38, -1.31, 0.00, 42.85, 46.50 -CTUN, 771, 0.20, 1.47, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.00, 1.37, -4.38, -1.69, 0.00, 43.10, 46.50 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 771, 0.20, 1.17, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, 0.49, -4.57, -2.29, 0.00, 43.41, 46.50 -CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, 0.61, -4.48, -2.26, 0.00, 43.82, 46.50 -CTUN, 770, 0.20, 0.97, 0.000000, 0, 0, 9, 770, 0 -ATT, 0.00, 0.48, -4.57, -2.22, 0.00, 44.37, 46.50 -DU32, 7, 166140 -CURR, 771, 1146128, 1006, 2037, 5051, 862.919490 -CTUN, 770, 0.20, 1.41, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.00, 0.15, -4.57, -1.77, 0.00, 44.96, 46.50 -CTUN, 771, 0.20, 1.51, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.00, 0.09, -4.48, -1.36, 0.00, 45.53, 46.50 -CTUN, 771, 0.20, 1.33, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, 0.52, -4.57, -1.08, 0.00, 45.99, 46.50 -CTUN, 771, 0.22, 1.41, 0.000000, 0, 0, 15, 770, 0 -ATT, 0.00, 0.26, -4.66, -0.83, 0.00, 46.32, 46.50 -CTUN, 770, 0.22, 1.41, 0.000000, 0, 0, 15, 770, 0 -ATT, 0.28, -0.32, -4.76, -1.10, 0.00, 46.48, 46.50 -CTUN, 771, 0.23, 1.46, 0.000000, 0, 0, 14, 771, 0 -ATT, 0.46, -0.03, -4.66, -2.53, 0.00, 46.63, 46.50 -CTUN, 771, 0.23, 1.61, 0.000000, 0, 1, 11, 771, 0 -ATT, 0.46, 0.33, -4.76, -3.69, 0.00, 46.59, 46.50 -CTUN, 770, 0.25, 1.42, 0.000000, 0, 1, 14, 772, 0 -ATT, 0.46, 0.11, -4.76, -3.65, 0.00, 46.36, 46.50 -CTUN, 770, 0.25, 1.41, 0.000000, 0, 1, 10, 772, 0 -ATT, 0.46, -0.06, -4.76, -3.46, 0.00, 46.09, 46.50 -CTUN, 771, 0.27, 1.52, 0.000000, 0, 1, 11, 771, 0 -ATT, 0.46, -0.35, -4.57, -2.87, 0.00, 45.71, 46.50 -DU32, 7, 166140 -CURR, 770, 1153836, 1006, 2060, 5051, 868.642330 -CTUN, 771, 0.27, 1.49, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.46, -0.69, -4.57, -1.53, 0.00, 45.30, 46.50 -CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.28, -0.82, -2.61, -0.14, 0.00, 44.91, 46.50 -CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, 10, 771, 0 -ATT, 1.03, -1.07, -2.24, 1.09, 0.00, 44.70, 46.50 -CTUN, 770, 0.28, 1.70, 0.000000, 0, 0, 5, 771, 0 -ATT, 1.87, -0.62, -2.14, 2.30, 0.00, 44.77, 46.50 -CTUN, 771, 0.28, 1.55, 0.000000, 0, 0, 3, 771, 0 -ATT, 2.90, -0.07, -2.24, 2.65, 0.00, 45.04, 46.50 -CTUN, 771, 0.28, 1.54, 0.000000, 0, 0, 0, 771, 0 -ATT, 2.90, 1.08, -2.24, 1.82, 0.00, 45.50, 46.50 -CTUN, 771, 0.28, 1.60, 0.000000, 0, 0, -1, 771, 0 -ATT, 2.90, 2.48, -2.52, 0.80, 0.00, 46.05, 46.50 -CTUN, 771, 0.28, 1.54, 0.000000, 0, 0, -2, 771, 0 -ATT, 2.90, 2.47, -2.61, -0.06, 0.00, 46.48, 46.50 -CTUN, 770, 0.27, 1.55, 0.000000, 0, 0, -2, 770, 0 -ATT, 2.81, 1.76, -2.52, -0.47, 0.00, 46.81, 46.50 -CTUN, 771, 0.27, 1.35, 0.000000, 0, 0, -1, 770, 0 -ATT, 2.71, 1.41, -3.26, -0.63, 0.00, 47.12, 46.50 -DU32, 7, 166140 -CURR, 770, 1161540, 1007, 2061, 5051, 874.380550 -CTUN, 771, 0.27, 1.39, 0.000000, 0, 0, -3, 770, 0 -ATT, 2.71, 1.74, -3.26, -0.66, 0.00, 47.22, 46.50 -CTUN, 771, 0.27, 1.29, 0.000000, 0, 0, -3, 771, 0 -ATT, 2.81, 1.56, -3.45, -0.85, 0.00, 47.09, 46.50 -CTUN, 771, 0.25, 1.25, 0.000000, 0, 0, -4, 770, 0 -ATT, 2.81, 1.29, -4.20, -0.93, 0.00, 46.75, 46.50 -CTUN, 771, 0.25, 1.39, 0.000000, 0, 0, -5, 771, 0 -ATT, 2.53, 1.90, -4.38, -1.00, 0.00, 46.24, 46.50 -CTUN, 771, 0.22, 1.24, 0.000000, 0, 0, -7, 771, 0 -ATT, 2.53, 2.66, -4.57, -1.32, 0.00, 45.73, 46.50 -CTUN, 771, 0.22, 1.30, 0.000000, 0, 1, -6, 771, 0 -ATT, 2.53, 3.40, -4.48, -1.94, 0.00, 45.16, 46.50 -CTUN, 770, 0.20, 1.39, 0.000000, 0, 1, -6, 771, 0 -ATT, 2.06, 3.63, -4.57, -2.39, 0.00, 44.69, 46.50 -CTUN, 770, 0.20, 1.22, 0.000000, 0, 1, -3, 772, 0 -ATT, 1.59, 3.36, -4.48, -2.66, 0.00, 44.33, 46.50 -CTUN, 771, 0.20, 1.46, 0.000000, 0, 1, -5, 772, 0 -ATT, 0.37, 2.58, -4.38, -3.00, 0.00, 44.02, 46.50 -CTUN, 771, 0.20, 1.28, 0.000000, 0, 1, 0, 772, 0 -ATT, 0.00, 1.68, -2.80, -3.02, 0.00, 43.81, 46.50 -DU32, 7, 166140 -CURR, 771, 1169248, 1015, 2060, 5051, 880.068730 -CTUN, 770, 0.20, 1.19, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.00, 0.54, -2.42, -2.06, 0.00, 43.75, 46.50 -CTUN, 771, 0.20, 1.43, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.60, -2.52, -0.21, 0.00, 43.84, 46.50 -CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -1.34, -2.42, 0.97, 0.00, 43.98, 46.50 -CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, -1.65, -2.52, 1.11, 0.00, 44.21, 46.50 -CTUN, 771, 0.20, 1.29, 0.000000, 0, 0, 13, 770, 0 -ATT, 0.00, -1.86, -2.61, 0.53, 0.00, 44.44, 46.50 -CTUN, 771, 0.20, 1.46, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.00, -2.20, -2.70, 0.29, 0.00, 44.72, 46.50 -CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 19, 771, 0 -ATT, 0.00, -1.46, -2.61, -0.22, 0.00, 44.99, 46.50 -CTUN, 770, 0.21, 1.50, 0.000000, 0, 0, 17, 770, 0 -ATT, 0.00, -0.49, -2.61, -0.69, 0.00, 45.24, 46.50 -CTUN, 771, 0.21, 1.41, 0.000000, 0, 0, 19, 771, 0 -ATT, 0.00, -0.22, -2.70, -0.63, 0.00, 45.37, 46.50 -CTUN, 771, 0.22, 1.41, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.00, -0.50, -2.80, -0.16, 0.00, 45.36, 46.50 -DU32, 7, 166140 -CURR, 770, 1176957, 1015, 2061, 5051, 885.775390 -CTUN, 770, 0.22, 1.45, 0.000000, 0, 0, 18, 770, 0 -ATT, 0.00, 0.05, -2.89, 0.18, 0.00, 45.08, 46.50 -CTUN, 771, 0.25, 1.49, 0.000000, 0, 0, 14, 770, 0 -ATT, 0.00, 0.96, -3.26, 0.16, 0.00, 44.63, 46.50 -CTUN, 771, 0.25, 1.33, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.00, 1.95, -4.38, -0.65, 0.00, 44.00, 46.50 -CTUN, 770, 0.26, 1.56, 0.000000, 0, 0, 11, 770, 0 -ATT, 0.00, 2.75, -4.57, -1.82, 0.00, 43.38, 46.50 -CTUN, 771, 0.26, 1.52, 0.000000, 0, 1, 13, 771, 0 -ATT, 0.00, 2.58, -4.76, -2.61, 0.00, 43.01, 46.50 -CTUN, 771, 0.28, 1.46, 0.000000, 0, 1, 9, 771, 0 -ATT, 0.00, 2.24, -4.57, -3.54, 0.00, 42.87, 46.50 -CTUN, 771, 0.28, 1.50, 0.000000, 0, 1, 8, 772, 0 -ATT, -0.37, 1.44, -4.38, -4.01, 0.00, 42.73, 46.50 -CTUN, 771, 0.28, 1.55, 0.000000, 0, 1, 9, 772, 0 -ATT, -2.36, 1.14, -2.33, -3.30, 0.00, 42.52, 46.50 -CTUN, 770, 0.28, 1.47, 0.000000, 0, 0, 5, 771, 0 -ATT, -2.27, 0.33, -2.24, -1.92, 0.00, 42.30, 46.50 -CTUN, 771, 0.29, 1.51, 0.000000, 0, 0, 2, 771, 0 -ATT, -2.08, -0.61, -2.05, -0.58, 0.00, 42.00, 46.50 -DU32, 7, 166140 -CURR, 770, 1184664, 1008, 2065, 5051, 891.542660 -CTUN, 770, 0.29, 1.63, 0.000000, 0, 0, 0, 771, 0 -ATT, -3.88, -0.88, -2.05, 0.01, 0.00, 41.75, 46.50 -CTUN, 771, 0.29, 1.69, 0.000000, 0, 0, -4, 771, 0 -ATT, -4.35, -1.73, -2.24, -0.03, 0.00, 41.69, 46.50 -CTUN, 771, 0.29, 1.50, 0.000000, 0, 0, -5, 771, 0 -ATT, -4.73, -2.82, -2.52, -0.84, 0.00, 41.90, 46.50 -CTUN, 770, 0.29, 1.56, 0.000000, 0, 1, -6, 772, 0 -ATT, -4.83, -3.73, -2.42, -1.18, 0.00, 42.30, 46.50 -CTUN, 771, 0.26, 1.41, 0.000000, 0, 1, -6, 772, 0 -ATT, -4.35, -3.94, -2.52, -0.95, 0.00, 42.83, 46.50 -CTUN, 770, 0.26, 1.36, 0.000000, 0, 1, -1, 772, 0 -ATT, -4.35, -3.60, -2.52, -0.34, 0.00, 43.34, 46.50 -CTUN, 770, 0.24, 1.49, 0.000000, 0, 1, -4, 771, 0 -ATT, -2.55, -3.39, -2.42, -0.13, 0.00, 43.81, 46.50 -CTUN, 771, 0.24, 1.69, 0.000000, 0, 0, -2, 771, 0 -ATT, -2.46, -2.92, -2.42, -0.61, 0.00, 44.36, 46.50 -CTUN, 771, 0.20, 1.52, 0.000000, 0, 0, 0, 771, 0 -ATT, -2.36, -2.82, -2.42, -0.75, 0.00, 45.02, 46.50 -CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 0, 771, 0 -ATT, -2.55, -2.69, -2.52, -1.04, 0.00, 45.67, 46.50 -DU32, 7, 166140 -CURR, 771, 1192375, 1010, 2039, 5028, 897.232540 -CTUN, 770, 0.20, 1.59, 0.000000, 0, 0, 4, 771, 0 -ATT, -2.46, -3.17, -2.52, -0.85, 0.00, 46.13, 46.50 -CTUN, 771, 0.20, 1.41, 0.000000, 0, 1, 8, 772, 0 -ATT, -2.36, -3.96, -2.33, -0.36, 0.00, 46.41, 46.50 -CTUN, 771, 0.20, 1.57, 0.000000, 0, 1, 14, 772, 0 -ATT, -1.80, -3.28, -1.77, -0.07, 0.00, 46.45, 46.50 -CTUN, 771, 0.20, 1.39, 0.000000, 0, 0, 16, 770, 0 -ATT, -0.94, -2.49, -2.61, 0.09, 0.00, 46.33, 46.50 -CTUN, 771, 0.20, 1.34, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.00, -2.13, -2.52, 0.30, 0.00, 46.17, 46.50 -CTUN, 770, 0.20, 1.38, 0.000000, 0, 0, 24, 770, 0 -ATT, 0.00, -1.45, -2.80, 0.16, 0.00, 46.09, 46.50 -CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 23, 771, 0 -ATT, 0.00, -1.20, -3.08, -0.05, 0.00, 46.05, 46.50 -CTUN, 771, 0.21, 1.51, 0.000000, 0, 0, 23, 771, 0 -ATT, 0.00, -0.82, -3.26, -0.38, 0.00, 46.02, 46.50 -CTUN, 770, 0.21, 1.56, 0.000000, 0, 0, 21, 770, 0 -ATT, 0.00, -0.02, -3.26, -0.76, 0.00, 46.07, 46.50 -CTUN, 771, 0.22, 1.49, 0.000000, 0, 0, 24, 771, 0 -ATT, 0.00, 0.14, -3.26, -1.44, 0.00, 46.04, 46.50 -DU32, 7, 166140 -CURR, 771, 1200085, 1005, 2054, 5051, 902.959410 -CTUN, 771, 0.22, 1.60, 0.000000, 0, 0, 24, 771, 0 -ATT, 0.00, 0.73, -3.45, -1.68, 0.00, 45.94, 46.50 -CTUN, 771, 0.24, 1.54, 0.000000, 0, 0, 26, 771, 0 -ATT, 0.00, 1.37, -3.26, -1.60, 0.00, 45.67, 46.50 -CTUN, 770, 0.24, 1.62, 0.000000, 0, 0, 22, 770, 0 -ATT, 0.09, 1.11, -3.45, -1.16, 0.00, 45.30, 46.50 -CTUN, 770, 0.27, 1.62, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.18, 0.91, -3.26, -0.81, 0.00, 44.83, 46.50 -CTUN, 771, 0.27, 1.66, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.28, 1.07, -3.45, -0.62, 0.00, 44.44, 46.50 -CTUN, 771, 0.29, 1.58, 0.000000, 0, 0, 17, 771, 0 -ATT, 0.37, 1.08, -3.45, -0.51, 0.00, 44.15, 46.50 -CTUN, 771, 0.29, 1.64, 0.000000, 0, 0, 11, 770, 0 -ATT, 0.46, 0.49, -3.54, -0.43, 0.00, 44.12, 46.50 -CTUN, 771, 0.31, 1.57, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.37, 0.62, -3.54, -0.41, 0.00, 44.31, 46.50 -CTUN, 770, 0.31, 1.68, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.18, 1.22, -3.26, -0.39, 0.00, 44.57, 46.50 -CTUN, 770, 0.31, 1.56, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.28, 1.27, -3.17, -0.22, 0.00, 44.92, 46.50 -DU32, 7, 166140 -CURR, 771, 1207791, 999, 2057, 5051, 908.689450 -CTUN, 771, 0.31, 1.77, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.46, 1.09, -3.45, -0.28, 0.00, 45.44, 46.50 -CTUN, 771, 0.31, 1.64, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.46, 0.96, -3.45, -0.50, 0.00, 45.81, 46.50 -CTUN, 771, 0.31, 1.66, 0.000000, 0, 0, -4, 771, 0 -ATT, 0.28, 1.43, -3.54, -0.67, 0.00, 46.22, 46.50 -CTUN, 770, 0.31, 1.48, 0.000000, 0, 0, -2, 771, 0 -ATT, 0.28, 1.93, -3.92, -1.00, 0.00, 46.73, 46.50 -CTUN, 770, 0.28, 1.57, 0.000000, 0, 0, -1, 770, 0 -ATT, 0.37, 2.11, -4.38, -1.29, 0.00, 47.25, 46.50 -CTUN, 771, 0.28, 1.60, 0.000000, 0, 0, 1, 771, 0 -ATT, 0.28, 1.90, -4.38, -1.78, 0.00, 47.69, 46.50 -CTUN, 771, 0.26, 1.54, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.28, 0.99, -4.38, -2.30, 0.00, 48.00, 46.50 -CTUN, 771, 0.26, 1.56, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.18, 0.74, -4.38, -2.31, 0.00, 48.23, 46.50 -CTUN, 771, 0.24, 1.54, 0.000000, 0, 0, 1, 770, 0 -ATT, 0.18, 0.65, -4.20, -1.84, 0.00, 48.42, 46.50 -CTUN, 771, 0.24, 1.45, 0.000000, 0, 0, 3, 770, 0 -ATT, 0.00, 0.07, -3.73, -1.18, 0.00, 48.64, 46.50 -DU32, 7, 166140 -CURR, 771, 1215500, 1002, 2093, 5028, 914.448360 -CTUN, 771, 0.23, 1.51, 0.000000, 0, 0, 3, 771, 0 -ATT, 0.00, -0.89, -3.36, -0.97, 0.00, 48.84, 46.50 -CTUN, 770, 0.23, 1.48, 0.000000, 0, 0, 5, 771, 0 -ATT, 0.00, -0.59, -3.26, -0.71, 0.00, 49.11, 46.50 -CTUN, 770, 0.21, 1.47, 0.000000, 0, 0, 6, 771, 0 -ATT, 0.00, -0.10, -3.08, 0.00, 0.00, 49.57, 46.50 -CTUN, 771, 0.21, 1.48, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.29, -2.61, 0.79, 0.00, 50.28, 46.50 -CTUN, 770, 0.21, 1.44, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.00, -1.16, -2.61, 0.82, 0.00, 50.87, 46.50 -CTUN, 771, 0.21, 1.46, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.00, -0.89, -2.61, 0.60, 0.00, 51.34, 46.50 -CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.50, -3.26, 0.73, 0.00, 51.63, 46.50 -PM, 0, 0, 0, 0, 1000, 10480, 0, 0 -CTUN, 771, 0.21, 1.46, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.00, -0.39, -4.01, 0.67, 0.00, 51.69, 46.50 -CTUN, 770, 0.21, 1.52, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.00, -0.83, -4.57, 0.34, 0.00, 51.68, 46.50 -CTUN, 771, 0.22, 1.52, 0.000000, 0, 0, 12, 770, 0 -ATT, 0.00, -1.11, -4.76, -0.53, 0.00, 51.49, 46.50 -DU32, 7, 166140 -CURR, 771, 1223209, 1012, 2067, 5051, 920.225280 -CTUN, 771, 0.22, 1.57, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -1.30, -5.22, -1.44, 0.00, 51.20, 46.50 -CTUN, 771, 0.23, 1.54, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.00, -0.58, -6.34, -1.58, 0.00, 50.81, 46.50 -CTUN, 771, 0.23, 1.52, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.84, 0.49, -6.25, -0.75, 0.00, 50.48, 46.50 -CTUN, 771, 0.24, 1.51, 0.000000, 0, 0, 11, 771, 0 -ATT, 1.50, 1.44, -6.16, -0.05, 0.00, 50.24, 46.50 -CTUN, 771, 0.24, 1.75, 0.000000, 0, 0, 8, 771, 0 -ATT, 1.78, 1.93, -6.06, -0.47, 0.00, 50.10, 46.50 -CTUN, 770, 0.25, 1.67, 0.000000, 0, 0, 8, 771, 0 -ATT, 1.87, 1.28, -6.06, -2.00, 0.00, 49.98, 46.50 -CTUN, 771, 0.25, 1.47, 0.000000, 0, 0, 8, 771, 0 -ATT, 1.40, 1.20, -6.53, -2.57, 0.00, 49.98, 46.50 -CTUN, 770, 0.25, 1.59, 0.000000, 0, 0, 6, 770, 0 -ATT, 0.28, 1.91, -6.53, -2.32, 0.00, 50.19, 46.50 -CTUN, 770, 0.25, 1.61, 0.000000, 0, 0, 7, 770, 0 -ATT, 0.46, 1.23, -6.81, -2.25, 0.00, 50.58, 46.50 -CTUN, 771, 0.25, 1.53, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.46, 0.69, -6.81, -1.79, 0.00, 50.97, 46.50 -DU32, 7, 166140 -CURR, 771, 1230918, 1003, 2082, 5051, 925.962770 -CTUN, 771, 0.25, 1.55, 0.000000, 0, 0, 4, 771, 0 -ATT, 0.46, 0.53, -6.72, -2.01, 0.00, 51.21, 46.50 -CTUN, 771, 0.25, 1.75, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.46, 0.26, -6.81, -2.51, 0.00, 51.26, 46.50 -CTUN, 771, 0.25, 1.69, 0.000000, 0, 0, 0, 771, 0 -ATT, 0.37, 0.11, -6.81, -2.36, 0.00, 51.07, 46.50 -CTUN, 771, 0.25, 1.65, 0.000000, 0, 0, -2, 770, 0 -ATT, 0.09, -0.08, -6.81, -1.77, 0.00, 50.57, 46.50 -CTUN, 771, 0.24, 1.47, 0.000000, 0, 0, -3, 771, 0 -ATT, 0.28, -0.71, -7.37, -2.52, 0.00, 49.84, 46.50 -CTUN, 770, 0.24, 1.61, 0.000000, 0, 1, -4, 772, 0 -ATT, 0.09, -0.93, -7.56, -3.45, 0.00, 49.03, 46.50 -CTUN, 771, 0.23, 1.52, 0.000000, 0, 1, -3, 771, 0 -ATT, 0.09, -0.11, -7.46, -3.27, 0.00, 48.23, 46.50 -CTUN, 771, 0.23, 1.63, 0.000000, 0, 0, 0, 770, 0 -ATT, 0.09, 0.48, -7.46, -2.51, 0.00, 47.53, 46.50 -CTUN, 771, 0.21, 1.59, 0.000000, 0, 0, 2, 771, 0 -ATT, 0.09, -0.45, -6.72, -2.42, 0.00, 47.06, 46.50 -CTUN, 770, 0.21, 1.48, 0.000000, 0, 0, 8, 771, 0 -ATT, 0.09, -0.38, -6.53, -1.68, 0.00, 46.70, 46.50 -DU32, 7, 166140 -CURR, 771, 1238625, 1008, 2071, 5051, 931.673460 -CTUN, 771, 0.20, 1.52, 0.000000, 0, 0, 11, 770, 0 -ATT, 0.09, -0.28, -6.16, -1.15, 0.00, 46.37, 46.50 -CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 9, 771, 0 -ATT, 0.09, -0.61, -5.88, -1.14, 0.00, 46.20, 46.50 -CTUN, 771, 0.20, 1.49, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.09, -0.64, -5.22, -0.98, 0.00, 46.07, 46.50 -CTUN, 771, 0.21, 1.56, 0.000000, 0, 0, 12, 770, 0 -ATT, 0.09, -0.63, -4.76, -0.54, 0.00, 45.97, 46.50 -CTUN, 771, 0.21, 1.59, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.09, -0.19, -4.57, 0.12, 0.00, 45.82, 46.50 -CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 10, 771, 0 -ATT, 0.09, 0.32, -4.57, 0.35, 0.00, 45.66, 46.50 -CTUN, 771, 0.21, 1.64, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.09, 0.75, -4.48, -0.24, 0.00, 45.47, 46.50 -CTUN, 770, 0.21, 1.59, 0.000000, 0, 0, 12, 771, 0 -ATT, 0.09, 0.67, -4.57, -1.12, 0.00, 45.29, 46.50 -CTUN, 771, 0.21, 1.60, 0.000000, 0, 0, 11, 771, 0 -ATT, 0.09, -0.14, -4.57, -1.77, 0.00, 45.47, 46.50 -CTUN, 771, 0.22, 1.47, 0.000000, 0, 0, 13, 771, 0 -ATT, 0.09, 0.07, -4.66, -1.42, 0.00, 45.96, 46.50 -DU32, 7, 166140 -CURR, 771, 1246334, 1006, 2055, 5051, 937.392030 -CTUN, 771, 0.22, 1.62, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.09, 0.73, -4.57, -1.01, 0.00, 46.63, 46.50 -CTUN, 770, 0.22, 1.69, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, 1.22, -4.85, -0.11, 0.00, 47.34, 46.50 -CTUN, 771, 0.22, 1.72, 0.000000, 0, 0, 15, 770, 0 -ATT, 0.09, 0.90, -4.76, 0.50, 0.00, 48.07, 46.50 -CTUN, 771, 0.23, 1.56, 0.000000, 0, 0, 18, 770, 0 -ATT, 0.09, 0.50, -4.76, 0.61, 0.00, 48.62, 46.50 -CTUN, 773, 0.23, 1.68, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.09, 0.61, -4.85, -0.35, 0.00, 48.99, 46.50 -CTUN, 771, 0.24, 1.66, 0.000000, 0, 0, 15, 771, 0 -ATT, 0.18, 0.95, -4.76, -1.31, 0.00, 49.11, 46.50 -CTUN, 771, 0.24, 1.81, 0.000000, 0, 0, 19, 770, 0 -ATT, 0.09, 1.19, -4.76, -1.40, 0.00, 48.93, 46.50 -CTUN, 771, 0.25, 1.56, 0.000000, 0, 0, 20, 771, 0 -ATT, 0.09, 1.15, -4.76, -0.97, 0.00, 48.39, 46.50 -CTUN, 770, 0.25, 1.71, 0.000000, 0, 0, 19, 770, 0 -ATT, 0.09, 0.39, -5.04, -1.11, 0.00, 47.64, 46.50 -CTUN, 771, 0.27, 1.71, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.00, 0.24, -5.50, -1.34, 0.19, 46.78, 46.50 -DU32, 7, 166140 -CURR, 770, 1254041, 1006, 2043, 5051, 943.124760 -CTUN, 775, 0.27, 1.55, 0.000000, 0, 0, 16, 771, 0 -ATT, 0.09, 0.08, -6.06, -1.15, 0.19, 45.94, 46.50 -CTUN, 787, 0.28, 1.70, 0.000000, 0, 0, 16, 786, 0 -ATT, 0.09, 0.54, -6.34, -0.70, 0.19, 45.07, 46.50 -CTUN, 789, 0.28, 1.69, 0.000000, 0, 0, 14, 789, 0 -ATT, 0.09, 0.94, -6.44, -0.74, 0.09, 44.17, 46.50 -CTUN, 792, 0.29, 1.73, 0.000000, 0, 0, 14, 791, 0 -ATT, 0.09, 0.24, -6.53, -1.63, 0.86, 43.39, 46.75 -CTUN, 791, 0.29, 1.76, 0.000000, 0, 0, 15, 791, 0 -ATT, 0.09, -0.54, -6.34, -2.39, 1.25, 42.77, 47.18 -CTUN, 792, 0.29, 1.73, 0.000000, 0, 0, 15, 792, 0 -ATT, 0.09, -0.73, -6.25, -2.22, 2.01, 42.35, 47.96 -CTUN, 793, 0.29, 1.79, 0.000000, 0, 0, 15, 792, 0 -ATT, 0.09, -0.23, -6.34, -1.81, 2.21, 42.28, 48.87 -CTUN, 795, 0.30, 1.73, 0.000000, 0, 0, 17, 796, 0 -ATT, 0.09, 0.24, -6.53, -1.88, 2.21, 42.64, 49.78 -CTUN, 795, 0.30, 1.79, 0.000000, 0, 0, 17, 795, 0 -ATT, 0.09, -0.18, -6.53, -2.15, 3.07, 43.28, 50.80 -CTUN, 796, 0.32, 1.83, 0.000000, 0, 0, 16, 796, 0 -ATT, 0.09, -0.85, -6.53, -2.51, 3.46, 44.20, 52.25 -DU32, 7, 166140 -CURR, 796, 1261938, 997, 2176, 5051, 949.100770 -CTUN, 796, 0.32, 1.75, 0.000000, 0, 0, 16, 796, 0 -ATT, 0.09, 0.04, -6.53, -2.55, 3.26, 45.52, 53.69 -CTUN, 796, 0.33, 1.81, 0.000000, 0, 0, 13, 796, 0 -ATT, 0.09, 0.96, -6.53, -2.48, 3.17, 47.18, 55.17 -CTUN, 796, 0.33, 1.85, 0.000000, 0, 0, 14, 796, 0 -ATT, 0.09, 1.34, -6.53, -1.78, 3.55, 49.13, 56.68 -CTUN, 796, 0.33, 1.76, 0.000000, 0, 0, 15, 796, 0 -ATT, 0.46, 1.90, -6.53, -0.79, 2.11, 51.26, 57.98 -CTUN, 796, 0.33, 1.77, 0.000000, 0, 0, 16, 796, 0 -ATT, 1.31, 1.90, -6.53, -0.52, 0.00, 53.48, 58.46 -CTUN, 794, 0.35, 1.98, 0.000000, 0, 0, 13, 796, 0 -ATT, 1.50, 2.06, -6.53, -1.05, 0.00, 55.40, 58.46 -CTUN, 791, 0.35, 1.86, 0.000000, 0, 0, 14, 796, 0 -ATT, 1.31, 2.55, -6.53, -1.53, 0.00, 56.88, 58.46 -CTUN, 786, 0.36, 1.83, 0.000000, 0, 0, 16, 786, 0 -ATT, 0.00, 2.14, -6.44, -1.52, 0.00, 57.95, 58.46 -CTUN, 786, 0.36, 1.80, 0.000000, 0, 0, 15, 786, 0 -ATT, 0.00, 0.88, -6.16, -1.59, 0.00, 58.33, 58.46 -CTUN, 786, 0.37, 1.89, 0.000000, 0, 0, 13, 786, 0 -ATT, 0.00, 0.34, -5.13, -1.77, 0.00, 58.23, 58.46 -DU32, 7, 166140 -CURR, 786, 1269867, 992, 2140, 5051, 955.139830 -CTUN, 786, 0.37, 1.91, 0.000000, 0, 0, 10, 786, 0 -ATT, 0.00, -0.07, -4.66, -1.29, 0.00, 57.76, 58.46 -CTUN, 786, 0.37, 1.92, 0.000000, 0, 0, 7, 786, 0 -ATT, 0.00, -0.40, -4.57, -0.69, 0.00, 57.09, 58.46 -CTUN, 786, 0.37, 1.79, 0.000000, 0, 0, 7, 786, 0 -ATT, 0.00, -0.05, -4.48, -0.60, 0.00, 56.38, 58.46 -CTUN, 786, 0.37, 1.87, 0.000000, 0, 0, 6, 786, 0 -ATT, 0.00, -0.76, -4.29, -0.14, 0.00, 55.60, 58.46 -CTUN, 786, 0.37, 1.85, 0.000000, 0, 0, 4, 786, 0 -ATT, 0.00, -1.02, -4.57, -0.11, 0.00, 54.91, 58.46 -CTUN, 786, 0.37, 1.82, 0.000000, 0, 0, 3, 787, 0 -ATT, 0.00, -0.16, -4.57, -0.12, 0.00, 54.52, 58.46 -CTUN, 786, 0.36, 1.97, 0.000000, 0, 0, 2, 785, 0 -ATT, 0.00, 1.15, -4.48, -0.60, 0.00, 54.48, 58.46 -CTUN, 786, 0.36, 1.75, 0.000000, 0, 0, 1, 786, 0 -ATT, 0.00, 1.37, -4.38, -1.09, 0.00, 54.84, 58.46 -CTUN, 786, 0.34, 1.88, 0.000000, 0, 0, -2, 786, 0 -ATT, 0.00, 0.69, -4.38, -1.11, 0.00, 55.56, 58.46 -CTUN, 786, 0.34, 1.79, 0.000000, 0, 0, -1, 786, 0 -ATT, -0.28, 0.75, -3.26, -1.02, 0.00, 56.65, 58.46 -DU32, 7, 166140 -CURR, 787, 1277727, 1001, 2107, 5051, 961.042660 -CTUN, 786, 0.32, 1.94, 0.000000, 0, 0, -3, 786, 0 -ATT, -2.17, 0.51, -2.14, -1.03, 0.00, 57.73, 58.46 -CTUN, 785, 0.32, 1.79, 0.000000, 0, 0, -4, 786, 0 -ATT, -2.55, -0.23, -2.52, -0.13, 0.00, 58.78, 58.46 -CTUN, 786, 0.29, 1.79, 0.000000, 0, 0, -3, 786, 0 -ATT, -2.46, -1.85, -2.42, 0.33, 0.00, 59.74, 58.46 -CTUN, 785, 0.29, 1.80, 0.000000, 0, 0, -3, 787, 0 -ATT, -2.36, -3.67, -2.14, 0.25, 0.00, 60.55, 58.46 -CTUN, 787, 0.27, 1.65, 0.000000, 0, 1, 0, 788, 0 -ATT, -2.17, -4.20, -2.14, 0.77, 0.00, 61.12, 58.46 -CTUN, 786, 0.27, 1.73, 0.000000, 0, 1, 4, 787, 0 -ATT, -1.80, -3.45, -1.77, 1.16, 0.00, 61.57, 58.46 -CTUN, 786, 0.25, 1.76, 0.000000, 0, 1, 9, 787, 0 -ATT, -1.89, -3.15, -1.86, 1.38, 0.00, 62.01, 58.46 -CTUN, 787, 0.25, 1.93, 0.000000, 0, 1, 11, 788, 0 -ATT, 0.00, -2.74, -3.26, 1.47, 0.00, 62.54, 58.46 -CTUN, 787, 0.24, 1.65, 0.000000, 0, 0, 15, 786, 0 -ATT, 0.00, -2.40, -3.73, 0.53, 0.00, 62.92, 58.46 -CTUN, 786, 0.24, 1.83, 0.000000, 0, 0, 16, 786, 0 -ATT, 0.00, -1.40, -3.82, -0.28, 0.00, 63.21, 58.46 -DU32, 7, 166140 -CURR, 785, 1285589, 1003, 2173, 5028, 966.961730 -CTUN, 785, 0.24, 1.73, 0.000000, 0, 0, 19, 785, 0 -ATT, 0.00, 0.56, -3.92, -0.47, 0.00, 63.29, 58.46 -CTUN, 786, 0.24, 1.73, 0.000000, 0, 0, 20, 786, 0 -ATT, 0.00, 1.34, -4.20, -0.06, 0.00, 63.03, 58.46 -CTUN, 786, 0.24, 1.75, 0.000000, 0, 0, 20, 786, 0 -ATT, 0.00, 0.86, -4.20, -0.49, 0.00, 62.45, 58.46 -CTUN, 786, 0.26, 1.70, 0.000000, 0, 0, 22, 786, 0 -ATT, 0.00, -0.30, -4.20, -1.37, 0.00, 61.56, 58.46 -CTUN, 786, 0.25, 1.64, 0.000000, 0, 0, 21, 785, 0 -ATT, 0.00, -0.08, -4.20, -1.76, 0.00, 60.49, 58.46 -CTUN, 786, 0.26, 1.78, 0.000000, 0, 0, 23, 786, 0 -ATT, 0.00, 0.18, -4.20, -2.14, 0.00, 59.42, 58.46 -CTUN, 785, 0.26, 1.71, 0.000000, 0, 0, 25, 786, 0 -ATT, 0.00, 0.14, -4.20, -2.38, 0.00, 58.42, 58.46 -CTUN, 786, 0.27, 1.83, 0.000000, 0, 0, 23, 785, 0 -ATT, 0.00, -0.38, -4.20, -2.65, 0.00, 57.54, 58.46 -CTUN, 786, 0.27, 1.68, 0.000000, 0, 0, 21, 786, 0 -ATT, 0.00, -0.99, -3.92, -2.41, 0.00, 56.89, 58.46 -CTUN, 785, 0.29, 1.84, 0.000000, 0, 0, 20, 786, 0 -ATT, 0.00, -1.02, -3.45, -1.50, 0.00, 56.54, 58.46 -DU32, 7, 166140 -CURR, 785, 1293448, 1005, 2112, 5051, 972.883060 -CTUN, 785, 0.29, 1.66, 0.000000, 0, 0, 17, 786, 0 -ATT, 0.00, -1.40, -3.45, -0.50, 0.00, 56.27, 58.46 -CTUN, 786, 0.31, 1.72, 0.000000, 0, 0, 18, 785, 0 -ATT, 0.00, -1.36, -3.36, 0.71, 0.00, 55.99, 58.46 -CTUN, 786, 0.31, 1.89, 0.000000, 0, 0, 13, 787, 0 -ATT, 0.00, -0.72, -3.54, 1.61, 0.00, 55.85, 58.46 -CTUN, 786, 0.32, 1.78, 0.000000, 0, 0, 10, 786, 0 -ATT, 0.00, -0.57, -3.45, 1.69, 0.00, 55.90, 58.46 -CTUN, 786, 0.32, 1.71, 0.000000, 0, 0, 7, 787, 0 -ATT, 0.18, -0.68, -3.26, 1.64, 0.00, 56.14, 58.46 -CTUN, 786, 0.32, 1.90, 0.000000, 0, 0, 3, 786, 0 -ATT, 0.18, -0.86, -3.45, 1.49, 0.00, 56.57, 58.46 -CTUN, 785, 0.31, 1.79, 0.000000, 0, 0, 0, 785, 0 -ATT, 0.28, -0.51, -3.45, 1.59, 0.00, 57.08, 58.46 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 786, 0.32, 1.76, 0.000000, 0, 0, 0, 786, 0 -ATT, 0.28, -0.14, -3.45, 1.57, 0.00, 57.43, 58.46 -CTUN, 786, 0.31, 1.64, 0.000000, 0, 0, -2, 786, 0 -ATT, 0.46, 0.09, -3.36, 0.93, 0.00, 57.78, 58.46 -CTUN, 785, 0.31, 1.73, 0.000000, 0, 0, -5, 786, 0 -ATT, 0.46, 0.76, -3.45, -0.19, 0.00, 58.01, 58.46 -DU32, 7, 166140 -CURR, 787, 1301307, 994, 2105, 5051, 978.759830 -CTUN, 786, 0.28, 1.78, 0.000000, 0, 0, -6, 786, 0 -ATT, 0.28, 1.74, -4.10, -0.84, 0.00, 58.14, 58.46 -CTUN, 786, 0.28, 1.73, 0.000000, 0, 0, -6, 786, 0 -ATT, 0.28, 1.33, -5.50, -0.25, 0.00, 58.31, 58.46 -CTUN, 786, 0.26, 1.85, 0.000000, 0, 0, -4, 786, 0 -ATT, 0.46, 0.00, -6.72, 0.32, 0.00, 58.38, 58.46 -CTUN, 785, 0.26, 1.74, 0.000000, 0, 0, 0, 786, 0 -ATT, 0.46, -0.38, -7.00, -0.80, 0.00, 58.51, 58.46 -CTUN, 786, 0.24, 1.74, 0.000000, 0, 0, 4, 786, 0 -ATT, 0.46, 0.28, -6.81, -2.86, 0.00, 58.74, 58.46 -CTUN, 786, 0.24, 1.69, 0.000000, 0, 1, 4, 787, 0 -ATT, 0.56, 0.53, -6.81, -4.56, 0.00, 58.81, 58.46 -CTUN, 786, 0.22, 1.72, 0.000000, 0, 2, 5, 788, 0 -ATT, 0.46, 0.35, -6.72, -4.97, 0.00, 58.86, 58.46 -CTUN, 786, 0.22, 1.68, 0.000000, 0, 2, 11, 788, 0 -ATT, 0.56, 0.81, -6.81, -5.12, 0.00, 58.84, 58.46 -CTUN, 786, 0.22, 1.52, 0.000000, 0, 2, 13, 788, 0 -ATT, 0.75, 1.14, -6.72, -5.41, 0.00, 58.83, 58.46 -CTUN, 786, 0.22, 1.73, 0.000000, 0, 3, 12, 789, 0 -ATT, 1.78, 1.07, -5.78, -5.08, 0.00, 58.88, 58.46 -DU32, 7, 166140 -CURR, 786, 1309178, 997, 2142, 5051, 984.664730 -CTUN, 786, 0.22, 1.70, 0.000000, 0, 2, 15, 788, 0 -ATT, 1.78, 1.86, -4.76, -5.08, 0.00, 58.92, 58.46 -CTUN, 786, 0.22, 1.66, 0.000000, 0, 3, 19, 789, 0 -ATT, 0.46, 3.33, -2.14, -4.32, 0.00, 58.88, 58.46 -CTUN, 786, 0.22, 1.73, 0.000000, 0, 2, 21, 787, 0 -ATT, 0.37, 3.48, -2.24, -2.05, 0.00, 58.82, 58.46 -CTUN, 785, 0.23, 1.66, 0.000000, 0, 1, 21, 787, 0 -ATT, 0.28, 1.97, -2.24, 0.36, 0.00, 58.81, 58.46 -CTUN, 785, 0.23, 1.88, 0.000000, 0, 0, 19, 786, 0 -ATT, 0.00, 0.12, -2.24, 1.24, 0.00, 58.77, 58.46 -CTUN, 786, 0.25, 1.84, 0.000000, 0, 0, 19, 786, 0 -ATT, 0.00, -0.33, -2.24, 1.09, 0.00, 58.73, 58.46 -CTUN, 786, 0.25, 1.90, 0.000000, 0, 0, 20, 786, 0 -ATT, 0.00, -0.42, -2.24, 1.20, 0.00, 58.73, 58.46 -CTUN, 785, 0.29, 1.78, 0.000000, 0, 0, 20, 785, 0 -ATT, 0.00, -0.40, -2.24, 2.06, 0.00, 58.80, 58.46 -CTUN, 787, 0.29, 1.79, 0.000000, 0, 0, 17, 786, 0 -ATT, 0.00, 0.52, -3.26, 3.06, 0.00, 58.87, 58.46 -CTUN, 786, 0.31, 1.76, 0.000000, 0, 1, 15, 787, 0 -ATT, 0.00, 1.15, -4.57, 3.16, 0.00, 59.04, 58.46 -DU32, 7, 166140 -CURR, 787, 1317045, 1002, 2140, 5051, 990.616090 -CTUN, 785, 0.31, 1.99, 0.000000, 0, 0, 12, 785, 0 -ATT, 0.00, 0.51, -5.13, 2.18, 0.00, 59.36, 58.46 -CTUN, 786, 0.33, 1.89, 0.000000, 0, 0, 9, 786, 0 -ATT, 0.00, -0.89, -5.69, 0.18, 0.00, 59.77, 58.46 -CTUN, 786, 0.33, 1.87, 0.000000, 0, 0, 7, 786, 0 -ATT, 0.00, -1.76, -6.81, -1.50, 0.00, 60.28, 58.46 -CTUN, 787, 0.35, 1.83, 0.000000, 0, 0, 5, 786, 0 -ATT, 0.00, -1.83, -7.46, -2.39, -0.09, 60.79, 58.45 -CTUN, 786, 0.35, 1.90, 0.000000, 0, 1, 4, 787, 0 -ATT, 0.00, -1.94, -6.62, -2.61, -0.75, 61.27, 58.25 -CTUN, 786, 0.35, 1.93, 0.000000, 0, 1, 3, 787, 0 -ATT, 0.00, -2.10, -6.16, -2.19, -1.13, 61.48, 57.70 -CTUN, 785, 0.35, 1.85, 0.000000, 0, 0, 0, 786, 0 -ATT, 0.00, -1.63, -5.22, -1.69, -2.26, 61.39, 56.90 -CTUN, 786, 0.35, 1.94, 0.000000, 0, 0, 0, 786, 0 -ATT, 0.00, -1.35, -5.22, -1.04, -2.73, 60.70, 55.72 -CTUN, 786, 0.35, 1.88, 0.000000, 0, 0, 0, 786, 0 -ATT, 0.00, -1.48, -5.22, -0.54, -3.11, 59.55, 54.33 -CTUN, 786, 0.35, 2.05, 0.000000, 0, 0, -2, 786, 0 -ATT, 0.00, -1.04, -5.41, -0.59, -3.39, 57.88, 52.86 -DU32, 7, 166140 -CURR, 786, 1324906, 996, 2133, 5051, 996.541990 -CTUN, 785, 0.33, 1.89, 0.000000, 0, 0, -3, 785, 0 -ATT, 0.00, -0.43, -5.50, -1.16, -3.39, 55.98, 51.29 -CTUN, 786, 0.33, 1.84, 0.000000, 0, 0, -3, 787, 0 -ATT, 0.00, -0.46, -5.69, -1.83, -3.20, 53.94, 49.69 -CTUN, 786, 0.31, 1.80, 0.000000, 0, 0, -1, 786, 0 -ATT, 0.28, -0.61, -5.88, -2.49, -3.20, 51.71, 48.20 -CTUN, 786, 0.31, 1.82, 0.000000, 0, 0, -2, 786, 0 -ATT, 0.18, -0.31, -5.78, -3.38, -3.20, 49.39, 46.71 -CTUN, 787, 0.30, 1.81, 0.000000, 0, 1, 1, 788, 0 -ATT, 0.28, 0.03, -5.88, -3.32, -3.20, 47.15, 45.20 -CTUN, 786, 0.30, 1.81, 0.000000, 0, 0, 2, 786, 0 -ATT, 0.28, 0.89, -4.85, -2.07, -3.20, 45.14, 43.70 -CTUN, 786, 0.28, 1.88, 0.000000, 0, 0, 2, 786, 0 -ATT, 0.28, 1.34, -3.73, -1.28, -3.20, 43.37, 42.19 -CTUN, 786, 0.28, 1.71, 0.000000, 0, 0, 4, 786, 0 -ATT, 0.00, 1.56, -2.24, -0.74, -3.20, 41.78, 40.69 -CTUN, 786, 0.27, 1.77, 0.000000, 0, 0, 6, 786, 0 -ATT, 0.28, 1.28, -2.52, -0.09, -3.20, 40.45, 39.16 -CTUN, 785, 0.27, 1.68, 0.000000, 0, 0, 10, 786, 0 -ATT, 0.00, 1.06, -2.05, 1.07, -3.20, 39.21, 37.66 -DU32, 7, 166140 -CURR, 786, 1332768, 994, 2146, 5051, 1002.471300 -CTUN, 786, 0.26, 1.68, 0.000000, 0, 0, 11, 786, 0 -ATT, 0.00, 1.30, -2.14, 2.76, -3.30, 38.00, 36.16 -CTUN, 786, 0.27, 1.86, 0.000000, 0, 1, 9, 787, 0 -ATT, 0.00, 1.25, -2.14, 3.78, -3.20, 36.76, 34.66 -CTUN, 787, 0.26, 1.87, 0.000000, 0, 1, 7, 788, 0 -ATT, 0.00, 0.81, -3.26, 3.19, -3.20, 35.45, 33.16 -CTUN, 785, 0.27, 1.87, 0.000000, 0, 0, 6, 785, 0 -ATT, 0.00, 0.36, -4.66, 1.57, -3.20, 34.32, 31.66 -CTUN, 786, 0.27, 1.74, 0.000000, 0, 0, 7, 786, 0 -ATT, 0.00, 0.20, -6.06, -0.20, -3.20, 33.24, 30.17 -CTUN, 786, 0.27, 1.72, 0.000000, 0, 0, 10, 786, 0 -ATT, 0.00, 0.84, -6.53, -1.35, -3.20, 32.25, 28.67 -CTUN, 786, 0.27, 1.82, 0.000000, 0, 0, 8, 786, 0 -ATT, 0.00, 0.99, -6.62, -2.53, -3.20, 31.34, 27.17 -CTUN, 785, 0.27, 1.75, 0.000000, 0, 0, 11, 786, 0 -ATT, 0.00, -0.14, -6.53, -3.29, -3.20, 30.23, 25.68 -CTUN, 786, 0.27, 1.76, 0.000000, 0, 1, 9, 787, 0 -ATT, 0.00, -1.10, -6.53, -3.71, -3.20, 28.94, 24.18 -CTUN, 786, 0.28, 1.80, 0.000000, 0, 1, 13, 788, 0 -ATT, 0.00, -1.55, -5.69, -3.46, -3.20, 27.45, 22.69 -DU32, 7, 166140 -CURR, 786, 1340631, 995, 2149, 5028, 1008.435900 -CTUN, 785, 0.28, 1.86, 0.000000, 0, 1, 10, 786, 0 -ATT, 0.00, -1.34, -4.57, -3.01, -3.39, 26.08, 21.18 -CTUN, 786, 0.29, 1.73, 0.000000, 0, 0, 12, 786, 0 -ATT, 0.00, -0.58, -4.57, -2.05, -3.77, 24.57, 19.48 -CTUN, 785, 0.29, 1.69, 0.000000, 0, 0, 10, 785, 0 -ATT, 0.00, -0.13, -4.48, -1.33, -3.96, 22.89, 17.64 -CTUN, 785, 0.29, 1.88, 0.000000, 0, 0, 9, 785, 0 -ATT, 0.00, -0.91, -3.64, -0.95, -4.15, 20.90, 15.77 -CTUN, 782, 0.29, 1.82, 0.000000, 0, 0, 7, 782, 0 -ATT, 0.00, -1.04, -3.08, -1.16, -4.24, 18.69, 13.86 -CTUN, 782, 0.30, 1.84, 0.000000, 0, 0, 7, 782, 0 -ATT, 0.00, 0.02, -3.26, -1.21, -4.15, 16.41, 11.98 -CTUN, 782, 0.30, 1.93, 0.000000, 0, 0, 5, 782, 0 -ATT, 0.00, 0.49, -3.26, -0.69, -4.52, 14.42, 9.99 -CTUN, 776, 0.31, 1.83, 0.000000, 0, 0, 5, 780, 0 -ATT, 0.00, -0.67, -2.70, -0.09, -4.52, 12.41, 7.89 -CTUN, 773, 0.31, 2.02, 0.000000, 0, 0, 4, 773, 0 -ATT, 0.00, -1.82, -2.42, -0.23, -4.52, 10.35, 5.81 -CTUN, 773, 0.31, 1.93, 0.000000, 0, 0, 2, 773, 0 -ATT, 0.00, -1.24, -2.70, 0.22, -4.62, 7.97, 3.74 -DU32, 7, 166140 -CURR, 774, 1348448, 992, 2092, 5028, 1014.345000 -CTUN, 774, 0.31, 2.10, 0.000000, 0, 0, 1, 774, 0 -ATT, 0.00, 0.42, -2.89, 0.89, -4.71, 5.62, 1.55 -CTUN, 774, 0.31, 2.04, 0.000000, 0, 0, 0, 774, 0 -ATT, 0.00, 0.79, -3.26, 1.20, -4.62, 3.38, 359.42 -CTUN, 773, 0.31, 1.89, 0.000000, 0, 0, 0, 774, 0 -ATT, 0.00, -0.48, -3.64, 0.62, -5.09, 1.24, 357.17 -CTUN, 773, 0.31, 1.84, 0.000000, 0, 0, 0, 773, 0 -ATT, 0.00, -0.78, -3.73, -0.18, -5.09, 359.16, 354.87 -CTUN, 773, 0.31, 1.82, 0.000000, 0, 0, -2, 773, 0 -ATT, 0.00, -0.54, -4.57, -0.69, -5.09, 357.13, 352.56 -CTUN, 774, 0.31, 1.88, 0.000000, 0, 0, 0, 773, 0 -ATT, 0.00, -0.36, -5.04, -0.68, -5.37, 355.12, 350.10 -CTUN, 773, 0.29, 1.84, 0.000000, 0, 0, -4, 773, 0 -ATT, 0.00, -0.68, -5.60, -1.30, -5.37, 352.95, 347.61 -CTUN, 774, 0.29, 1.83, 0.000000, 0, 0, -4, 774, 0 -ATT, 0.00, -0.81, -5.69, -2.32, -5.47, 350.63, 345.14 -CTUN, 773, 0.29, 1.93, 0.000000, 0, 0, -8, 773, 0 -ATT, 0.00, -0.74, -5.78, -3.23, -5.09, 348.26, 342.73 -CTUN, 773, 0.29, 1.84, 0.000000, 0, 1, -8, 774, 0 -ATT, 0.00, -0.49, -6.16, -3.57, -4.90, 345.84, 340.43 -DU32, 7, 166140 -CURR, 773, 1356184, 1008, 2054, 5051, 1020.115400 -CTUN, 773, 0.27, 1.81, 0.000000, 0, 1, -7, 774, 0 -ATT, 0.00, -0.43, -6.53, -3.32, -4.33, 343.16, 338.29 -CTUN, 774, 0.27, 1.83, 0.000000, 0, 1, -9, 775, 0 -ATT, 0.00, -0.79, -6.53, -3.50, -3.77, 340.54, 336.40 -CTUN, 774, 0.23, 1.89, 0.000000, 0, 1, -10, 775, 0 -ATT, 0.00, -1.68, -5.97, -3.97, -3.01, 338.15, 334.81 -CTUN, 767, 0.23, 1.78, 0.000000, 0, 1, -11, 767, 0 -ATT, 0.00, -1.98, -5.50, -4.15, 0.00, 336.15, 334.30 -CTUN, 765, 0.21, 1.83, 0.000000, 0, 1, -6, 766, 0 -ATT, 0.09, -1.68, -5.41, -3.91, 0.00, 334.67, 334.30 -CTUN, 765, 0.21, 1.89, 0.000000, 0, 1, -4, 766, 0 -ATT, 1.31, -0.85, -5.88, -2.95, 0.00, 333.80, 334.30 -CTUN, 765, 0.20, 1.82, 0.000000, 0, 0, -3, 765, 0 -ATT, 2.53, 0.61, -6.06, -2.00, 0.00, 333.37, 334.30 -CTUN, 765, 0.20, 1.55, 0.000000, 0, 0, 0, 765, 0 -ATT, 3.56, 2.20, -5.69, -2.21, 0.00, 333.26, 334.30 -CTUN, 765, 0.20, 1.41, 0.000000, 0, 1, 1, 766, 0 -ATT, 3.56, 4.01, -4.85, -2.62, 0.00, 333.40, 334.30 -CTUN, 765, 0.20, 1.34, 0.000000, 0, 2, 4, 767, 0 -ATT, 6.37, 4.60, -2.14, -2.26, 0.00, 333.92, 334.30 -DU32, 7, 166140 -CURR, 765, 1363878, 999, 2022, 5051, 1025.738600 -CTUN, 764, 0.20, 1.40, 0.000000, 0, 2, 8, 766, 0 -ATT, 9.09, 5.12, -2.14, -1.33, 0.00, 334.90, 334.30 -CTUN, 759, 0.20, 1.57, 0.000000, 0, 3, 9, 763, 0 -ATT, 10.31, 7.74, 0.00, -0.03, 0.00, 336.05, 334.30 -CTUN, 755, 0.20, 1.54, 0.000000, 0, 8, 12, 763, 0 -ATT, 9.28, 10.62, 2.33, 1.03, 0.00, 337.19, 334.30 -CTUN, 751, 0.20, 1.62, 0.000000, 0, 12, 7, 765, 0 -ATT, 7.68, 11.10, 10.36, 1.49, 0.00, 338.20, 334.30 -CTUN, 748, 0.20, 1.68, 0.000000, 0, 11, 4, 759, 0 -ATT, 3.37, 9.98, 11.67, 3.60, 0.00, 339.40, 334.30 -CTUN, 748, 0.20, 1.74, 0.000000, 0, 9, 1, 757, 0 -ATT, 0.00, 7.25, 14.56, 7.22, 0.00, 340.27, 334.30 -CTUN, 747, 0.20, 1.71, 0.000000, 0, 11, -3, 757, 0 -ATT, 0.46, 4.37, 21.19, 11.13, 0.00, 340.52, 334.30 -CTUN, 745, 0.20, 1.70, 0.000000, 0, 17, -6, 762, 0 -ATT, 0.00, 2.26, 19.88, 15.58, 0.00, 340.08, 334.30 -CTUN, 745, 0.20, 1.72, 0.000000, 0, 30, -14, 775, 0 -ATT, -0.18, 0.93, 6.16, 19.17, 0.00, 339.50, 334.30 -CTUN, 745, 0.20, 1.58, 0.000000, 0, 37, -25, 782, 0 -ATT, -11.27, -0.42, 1.77, 18.63, 0.00, 338.84, 334.30 -DU32, 7, 166140 -CURR, 746, 1371525, 1005, 2170, 5051, 1031.436600 -CTUN, 747, 0.20, 1.74, 0.000000, 0, 25, -34, 772, 0 -ATT, -24.34, -4.35, 0.00, 12.53, 0.00, 338.40, 334.30 -CTUN, 746, 0.20, 0.77, 0.000000, 0, 13, -34, 759, 0 -ATT, -31.54, -13.67, -4.10, 4.16, 0.00, 338.50, 334.30 -CTUN, 746, 0.20, 0.80, 0.000000, 0, 30, -29, 776, 0 -ATT, -30.31, -20.75, -9.33, 0.31, 0.00, 339.19, 334.30 -CTUN, 746, 0.20, 0.91, 0.000000, 0, 33, -13, 779, 0 -ATT, -20.08, -14.57, -16.89, 8.07, 0.00, 340.79, 334.30 -CTUN, 741, 0.20, 1.04, 0.000000, 0, 19, -26, 763, 0 -ATT, -2.93, -7.99, -23.06, 7.13, 0.00, 347.90, 337.90 -CTUN, 730, 0.20, 1.12, 0.000000, 0, 6, -44, 740, 0 -ATT, 0.00, -5.73, -22.96, -1.95, 0.00, 355.03, 345.03 -CTUN, 708, 0.20, -1.26, 0.000000, 0, 1, -21, 720, 0 -ATT, -7.76, 0.38, -18.85, -0.95, 0.00, 0.42, 350.42 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 680, 2.10, -1.42, 0.000000, 0, 0, -13, 674, 0 -ATT, -16.10, -5.52, -16.89, -0.65, 0.00, 1.77, 351.77 -CTUN, 680, 2.10, -1.53, 0.000000, 0, 2, -12, 682, 0 -ATT, -18.47, -3.73, -14.09, -7.13, 0.00, 6.65, 356.65 -CTUN, 680, 6.51, -1.51, 0.000000, 0, 8, -6, 688, 0 -ATT, -20.65, -5.28, -10.82, -10.06, 2.11, 10.85, 0.85 -DU32, 7, 166140 -CURR, 677, 1378887, 1012, 1885, 5028, 1036.539800 -CTUN, 681, 6.51, -0.32, 0.000000, 0, 13, -11, 684, 0 -ATT, -21.97, -10.59, -8.49, -7.74, 6.15, 13.76, 3.83 -CTUN, 692, 6.51, 0.51, 0.000000, 0, 19, -14, 712, 0 -ATT, -18.00, -16.33, -8.21, -3.85, 6.05, 15.99, 6.86 -CTUN, 694, 1.62, 0.80, 0.000000, 0, 28, -23, 720, 0 -ATT, -4.64, -19.02, -8.49, -1.42, 3.36, 18.32, 8.80 -CTUN, 692, 1.62, 1.15, 0.000000, 0, 31, -32, 723, 0 -ATT, 0.00, -16.13, -10.64, -0.53, 0.38, 20.78, 10.78 -CTUN, 692, 0.20, 1.02, 0.000000, 0, 15, -41, 707, 0 -ATT, 0.00, -8.70, -10.64, -1.43, 0.00, 22.27, 12.27 -CTUN, 684, 0.20, 0.94, 0.000000, 0, 3, -38, 693, 0 -ATT, 0.00, -3.41, -8.12, -3.14, 0.00, 22.90, 12.90 -CTUN, 680, 0.20, 0.19, 0.000000, 0, 1, -37, 681, 0 -ATT, 3.09, -1.96, -2.42, -4.17, 2.59, 22.81, 13.39 -CTUN, 680, 0.22, -0.99, 0.000000, 0, 1, -35, 681, 0 -ATT, 3.65, -1.01, -2.80, -3.63, 14.23, 22.03, 17.92 -CTUN, 687, 0.21, -0.47, 0.000000, 0, 0, -33, 687, 0 -ATT, 10.03, 0.45, -6.53, -1.89, 15.09, 21.91, 24.49 -CTUN, 684, 0.21, -1.18, 0.000000, 0, 0, -34, 686, 0 -ATT, 18.00, 3.60, -6.72, -1.16, 18.36, 22.92, 31.87 -DU32, 7, 166140 -CURR, 680, 1385862, 1025, 1705, 5051, 1041.508200 -CTUN, 674, 0.20, -1.24, 0.000000, 0, 2, -28, 680, 0 -ATT, 22.59, 5.08, -4.76, 0.57, 19.90, 26.46, 36.46 -CTUN, 669, 0.20, -1.02, 0.000000, 0, 3, -26, 672, 0 -ATT, 15.00, 10.13, -2.33, 0.66, 18.46, 31.86, 41.86 -CTUN, 669, 0.20, -0.99, 0.000000, 0, 11, -23, 680, 0 -ATT, 7.03, 10.82, -2.33, 2.07, 13.55, 37.89, 47.82 -CTUN, 670, 0.20, -0.42, 0.000000, 0, 9, -32, 679, 0 -ATT, 0.00, 9.15, -2.52, 2.92, 5.57, 44.13, 51.69 -CTUN, 671, 0.20, -0.42, 0.000000, 0, 5, -39, 676, 0 -ATT, 0.00, 4.73, -2.52, 1.25, 0.00, 49.50, 52.50 -CTUN, 671, 0.20, -0.77, 0.000000, 0, 0, -45, 672, 0 -ATT, -1.13, 1.03, -3.45, -0.68, 0.00, 53.59, 52.50 -CTUN, 707, 0.20, -1.12, 0.000000, 0, 0, -48, 707, 0 -ATT, -3.22, 0.17, -3.17, -1.47, 0.00, 56.66, 52.50 -CTUN, 746, 0.20, -0.94, 0.000000, 0, 0, -48, 744, 0 -ATT, -2.74, -1.05, -5.78, -1.95, 0.00, 58.72, 52.50 -CTUN, 755, 0.20, -1.77, 0.000000, 0, 0, -41, 755, 0 -ATT, 0.00, -2.60, -5.69, -2.18, 0.00, 59.75, 52.50 -CTUN, 755, 0.21, -1.66, 0.000000, 0, 1, -24, 755, 0 -ATT, 0.00, -2.80, -5.60, -0.76, 0.00, 60.08, 52.50 -DU32, 7, 166140 -CURR, 756, 1392858, 1013, 2077, 5051, 1046.405300 -CTUN, 763, 0.21, -1.22, 0.000000, 0, 0, -14, 763, 0 -ATT, 0.00, -2.83, -5.22, 0.37, 0.00, 59.94, 52.50 -CTUN, 765, 0.21, -0.71, 0.000000, 0, 0, -9, 765, 0 -ATT, 0.00, -2.83, -5.32, 0.00, 0.00, 59.48, 52.50 -CTUN, 764, 0.20, 0.67, 0.000000, 0, 0, -7, 765, 0 -ATT, 0.00, -2.31, -5.69, -0.77, 0.00, 58.52, 52.50 -CTUN, 755, 0.20, 1.52, 0.000000, 0, 0, -4, 759, 0 -ATT, 0.00, -1.76, -7.56, -1.47, 0.00, 57.22, 52.50 -CTUN, 753, 0.20, 1.69, 0.000000, 0, 0, -6, 752, 0 -ATT, 1.40, -0.81, -10.64, -2.33, 0.00, 55.90, 52.50 -CTUN, 754, 0.20, 1.83, 0.000000, 0, 0, -8, 754, 0 -ATT, 6.84, 0.85, -10.92, -3.99, 0.00, 54.59, 52.50 -CTUN, 753, 0.20, 1.98, 0.000000, 0, 2, -12, 755, 0 -ATT, 8.62, 3.27, -11.29, -6.02, 0.00, 53.23, 52.50 -CTUN, 752, 0.24, 1.76, 0.000000, 0, 6, -14, 758, 0 -ATT, 8.81, 6.71, -11.57, -6.86, 0.00, 52.00, 52.50 -CTUN, 753, 0.24, 1.86, 0.000000, 0, 10, -18, 763, 0 -ATT, 8.62, 9.25, -11.10, -7.35, 0.00, 50.91, 52.50 -CTUN, 753, 0.26, 1.96, 0.000000, 0, 14, -28, 766, 0 -ATT, 7.40, 10.24, -10.92, -7.12, 0.00, 50.03, 52.50 -DU32, 7, 166140 -CURR, 752, 1400465, 997, 2003, 5028, 1051.960300 -CTUN, 753, 0.26, 1.95, 0.000000, 0, 14, -33, 767, 0 -ATT, 2.53, 9.32, -8.30, -6.16, 0.00, 49.34, 52.50 -CTUN, 755, 0.27, 1.92, 0.000000, 0, 10, -33, 764, 0 -ATT, 0.00, 7.26, -4.76, -5.05, 0.00, 48.67, 52.50 -CTUN, 755, 0.27, 2.07, 0.000000, 0, 4, -34, 759, 0 -ATT, -5.77, -1.59, -2.42, 0.73, 0.00, 47.94, 52.50 -CTUN, 741, 0.27, 1.81, 0.000000, 0, 1, -34, 742, 0 -ATT, -9.75, -3.71, -2.42, 3.63, 0.00, 47.50, 52.50 -CTUN, 742, 0.27, 1.83, 0.000000, 0, 3, -38, 744, 0 -ATT, -10.04, -6.43, -3.45, 4.26, 0.00, 47.40, 52.50 -CTUN, 742, 0.27, 1.84, 0.000000, 0, 7, -41, 748, 0 -ATT, -6.91, -10.04, -6.72, 2.13, 0.00, 47.87, 52.50 -CTUN, 741, 0.24, 1.83, 0.000000, 0, 11, -44, 753, 0 -ATT, -4.16, -10.85, -8.21, -1.43, 0.00, 48.76, 52.50 -CTUN, 741, 0.24, 1.76, 0.000000, 0, 10, -42, 751, 0 -ATT, 0.00, -8.74, -8.77, -4.40, 0.00, 49.30, 52.50 -CTUN, 741, 0.20, 1.29, 0.000000, 0, 7, -37, 749, 0 -ATT, 0.00, -5.52, -6.81, -5.85, 0.00, 49.23, 52.50 -CTUN, 742, 0.20, 0.46, 0.000000, 0, 4, -31, 745, 0 -ATT, 0.18, -3.07, -2.05, -4.90, 0.00, 48.93, 52.50 -DU32, 7, 166140 -CURR, 741, 1407990, 1017, 1927, 5051, 1057.430900 -CTUN, 740, 0.20, -0.68, 0.000000, 0, 1, -23, 741, 0 -ATT, 1.59, -1.33, -1.21, -1.90, 0.00, 48.80, 52.50 -CTUN, 741, 0.20, -0.98, 0.000000, 0, 0, -13, 740, 0 -ATT, 0.84, -0.58, 0.00, 1.74, 0.00, 48.80, 52.50 -CTUN, 741, 0.20, -1.50, 0.000000, 0, 0, -9, 741, 0 -ATT, 0.09, 0.01, 0.00, 3.41, 0.00, 48.94, 52.50 -CTUN, 741, 0.20, -1.33, 0.000000, 0, 1, 0, 742, 0 -ATT, 0.00, 0.74, 0.00, 3.79, 0.00, 49.26, 52.50 -CTUN, 740, 0.20, -1.17, 0.000000, 0, 1, 1, 742, 0 -ATT, 0.00, 0.45, 0.00, 3.66, 0.00, 49.60, 52.50 -CTUN, 740, 0.20, -0.45, 0.000000, 0, 1, 5, 741, 0 -ATT, 0.00, 0.11, 0.00, 3.64, 0.00, 50.08, 52.50 -CTUN, 740, 0.20, 0.55, 0.000000, 0, 1, 4, 742, 0 -ATT, 0.00, 0.08, 0.00, 4.61, 0.00, 50.65, 52.50 -CTUN, 740, 0.20, 1.12, 0.000000, 0, 2, 5, 742, 0 -ATT, 0.00, -0.27, 0.00, 5.92, 0.00, 51.33, 52.50 -CTUN, 740, 0.20, 1.51, 0.000000, 0, 3, 1, 744, 0 -ATT, 0.00, -0.41, 0.00, 5.49, 0.00, 51.97, 52.50 -CTUN, 740, 0.20, 1.62, 0.000000, 0, 2, -1, 742, 0 -ATT, 0.00, -0.26, -0.84, 4.04, 0.00, 52.46, 52.50 -DU32, 7, 166140 -CURR, 740, 1415407, 1008, 1897, 5051, 1062.697600 -CTUN, 740, 0.20, 1.83, 0.000000, 0, 1, -3, 741, 0 -ATT, 0.00, -0.15, -2.52, 2.82, 0.00, 52.86, 52.50 -CTUN, 736, 0.20, 1.84, 0.000000, 0, 0, -7, 736, 0 -ATT, 0.00, 0.00, -2.42, 1.94, 0.00, 53.10, 52.50 -CTUN, 736, 0.20, 1.93, 0.000000, 0, 0, -10, 735, 0 -ATT, 0.00, 0.21, -2.42, 1.30, 0.00, 53.27, 52.50 -CTUN, 736, 0.20, 1.84, 0.000000, 0, 0, -13, 736, 0 -ATT, 0.00, 0.36, -4.48, 1.08, 0.00, 53.38, 52.50 -CTUN, 737, 0.20, 1.80, 0.000000, 0, 0, -15, 737, 0 -ATT, 0.00, -0.02, -4.76, 0.72, 0.00, 53.39, 52.50 -CTUN, 742, 0.20, 1.65, 0.000000, 0, 0, -17, 741, 0 -ATT, 0.00, -0.32, -4.76, -0.54, 0.00, 53.36, 52.50 -CTUN, 745, 0.20, 1.43, 0.000000, 0, 0, -22, 745, 0 -ATT, 0.09, -0.90, -4.85, -1.55, 0.00, 53.24, 52.50 -CTUN, 751, 0.20, 0.99, 0.000000, 0, 0, -20, 751, 0 -ATT, 1.03, -1.45, -5.60, -2.22, 0.00, 53.10, 52.50 -CTUN, 768, 0.20, 1.16, 0.000000, 0, 0, -18, 767, 0 -ATT, 1.03, -0.96, -5.69, -2.26, 0.00, 52.94, 52.50 -CTUN, 782, 0.20, 0.85, 0.000000, 0, 0, -12, 782, 0 -ATT, 1.40, -0.19, -5.69, -2.20, 0.00, 52.68, 52.50 -DU32, 7, 166140 -CURR, 782, 1422866, 1004, 2076, 5051, 1068.017600 -CTUN, 788, 0.20, 0.98, 0.000000, 0, 0, -1, 786, 0 -ATT, 1.59, 0.25, -5.69, -1.72, 0.00, 52.43, 52.50 -CTUN, 789, 0.20, 0.32, 0.000000, 0, 0, 3, 788, 0 -ATT, 2.06, 0.49, -5.69, -1.44, 0.00, 52.09, 52.50 -CTUN, 789, 0.20, 1.01, 0.000000, 0, 0, 8, 789, 0 -ATT, 2.06, 0.61, -5.69, -1.75, 0.00, 51.71, 52.50 -CTUN, 789, 0.20, 0.91, 0.000000, 0, 0, 16, 789, 0 -ATT, 2.34, 0.35, -5.69, -1.99, 0.00, 51.46, 52.50 -CTUN, 789, 0.20, 1.62, 0.000000, 0, 0, 22, 789, 0 -ATT, 2.34, 0.36, -5.22, -2.24, 0.00, 51.34, 52.50 -CTUN, 789, 0.20, 1.85, 0.000000, 0, 0, 24, 789, 0 -ATT, 3.18, 0.72, -5.04, -2.24, 0.00, 51.27, 52.50 -CTUN, 789, 0.20, 1.80, 0.000000, 0, 0, 28, 789, 0 -ATT, 3.93, 1.30, -4.85, -2.42, 0.00, 51.17, 52.50 -CTUN, 789, 0.21, 1.95, 0.000000, 0, 0, 29, 789, 0 -ATT, 3.93, 2.02, -4.85, -2.40, 0.00, 51.07, 52.50 -CTUN, 789, 0.21, 1.93, 0.000000, 0, 1, 25, 791, 0 -ATT, 4.50, 2.88, -4.76, -2.33, 0.00, 50.94, 52.50 -CTUN, 789, 0.26, 2.12, 0.000000, 0, 1, 26, 790, 0 -ATT, 4.50, 3.02, -4.85, -1.77, 0.00, 50.74, 52.50 -DU32, 7, 166140 -CURR, 789, 1430750, 998, 2135, 5028, 1073.940600 -CTUN, 790, 0.26, 1.95, 0.000000, 0, 1, 23, 790, 0 -ATT, 3.75, 3.59, -4.76, -1.34, 0.00, 50.42, 52.50 -CTUN, 789, 0.31, 2.11, 0.000000, 0, 1, 18, 790, 0 -ATT, 3.28, 3.61, -4.48, -1.13, 0.00, 49.99, 52.50 -CTUN, 789, 0.31, 2.05, 0.000000, 0, 1, 14, 791, 0 -ATT, 1.78, 2.72, -3.08, -0.99, 0.00, 49.57, 52.50 -CTUN, 796, 0.36, 2.14, 0.000000, 0, 0, 8, 796, 0 -ATT, 0.00, 1.23, -2.24, -0.53, 0.00, 49.05, 52.50 -CTUN, 800, 0.36, 2.00, 0.000000, 0, 0, 9, 798, 0 -ATT, 0.00, -0.84, -2.24, 0.56, 0.00, 48.43, 52.50 -CTUN, 804, 0.39, 2.07, 0.000000, 0, 0, 5, 804, 0 -ATT, 0.00, -1.71, -2.52, 1.40, 0.00, 47.83, 52.50 -CTUN, 804, 0.39, 2.17, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, -1.27, -2.70, 1.84, 0.00, 47.51, 52.50 -CTUN, 813, 0.40, 2.14, 0.000000, 0, 0, 3, 813, 0 -ATT, 0.00, -0.83, -3.26, 1.71, 0.00, 47.29, 52.50 -CTUN, 819, 0.39, 2.14, 0.000000, 0, 0, 4, 818, 0 -ATT, 0.00, -1.00, -3.26, 1.14, 0.00, 47.20, 52.50 -CTUN, 830, 0.40, 2.21, 0.000000, 0, 0, 5, 828, 0 -ATT, 0.00, -1.06, -3.45, 0.85, 0.00, 47.27, 52.50 -DU32, 7, 166140 -CURR, 830, 1438770, 987, 2284, 5051, 1079.993700 -CTUN, 830, 0.40, 2.22, 0.000000, 0, 0, 8, 830, 0 -ATT, 0.00, -0.67, -3.92, 0.54, 0.00, 47.41, 52.50 -CTUN, 834, 0.40, 2.24, 0.000000, 0, 0, 11, 834, 0 -ATT, 0.00, -0.33, -4.20, 0.20, 0.00, 47.57, 52.50 -CTUN, 834, 0.40, 2.34, 0.000000, 0, 0, 12, 834, 0 -ATT, 0.00, 0.04, -4.57, 0.26, 0.00, 47.76, 52.50 -CTUN, 834, 0.40, 2.22, 0.000000, 0, 0, 17, 834, 0 -ATT, 0.09, 0.16, -4.57, 0.55, 0.00, 47.89, 52.50 -CTUN, 834, 0.40, 2.17, 0.000000, 0, 0, 22, 834, 0 -ATT, 0.18, 0.19, -4.57, 0.04, 0.00, 47.85, 52.50 -CTUN, 833, 0.41, 2.39, 0.000000, 0, 0, 21, 833, 0 -ATT, 0.28, 0.55, -4.57, -1.31, 0.00, 47.85, 52.50 -CTUN, 831, 0.41, 2.31, 0.000000, 0, 0, 22, 831, 0 -ATT, 0.37, 1.14, -4.57, -2.06, 0.00, 47.92, 52.50 -CTUN, 831, 0.43, 2.13, 0.000000, 0, 0, 25, 831, 0 -ATT, 0.28, 1.15, -5.04, -2.04, 0.00, 48.03, 52.50 -CTUN, 830, 0.43, 2.29, 0.000000, 0, 0, 26, 830, 0 -ATT, 0.28, 1.34, -6.81, -2.22, 0.00, 48.19, 52.50 -CTUN, 824, 0.46, 2.25, 0.000000, 0, 0, 30, 825, 0 -ATT, 0.09, 1.72, -6.81, -2.34, 0.00, 48.35, 52.50 -DU32, 7, 166140 -CURR, 821, 1447086, 988, 2314, 5051, 1086.510400 -CTUN, 821, 0.46, 2.40, 0.000000, 0, 0, 31, 821, 0 -ATT, 0.00, 1.26, -6.72, -2.53, 0.00, 48.50, 52.50 -CTUN, 821, 0.49, 2.52, 0.000000, 0, 0, 29, 821, 0 -ATT, 0.00, 0.61, -6.53, -3.07, 0.00, 48.49, 52.50 -CTUN, 815, 0.49, 2.54, 0.000000, 0, 1, 29, 816, 0 -ATT, 0.00, 0.53, -6.16, -3.51, 0.00, 48.40, 52.50 -CTUN, 803, 0.52, 2.36, 0.000000, 0, 1, 30, 806, 0 -ATT, 0.00, 0.74, -6.06, -2.97, 0.00, 48.23, 52.50 -CTUN, 796, 0.52, 2.46, 0.000000, 0, 0, 30, 796, 0 -ATT, 0.00, 0.60, -6.25, -2.34, 0.00, 48.08, 52.50 -CTUN, 795, 0.55, 2.41, 0.000000, 0, 0, 25, 795, 0 -ATT, 0.00, 0.24, -6.25, -2.39, 0.00, 48.01, 52.50 -CTUN, 795, 0.55, 2.33, 0.000000, 0, 0, 20, 794, 0 -ATT, 0.00, -0.31, -6.53, -3.01, 0.00, 47.90, 52.50 -PM, 0, 0, 0, 1, 1000, 111708, 0, 0 -CTUN, 795, 0.58, 2.48, 0.000000, 0, 1, 14, 796, 0 -ATT, 0.00, -0.76, -6.06, -3.53, 0.00, 47.91, 52.50 -CTUN, 795, 0.58, 2.33, 0.000000, 0, 1, 11, 796, 0 -ATT, 0.00, -0.35, -6.06, -3.86, 0.00, 48.05, 52.50 -CTUN, 796, 0.58, 2.40, 0.000000, 0, 1, 7, 797, 0 -ATT, 0.00, -0.10, -5.97, -3.62, 0.00, 48.26, 52.50 -DU32, 7, 166140 -CURR, 798, 1455130, 997, 2134, 5051, 1092.585100 -CTUN, 798, 0.58, 2.44, 0.000000, 0, 1, 6, 799, 0 -ATT, 0.00, -0.38, -4.76, -2.79, 0.00, 48.61, 52.50 -CTUN, 804, 0.58, 2.41, 0.000000, 0, 0, 2, 804, 0 -ATT, 0.00, -0.16, -4.57, -1.57, 0.00, 49.11, 52.50 -CTUN, 810, 0.57, 2.31, 0.000000, 0, 0, 0, 807, 0 -ATT, 0.00, 0.04, -4.38, -0.53, 0.00, 49.76, 52.50 -CTUN, 814, 0.57, 2.37, 0.000000, 0, 0, -1, 814, 0 -ATT, -0.18, -0.16, -2.70, 0.16, 0.00, 50.50, 52.50 -CTUN, 823, 0.53, 2.35, 0.000000, 0, 0, -3, 823, 0 -ATT, -0.75, -0.29, -2.70, 0.75, 0.00, 51.20, 52.50 -CTUN, 831, 0.53, 2.36, 0.000000, 0, 0, -3, 830, 0 -ATT, -0.75, 0.04, -2.42, 1.39, 0.00, 51.82, 52.50 -CTUN, 836, 0.50, 2.40, 0.000000, 0, 0, -4, 836, 0 -ATT, -0.75, 0.28, -2.52, 1.43, 0.00, 52.27, 52.50 -CTUN, 838, 0.50, 2.25, 0.000000, 0, 0, -1, 837, 0 -ATT, -0.94, 0.34, -2.70, 1.37, 0.00, 52.42, 52.50 -CTUN, 840, 0.46, 2.30, 0.000000, 0, 0, 0, 840, 0 -ATT, -1.13, 0.64, -2.89, 1.59, 0.00, 52.52, 52.50 -CTUN, 844, 0.46, 2.13, 0.000000, 0, 0, 3, 844, 0 -ATT, -1.80, 0.39, -1.96, 1.63, 0.00, 52.62, 52.50 -DU32, 7, 166140 -CURR, 846, 1463348, 984, 2402, 5051, 1098.897700 -CTUN, 847, 0.42, 2.18, 0.000000, 0, 0, 7, 847, 0 -ATT, -2.55, 0.77, -2.52, 1.67, 0.00, 52.82, 52.50 -CTUN, 846, 0.42, 1.99, 0.000000, 0, 0, 12, 846, 0 -ATT, -3.69, 0.82, -3.64, 1.49, 0.00, 53.13, 52.50 -CTUN, 847, 0.40, 2.24, 0.000000, 0, 0, 10, 847, 0 -ATT, -3.69, 0.19, -3.54, 0.40, 0.00, 53.44, 52.50 -CTUN, 846, 0.40, 2.16, 0.000000, 0, 0, 13, 846, 0 -ATT, -3.69, -1.46, -6.53, -1.23, 0.00, 53.61, 52.50 -CTUN, 844, 0.39, 2.14, 0.000000, 0, 0, 18, 844, 0 -ATT, -3.78, -2.52, -7.84, -2.89, 0.00, 53.78, 52.50 -CTUN, 842, 0.40, 2.03, 0.000000, 0, 2, 23, 844, 0 -ATT, -3.78, -2.61, -7.84, -4.55, 0.00, 53.77, 52.50 -CTUN, 840, 0.39, 2.08, 0.000000, 0, 3, 26, 843, 0 -ATT, -3.97, -2.16, -7.56, -5.48, 0.00, 53.79, 52.50 -CTUN, 838, 0.40, 2.00, 0.000000, 0, 3, 30, 841, 0 -ATT, -3.97, -2.58, -7.56, -5.48, 0.00, 53.95, 52.50 -CTUN, 835, 0.40, 2.19, 0.000000, 0, 4, 35, 840, 0 -ATT, -3.69, -3.80, -7.46, -4.82, 0.00, 54.16, 52.50 -CTUN, 830, 0.43, 2.17, 0.000000, 0, 3, 37, 833, 0 -ATT, -2.93, -3.90, -7.18, -4.34, 0.00, 54.26, 52.50 -DU32, 7, 166140 -CURR, 828, 1471782, 983, 2375, 5051, 1105.572000 -CTUN, 826, 0.43, 2.37, 0.000000, 0, 3, 38, 829, 0 -ATT, -1.80, -3.18, -6.72, -4.14, 0.00, 54.10, 52.50 -CTUN, 824, 0.47, 2.29, 0.000000, 0, 2, 42, 828, 0 -ATT, -0.94, -1.56, -6.72, -3.36, 0.00, 53.48, 52.50 -CTUN, 821, 0.47, 2.48, 0.000000, 0, 0, 40, 821, 0 -ATT, 0.00, -0.64, -6.06, -2.07, 0.00, 52.70, 52.50 -CTUN, 815, 0.51, 2.49, 0.000000, 0, 0, 40, 815, 0 -ATT, 0.00, -0.93, -4.76, -1.12, 0.00, 51.93, 52.50 -CTUN, 813, 0.51, 2.52, 0.000000, 0, 0, 41, 813, 0 -ATT, 0.00, 0.67, -4.57, -0.64, 0.00, 51.09, 52.50 -CTUN, 813, 0.57, 2.65, 0.000000, 0, 0, 39, 813, 0 -ATT, 0.00, 2.02, -4.57, -0.49, 0.00, 50.07, 52.50 -CTUN, 813, 0.57, 2.55, 0.000000, 0, 0, 35, 813, 0 -ATT, 0.00, 2.17, -4.38, -0.73, 0.00, 49.15, 52.50 -CTUN, 813, 0.61, 2.63, 0.000000, 0, 0, 29, 813, 0 -ATT, 0.00, 1.79, -4.57, -0.91, 0.00, 48.46, 52.50 -CTUN, 813, 0.61, 2.56, 0.000000, 0, 0, 25, 813, 0 -ATT, -0.94, 1.66, -3.92, -0.95, 0.00, 48.13, 52.50 -CTUN, 812, 0.64, 2.59, 0.000000, 0, 0, 22, 813, 0 -ATT, -1.32, 0.91, -3.73, -0.13, 0.00, 48.18, 52.50 -DU32, 7, 166140 -CURR, 813, 1479959, 987, 2201, 5051, 1111.829200 -CTUN, 812, 0.64, 2.59, 0.000000, 0, 0, 19, 812, 0 -ATT, -1.32, -0.50, -3.64, 1.50, 0.00, 48.38, 52.50 -CTUN, 813, 0.67, 2.51, 0.000000, 0, 0, 20, 813, 0 -ATT, -1.61, -1.71, -3.36, 3.55, 0.00, 48.74, 52.50 -CTUN, 813, 0.67, 2.61, 0.000000, 0, 2, 19, 815, 0 -ATT, -2.36, -1.99, -2.24, 4.67, 0.00, 49.38, 52.50 -CTUN, 816, 0.69, 2.58, 0.000000, 0, 3, 18, 817, 0 -ATT, -2.74, -2.49, -2.70, 4.89, 0.00, 50.30, 52.50 -CTUN, 816, 0.69, 2.63, 0.000000, 0, 3, 16, 819, 0 -ATT, -2.65, -2.90, -2.61, 4.30, 0.00, 51.38, 52.50 -CTUN, 816, 0.69, 2.61, 0.000000, 0, 2, 14, 817, 0 -ATT, -2.65, -3.30, -4.38, 3.67, 0.00, 52.22, 52.50 -CTUN, 818, 0.69, 2.63, 0.000000, 0, 2, 14, 820, 0 -ATT, -2.17, -3.53, -4.57, 3.26, 0.00, 53.00, 52.50 -CTUN, 824, 0.69, 2.73, 0.000000, 0, 2, 12, 826, 0 -ATT, -0.75, -3.65, -5.50, 2.49, 0.00, 53.66, 52.50 -CTUN, 825, 0.68, 2.68, 0.000000, 0, 1, 13, 826, 0 -ATT, 0.00, -3.60, -6.25, 0.70, 0.00, 54.31, 52.50 -CTUN, 827, 0.68, 2.63, 0.000000, 0, 1, 11, 828, 0 -ATT, 0.00, -2.93, -7.28, -1.99, 0.00, 54.87, 52.50 -DU32, 7, 166140 -CURR, 826, 1488145, 991, 2309, 5051, 1118.114700 -CTUN, 827, 0.68, 2.53, 0.000000, 0, 1, 10, 827, 0 -ATT, 0.00, -2.21, -7.84, -4.42, 0.00, 55.17, 52.50 -CTUN, 826, 0.68, 2.48, 0.000000, 0, 3, 12, 828, 0 -ATT, 0.00, -1.92, -8.02, -5.92, 0.00, 55.23, 52.50 -CTUN, 826, 0.65, 2.40, 0.000000, 0, 4, 13, 830, 0 -ATT, 0.28, -1.55, -8.12, -6.53, 0.00, 55.16, 52.50 -CTUN, 826, 0.65, 2.40, 0.000000, 0, 4, 14, 830, 0 -ATT, 1.78, -0.87, -7.56, -6.63, 0.00, 54.88, 52.50 -CTUN, 825, 0.65, 2.43, 0.000000, 0, 4, 14, 830, 0 -ATT, 3.18, -0.22, -6.81, -6.38, 0.00, 54.46, 52.50 -CTUN, 826, 0.65, 2.41, 0.000000, 0, 3, 16, 829, 0 -ATT, 3.09, 1.16, -6.16, -5.63, 0.00, 53.98, 52.50 -CTUN, 825, 0.63, 2.51, 0.000000, 0, 3, 17, 828, 0 -ATT, 3.18, 3.48, -5.97, -4.78, 0.00, 53.50, 52.50 -CTUN, 825, 0.63, 2.61, 0.000000, 0, 4, 17, 830, 0 -ATT, 3.09, 4.52, -5.88, -4.25, 0.00, 53.06, 52.50 -CTUN, 825, 0.63, 2.41, 0.000000, 0, 3, 19, 828, 0 -ATT, 3.18, 4.46, -5.50, -3.72, 0.00, 52.75, 52.50 -CTUN, 826, 0.64, 2.39, 0.000000, 0, 3, 22, 829, 0 -ATT, 0.28, 4.93, -4.76, -3.64, 0.00, 52.78, 52.50 -DU32, 7, 166140 -CURR, 825, 1496432, 986, 2343, 5028, 1124.604500 -CTUN, 825, 0.64, 2.37, 0.000000, 0, 4, 23, 829, 0 -ATT, 0.00, 4.52, -4.76, -3.62, 0.00, 53.17, 52.50 -CTUN, 825, 0.65, 2.55, 0.000000, 0, 2, 25, 828, 0 -ATT, 0.00, 1.87, -5.50, -3.39, 0.00, 53.73, 52.50 -CTUN, 825, 0.65, 2.61, 0.000000, 0, 1, 26, 826, 0 -ATT, 0.00, -0.23, -6.16, -2.72, 0.00, 54.47, 52.50 -CTUN, 824, 0.67, 2.59, 0.000000, 0, 0, 27, 825, 0 -ATT, 0.00, -0.90, -6.53, -2.03, 0.00, 55.36, 52.50 -CTUN, 824, 0.67, 2.65, 0.000000, 0, 0, 27, 824, 0 -ATT, 0.00, -1.25, -6.34, -1.76, 0.00, 56.38, 52.50 -CTUN, 824, 0.70, 2.63, 0.000000, 0, 0, 29, 824, 0 -ATT, 0.00, -1.29, -6.53, -2.15, 0.00, 57.32, 52.50 -CTUN, 823, 0.70, 2.63, 0.000000, 0, 0, 31, 824, 0 -ATT, 0.00, -1.34, -5.22, -2.85, 0.00, 58.23, 52.50 -CTUN, 823, 0.73, 2.70, 0.000000, 0, 1, 31, 824, 0 -ATT, 0.00, -1.46, -2.33, -3.20, 0.00, 59.09, 52.50 -CTUN, 824, 0.73, 2.66, 0.000000, 0, 1, 29, 825, 0 -ATT, 0.00, -0.98, -2.33, -2.26, 0.00, 59.73, 52.50 -CTUN, 824, 0.77, 2.76, 0.000000, 0, 0, 30, 824, 0 -ATT, 0.00, -0.74, -2.52, -0.29, 0.00, 60.00, 52.50 -DU32, 7, 166140 -CURR, 824, 1504683, 984, 2262, 5051, 1131.049000 -CTUN, 824, 0.77, 2.79, 0.000000, 0, 0, 29, 823, 0 -ATT, 0.00, -1.51, -2.52, 1.30, 0.00, 59.93, 52.50 -CTUN, 823, 0.79, 2.70, 0.000000, 0, 0, 26, 823, 0 -ATT, 0.00, -1.68, -2.52, 1.66, 0.00, 59.61, 52.50 -CTUN, 824, 0.79, 2.75, 0.000000, 0, 0, 26, 824, 0 -ATT, 0.00, -1.40, -2.52, 1.04, 0.00, 59.23, 52.50 -CTUN, 823, 0.82, 2.76, 0.000000, 0, 0, 25, 823, 0 -ATT, 0.00, -0.80, -2.52, -0.08, 0.00, 58.85, 52.50 -CTUN, 823, 0.82, 2.85, 0.000000, 0, 0, 24, 823, 0 -ATT, 0.00, -0.32, -2.52, -0.58, 0.00, 58.60, 52.50 -CTUN, 823, 0.85, 2.94, 0.000000, 0, 0, 27, 823, 0 -ATT, 0.00, -0.72, -2.70, -0.51, 0.00, 58.48, 52.50 -CTUN, 823, 0.85, 2.90, 0.000000, 0, 0, 27, 823, 0 -ATT, 0.00, -1.31, -2.61, -0.56, 0.00, 58.44, 52.50 -CTUN, 824, 0.87, 2.81, 0.000000, 0, 0, 27, 824, 0 -ATT, 0.00, -1.25, -2.61, -0.76, 0.00, 58.48, 52.50 -CTUN, 824, 0.87, 2.75, 0.000000, 0, 0, 27, 824, 0 -ATT, 0.00, -1.04, -2.61, -0.94, 0.00, 58.57, 52.50 -CTUN, 823, 0.90, 2.87, 0.000000, 0, 0, 27, 823, 0 -ATT, 0.00, -1.02, -2.70, -1.25, 0.00, 58.69, 52.50 -DU32, 7, 166140 -CURR, 823, 1512918, 985, 2317, 5051, 1137.431900 -CTUN, 823, 0.90, 2.87, 0.000000, 0, 0, 27, 823, 0 -ATT, 0.18, -1.19, -2.89, -1.70, 0.00, 58.77, 52.50 -CTUN, 823, 0.91, 2.81, 0.000000, 0, 0, 28, 823, 0 -ATT, 1.68, -1.38, -2.70, -2.05, 0.00, 58.80, 52.50 -CTUN, 823, 0.91, 2.86, 0.000000, 0, 0, 28, 824, 0 -ATT, 2.71, -0.94, -2.61, -1.99, 0.00, 58.75, 52.50 -CTUN, 823, 0.94, 2.88, 0.000000, 0, 0, 28, 823, 0 -ATT, 3.28, 0.51, -2.61, -1.84, 0.00, 58.69, 52.50 -CTUN, 822, 0.94, 3.00, 0.000000, 0, 0, 27, 821, 0 -ATT, 3.93, 1.78, -2.70, -1.73, 0.00, 58.61, 52.50 -CTUN, 816, 0.96, 2.93, 0.000000, 0, 0, 28, 816, 0 -ATT, 4.50, 2.82, -2.70, -1.54, 0.00, 58.47, 52.50 -CTUN, 804, 0.96, 2.89, 0.000000, 0, 1, 27, 805, 0 -ATT, 5.25, 3.97, -2.70, -1.55, 0.00, 58.18, 52.50 -CTUN, 792, 0.98, 2.82, 0.000000, 0, 2, 24, 794, 0 -ATT, 5.06, 5.16, -2.70, -1.90, 0.00, 57.69, 52.50 -CTUN, 789, 0.98, 2.99, 0.000000, 0, 3, 19, 792, 0 -ATT, 5.25, 5.95, -3.08, -2.35, 0.00, 57.13, 52.50 -CTUN, 788, 1.01, 2.97, 0.000000, 0, 4, 16, 793, 0 -ATT, 5.06, 6.37, -3.08, -2.55, 0.00, 56.49, 52.50 -DU32, 7, 166140 -CURR, 788, 1521038, 995, 2125, 5051, 1143.694700 -CTUN, 788, 1.01, 3.08, 0.000000, 0, 4, 11, 792, 0 -ATT, 4.96, 6.27, -3.08, -2.53, 0.00, 55.89, 52.50 -CTUN, 788, 1.02, 2.96, 0.000000, 0, 4, 10, 792, 0 -ATT, 3.93, 5.75, -3.26, -2.12, 0.00, 55.37, 52.50 -CTUN, 792, 1.02, 2.99, 0.000000, 0, 3, 5, 795, 0 -ATT, 2.53, 4.64, -2.80, -2.05, 0.00, 54.92, 52.50 -CTUN, 796, 1.02, 3.06, 0.000000, 0, 1, 4, 797, 0 -ATT, 0.37, 3.06, -2.52, -2.18, 0.00, 54.42, 52.50 -CTUN, 805, 1.02, 2.95, 0.000000, 0, 0, 0, 803, 0 -ATT, 0.00, 1.33, -2.70, -1.90, 0.00, 53.83, 52.50 -CTUN, 809, 1.02, 2.95, 0.000000, 0, 0, 0, 809, 0 -ATT, 0.00, 0.29, -2.98, -1.58, 0.00, 53.23, 52.50 -CTUN, 813, 1.00, 3.07, 0.000000, 0, 0, -1, 813, 0 -ATT, 0.00, 0.16, -3.36, -1.48, 0.00, 52.61, 52.50 -CTUN, 815, 1.00, 2.96, 0.000000, 0, 0, -1, 815, 0 -ATT, 0.00, 0.51, -3.64, -1.38, 0.00, 52.03, 52.50 -CTUN, 819, 0.98, 3.02, 0.000000, 0, 0, 0, 819, 0 -ATT, 0.00, 0.42, -4.01, -1.22, 0.00, 51.43, 52.50 -CTUN, 828, 0.98, 2.94, 0.000000, 0, 0, -4, 828, 0 -ATT, 0.00, 0.29, -3.92, -1.17, 0.00, 51.01, 52.50 -DU32, 7, 166140 -CURR, 830, 1529087, 986, 2257, 5028, 1149.725200 -CTUN, 830, 0.94, 2.88, 0.000000, 0, 0, -2, 829, 0 -ATT, 0.00, 0.21, -3.92, -0.92, 0.00, 50.76, 52.50 -CTUN, 831, 0.94, 2.81, 0.000000, 0, 0, -1, 831, 0 -ATT, 0.00, 0.77, -3.82, -0.54, 0.00, 50.73, 52.50 -CTUN, 833, 0.90, 2.85, 0.000000, 0, 0, 0, 833, 0 -ATT, 0.00, 1.26, -3.92, -0.08, 0.00, 50.83, 52.50 -CTUN, 838, 0.90, 2.81, 0.000000, 0, 0, 4, 836, 0 -ATT, -0.75, 1.15, -4.38, 0.10, 0.00, 50.97, 52.50 -CTUN, 838, 0.87, 2.86, 0.000000, 0, 0, 7, 838, 0 -ATT, -1.42, 0.93, -4.10, 0.03, 0.00, 51.22, 52.50 -CTUN, 838, 0.87, 2.76, 0.000000, 0, 0, 13, 838, 0 -ATT, -1.98, 0.54, -3.92, 0.05, 0.00, 51.63, 52.50 -CTUN, 837, 0.85, 2.70, 0.000000, 0, 0, 16, 837, 0 -ATT, -2.55, -0.05, -4.29, -0.15, 0.00, 52.04, 52.50 -PM, 0, 0, 0, 0, 1000, 10464, 0, 0 -CTUN, 838, 0.85, 2.80, 0.000000, 0, 0, 16, 838, 0 -ATT, -2.84, -1.51, -4.57, -2.00, 0.00, 52.41, 52.50 -CTUN, 838, 0.84, 2.74, 0.000000, 0, 1, 18, 839, 0 -ATT, -3.97, -2.33, -3.92, -2.61, 0.00, 52.62, 52.50 -CTUN, 838, 0.84, 2.79, 0.000000, 0, 1, 23, 839, 0 -ATT, -4.83, -2.26, -4.57, -1.63, 0.00, 52.54, 52.50 -DU32, 7, 166140 -CURR, 838, 1537441, 982, 2377, 5051, 1156.191200 -CTUN, 838, 0.84, 2.79, 0.000000, 0, 0, 24, 838, 0 -ATT, -4.54, -3.49, -4.48, -0.45, 0.00, 52.51, 52.50 -CTUN, 838, 0.84, 2.75, 0.000000, 0, 1, 28, 839, 0 -ATT, -4.64, -4.50, -4.57, 0.16, 0.00, 52.54, 52.50 -CTUN, 838, 0.84, 2.77, 0.000000, 0, 1, 28, 839, 0 -ATT, -4.35, -3.89, -4.29, 0.20, 0.00, 52.80, 52.50 -CTUN, 838, 0.87, 2.77, 0.000000, 0, 1, 32, 839, 0 -ATT, -4.16, -3.27, -4.10, 0.23, 0.00, 53.07, 52.50 -CTUN, 836, 0.87, 2.84, 0.000000, 0, 0, 34, 836, 0 -ATT, -3.22, -2.69, -4.94, 0.41, 0.00, 53.29, 52.50 -CTUN, 819, 0.88, 2.79, 0.000000, 0, 0, 35, 819, 0 -ATT, -1.98, -2.44, -5.22, 0.59, 0.00, 53.54, 52.50 -CTUN, 809, 0.87, 2.91, 0.000000, 0, 0, 32, 814, 0 -ATT, -1.80, -1.80, -5.69, -0.04, 0.00, 53.96, 52.50 -CTUN, 798, 0.88, 2.88, 0.000000, 0, 0, 32, 798, 0 -ATT, -1.70, -0.85, -6.06, -1.41, 0.00, 54.36, 52.50 -CTUN, 792, 0.88, 2.84, 0.000000, 0, 0, 30, 792, 0 -ATT, -1.61, -0.38, -6.53, -2.73, 0.00, 54.82, 52.50 -CTUN, 780, 0.96, 2.89, 0.000000, 0, 0, 26, 784, 0 -ATT, -1.61, -0.39, -6.44, -3.35, 0.00, 55.09, 52.50 -DU32, 7, 166140 -CURR, 766, 1545654, 994, 2089, 5051, 1162.539600 -CTUN, 765, 0.96, 2.87, 0.000000, 0, 1, 19, 766, 0 -ATT, -1.61, -0.48, -6.25, -3.82, 0.00, 55.28, 52.50 -CTUN, 766, 0.99, 2.97, 0.000000, 0, 1, 11, 767, 0 -ATT, -1.61, -0.78, -6.53, -4.32, 0.00, 55.21, 52.50 -CTUN, 768, 0.99, 2.99, 0.000000, 0, 2, 3, 769, 0 -ATT, -1.51, -1.02, -6.16, -4.69, 0.00, 54.94, 52.50 -CTUN, 782, 1.00, 2.94, 0.000000, 0, 2, -7, 784, 0 -ATT, -1.80, -1.18, -5.88, -5.09, 0.00, 54.63, 52.50 -CTUN, 790, 0.99, 2.97, 0.000000, 0, 2, -12, 792, 0 -ATT, -1.70, -0.85, -5.60, -5.23, 0.00, 54.28, 52.50 -CTUN, 805, 0.99, 2.88, 0.000000, 0, 2, -17, 801, 0 -ATT, -1.80, -0.41, -5.69, -4.71, 0.00, 53.74, 52.50 -CTUN, 813, 0.96, 2.96, 0.000000, 0, 1, -23, 814, 0 -ATT, -1.80, -0.28, -5.41, -3.77, 0.00, 52.84, 52.50 -CTUN, 815, 0.96, 2.91, 0.000000, 0, 0, -26, 815, 0 -ATT, -1.80, 0.28, -5.04, -2.31, 0.00, 51.54, 52.50 -CTUN, 817, 0.90, 2.97, 0.000000, 0, 0, -28, 817, 0 -ATT, -1.80, 0.15, -4.85, -0.96, 0.00, 50.18, 52.50 -CTUN, 821, 0.90, 2.83, 0.000000, 0, 0, -28, 821, 0 -ATT, -2.36, -1.67, -4.57, 0.56, 0.00, 49.03, 52.50 -DU32, 7, 166140 -CURR, 827, 1553592, 997, 2229, 5028, 1168.386000 -CTUN, 833, 0.80, 2.99, 0.000000, 0, 1, -32, 834, 0 -ATT, -3.60, -4.24, -3.45, 1.58, 0.00, 48.26, 52.50 -CTUN, 836, 0.80, 2.92, 0.000000, 0, 3, -33, 838, 0 -ATT, -3.12, -6.00, -3.08, 2.57, 0.00, 47.93, 52.50 -CTUN, 836, 0.73, 2.87, 0.000000, 0, 5, -30, 841, 0 -ATT, -3.12, -6.20, -3.08, 3.94, 0.00, 47.84, 52.50 -CTUN, 835, 0.73, 2.90, 0.000000, 0, 5, -34, 841, 0 -ATT, -2.74, -5.07, -2.80, 4.21, 0.00, 48.40, 52.50 -CTUN, 836, 0.65, 2.87, 0.000000, 0, 4, -35, 840, 0 -ATT, -0.75, -4.35, -4.85, 3.72, 0.00, 49.40, 52.50 -CTUN, 835, 0.65, 2.64, 0.000000, 0, 2, -33, 837, 0 -ATT, 0.00, -3.35, -5.13, 2.42, 0.00, 50.44, 52.50 -CTUN, 835, 0.56, 2.59, 0.000000, 0, 0, -33, 835, 0 -ATT, 0.00, -1.78, -5.78, 0.69, 0.00, 51.35, 52.50 -CTUN, 836, 0.56, 2.44, 0.000000, 0, 0, -33, 836, 0 -ATT, 0.00, -0.37, -5.50, -0.82, 0.00, 52.33, 52.50 -CTUN, 835, 0.46, 2.39, 0.000000, 0, 0, -32, 836, 0 -ATT, 0.00, 0.39, -5.22, -1.85, 0.00, 53.36, 52.50 -CTUN, 836, 0.46, 2.44, 0.000000, 0, 0, -28, 836, 0 -ATT, 0.00, 0.32, -5.50, -2.37, 0.00, 54.18, 52.50 -DU32, 7, 166140 -CURR, 836, 1561964, 973, 2352, 5051, 1174.850100 -CTUN, 835, 0.37, 2.39, 0.000000, 0, 0, -23, 835, 0 -ATT, 0.28, -0.67, -5.69, -2.39, 0.00, 54.81, 52.50 -CTUN, 836, 0.37, 2.29, 0.000000, 0, 0, -16, 836, 0 -ATT, 1.21, -0.60, -5.88, -2.59, 0.00, 55.27, 52.50 -CTUN, 835, 0.30, 2.36, 0.000000, 0, 0, -9, 836, 0 -ATT, 2.53, 0.05, -6.16, -2.42, 0.00, 55.47, 52.50 -CTUN, 836, 0.30, 2.14, 0.000000, 0, 0, -4, 836, 0 -ATT, 2.53, 0.32, -6.44, -2.28, 0.00, 55.69, 52.50 -CTUN, 836, 0.26, 2.14, 0.000000, 0, 0, 2, 836, 0 -ATT, 3.18, 0.97, -6.25, -2.35, 0.00, 55.84, 52.50 -CTUN, 836, 0.26, 2.01, 0.000000, 0, 0, 11, 835, 0 -ATT, 3.56, 1.59, -6.25, -2.66, 0.00, 55.86, 52.50 -CTUN, 836, 0.24, 2.11, 0.000000, 0, 1, 20, 837, 0 -ATT, 3.93, 2.92, -6.16, -2.52, 0.00, 55.86, 52.50 -CTUN, 835, 0.24, 2.10, 0.000000, 0, 1, 24, 837, 0 -ATT, 3.93, 2.98, -5.69, -1.79, 0.00, 55.92, 52.50 -CTUN, 836, 0.24, 2.24, 0.000000, 0, 1, 26, 837, 0 -ATT, 3.75, 2.59, -4.85, -1.03, 0.00, 55.98, 52.50 -CTUN, 835, 0.25, 2.21, 0.000000, 0, 0, 30, 835, 0 -ATT, 3.28, 2.61, -4.48, -0.18, 0.00, 55.91, 52.50 -DU32, 7, 166140 -CURR, 835, 1570325, 982, 2357, 5051, 1181.419100 -CTUN, 833, 0.25, 2.31, 0.000000, 0, 0, 33, 833, 0 -ATT, 1.78, 2.56, -5.69, 0.47, 0.00, 55.64, 52.50 -CTUN, 830, 0.29, 2.37, 0.000000, 0, 0, 32, 831, 0 -ATT, 0.28, 2.05, -8.02, 0.74, 0.00, 55.29, 52.50 -CTUN, 830, 0.29, 2.24, 0.000000, 0, 0, 32, 830, 0 -ATT, 0.09, 0.80, -8.21, -0.07, 0.00, 54.97, 52.50 -CTUN, 828, 0.35, 2.26, 0.000000, 0, 0, 34, 828, 0 -ATT, 0.28, -0.10, -8.40, -1.64, 0.00, 54.57, 52.50 -CTUN, 821, 0.35, 2.50, 0.000000, 0, 0, 33, 822, 0 -ATT, 0.09, -0.49, -8.77, -3.80, 0.00, 54.27, 52.50 -CTUN, 816, 0.40, 2.74, 0.000000, 0, 2, 33, 818, 0 -ATT, 1.78, -0.22, -10.36, -4.76, 0.00, 53.87, 52.50 -CTUN, 815, 0.40, 2.53, 0.000000, 0, 2, 30, 818, 0 -ATT, 2.43, 0.73, -10.64, -5.33, 0.00, 53.52, 52.50 -CTUN, 815, 0.45, 2.84, 0.000000, 0, 3, 30, 818, 0 -ATT, 3.18, 1.78, -10.64, -5.96, 0.00, 53.19, 52.50 -CTUN, 815, 0.45, 2.72, 0.000000, 0, 4, 25, 820, 0 -ATT, 3.37, 2.46, -10.64, -6.52, 0.00, 53.01, 52.50 -CTUN, 815, 0.50, 2.66, 0.000000, 0, 5, 26, 820, 0 -ATT, 2.81, 2.81, -8.96, -7.09, 0.00, 52.95, 52.50 -DU32, 7, 166140 -CURR, 815, 1578561, 987, 2263, 5028, 1187.802100 -CTUN, 816, 0.50, 2.59, 0.000000, 0, 6, 22, 822, 0 -ATT, 1.78, 3.11, -8.02, -7.19, 0.00, 53.11, 52.50 -CTUN, 815, 0.54, 2.56, 0.000000, 0, 5, 21, 820, 0 -ATT, 0.00, 2.57, -6.72, -6.14, 0.00, 53.44, 52.50 -CTUN, 816, 0.54, 2.60, 0.000000, 0, 3, 19, 819, 0 -ATT, 0.00, 0.70, -4.76, -4.33, 0.00, 54.06, 52.50 -CTUN, 815, 0.57, 2.61, 0.000000, 0, 1, 17, 816, 0 -ATT, 0.00, -0.29, -4.76, -2.52, 0.00, 54.83, 52.50 -CTUN, 815, 0.57, 2.72, 0.000000, 0, 0, 17, 815, 0 -ATT, 0.00, 0.02, -4.76, -0.89, 0.00, 55.47, 52.50 -CTUN, 816, 0.60, 2.73, 0.000000, 0, 0, 15, 815, 0 -ATT, 0.00, 0.88, -4.76, -0.16, 0.00, 56.04, 52.50 -CTUN, 815, 0.60, 2.67, 0.000000, 0, 0, 16, 815, 0 -ATT, 0.00, 1.22, -4.48, -0.49, 0.00, 56.57, 52.50 -CTUN, 816, 0.61, 2.84, 0.000000, 0, 0, 13, 815, 0 -ATT, 0.00, 1.14, -3.73, -1.25, 0.00, 56.92, 52.50 -CTUN, 813, 0.61, 2.75, 0.000000, 0, 0, 15, 813, 0 -ATT, 0.00, 0.49, -2.61, -1.60, 0.00, 57.06, 52.50 -CTUN, 812, 0.64, 2.76, 0.000000, 0, 0, 16, 812, 0 -ATT, 0.00, 0.00, -2.52, -1.10, 0.00, 56.93, 52.50 -DU32, 7, 166140 -CURR, 812, 1586727, 989, 2266, 5051, 1194.098300 -CTUN, 813, 0.64, 2.84, 0.000000, 0, 0, 16, 813, 0 -ATT, 0.00, 0.09, -2.52, -0.03, 0.00, 56.55, 52.50 -CTUN, 813, 0.66, 2.93, 0.000000, 0, 0, 13, 813, 0 -ATT, 0.00, 0.34, -2.52, 0.99, 0.00, 56.01, 52.50 -CTUN, 813, 0.66, 2.89, 0.000000, 0, 0, 12, 812, 0 -ATT, 0.00, 0.32, -2.52, 1.93, 0.00, 55.20, 52.50 -CTUN, 813, 0.69, 2.73, 0.000000, 0, 0, 13, 813, 0 -ATT, 0.00, 0.39, -2.05, 2.53, 0.00, 54.07, 52.50 -CTUN, 813, 0.69, 2.69, 0.000000, 0, 0, 16, 813, 0 -ATT, 0.00, 0.73, -2.33, 2.95, 0.00, 52.67, 52.50 -CTUN, 812, 0.70, 2.73, 0.000000, 0, 1, 12, 813, 0 -ATT, 0.00, 0.89, -2.42, 2.99, 0.00, 51.05, 52.50 -CTUN, 813, 0.70, 2.77, 0.000000, 0, 0, 11, 813, 0 -ATT, 0.00, 0.51, -3.26, 2.51, 0.00, 49.41, 52.50 -CTUN, 813, 0.71, 2.71, 0.000000, 0, 0, 9, 813, 0 -ATT, 0.00, -0.02, -4.20, 1.72, 0.00, 47.94, 52.50 -CTUN, 813, 0.71, 2.63, 0.000000, 0, 0, 8, 813, 0 -ATT, 0.00, -0.41, -4.76, 0.75, 0.00, 46.65, 52.50 -CTUN, 813, 0.72, 2.67, 0.000000, 0, 0, 6, 813, 0 -ATT, 0.00, -0.36, -4.57, -0.34, 0.00, 45.62, 52.50 -DU32, 7, 166140 -CURR, 813, 1594855, 989, 2242, 5028, 1200.329300 -CTUN, 812, 0.72, 2.69, 0.000000, 0, 0, 5, 812, 0 -ATT, 0.00, -0.01, -2.52, -1.42, 0.00, 44.88, 52.50 -CTUN, 813, 0.74, 2.67, 0.000000, 0, 0, 5, 812, 0 -ATT, 0.00, -0.09, -2.52, -1.14, 0.00, 44.44, 52.50 -CTUN, 813, 0.74, 2.77, 0.000000, 0, 0, 2, 813, 0 -ATT, 0.00, -0.40, -2.52, 0.01, 0.00, 44.35, 52.50 -CTUN, 813, 0.75, 2.81, 0.000000, 0, 0, 0, 813, 0 -ATT, 0.00, -1.36, -2.33, 1.28, 0.00, 44.69, 52.50 -CTUN, 813, 0.75, 2.76, 0.000000, 0, 0, 1, 813, 0 -ATT, 0.00, -1.96, -2.52, 2.01, 0.00, 45.39, 52.50 -CTUN, 813, 0.76, 2.86, 0.000000, 0, 0, -1, 813, 0 -ATT, 0.00, -1.10, -2.52, 1.60, 0.00, 46.31, 52.50 -CTUN, 812, 0.76, 2.76, 0.000000, 0, 0, -4, 812, 0 -ATT, 0.00, -0.10, -3.36, 1.12, 0.00, 47.36, 52.50 -CTUN, 813, 0.77, 2.87, 0.000000, 0, 0, -8, 813, 0 -ATT, 0.00, 0.48, -4.57, 0.56, 0.00, 48.47, 52.50 -CTUN, 812, 0.76, 2.81, 0.000000, 0, 0, -7, 812, 0 -ATT, 0.00, 1.02, -4.76, -0.71, 0.00, 49.71, 52.50 -CTUN, 812, 0.76, 2.94, 0.000000, 0, 0, -9, 812, 0 -ATT, 0.00, 1.13, -6.72, -1.59, 0.00, 50.72, 52.50 -DU32, 7, 166140 -CURR, 813, 1602982, 987, 2206, 5028, 1206.486700 -CTUN, 812, 0.76, 2.88, 0.000000, 0, 0, -12, 813, 0 -ATT, 0.00, 1.18, -6.72, -1.86, 0.00, 51.78, 52.50 -CTUN, 812, 0.76, 2.89, 0.000000, 0, 0, -16, 812, 0 -ATT, 0.00, 1.21, -4.85, -2.10, 0.00, 52.83, 52.50 -CTUN, 813, 0.73, 2.79, 0.000000, 0, 0, -18, 813, 0 -ATT, -0.18, 1.02, -4.76, -2.36, 0.00, 53.83, 52.50 -CTUN, 813, 0.73, 2.75, 0.000000, 0, 0, -24, 813, 0 -ATT, -2.08, 0.66, -4.38, -2.63, 0.00, 54.85, 52.50 -CTUN, 812, 0.71, 2.69, 0.000000, 0, 0, -24, 812, 0 -ATT, -3.41, -0.61, -3.36, -2.70, 0.00, 55.68, 52.50 -CTUN, 812, 0.71, 2.79, 0.000000, 0, 0, -26, 812, 0 -ATT, -3.12, -2.32, -3.08, -2.79, 0.00, 56.48, 52.50 -CTUN, 812, 0.67, 2.71, 0.000000, 0, 1, -27, 813, 0 -ATT, -3.12, -3.58, -3.08, -2.92, 0.00, 57.14, 52.50 -CTUN, 812, 0.67, 2.73, 0.000000, 0, 2, -30, 815, 0 -ATT, -3.31, -4.34, -3.26, -2.78, 0.00, 57.60, 52.50 -CTUN, 813, 0.63, 2.84, 0.000000, 0, 3, -34, 816, 0 -ATT, -3.22, -4.84, -3.26, -2.57, 0.00, 57.78, 52.50 -CTUN, 813, 0.63, 2.70, 0.000000, 0, 2, -37, 815, 0 -ATT, -3.03, -3.40, -3.08, -1.54, 0.00, 57.72, 52.50 -DU32, 7, 166140 -CURR, 812, 1611116, 985, 2239, 5051, 1212.663700 -CTUN, 813, 0.57, 2.67, 0.000000, 0, 0, -38, 813, 0 -ATT, -3.12, -2.22, -3.08, -0.44, 0.00, 57.36, 52.50 -CTUN, 813, 0.57, 2.52, 0.000000, 0, 0, -39, 813, 0 -ATT, -1.51, -1.66, -3.17, 0.45, 0.00, 56.82, 52.50 -CTUN, 813, 0.50, 2.38, 0.000000, 0, 0, -41, 813, 0 -ATT, -0.94, -2.41, -3.08, 1.14, 0.00, 56.30, 52.50 -CTUN, 813, 0.50, 2.54, 0.000000, 0, 0, -43, 813, 0 -ATT, -0.85, -2.25, -3.08, 0.39, 0.00, 55.93, 52.50 -CTUN, 813, 0.43, 2.54, 0.000000, 0, 0, -45, 813, 0 -ATT, -0.94, -0.13, -3.26, -0.95, 0.00, 55.80, 52.50 -CTUN, 813, 0.43, 2.21, 0.000000, 0, 0, -45, 813, 0 -ATT, -0.75, 1.06, -4.38, -2.06, 0.00, 55.77, 52.50 -CTUN, 813, 0.35, 2.26, 0.000000, 0, 0, -43, 813, 0 -ATT, -0.85, 0.70, -4.57, -2.52, 0.00, 55.98, 52.50 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 813, 0.35, 2.30, 0.000000, 0, 0, -40, 813, 0 -ATT, -0.94, 0.84, -3.54, -2.81, 0.00, 56.22, 52.50 -CTUN, 812, 0.27, 2.26, 0.000000, 0, 0, -35, 813, 0 -ATT, -1.80, 0.69, -1.77, -2.58, 0.00, 56.55, 52.50 -CTUN, 813, 0.27, 2.22, 0.000000, 0, 0, -25, 813, 0 -ATT, -2.55, -0.53, -2.52, -2.05, 0.00, 56.94, 52.50 -DU32, 7, 166140 -CURR, 813, 1619245, 979, 2232, 5051, 1218.859300 -CTUN, 812, 0.21, 2.09, 0.000000, 0, 0, -15, 813, 0 -ATT, -2.74, -1.23, -2.61, -1.34, 0.00, 57.44, 52.50 -CTUN, 812, 0.21, 2.10, 0.000000, 0, 0, -2, 812, 0 -ATT, -2.74, -1.61, -2.70, -0.52, 0.00, 57.87, 52.50 -CTUN, 813, 0.21, 2.30, 0.000000, 0, 0, 3, 813, 0 -ATT, -2.74, -1.90, -2.70, -0.72, 0.00, 58.22, 52.50 -CTUN, 813, 0.21, 2.14, 0.000000, 0, 0, 9, 813, 0 -ATT, -2.27, -2.51, -2.24, -1.44, 0.00, 58.62, 52.50 -CTUN, 812, 0.20, 2.20, 0.000000, 0, 0, 17, 813, 0 -ATT, -2.08, -1.81, -2.05, -1.83, 0.00, 58.91, 52.50 -CTUN, 813, 0.20, 2.26, 0.000000, 0, 0, 21, 812, 0 -ATT, -1.80, -0.82, -1.77, -0.67, 0.00, 59.18, 52.50 -CTUN, 813, 0.20, 2.20, 0.000000, 0, 0, 25, 813, 0 -ATT, -2.08, -0.92, -2.05, 0.87, 0.00, 59.57, 52.50 -CTUN, 812, 0.22, 2.26, 0.000000, 0, 0, 26, 812, 0 -ATT, 0.00, -0.89, -2.52, 1.89, 0.00, 59.96, 52.50 -CTUN, 812, 0.22, 2.41, 0.000000, 0, 0, 22, 812, 0 -ATT, 0.00, -0.09, -2.42, 1.84, 0.00, 60.31, 52.50 -CTUN, 813, 0.27, 2.21, 0.000000, 0, 0, 23, 813, 0 -ATT, 0.00, 2.19, -2.42, 2.14, 0.00, 60.69, 52.50 -DU32, 7, 166140 -CURR, 813, 1627375, 988, 2094, 5051, 1224.965100 -CTUN, 813, 0.27, 2.41, 0.000000, 0, 1, 18, 814, 0 -ATT, 0.00, 3.42, -2.52, 3.20, 0.00, 60.58, 52.50 -CTUN, 813, 0.31, 2.40, 0.000000, 0, 2, 10, 815, 0 -ATT, 0.00, 2.77, -2.52, 2.98, 0.00, 59.86, 52.50 -CTUN, 813, 0.31, 2.47, 0.000000, 0, 1, 4, 814, 0 -ATT, 0.00, 2.60, -2.42, 1.24, 0.00, 58.80, 52.50 -CTUN, 813, 0.34, 2.50, 0.000000, 0, 0, 4, 813, 0 -ATT, -0.09, 2.44, -2.42, -0.82, 0.00, 57.41, 52.50 -CTUN, 813, 0.34, 2.47, 0.000000, 0, 0, 8, 812, 0 -ATT, -0.75, 1.65, -2.52, -2.17, 0.00, 56.34, 52.50 -CTUN, 813, 0.36, 2.48, 0.000000, 0, 0, 9, 813, 0 -ATT, -0.75, 0.71, -2.70, -2.26, 0.00, 55.67, 52.50 -CTUN, 813, 0.36, 2.61, 0.000000, 0, 0, 10, 813, 0 -ATT, -0.56, -1.33, -2.52, -2.01, 0.00, 55.22, 52.50 -CTUN, 813, 0.38, 2.60, 0.000000, 0, 0, 8, 813, 0 -ATT, -0.75, -2.84, -2.52, -1.82, 0.00, 55.10, 52.50 -CTUN, 813, 0.38, 2.71, 0.000000, 0, 1, 7, 814, 0 -ATT, -0.66, -3.46, -2.70, -1.77, 0.00, 55.21, 52.50 -CTUN, 813, 0.42, 2.69, 0.000000, 0, 1, 4, 814, 0 -ATT, -0.66, -2.77, -2.61, -1.50, 0.00, 55.36, 52.50 -DU32, 7, 166140 -CURR, 813, 1635507, 986, 2239, 5028, 1231.110200 -CTUN, 813, 0.42, 2.72, 0.000000, 0, 0, 7, 813, 0 -ATT, 0.00, -1.09, -2.52, -0.14, 0.00, 55.58, 52.50 -CTUN, 813, 0.43, 2.65, 0.000000, 0, 0, 5, 813, 0 -ATT, 0.00, 0.02, -2.52, 2.04, 0.00, 56.00, 52.50 -CTUN, 812, 0.43, 2.77, 0.000000, 0, 0, 2, 812, 0 -ATT, 0.00, -0.05, -1.77, 2.50, 0.00, 56.77, 52.50 -CTUN, 813, 0.44, 2.43, 0.000000, 0, 0, 0, 813, 0 -ATT, 0.00, -0.05, -1.40, 1.07, 0.00, 57.38, 52.50 -CTUN, 813, 0.43, 2.63, 0.000000, 0, 0, 2, 813, 0 -ATT, 0.00, -0.26, -2.14, -0.06, 0.00, 57.19, 52.50 -CTUN, 813, 0.43, 2.64, 0.000000, 0, 0, 4, 813, 0 -ATT, 0.00, -0.45, -2.42, -1.08, 0.00, 56.36, 52.50 -CTUN, 813, 0.42, 2.47, 0.000000, 0, 0, 4, 813, 0 -ATT, 0.00, 0.83, -2.42, -1.86, 0.00, 54.80, 52.50 -CTUN, 813, 0.42, 2.52, 0.000000, 0, 0, 2, 812, 0 -ATT, 0.00, 0.91, -2.61, -1.72, 0.00, 52.91, 52.50 -CTUN, 813, 0.42, 2.48, 0.000000, 0, 0, 4, 813, 0 -ATT, 0.00, 0.06, -2.42, -1.12, 0.00, 51.81, 52.50 -CTUN, 813, 0.43, 2.66, 0.000000, 0, 0, 2, 812, 0 -ATT, 0.00, 0.08, -2.70, -0.84, 0.00, 51.26, 52.50 -DU32, 7, 166140 -CURR, 813, 1643634, 984, 2213, 5051, 1237.312500 -CTUN, 812, 0.42, 2.70, 0.000000, 0, 0, 1, 812, 0 -ATT, 0.00, 0.61, -2.70, -0.38, 0.00, 50.89, 52.50 -CTUN, 813, 0.43, 2.68, 0.000000, 0, 0, 0, 813, 0 -ATT, 0.00, 0.80, -2.61, -0.15, 0.00, 50.56, 52.50 -CTUN, 813, 0.42, 2.62, 0.000000, 0, 0, 0, 812, 0 -ATT, 0.00, 0.54, -2.70, 0.08, 0.00, 50.23, 52.50 -CTUN, 813, 0.42, 2.59, 0.000000, 0, 0, 0, 813, 0 -ATT, 0.00, 0.07, -2.89, 0.14, 0.00, 49.96, 52.50 -CTUN, 813, 0.42, 2.59, 0.000000, 0, 0, 0, 812, 0 -ATT, 0.00, 0.22, -2.70, 0.45, 0.00, 49.76, 52.50 -CTUN, 813, 0.42, 2.58, 0.000000, 0, 0, -2, 813, 0 -ATT, -0.37, 0.69, -3.36, 0.30, 0.00, 49.48, 52.50 -CTUN, 812, 0.42, 2.63, 0.000000, 0, 0, -5, 813, 0 -ATT, -0.66, 0.00, -4.29, -0.15, 0.00, 49.32, 52.50 -CTUN, 813, 0.42, 2.53, 0.000000, 0, 0, -10, 813, 0 -ATT, -0.75, -1.60, -4.76, -0.97, 0.00, 49.45, 52.50 -CTUN, 813, 0.40, 2.47, 0.000000, 0, 0, -16, 812, 0 -ATT, -0.85, -1.72, -4.76, -2.14, 0.00, 49.93, 52.50 -CTUN, 813, 0.40, 2.37, 0.000000, 0, 0, -17, 813, 0 -ATT, -1.42, -0.92, -4.76, -2.77, 0.00, 50.75, 52.50 -DU32, 7, 166140 -CURR, 812, 1651759, 982, 2180, 5051, 1243.450800 -CTUN, 813, 0.39, 2.62, 0.000000, 0, 0, -17, 813, 0 -ATT, -1.42, -0.49, -4.85, -2.48, 0.00, 51.46, 52.50 -CTUN, 813, 0.39, 2.50, 0.000000, 0, 0, -19, 813, 0 -ATT, -0.66, -0.59, -4.38, -2.48, 0.00, 52.33, 52.50 -CTUN, 813, 0.36, 2.46, 0.000000, 0, 0, -22, 813, 0 -ATT, -0.18, -0.95, -4.01, -3.38, 0.00, 53.37, 52.50 -CTUN, 813, 0.36, 2.55, 0.000000, 0, 1, -21, 814, 0 -ATT, -0.18, -0.36, -3.45, -3.63, 0.00, 54.34, 52.50 -CTUN, 813, 0.32, 2.61, 0.000000, 0, 1, -19, 814, 0 -ATT, 0.00, -0.64, -3.08, -2.45, 0.00, 55.04, 52.50 -CTUN, 813, 0.32, 2.37, 0.000000, 0, 0, -19, 813, 0 -ATT, 0.00, -1.17, -2.70, -1.69, 0.00, 55.58, 52.50 -CTUN, 812, 0.29, 2.49, 0.000000, 0, 0, -14, 812, 0 -ATT, 0.00, -0.76, -2.52, -0.75, 0.00, 55.87, 52.50 -CTUN, 813, 0.29, 2.37, 0.000000, 0, 0, -11, 812, 0 -ATT, 0.00, -0.73, -2.52, 0.49, 0.00, 55.97, 52.50 -CTUN, 812, 0.26, 2.31, 0.000000, 0, 0, -8, 812, 0 -ATT, 0.00, -0.57, -2.52, 1.18, 0.00, 56.11, 52.50 -CTUN, 813, 0.26, 2.14, 0.000000, 0, 0, -6, 813, 0 -ATT, 0.00, 0.26, -2.52, 0.56, 0.00, 56.40, 52.50 -DU32, 7, 166140 -CURR, 813, 1659888, 988, 2238, 5051, 1249.593900 -CTUN, 812, 0.25, 2.15, 0.000000, 0, 0, 0, 813, 0 -ATT, 0.00, 0.02, -2.52, -0.53, 0.00, 56.75, 52.50 -CTUN, 813, 0.25, 2.22, 0.000000, 0, 0, 1, 813, 0 -ATT, 0.00, -0.30, -2.61, -1.92, 0.00, 57.21, 52.50 -CTUN, 812, 0.25, 2.31, 0.000000, 0, 0, 6, 813, 0 -ATT, 0.00, 0.15, -2.70, -1.85, 0.00, 57.48, 52.50 -CTUN, 813, 0.25, 2.12, 0.000000, 0, 0, 12, 812, 0 -ATT, 0.00, -0.32, -2.70, -0.76, 0.00, 57.54, 52.50 -CTUN, 812, 0.25, 2.28, 0.000000, 0, 0, 14, 813, 0 -ATT, 0.00, -0.70, -2.61, -0.77, 0.00, 57.53, 52.50 -CTUN, 812, 0.28, 2.24, 0.000000, 0, 0, 14, 812, 0 -ATT, 0.00, 0.03, -2.70, -1.59, 0.00, 57.48, 52.50 -CTUN, 812, 0.28, 2.29, 0.000000, 0, 0, 11, 813, 0 -ATT, 0.00, 0.63, -2.70, -1.94, 0.00, 57.36, 52.50 -CTUN, 813, 0.31, 2.42, 0.000000, 0, 0, 11, 813, 0 -ATT, 0.00, 0.90, -2.61, -2.27, 0.00, 57.50, 52.50 -CTUN, 812, 0.31, 2.43, 0.000000, 0, 0, 12, 812, 0 -ATT, 0.00, 1.70, -2.61, -1.65, 0.00, 57.68, 52.50 -CTUN, 813, 0.34, 2.58, 0.000000, 0, 0, 13, 813, 0 -ATT, 0.00, 2.50, -2.70, -0.07, 0.00, 57.45, 52.50 -DU32, 7, 166140 -CURR, 812, 1668016, 992, 2136, 5051, 1255.850300 -CTUN, 812, 0.34, 2.58, 0.000000, 0, 0, 10, 812, 0 -ATT, 0.00, 1.94, -2.42, 0.30, 0.00, 56.94, 52.50 -CTUN, 812, 0.37, 2.58, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, 0.72, -2.52, 0.03, 0.00, 56.58, 52.50 -CTUN, 813, 0.37, 2.47, 0.000000, 0, 0, 8, 813, 0 -ATT, 0.00, -0.19, -2.24, -1.16, 0.00, 56.66, 52.50 -CTUN, 812, 0.40, 2.58, 0.000000, 0, 0, 6, 813, 0 -ATT, 0.00, -0.76, -2.42, -1.33, 0.00, 56.78, 52.50 -CTUN, 812, 0.40, 2.64, 0.000000, 0, 0, 9, 812, 0 -ATT, -0.56, -0.51, -2.33, -0.85, 0.00, 56.71, 52.50 -CTUN, 813, 0.41, 2.59, 0.000000, 0, 0, 7, 813, 0 -ATT, -0.75, 0.24, -0.74, -0.71, 0.00, 56.28, 52.50 -CTUN, 813, 0.41, 2.62, 0.000000, 0, 0, 12, 813, 0 -ATT, -0.75, -0.65, -0.74, 0.70, 0.00, 55.76, 52.50 -CTUN, 813, 0.43, 2.77, 0.000000, 0, 0, 14, 813, 0 -ATT, -0.56, -1.50, -0.56, 2.61, 0.00, 55.24, 52.50 -CTUN, 813, 0.43, 2.81, 0.000000, 0, 1, 13, 813, 0 -ATT, -0.37, -1.72, -0.37, 2.89, 0.00, 55.03, 52.50 -CTUN, 812, 0.45, 2.67, 0.000000, 0, 0, 13, 812, 0 -ATT, -0.75, -1.06, -0.74, 1.22, 0.00, 54.93, 52.50 -DU32, 7, 166140 -CURR, 812, 1676146, 983, 2254, 5051, 1262.135900 -CTUN, 813, 0.45, 2.80, 0.000000, 0, 0, 13, 813, 0 -ATT, 0.00, -1.41, -2.05, -0.04, 0.00, 54.84, 52.50 -CTUN, 812, 0.48, 2.76, 0.000000, 0, 0, 17, 812, 0 -ATT, 0.00, -1.65, -2.52, -0.96, 0.00, 54.57, 52.50 -CTUN, 813, 0.48, 2.86, 0.000000, 0, 0, 11, 813, 0 -ATT, 0.00, -0.88, -2.61, -2.28, 0.00, 54.23, 52.50 -CTUN, 813, 0.49, 2.79, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, -0.78, -2.70, -2.78, 0.00, 53.96, 52.50 -CTUN, 813, 0.49, 2.77, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, -0.56, -2.70, -2.79, 0.00, 53.52, 52.50 -CTUN, 813, 0.51, 2.90, 0.000000, 0, 0, 10, 813, 0 -ATT, 0.00, -0.12, -2.80, -2.59, 0.00, 53.11, 52.50 -CTUN, 812, 0.51, 2.85, 0.000000, 0, 0, 9, 812, 0 -ATT, 0.00, -0.69, -2.89, -2.55, 0.00, 53.05, 52.50 -CTUN, 813, 0.52, 2.82, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, -2.46, -2.70, -2.18, 0.00, 53.31, 52.50 -CTUN, 813, 0.52, 2.82, 0.000000, 0, 1, 13, 813, 0 -ATT, 0.00, -3.09, -2.70, -1.18, 0.00, 54.00, 52.50 -CTUN, 812, 0.54, 2.91, 0.000000, 0, 0, 14, 813, 0 -ATT, 0.00, -1.78, -2.70, -0.37, 0.00, 54.86, 52.50 -DU32, 7, 166140 -CURR, 813, 1684275, 987, 2272, 5051, 1268.367900 -CTUN, 813, 0.54, 2.89, 0.000000, 0, 0, 13, 813, 0 -ATT, 0.00, -1.07, -2.70, 0.41, 0.00, 55.79, 52.50 -CTUN, 813, 0.56, 2.85, 0.000000, 0, 0, 13, 812, 0 -ATT, 0.00, -2.11, -2.61, 1.54, 0.00, 57.00, 52.50 -CTUN, 813, 0.56, 2.78, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, -1.96, -2.61, 1.62, 0.00, 58.46, 52.50 -CTUN, 813, 0.58, 2.89, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, -1.35, -2.70, 1.01, 0.00, 59.86, 52.50 -CTUN, 813, 0.58, 2.75, 0.000000, 0, 0, 12, 813, 0 -ATT, 0.00, 0.09, -2.70, 0.56, 0.00, 61.13, 52.50 -CTUN, 810, 0.60, 2.93, 0.000000, 0, 0, 4, 810, 0 -ATT, 0.00, 1.32, -2.61, 0.69, 0.00, 62.34, 52.50 -CTUN, 809, 0.60, 2.76, 0.000000, 0, 0, -2, 809, 0 -ATT, 0.00, 1.01, -2.61, 0.72, 0.00, 63.41, 53.41 -CTUN, 808, 0.60, 2.82, 0.000000, 0, 0, -10, 808, 0 -ATT, 0.00, 0.31, -2.80, 0.37, 0.00, 64.35, 54.35 -CTUN, 806, 0.60, 2.90, 0.000000, 0, 0, -17, 807, 0 -ATT, 0.09, -0.17, -3.08, -0.03, 0.00, 65.01, 55.01 -CTUN, 805, 0.60, 2.84, 0.000000, 0, 0, -20, 805, 0 -ATT, 0.46, -0.27, -3.17, -0.33, 0.00, 65.31, 55.31 -DU32, 7, 166140 -CURR, 805, 1692378, 992, 2200, 5051, 1274.398100 -CTUN, 805, 0.57, 2.80, 0.000000, 0, 0, -26, 805, 0 -ATT, 0.46, 0.46, -3.26, -0.31, 0.00, 65.39, 55.40 -CTUN, 804, 0.57, 2.58, 0.000000, 0, 0, -31, 804, 0 -ATT, 0.46, 1.33, -3.73, -0.15, 0.00, 65.26, 55.40 -CTUN, 804, 0.50, 2.74, 0.000000, 0, 0, -42, 804, 0 -ATT, 1.78, 0.78, -4.29, -0.44, 0.00, 64.81, 55.40 -CTUN, 804, 0.50, 2.48, 0.000000, 0, 0, -44, 805, 0 -ATT, 1.59, -0.16, -4.38, -0.82, 0.00, 63.99, 55.40 -CTUN, 805, 0.43, 2.53, 0.000000, 0, 0, -47, 805, 0 -ATT, 1.59, -0.16, -4.57, -0.77, 0.00, 62.80, 55.40 -CTUN, 804, 0.43, 2.54, 0.000000, 0, 0, -48, 804, 0 -ATT, 1.59, 0.34, -4.57, -0.90, 0.00, 61.17, 55.40 -CTUN, 805, 0.33, 2.40, 0.000000, 0, 0, -44, 805, 0 -ATT, 1.40, 0.62, -4.76, -1.48, 0.00, 59.36, 55.40 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 805, 0.33, 2.38, 0.000000, 0, 0, -41, 805, 0 -ATT, 1.78, 0.20, -4.76, -2.22, 0.00, 57.76, 55.40 -CTUN, 804, 0.25, 1.98, 0.000000, 0, 0, -33, 805, 0 -ATT, 1.78, 0.24, -4.85, -2.18, 0.00, 56.40, 55.40 -CTUN, 805, 0.25, 2.06, 0.000000, 0, 0, -21, 804, 0 -ATT, 1.68, 0.14, -4.85, -1.06, 0.00, 55.42, 55.40 -DU32, 7, 166140 -CURR, 804, 1700422, 984, 2192, 5051, 1280.453400 -CTUN, 804, 0.20, 1.20, 0.000000, 0, 0, -9, 804, 0 -ATT, 1.78, 0.05, -4.76, -0.11, 0.00, 54.57, 55.40 -CTUN, 805, 0.20, 0.69, 0.000000, 0, 0, 0, 805, 0 -ATT, 2.81, 0.57, -4.48, 0.17, 0.00, 53.67, 55.40 -CTUN, 805, 0.20, 0.64, 0.000000, 0, 0, 7, 804, 0 -ATT, 2.90, 0.75, -4.57, 0.09, 0.00, 52.94, 55.40 -CTUN, 805, 0.20, 1.07, 0.000000, 0, 0, 14, 805, 0 -ATT, 3.09, 0.73, -4.85, 0.14, 0.00, 52.43, 55.40 -CTUN, 805, 0.20, 1.05, 0.000000, 0, 0, 22, 805, 0 -ATT, 3.37, 1.48, -4.76, -0.43, 0.00, 52.19, 55.40 -CTUN, 804, 0.20, 1.92, 0.000000, 0, 0, 25, 805, 0 -ATT, 6.00, 1.26, -6.16, -1.18, 0.00, 52.19, 55.40 -CTUN, 804, 0.20, 2.27, 0.000000, 0, 0, 27, 804, 0 -ATT, 7.12, 2.30, -6.53, -2.06, 0.00, 52.22, 55.40 -CTUN, 805, 0.21, 2.28, 0.000000, 0, 1, 31, 805, 0 -ATT, 7.87, 5.53, -6.72, -2.35, 0.00, 52.40, 55.40 -CTUN, 804, 0.21, 2.45, 0.000000, 0, 5, 31, 809, 0 -ATT, 7.87, 8.42, -6.72, -2.49, 0.00, 52.83, 55.40 -CTUN, 804, 0.24, 2.49, 0.000000, 0, 9, 28, 814, 0 -ATT, 7.78, 9.36, -6.81, -3.20, 0.00, 53.34, 55.40 -DU32, 7, 166140 -CURR, 804, 1708481, 994, 2223, 5051, 1286.538800 -CTUN, 804, 0.24, 2.46, 0.000000, 0, 11, 23, 815, 0 -ATT, 6.28, 9.72, -6.81, -4.34, 0.00, 53.78, 55.40 -CTUN, 805, 0.30, 2.54, 0.000000, 0, 11, 22, 815, 0 -ATT, 0.28, 8.89, -6.72, -4.51, 0.00, 54.15, 55.40 -CTUN, 804, 0.30, 2.45, 0.000000, 0, 8, 19, 813, 0 -ATT, 0.00, 5.31, -6.72, -3.84, 0.00, 54.34, 55.40 -CTUN, 803, 0.36, 2.61, 0.000000, 0, 3, 15, 808, 0 -ATT, 0.00, 1.64, -6.06, -3.62, 0.00, 54.06, 55.40 -CTUN, 805, 0.36, 2.61, 0.000000, 0, 1, 13, 805, 0 -ATT, 0.00, 0.60, -6.06, -3.07, 0.00, 53.36, 55.40 -CTUN, 805, 0.43, 2.65, 0.000000, 0, 0, 9, 805, 0 -ATT, 0.00, 0.64, -6.72, -1.80, 0.00, 52.46, 55.40 -CTUN, 804, 0.43, 2.82, 0.000000, 0, 0, 6, 805, 0 -ATT, -1.32, 0.19, -6.81, -1.06, 0.00, 51.66, 55.40 -CTUN, 805, 0.46, 2.88, 0.000000, 0, 0, 3, 805, 0 -ATT, -4.16, -0.64, -7.93, -1.78, 0.00, 51.30, 55.40 -CTUN, 804, 0.46, 2.81, 0.000000, 0, 0, 1, 804, 0 -ATT, -6.25, -1.86, -8.30, -3.19, 0.00, 51.03, 55.40 -CTUN, 805, 0.50, 2.73, 0.000000, 0, 1, 0, 806, 0 -ATT, -7.76, -3.84, -7.56, -4.51, 0.00, 50.84, 55.40 -DU32, 7, 166140 -CURR, 804, 1716561, 997, 2179, 5051, 1292.618400 -CTUN, 805, 0.50, 2.81, 0.000000, 0, 4, -4, 809, 0 -ATT, -7.76, -6.16, -9.42, -5.05, 0.00, 50.50, 55.40 -CTUN, 804, 0.52, 2.67, 0.000000, 0, 7, -5, 811, 0 -ATT, -7.67, -7.35, -7.56, -5.51, 0.00, 49.96, 55.40 -CTUN, 804, 0.52, 2.72, 0.000000, 0, 9, -5, 813, 0 -ATT, -6.25, -7.23, -8.12, -5.50, 0.00, 49.18, 55.40 -CTUN, 805, 0.54, 2.72, 0.000000, 0, 7, -5, 812, 0 -ATT, -2.55, -6.27, -7.56, -5.15, 0.00, 48.41, 55.40 -CTUN, 805, 0.53, 2.82, 0.000000, 0, 6, -7, 811, 0 -ATT, -0.37, -4.68, -6.34, -4.90, 0.00, 47.79, 55.40 -CTUN, 804, 0.53, 2.92, 0.000000, 0, 3, -10, 808, 0 -ATT, 0.00, -2.61, -4.57, -4.25, 0.00, 47.34, 55.40 -CTUN, 804, 0.52, 2.81, 0.000000, 0, 1, -13, 806, 0 -ATT, 0.00, -0.55, -2.52, -3.20, 0.00, 47.20, 55.40 -CTUN, 805, 0.52, 2.89, 0.000000, 0, 0, -12, 805, 0 -ATT, 0.00, 0.64, -2.70, -1.73, 0.00, 47.52, 55.40 -CTUN, 804, 0.52, 2.96, 0.000000, 0, 0, -16, 804, 0 -ATT, 0.00, 1.25, -2.42, 0.19, 0.00, 48.17, 55.40 -CTUN, 804, 0.52, 2.92, 0.000000, 0, 0, -14, 805, 0 -ATT, 0.00, 1.11, -2.42, 2.24, 0.00, 49.12, 55.40 -DU32, 7, 166140 -CURR, 804, 1724645, 987, 2168, 5051, 1298.715700 -CTUN, 804, 0.50, 2.83, 0.000000, 0, 1, -15, 806, 0 -ATT, 0.00, 1.27, -2.52, 3.73, 0.00, 50.22, 55.40 -CTUN, 805, 0.50, 2.84, 0.000000, 0, 1, -23, 806, 0 -ATT, 0.00, 1.61, -2.61, 3.99, 0.00, 51.34, 55.40 -CTUN, 804, 0.48, 2.89, 0.000000, 0, 1, -24, 806, 0 -ATT, 0.00, 1.50, -2.70, 3.93, 0.00, 52.36, 55.40 -CTUN, 805, 0.48, 2.81, 0.000000, 0, 1, -27, 805, 0 -ATT, 0.00, 0.93, -3.64, 4.01, 0.00, 53.27, 55.40 -CTUN, 804, 0.46, 2.67, 0.000000, 0, 1, -31, 806, 0 -ATT, 0.00, 0.56, -5.04, 3.62, 0.00, 54.02, 55.40 -CTUN, 804, 0.46, 2.70, 0.000000, 0, 1, -31, 805, 0 -ATT, 0.00, 0.96, -6.34, 2.56, 0.00, 54.59, 55.40 -CTUN, 804, 0.41, 2.71, 0.000000, 0, 0, -34, 804, 0 -ATT, 0.00, 1.62, -6.81, 1.21, 0.00, 55.09, 55.40 -CTUN, 805, 0.41, 2.75, 0.000000, 0, 0, -34, 805, 0 -ATT, 0.00, 1.33, -6.81, -0.08, 0.00, 55.59, 55.40 -CTUN, 805, 0.35, 2.54, 0.000000, 0, 0, -34, 805, 0 -ATT, 0.00, 0.33, -6.72, -1.60, 0.00, 56.21, 55.40 -CTUN, 804, 0.35, 2.49, 0.000000, 0, 0, -30, 805, 0 -ATT, 0.00, -0.29, -6.81, -2.53, 0.00, 56.65, 55.40 -DU32, 7, 166140 -CURR, 805, 1732696, 982, 2161, 5051, 1304.756300 -CTUN, 804, 0.30, 2.56, 0.000000, 0, 0, -28, 804, 0 -ATT, 0.00, 0.02, -7.18, -2.91, 0.00, 56.98, 55.40 -CTUN, 804, 0.30, 2.49, 0.000000, 0, 0, -26, 804, 0 -ATT, 0.00, 0.45, -6.90, -2.65, 0.00, 57.04, 55.40 -CTUN, 804, 0.25, 2.52, 0.000000, 0, 0, -23, 804, 0 -ATT, 0.00, -0.45, -6.53, -2.22, 0.00, 56.95, 55.40 -CTUN, 805, 0.25, 2.43, 0.000000, 0, 0, -19, 804, 0 -ATT, 0.00, -0.70, -6.53, -2.10, 0.00, 56.84, 55.40 -CTUN, 805, 0.20, 2.33, 0.000000, 0, 0, -14, 804, 0 -ATT, 0.00, 0.00, -6.62, -1.55, 0.00, 56.65, 55.40 -CTUN, 805, 0.20, 2.38, 0.000000, 0, 0, -12, 805, 0 -ATT, 0.00, 0.29, -6.81, -1.55, 0.00, 56.51, 55.40 -CTUN, 805, 0.20, 2.35, 0.000000, 0, 0, -6, 805, 0 -ATT, 0.00, -0.08, -6.53, -2.03, 0.00, 56.44, 55.40 -CTUN, 804, 0.20, 2.45, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, -0.63, -6.53, -2.36, 0.00, 56.33, 55.40 -CTUN, 805, 0.20, 2.28, 0.000000, 0, 0, 6, 804, 0 -ATT, 0.00, -0.10, -6.53, -1.69, 0.00, 56.36, 55.40 -CTUN, 804, 0.20, 2.33, 0.000000, 0, 0, 9, 804, 0 -ATT, 0.00, -0.01, -6.62, -0.77, 0.00, 56.32, 55.40 -DU32, 7, 166140 -CURR, 805, 1740738, 986, 2173, 5051, 1310.781400 -CTUN, 804, 0.20, 2.41, 0.000000, 0, 0, 13, 805, 0 -ATT, 0.00, -0.14, -6.53, -0.73, 0.00, 56.22, 55.40 -CTUN, 804, 0.20, 2.43, 0.000000, 0, 0, 15, 804, 0 -ATT, 0.00, -0.45, -6.44, -1.22, 0.00, 56.24, 55.40 -CTUN, 804, 0.20, 2.57, 0.000000, 0, 0, 17, 804, 0 -ATT, 0.00, -0.53, -6.06, -1.86, 0.00, 56.30, 55.40 -CTUN, 805, 0.21, 2.42, 0.000000, 0, 0, 21, 804, 0 -ATT, 0.00, 0.38, -6.06, -1.34, 0.00, 56.46, 55.40 -CTUN, 804, 0.21, 2.50, 0.000000, 0, 0, 21, 805, 0 -ATT, 0.00, 0.17, -6.16, -0.84, 0.00, 56.85, 55.40 -CTUN, 804, 0.25, 2.61, 0.000000, 0, 0, 16, 804, 0 -ATT, 0.00, -0.45, -6.16, -1.53, 0.00, 57.46, 55.40 -CTUN, 804, 0.25, 2.57, 0.000000, 0, 0, 18, 804, 0 -ATT, 0.00, -0.71, -6.06, -1.64, 0.00, 58.10, 55.40 -CTUN, 805, 0.28, 2.66, 0.000000, 0, 0, 14, 805, 0 -ATT, 0.00, -0.59, -6.25, -1.48, 0.00, 58.81, 55.40 -CTUN, 805, 0.28, 2.68, 0.000000, 0, 0, 14, 804, 0 -ATT, 0.00, -0.41, -6.16, -1.41, 0.00, 59.56, 55.40 -CTUN, 801, 0.31, 2.62, 0.000000, 0, 0, 11, 805, 0 -ATT, 0.00, -0.31, -6.16, -1.21, 0.00, 60.39, 55.40 -DU32, 7, 166140 -CURR, 805, 1748783, 985, 2191, 5051, 1316.841300 -CTUN, 805, 0.31, 2.57, 0.000000, 0, 0, 13, 804, 0 -ATT, 0.00, 0.11, -6.06, -0.52, 0.00, 61.30, 55.40 -CTUN, 805, 0.35, 2.67, 0.000000, 0, 0, 9, 804, 0 -ATT, 0.00, 0.74, -6.06, 0.37, 0.00, 62.21, 55.40 -CTUN, 804, 0.35, 2.76, 0.000000, 0, 0, 8, 805, 0 -ATT, 0.00, 1.37, -6.53, 0.61, 0.00, 62.87, 55.40 -CTUN, 804, 0.36, 2.79, 0.000000, 0, 0, -2, 805, 0 -ATT, 0.00, 0.94, -6.81, 0.27, 0.00, 63.32, 55.40 -CTUN, 804, 0.36, 2.61, 0.000000, 0, 0, -5, 804, 0 -ATT, 0.00, 0.22, -7.65, -0.75, 0.00, 63.43, 55.40 -CTUN, 805, 0.36, 2.59, 0.000000, 0, 0, -7, 804, 0 -ATT, 0.00, 0.00, -8.12, -1.43, 0.00, 63.53, 55.40 -CTUN, 805, 0.35, 2.45, 0.000000, 0, 0, -7, 805, 0 -ATT, 0.00, -0.45, -8.30, -1.93, 0.00, 63.13, 55.40 -CTUN, 805, 0.35, 2.69, 0.000000, 0, 0, -9, 805, 0 -ATT, 0.00, -0.89, -8.21, -1.78, 0.00, 62.54, 55.40 -CTUN, 804, 0.31, 2.67, 0.000000, 0, 0, -10, 805, 0 -ATT, 0.00, -0.60, -8.21, -1.45, 0.00, 61.84, 55.40 -CTUN, 804, 0.31, 2.66, 0.000000, 0, 0, -7, 804, 0 -ATT, 0.00, 0.38, -8.21, -1.40, 0.00, 60.94, 55.40 -DU32, 7, 166140 -CURR, 804, 1756828, 988, 2201, 5051, 1322.861200 -CTUN, 804, 0.30, 2.59, 0.000000, 0, 0, -6, 804, 0 -ATT, 0.00, 0.45, -8.30, -0.97, 0.00, 59.84, 55.40 -CTUN, 805, 0.30, 2.58, 0.000000, 0, 0, -3, 805, 0 -ATT, 0.00, 0.10, -8.21, -0.90, 0.00, 58.76, 55.40 -CTUN, 805, 0.28, 2.64, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, -0.51, -8.21, -1.60, 0.00, 57.97, 55.40 -CTUN, 804, 0.28, 2.50, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, -0.91, -8.30, -2.47, 0.00, 57.53, 55.40 -CTUN, 805, 0.25, 2.54, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, -1.12, -8.77, -2.85, 0.00, 57.48, 55.40 -CTUN, 805, 0.25, 2.65, 0.000000, 0, 1, 3, 806, 0 -ATT, 0.00, -1.26, -10.64, -2.92, 0.00, 57.99, 55.40 -CTUN, 805, 0.25, 2.49, 0.000000, 0, 0, 4, 804, 0 -ATT, 0.00, -0.52, -10.64, -2.99, 0.00, 58.74, 55.40 -CTUN, 804, 0.25, 2.42, 0.000000, 0, 1, 6, 806, 0 -ATT, 0.00, -0.19, -10.64, -3.89, 0.00, 59.32, 55.40 -CTUN, 804, 0.24, 2.84, 0.000000, 0, 2, 6, 807, 0 -ATT, 0.00, -0.67, -9.33, -5.32, 0.00, 59.73, 55.40 -CTUN, 805, 0.24, 2.63, 0.000000, 0, 3, 8, 808, 0 -ATT, 0.00, -0.96, -9.33, -6.47, 0.00, 60.00, 55.40 -DU32, 7, 166140 -CURR, 804, 1764878, 980, 2189, 5028, 1328.926500 -CTUN, 804, 0.23, 2.53, 0.000000, 0, 4, 10, 809, 0 -ATT, 0.00, -2.12, -9.33, -6.30, 0.00, 60.12, 55.40 -CTUN, 805, 0.24, 2.51, 0.000000, 0, 4, 14, 809, 0 -ATT, 0.00, -1.60, -7.84, -5.16, 0.00, 60.06, 55.40 -CTUN, 804, 0.24, 2.63, 0.000000, 0, 2, 18, 807, 0 -ATT, 0.00, 0.13, -6.81, -3.67, 0.00, 60.03, 55.40 -CTUN, 804, 0.24, 2.57, 0.000000, 0, 1, 21, 805, 0 -ATT, 0.00, 1.52, -5.78, -2.29, 0.00, 59.94, 55.40 -CTUN, 805, 0.24, 2.63, 0.000000, 0, 0, 26, 805, 0 -ATT, 0.00, 2.09, -4.76, -0.69, 0.00, 59.65, 55.40 -CTUN, 804, 0.25, 2.52, 0.000000, 0, 0, 26, 804, 0 -ATT, 0.00, 1.49, -4.01, 0.59, 0.00, 59.12, 55.40 -CTUN, 805, 0.25, 2.68, 0.000000, 0, 0, 29, 804, 0 -ATT, 0.00, 0.97, -2.70, 1.26, 0.00, 58.25, 55.40 -CTUN, 804, 0.27, 2.86, 0.000000, 0, 0, 30, 805, 0 -ATT, 0.00, 1.28, -2.89, 1.91, 0.00, 57.22, 55.40 -CTUN, 804, 0.27, 2.74, 0.000000, 0, 0, 30, 805, 0 -ATT, 0.00, 1.15, -4.48, 2.37, 0.00, 56.17, 55.40 -CTUN, 804, 0.31, 2.73, 0.000000, 0, 0, 30, 805, 0 -ATT, 0.00, 1.04, -4.85, 1.61, 0.00, 55.24, 55.40 -DU32, 7, 166140 -CURR, 805, 1772934, 975, 2187, 5051, 1335.044300 -CTUN, 805, 0.31, 2.68, 0.000000, 0, 0, 27, 804, 0 -ATT, 0.00, 1.14, -5.69, -0.05, 0.00, 54.59, 55.40 -CTUN, 805, 0.34, 2.70, 0.000000, 0, 0, 26, 805, 0 -ATT, 0.00, 2.22, -6.53, -0.67, 0.00, 54.29, 55.40 -CTUN, 805, 0.34, 2.83, 0.000000, 0, 0, 24, 805, 0 -ATT, 0.00, 3.10, -6.72, -0.92, 0.00, 54.24, 55.40 -CTUN, 804, 0.37, 2.84, 0.000000, 0, 1, 23, 805, 0 -ATT, 0.00, 2.48, -6.72, -1.59, 0.00, 54.32, 55.40 -CTUN, 804, 0.37, 2.95, 0.000000, 0, 0, 22, 805, 0 -ATT, 0.00, 1.99, -6.81, -2.51, 0.00, 54.61, 55.40 -CTUN, 805, 0.40, 2.75, 0.000000, 0, 1, 22, 805, 0 -ATT, 0.00, 2.13, -6.72, -3.03, 0.00, 54.89, 55.40 -CTUN, 804, 0.40, 2.86, 0.000000, 0, 1, 19, 805, 0 -ATT, 0.00, 1.69, -6.81, -2.63, 0.00, 55.18, 55.40 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 804, 0.43, 2.96, 0.000000, 0, 0, 20, 804, 0 -ATT, 0.00, 0.86, -6.72, -1.94, 0.00, 55.38, 55.40 -CTUN, 805, 0.43, 2.84, 0.000000, 0, 0, 17, 805, 0 -ATT, 0.00, 0.51, -6.81, -1.93, 0.00, 55.48, 55.40 -CTUN, 804, 0.46, 2.81, 0.000000, 0, 0, 15, 805, 0 -ATT, 0.00, 0.12, -6.81, -2.07, 0.00, 55.39, 55.40 -DU32, 7, 166140 -CURR, 805, 1780985, 980, 2207, 5051, 1341.179300 -CTUN, 805, 0.46, 2.93, 0.000000, 0, 0, 13, 805, 0 -ATT, 0.00, -0.86, -7.74, -2.03, 0.00, 55.41, 55.40 -CTUN, 805, 0.47, 2.96, 0.000000, 0, 0, 12, 804, 0 -ATT, 0.00, -1.34, -7.84, -1.97, 0.00, 55.53, 55.40 -CTUN, 805, 0.47, 2.95, 0.000000, 0, 0, 10, 805, 0 -ATT, 0.00, -0.70, -7.84, -2.49, 0.00, 55.94, 55.40 -CTUN, 804, 0.49, 3.08, 0.000000, 0, 0, 8, 805, 0 -ATT, 0.00, 0.49, -7.65, -3.31, 0.00, 56.52, 55.40 -CTUN, 805, 0.49, 2.86, 0.000000, 0, 1, 8, 805, 0 -ATT, 0.00, 0.83, -6.90, -3.75, 0.00, 57.10, 55.40 -CTUN, 805, 0.49, 2.93, 0.000000, 0, 1, 10, 806, 0 -ATT, 0.00, 0.36, -6.72, -3.41, 0.00, 57.57, 55.40 -CTUN, 804, 0.49, 2.86, 0.000000, 0, 1, 10, 806, 0 -ATT, 0.00, -0.27, -5.97, -2.76, 0.00, 57.73, 55.40 -CTUN, 805, 0.49, 3.03, 0.000000, 0, 0, 10, 805, 0 -ATT, 0.00, -1.17, -4.76, -2.08, 0.00, 57.47, 55.40 -CTUN, 805, 0.49, 3.11, 0.000000, 0, 0, 8, 805, 0 -ATT, 0.00, -1.73, -2.89, -0.92, 0.00, 56.91, 55.40 -CTUN, 805, 0.49, 3.01, 0.000000, 0, 0, 7, 805, 0 -ATT, 0.00, -1.54, -2.61, 0.90, 0.00, 56.09, 55.40 -DU32, 7, 166140 -CURR, 805, 1789034, 989, 2194, 5051, 1347.313600 -CTUN, 805, 0.49, 2.91, 0.000000, 0, 0, 6, 804, 0 -ATT, 0.00, -1.38, -2.80, 2.77, 0.00, 55.24, 55.40 -CTUN, 804, 0.49, 3.12, 0.000000, 0, 1, 1, 805, 0 -ATT, 0.00, -1.70, -2.89, 3.30, 0.00, 54.55, 55.40 -CTUN, 804, 0.49, 2.94, 0.000000, 0, 1, 0, 806, 0 -ATT, 0.00, -1.77, -3.26, 2.71, 0.00, 54.02, 55.40 -CTUN, 804, 0.49, 2.96, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, -1.32, -4.20, 1.90, 0.00, 53.52, 55.40 -CTUN, 804, 0.47, 2.84, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, -1.47, -4.76, 1.04, 0.00, 53.18, 55.40 -CTUN, 804, 0.47, 2.91, 0.000000, 0, 0, -4, 805, 0 -ATT, 0.00, -1.88, -4.66, -0.20, 0.00, 53.07, 55.40 -CTUN, 806, 0.44, 2.77, 0.000000, 0, 0, -8, 804, 0 -ATT, 0.00, -1.79, -4.76, -1.37, 0.00, 53.07, 55.40 -CTUN, 804, 0.44, 2.69, 0.000000, 0, 0, -7, 804, 0 -ATT, 0.00, -2.09, -4.85, -1.93, 0.00, 53.14, 55.40 -CTUN, 804, 0.41, 2.68, 0.000000, 0, 0, -8, 804, 0 -ATT, 0.00, -1.73, -4.76, -2.28, 0.00, 53.37, 55.40 -CTUN, 804, 0.41, 2.75, 0.000000, 0, 0, -8, 805, 0 -ATT, 0.00, -0.46, -4.76, -2.16, 0.00, 53.70, 55.40 -DU32, 7, 166140 -CURR, 804, 1797081, 989, 2181, 5051, 1353.370500 -CTUN, 805, 0.37, 2.67, 0.000000, 0, 0, -6, 804, 0 -ATT, 0.00, 0.00, -4.85, -1.54, 0.00, 54.03, 55.40 -CTUN, 804, 0.37, 2.78, 0.000000, 0, 0, -4, 806, 0 -ATT, 0.00, -0.49, -4.76, -1.09, 0.00, 54.43, 55.40 -CTUN, 805, 0.33, 2.62, 0.000000, 0, 0, -4, 805, 0 -ATT, 0.00, -0.80, -4.85, -1.10, 0.00, 55.02, 55.40 -CTUN, 804, 0.33, 2.65, 0.000000, 0, 0, -1, 804, 0 -ATT, 0.00, -0.14, -4.76, -1.48, 0.00, 55.83, 55.40 -CTUN, 805, 0.30, 2.65, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, 0.81, -4.76, -1.81, 0.00, 56.83, 55.40 -CTUN, 805, 0.30, 2.73, 0.000000, 0, 0, 4, 804, 0 -ATT, 0.00, 1.09, -4.76, -2.12, 0.00, 58.06, 55.40 -CTUN, 805, 0.28, 2.72, 0.000000, 0, 0, 8, 804, 0 -ATT, 0.00, 0.95, -4.57, -2.22, 0.00, 59.15, 55.40 -CTUN, 805, 0.28, 2.69, 0.000000, 0, 0, 7, 805, 0 -ATT, 0.00, 1.25, -4.38, -2.28, 0.00, 60.13, 55.40 -CTUN, 804, 0.26, 2.69, 0.000000, 0, 0, 11, 804, 0 -ATT, 0.00, 1.19, -2.98, -1.75, 0.00, 60.81, 55.40 -CTUN, 804, 0.26, 2.68, 0.000000, 0, 0, 15, 804, 0 -ATT, 0.00, 0.15, -2.42, -0.94, 0.00, 61.29, 55.40 -DU32, 7, 166140 -CURR, 804, 1805127, 986, 2214, 5051, 1359.485800 -CTUN, 804, 0.25, 2.61, 0.000000, 0, 0, 13, 804, 0 -ATT, 0.00, -0.16, -2.42, 0.20, 0.00, 61.54, 55.40 -CTUN, 804, 0.26, 2.64, 0.000000, 0, 0, 16, 805, 0 -ATT, 0.00, 0.24, -2.42, 1.02, 0.00, 61.41, 55.40 -CTUN, 805, 0.25, 2.60, 0.000000, 0, 0, 14, 805, 0 -ATT, 0.00, 0.10, -3.08, 1.42, 0.00, 61.00, 55.40 -CTUN, 805, 0.26, 2.68, 0.000000, 0, 0, 14, 804, 0 -ATT, 0.00, -0.57, -4.10, 1.02, 0.00, 60.16, 55.40 -CTUN, 806, 0.25, 2.59, 0.000000, 0, 0, 14, 805, 0 -ATT, 0.00, -0.85, -4.66, 0.01, 0.00, 59.32, 55.40 -CTUN, 805, 0.26, 2.66, 0.000000, 0, 0, 17, 805, 0 -ATT, 0.00, -1.15, -4.76, -1.17, 0.00, 58.42, 55.40 -CTUN, 805, 0.26, 2.70, 0.000000, 0, 0, 19, 805, 0 -ATT, 0.00, -1.20, -4.76, -2.29, 0.00, 57.50, 55.40 -CTUN, 805, 0.26, 2.63, 0.000000, 0, 0, 20, 806, 0 -ATT, 0.00, -1.75, -4.85, -2.64, 0.00, 56.76, 55.40 -CTUN, 805, 0.26, 2.64, 0.000000, 0, 1, 18, 806, 0 -ATT, 0.00, -2.12, -4.85, -2.48, 0.00, 56.18, 55.40 -CTUN, 806, 0.27, 2.69, 0.000000, 0, 0, 19, 806, 0 -ATT, 0.09, -1.89, -4.85, -1.47, 0.00, 55.40, 55.40 -DU32, 7, 166140 -CURR, 805, 1813177, 983, 2190, 5051, 1365.581700 -CTUN, 807, 0.27, 2.64, 0.000000, 0, 0, 19, 805, 0 -ATT, 0.46, -1.18, -4.76, -0.44, 0.00, 54.44, 55.40 -CTUN, 806, 0.28, 2.63, 0.000000, 0, 0, 18, 805, 0 -ATT, 1.31, -0.57, -4.57, -0.48, 0.00, 53.34, 55.40 -CTUN, 805, 0.28, 2.73, 0.000000, 0, 0, 19, 804, 0 -ATT, 1.59, -0.33, -4.57, -0.92, 0.00, 52.17, 55.40 -CTUN, 805, 0.29, 2.80, 0.000000, 0, 0, 15, 805, 0 -ATT, 1.78, -0.11, -4.57, -1.52, 0.00, 51.02, 55.40 -CTUN, 806, 0.29, 2.81, 0.000000, 0, 0, 17, 805, 0 -ATT, 2.34, 0.75, -4.57, -1.53, 0.00, 49.90, 55.40 -CTUN, 804, 0.30, 2.73, 0.000000, 0, 0, 15, 805, 0 -ATT, 2.53, 1.69, -4.57, -1.39, 0.00, 48.68, 55.40 -CTUN, 804, 0.30, 2.92, 0.000000, 0, 0, 15, 804, 0 -ATT, 4.03, 2.43, -4.57, -1.05, 0.00, 47.40, 55.40 -CTUN, 805, 0.31, 2.81, 0.000000, 0, 0, 12, 804, 0 -ATT, 4.96, 2.79, -4.57, -0.65, 0.00, 46.00, 55.40 -CTUN, 804, 0.31, 2.58, 0.000000, 0, 1, 9, 806, 0 -ATT, 4.78, 3.64, -4.38, -0.50, 0.00, 44.78, 54.78 -CTUN, 803, 0.32, 2.78, 0.000000, 0, 1, 5, 806, 0 -ATT, 4.68, 4.47, -4.38, -0.32, 0.00, 43.72, 53.72 -DU32, 7, 166140 -CURR, 805, 1821225, 978, 2180, 5051, 1371.645100 -CTUN, 804, 0.32, 2.78, 0.000000, 0, 2, 5, 806, 0 -ATT, 4.59, 5.28, -4.38, 0.21, 0.00, 42.70, 52.70 -CTUN, 804, 0.32, 2.73, 0.000000, 0, 3, 8, 808, 0 -ATT, 4.31, 4.96, -4.66, 1.40, 0.00, 41.88, 51.88 -CTUN, 805, 0.32, 2.72, 0.000000, 0, 2, 6, 806, 0 -ATT, 3.56, 4.02, -4.48, 2.43, 0.00, 41.33, 51.33 -CTUN, 804, 0.32, 2.78, 0.000000, 0, 1, 5, 806, 0 -ATT, 2.71, 2.82, -4.48, 1.87, 0.00, 41.14, 51.14 -CTUN, 804, 0.32, 2.74, 0.000000, 0, 0, 2, 804, 0 -ATT, 0.28, 1.75, -4.76, 1.39, 0.00, 41.40, 51.14 -CTUN, 804, 0.32, 2.71, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, 0.73, -6.53, 1.08, 0.00, 42.16, 51.14 -CTUN, 805, 0.32, 2.74, 0.000000, 0, 0, 1, 805, 0 -ATT, 0.00, -0.69, -6.53, 0.29, 0.00, 43.31, 51.14 -CTUN, 804, 0.32, 2.66, 0.000000, 0, 0, 1, 804, 0 -ATT, 0.00, -1.70, -6.81, -0.74, 0.00, 44.66, 51.14 -CTUN, 805, 0.30, 2.73, 0.000000, 0, 0, 3, 804, 0 -ATT, 0.00, -1.86, -6.81, -1.62, 0.00, 46.17, 51.14 -CTUN, 805, 0.30, 2.78, 0.000000, 0, 0, 1, 800, 0 -ATT, 0.00, -1.24, -6.81, -2.03, 0.00, 47.40, 51.14 -DU32, 7, 166140 -CURR, 804, 1829279, 979, 2190, 5028, 1377.735600 -CTUN, 805, 0.29, 2.73, 0.000000, 0, 0, 2, 805, 0 -ATT, 0.00, -0.38, -6.81, -1.85, 0.00, 48.56, 51.14 -CTUN, 804, 0.29, 2.64, 0.000000, 0, 0, 5, 804, 0 -ATT, 0.00, -0.51, -6.72, -2.02, 0.00, 49.59, 51.14 -CTUN, 804, 0.29, 2.75, 0.000000, 0, 0, 6, 805, 0 -ATT, 0.00, -0.41, -6.72, -2.98, 0.00, 50.44, 51.14 -CTUN, 804, 0.29, 2.70, 0.000000, 0, 1, 9, 805, 0 -ATT, 0.28, -0.04, -6.90, -3.46, 0.00, 50.98, 51.14 -CTUN, 804, 0.29, 2.78, 0.000000, 0, 1, 10, 805, 0 -ATT, 0.09, 0.53, -6.81, -3.21, 0.00, 51.36, 51.14 -CTUN, 804, 0.29, 2.70, 0.000000, 0, 0, 12, 805, 0 -ATT, 0.65, 0.42, -6.72, -2.77, 0.00, 51.61, 51.14 -CTUN, 804, 0.29, 2.82, 0.000000, 0, 0, 14, 805, 0 -ATT, 1.03, -0.03, -6.81, -2.28, 0.00, 51.81, 51.14 -CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 15, 804, 0 -ATT, 0.93, 0.00, -6.72, -1.52, 0.00, 51.97, 51.14 -CTUN, 804, 0.29, 2.89, 0.000000, 0, 0, 12, 804, 0 -ATT, 0.84, 0.00, -6.81, -1.22, 0.00, 52.10, 51.14 -CTUN, 805, 0.30, 2.79, 0.000000, 0, 0, 11, 804, 0 -ATT, 0.93, -0.46, -6.72, -1.55, 0.00, 52.31, 51.14 -DU32, 7, 166140 -CURR, 805, 1837325, 980, 2172, 5051, 1383.812300 -CTUN, 804, 0.30, 2.73, 0.000000, 0, 0, 12, 805, 0 -ATT, 1.03, -0.97, -6.81, -2.00, 0.00, 52.42, 51.14 -CTUN, 804, 0.30, 2.83, 0.000000, 0, 0, 11, 804, 0 -ATT, 1.03, -0.35, -6.81, -2.37, 0.00, 52.50, 51.14 -CTUN, 805, 0.30, 2.63, 0.000000, 0, 0, 14, 805, 0 -ATT, 1.03, 0.64, -6.72, -1.82, 0.00, 52.40, 51.14 -CTUN, 804, 0.30, 2.75, 0.000000, 0, 0, 11, 804, 0 -ATT, 1.12, 1.26, -6.72, -1.31, 0.00, 52.39, 51.14 -CTUN, 804, 0.30, 2.85, 0.000000, 0, 0, 9, 806, 0 -ATT, 1.96, 1.69, -6.81, -1.28, 0.00, 52.48, 51.14 -CTUN, 804, 0.31, 2.71, 0.000000, 0, 0, 8, 804, 0 -ATT, 2.34, 1.65, -6.53, -1.62, 0.00, 52.68, 51.14 -CTUN, 804, 0.31, 2.75, 0.000000, 0, 0, 9, 804, 0 -ATT, 2.34, 2.32, -6.53, -1.75, 0.00, 52.86, 51.14 -CTUN, 804, 0.31, 2.82, 0.000000, 0, 1, 7, 805, 0 -ATT, 2.53, 3.18, -6.25, -1.70, 0.00, 53.01, 51.14 -CTUN, 805, 0.31, 2.78, 0.000000, 0, 1, 4, 805, 0 -ATT, 2.53, 3.88, -6.34, -1.11, 0.00, 53.23, 51.14 -CTUN, 804, 0.32, 2.83, 0.000000, 0, 1, 4, 806, 0 -ATT, 2.53, 3.64, -6.16, -0.62, 0.00, 53.61, 51.14 -DU32, 7, 166140 -CURR, 804, 1845373, 984, 2208, 5051, 1389.891400 -CTUN, 805, 0.32, 2.85, 0.000000, 0, 1, 4, 806, 0 -ATT, 1.12, 2.39, -6.06, -1.16, 0.00, 54.20, 51.14 -CTUN, 804, 0.33, 2.82, 0.000000, 0, 0, 2, 805, 0 -ATT, 0.09, 1.31, -5.13, -1.65, 0.00, 54.92, 51.14 -CTUN, 805, 0.33, 2.79, 0.000000, 0, 0, 1, 806, 0 -ATT, 0.00, 0.67, -4.66, -1.90, 0.00, 55.60, 51.14 -CTUN, 805, 0.33, 2.89, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, 0.16, -4.66, -1.66, 0.00, 56.13, 51.14 -CTUN, 806, 0.33, 2.90, 0.000000, 0, 0, 1, 806, 0 -ATT, 0.00, -0.29, -4.29, -0.84, 0.00, 56.54, 51.14 -CTUN, 806, 0.33, 2.96, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, -0.32, -3.92, 0.31, 0.00, 56.91, 51.14 -CTUN, 805, 0.32, 2.89, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, -0.18, -3.92, 0.51, 0.00, 57.03, 51.14 -CTUN, 807, 0.32, 2.84, 0.000000, 0, 0, 0, 807, 0 -ATT, 0.00, -0.11, -4.20, 0.21, 0.00, 56.81, 51.14 -CTUN, 806, 0.32, 2.81, 0.000000, 0, 0, 0, 806, 0 -ATT, 0.00, -0.32, -4.48, -0.14, 0.00, 56.51, 51.14 -CTUN, 805, 0.32, 2.80, 0.000000, 0, 0, -1, 805, 0 -ATT, 0.00, -1.39, -4.38, -0.47, 0.00, 56.23, 51.14 -DU32, 7, 166140 -CURR, 805, 1853428, 979, 2197, 5051, 1396.002900 -CTUN, 806, 0.30, 2.79, 0.000000, 0, 0, -2, 806, 0 -ATT, 0.00, -1.44, -4.29, -0.73, 0.00, 56.02, 51.14 -CTUN, 804, 0.30, 2.86, 0.000000, 0, 0, -1, 805, 0 -ATT, 0.00, -0.94, -3.82, -0.57, 0.00, 55.86, 51.14 -CTUN, 808, 0.29, 2.82, 0.000000, 0, 0, 0, 808, 0 -ATT, 0.00, -0.94, -3.73, -0.36, 0.00, 55.58, 51.14 -CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, -0.65, -3.82, 0.21, 0.00, 55.09, 51.14 -CTUN, 804, 0.28, 2.71, 0.000000, 0, 0, 1, 805, 0 -ATT, 0.00, -0.31, -3.73, 0.48, 0.00, 54.28, 51.14 -CTUN, 805, 0.28, 2.72, 0.000000, 0, 0, 1, 805, 0 -ATT, 0.00, 0.68, -3.82, 0.31, 0.00, 53.24, 51.14 -CTUN, 804, 0.28, 2.80, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, 1.32, -4.38, -0.02, 0.00, 52.42, 51.14 -PM, 0, 0, 0, 0, 1000, 10468, 0, 0 -CTUN, 805, 0.28, 2.88, 0.000000, 0, 0, 6, 805, 0 -ATT, 0.00, 1.13, -4.20, -0.51, 0.00, 51.98, 51.14 -CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, 1.22, -3.92, -0.95, 0.00, 51.98, 51.14 -CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 3, 804, 0 -ATT, 0.00, 0.84, -4.01, -1.37, 0.00, 52.23, 51.14 -DU32, 7, 166140 -CURR, 805, 1861474, 982, 2167, 5028, 1402.072800 -CTUN, 804, 0.27, 2.76, 0.000000, 0, 0, 2, 804, 0 -ATT, 0.00, 0.15, -4.20, -1.63, 0.00, 52.63, 51.14 -CTUN, 805, 0.27, 2.82, 0.000000, 0, 0, 5, 805, 0 -ATT, 0.00, -0.58, -3.73, -1.04, 0.00, 52.94, 51.14 -CTUN, 804, 0.27, 2.74, 0.000000, 0, 0, 7, 804, 0 -ATT, 0.00, -0.69, -2.80, -0.91, 0.00, 53.40, 51.14 -CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 8, 804, 0 -ATT, 0.00, -0.17, -2.70, -1.18, 0.00, 53.87, 51.14 -CTUN, 805, 0.27, 2.91, 0.000000, 0, 0, 10, 804, 0 -ATT, 0.00, -0.48, -2.70, -1.52, 0.00, 54.52, 51.14 -CTUN, 804, 0.27, 2.78, 0.000000, 0, 0, 12, 804, 0 -ATT, 0.00, -0.61, -2.61, -1.02, 0.00, 55.28, 51.14 -CTUN, 805, 0.27, 2.81, 0.000000, 0, 0, 14, 805, 0 -ATT, 0.00, 0.53, -2.70, 0.36, 0.00, 55.96, 51.14 -CTUN, 805, 0.27, 2.79, 0.000000, 0, 0, 12, 804, 0 -ATT, 0.00, 0.30, -2.42, 1.32, 0.00, 56.37, 51.14 -CTUN, 804, 0.27, 2.76, 0.000000, 0, 0, 12, 804, 0 -ATT, 0.00, -0.18, -2.70, 0.62, 0.00, 56.82, 51.14 -CTUN, 804, 0.29, 2.77, 0.000000, 0, 0, 11, 804, 0 -ATT, 0.00, 0.00, -2.61, -0.35, 0.00, 57.27, 51.14 -DU32, 7, 166140 -CURR, 805, 1869520, 985, 2210, 5051, 1408.149700 -CTUN, 804, 0.29, 2.94, 0.000000, 0, 0, 14, 804, 0 -ATT, 0.00, 0.51, -2.61, -0.96, 0.00, 57.79, 51.14 -CTUN, 804, 0.29, 2.93, 0.000000, 0, 0, 13, 804, 0 -ATT, 0.00, 0.81, -2.61, -1.20, 0.00, 58.36, 51.14 -CTUN, 804, 0.29, 3.03, 0.000000, 0, 0, 13, 804, 0 -ATT, 0.00, 1.48, -2.52, -0.45, 0.00, 58.84, 51.14 -CTUN, 805, 0.29, 2.80, 0.000000, 0, 0, 15, 805, 0 -ATT, 0.00, 1.97, -2.52, 0.08, 0.00, 59.28, 51.14 -CTUN, 805, 0.29, 2.78, 0.000000, 0, 0, 11, 805, 0 -ATT, 0.00, 1.88, -2.42, 0.19, 0.00, 59.73, 51.14 -CTUN, 805, 0.30, 2.95, 0.000000, 0, 0, 12, 805, 0 -ATT, 0.00, 1.64, -2.52, 0.27, 0.00, 59.81, 51.14 -CTUN, 805, 0.30, 2.90, 0.000000, 0, 0, 8, 804, 0 -ATT, -0.37, 1.21, -2.70, 0.41, 0.00, 59.74, 51.14 -CTUN, 805, 0.30, 2.94, 0.000000, 0, 0, 10, 805, 0 -ATT, -1.61, 0.58, -1.58, 0.29, 0.00, 59.52, 51.14 -CTUN, 805, 0.30, 2.84, 0.000000, 0, 0, 13, 805, 0 -ATT, -2.74, 0.07, -2.70, 0.60, 0.00, 59.18, 51.14 -CTUN, 805, 0.30, 2.95, 0.000000, 0, 0, 9, 805, 0 -ATT, -2.74, 0.60, -2.70, 0.75, 0.00, 58.97, 51.14 -DU32, 7, 166140 -CURR, 804, 1877560, 978, 2153, 5051, 1414.243900 -CTUN, 804, 0.30, 2.79, 0.000000, 0, 0, 8, 804, 0 -ATT, -2.74, 0.41, -2.70, 0.39, 0.00, 58.74, 51.14 -CTUN, 804, 0.30, 2.97, 0.000000, 0, 0, 6, 805, 0 -ATT, -2.74, -0.69, -2.70, -0.22, 0.00, 58.62, 51.14 -CTUN, 805, 0.30, 2.98, 0.000000, 0, 0, 9, 805, 0 -ATT, -2.74, -0.96, -2.70, -1.08, 0.00, 58.57, 51.14 -CTUN, 804, 0.31, 2.90, 0.000000, 0, 0, 11, 804, 0 -ATT, -2.74, 0.28, -2.70, -1.27, 0.00, 58.68, 51.14 -CTUN, 804, 0.30, 2.84, 0.000000, 0, 0, 8, 804, 0 -ATT, -6.25, 0.85, -2.70, -0.48, 0.00, 59.05, 51.14 -CTUN, 805, 0.30, 2.74, 0.000000, 0, 0, 4, 804, 0 -ATT, -6.72, -1.65, -2.52, -0.14, 0.00, 59.23, 51.14 -CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 5, 804, 0 -ATT, -6.72, -3.59, -2.24, -0.60, 0.00, 59.10, 51.14 -CTUN, 805, 0.29, 2.91, 0.000000, 0, 1, 5, 806, 0 -ATT, -7.48, -3.53, -2.42, -0.38, 0.00, 58.71, 51.14 -CTUN, 805, 0.29, 2.80, 0.000000, 0, 1, 3, 806, 0 -ATT, -7.48, -4.54, -2.52, 0.14, 0.00, 58.13, 51.14 -CTUN, 804, 0.29, 2.64, 0.000000, 0, 3, 6, 807, 0 -ATT, -7.29, -6.49, -2.24, -0.23, 0.00, 57.10, 51.14 -DU32, 7, 166140 -CURR, 806, 1885606, 987, 2266, 5051, 1420.325200 -CTUN, 805, 0.28, 2.80, 0.000000, 0, 4, 3, 809, 0 -ATT, -6.63, -6.46, -2.24, -1.30, 0.00, 55.86, 51.14 -CTUN, 805, 0.28, 2.58, 0.000000, 0, 3, 2, 808, 0 -ATT, -4.16, -4.77, -2.24, -1.02, 0.00, 54.52, 51.14 -CTUN, 805, 0.26, 2.85, 0.000000, 0, 1, 3, 806, 0 -ATT, -2.55, -3.00, -2.42, -0.31, 0.00, 53.44, 51.14 -CTUN, 805, 0.26, 2.74, 0.000000, 0, 0, 3, 805, 0 -ATT, -1.13, -1.71, -1.12, 0.00, 0.00, 52.58, 51.14 -CTUN, 805, 0.25, 2.89, 0.000000, 0, 0, 0, 804, 0 -ATT, 0.00, 1.60, -2.52, -0.55, 0.00, 51.78, 51.14 -CTUN, 805, 0.25, 2.67, 0.000000, 0, 1, 0, 806, 0 -ATT, 0.00, 3.57, -2.52, -0.64, 0.00, 50.95, 51.14 -CTUN, 804, 0.24, 2.78, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, 0.90, -1.96, -0.34, 0.00, 50.84, 51.14 -CTUN, 805, 0.24, 2.92, 0.000000, 0, 0, 9, 805, 0 -ATT, 0.00, -0.76, 0.00, -0.43, 0.00, 51.49, 51.14 -CTUN, 805, 0.24, 2.81, 0.000000, 0, 0, 12, 805, 0 -ATT, 0.00, -0.94, 0.00, -0.40, 0.00, 52.46, 51.14 -CTUN, 805, 0.24, 2.81, 0.000000, 0, 0, 18, 805, 0 -ATT, 0.00, -0.12, 0.00, 1.70, 0.00, 52.90, 51.14 -DU32, 7, 166140 -CURR, 804, 1893664, 977, 2216, 5051, 1426.432100 -CTUN, 805, 0.24, 2.77, 0.000000, 0, 0, 17, 805, 0 -ATT, -0.66, 0.02, 0.00, 4.20, 0.00, 53.07, 51.14 -CTUN, 805, 0.26, 2.74, 0.000000, 0, 2, 12, 807, 0 -ATT, -0.66, -0.11, 0.00, 4.32, 0.00, 53.49, 51.14 -CTUN, 805, 0.26, 2.81, 0.000000, 0, 1, 10, 806, 0 -ATT, 0.00, -0.27, 0.00, 2.74, 0.00, 53.29, 51.14 -CTUN, 806, 0.27, 2.76, 0.000000, 0, 0, 10, 804, 0 -ATT, 0.00, -0.31, -1.21, 2.12, 0.00, 52.61, 51.14 -CTUN, 805, 0.27, 2.99, 0.000000, 0, 0, 9, 805, 0 -ATT, 0.00, -0.41, -2.24, 2.02, 0.00, 51.87, 51.14 -CTUN, 805, 0.29, 2.93, 0.000000, 0, 0, 6, 805, 0 -ATT, 0.00, -0.61, -2.70, 1.10, 0.00, 51.11, 51.14 -CTUN, 805, 0.29, 2.89, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, -0.37, -3.08, -0.68, 0.00, 50.56, 51.14 -CTUN, 805, 0.30, 2.90, 0.000000, 0, 0, 6, 805, 0 -ATT, 0.00, -1.11, -4.20, -1.55, 0.00, 50.19, 51.14 -CTUN, 805, 0.30, 3.02, 0.000000, 0, 0, 6, 805, 0 -ATT, 0.00, -2.21, -4.85, -1.77, 0.00, 49.99, 51.14 -CTUN, 805, 0.30, 2.93, 0.000000, 0, 0, 4, 805, 0 -ATT, 0.00, -1.51, -4.57, -2.80, 0.00, 49.95, 51.14 -DU32, 7, 166140 -CURR, 805, 1901718, 992, 2163, 5051, 1432.476100 -CTUN, 805, 0.30, 2.80, 0.000000, 0, 1, 7, 806, 0 -ATT, 0.00, -0.53, -4.38, -3.45, 0.00, 50.09, 51.14 -CTUN, 805, 0.31, 2.72, 0.000000, 0, 1, 5, 806, 0 -ATT, 0.18, -0.60, -4.10, -3.41, 0.00, 50.58, 51.14 -CTUN, 807, 0.31, 2.78, 0.000000, 0, 1, 3, 808, 0 -ATT, 0.46, -1.00, -3.92, -2.73, 0.00, 51.41, 51.14 -CTUN, 805, 0.31, 3.01, 0.000000, 0, 0, 5, 807, 0 -ATT, 0.84, -1.93, -3.08, -1.96, 0.00, 52.34, 51.14 -CTUN, 807, 0.31, 3.05, 0.000000, 0, 0, 2, 807, 0 -ATT, 1.21, -1.95, -2.42, -1.32, 0.00, 53.20, 51.14 -CTUN, 805, 0.32, 2.98, 0.000000, 0, 0, 2, 804, 0 -ATT, 1.78, -1.15, -2.52, -0.32, 0.00, 53.87, 51.14 -CTUN, 805, 0.32, 2.90, 0.000000, 0, 0, -1, 805, 0 -ATT, 2.90, -0.57, -2.52, 0.83, 0.00, 54.31, 51.14 -CTUN, 804, 0.32, 3.00, 0.000000, 0, 0, -3, 804, 0 -ATT, 6.09, 0.00, -2.52, 1.33, 0.00, 54.38, 51.14 -CTUN, 804, 0.31, 2.87, 0.000000, 0, 0, -2, 804, 0 -ATT, 6.75, 0.88, -2.52, 1.98, 0.00, 54.21, 51.14 -CTUN, 804, 0.31, 2.91, 0.000000, 0, 0, -1, 804, 0 -ATT, 9.18, 2.55, -2.24, 3.28, 0.00, 53.90, 51.14 -DU32, 7, 166140 -CURR, 804, 1909768, 987, 2168, 5051, 1438.520500 -CTUN, 805, 0.29, 2.93, 0.000000, 0, 2, -3, 807, 0 -ATT, 9.56, 6.04, -3.08, 3.26, 0.00, 52.90, 51.14 -CTUN, 804, 0.29, 2.81, 0.000000, 0, 6, -4, 810, 0 -ATT, 9.56, 8.53, -3.08, 2.12, 0.00, 51.48, 51.14 -CTUN, 804, 0.26, 2.83, 0.000000, 0, 7, -10, 811, 0 -ATT, 8.06, 7.66, -4.57, 1.42, 0.00, 50.00, 51.14 -CTUN, 805, 0.26, 2.74, 0.000000, 0, 5, -9, 809, 0 -ATT, 2.62, 6.57, -6.62, 0.79, 0.00, 48.84, 51.14 -CTUN, 805, 0.23, 2.75, 0.000000, 0, 3, -4, 808, 0 -ATT, 0.00, 4.32, -7.56, 0.28, 0.00, 48.23, 51.14 -CTUN, 804, 0.23, 2.57, 0.000000, 0, 0, -7, 804, 0 -ATT, 0.00, -0.82, -6.81, -0.63, 0.00, 48.22, 51.14 -CTUN, 804, 0.22, 2.61, 0.000000, 0, 0, -6, 805, 0 -ATT, 0.46, -3.48, -6.81, -1.50, 0.00, 48.11, 51.14 -CTUN, 804, 0.22, 2.74, 0.000000, 0, 1, -7, 806, 0 -ATT, 2.34, -3.29, -6.72, -1.92, 0.00, 47.63, 51.14 -CTUN, 804, 0.21, 2.69, 0.000000, 0, 0, -3, 804, 0 -ATT, 7.31, -0.20, -6.81, -2.62, 0.00, 47.02, 51.14 -CTUN, 804, 0.21, 2.65, 0.000000, 0, 1, 1, 805, 0 -ATT, 9.28, 3.66, -6.81, -2.99, 0.00, 46.63, 51.14 -DU32, 7, 166140 -CURR, 804, 1917840, 980, 2148, 5051, 1444.571500 -CTUN, 804, 0.20, 2.70, 0.000000, 0, 3, 8, 807, 0 -ATT, 9.09, 7.06, -7.28, -2.74, 0.00, 46.57, 51.14 -CTUN, 804, 0.20, 2.60, 0.000000, 0, 7, 8, 812, 0 -ATT, 8.81, 8.42, -7.93, -2.63, 0.00, 46.86, 51.14 -CTUN, 804, 0.20, 2.69, 0.000000, 0, 8, 7, 812, 0 -ATT, 7.40, 8.12, -8.21, -3.19, 0.00, 47.40, 51.14 -CTUN, 805, 0.20, 2.74, 0.000000, 0, 7, 9, 812, 0 -ATT, 2.25, 6.75, -10.64, -3.46, 0.00, 48.28, 51.14 -CTUN, 804, 0.20, 2.79, 0.000000, 0, 4, 10, 808, 0 -ATT, 0.28, 4.17, -10.82, -3.92, 0.00, 49.58, 51.14 -CTUN, 804, 0.20, 2.64, 0.000000, 0, 2, 5, 806, 0 -ATT, 0.28, 1.37, -10.92, -5.46, 0.00, 51.12, 51.14 -CTUN, 804, 0.20, 2.59, 0.000000, 0, 3, 9, 808, 0 -ATT, 0.09, -0.21, -10.73, -6.37, 0.00, 52.69, 51.14 -CTUN, 804, 0.23, 2.86, 0.000000, 0, 4, 9, 808, 0 -ATT, 0.09, -0.88, -10.64, -6.45, 0.00, 54.31, 51.14 -CTUN, 804, 0.23, 2.90, 0.000000, 0, 4, 9, 812, 0 -ATT, 0.28, -1.33, -9.33, -6.22, 0.00, 55.75, 51.14 -CTUN, 804, 0.26, 2.98, 0.000000, 0, 3, 10, 807, 0 -ATT, 0.00, -1.44, -7.56, -5.68, 0.00, 56.71, 51.14 -DU32, 7, 166140 -CURR, 804, 1925936, 984, 2241, 5051, 1450.672700 -CTUN, 804, 0.26, 3.05, 0.000000, 0, 2, 13, 806, 0 -ATT, 0.09, -0.65, -6.25, -4.30, 0.00, 56.98, 51.14 -CTUN, 804, 0.29, 2.96, 0.000000, 0, 1, 16, 806, 0 -ATT, 0.00, -0.07, -4.85, -2.32, 0.00, 56.50, 51.14 -CTUN, 805, 0.29, 2.98, 0.000000, 0, 0, 19, 805, 0 -ATT, 0.00, 0.38, -4.66, -0.10, 0.00, 55.47, 51.14 -CTUN, 805, 0.32, 3.00, 0.000000, 0, 0, 18, 803, 0 -ATT, 0.00, 0.61, -4.76, 1.37, 0.00, 54.23, 51.14 -CTUN, 804, 0.32, 3.03, 0.000000, 0, 0, 18, 804, 0 -ATT, 0.00, 0.37, -4.76, 1.74, 0.00, 53.01, 51.14 -CTUN, 804, 0.36, 2.94, 0.000000, 0, 0, 20, 804, 0 -ATT, 0.00, -0.06, -5.50, 1.78, 0.00, 52.02, 51.14 -CTUN, 805, 0.36, 3.24, 0.000000, 0, 0, 20, 805, 0 -ATT, 0.00, -0.21, -5.69, 1.53, 0.00, 51.10, 51.14 -CTUN, 805, 0.39, 3.17, 0.000000, 0, 0, 17, 804, 0 -ATT, 0.00, -0.37, -6.06, 0.64, 0.00, 50.06, 51.14 -CTUN, 804, 0.39, 3.18, 0.000000, 0, 0, 14, 804, 0 -ATT, 0.00, -0.18, -6.62, -0.27, 0.00, 48.73, 51.14 -CTUN, 805, 0.41, 2.94, 0.000000, 0, 0, 8, 805, 0 -ATT, 0.00, 0.82, -7.84, -1.20, 0.00, 47.19, 51.14 -DU32, 7, 166140 -CURR, 805, 1933986, 986, 2168, 5028, 1456.755400 -CTUN, 804, 0.41, 2.96, 0.000000, 0, 0, 10, 804, 0 -ATT, 0.00, 1.30, -7.84, -1.71, 0.00, 45.82, 51.14 -CTUN, 805, 0.45, 3.20, 0.000000, 0, 0, 5, 805, 0 -ATT, 0.00, 1.19, -7.84, -1.78, 0.00, 44.58, 51.14 -CTUN, 804, 0.45, 3.18, 0.000000, 0, 0, 3, 805, 0 -ATT, 0.00, 1.05, -7.84, -1.66, 0.00, 43.56, 51.14 -CTUN, 798, 0.46, 3.06, 0.000000, 0, 0, 1, 798, 0 -ATT, 0.00, 0.54, -7.84, -1.70, 0.00, 42.89, 51.14 -CTUN, 799, 0.46, 3.21, 0.000000, 0, 0, -5, 799, 0 -ATT, 0.00, 0.07, -8.40, -2.20, 0.00, 42.62, 51.14 -CTUN, 800, 0.47, 3.17, 0.000000, 0, 0, -11, 800, 0 -ATT, 0.00, 0.02, -10.73, -3.20, 0.00, 42.63, 51.14 -CTUN, 802, 0.46, 3.04, 0.000000, 0, 1, -14, 803, 0 -ATT, 0.00, 0.61, -10.92, -4.42, 0.00, 42.76, 51.14 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 801, 0.46, 3.14, 0.000000, 0, 2, -20, 803, 0 -ATT, 0.00, 1.09, -10.64, -5.09, 0.00, 43.07, 51.14 -CTUN, 800, 0.44, 3.10, 0.000000, 0, 2, -21, 802, 0 -ATT, 0.00, 1.11, -8.02, -5.24, 0.00, 43.57, 51.14 -CTUN, 800, 0.44, 3.03, 0.000000, 0, 2, -23, 802, 0 -ATT, 0.00, 0.73, -5.69, -4.46, 0.00, 43.93, 51.14 -DU32, 7, 166140 -CURR, 800, 1942011, 980, 2131, 5051, 1462.690400 -CTUN, 802, 0.41, 3.10, 0.000000, 0, 1, -27, 803, 0 -ATT, 0.00, 0.39, -3.08, -2.13, 0.00, 44.16, 51.14 -CTUN, 802, 0.41, 3.09, 0.000000, 0, 0, -28, 802, 0 -ATT, 0.00, 0.71, -2.52, 0.88, 0.00, 44.50, 51.14 -CTUN, 802, 0.36, 3.04, 0.000000, 0, 0, -33, 802, 0 -ATT, 0.00, 0.94, -2.52, 2.95, 0.00, 44.98, 51.14 -CTUN, 805, 0.36, 2.94, 0.000000, 0, 1, -33, 806, 0 -ATT, 0.00, 1.19, -2.42, 3.85, 0.00, 45.49, 51.14 -CTUN, 805, 0.30, 2.89, 0.000000, 0, 1, -32, 806, 0 -ATT, 0.00, 1.03, -2.42, 3.71, 0.00, 46.10, 51.14 -CTUN, 804, 0.30, 2.85, 0.000000, 0, 1, -28, 805, 0 -ATT, -0.94, -0.52, -2.70, 3.29, 0.00, 46.90, 51.14 -CTUN, 805, 0.24, 2.90, 0.000000, 0, 1, -24, 806, 0 -ATT, -2.46, -1.97, -2.42, 2.96, 0.00, 47.84, 51.14 -CTUN, 804, 0.24, 2.92, 0.000000, 0, 1, -19, 805, 0 -ATT, -3.31, -2.39, -3.26, 2.53, 0.00, 48.73, 51.14 -CTUN, 804, 0.20, 2.87, 0.000000, 0, 1, -12, 804, 0 -ATT, -3.60, -2.16, -3.73, 2.00, 0.00, 49.48, 51.14 -CTUN, 804, 0.20, 2.47, 0.000000, 0, 0, -6, 804, 0 -ATT, -3.69, -2.87, -3.64, 1.74, 0.00, 50.15, 51.14 -DU32, 7, 166140 -CURR, 804, 1950052, 982, 2162, 5028, 1468.692400 -CTUN, 804, 0.20, 2.66, 0.000000, 0, 1, 0, 805, 0 -ATT, -1.89, -4.60, -4.57, 1.61, 0.00, 50.78, 51.14 -CTUN, 805, 0.20, 2.52, 0.000000, 0, 2, 6, 807, 0 -ATT, 0.00, -4.31, -4.85, 0.94, 0.00, 51.36, 51.14 -CTUN, 804, 0.20, 2.79, 0.000000, 0, 1, 9, 805, 0 -ATT, 0.00, -1.78, -5.78, 0.06, 0.00, 51.55, 51.14 -CTUN, 805, 0.20, 2.81, 0.000000, 0, 0, 15, 805, 0 -ATT, 0.00, 0.70, -7.93, -0.62, 0.00, 51.37, 51.14 -CTUN, 804, 0.20, 2.80, 0.000000, 0, 0, 17, 805, 0 -ATT, 0.00, 2.23, -10.08, -2.05, 0.00, 51.09, 51.14 -CTUN, 805, 0.20, 2.87, 0.000000, 0, 1, 18, 806, 0 -ATT, 0.00, 2.55, -10.17, -3.81, 0.00, 50.96, 51.14 -CTUN, 804, 0.20, 2.86, 0.000000, 0, 3, 16, 807, 0 -ATT, 0.00, 2.54, -9.14, -5.49, 0.00, 51.03, 51.14 -CTUN, 804, 0.22, 2.81, 0.000000, 0, 3, 16, 807, 0 -ATT, 0.00, 1.01, -8.96, -5.74, 0.00, 51.21, 51.14 -CTUN, 804, 0.22, 2.98, 0.000000, 0, 3, 12, 807, 0 -ATT, 0.00, 0.08, -9.14, -4.92, 0.00, 51.12, 51.14 -CTUN, 804, 0.27, 2.93, 0.000000, 0, 2, 8, 807, 0 -ATT, 0.00, 1.15, -9.14, -3.86, 0.00, 50.83, 51.14 -DU32, 7, 166140 -CURR, 804, 1958112, 979, 2159, 5028, 1474.724100 -CTUN, 805, 0.27, 3.00, 0.000000, 0, 1, 3, 806, 0 -ATT, 0.00, 1.61, -8.86, -2.82, 0.00, 50.52, 51.14 -CTUN, 804, 0.30, 2.97, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, 1.89, -8.86, -2.56, 0.00, 50.18, 51.14 -CTUN, 804, 0.30, 3.05, 0.000000, 0, 1, -4, 805, 0 -ATT, 0.00, 1.91, -9.14, -2.90, 0.00, 50.00, 51.14 -CTUN, 804, 0.32, 3.04, 0.000000, 0, 1, -9, 805, 0 -ATT, 0.00, 0.82, -9.42, -3.39, 0.00, 50.17, 51.14 -CTUN, 804, 0.32, 3.01, 0.000000, 0, 1, -11, 805, 0 -ATT, 0.00, 0.23, -9.89, -4.13, 0.00, 50.55, 51.14 -CTUN, 805, 0.32, 3.05, 0.000000, 0, 2, -14, 806, 0 -ATT, 0.00, 0.04, -10.17, -4.91, 0.00, 50.96, 51.14 -CTUN, 804, 0.32, 3.08, 0.000000, 0, 2, -10, 806, 0 -ATT, 0.00, 0.35, -9.52, -5.21, 0.00, 51.44, 51.14 -CTUN, 805, 0.32, 3.06, 0.000000, 0, 2, -14, 807, 0 -ATT, 0.00, 1.12, -8.12, -4.25, 0.00, 51.86, 51.14 -CTUN, 804, 0.32, 2.99, 0.000000, 0, 1, -13, 805, 0 -ATT, 0.00, 0.91, -4.85, -2.45, 0.00, 52.17, 51.14 -CTUN, 805, 0.32, 3.07, 0.000000, 0, 0, -12, 805, 0 -ATT, 0.00, 0.81, -3.73, -0.42, 0.00, 52.39, 51.14 -DU32, 7, 166140 -CURR, 805, 1966164, 978, 2149, 5028, 1480.727500 -CTUN, 805, 0.31, 3.14, 0.000000, 0, 0, -12, 805, 0 -ATT, 0.00, 1.51, -3.92, 1.50, 0.00, 52.50, 51.14 -CTUN, 805, 0.31, 3.17, 0.000000, 0, 0, -12, 804, 0 -ATT, 0.00, 2.09, -4.76, 2.62, 0.00, 52.35, 51.14 -CTUN, 804, 0.29, 3.06, 0.000000, 0, 1, -14, 805, 0 -ATT, 0.00, 1.59, -4.85, 2.36, 0.00, 51.98, 51.14 -CTUN, 805, 0.29, 2.97, 0.000000, 0, 0, -14, 805, 0 -ATT, 0.00, 1.63, -4.85, 1.46, 0.00, 51.78, 51.14 -CTUN, 804, 0.28, 3.11, 0.000000, 0, 0, -14, 804, 0 -ATT, 0.00, 2.05, -4.85, 0.78, 0.00, 51.66, 51.14 -CTUN, 805, 0.28, 3.01, 0.000000, 0, 0, -12, 805, 0 -ATT, -0.18, 1.54, -4.57, 0.68, 0.00, 51.51, 51.14 -CTUN, 804, 0.27, 2.90, 0.000000, 0, 0, -12, 804, 0 -ATT, -0.75, -0.17, -4.57, 0.07, 0.00, 51.26, 51.14 -CTUN, 804, 0.27, 2.91, 0.000000, 0, 0, -9, 804, 0 -ATT, -0.94, -0.66, -4.48, -0.34, 0.00, 51.01, 51.14 -CTUN, 804, 0.25, 2.84, 0.000000, 0, 0, -6, 805, 0 -ATT, -1.32, -0.91, -4.57, -0.15, 0.00, 50.91, 51.14 -CTUN, 805, 0.25, 2.88, 0.000000, 0, 0, -5, 804, 0 -ATT, -1.61, -1.97, -4.48, -0.44, 0.00, 50.97, 51.14 -DU32, 7, 166140 -CURR, 804, 1974209, 978, 2173, 5051, 1486.730200 -CTUN, 805, 0.25, 3.05, 0.000000, 0, 0, -3, 805, 0 -ATT, -1.61, -1.61, -4.57, -0.78, 0.00, 50.94, 51.14 -CTUN, 805, 0.25, 2.86, 0.000000, 0, 0, 1, 805, 0 -ATT, -1.61, -1.16, -4.57, -1.00, 0.00, 50.87, 51.14 -CTUN, 804, 0.25, 2.94, 0.000000, 0, 0, 5, 804, 0 -ATT, -1.61, -1.51, -4.57, -1.27, 0.00, 50.58, 51.14 -CTUN, 805, 0.26, 3.00, 0.000000, 0, 0, 7, 804, 0 -ATT, -1.61, -0.87, -4.57, -1.65, 0.00, 50.00, 51.14 -CTUN, 804, 0.26, 2.99, 0.000000, 0, 0, 10, 804, 0 -ATT, -1.61, -0.09, -4.48, -1.81, 0.00, 49.43, 51.14 -CTUN, 804, 0.27, 2.93, 0.000000, 0, 0, 9, 804, 0 -ATT, -1.42, 0.62, -4.57, -1.88, 0.00, 49.06, 51.14 -CTUN, 804, 0.27, 3.06, 0.000000, 0, 0, 8, 805, 0 -ATT, -1.13, 0.24, -4.48, -1.54, 0.00, 49.04, 51.14 -CTUN, 804, 0.27, 2.97, 0.000000, 0, 0, 4, 804, 0 -ATT, -1.32, -1.18, -4.20, -1.47, 0.00, 49.24, 51.14 -CTUN, 805, 0.27, 2.81, 0.000000, 0, 0, 1, 804, 0 -ATT, -1.32, -1.84, -3.92, -1.79, 0.00, 49.62, 51.14 -CTUN, 805, 0.29, 3.06, 0.000000, 0, 0, 2, 805, 0 -ATT, -1.13, -1.33, -3.08, -1.61, 0.00, 50.12, 51.14 -DU32, 7, 166140 -CURR, 805, 1982253, 984, 2151, 5051, 1492.757800 -CTUN, 804, 0.29, 3.08, 0.000000, 0, 0, 3, 804, 0 -ATT, -1.32, -0.87, -3.08, -0.83, 0.00, 50.69, 51.14 -CTUN, 805, 0.30, 2.88, 0.000000, 0, 0, 1, 805, 0 -ATT, -0.94, -1.10, -3.26, 0.02, 0.00, 51.17, 51.14 -CTUN, 805, 0.30, 3.03, 0.000000, 0, 0, -1, 804, 0 -ATT, -0.85, -2.14, -2.98, 0.04, 0.00, 51.53, 51.14 -CTUN, 804, 0.31, 3.06, 0.000000, 0, 0, 0, 804, 0 -ATT, -0.75, -2.34, -3.08, -0.06, 0.00, 51.82, 51.14 -CTUN, 805, 0.31, 3.05, 0.000000, 0, 0, -1, 805, 0 -ATT, -0.37, -1.65, -3.26, 0.03, 0.00, 52.10, 51.14 -CTUN, 804, 0.31, 3.02, 0.000000, 0, 0, -1, 805, 0 -ATT, 0.00, -0.60, -3.17, 0.83, 0.00, 52.45, 51.14 -CTUN, 805, 0.31, 3.05, 0.000000, 0, 0, -4, 805, 0 -ATT, 0.00, 0.51, -3.26, 1.40, 0.00, 52.85, 51.14 -CTUN, 805, 0.31, 3.11, 0.000000, 0, 0, -3, 804, 0 -ATT, 0.00, 1.10, -3.08, 1.06, 0.00, 53.44, 51.14 -CTUN, 804, 0.29, 3.05, 0.000000, 0, 0, -3, 804, 0 -ATT, 0.00, 0.53, -3.17, 0.09, 0.00, 54.08, 51.14 -CTUN, 805, 0.29, 3.18, 0.000000, 0, 0, -4, 805, 0 -ATT, 0.00, -0.19, -2.61, -1.29, 0.00, 54.88, 51.14 -DU32, 7, 166140 -CURR, 804, 1990299, 983, 2174, 5051, 1498.779300 -CTUN, 805, 0.27, 3.05, 0.000000, 0, 0, 0, 805, 0 -ATT, 0.00, -0.72, -2.42, -1.62, 0.00, 55.62, 51.14 -CTUN, 805, 0.27, 2.96, 0.000000, 0, 0, 2, 804, 0 -ATT, 0.00, -0.22, -2.42, -1.67, 0.00, 56.34, 51.14 -CTUN, 804, 0.27, 3.14, 0.000000, 0, 0, 6, 804, 0 -ATT, 0.00, 1.17, -2.70, -1.55, 0.00, 56.98, 51.14 -CTUN, 804, 0.27, 2.92, 0.000000, 0, 0, 5, 804, 0 -ATT, 0.00, 1.15, -2.42, -1.07, 0.00, 57.50, 51.14 -CTUN, 805, 0.27, 3.05, 0.000000, 0, 0, 6, 804, 0 -ATT, 0.00, 0.66, -2.70, -1.00, 0.00, 57.76, 51.14 -CTUN, 804, 0.27, 3.01, 0.000000, 0, 0, 9, 804, 0 -ATT, 0.00, 1.11, -2.52, -1.39, 0.00, 57.63, 51.14 -CTUN, 804, 0.27, 3.06, 0.000000, 0, 0, 11, 804, 0 -ATT, 0.00, 1.85, 0.00, -1.45, 0.00, 57.18, 51.14 -CTUN, 805, 0.27, 2.98, 0.000000, 0, 0, 11, 805, 0 -ATT, 0.00, 1.89, 0.00, -0.32, 0.00, 56.42, 51.14 -CTUN, 804, 0.26, 3.17, 0.000000, 0, 0, 11, 805, 0 -ATT, 0.00, -0.17, 0.00, 1.32, 0.00, 55.51, 51.14 -CTUN, 804, 0.26, 3.04, 0.000000, 0, 0, 9, 804, 0 -ATT, 0.00, -1.65, 0.00, 2.49, 0.00, 54.58, 51.14 -DU32, 7, 166140 -CURR, 804, 1998342, 980, 2130, 5051, 1504.829000 -CTUN, 804, 0.26, 3.17, 0.000000, 0, 1, 8, 805, 0 -ATT, 0.00, -0.36, 0.00, 3.27, 0.00, 53.76, 51.14 -CTUN, 805, 0.26, 3.04, 0.000000, 0, 1, 6, 805, 0 -ATT, 0.00, 0.70, 0.00, 4.39, 0.00, 52.74, 51.14 -CTUN, 804, 0.26, 2.97, 0.000000, 0, 2, 8, 806, 0 -ATT, 0.00, 0.41, 0.00, 5.15, 0.00, 51.80, 51.14 -CTUN, 804, 0.27, 3.01, 0.000000, 0, 2, 6, 806, 0 -ATT, 0.00, 0.67, 0.00, 4.79, 0.00, 51.04, 51.14 -CTUN, 804, 0.27, 3.08, 0.000000, 0, 2, 8, 806, 0 -ATT, 0.00, 0.81, -0.09, 4.18, 0.00, 50.48, 51.14 -CTUN, 806, 0.27, 3.12, 0.000000, 0, 1, 9, 805, 0 -ATT, 0.00, -0.18, -1.02, 2.63, 0.00, 50.52, 51.14 -CTUN, 813, 0.26, 3.03, 0.000000, 0, 0, 10, 813, 0 -ATT, 0.00, -1.21, -1.86, 0.78, 0.00, 51.07, 51.14 -CTUN, 813, 0.26, 3.01, 0.000000, 0, 0, 10, 813, 0 -ATT, 0.00, -1.28, -2.33, -0.72, 0.00, 52.03, 51.14 -CTUN, 814, 0.26, 3.00, 0.000000, 0, 0, 16, 813, 0 -ATT, 0.00, -0.93, -2.33, -1.29, 0.00, 53.20, 51.14 -CTUN, 815, 0.26, 3.05, 0.000000, 0, 0, 16, 815, 0 -ATT, 0.00, -0.85, -2.42, -1.39, 0.00, 54.24, 51.14 -DU32, 7, 166140 -CURR, 814, 2006432, 977, 2228, 5051, 1510.878800 -CTUN, 815, 0.26, 3.10, 0.000000, 0, 0, 18, 815, 0 -ATT, 0.00, -1.14, -2.33, -1.63, 0.00, 55.33, 51.14 -CTUN, 815, 0.28, 3.01, 0.000000, 0, 0, 19, 815, 0 -ATT, 0.00, -1.92, -2.42, -1.91, 0.00, 56.40, 51.14 -CTUN, 815, 0.28, 3.09, 0.000000, 0, 0, 20, 816, 0 -ATT, 0.00, -1.78, -2.52, -1.25, 0.00, 57.14, 51.14 -CTUN, 816, 0.29, 3.10, 0.000000, 0, 0, 22, 816, 0 -ATT, 0.00, -1.58, -2.61, 0.00, 0.00, 57.78, 51.14 -CTUN, 815, 0.29, 3.06, 0.000000, 0, 0, 19, 815, 0 -ATT, 0.28, -2.14, -2.70, 0.53, 0.00, 58.37, 51.14 -CTUN, 816, 0.31, 3.22, 0.000000, 0, 0, 19, 815, 0 -ATT, 0.46, -1.92, -2.61, 0.40, 0.00, 58.78, 51.14 -CTUN, 814, 0.31, 3.14, 0.000000, 0, 0, 18, 814, 0 -ATT, 0.93, -0.87, -3.26, -0.18, 0.00, 59.04, 51.14 -CTUN, 815, 0.33, 3.23, 0.000000, 0, 0, 17, 815, 0 -ATT, 1.21, -0.73, -3.64, -1.34, 0.00, 59.09, 51.14 -CTUN, 815, 0.33, 3.13, 0.000000, 0, 0, 16, 815, 0 -ATT, 1.50, -0.95, -3.92, -1.91, 0.00, 58.97, 51.14 -CTUN, 816, 0.34, 3.01, 0.000000, 0, 0, 13, 815, 0 -ATT, 1.78, -1.01, -4.01, -1.85, 0.00, 58.63, 51.14 -DU32, 7, 166140 -CURR, 814, 2014585, 974, 2251, 5051, 1517.089400 -CTUN, 815, 0.34, 3.07, 0.000000, 0, 0, 12, 815, 0 -ATT, 2.34, -0.63, -3.82, -1.74, 0.00, 58.20, 51.14 -CTUN, 814, 0.35, 3.21, 0.000000, 0, 0, 14, 814, 0 -ATT, 2.53, -0.31, -4.01, -1.52, 0.00, 57.67, 51.14 -CTUN, 816, 0.35, 3.21, 0.000000, 0, 0, 11, 815, 0 -ATT, 3.28, -0.03, -3.92, -1.23, 0.00, 57.05, 51.14 -CTUN, 816, 0.35, 3.02, 0.000000, 0, 0, 8, 816, 0 -ATT, 4.87, 0.98, -3.92, -1.09, 0.00, 56.25, 51.14 -CTUN, 816, 0.35, 3.30, 0.000000, 0, 0, 10, 816, 0 -ATT, 6.56, 2.79, -3.92, -0.38, 0.00, 55.21, 51.14 -CTUN, 815, 0.35, 3.15, 0.000000, 0, 1, 12, 816, 0 -ATT, 6.56, 4.00, -3.92, 0.56, 0.00, 54.19, 51.14 -CTUN, 815, 0.35, 3.03, 0.000000, 0, 2, 14, 817, 0 -ATT, 6.93, 5.91, -3.92, 0.58, 0.00, 53.38, 51.14 -PM, 0, 0, 0, 0, 1001, 10476, 0, 0 -CTUN, 815, 0.35, 3.12, 0.000000, 0, 4, 10, 819, 0 -ATT, 6.84, 7.14, -4.20, 0.11, 0.00, 52.61, 51.14 -CTUN, 816, 0.34, 3.17, 0.000000, 0, 5, 9, 821, 0 -ATT, 6.37, 7.45, -4.57, -0.45, 0.00, 52.08, 51.14 -CTUN, 816, 0.34, 3.24, 0.000000, 0, 5, 8, 820, 0 -ATT, 3.75, 5.79, -6.25, -1.27, 0.00, 51.86, 51.14 -DU32, 7, 166140 -CURR, 816, 2022752, 977, 2250, 5051, 1523.341100 -CTUN, 814, 0.33, 3.15, 0.000000, 0, 2, 4, 817, 0 -ATT, 3.09, 4.10, -6.53, -2.05, 0.00, 51.71, 51.14 -CTUN, 815, 0.33, 3.14, 0.000000, 0, 1, 6, 816, 0 -ATT, 2.34, 2.97, -6.34, -2.41, 0.00, 51.54, 51.14 -CTUN, 815, 0.32, 3.01, 0.000000, 0, 1, 2, 816, 0 -ATT, 1.78, 0.90, -6.53, -2.82, 0.00, 51.38, 51.14 -CTUN, 815, 0.32, 3.06, 0.000000, 0, 0, 2, 815, 0 -ATT, 0.37, -0.72, -6.62, -2.82, 0.00, 51.32, 51.14 -CTUN, 816, 0.31, 3.08, 0.000000, 0, 0, -3, 816, 0 -ATT, 0.28, -0.74, -6.81, -2.93, 0.00, 51.31, 51.14 -CTUN, 816, 0.31, 3.07, 0.000000, 0, 1, -5, 817, 0 -ATT, 0.28, -0.74, -7.65, -3.10, 0.00, 51.32, 51.14 -CTUN, 816, 0.30, 3.15, 0.000000, 0, 1, -4, 817, 0 -ATT, 0.28, -1.45, -7.84, -3.07, 0.00, 51.25, 51.14 -CTUN, 816, 0.30, 3.11, 0.000000, 0, 1, -2, 817, 0 -ATT, 0.28, -2.06, -7.84, -2.67, 0.00, 51.17, 51.14 -CTUN, 818, 0.28, 3.09, 0.000000, 0, 1, -3, 816, 0 -ATT, 0.28, -2.20, -7.65, -2.26, 0.00, 51.15, 51.14 -CTUN, 815, 0.28, 3.03, 0.000000, 0, 1, 0, 816, 0 -ATT, 0.28, -1.88, -6.72, -2.49, 0.00, 51.21, 51.14 -DU32, 7, 166140 -CURR, 815, 2030914, 981, 2211, 5051, 1529.467800 -CTUN, 815, 0.26, 3.15, 0.000000, 0, 1, 0, 817, 0 -ATT, 0.28, -0.82, -6.81, -3.62, 0.00, 51.27, 51.14 -CTUN, 816, 0.26, 3.12, 0.000000, 0, 1, 5, 817, 0 -ATT, 0.18, -0.37, -6.81, -4.40, 0.00, 51.33, 51.14 -CTUN, 815, 0.24, 3.04, 0.000000, 0, 2, 7, 818, 0 -ATT, 0.65, -0.11, -6.81, -4.30, 0.00, 51.43, 51.14 -CTUN, 815, 0.24, 3.00, 0.000000, 0, 1, 11, 816, 0 -ATT, 1.40, 0.84, -6.81, -3.13, 0.00, 51.71, 51.14 -CTUN, 815, 0.23, 3.06, 0.000000, 0, 0, 14, 815, 0 -ATT, 1.40, 1.59, -4.38, -1.83, 0.00, 52.14, 51.14 -CTUN, 815, 0.23, 3.20, 0.000000, 0, 0, 18, 816, 0 -ATT, 0.46, 1.73, -3.26, -1.10, 0.00, 52.60, 51.14 -CTUN, 815, 0.23, 3.06, 0.000000, 0, 0, 18, 815, 0 -ATT, 0.09, 0.53, -2.61, -0.41, 0.00, 53.05, 51.14 -CTUN, 815, 0.24, 3.02, 0.000000, 0, 0, 21, 815, 0 -ATT, 0.09, -0.62, -2.24, 0.63, 0.00, 53.49, 51.14 -CTUN, 815, 0.24, 3.20, 0.000000, 0, 0, 20, 815, 0 -ATT, 0.00, -0.34, -2.05, 1.80, 0.00, 53.95, 51.14 -CTUN, 815, 0.27, 3.16, 0.000000, 0, 0, 19, 815, 0 -ATT, 0.00, -0.08, -2.24, 2.76, 0.00, 54.46, 51.14 -DU32, 7, 166140 -CURR, 816, 2039074, 973, 2224, 5028, 1535.644800 -CTUN, 815, 0.27, 3.19, 0.000000, 0, 0, 19, 815, 0 -ATT, 0.00, -0.23, -2.14, 2.90, 0.00, 54.95, 51.14 -CTUN, 815, 0.30, 3.21, 0.000000, 0, 0, 18, 815, 0 -ATT, 0.00, -0.43, -2.14, 2.39, 0.00, 55.30, 51.14 -CTUN, 815, 0.30, 3.19, 0.000000, 0, 0, 19, 816, 0 -ATT, 0.00, 0.10, -2.24, 1.87, 0.00, 55.35, 51.14 -CTUN, 815, 0.32, 3.07, 0.000000, 0, 0, 18, 815, 0 -ATT, 0.00, 0.35, -2.24, 1.43, 0.00, 54.95, 51.14 -CTUN, 815, 0.32, 3.23, 0.000000, 0, 0, 18, 815, 0 -ATT, 0.00, 0.21, -4.57, 0.62, 0.00, 54.28, 51.14 -CTUN, 815, 0.35, 3.24, 0.000000, 0, 0, 17, 815, 0 -ATT, 0.00, -0.01, -4.76, -1.10, 0.00, 53.30, 51.14 -CTUN, 816, 0.35, 3.13, 0.000000, 0, 0, 14, 815, 0 -ATT, 0.00, 0.29, -5.04, -2.79, 0.00, 52.02, 51.14 -CTUN, 815, 0.37, 3.25, 0.000000, 0, 0, 16, 815, 0 -ATT, 0.00, 0.76, -5.22, -2.71, 0.00, 50.74, 51.14 -CTUN, 816, 0.37, 3.25, 0.000000, 0, 0, 15, 816, 0 -ATT, 0.00, 0.96, -5.22, -1.72, 0.00, 49.47, 51.14 -CTUN, 815, 0.39, 3.27, 0.000000, 0, 0, 15, 815, 0 -ATT, 0.00, 0.63, -5.22, -0.43, 0.00, 48.39, 51.14 -DU32, 7, 166140 -CURR, 816, 2047227, 979, 2202, 5051, 1541.817400 -CTUN, 816, 0.39, 3.36, 0.000000, 0, 0, 11, 816, 0 -ATT, 0.00, 0.14, -5.50, 0.19, 0.00, 47.58, 51.14 -CTUN, 814, 0.41, 3.39, 0.000000, 0, 0, 7, 814, 0 -ATT, 0.00, 0.86, -6.53, -0.03, 0.00, 47.11, 51.14 -CTUN, 815, 0.41, 3.24, 0.000000, 0, 0, 5, 815, 0 -ATT, 0.00, 1.66, -6.72, -1.05, 0.00, 46.98, 51.14 -CTUN, 815, 0.41, 3.31, 0.000000, 0, 0, 3, 815, 0 -ATT, 0.00, 1.20, -7.84, -2.25, 0.00, 47.28, 51.14 -CTUN, 815, 0.41, 3.22, 0.000000, 0, 0, 0, 815, 0 -ATT, 0.00, 0.30, -7.74, -3.24, 0.00, 47.88, 51.14 -CTUN, 816, 0.41, 3.20, 0.000000, 0, 1, -2, 817, 0 -ATT, 0.00, 0.40, -7.37, -3.94, 0.00, 48.58, 51.14 -CTUN, 816, 0.41, 3.41, 0.000000, 0, 1, -2, 817, 0 -ATT, 0.00, 0.70, -6.81, -3.63, 0.00, 49.21, 51.14 -CTUN, 815, 0.41, 3.28, 0.000000, 0, 1, -5, 816, 0 -ATT, 0.00, 0.40, -6.72, -2.67, 0.00, 49.83, 51.14 -CTUN, 815, 0.41, 3.29, 0.000000, 0, 0, -5, 815, 0 -ATT, 0.00, 0.18, -4.85, -1.84, 0.00, 50.26, 51.14 -CTUN, 815, 0.41, 3.30, 0.000000, 0, 0, -4, 815, 0 -ATT, 0.00, -0.29, -4.38, -0.99, 0.00, 50.52, 51.14 -DU32, 7, 166140 -CURR, 816, 2055380, 976, 2183, 5051, 1547.925400 -CTUN, 816, 0.39, 3.34, 0.000000, 0, 0, -7, 815, 0 -ATT, 0.00, -1.16, -4.48, -0.05, 0.00, 50.86, 51.14 -CTUN, 815, 0.39, 3.34, 0.000000, 0, 0, -6, 815, 0 -ATT, 0.00, -1.53, -4.76, 0.26, 0.00, 51.13, 51.14 -CTUN, 815, 0.36, 3.33, 0.000000, 0, 0, -7, 815, 0 -ATT, 0.00, -1.76, -4.85, -0.42, 0.00, 51.45, 51.14 -CTUN, 816, 0.36, 3.22, 0.000000, 0, 0, -9, 816, 0 -ATT, 0.00, -1.43, -4.76, -0.87, 0.00, 51.64, 51.14 -CTUN, 815, 0.35, 3.23, 0.000000, 0, 0, -8, 816, 0 -ATT, -0.75, -0.18, -4.85, -1.28, 0.00, 51.54, 51.14 -CTUN, 815, 0.35, 3.27, 0.000000, 0, 0, -8, 815, 0 -ATT, -0.75, -0.10, -4.76, -1.11, 0.00, 51.19, 51.14 -CTUN, 815, 0.31, 3.21, 0.000000, 0, 0, -6, 815, 0 -ATT, -0.75, -1.34, -4.38, -0.67, 0.00, 50.89, 51.14 -CTUN, 816, 0.31, 3.10, 0.000000, 0, 0, -5, 816, 0 -ATT, -0.75, -2.16, -3.26, -0.58, 0.00, 50.66, 51.14 -CTUN, 815, 0.29, 3.25, 0.000000, 0, 0, -2, 815, 0 -ATT, -0.75, -0.93, -2.52, -0.26, 0.00, 50.56, 51.14 -CTUN, 815, 0.29, 3.16, 0.000000, 0, 0, -1, 815, 0 -ATT, -0.75, 0.40, -2.70, 0.98, 0.00, 50.58, 51.14 -DU32, 7, 166140 -CURR, 815, 2063534, 976, 2215, 5028, 1554.070100 -CTUN, 815, 0.28, 3.25, 0.000000, 0, 0, 0, 815, 0 -ATT, -0.75, 0.17, -2.52, 1.92, 0.00, 50.76, 51.14 -CTUN, 815, 0.28, 3.33, 0.000000, 0, 0, -1, 816, 0 -ATT, -0.75, -0.25, -2.52, 1.54, 0.00, 51.17, 51.14 -CTUN, 815, 0.27, 3.20, 0.000000, 0, 0, -2, 815, 0 -ATT, -0.85, -0.42, -2.52, 0.79, 0.00, 51.49, 51.14 -CTUN, 815, 0.27, 3.10, 0.000000, 0, 0, -1, 816, 0 -ATT, -0.37, -0.81, -3.26, 0.30, 0.00, 51.66, 51.14 -CTUN, 816, 0.26, 3.19, 0.000000, 0, 0, 0, 816, 0 -ATT, 0.00, -1.03, -3.36, 0.62, 0.00, 51.58, 51.14 -CTUN, 816, 0.26, 3.22, 0.000000, 0, 0, 2, 816, 0 -ATT, 0.00, -1.12, -3.26, 0.09, 0.00, 51.54, 51.14 -CTUN, 815, 0.26, 3.24, 0.000000, 0, 0, 2, 815, 0 -ATT, 0.00, -1.16, -3.92, -1.00, 0.00, 51.31, 51.14 -CTUN, 816, 0.26, 3.14, 0.000000, 0, 0, 7, 816, 0 -ATT, 0.00, -0.40, -3.26, -2.22, 0.00, 50.86, 51.14 -CTUN, 815, 0.26, 3.27, 0.000000, 0, 0, 11, 815, 0 -ATT, 0.00, 0.70, -3.26, -2.54, 0.00, 50.11, 51.14 -CTUN, 815, 0.26, 3.21, 0.000000, 0, 0, 13, 815, 0 -ATT, 0.00, 1.57, -3.26, -2.15, 0.00, 49.31, 51.14 -DU32, 7, 166140 -CURR, 815, 2071688, 976, 2220, 5051, 1560.192000 -CTUN, 816, 0.26, 3.10, 0.000000, 0, 0, 12, 816, 0 -ATT, 0.00, 2.27, -2.52, -1.92, 0.00, 48.59, 51.14 -CTUN, 815, 0.26, 3.17, 0.000000, 0, 0, 13, 815, 0 -ATT, 0.00, 2.46, -2.42, -1.05, 0.00, 48.08, 51.14 -CTUN, 815, 0.26, 3.22, 0.000000, 0, 0, 12, 816, 0 -ATT, 0.00, 2.18, -2.89, 0.39, 0.00, 47.83, 51.14 -CTUN, 816, 0.28, 3.21, 0.000000, 0, 0, 13, 816, 0 -MODE, ALT_HOLD, 815 -ATT, 0.00, 1.68, -2.98, 0.77, 0.00, 47.87, 51.14 -CTUN, 815, 0.28, 3.33, 3.517400, 0, 0, 16, 813, 134 -ATT, 0.00, 1.67, -3.26, 0.47, 0.00, 48.16, 51.14 -CTUN, 815, 0.30, 3.35, 3.672000, 0, 0, 11, 909, 134 -ATT, 0.00, 1.43, -3.45, -0.75, 0.00, 48.71, 51.14 -CTUN, 816, 0.30, 3.22, 3.806000, 0, 0, 17, 945, 134 -ATT, 0.00, 1.20, -3.26, -1.63, 0.00, 49.33, 51.14 -CTUN, 815, 0.31, 3.11, 3.950400, 0, 0, 30, 949, 134 -ATT, 0.00, 1.36, -2.70, -1.46, 0.00, 49.97, 51.14 -CTUN, 815, 0.31, 3.22, 4.094800, 0, 0, 37, 963, 134 -ATT, -2.36, 0.87, -2.33, -0.43, 0.00, 50.83, 51.14 -CTUN, 815, 0.35, 3.38, 4.269200, 0, 0, 44, 1000, 134 -ATT, -5.87, -0.38, -2.52, 0.26, 0.00, 51.80, 51.14 -DU32, 7, 166132 -CURR, 815, 2080512, 965, 2418, 5051, 1566.842900 -CTUN, 816, 0.35, 3.46, 4.403200, 0, 0, 44, 1000, 134 -ATT, -9.09, -1.96, -2.52, 0.20, 0.00, 52.66, 51.14 -CTUN, 815, 0.42, 3.53, 4.587399, 0, 0, 46, 1000, 134 -ATT, -9.56, -4.93, -2.52, 0.14, 0.00, 53.41, 51.14 -CTUN, 815, 0.42, 3.72, 4.691799, 0, 0, 45, 1000, 135 -ATT, -8.62, -8.37, -2.52, 0.14, 0.00, 53.94, 51.14 -CTUN, 816, 0.49, 3.70, 4.886199, 0, 0, 48, 1000, 135 -ATT, -8.24, -9.50, -2.52, 0.02, 0.00, 54.16, 51.14 -CTUN, 815, 0.49, 3.75, 5.010599, 0, 0, 53, 1000, 135 -ATT, -6.63, -8.96, -2.52, 0.30, 0.00, 54.12, 51.14 -CTUN, 816, 0.58, 3.89, 5.204998, 0, 0, 51, 1000, 135 -ATT, -3.12, -8.02, -2.80, 0.62, 0.00, 53.84, 51.14 -CTUN, 816, 0.58, 3.90, 5.309398, 0, 0, 50, 1000, 135 -ATT, 0.00, -6.19, -4.20, 0.44, 0.00, 53.50, 51.14 -CTUN, 814, 0.67, 3.79, 5.503398, 0, 0, 51, 1000, 133 -ATT, 0.00, -3.17, -4.20, 0.02, 0.00, 53.20, 51.14 -CTUN, 813, 0.67, 3.85, 5.595798, 0, 0, 52, 1000, 132 -ATT, 0.00, -1.31, -3.82, 0.14, 0.00, 52.97, 51.14 -CTUN, 813, 0.75, 3.99, 5.778598, 0, 0, 54, 1000, 133 -ATT, 0.00, -0.32, -4.01, 1.27, 0.00, 52.65, 51.14 -DU32, 7, 166132 -CURR, 813, 2091512, 970, 2335, 5051, 1574.340800 -CTUN, 811, 0.75, 3.91, 5.891598, 0, 0, 52, 1000, 133 -ATT, 0.00, 1.18, -4.85, 2.31, 0.00, 52.01, 51.14 -CTUN, 804, 0.85, 3.90, 6.060998, 0, 0, 53, 1000, 127 -ATT, 0.00, 2.96, -4.76, 2.79, 0.00, 51.27, 51.14 -CTUN, 807, 0.85, 4.01, 6.138998, 0, 0, 51, 1000, 129 -ATT, 0.00, 3.36, -5.41, 2.69, 0.00, 50.34, 51.14 -CTUN, 804, 0.95, 3.85, 6.316998, 0, 0, 57, 1000, 127 -ATT, 0.00, 2.05, -6.62, 2.14, 0.00, 49.24, 51.14 -MODE, STABILIZE, 815 -CTUN, 805, 0.95, 4.06, 6.384198, 0, 0, 63, 1000, 0 -ATT, 0.00, 1.40, -7.84, 0.83, 0.00, 48.11, 51.14 -CTUN, 807, 1.06, 4.14, 0.000000, 0, 0, 69, 807, 0 -ATT, 0.00, 1.44, -7.84, -1.38, 0.00, 47.18, 51.14 -CTUN, 809, 1.06, 4.15, 0.000000, 0, 0, 69, 809, 0 -ATT, 0.00, 1.39, -7.84, -3.71, 0.00, 46.65, 51.14 -CTUN, 809, 1.19, 4.18, 0.000000, 0, 2, 66, 811, 0 -ATT, 0.00, 1.09, -8.12, -4.98, 0.00, 46.57, 51.14 -CTUN, 809, 1.19, 4.22, 0.000000, 0, 3, 61, 812, 0 -ATT, 0.00, 0.86, -10.64, -5.50, 0.00, 46.88, 51.14 -CTUN, 809, 1.33, 4.29, 0.000000, 0, 3, 60, 812, 0 -ATT, 0.00, 0.62, -10.26, -6.42, 0.00, 47.53, 51.14 -DU32, 7, 166140 -CURR, 809, 2100373, 977, 2194, 5051, 1580.768300 -CTUN, 806, 1.33, 4.47, 0.000000, 0, 4, 57, 810, 0 -ATT, 0.00, 0.29, -8.21, -7.28, 0.00, 48.47, 51.14 -CTUN, 809, 1.46, 4.51, 0.000000, 0, 5, 54, 814, 0 -ATT, 0.00, -0.12, -5.69, -7.17, 0.00, 49.57, 51.14 -CTUN, 809, 1.46, 4.60, 0.000000, 0, 4, 50, 813, 0 -ATT, 0.00, -0.18, -4.85, -5.80, 0.00, 50.78, 51.14 -CTUN, 805, 1.57, 4.74, 0.000000, 0, 2, 51, 811, 0 -ATT, 0.00, -0.31, -4.76, -3.54, 0.00, 51.98, 51.14 -CTUN, 719, 1.57, 4.86, 0.000000, 0, 0, 50, 719, 0 -ATT, 0.00, -0.29, -5.69, -1.85, 0.00, 53.18, 51.14 -CTUN, 555, 1.69, 5.06, 0.000000, 0, 0, 37, 555, 0 -ATT, 0.00, 2.08, -5.69, -0.16, 0.00, 53.63, 51.14 -CTUN, 517, 1.69, 5.34, 0.000000, 0, 1, -21, 518, 0 -ATT, 0.00, 7.50, -5.41, 2.38, 0.00, 52.40, 51.14 -PM, 0, 0, 0, 0, 1000, 10476, 0, 0 -CTUN, 526, 1.78, 5.26, 0.000000, 0, 4, -54, 530, 0 -ATT, 0.00, 6.31, -6.16, 3.27, 0.00, 51.37, 51.14 -CTUN, 626, 1.76, 5.17, 0.000000, 0, 1, -90, 608, 0 -ATT, 0.00, 1.42, -6.06, 0.90, 0.00, 50.21, 51.14 -CTUN, 802, 1.76, 5.01, 0.000000, 0, 0, -121, 802, 0 -ATT, 0.00, -2.00, -6.81, -2.26, 0.00, 49.09, 51.14 -DU32, 7, 166140 -CURR, 911, 2107461, 948, 2757, 5051, 1585.548700 -CTUN, 925, 1.69, 4.83, 0.000000, 0, 2, -135, 927, 0 -ATT, 0.00, -2.32, -8.12, -3.74, 0.00, 47.87, 51.14 -CTUN, 989, 1.69, 4.55, 0.000000, 0, 2, -126, 991, 0 -ATT, 0.00, -2.02, -6.72, -3.55, 0.00, 46.48, 51.14 -CTUN, 999, 1.47, 4.32, 0.000000, 0, 1, -110, 1000, 0 -ATT, 0.00, -2.55, -6.44, -2.89, 0.00, 45.24, 51.14 -CTUN, 1000, 1.47, 4.16, 0.000000, 0, 0, -91, 1000, 0 -ATT, 0.00, -3.11, -6.81, -2.15, 0.00, 44.23, 51.14 -CTUN, 1000, 1.25, 4.22, 0.000000, 0, 0, -79, 1000, 0 -ATT, 0.00, -3.06, -6.62, -1.88, 0.00, 43.57, 51.14 -CTUN, 1000, 1.25, 4.09, 0.000000, 0, 0, -63, 1000, 0 -ATT, 0.00, -2.73, -6.06, -1.97, 0.00, 43.41, 51.14 -CTUN, 1000, 1.07, 4.16, 0.000000, 0, 0, -46, 1000, 0 -ATT, 0.00, -2.80, -5.13, -1.24, 0.00, 43.60, 51.14 -CTUN, 1000, 1.07, 3.91, 0.000000, 0, 0, -31, 1000, 0 -ATT, 0.00, -3.20, -5.50, -0.06, 0.00, 44.28, 51.14 -CTUN, 1000, 0.96, 3.98, 0.000000, 0, 0, -19, 1000, 0 -ATT, 0.00, -3.23, -4.76, 0.59, 0.00, 45.44, 51.14 -CTUN, 1000, 0.96, 3.97, 0.000000, 0, 0, -5, 1000, 0 -ATT, 0.00, -3.00, -4.76, 1.06, 0.00, 46.88, 51.14 -DU32, 7, 166140 -CURR, 1000, 2117434, 959, 2583, 5051, 1593.265100 -CTUN, 1000, 0.91, 4.00, 0.000000, 0, 0, 3, 1000, 0 -ATT, 0.00, -3.06, -4.76, 1.36, 0.00, 48.45, 51.14 -CTUN, 862, 0.91, 3.94, 0.000000, 0, 1, 8, 885, 0 -ATT, 0.00, -3.28, -4.85, 1.27, 0.00, 50.09, 51.14 -CTUN, 766, 0.91, 3.96, 0.000000, 0, 1, 13, 767, 0 -ATT, 0.00, -2.97, -4.76, 0.58, 0.00, 51.63, 51.14 -CTUN, 753, 0.91, 3.97, 0.000000, 0, 0, 7, 753, 0 -ATT, 0.00, -2.24, -4.76, -0.24, 0.00, 53.03, 51.14 -CTUN, 743, 0.91, 4.06, 0.000000, 0, 0, -4, 743, 0 -ATT, 0.00, -1.46, -4.85, -0.77, 0.00, 54.10, 51.14 -CTUN, 775, 0.91, 4.01, 0.000000, 0, 0, -16, 759, 0 -ATT, 0.18, -0.92, -4.57, -1.24, 0.00, 54.78, 51.14 -CTUN, 842, 0.91, 3.98, 0.000000, 0, 0, -27, 842, 0 -ATT, 1.50, -0.31, -3.26, -2.07, 0.00, 55.13, 51.14 -CTUN, 888, 0.95, 4.02, 0.000000, 0, 0, -28, 888, 0 -ATT, 3.18, 0.39, -2.42, -2.65, 0.00, 55.09, 51.14 -CTUN, 913, 0.91, 4.05, 0.000000, 0, 0, -24, 911, 0 -ATT, 3.56, 1.85, -2.52, -2.40, 0.00, 54.97, 51.14 -CTUN, 911, 0.91, 3.95, 0.000000, 0, 1, -21, 912, 0 -ATT, 3.65, 2.97, -2.42, -2.01, 0.00, 54.81, 51.14 -DU32, 7, 166140 -CURR, 905, 2125818, 961, 2494, 5028, 1599.519300 -CTUN, 906, 0.89, 3.92, 0.000000, 0, 1, -17, 909, 0 -ATT, 3.84, 4.15, -2.52, -1.71, 0.00, 54.49, 51.14 -CTUN, 906, 0.89, 3.75, 0.000000, 0, 2, -9, 908, 0 -ATT, 3.93, 5.14, -2.42, -1.30, 0.00, 54.09, 51.14 -CTUN, 886, 0.86, 3.84, 0.000000, 0, 3, -6, 901, 0 -ATT, 3.46, 5.19, -2.52, -0.68, 0.00, 53.64, 51.14 -CTUN, 876, 0.86, 4.00, 0.000000, 0, 2, 0, 878, 0 -ATT, 2.53, 4.72, -2.52, 0.09, 0.00, 53.01, 51.14 -CTUN, 873, 0.86, 3.90, 0.000000, 0, 2, 7, 875, 0 -ATT, 0.00, 4.23, -2.52, 0.85, 0.00, 52.36, 51.14 -CTUN, 868, 0.86, 3.92, 0.000000, 0, 1, 12, 869, 0 -ATT, 0.00, 2.59, -3.54, 1.51, 0.00, 51.93, 51.14 -CTUN, 835, 0.86, 3.96, 0.000000, 0, 0, 15, 835, 0 -ATT, 0.00, 0.48, -6.25, 1.93, 0.00, 51.61, 51.14 -CTUN, 802, 0.87, 3.95, 0.000000, 0, 0, 19, 809, 0 -ATT, 0.00, -0.41, -7.84, 1.51, 0.00, 51.50, 51.14 -CTUN, 789, 0.87, 3.98, 0.000000, 0, 0, 19, 789, 0 -ATT, 0.00, -0.32, -8.12, -0.07, 0.00, 51.44, 51.14 -CTUN, 787, 0.91, 4.03, 0.000000, 0, 0, 15, 786, 0 -ATT, 0.00, -0.12, -8.02, -2.12, 0.00, 51.50, 51.14 -DU32, 7, 166140 -CURR, 783, 2134283, 983, 2033, 5028, 1606.002100 -CTUN, 783, 0.91, 4.04, 0.000000, 0, 0, 10, 786, 0 -ATT, 0.00, -0.69, -7.56, -3.44, 0.00, 51.64, 51.14 -CTUN, 784, 0.95, 4.08, 0.000000, 0, 1, 1, 784, 0 -ATT, 0.00, -1.01, -6.62, -3.68, 0.00, 51.71, 51.14 -CTUN, 792, 0.95, 4.04, 0.000000, 0, 1, -3, 793, 0 -ATT, 0.00, -1.37, -4.94, -3.15, 0.00, 51.72, 51.14 -CTUN, 802, 0.96, 4.00, 0.000000, 0, 1, -5, 802, 0 -ATT, 0.00, -1.50, -5.50, -2.29, 0.00, 51.82, 51.14 -CTUN, 805, 0.95, 4.03, 0.000000, 0, 0, -12, 805, 0 -ATT, 0.00, -1.28, -5.13, -1.56, 0.00, 52.10, 51.14 -CTUN, 813, 0.95, 4.01, 0.000000, 0, 0, -15, 813, 0 -ATT, 0.00, -0.77, -4.57, -1.24, 0.00, 52.42, 51.14 -CTUN, 813, 0.94, 4.01, 0.000000, 0, 0, -16, 813, 0 -ATT, 0.00, -0.01, -4.48, -1.24, 0.00, 52.68, 51.14 -CTUN, 815, 0.94, 4.12, 0.000000, 0, 0, -17, 813, 0 -ATT, 0.00, 0.61, -4.38, -1.55, 0.00, 52.75, 51.14 -CTUN, 814, 0.91, 3.99, 0.000000, 0, 0, -14, 815, 0 -ATT, 0.00, 0.50, -2.52, -1.70, 0.00, 52.64, 51.14 -CTUN, 814, 0.91, 3.92, 0.000000, 0, 0, -13, 816, 0 -ATT, 0.00, 0.34, -2.52, -0.96, 0.00, 52.41, 51.14 -DU32, 7, 166140 -CURR, 813, 2142349, 979, 2234, 5028, 1612.038800 -CTUN, 813, 0.88, 3.90, 0.000000, 0, 0, -13, 813, 0 -ATT, 0.00, 0.03, -2.42, -0.03, 0.00, 52.08, 51.14 -CTUN, 813, 0.88, 3.96, 0.000000, 0, 0, -13, 813, 0 -ATT, 0.00, -0.37, -2.52, 0.60, 0.00, 51.66, 51.14 -CTUN, 813, 0.85, 4.00, 0.000000, 0, 0, -14, 813, 0 -ATT, 0.00, -0.06, -2.70, 0.74, 0.00, 51.36, 51.14 -CTUN, 813, 0.85, 3.92, 0.000000, 0, 0, -17, 813, 0 -ATT, 0.00, 0.72, -2.80, 0.44, 0.00, 51.25, 51.14 -CTUN, 816, 0.82, 3.94, 0.000000, 0, 0, -19, 815, 0 -ATT, -1.32, 0.27, -3.08, -0.46, 0.00, 51.37, 51.14 -CTUN, 822, 0.82, 3.79, 0.000000, 0, 0, -24, 819, 0 -ATT, -2.74, -1.02, -2.70, -1.57, 0.00, 51.71, 51.14 -CTUN, 824, 0.77, 3.91, 0.000000, 0, 0, -25, 823, 0 -ATT, -2.74, -2.53, -2.70, -2.29, 0.00, 52.11, 51.14 -CTUN, 828, 0.77, 3.95, 0.000000, 0, 1, -26, 829, 0 -ATT, -2.55, -3.14, -2.52, -2.66, 0.00, 52.56, 51.14 -CTUN, 835, 0.74, 3.80, 0.000000, 0, 1, -27, 837, 0 -ATT, -2.55, -2.88, -2.52, -2.17, 0.00, 52.99, 51.14 -CTUN, 836, 0.74, 3.90, 0.000000, 0, 1, -25, 837, 0 -ATT, -1.32, -2.91, -1.40, -1.06, 0.00, 53.52, 51.14 -DU32, 7, 166140 -CURR, 836, 2150582, 968, 2352, 5051, 1618.310700 -CTUN, 836, 0.69, 3.87, 0.000000, 0, 0, -24, 836, 0 -ATT, 0.00, -2.78, -1.77, 0.25, 0.00, 54.15, 51.14 -CTUN, 836, 0.69, 3.88, 0.000000, 0, 0, -25, 836, 0 -ATT, 0.00, -0.99, -1.30, 0.45, 0.00, 55.02, 51.14 -CTUN, 840, 0.63, 3.72, 0.000000, 0, 0, -27, 837, 0 -ATT, 0.00, 1.15, -1.58, 0.06, 0.00, 55.84, 51.14 -CTUN, 840, 0.63, 3.91, 0.000000, 0, 0, -25, 840, 0 -ATT, 0.00, 2.10, -1.68, -0.18, 0.00, 56.46, 51.14 -CTUN, 840, 0.58, 3.68, 0.000000, 0, 0, -31, 840, 0 -ATT, 0.00, 1.33, -2.42, -0.54, 0.00, 57.24, 51.14 -CTUN, 838, 0.58, 3.57, 0.000000, 0, 0, -34, 838, 0 -ATT, 0.00, 0.35, -2.42, -0.16, 0.00, 58.13, 51.14 -CTUN, 838, 0.52, 3.66, 0.000000, 0, 0, -34, 838, 0 -ATT, 0.00, -0.66, -2.42, 0.00, 0.00, 58.93, 51.14 -CTUN, 839, 0.52, 3.61, 0.000000, 0, 0, -36, 838, 0 -ATT, 0.00, -0.52, -2.33, 0.29, 0.00, 59.47, 51.14 -CTUN, 855, 0.47, 3.67, 0.000000, 0, 0, -42, 850, 0 -ATT, -2.17, 0.44, -2.24, 0.08, 0.00, 59.62, 51.14 -CTUN, 857, 0.47, 3.35, 0.000000, 0, 0, -49, 857, 0 -ATT, -4.07, -0.03, -1.58, -1.24, 0.00, 59.40, 51.14 -DU32, 7, 166140 -CURR, 866, 2159016, 968, 2364, 5051, 1624.549600 -CTUN, 870, 0.38, 3.39, 0.000000, 0, 0, -48, 866, 0 -ATT, -5.87, -2.90, -1.49, -0.61, 0.00, 58.66, 51.14 -CTUN, 879, 0.38, 3.45, 0.000000, 0, 1, -44, 880, 0 -ATT, -6.06, -4.97, -1.40, 0.80, 0.00, 57.64, 51.14 -CTUN, 906, 0.30, 3.37, 0.000000, 0, 3, -39, 901, 0 -ATT, -5.87, -5.02, -1.21, 1.62, 0.00, 56.56, 51.14 -CTUN, 909, 0.30, 3.28, 0.000000, 0, 3, -34, 912, 0 -ATT, -2.84, -5.51, -0.93, 1.50, 0.00, 55.43, 51.14 -CTUN, 909, 0.23, 3.33, 0.000000, 0, 3, -21, 912, 0 -ATT, 0.00, -4.56, -2.14, 1.71, 0.00, 54.46, 51.14 -CTUN, 908, 0.23, 3.20, 0.000000, 0, 1, -7, 910, 0 -ATT, 0.00, -1.60, -2.24, 1.89, 0.00, 53.56, 51.14 -CTUN, 904, 0.20, 3.12, 0.000000, 0, 0, 6, 906, 0 -ATT, 0.00, 0.45, -2.52, 1.29, 0.00, 52.91, 51.14 -CTUN, 864, 0.20, 3.17, 0.000000, 0, 0, 19, 880, 0 -ATT, 0.00, 0.70, -2.42, 0.64, 0.00, 52.55, 51.14 -CTUN, 849, 0.20, 3.43, 0.000000, 0, 0, 33, 852, 0 -ATT, 0.00, 0.33, -2.52, 0.43, 0.00, 52.38, 51.14 -CTUN, 827, 0.20, 3.38, 0.000000, 0, 0, 44, 827, 0 -ATT, 0.00, 0.60, -2.61, 0.52, 0.00, 52.38, 51.14 -DU32, 7, 166140 -CURR, 809, 2167810, 968, 2192, 5051, 1631.232900 -CTUN, 809, 0.20, 3.42, 0.000000, 0, 0, 48, 813, 0 -ATT, 0.00, 1.37, -2.70, 0.64, 0.00, 52.66, 51.14 -CTUN, 790, 0.25, 3.58, 0.000000, 0, 0, 45, 795, 0 -ATT, 0.00, 1.51, -3.08, 0.03, 0.00, 53.34, 51.14 -CTUN, 786, 0.25, 3.54, 0.000000, 0, 0, 41, 786, 0 -ATT, 0.00, 0.19, -3.08, -1.06, 0.00, 54.21, 51.14 -CTUN, 780, 0.33, 3.67, 0.000000, 0, 0, 34, 780, 0 -ATT, 0.00, -0.15, -3.26, -1.05, 0.00, 55.25, 51.14 -CTUN, 782, 0.33, 3.45, 0.000000, 0, 0, 25, 781, 0 -ATT, 0.00, 0.44, -3.17, -0.16, 0.00, 56.02, 51.14 -CTUN, 788, 0.42, 3.79, 0.000000, 0, 0, 12, 787, 0 -ATT, 0.00, -0.03, -3.26, 0.16, 0.00, 56.46, 51.14 -CTUN, 796, 0.42, 3.68, 0.000000, 0, 0, 2, 796, 0 -ATT, 0.00, -0.83, -2.89, -0.59, 0.00, 56.53, 51.14 -CTUN, 824, 0.46, 3.56, 0.000000, 0, 0, -3, 822, 0 -ATT, 0.00, -0.77, -3.08, -1.23, 0.00, 56.43, 51.14 -CTUN, 843, 0.46, 3.73, 0.000000, 0, 0, -6, 841, 0 -ATT, 0.00, -0.82, -3.08, -1.09, 0.00, 56.13, 51.14 -CTUN, 857, 0.47, 3.66, 0.000000, 0, 0, -8, 855, 0 -ATT, 0.00, -0.84, -3.08, -1.14, 0.00, 55.67, 51.14 -DU32, 7, 166140 -CURR, 857, 2175896, 952, 2462, 5051, 1637.331400 -CTUN, 857, 0.46, 3.50, 0.000000, 0, 0, -3, 857, 0 -ATT, 0.18, -0.59, -3.08, -1.44, 0.00, 55.13, 51.14 -CTUN, 870, 0.46, 3.54, 0.000000, 0, 0, 2, 868, 0 -ATT, 1.31, 0.11, -2.42, -1.58, 0.00, 54.62, 51.14 -CTUN, 871, 0.46, 3.58, 0.000000, 0, 0, 3, 871, 0 -ATT, 1.50, 0.39, -2.42, -1.49, 0.00, 54.08, 51.14 -CTUN, 867, 0.46, 3.35, 0.000000, 0, 0, 8, 868, 0 -ATT, 1.03, 1.00, -2.42, -1.21, 0.00, 53.45, 51.14 -CTUN, 868, 0.45, 3.51, 0.000000, 0, 0, 15, 867, 0 -ATT, 0.84, 1.63, -2.42, -0.46, 0.00, 52.93, 51.14 -CTUN, 860, 0.46, 3.68, 0.000000, 0, 0, 25, 860, 0 -ATT, 0.84, 1.81, -2.52, 0.62, 0.00, 52.58, 51.14 -CTUN, 856, 0.46, 3.71, 0.000000, 0, 0, 26, 856, 0 -ATT, 0.65, 1.81, -2.89, 0.99, 0.00, 52.58, 51.14 -CTUN, 836, 0.48, 3.70, 0.000000, 0, 0, 29, 837, 0 -ATT, 0.46, 1.10, -4.38, 1.25, 0.00, 52.86, 51.14 -CTUN, 814, 0.48, 3.76, 0.000000, 0, 0, 29, 814, 0 -ATT, 0.46, 0.83, -4.76, 1.24, 0.00, 53.44, 51.14 -CTUN, 812, 0.52, 3.72, 0.000000, 0, 0, 30, 813, 0 -ATT, 0.46, 1.08, -5.13, 0.15, 0.00, 54.18, 51.14 -DU32, 7, 166140 -CURR, 813, 2184374, 973, 2217, 5051, 1643.956300 -CTUN, 813, 0.52, 3.73, 0.000000, 0, 0, 27, 813, 0 -ATT, 0.28, 1.80, -5.22, -1.65, 0.00, 55.04, 51.14 -CTUN, 817, 0.58, 3.80, 0.000000, 0, 0, 30, 816, 0 -ATT, 0.28, 1.80, -5.04, -3.07, 0.00, 55.91, 51.14 -CTUN, 821, 0.58, 3.73, 0.000000, 0, 1, 25, 822, 0 -ATT, 0.09, 1.21, -4.76, -3.53, 0.00, 56.85, 51.14 -CTUN, 821, 0.62, 3.86, 0.000000, 0, 1, 25, 822, 0 -ATT, 0.00, 0.01, -4.38, -3.16, 0.00, 57.77, 51.14 -CTUN, 821, 0.62, 3.91, 0.000000, 0, 0, 25, 821, 0 -ATT, 0.00, -1.25, -3.82, -2.55, 0.00, 58.64, 51.14 -CTUN, 821, 0.66, 3.96, 0.000000, 0, 0, 26, 822, 0 -ATT, 0.00, -2.11, -3.92, -1.86, 0.00, 59.38, 51.14 -CTUN, 821, 0.66, 3.93, 0.000000, 0, 0, 21, 822, 0 -ATT, 0.00, -2.66, -3.45, -1.50, 0.00, 60.12, 51.14 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 821, 0.70, 3.92, 0.000000, 0, 1, 17, 821, 0 -ATT, 0.00, -3.14, -4.57, -1.40, 0.00, 60.81, 51.14 -CTUN, 821, 0.70, 3.90, 0.000000, 0, 1, 15, 822, 0 -ATT, 0.00, -3.15, -4.76, -1.78, 0.00, 61.35, 51.35 -CTUN, 821, 0.72, 3.89, 0.000000, 0, 1, 11, 822, 0 -ATT, 0.00, -2.76, -4.76, -2.57, 0.00, 61.78, 51.78 -DU32, 7, 166140 -CURR, 821, 2192586, 972, 2227, 5051, 1650.209800 -CTUN, 821, 0.72, 3.96, 0.000000, 0, 1, 9, 822, 0 -ATT, 0.00, -1.71, -4.85, -3.13, 0.00, 62.27, 52.27 -CTUN, 822, 0.72, 4.05, 0.000000, 0, 1, 5, 823, 0 -ATT, 0.00, -0.74, -3.73, -3.64, 0.00, 62.89, 52.89 -CTUN, 829, 0.72, 3.92, 0.000000, 0, 1, 0, 828, 0 -ATT, 0.00, 0.18, -3.26, -3.86, 0.00, 63.50, 53.50 -CTUN, 831, 0.72, 4.04, 0.000000, 0, 1, -6, 832, 0 -ATT, 0.00, 1.15, -2.89, -3.18, 0.00, 63.91, 53.91 -CTUN, 834, 0.71, 4.09, 0.000000, 0, 1, -12, 835, 0 -ATT, 0.00, 2.10, -2.70, -2.39, 0.00, 64.24, 54.24 -CTUN, 837, 0.71, 3.99, 0.000000, 0, 1, -17, 837, 0 -ATT, 0.00, 2.45, -2.52, -1.96, 0.00, 64.53, 54.53 -CTUN, 855, 0.68, 3.92, 0.000000, 0, 0, -22, 850, 0 -ATT, 0.00, 1.73, -2.61, -1.61, 0.00, 64.64, 54.65 -CTUN, 857, 0.68, 3.85, 0.000000, 0, 0, -26, 857, 0 -ATT, 0.00, 1.04, -2.61, -1.46, 0.00, 64.54, 54.65 -CTUN, 870, 0.63, 3.87, 0.000000, 0, 0, -29, 868, 0 -ATT, 0.00, 1.34, -2.70, -1.68, 0.00, 64.15, 54.65 -CTUN, 885, 0.63, 3.84, 0.000000, 0, 0, -32, 877, 0 -ATT, 0.00, 1.43, -2.80, -1.70, 0.00, 63.49, 54.65 -DU32, 7, 166140 -CURR, 900, 2201079, 970, 2303, 5051, 1656.208500 -CTUN, 903, 0.56, 3.74, 0.000000, 0, 0, -29, 900, 0 -ATT, 0.00, 1.03, -2.61, -1.22, 0.00, 62.58, 54.65 -CTUN, 907, 0.56, 3.56, 0.000000, 0, 0, -23, 906, 0 -ATT, 0.00, 0.67, -2.70, -0.17, 0.00, 61.57, 54.65 -CTUN, 906, 0.47, 3.81, 0.000000, 0, 0, -22, 906, 0 -ATT, -2.17, 0.87, -2.52, 0.53, 0.00, 60.63, 54.65 -CTUN, 906, 0.47, 3.62, 0.000000, 0, 0, -17, 906, 0 -ATT, -3.97, 1.40, -1.77, 0.97, 0.00, 59.84, 54.65 -CTUN, 906, 0.40, 3.61, 0.000000, 0, 0, -12, 906, 0 -ATT, -6.06, -0.05, -0.93, 1.50, 0.00, 59.24, 54.65 -CTUN, 906, 0.40, 3.78, 0.000000, 0, 0, -13, 905, 0 -ATT, -7.48, -2.11, 0.00, 1.86, 0.00, 58.98, 54.65 -CTUN, 906, 0.35, 3.49, 0.000000, 0, 1, -7, 907, 0 -ATT, -9.47, -3.96, 0.00, 1.96, 0.00, 58.78, 54.65 -CTUN, 906, 0.35, 3.49, 0.000000, 0, 3, 0, 909, 0 -ATT, -9.37, -5.76, 0.00, 2.39, 0.00, 58.75, 54.65 -CTUN, 906, 0.30, 3.48, 0.000000, 0, 5, 5, 911, 0 -ATT, -8.05, -7.17, -0.84, 2.74, 0.00, 58.84, 54.65 -CTUN, 906, 0.30, 3.46, 0.000000, 0, 7, 9, 913, 0 -ATT, -6.15, -7.17, -2.24, 2.67, 0.00, 59.27, 54.65 -CTUN, 906, 0.29, 3.43, 0.000000, 0, 7, 15, 913, 0 -DU32, 7, 166140 -CURR, 906, 2210159, 970, 2242, 5051, 1662.691000 -ATT, -2.55, -7.23, -2.52, 2.43, 0.00, 60.08, 54.65 -CTUN, 906, 0.30, 3.29, 0.000000, 0, 6, 13, 912, 0 -ATT, -0.28, -6.65, -3.64, 1.88, 0.00, 60.75, 54.65 -CTUN, 904, 0.29, 3.47, 0.000000, 0, 4, 13, 909, 0 -ATT, 0.00, -4.31, -4.57, 1.77, 0.00, 61.14, 54.65 -CTUN, 885, 0.29, 3.41, 0.000000, 0, 1, 12, 888, 0 -ATT, 0.00, -0.86, -4.57, 0.93, 0.00, 61.29, 54.65 -CTUN, 879, 0.29, 3.24, 0.000000, 0, 0, 7, 879, 0 -ATT, 0.00, 1.23, -4.76, -0.21, 0.00, 61.07, 54.65 -CTUN, 879, 0.29, 3.31, 0.000000, 0, 0, 7, 880, 0 -ATT, 0.46, 1.38, -4.85, -1.05, 0.00, 60.50, 54.65 -CTUN, 879, 0.28, 3.44, 0.000000, 0, 0, 13, 880, 0 -ATT, 1.78, 0.91, -4.76, -1.29, 0.00, 59.71, 54.65 -CTUN, 879, 0.28, 3.66, 0.000000, 0, 0, 17, 880, 0 -ATT, 1.78, 1.25, -4.76, -1.08, 0.00, 59.03, 54.65 -CTUN, 879, 0.28, 3.68, 0.000000, 0, 0, 24, 879, 0 -ATT, 2.34, 1.65, -4.85, -1.21, 0.00, 58.33, 54.65 -CTUN, 879, 0.28, 3.51, 0.000000, 0, 0, 28, 879, 0 -ATT, 2.34, 3.36, -4.85, -1.78, 0.00, 57.51, 54.65 -CTUN, 879, 0.28, 3.46, 0.000000, 0, 1, 31, 880, 0 -DU32, 7, 166140 -CURR, 879, 2219033, 963, 2371, 5051, 1669.077900 -ATT, 2.34, 3.68, -4.85, -1.69, 0.00, 56.78, 54.65 -CTUN, 880, 0.30, 3.63, 0.000000, 0, 1, 36, 880, 0 -ATT, 2.34, 2.71, -5.04, -1.26, 0.00, 56.21, 54.65 -CTUN, 877, 0.30, 3.64, 0.000000, 0, 0, 43, 877, 0 -ATT, 1.96, 3.16, -6.34, -0.27, 0.00, 55.93, 54.65 -CTUN, 874, 0.34, 3.48, 0.000000, 0, 1, 48, 874, 0 -ATT, 0.00, 3.29, -7.84, 0.58, 0.00, 56.06, 54.65 -CTUN, 871, 0.34, 3.62, 0.000000, 0, 0, 45, 872, 0 -ATT, 0.00, 1.91, -10.82, -0.20, 0.00, 56.55, 54.65 -CTUN, 870, 0.39, 3.84, 0.000000, 0, 0, 41, 871, 0 -ATT, 0.00, 0.02, -10.82, -2.37, 0.00, 57.36, 54.65 -CTUN, 857, 0.39, 3.87, 0.000000, 0, 1, 43, 858, 0 -ATT, 0.00, -1.24, -11.76, -4.85, 0.00, 58.45, 54.65 -CTUN, 855, 0.46, 3.72, 0.000000, 0, 3, 40, 858, 0 -ATT, 0.00, -1.33, -11.95, -6.19, 0.00, 59.47, 54.65 -CTUN, 855, 0.46, 3.85, 0.000000, 0, 4, 39, 859, 0 -ATT, 0.00, -1.50, -11.76, -6.83, 0.00, 60.37, 54.65 -CTUN, 855, 0.53, 3.78, 0.000000, 0, 5, 38, 859, 0 -ATT, 0.00, -1.64, -11.67, -7.45, 0.00, 60.95, 54.65 -CTUN, 855, 0.53, 3.81, 0.000000, 0, 6, 33, 861, 0 -DU32, 7, 166140 -CURR, 855, 2227707, 970, 2243, 5028, 1675.541900 -ATT, 0.00, -1.44, -10.82, -7.71, 0.00, 61.56, 54.65 -CTUN, 854, 0.58, 3.91, 0.000000, 0, 6, 30, 861, 0 -ATT, 0.00, -1.01, -10.92, -7.29, 0.00, 62.02, 54.65 -CTUN, 855, 0.58, 3.95, 0.000000, 0, 5, 29, 860, 0 -ATT, 0.00, -0.30, -10.82, -6.66, 0.00, 62.25, 54.65 -CTUN, 855, 0.62, 3.97, 0.000000, 0, 4, 21, 859, 0 -ATT, 0.00, 0.50, -10.17, -6.34, 0.00, 61.99, 54.65 -CTUN, 855, 0.62, 4.05, 0.000000, 0, 4, 14, 859, 0 -ATT, 0.00, 0.84, -6.44, -6.06, 0.00, 61.25, 54.65 -CTUN, 855, 0.64, 3.92, 0.000000, 0, 3, 18, 858, 0 -ATT, 0.00, 0.93, -2.61, -5.09, 0.00, 60.07, 54.65 -CTUN, 857, 0.64, 3.95, 0.000000, 0, 2, 14, 859, 0 -ATT, 0.00, 0.63, -2.52, -3.11, 0.00, 58.49, 54.65 -CTUN, 857, 0.64, 4.13, 0.000000, 0, 0, 17, 857, 0 -ATT, 0.00, -0.19, -2.05, -0.39, 0.00, 56.53, 54.65 -CTUN, 857, 0.64, 4.05, 0.000000, 0, 0, 20, 857, 0 -ATT, -0.37, -0.13, -0.37, 1.76, 0.00, 54.13, 54.65 -CTUN, 857, 0.64, 3.98, 0.000000, 0, 0, 24, 857, 0 -ATT, -1.13, 0.31, -1.12, 2.83, 0.00, 51.79, 54.65 -CTUN, 857, 0.63, 4.06, 0.000000, 0, 1, 26, 858, 0 -DU32, 7, 166140 -CURR, 857, 2236290, 970, 2406, 5051, 1681.952000 -ATT, -0.75, -0.47, -0.74, 3.86, 0.00, 49.77, 54.65 -CTUN, 857, 0.64, 4.12, 0.000000, 0, 2, 26, 859, 0 -ATT, -0.75, -1.58, -2.52, 4.72, 0.00, 48.25, 54.65 -CTUN, 857, 0.64, 4.14, 0.000000, 0, 2, 29, 859, 0 -ATT, -1.04, -2.06, -1.12, 4.90, 0.00, 47.42, 54.65 -CTUN, 857, 0.65, 4.12, 0.000000, 0, 2, 33, 859, 0 -ATT, -2.55, -1.89, -2.52, 4.14, 0.00, 47.39, 54.65 -CTUN, 857, 0.65, 4.02, 0.000000, 0, 1, 34, 858, 0 -ATT, -4.83, -2.76, -4.76, 2.59, 0.00, 47.99, 54.65 -CTUN, 857, 0.68, 4.16, 0.000000, 0, 2, 37, 859, 0 -ATT, -5.68, -6.07, -5.60, 0.99, 0.00, 49.01, 54.65 -CTUN, 857, 0.68, 4.10, 0.000000, 0, 4, 33, 861, 0 -ATT, -4.64, -6.70, -6.72, -0.71, 0.00, 50.09, 54.65 -CTUN, 857, 0.72, 4.05, 0.000000, 0, 4, 33, 860, 0 -ATT, -4.16, -5.38, -8.12, -2.59, 0.00, 51.15, 54.65 -CTUN, 857, 0.72, 4.12, 0.000000, 0, 3, 35, 860, 0 -ATT, -4.07, -3.94, -8.21, -4.24, 0.00, 52.16, 54.65 -CTUN, 857, 0.76, 4.12, 0.000000, 0, 3, 37, 860, 0 -ATT, -0.28, -3.39, -7.74, -5.27, 0.00, 53.07, 54.65 -CTUN, 857, 0.76, 4.07, 0.000000, 0, 4, 39, 861, 0 -DU32, 7, 166140 -CURR, 857, 2244887, 966, 2423, 5051, 1688.667000 -ATT, 0.00, -3.18, -7.37, -5.36, 0.00, 53.77, 54.65 -CTUN, 860, 0.79, 4.07, 0.000000, 0, 3, 42, 860, 0 -ATT, 0.00, -2.03, -6.81, -4.39, 0.00, 54.40, 54.65 -CTUN, 857, 0.79, 4.02, 0.000000, 0, 1, 47, 858, 0 -ATT, 0.00, -1.06, -6.72, -3.11, 0.00, 54.92, 54.65 -CTUN, 839, 0.84, 4.08, 0.000000, 0, 0, 48, 846, 0 -ATT, 0.00, -0.35, -6.72, -2.91, 0.00, 55.19, 54.65 -CTUN, 818, 0.84, 4.14, 0.000000, 0, 0, 48, 823, 0 -ATT, 0.00, -0.65, -6.81, -3.20, 0.00, 55.27, 54.65 -CTUN, 796, 0.91, 4.26, 0.000000, 0, 1, 47, 799, 0 -ATT, 0.00, -1.40, -6.81, -3.33, 0.00, 55.13, 54.65 -CTUN, 797, 0.91, 4.31, 0.000000, 0, 1, 45, 797, 0 -ATT, 0.00, -1.95, -6.72, -3.21, 0.00, 54.78, 54.65 -CTUN, 796, 0.97, 4.35, 0.000000, 0, 1, 38, 797, 0 -ATT, 0.00, -1.55, -6.72, -3.34, 0.00, 54.37, 54.65 -CTUN, 798, 0.97, 4.24, 0.000000, 0, 1, 33, 799, 0 -ATT, 0.00, -1.00, -6.34, -3.28, 0.00, 53.95, 54.65 -CTUN, 802, 1.03, 4.36, 0.000000, 0, 1, 26, 800, 0 -ATT, 0.00, -1.29, -5.69, -2.95, 0.00, 53.61, 54.65 -CTUN, 804, 1.03, 4.41, 0.000000, 0, 1, 21, 805, 0 -DU32, 7, 166140 -CURR, 804, 2253083, 971, 2151, 5028, 1694.844000 -ATT, 0.00, -1.53, -2.52, -2.61, 0.00, 53.43, 54.65 -CTUN, 804, 1.06, 4.40, 0.000000, 0, 0, 17, 804, 0 -ATT, 0.46, -1.09, -2.42, -1.83, 0.00, 53.52, 54.65 -CTUN, 815, 1.06, 4.22, 0.000000, 0, 0, 10, 813, 0 -ATT, 0.93, -0.50, -2.24, -0.65, 0.00, 53.78, 54.65 -CTUN, 831, 1.09, 4.50, 0.000000, 0, 0, 10, 830, 0 -ATT, 1.40, 0.08, -2.24, -0.01, 0.00, 54.20, 54.65 -CTUN, 836, 1.09, 4.46, 0.000000, 0, 0, 10, 836, 0 -ATT, 1.31, 0.57, -2.33, 0.43, 0.00, 54.82, 54.65 -CTUN, 842, 1.10, 4.55, 0.000000, 0, 0, 11, 842, 0 -ATT, 1.21, 0.48, -2.33, 1.19, 0.00, 55.41, 54.65 -CTUN, 850, 1.10, 4.41, 0.000000, 0, 0, 11, 848, 0 -ATT, 1.21, 0.26, -2.24, 2.12, 0.00, 55.95, 54.65 -CTUN, 855, 1.10, 4.44, 0.000000, 0, 0, 11, 853, 0 -ATT, 1.68, 0.10, -2.42, 2.96, 0.00, 56.45, 54.65 -CTUN, 855, 1.10, 4.52, 0.000000, 0, 1, 11, 856, 0 -ATT, 1.78, 0.53, -2.42, 3.24, 0.00, 56.94, 54.65 -CTUN, 855, 1.10, 4.50, 0.000000, 0, 1, 12, 856, 0 -ATT, 2.06, 1.45, -2.52, 3.17, 0.00, 57.24, 54.65 -CTUN, 855, 1.10, 4.52, 0.000000, 0, 1, 11, 856, 0 -DU32, 7, 166140 -CURR, 855, 2261465, 965, 2317, 5051, 1701.228300 -ATT, 2.81, 2.33, -2.52, 2.81, 0.00, 57.49, 54.65 -CTUN, 852, 1.11, 4.61, 0.000000, 0, 1, 12, 853, 0 -ATT, 3.09, 2.86, -3.26, 2.20, 0.00, 57.57, 54.65 -CTUN, 853, 1.11, 4.55, 0.000000, 0, 1, 13, 854, 0 -ATT, 3.18, 3.79, -3.92, 1.44, 0.00, 57.54, 54.65 -CTUN, 850, 1.12, 4.46, 0.000000, 0, 2, 15, 852, 0 -ATT, 3.09, 4.58, -4.48, 0.68, 0.00, 57.27, 54.65 -CTUN, 849, 1.12, 4.55, 0.000000, 0, 2, 10, 851, 0 -ATT, 2.62, 4.66, -4.57, -0.35, 0.00, 56.75, 54.65 -CTUN, 853, 1.14, 4.56, 0.000000, 0, 2, 12, 854, 0 -ATT, 0.75, 4.17, -4.57, -1.15, 0.00, 56.07, 54.65 -CTUN, 850, 1.14, 4.43, 0.000000, 0, 1, 14, 851, 0 -ATT, 0.18, 3.24, -4.66, -1.92, 0.00, 55.51, 54.65 -CTUN, 837, 1.15, 4.54, 0.000000, 0, 1, 17, 843, 0 -ATT, 0.00, 1.68, -6.06, -2.78, 0.00, 55.17, 54.65 -CTUN, 836, 1.15, 4.64, 0.000000, 0, 1, 16, 837, 0 -ATT, 0.00, 0.85, -6.53, -3.64, 0.00, 55.03, 54.65 -CTUN, 836, 1.18, 4.52, 0.000000, 0, 1, 18, 836, 0 -ATT, 0.00, 0.11, -6.53, -4.18, 0.00, 55.10, 54.65 -CTUN, 836, 1.18, 4.52, 0.000000, 0, 2, 17, 838, 0 -DU32, 7, 166140 -CURR, 836, 2269938, 970, 2309, 5051, 1707.732400 -ATT, 0.00, -0.81, -6.53, -4.40, 0.00, 55.12, 54.65 -CTUN, 835, 1.21, 4.55, 0.000000, 0, 2, 18, 837, 0 -ATT, 0.00, -0.93, -6.06, -4.73, 0.00, 55.15, 54.65 -CTUN, 831, 1.21, 4.61, 0.000000, 0, 2, 20, 833, 0 -ATT, 0.00, -0.57, -5.97, -4.59, 0.00, 54.92, 54.65 -CTUN, 830, 1.24, 4.68, 0.000000, 0, 2, 17, 832, 0 -ATT, 0.00, -0.24, -6.06, -4.28, 0.00, 54.63, 54.65 -CTUN, 809, 1.24, 4.75, 0.000000, 0, 1, 19, 814, 0 -ATT, 0.00, -0.13, -5.88, -3.84, 0.00, 54.27, 54.65 -CTUN, 796, 1.28, 4.69, 0.000000, 0, 1, 16, 797, 0 -ATT, 0.00, 0.15, -5.69, -3.60, 0.00, 53.88, 54.65 -CTUN, 796, 1.28, 4.75, 0.000000, 0, 1, 10, 797, 0 -ATT, 0.00, 0.15, -5.69, -3.55, 0.00, 53.36, 54.65 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 796, 1.31, 4.68, 0.000000, 0, 1, 8, 797, 0 -ATT, 0.00, -0.28, -5.60, -3.27, 0.00, 52.61, 54.65 -CTUN, 798, 1.31, 4.75, 0.000000, 0, 0, 7, 798, 0 -ATT, 0.00, -0.52, -4.85, -2.71, 0.00, 51.84, 54.65 -CTUN, 805, 1.32, 4.77, 0.000000, 0, 0, 2, 805, 0 -ATT, 0.00, -0.64, -4.76, -1.99, 0.00, 51.27, 54.65 -CTUN, 814, 1.31, 4.70, 0.000000, 0, 0, 0, 814, 0 -DU32, 7, 166140 -CURR, 814, 2278070, 974, 2157, 5051, 1713.787000 -ATT, 0.00, -0.46, -4.76, -1.55, 0.00, 50.95, 54.65 -CTUN, 833, 1.31, 4.76, 0.000000, 0, 0, -5, 828, 0 -ATT, 0.00, -0.75, -4.76, -1.51, 0.00, 50.95, 54.65 -CTUN, 836, 1.31, 4.78, 0.000000, 0, 0, -6, 836, 0 -ATT, 0.00, -0.89, -4.76, -1.85, 0.00, 51.19, 54.65 -CTUN, 838, 1.33, 4.72, 0.000000, 0, 0, -5, 836, 0 -ATT, 0.00, -0.50, -4.85, -1.97, 0.00, 51.49, 54.65 -CTUN, 840, 1.32, 4.80, 0.000000, 0, 0, -3, 840, 0 -ATT, 0.00, 0.31, -4.85, -1.61, 0.00, 51.78, 54.65 -CTUN, 843, 1.32, 4.64, 0.000000, 0, 0, -3, 843, 0 -ATT, 0.00, 1.31, -4.76, -0.81, 0.00, 51.90, 54.65 -CTUN, 852, 1.30, 4.68, 0.000000, 0, 0, 0, 852, 0 -ATT, 0.00, 1.34, -4.76, -0.12, 0.00, 52.04, 54.65 -CTUN, 853, 1.30, 4.69, 0.000000, 0, 0, 3, 853, 0 -ATT, 0.00, 0.70, -4.85, -0.18, 0.00, 52.15, 54.65 -CTUN, 853, 1.07, 4.68, 0.000000, 0, 0, 4, 853, 0 -ATT, 0.00, 0.39, -4.85, -0.41, 0.00, 52.24, 54.65 -CTUN, 848, 1.07, 4.66, 0.000000, 0, 0, 11, 848, 0 -ATT, 0.00, 1.09, -4.85, 0.06, 0.00, 52.31, 54.65 -CTUN, 840, 1.02, 4.71, 0.000000, 0, 0, 16, 840, 0 -DU32, 7, 166140 -CURR, 839, 2286493, 967, 2350, 5028, 1720.267300 -ATT, 0.00, 1.79, -4.85, 0.70, 0.00, 52.44, 54.65 -CTUN, 836, 1.03, 4.78, 0.000000, 0, 0, 17, 836, 0 -ATT, 0.00, 1.77, -4.85, 0.84, 0.00, 52.58, 54.65 -CTUN, 816, 1.03, 4.69, 0.000000, 0, 0, 17, 817, 0 -ATT, 0.00, 1.46, -4.85, 0.63, 0.00, 52.68, 54.65 -CTUN, 812, 1.04, 4.71, 0.000000, 0, 0, 18, 812, 0 -ATT, 0.00, 1.22, -4.85, 0.13, 0.00, 52.63, 54.65 -CTUN, 804, 1.04, 4.77, 0.000000, 0, 0, 14, 805, 0 -ATT, 0.00, 0.88, -5.04, -0.14, 0.00, 52.43, 54.65 -CTUN, 805, 1.07, 4.80, 0.000000, 0, 0, 11, 805, 0 -ATT, 0.00, 0.75, -5.60, -0.28, 0.00, 52.31, 54.65 -CTUN, 805, 1.06, 4.78, 0.000000, 0, 0, 7, 805, 0 -ATT, 0.00, 0.14, -5.69, -0.88, 0.00, 52.50, 54.65 -CTUN, 805, 1.07, 4.81, 0.000000, 0, 0, 10, 805, 0 -ATT, 0.00, -0.53, -6.06, -1.79, 0.00, 52.98, 54.65 -CTUN, 806, 1.06, 4.84, 0.000000, 0, 0, 7, 806, 0 -ATT, -0.94, -1.05, -6.53, -2.44, 0.00, 53.68, 54.65 -CTUN, 809, 1.06, 4.88, 0.000000, 0, 0, 6, 808, 0 -ATT, -2.65, -1.74, -6.53, -2.48, 0.00, 54.28, 54.65 -CTUN, 809, 0.92, 4.79, 0.000000, 0, 1, 4, 810, 0 -DU32, 7, 166140 -CURR, 809, 2294604, 971, 2175, 5028, 1726.323500 -ATT, -3.88, -2.86, -6.16, -2.53, 0.00, 54.74, 54.65 -CTUN, 807, 1.06, 4.83, 0.000000, 0, 2, 4, 810, 0 -ATT, -3.88, -4.39, -5.88, -2.64, 0.00, 55.01, 54.65 -CTUN, 806, 0.92, 4.95, 0.000000, 0, 3, 7, 809, 0 -ATT, -3.69, -5.19, -5.69, -2.34, 0.00, 55.10, 54.65 -CTUN, 806, 0.92, 4.88, 0.000000, 0, 3, 6, 809, 0 -ATT, -1.42, -5.46, -5.88, -2.08, 0.00, 55.12, 54.65 -CTUN, 806, 0.90, 4.98, 0.000000, 0, 3, 5, 810, 0 -ATT, 0.00, -5.12, -5.60, -2.16, 0.00, 55.02, 54.65 -CTUN, 807, 0.91, 5.02, 0.000000, 0, 2, 5, 809, 0 -ATT, 0.00, -3.94, -5.69, -2.47, -0.09, 54.84, 54.64 -CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 4, 808, 0 -ATT, 0.00, -3.02, -5.69, -2.84, -3.01, 54.67, 53.92 -CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 8, 808, 0 -ATT, 0.00, -3.12, -5.50, -2.96, -4.33, 54.23, 52.23 -CTUN, 806, 0.91, 4.86, 0.000000, 0, 1, 5, 808, 0 -ATT, 0.00, -2.82, -5.32, -2.60, -6.98, 53.41, 49.69 -CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 5, 808, 0 -ATT, 0.00, -1.97, -4.85, -2.00, -8.11, 52.14, 46.09 -CTUN, 807, 0.91, 4.96, 0.000000, 0, 0, 2, 806, 0 -DU32, 7, 166140 -CURR, 806, 2302687, 977, 2121, 5051, 1732.369000 -ATT, 0.00, -1.76, -4.85, -1.57, -8.01, 50.23, 42.42 -CTUN, 806, 0.94, 4.94, 0.000000, 0, 0, 2, 807, 0 -ATT, 0.00, -2.96, -4.76, -1.45, -7.92, 47.87, 38.76 -CTUN, 805, 0.94, 4.94, 0.000000, 0, 1, 1, 806, 0 -ATT, 0.00, -2.91, -4.20, -1.52, -6.79, 45.18, 35.29 -CTUN, 796, 1.00, 5.07, 0.000000, 0, 0, 0, 798, 0 -ATT, 0.00, -1.42, -3.08, -1.81, -5.94, 42.39, 32.44 -CTUN, 796, 0.99, 5.17, 0.000000, 0, 0, 0, 796, 0 -ATT, 0.00, -0.26, -2.70, -2.09, -5.94, 39.64, 29.73 -CTUN, 796, 0.99, 5.05, 0.000000, 0, 0, -1, 796, 0 -ATT, 0.00, 0.30, -2.70, -2.13, -5.47, 37.08, 27.13 -CTUN, 796, 0.96, 5.05, 0.000000, 0, 0, -2, 796, 0 -ATT, 0.00, 0.61, -2.70, -1.52, -3.39, 34.65, 25.06 -CTUN, 796, 0.99, 5.12, 0.000000, 0, 0, -5, 797, 0 -ATT, 0.00, 0.90, -2.89, -0.70, 0.00, 32.46, 24.31 -CTUN, 796, 0.99, 5.09, 0.000000, 0, 0, -6, 796, 0 -ATT, 0.00, 1.31, -2.70, 0.27, 0.00, 30.93, 24.31 -CTUN, 796, 1.23, 5.06, 0.000000, 0, 0, -7, 796, 0 -ATT, 0.00, 1.65, -2.52, 0.99, 0.00, 29.89, 24.31 -CTUN, 805, 1.22, 5.12, 0.000000, 0, 0, -12, 800, 0 -DU32, 7, 166140 -CURR, 805, 2310678, 969, 2076, 5051, 1738.325100 -ATT, 0.00, 1.33, -2.52, 1.19, 0.00, 29.09, 24.31 -CTUN, 824, 1.22, 5.07, 0.000000, 0, 0, -12, 824, 0 -ATT, 0.00, 0.51, -2.52, 1.13, 0.00, 28.71, 24.31 -CTUN, 846, 1.20, 5.09, 0.000000, 0, 0, -14, 843, 0 -ATT, 0.00, 0.39, -2.52, 0.77, 0.00, 28.83, 24.31 -CTUN, 853, 1.20, 4.98, 0.000000, 0, 0, -10, 850, 0 -ATT, 0.00, 1.05, -2.42, 0.64, 0.00, 29.31, 24.31 -CTUN, 855, 1.18, 5.05, 0.000000, 0, 0, -11, 854, 0 -ATT, 0.00, 1.54, -2.42, 0.70, 0.00, 29.88, 24.31 -CTUN, 857, 1.18, 4.99, 0.000000, 0, 0, -15, 857, 0 -ATT, 0.00, 1.76, -2.52, 0.45, 0.00, 30.30, 24.31 -CTUN, 857, 1.13, 4.95, 0.000000, 0, 0, -16, 857, 0 -ATT, 0.00, 2.24, -2.52, 0.34, 0.00, 30.62, 24.31 -CTUN, 857, 1.13, 4.94, 0.000000, 0, 0, -18, 857, 0 -ATT, 0.00, 2.39, -2.52, 0.68, 0.00, 30.78, 24.31 -CTUN, 867, 1.09, 5.01, 0.000000, 0, 0, -20, 861, 0 -ATT, 0.00, 2.11, -2.33, 1.11, 0.00, 30.58, 24.31 -CTUN, 871, 1.09, 4.89, 0.000000, 0, 0, -23, 871, 0 -ATT, 0.00, 1.81, -2.42, 1.47, 0.00, 29.98, 24.31 -CTUN, 877, 1.03, 5.00, 0.000000, 0, 0, -24, 877, 0 -DU32, 7, 166140 -CURR, 879, 2319217, 968, 2271, 5051, 1744.419400 -ATT, 0.00, 1.65, -2.52, 1.72, 0.00, 29.01, 24.31 -CTUN, 887, 1.03, 4.91, 0.000000, 0, 0, -22, 884, 0 -ATT, -2.55, 1.09, -2.42, 2.04, 0.00, 27.97, 24.31 -CTUN, 898, 0.96, 4.92, 0.000000, 0, 0, -25, 897, 0 -ATT, -4.26, 0.13, -2.52, 1.66, 0.00, 27.11, 24.31 -CTUN, 903, 0.96, 4.95, 0.000000, 0, 0, -22, 903, 0 -ATT, -4.35, -1.44, -2.52, 1.68, 0.00, 26.46, 24.31 -CTUN, 905, 0.90, 4.85, 0.000000, 0, 0, -17, 906, 0 -ATT, -4.45, -2.25, -2.52, 1.55, 0.00, 26.00, 24.31 -CTUN, 905, 0.90, 4.89, 0.000000, 0, 0, -12, 907, 0 -ATT, -4.83, -2.05, -2.42, 1.40, 0.00, 25.81, 24.31 -CTUN, 904, 0.83, 4.90, 0.000000, 0, 0, -12, 904, 0 -ATT, -4.35, -1.94, -2.52, 0.96, 0.00, 26.08, 24.31 -CTUN, 906, 0.83, 4.71, 0.000000, 0, 0, -10, 905, 0 -ATT, -2.74, -2.56, -2.70, 0.17, 0.00, 26.68, 24.31 -CTUN, 907, 0.79, 4.59, 0.000000, 0, 1, -8, 907, 0 -ATT, -4.54, -2.52, -2.70, -0.69, 0.00, 27.54, 24.31 -CTUN, 884, 0.79, 4.71, 0.000000, 0, 0, -10, 889, 0 -ATT, -4.07, -1.40, -4.20, -1.25, 0.00, 28.50, 24.31 -CTUN, 859, 0.76, 4.63, 0.000000, 0, 0, -16, 864, 0 -DU32, 7, 166140 -CURR, 859, 2328195, 962, 2167, 5051, 1750.929700 -ATT, -4.16, -0.59, -4.10, -2.18, 0.00, 29.32, 24.31 -CTUN, 857, 0.76, 4.60, 0.000000, 0, 0, -19, 857, 0 -ATT, -4.16, -0.84, -4.10, -2.84, 0.00, 29.71, 24.31 -CTUN, 857, 0.70, 4.62, 0.000000, 0, 1, -23, 858, 0 -ATT, -4.26, -1.78, -4.20, -2.86, 0.00, 29.95, 24.31 -CTUN, 857, 0.70, 4.56, 0.000000, 0, 1, -28, 854, 0 -ATT, -4.16, -2.40, -4.10, -2.58, 0.00, 29.74, 24.31 -CTUN, 886, 0.64, 4.41, 0.000000, 0, 1, -31, 877, 0 -ATT, -4.26, -3.30, -4.10, -2.60, 0.00, 29.46, 24.31 -CTUN, 910, 0.64, 4.47, 0.000000, 0, 2, -32, 911, 0 -ATT, -4.16, -4.33, -4.10, -2.42, 0.00, 28.95, 24.31 -CTUN, 913, 0.59, 4.36, 0.000000, 0, 3, -33, 916, 0 -ATT, -3.97, -4.90, -3.82, -2.36, 0.00, 28.21, 24.31 -CTUN, 921, 0.59, 4.40, 0.000000, 0, 4, -36, 925, 0 -ATT, -3.69, -5.41, -3.73, -2.79, 0.00, 27.41, 24.31 -CTUN, 921, 0.51, 4.36, 0.000000, 0, 4, -32, 926, 0 -ATT, -1.23, -4.63, -4.76, -3.02, 0.00, 26.69, 24.31 -CTUN, 914, 0.51, 4.28, 0.000000, 0, 2, -30, 916, 0 -ATT, 0.00, -3.00, -5.78, -2.59, 0.00, 26.25, 24.31 -CTUN, 913, 0.47, 4.30, 0.000000, 0, 1, -28, 914, 0 -DU32, 7, 166140 -CURR, 913, 2337150, 968, 2271, 5028, 1757.361100 -ATT, 0.00, -0.69, -6.25, -2.38, 0.00, 26.07, 24.31 -CTUN, 912, 0.47, 4.11, 0.000000, 0, 0, -26, 913, 0 -ATT, 0.00, 0.73, -5.60, -3.00, 0.00, 26.11, 24.31 -CTUN, 914, 0.47, 4.14, 0.000000, 0, 1, -26, 914, 0 -ATT, 0.09, 1.00, -4.66, -3.86, 0.00, 26.35, 24.31 -CTUN, 913, 0.67, 4.19, 0.000000, 0, 1, -25, 914, 0 -ATT, 0.18, 0.82, -3.92, -3.77, 0.00, 26.66, 24.31 -CTUN, 913, 0.65, 3.97, 0.000000, 0, 1, -21, 914, 0 -ATT, 0.18, 0.52, -2.52, -2.75, 0.96, 26.86, 24.47 -CTUN, 913, 0.65, 3.99, 0.000000, 0, 0, -21, 913, 0 -ATT, 0.09, 0.42, -2.52, -1.09, 2.11, 26.98, 25.10 -CTUN, 913, 0.62, 4.03, 0.000000, 0, 0, -18, 913, 0 -ATT, 0.00, 0.16, -2.52, 0.58, 3.26, 27.12, 26.23 -CTUN, 915, 0.62, 3.95, 0.000000, 0, 0, -15, 915, 0 -ATT, 0.00, 0.09, -2.52, 1.94, 3.26, 27.16, 27.64 -CTUN, 920, 0.58, 4.31, 0.000000, 0, 0, -10, 919, 0 -ATT, 0.00, 0.34, -2.42, 2.53, 3.55, 27.08, 29.14 -CTUN, 923, 0.58, 4.13, 0.000000, 0, 0, -6, 923, 0 -ATT, 0.00, 0.34, -2.52, 2.00, 3.55, 27.19, 30.68 -CTUN, 923, 0.54, 3.99, 0.000000, 0, 0, 2, 923, 0 -DU32, 7, 166140 -CURR, 923, 2346308, 924, 2794, 5051, 1764.170200 -ATT, 0.00, -0.21, -3.73, 0.52, 3.55, 27.85, 32.22 -CTUN, 924, 0.54, 3.89, 0.000000, 0, 0, 12, 923, 0 -ATT, 0.00, 0.41, -4.10, -0.35, 3.55, 29.16, 33.75 -CTUN, 923, 0.53, 4.03, 0.000000, 0, 0, 23, 923, 0 -ATT, 0.00, 0.97, -4.38, -0.58, 3.55, 30.88, 35.32 -CTUN, 924, 0.54, 4.17, 0.000000, 0, 0, 28, 923, 0 -ATT, 0.09, 0.66, -4.29, -1.65, 3.75, 32.96, 36.88 -CTUN, 908, 0.54, 4.28, 0.000000, 0, 0, 37, 915, 0 -ATT, 0.28, 0.09, -4.38, -2.43, 3.55, 35.31, 38.45 -CTUN, 877, 0.57, 4.17, 0.000000, 0, 0, 43, 892, 0 -ATT, 0.18, 0.01, -4.29, -2.60, 3.55, 37.83, 39.98 -CTUN, 856, 0.57, 4.24, 0.000000, 0, 0, 46, 856, 0 -ATT, 0.00, 0.26, -4.38, -2.27, 3.36, 40.41, 41.49 -CTUN, 838, 0.64, 4.13, 0.000000, 0, 0, 44, 838, 0 -ATT, 0.00, 0.08, -4.48, -2.39, 1.25, 43.15, 42.41 -CTUN, 806, 0.64, 4.25, 0.000000, 0, 0, 42, 809, 0 -ATT, 0.00, -0.77, -4.48, -3.06, 0.00, 45.61, 42.49 -CTUN, 788, 0.71, 4.21, 0.000000, 0, 1, 39, 789, 0 -ATT, 0.00, -1.62, -4.85, -3.41, 0.00, 47.57, 42.49 -CTUN, 770, 0.71, 4.20, 0.000000, 0, 1, 33, 782, 0 -DU32, 7, 166140 -CURR, 770, 2355015, 975, 2025, 5051, 1770.921400 -ATT, 0.00, -2.37, -6.53, -3.15, 0.00, 48.99, 42.49 -CTUN, 765, 0.80, 4.35, 0.000000, 0, 1, 20, 766, 0 -ATT, 0.00, -2.83, -6.25, -3.08, 0.00, 49.96, 42.49 -CTUN, 770, 0.80, 4.30, 0.000000, 0, 1, 11, 766, 0 -ATT, 0.28, -3.53, -5.22, -3.30, 0.00, 50.41, 42.49 -CTUN, 796, 0.85, 4.39, 0.000000, 0, 2, 0, 788, 0 -ATT, 1.78, -3.62, -4.66, -3.24, 0.00, 50.58, 42.49 -CTUN, 842, 0.85, 4.30, 0.000000, 0, 1, -6, 831, 0 -ATT, 2.34, -2.44, -4.29, -2.31, 0.00, 50.63, 42.49 -CTUN, 876, 0.85, 4.28, 0.000000, 0, 0, -10, 876, 0 -ATT, 3.09, -1.12, -2.89, -1.17, 0.00, 50.77, 42.49 -CTUN, 907, 0.84, 4.27, 0.000000, 0, 0, -18, 906, 0 -ATT, 5.53, 0.00, -2.52, -0.20, 0.00, 50.97, 42.49 -PM, 0, 0, 0, 0, 1000, 10480, 0, 0 -CTUN, 909, 0.84, 4.31, 0.000000, 0, 0, -24, 911, 0 -ATT, 6.28, 1.41, -2.52, 0.88, 0.00, 51.28, 42.49 -CTUN, 906, 0.78, 4.38, 0.000000, 0, 1, -26, 907, 0 -ATT, 6.28, 3.70, -2.42, 2.22, 0.00, 51.56, 42.49 -CTUN, 908, 0.78, 4.31, 0.000000, 0, 3, -37, 909, 0 -ATT, 6.37, 4.82, -2.42, 2.80, 0.00, 51.71, 42.49 -CTUN, 911, 0.75, 4.35, 0.000000, 0, 4, -46, 915, 0 -DU32, 7, 166140 -CURR, 913, 2363560, 970, 2097, 5051, 1776.639800 -ATT, 6.37, 5.60, -2.24, 2.52, 0.00, 51.54, 42.49 -CTUN, 931, 0.75, 4.18, 0.000000, 0, 4, -53, 932, 0 -ATT, 2.90, 6.16, -2.33, 1.71, 0.00, 51.13, 42.49 -CTUN, 965, 0.66, 4.15, 0.000000, 0, 5, -60, 951, 0 -ATT, 0.00, 5.97, -4.76, 1.02, 0.00, 50.64, 42.49 -CTUN, 996, 0.66, 4.11, 0.000000, 0, 3, -65, 993, 0 -ATT, 0.00, 3.71, -4.76, 0.24, 0.00, 50.23, 42.49 -CTUN, 1000, 0.54, 3.85, 0.000000, 0, 0, -67, 1000, 0 -ATT, 0.00, 1.47, -4.66, -0.55, 0.00, 49.84, 42.49 -CTUN, 1000, 0.54, 3.88, 0.000000, 0, 0, -68, 1000, 0 -ATT, -2.74, 0.49, -4.66, -0.77, 0.00, 49.31, 42.49 -CTUN, 1000, 0.40, 3.96, 0.000000, 0, 0, -65, 1000, 0 -ATT, -2.17, -0.63, -5.41, -1.13, 0.00, 48.73, 42.49 -CTUN, 1000, 0.40, 3.60, 0.000000, 0, 0, -63, 1000, 0 -ATT, -0.37, -2.53, -4.85, -2.66, 0.00, 48.30, 42.49 -CTUN, 1000, 0.27, 3.35, 0.000000, 0, 0, -52, 1000, 0 -ATT, -3.69, -2.80, -3.54, -3.22, 0.00, 47.89, 42.49 -CTUN, 1000, 0.27, 2.66, 0.000000, 0, 0, -36, 1000, 0 -ATT, -46.04, -2.04, -4.57, -1.99, 0.00, 47.39, 42.49 -CTUN, 999, 0.20, 1.38, 0.000000, 0, 0, -33, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2373425, 1011, 1357, 5028, 1782.612700 -ATT, 0.00, -9.12, -4.76, -1.94, 0.00, 46.81, 42.49 -CTUN, 1000, 0.27, 0.32, 0.000000, 0, 0, -7, 1000, 0 -ATT, 0.00, -0.42, -4.57, 4.98, 0.00, 43.05, 42.49 -CTUN, 999, 0.27, 0.23, 0.000000, 0, 0, -4, 1000, 0 -ATT, 0.00, 1.49, -4.57, 4.29, 0.00, 41.08, 42.49 -CTUN, 1000, 2.09, 0.13, 0.000000, 0, 0, 13, 1000, 0 -ATT, 0.00, -3.39, -4.85, -1.00, 0.00, 40.29, 42.49 -CTUN, 1000, 2.09, 1.64, 0.000000, 0, 0, 33, 1000, 0 -ATT, 0.00, -3.08, -4.57, -2.71, 0.00, 39.44, 42.49 -CTUN, 1000, 2.09, 2.82, 0.000000, 0, 0, 56, 1000, 0 -ATT, 0.00, -0.98, -4.57, -0.80, 0.00, 38.88, 42.49 -CTUN, 1000, 0.22, 3.37, 0.000000, 0, 0, 67, 1000, 0 -ATT, 0.00, 0.22, -4.76, 1.54, 0.00, 38.85, 42.49 -CTUN, 995, 0.23, 3.59, 0.000000, 0, 0, 69, 1000, 0 -ATT, 0.00, -0.54, -4.76, 1.86, 0.00, 39.27, 42.49 -CTUN, 926, 0.23, 3.83, 0.000000, 0, 0, 72, 926, 0 -ATT, 0.37, -2.67, -4.85, 0.39, 0.00, 39.98, 42.49 -CTUN, 860, 0.30, 3.91, 0.000000, 0, 1, 80, 868, 0 -ATT, 2.43, -3.52, -4.85, -1.25, 0.00, 40.94, 42.49 -CTUN, 836, 0.30, 4.08, 0.000000, 0, 1, 86, 843, 0 -DU32, 7, 166140 -CURR, 836, 2383098, 961, 2386, 5051, 1789.624400 -ATT, 3.37, -2.22, -6.06, -1.42, 0.00, 41.90, 42.49 -CTUN, 824, 0.47, 4.14, 0.000000, 0, 0, 87, 824, 0 -ATT, 3.84, -0.50, -6.06, -1.09, 1.05, 42.63, 42.74 -CTUN, 840, 0.47, 4.23, 0.000000, 0, 0, 84, 838, 0 -ATT, 6.00, 0.53, -6.06, -1.18, 3.65, 43.16, 44.06 -CTUN, 855, 0.66, 4.22, 0.000000, 0, 0, 80, 855, 0 -ATT, 6.56, 1.32, -5.88, -1.72, 5.76, 43.75, 46.27 -CTUN, 816, 0.66, 4.30, 0.000000, 0, 0, 78, 821, 0 -ATT, 6.46, 2.32, -5.78, -2.22, 9.90, 44.63, 50.01 -CTUN, 778, 0.82, 4.45, 0.000000, 0, 1, 75, 787, 0 -ATT, 6.37, 3.63, -5.88, -2.68, 12.30, 45.95, 55.10 -CTUN, 720, 0.82, 4.38, 0.000000, 0, 2, 66, 742, 0 -ATT, 6.28, 5.39, -6.25, -2.74, 12.40, 48.22, 58.22 -CTUN, 700, 0.98, 4.50, 0.000000, 0, 3, 54, 705, 0 -ATT, 3.65, 6.28, -6.25, -2.89, 12.21, 51.10, 61.10 -CTUN, 700, 0.98, 4.65, 0.000000, 0, 4, 34, 703, 0 -ATT, 0.00, 5.59, -5.69, -2.79, 10.48, 54.42, 64.42 -CTUN, 746, 1.10, 4.61, 0.000000, 0, 2, 17, 748, 0 -ATT, 0.00, 3.40, -4.57, -2.47, 5.19, 57.93, 67.66 -CTUN, 839, 1.10, 4.64, 0.000000, 0, 1, 0, 810, 0 -DU32, 7, 166140 -CURR, 839, 2390937, 978, 2001, 5028, 1795.249600 -ATT, 0.00, 1.40, -4.57, -2.12, 3.17, 61.19, 69.38 -CTUN, 913, 1.18, 4.63, 0.000000, 0, 0, -8, 906, 0 -ATT, 0.00, 0.88, -4.48, -1.70, 1.05, 64.00, 70.09 -CTUN, 954, 1.18, 4.65, 0.000000, 0, 0, -5, 943, 0 -ATT, 0.00, 1.05, -4.38, -1.16, 0.09, 66.32, 70.27 -CTUN, 994, 1.19, 4.61, 0.000000, 0, 0, -1, 990, 0 -ATT, 0.00, 0.58, -3.92, -0.75, 0.00, 68.12, 70.27 -CTUN, 1000, 1.19, 4.67, 0.000000, 0, 0, 1, 999, 0 -ATT, 0.00, -0.21, -3.73, -0.92, 0.00, 69.38, 70.27 -CTUN, 999, 1.19, 4.70, 0.000000, 0, 0, 11, 1000, 0 -ATT, 0.00, -0.58, -4.20, -1.21, 0.00, 70.15, 70.27 -CTUN, 980, 1.19, 4.59, 0.000000, 0, 0, 18, 993, 0 -ATT, 0.00, -0.51, -4.76, -1.26, 0.00, 70.47, 70.27 -CTUN, 908, 1.25, 4.75, 0.000000, 0, 0, 22, 909, 0 -ATT, 0.00, -0.51, -5.32, -1.40, 0.00, 70.53, 70.27 -CTUN, 870, 1.25, 4.85, 0.000000, 0, 0, 26, 883, 0 -ATT, 0.00, -0.77, -5.41, -1.91, 0.00, 70.29, 70.27 -CTUN, 795, 1.26, 4.84, 0.000000, 0, 0, 32, 805, 0 -ATT, 0.00, -1.07, -6.16, -2.85, 0.00, 69.87, 70.27 -CTUN, 782, 1.25, 4.87, 0.000000, 0, 1, 32, 788, 0 -DU32, 7, 166140 -CURR, 782, 2400140, 972, 1978, 5028, 1802.078000 -ATT, 0.00, -1.21, -6.25, -3.82, 0.00, 69.20, 70.27 -CTUN, 780, 1.26, 4.78, 0.000000, 0, 1, 25, 780, 0 -ATT, 0.00, -0.95, -6.25, -4.88, 0.00, 68.13, 70.27 -CTUN, 779, 1.26, 4.96, 0.000000, 0, 2, 18, 781, 0 -ATT, 0.00, -0.73, -6.06, -5.53, 0.00, 66.99, 70.27 -CTUN, 767, 1.38, 4.97, 0.000000, 0, 3, 11, 770, 0 -ATT, 0.00, -0.41, -5.69, -5.56, 0.00, 65.74, 70.27 -CTUN, 786, 1.38, 4.98, 0.000000, 0, 2, 3, 778, 0 -ATT, -0.37, -0.24, -4.66, -4.98, 0.00, 64.51, 70.27 -CTUN, 820, 1.42, 4.99, 0.000000, 0, 2, -8, 808, 0 -ATT, -2.84, -0.60, -3.08, -3.95, 0.00, 63.30, 70.27 -CTUN, 852, 1.38, 4.96, 0.000000, 0, 1, -12, 852, 0 -ATT, -3.12, -2.08, -3.08, -2.20, 0.00, 62.17, 70.27 -CTUN, 856, 1.38, 5.10, 0.000000, 0, 1, -10, 856, 0 -ATT, -6.06, -4.18, -3.08, -0.45, 0.00, 61.32, 70.27 -CTUN, 871, 0.93, 4.97, 0.000000, 0, 2, -8, 869, 0 -ATT, -6.06, -6.13, -2.89, 0.48, 0.00, 60.88, 70.27 -CTUN, 884, 0.93, 5.07, 0.000000, 0, 6, -4, 888, 0 -ATT, -5.96, -8.08, -2.80, 0.59, 0.00, 61.14, 70.27 -CTUN, 884, 0.86, 5.18, 0.000000, 0, 8, 2, 892, 0 -DU32, 7, 166140 -CURR, 884, 2408384, 948, 2584, 5051, 1808.237200 -ATT, -2.84, -8.29, -2.89, 0.92, 0.00, 61.94, 70.27 -CTUN, 882, 0.86, 5.29, 0.000000, 0, 7, 15, 890, 0 -ATT, 0.00, -7.11, -3.45, 1.90, 0.00, 62.96, 70.27 -CTUN, 854, 0.85, 5.28, 0.000000, 0, 4, 23, 861, 0 -ATT, 0.00, -4.27, -3.17, 2.29, 0.00, 64.36, 70.27 -CTUN, 816, 0.86, 5.10, 0.000000, 0, 1, 29, 822, 0 -ATT, 0.00, -1.86, -3.26, 1.86, 0.00, 65.55, 70.27 -CTUN, 772, 0.86, 5.26, 0.000000, 0, 0, 31, 780, 0 -ATT, 0.00, -0.97, -3.08, 1.14, 0.00, 66.35, 70.27 -CTUN, 740, 0.92, 5.13, 0.000000, 0, 0, 23, 742, 0 -ATT, 0.00, -0.66, -3.17, 0.24, 0.00, 66.72, 70.27 -CTUN, 736, 0.92, 5.18, 0.000000, 0, 0, 14, 735, 0 -ATT, 0.00, 0.29, -3.26, -1.13, 0.00, 66.92, 70.27 -CTUN, 736, 1.03, 5.21, 0.000000, 0, 0, 0, 736, 0 -ATT, 0.00, 1.66, -3.26, -2.61, 0.00, 67.10, 70.27 -CTUN, 741, 1.03, 5.11, 0.000000, 0, 1, -14, 737, 0 -ATT, 0.00, 2.22, -3.17, -3.65, 0.00, 67.45, 70.27 -CTUN, 789, 1.09, 5.17, 0.000000, 0, 1, -26, 781, 0 -ATT, 0.00, 1.65, -2.89, -4.13, 0.00, 67.86, 70.27 -CTUN, 855, 1.09, 5.19, 0.000000, 0, 2, -37, 843, 0 -DU32, 7, 166140 -CURR, 863, 2416311, 968, 2156, 5051, 1813.939600 -ATT, 0.00, 1.26, -2.98, -3.77, 0.00, 68.10, 70.27 -CTUN, 916, 1.49, 5.08, 0.000000, 0, 1, -36, 912, 0 -ATT, 0.00, 1.31, -2.80, -2.48, 0.00, 68.12, 70.27 -CTUN, 951, 1.44, 5.09, 0.000000, 0, 0, -30, 951, 0 -ATT, 0.00, 1.39, -2.70, -0.85, 0.00, 68.01, 70.27 -CTUN, 973, 1.44, 5.07, 0.000000, 0, 0, -17, 972, 0 -ATT, 0.00, 0.50, -2.70, 0.21, 0.00, 67.77, 70.27 -CTUN, 973, 1.26, 4.98, 0.000000, 0, 0, -9, 973, 0 -ATT, 0.00, -0.34, -2.70, 0.29, 0.00, 67.47, 70.27 -CTUN, 952, 1.26, 5.08, 0.000000, 0, 0, 1, 965, 0 -ATT, 0.00, -0.35, -2.61, -0.06, 0.00, 67.29, 70.27 -CTUN, 882, 1.26, 5.04, 0.000000, 0, 0, 17, 897, 0 -ATT, 0.00, 0.15, -2.70, -0.48, 0.00, 67.21, 70.27 -CTUN, 832, 1.26, 4.97, 0.000000, 0, 0, 28, 850, 0 -ATT, 0.00, 0.42, -2.89, -0.77, 0.00, 67.25, 70.27 -CTUN, 768, 1.26, 4.97, 0.000000, 0, 0, 32, 774, 0 -ATT, 0.00, 0.44, -3.08, -1.18, 0.00, 67.43, 70.27 -CTUN, 761, 1.28, 4.99, 0.000000, 0, 0, 27, 761, 0 -ATT, 0.00, 0.44, -3.17, -1.86, 0.00, 67.64, 70.27 -CTUN, 761, 1.28, 5.10, 0.000000, 0, 0, 16, 761, 0 -DU32, 7, 166140 -CURR, 761, 2425175, 985, 1826, 5051, 1820.760700 -ATT, 0.00, 0.36, -3.26, -2.40, 0.00, 67.83, 70.27 -CTUN, 761, 1.49, 5.14, 0.000000, 0, 0, 8, 761, 0 -ATT, 0.00, 0.27, -3.26, -2.75, 0.00, 67.85, 70.27 -CTUN, 766, 1.49, 5.06, 0.000000, 0, 0, -3, 765, 0 -ATT, 0.00, 0.59, -3.17, -2.92, 0.00, 67.71, 70.27 -CTUN, 801, 1.52, 4.97, 0.000000, 0, 0, -11, 798, 0 -ATT, 0.00, 0.87, -3.17, -2.76, 0.00, 67.49, 70.27 -CTUN, 832, 1.52, 5.06, 0.000000, 0, 0, -17, 825, 0 -ATT, 0.00, 0.89, -3.26, -2.35, 0.00, 67.27, 70.27 -CTUN, 838, 1.52, 5.02, 0.000000, 0, 0, -21, 838, 0 -ATT, 0.00, 0.62, -3.26, -1.88, 0.00, 67.06, 70.27 -CTUN, 838, 1.52, 5.08, 0.000000, 0, 0, -20, 838, 0 -ATT, 0.00, -0.24, -3.08, -1.58, 0.00, 67.05, 70.27 -CTUN, 838, 1.52, 5.03, 0.000000, 0, 0, -21, 838, 0 -ATT, 0.00, -1.23, -3.08, -1.47, 0.00, 67.27, 70.27 -CTUN, 835, 1.47, 5.14, 0.000000, 0, 0, -17, 836, 0 -ATT, 0.00, -1.80, -3.08, -1.58, 0.00, 67.57, 70.27 -CTUN, 836, 1.47, 5.08, 0.000000, 0, 0, -16, 836, 0 -ATT, 0.00, -1.85, -3.08, -1.90, 0.00, 68.07, 70.27 -CTUN, 836, 1.45, 4.97, 0.000000, 0, 0, -18, 836, 0 -DU32, 7, 166140 -CURR, 835, 2433332, 963, 2262, 5051, 1826.762800 -ATT, 0.00, -1.53, -2.89, -2.06, 0.00, 68.68, 70.27 -CTUN, 836, 1.45, 5.04, 0.000000, 0, 0, -13, 836, 0 -ATT, 0.00, -1.08, -2.70, -1.96, 0.00, 69.47, 70.27 -CTUN, 836, 1.15, 5.04, 0.000000, 0, 0, -14, 836, 0 -ATT, 0.00, -0.78, -2.89, -1.75, 0.00, 70.46, 70.27 -CTUN, 836, 1.27, 5.08, 0.000000, 0, 0, -13, 836, 0 -ATT, 0.00, -0.66, -3.08, -1.48, 0.00, 71.51, 70.27 -CTUN, 836, 1.16, 5.04, 0.000000, 0, 0, -12, 836, 0 -ATT, 0.00, -0.65, -2.89, -1.38, 0.00, 72.67, 70.27 -CTUN, 836, 1.23, 5.08, 0.000000, 0, 0, -9, 836, 0 -ATT, 0.00, -0.76, -2.70, -1.43, 0.00, 73.83, 70.27 -CTUN, 836, 1.18, 4.93, 0.000000, 0, 0, -9, 836, 0 -ATT, 0.00, -0.83, -2.80, -1.44, 0.00, 74.97, 70.27 -CTUN, 836, 1.23, 5.14, 0.000000, 0, 0, -5, 836, 0 -ATT, 0.00, -0.83, -2.80, -1.13, 0.00, 76.12, 70.27 -CTUN, 836, 1.19, 5.08, 0.000000, 0, 0, -3, 836, 0 -ATT, 0.00, -0.37, -2.70, -0.69, 0.00, 77.28, 70.27 -CTUN, 836, 1.23, 4.95, 0.000000, 0, 0, -2, 836, 0 -ATT, 0.00, 0.18, -2.61, -0.02, 0.00, 78.39, 70.27 -CTUN, 836, 1.23, 5.05, 0.000000, 0, 0, -5, 835, 0 -DU32, 7, 166140 -CURR, 836, 2441690, 963, 2070, 5028, 1833.006700 -ATT, 0.00, 0.62, -2.70, 0.49, 0.00, 79.39, 70.27 -CTUN, 836, 1.35, 5.13, 0.000000, 0, 0, -8, 835, 0 -ATT, 0.00, 0.95, -2.70, 0.73, 0.00, 80.15, 70.27 -CTUN, 836, 1.35, 5.06, 0.000000, 0, 0, -14, 835, 0 -ATT, 0.00, 1.08, -2.80, 0.46, 0.00, 80.70, 70.70 -CTUN, 836, 1.37, 5.18, 0.000000, 0, 0, -19, 835, 0 -ATT, 0.00, 0.84, -2.61, -0.16, 0.00, 81.12, 71.12 -CTUN, 835, 1.35, 5.17, 0.000000, 0, 0, -23, 836, 0 -ATT, 0.00, 0.68, -2.52, -1.01, 0.00, 81.40, 71.40 -CTUN, 857, 1.35, 5.12, 0.000000, 0, 0, -25, 855, 0 -ATT, 0.00, 0.66, -2.61, -1.57, -3.58, 81.49, 71.49 -CTUN, 882, 1.34, 5.13, 0.000000, 0, 0, -28, 876, 0 -ATT, 0.00, 0.71, -2.70, -2.02, -4.90, 81.00, 71.00 -PM, 0, 0, 0, 0, 1000, 10492, 0, 0 -CTUN, 904, 1.34, 5.09, 0.000000, 0, 0, -35, 904, 0 -ATT, 0.00, 0.58, -2.70, -2.49, -8.11, 79.73, 69.73 -CTUN, 906, 1.31, 5.01, 0.000000, 0, 0, -38, 906, 0 -ATT, 0.00, 0.33, -2.61, -2.59, -8.49, 77.53, 67.53 -CTUN, 906, 1.31, 5.06, 0.000000, 0, 0, -46, 906, 0 -ATT, 0.00, -0.17, -2.70, -2.27, -8.67, 74.59, 64.59 -CTUN, 909, 1.25, 5.07, 0.000000, 0, 0, -51, 909, 0 -DU32, 7, 166140 -CURR, 909, 2450372, 970, 2157, 5051, 1838.877900 -ATT, -0.56, -0.96, -2.61, -1.96, -9.62, 70.92, 60.92 -CTUN, 911, 1.25, 5.04, 0.000000, 0, 0, -52, 911, 0 -ATT, -4.73, -1.70, -2.70, -1.62, -10.66, 66.36, 56.36 -CTUN, 911, 1.17, 4.87, 0.000000, 0, 0, -57, 911, 0 -ATT, -5.49, -2.71, -2.70, -1.37, -10.75, 61.58, 51.62 -CTUN, 925, 1.17, 4.85, 0.000000, 0, 1, -60, 920, 0 -ATT, -2.74, -4.92, -2.70, -1.59, -9.81, 56.58, 46.83 -CTUN, 957, 1.06, 4.85, 0.000000, 0, 4, -59, 952, 0 -ATT, -1.61, -5.63, -1.58, -2.00, -7.73, 51.37, 42.91 -CTUN, 983, 1.06, 4.62, 0.000000, 0, 3, -56, 986, 0 -ATT, 0.00, -4.37, -2.80, -1.67, -4.05, 46.19, 40.59 -CTUN, 1000, 0.95, 4.66, 0.000000, 0, 1, -52, 1000, 0 -ATT, 0.00, -2.98, -2.80, -0.86, -0.94, 41.30, 39.50 -CTUN, 1000, 0.95, 4.68, 0.000000, 0, 0, -44, 1000, 0 -ATT, 0.00, -1.97, -3.08, -0.22, 0.00, 37.09, 39.41 -CTUN, 999, 0.83, 4.62, 0.000000, 0, 0, -31, 1000, 0 -ATT, 0.00, -1.52, -3.08, -0.47, 0.00, 33.84, 39.41 -CTUN, 980, 0.83, 4.42, 0.000000, 0, 0, -19, 980, 0 -ATT, 0.00, -1.23, -4.01, -1.21, 0.00, 31.64, 39.41 -CTUN, 946, 0.76, 4.45, 0.000000, 0, 0, -1, 952, 0 -DU32, 7, 166140 -CURR, 946, 2459980, 939, 2700, 5051, 1845.866100 -ATT, 0.00, -0.84, -4.29, -1.82, 0.00, 30.33, 39.41 -CTUN, 900, 0.76, 4.41, 0.000000, 0, 0, 8, 909, 0 -ATT, 0.00, -0.34, -4.57, -2.07, 0.00, 30.03, 39.41 -CTUN, 857, 0.72, 4.40, 0.000000, 0, 0, 17, 864, 0 -ATT, 0.00, -0.05, -4.48, -1.71, 0.00, 30.45, 39.41 -CTUN, 830, 0.72, 4.35, 0.000000, 0, 0, 20, 838, 0 -ATT, 0.00, 0.28, -2.70, -1.07, 0.00, 31.21, 39.41 -CTUN, 817, 0.72, 4.40, 0.000000, 0, 0, 21, 819, 0 -ATT, 0.00, -0.07, -2.70, -0.48, 0.00, 32.19, 39.41 -CTUN, 807, 0.74, 4.38, 0.000000, 0, 0, 16, 813, 0 -ATT, 0.00, -0.06, -2.52, 0.13, 0.00, 33.32, 39.41 -CTUN, 805, 0.74, 4.44, 0.000000, 0, 0, 12, 805, 0 -ATT, 0.00, 0.11, -2.70, 0.89, 0.00, 34.57, 39.41 -CTUN, 805, 0.77, 4.45, 0.000000, 0, 0, 3, 805, 0 -ATT, 0.18, 0.11, -2.61, 0.91, 0.00, 35.97, 39.41 -CTUN, 830, 0.77, 4.43, 0.000000, 0, 0, -5, 830, 0 -ATT, 0.28, 0.09, -2.42, -0.01, 0.00, 37.33, 39.41 -CTUN, 870, 0.77, 4.52, 0.000000, 0, 0, -6, 859, 0 -ATT, 0.46, 1.03, -2.52, -0.89, 0.00, 38.49, 39.41 -CTUN, 888, 0.77, 4.53, 0.000000, 0, 0, -4, 888, 0 -DU32, 7, 166140 -CURR, 888, 2468422, 949, 2516, 5051, 1852.241200 -ATT, 1.96, 3.26, -2.42, -1.86, 0.00, 39.45, 39.41 -CTUN, 889, 0.77, 4.36, 0.000000, 0, 2, -1, 891, 0 -ATT, 2.53, 4.67, -2.52, -2.35, 0.00, 40.22, 39.41 -CTUN, 889, 0.77, 4.36, 0.000000, 0, 3, 4, 891, 0 -ATT, 3.18, 5.17, -2.52, -2.36, 0.00, 40.76, 39.41 -CTUN, 889, 0.77, 4.45, 0.000000, 0, 4, 4, 892, 0 -ATT, 3.18, 6.08, -2.52, -1.95, 0.00, 41.12, 39.41 -CTUN, 884, 0.76, 4.55, 0.000000, 0, 4, 6, 890, 0 -ATT, 0.46, 6.32, -2.42, -1.05, 0.00, 41.25, 39.41 -CTUN, 870, 0.76, 4.48, 0.000000, 0, 4, 7, 874, 0 -ATT, 0.00, 5.30, -2.61, -0.47, 0.00, 41.20, 39.41 -CTUN, 841, 0.76, 4.42, 0.000000, 0, 1, 7, 848, 0 -ATT, 0.00, 2.73, -3.08, -0.36, 0.00, 41.07, 39.41 -CTUN, 825, 0.76, 4.50, 0.000000, 0, 0, 9, 825, 0 -ATT, -0.09, 0.51, -3.54, -0.34, 0.00, 40.90, 39.41 -CTUN, 822, 0.76, 4.40, 0.000000, 0, 0, 9, 821, 0 -ATT, -0.18, -0.46, -3.54, -0.53, 0.00, 40.85, 39.41 -CTUN, 823, 0.79, 4.45, 0.000000, 0, 0, 11, 821, 0 -ATT, -0.75, -0.37, -3.26, -0.92, 0.00, 40.94, 39.41 -CTUN, 825, 0.79, 4.48, 0.000000, 0, 0, 8, 825, 0 -DU32, 7, 166140 -CURR, 825, 2477016, 963, 2219, 5028, 1858.748200 -ATT, -2.46, 0.26, -2.42, -0.88, 0.00, 41.19, 39.41 -CTUN, 823, 0.81, 4.54, 0.000000, 0, 0, 6, 826, 0 -ATT, -2.84, -0.19, -2.80, -0.36, 0.00, 41.59, 39.41 -CTUN, 823, 0.81, 4.57, 0.000000, 0, 0, 5, 823, 0 -ATT, -3.03, -1.04, -2.98, -0.05, 0.00, 42.13, 39.41 -CTUN, 823, 0.82, 4.62, 0.000000, 0, 0, 3, 823, 0 -ATT, -2.84, -1.22, -2.80, -0.32, 0.00, 42.74, 39.41 -CTUN, 824, 0.82, 4.46, 0.000000, 0, 0, 2, 824, 0 -ATT, -2.93, -1.52, -2.89, -0.51, 0.00, 43.51, 39.41 -CTUN, 825, 0.83, 4.52, 0.000000, 0, 0, 4, 826, 0 -ATT, -2.93, -2.23, -2.89, -0.58, 0.00, 44.53, 39.41 -CTUN, 828, 0.82, 4.46, 0.000000, 0, 0, 3, 828, 0 -ATT, -3.31, -3.23, -3.26, -0.68, 0.00, 45.77, 39.41 -CTUN, 826, 0.82, 4.39, 0.000000, 0, 1, 0, 827, 0 -ATT, -2.36, -3.90, -2.24, -0.75, 0.00, 47.29, 39.41 -CTUN, 826, 0.82, 4.51, 0.000000, 0, 1, -4, 827, 0 -ATT, -1.32, -3.94, -3.17, -0.83, 0.00, 48.96, 39.41 -CTUN, 826, 0.82, 4.46, 0.000000, 0, 1, -8, 827, 0 -ATT, -0.94, -2.80, -3.17, -0.72, 0.00, 50.60, 40.60 -CTUN, 828, 0.81, 4.36, 0.000000, 0, 0, -18, 826, 0 -DU32, 7, 166140 -CURR, 828, 2485270, 977, 1909, 5028, 1864.784100 -ATT, 0.00, -1.40, -3.26, -0.57, 0.00, 52.13, 42.13 -CTUN, 830, 0.81, 4.47, 0.000000, 0, 0, -29, 828, 0 -ATT, 0.00, -0.65, -3.08, -0.70, 0.00, 53.47, 43.47 -CTUN, 836, 0.77, 4.39, 0.000000, 0, 0, -38, 836, 0 -ATT, 0.00, -0.25, -2.98, -0.76, 0.00, 54.74, 44.74 -CTUN, 852, 0.77, 4.39, 0.000000, 0, 0, -46, 853, 0 -ATT, 0.00, -0.12, -2.80, -0.55, 0.00, 56.01, 46.01 -CTUN, 908, 0.70, 4.43, 0.000000, 0, 0, -52, 907, 0 -ATT, 0.00, -0.29, -2.80, -0.10, 0.00, 57.23, 47.23 -CTUN, 932, 0.70, 4.33, 0.000000, 0, 0, -58, 923, 0 -ATT, 0.00, 0.03, -2.70, 0.61, 0.00, 58.40, 48.40 -CTUN, 973, 0.60, 4.33, 0.000000, 0, 0, -67, 959, 0 -ATT, 0.00, 0.55, -2.61, 1.10, 0.00, 59.39, 49.39 -CTUN, 1000, 0.60, 4.18, 0.000000, 0, 0, -73, 1000, 0 -ATT, 0.00, 0.75, -2.70, 1.28, 0.00, 60.15, 50.15 -CTUN, 1000, 0.46, 4.00, 0.000000, 0, 0, -80, 999, 0 -ATT, 0.00, -0.03, -2.89, 1.05, 0.00, 60.76, 50.76 -CTUN, 999, 0.46, 4.13, 0.000000, 0, 0, -85, 999, 0 -ATT, 0.00, -1.12, -2.89, 0.40, 0.00, 61.05, 51.05 -CTUN, 1000, 0.31, 3.83, 0.000000, 0, 0, -81, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2494526, 968, 2202, 5051, 1870.459400 -ATT, 0.00, -1.33, -2.89, -0.08, 0.00, 61.10, 51.10 -CTUN, 1000, 0.31, 2.20, 0.000000, 0, 0, -68, 1000, 0 -ATT, 0.00, -2.19, -2.70, -0.21, 0.00, 60.89, 51.10 -CTUN, 1000, 0.21, -0.33, 0.000000, 0, 0, -45, 1000, 0 -ATT, 0.00, -1.45, -2.70, 0.14, 0.00, 60.32, 51.10 -CTUN, 1000, 0.21, -1.88, 0.000000, 0, 0, 21, 1000, 0 -ATT, 0.00, -0.72, -2.80, 0.42, 0.00, 60.53, 51.10 -CTUN, 1000, 0.21, -0.60, 0.000000, 0, 0, 37, 1000, 0 -ATT, 0.00, -2.10, -2.89, 0.79, 0.00, 60.35, 51.10 -CTUN, 1000, 0.21, 1.17, 0.000000, 0, 0, 41, 1000, 0 -ATT, 0.00, -3.53, -3.17, 2.02, 0.00, 59.61, 51.10 -CTUN, 993, 0.20, 3.41, 0.000000, 0, 0, 46, 1000, 0 -ATT, 0.00, -2.38, -4.66, 2.60, 0.00, 58.83, 51.10 -CTUN, 911, 0.20, 3.96, 0.000000, 0, 1, 46, 921, 0 -ATT, 0.00, -1.15, -6.72, 2.16, 0.00, 58.08, 51.10 -CTUN, 871, 0.20, 3.94, 0.000000, 0, 0, 40, 873, 0 -ATT, 0.00, -0.66, -8.96, 0.18, 0.00, 57.54, 51.10 -CTUN, 857, 0.23, 4.06, 0.000000, 0, 0, 42, 857, 0 -ATT, 0.00, -0.06, -10.64, -2.83, 0.00, 57.02, 51.10 -CTUN, 857, 0.23, 3.97, 0.000000, 0, 1, 41, 858, 0 -DU32, 7, 166140 -CURR, 857, 2504073, 947, 2292, 5028, 1876.595700 -ATT, 0.00, 0.68, -10.82, -4.79, 0.00, 56.54, 51.10 -CTUN, 859, 0.32, 3.99, 0.000000, 0, 3, 37, 862, 0 -ATT, 0.00, 0.71, -11.10, -5.49, 0.00, 56.12, 51.10 -CTUN, 872, 0.32, 4.14, 0.000000, 0, 3, 34, 872, 0 -ATT, 1.03, 0.41, -10.92, -5.99, 0.00, 55.75, 51.10 -CTUN, 902, 0.41, 4.00, 0.000000, 0, 4, 37, 898, 0 -ATT, 1.12, 1.02, -10.82, -6.18, 0.00, 55.76, 51.10 -CTUN, 904, 0.41, 4.16, 0.000000, 0, 4, 36, 908, 0 -ATT, 1.03, 0.96, -10.92, -6.08, 0.00, 56.09, 51.10 -CTUN, 870, 0.48, 4.33, 0.000000, 0, 4, 30, 880, 0 -ATT, 0.84, 0.35, -11.76, -6.12, 0.00, 56.76, 51.10 -CTUN, 864, 0.48, 4.48, 0.000000, 0, 4, 24, 868, 0 -ATT, 0.84, 0.18, -11.76, -6.47, 0.00, 57.51, 51.10 -CTUN, 867, 0.54, 4.50, 0.000000, 0, 4, 16, 869, 0 -ATT, 0.28, 0.07, -10.92, -6.73, 0.00, 58.31, 51.10 -CTUN, 903, 0.54, 4.38, 0.000000, 0, 5, 13, 894, 0 -ATT, 0.00, 0.03, -7.18, -6.46, 0.00, 58.90, 51.10 -CTUN, 923, 0.59, 4.39, 0.000000, 0, 4, 4, 923, 0 -ATT, 0.00, 0.49, -4.85, -5.36, 0.00, 59.32, 51.10 -CTUN, 951, 0.59, 4.43, 0.000000, 0, 2, 2, 950, 0 -DU32, 7, 166140 -CURR, 951, 2512975, 969, 2074, 5051, 1882.644900 -ATT, 0.00, 0.87, -2.52, -3.26, 0.00, 59.49, 51.10 -CTUN, 971, 0.60, 4.39, 0.000000, 0, 0, -4, 961, 0 -ATT, 0.00, 0.82, -2.61, -1.06, 0.00, 59.59, 51.10 -CTUN, 979, 0.59, 4.32, 0.000000, 0, 0, -13, 979, 0 -ATT, 0.00, 0.94, -2.52, 1.00, 0.00, 59.59, 51.10 -CTUN, 982, 0.59, 4.42, 0.000000, 0, 0, -22, 981, 0 -ATT, 0.00, 1.22, -2.61, 2.09, 0.00, 59.54, 51.10 -CTUN, 993, 0.57, 4.34, 0.000000, 0, 1, -29, 992, 0 -ATT, 0.00, 1.93, -2.70, 2.58, 0.00, 59.35, 51.10 -CTUN, 1000, 0.57, 4.31, 0.000000, 0, 0, -38, 1000, 0 -ATT, 0.00, 2.21, -2.52, 2.84, 0.00, 59.28, 51.10 -CTUN, 1000, 0.50, 4.29, 0.000000, 0, 0, -47, 1000, 0 -ATT, 0.00, 2.64, -2.52, 2.61, 0.00, 59.16, 51.10 -CTUN, 1000, 0.50, 4.25, 0.000000, 0, 0, -51, 1000, 0 -ATT, 0.00, 2.48, -2.52, 2.22, 0.00, 58.90, 51.10 -CTUN, 1000, 0.41, 4.22, 0.000000, 0, 0, -56, 1000, 0 -ATT, 0.00, 1.67, -4.29, 1.92, 0.00, 58.58, 51.10 -CTUN, 1000, 0.41, 4.10, 0.000000, 0, 0, -57, 1000, 0 -ATT, 0.00, 0.01, -6.53, 0.76, 0.00, 58.42, 51.10 -CTUN, 1000, 0.29, 3.69, 0.000000, 0, 0, -49, 999, 0 -DU32, 7, 166140 -CURR, 1000, 2522879, 961, 2298, 5051, 1888.454200 -ATT, 0.00, -1.19, -7.84, -0.84, 0.00, 58.15, 51.10 -CTUN, 1000, 0.29, 2.75, 0.000000, 0, 0, -41, 1000, 0 -ATT, 0.00, -1.19, -8.30, -2.29, 0.00, 57.80, 51.10 -CTUN, 1000, 0.20, 0.98, 0.000000, 0, 0, -26, 1000, 0 -ATT, 0.00, -0.05, -8.21, -2.44, 0.00, 57.15, 51.10 -CTUN, 999, 0.21, 0.03, 0.000000, 0, 0, -10, 1000, 0 -ATT, 0.00, 0.12, -8.30, -2.08, 0.00, 56.44, 51.10 -CTUN, 1000, 0.21, -0.25, 0.000000, 0, 0, 5, 1000, 0 -ATT, 0.00, 0.32, -8.12, -1.23, 0.00, 55.44, 51.10 -CTUN, 1000, 0.21, 0.36, 0.000000, 0, 0, 19, 1000, 0 -ATT, 0.00, -0.76, -8.30, -0.58, 0.00, 54.12, 51.10 -CTUN, 1000, 0.21, 0.95, 0.000000, 0, 0, 34, 1000, 0 -ATT, 0.00, -2.09, -8.21, -1.41, 0.00, 52.71, 51.10 -CTUN, 1000, 0.21, 1.55, 0.000000, 0, 0, 53, 1000, 0 -ATT, 0.00, -0.90, -8.86, -2.20, 0.00, 51.67, 51.10 -CTUN, 1000, 0.20, 3.60, 0.000000, 0, 0, 63, 999, 0 -ATT, 0.00, -1.03, -10.92, -2.31, 0.00, 51.15, 51.10 -CTUN, 1000, 0.21, 4.24, 0.000000, 0, 0, 66, 1000, 0 -ATT, 0.00, -2.10, -10.82, -3.68, 0.00, 51.32, 51.10 -CTUN, 986, 0.21, 4.25, 0.000000, 0, 0, 71, 1000, 0 -DU32, 7, 166140 -CURR, 986, 2532879, 944, 2543, 5051, 1895.010900 -ATT, 0.00, -2.21, -9.14, -5.50, 0.00, 51.69, 51.10 -CTUN, 888, 0.29, 4.15, 0.000000, 0, 5, 76, 903, 0 -ATT, 0.00, -1.84, -8.77, -7.02, 0.00, 52.15, 51.10 -CTUN, 858, 0.29, 4.21, 0.000000, 0, 6, 81, 865, 0 -ATT, 0.00, -1.97, -8.21, -7.13, 0.00, 52.47, 51.10 -CTUN, 852, 0.44, 4.29, 0.000000, 0, 5, 84, 857, 0 -ATT, 0.00, -2.69, -8.12, -6.03, 0.00, 52.73, 51.10 -CTUN, 806, 0.44, 4.33, 0.000000, 0, 3, 86, 812, 0 -ATT, 0.00, -2.15, -8.30, -4.74, 0.00, 53.09, 51.10 -CTUN, 797, 0.63, 4.56, 0.000000, 0, 2, 83, 800, 0 -ATT, 0.00, -0.98, -8.12, -3.91, 0.00, 53.67, 51.10 -CTUN, 790, 0.63, 4.72, 0.000000, 0, 1, 77, 792, 0 -ATT, 0.00, 0.12, -8.02, -3.84, 0.00, 54.39, 51.10 -PM, 0, 0, 0, 0, 1000, 10492, 0, 0 -CTUN, 771, 0.79, 4.64, 0.000000, 0, 1, 67, 774, 0 -ATT, 0.00, 0.73, -8.12, -4.17, 0.00, 55.24, 51.10 -CTUN, 769, 0.79, 4.70, 0.000000, 0, 1, 59, 770, 0 -ATT, 0.00, 0.62, -6.81, -4.49, 0.00, 55.94, 51.10 -CTUN, 783, 0.94, 4.77, 0.000000, 0, 1, 51, 779, 0 -ATT, 0.00, 0.26, -5.97, -4.09, 0.00, 56.28, 51.10 -CTUN, 801, 0.94, 4.95, 0.000000, 0, 1, 41, 794, 0 -DU32, 7, 166140 -CURR, 813, 2541047, 965, 2045, 5051, 1901.108000 -ATT, 0.00, -0.16, -4.38, -2.97, 0.00, 56.26, 51.10 -CTUN, 852, 0.94, 4.97, 0.000000, 0, 0, 32, 843, 0 -ATT, 0.00, -0.20, -2.33, -1.17, 0.00, 55.90, 51.10 -CTUN, 874, 0.89, 4.97, 0.000000, 0, 0, 31, 874, 0 -ATT, 0.00, -0.08, -2.42, 1.19, 0.00, 55.26, 51.10 -CTUN, 906, 0.89, 5.06, 0.000000, 0, 0, 29, 904, 0 -ATT, 0.00, 0.00, -2.42, 3.17, 0.00, 54.44, 51.10 -CTUN, 910, 0.88, 5.06, 0.000000, 0, 1, 26, 910, 0 -ATT, 0.00, 0.06, -2.42, 4.28, 0.00, 53.42, 51.10 -CTUN, 911, 0.88, 5.11, 0.000000, 0, 2, 27, 913, 0 -ATT, 0.00, 0.17, -3.73, 4.39, 0.00, 52.31, 51.10 -CTUN, 909, 0.88, 5.20, 0.000000, 0, 2, 28, 910, 0 -ATT, 0.00, 0.17, -3.92, 3.65, 0.00, 51.23, 51.10 -CTUN, 909, 0.89, 5.20, 0.000000, 0, 1, 29, 908, 0 -ATT, 0.00, 0.01, -4.20, 2.50, 0.00, 50.26, 51.10 -CTUN, 857, 0.89, 5.21, 0.000000, 0, 0, 36, 865, 0 -ATT, 0.00, -0.09, -4.29, 1.81, 0.00, 49.40, 51.10 -CTUN, 834, 0.93, 5.19, 0.000000, 0, 0, 40, 840, 0 -ATT, 0.00, 0.12, -4.66, 1.53, 0.00, 48.61, 51.10 -CTUN, 775, 0.93, 5.24, 0.000000, 0, 0, 40, 789, 0 -DU32, 7, 166140 -CURR, 775, 2549818, 958, 2189, 5028, 1907.629300 -ATT, 0.00, 0.14, -4.76, 1.19, 0.00, 47.99, 51.10 -CTUN, 730, 1.00, 5.29, 0.000000, 0, 0, 38, 745, 0 -ATT, 0.00, 0.08, -4.57, 0.48, 0.00, 47.45, 51.10 -CTUN, 702, 1.00, 5.26, 0.000000, 0, 0, 24, 703, 0 -ATT, 0.00, 0.07, -4.57, -0.64, 0.00, 46.95, 51.10 -CTUN, 705, 1.07, 5.32, 0.000000, 0, 0, 10, 704, 0 -ATT, 0.00, 0.07, -4.76, -1.89, 0.00, 46.45, 51.10 -CTUN, 745, 1.07, 5.36, 0.000000, 0, 0, -9, 740, 0 -ATT, 0.00, -0.16, -4.57, -2.65, 0.00, 46.01, 51.10 -CTUN, 850, 1.13, 5.36, 0.000000, 0, 0, -23, 838, 0 -ATT, 0.00, -0.93, -4.48, -2.61, 0.00, 45.80, 51.10 -CTUN, 950, 1.13, 5.46, 0.000000, 0, 0, -26, 913, 0 -ATT, 0.00, -1.53, -4.38, -2.14, 0.00, 45.88, 51.10 -CTUN, 997, 1.13, 5.31, 0.000000, 0, 0, -22, 997, 0 -ATT, 0.00, -1.39, -4.38, -1.77, 0.00, 46.38, 51.10 -CTUN, 1000, 1.07, 5.30, 0.000000, 0, 0, -5, 1000, 0 -ATT, 0.00, -1.34, -4.38, -1.62, 0.00, 47.28, 51.10 -CTUN, 1000, 1.07, 5.34, 0.000000, 0, 0, 3, 1000, 0 -ATT, 0.00, -1.64, -4.20, -1.71, 0.00, 48.67, 51.10 -CTUN, 994, 1.02, 5.24, 0.000000, 0, 0, 10, 1000, 0 -DU32, 7, 166140 -CURR, 993, 2558414, 937, 2524, 5051, 1913.733900 -ATT, 0.00, -1.76, -4.38, -2.06, 0.00, 50.52, 51.10 -CTUN, 967, 1.02, 5.22, 0.000000, 0, 0, 16, 972, 0 -ATT, 0.00, -1.59, -4.20, -2.27, 0.00, 52.57, 51.10 -CTUN, 943, 1.02, 5.14, 0.000000, 0, 0, 21, 946, 0 -ATT, 0.00, -1.83, -3.92, -2.15, 0.00, 54.53, 51.10 -CTUN, 872, 1.02, 5.23, 0.000000, 0, 0, 22, 883, 0 -ATT, 0.28, -1.91, -2.52, -1.79, 0.00, 56.21, 51.10 -CTUN, 804, 1.02, 5.31, 0.000000, 0, 0, 20, 804, 0 -ATT, 1.78, -1.57, -2.52, -1.22, 0.00, 57.47, 51.10 -CTUN, 792, 1.06, 5.37, 0.000000, 0, 0, 17, 792, 0 -ATT, 2.34, -1.02, -2.24, -0.50, 0.00, 58.12, 51.10 -CTUN, 834, 1.06, 5.47, 0.000000, 0, 0, 8, 820, 0 -ATT, 3.46, -0.45, -2.70, 0.05, 0.00, 58.15, 51.10 -CTUN, 871, 1.08, 5.45, 0.000000, 0, 0, -1, 864, 0 -ATT, 6.09, -0.02, -2.24, 0.39, 0.00, 57.89, 51.10 -CTUN, 902, 1.08, 5.50, 0.000000, 0, 0, -7, 893, 0 -ATT, 6.37, 0.95, -2.05, 0.25, 0.00, 57.42, 51.10 -CTUN, 925, 1.08, 5.43, 0.000000, 0, 0, -8, 911, 0 -ATT, 6.37, 2.45, -2.05, 0.07, 0.00, 56.87, 51.10 -CTUN, 966, 1.08, 5.41, 0.000000, 0, 1, -5, 960, 0 -DU32, 7, 166140 -CURR, 966, 2567253, 955, 2319, 5051, 1919.991900 -ATT, 6.37, 3.60, -2.05, 0.15, 0.00, 56.26, 51.10 -CTUN, 980, 1.18, 5.30, 0.000000, 0, 1, -2, 980, 0 -ATT, 6.28, 4.09, -2.05, -0.15, 0.00, 55.66, 51.10 -CTUN, 980, 1.10, 5.44, 0.000000, 0, 2, -3, 984, 0 -ATT, 6.28, 3.85, -2.05, -0.91, 0.00, 54.97, 51.10 -CTUN, 975, 1.10, 5.51, 0.000000, 0, 2, 2, 977, 0 -ATT, 6.09, 3.87, -2.24, -1.79, 0.00, 54.18, 51.10 -CTUN, 973, 1.04, 5.50, 0.000000, 0, 2, 13, 975, 0 -ATT, 5.53, 4.70, -2.24, -1.89, 0.00, 53.30, 51.10 -CTUN, 972, 1.05, 5.44, 0.000000, 0, 3, 19, 976, 0 -ATT, 4.78, 5.61, -2.14, -1.31, 0.00, 52.37, 51.10 -CTUN, 958, 1.05, 5.43, 0.000000, 0, 4, 26, 966, 0 -ATT, 3.84, 5.92, -2.24, -0.67, 0.00, 51.24, 51.10 -CTUN, 890, 1.05, 5.47, 0.000000, 0, 3, 30, 933, 0 -ATT, 3.46, 4.93, -2.24, 0.07, 0.00, 49.98, 51.10 -CTUN, 857, 1.03, 5.49, 0.000000, 0, 1, 37, 864, 0 -ATT, 1.03, 3.60, -2.24, 0.36, 0.00, 48.62, 51.10 -CTUN, 857, 1.03, 5.39, 0.000000, 0, 1, 39, 858, 0 -ATT, 0.00, 2.58, -2.24, 0.33, 0.00, 47.34, 51.10 -CTUN, 857, 1.02, 5.35, 0.000000, 0, 0, 38, 857, 0 -DU32, 7, 166140 -CURR, 857, 2576638, 951, 2294, 5051, 1926.811600 -ATT, 0.00, 1.65, -2.24, 0.11, 0.00, 46.25, 51.10 -CTUN, 857, 1.03, 5.46, 0.000000, 0, 0, 40, 857, 0 -ATT, 0.00, 2.00, -2.42, 0.48, 0.00, 45.05, 51.10 -CTUN, 825, 1.03, 5.43, 0.000000, 0, 0, 38, 825, 0 -ATT, 0.00, 3.59, -3.08, 1.12, 0.00, 43.57, 51.10 -CTUN, 823, 1.04, 5.51, 0.000000, 0, 1, 39, 825, 0 -ATT, 0.00, 4.32, -2.52, 1.31, 0.00, 41.68, 51.10 -CTUN, 824, 1.04, 5.46, 0.000000, 0, 1, 35, 825, 0 -ATT, 0.00, 3.32, -2.42, 0.95, 0.00, 39.85, 49.85 -CTUN, 825, 1.06, 5.36, 0.000000, 0, 0, 30, 825, 0 -ATT, 0.00, 2.11, -3.26, 0.81, 0.00, 37.89, 47.89 -CTUN, 823, 1.06, 5.35, 0.000000, 0, 0, 27, 825, 0 -ATT, 0.00, 0.95, -3.26, 0.36, 0.00, 35.70, 45.70 -CTUN, 815, 1.08, 5.49, 0.000000, 0, 0, 21, 819, 0 -ATT, -1.42, 0.10, -3.26, -0.27, 0.00, 33.49, 43.49 -CTUN, 809, 1.08, 5.44, 0.000000, 0, 0, 15, 809, 0 -ATT, -3.31, 0.18, -3.26, -0.52, 0.00, 31.24, 41.24 -CTUN, 809, 1.10, 5.43, 0.000000, 0, 0, 12, 808, 0 -ATT, -3.22, -0.55, -3.26, -0.30, 0.00, 29.09, 39.09 -CTUN, 809, 1.08, 5.36, 0.000000, 0, 0, 2, 809, 0 -DU32, 7, 166140 -CURR, 809, 2584872, 962, 2092, 5028, 1932.868700 -ATT, -3.03, -1.55, -2.98, -0.52, 0.00, 27.15, 37.15 -CTUN, 809, 1.08, 5.53, 0.000000, 0, 0, -1, 809, 0 -ATT, -2.74, -1.99, -2.70, -1.24, 0.00, 25.49, 35.49 -CTUN, 815, 0.87, 5.33, 0.000000, 0, 0, -9, 809, 0 -ATT, -5.02, -2.13, -2.70, -2.06, 0.00, 24.00, 34.00 -CTUN, 843, 0.87, 5.37, 0.000000, 0, 1, -10, 837, 0 -ATT, -5.87, -2.94, -2.61, -2.68, 0.00, 22.65, 32.65 -CTUN, 880, 0.78, 5.39, 0.000000, 0, 2, -12, 871, 0 -ATT, -5.87, -5.98, -2.61, -2.89, 0.00, 21.54, 31.54 -CTUN, 908, 0.78, 5.36, 0.000000, 0, 7, -9, 914, 0 -ATT, -4.26, -8.36, -2.52, -2.91, 0.00, 20.58, 30.58 -CTUN, 911, 0.70, 5.23, 0.000000, 0, 9, -5, 920, 0 -ATT, -2.55, -7.06, -2.52, -3.25, 0.00, 19.73, 29.73 -CTUN, 910, 0.70, 5.25, 0.000000, 0, 5, 2, 915, 0 -ATT, -2.36, -4.08, -2.33, -3.39, 0.00, 19.19, 29.19 -CTUN, 906, 0.65, 5.09, 0.000000, 0, 2, 8, 909, 0 -ATT, -0.75, -1.87, -3.26, -2.94, 0.00, 19.11, 29.09 -CTUN, 864, 0.65, 5.08, 0.000000, 0, 1, 17, 865, 0 -ATT, 0.00, -0.45, -3.54, -2.37, 0.00, 19.45, 29.09 -CTUN, 853, 0.63, 5.19, 0.000000, 0, 0, 31, 856, 0 -DU32, 7, 166140 -CURR, 850, 2593570, 951, 2262, 5051, 1939.540500 -ATT, 0.00, 0.75, -3.26, -2.14, 0.00, 20.23, 29.09 -CTUN, 848, 0.63, 5.15, 0.000000, 0, 0, 30, 851, 0 -ATT, 0.00, 1.40, -2.98, -2.02, 0.00, 21.27, 29.09 -CTUN, 839, 0.63, 5.33, 0.000000, 0, 0, 29, 840, 0 -ATT, 0.00, 1.81, -3.08, -1.86, 0.00, 22.52, 29.09 -CTUN, 821, 0.63, 5.27, 0.000000, 0, 0, 25, 821, 0 -ATT, 0.00, 1.90, -3.08, -1.98, 0.00, 23.98, 29.09 -CTUN, 824, 0.63, 5.30, 0.000000, 0, 0, 17, 824, 0 -ATT, 0.00, 1.32, -2.80, -2.23, 0.00, 25.69, 29.09 -CTUN, 852, 0.65, 5.30, 0.000000, 0, 0, 15, 843, 0 -ATT, 0.00, 0.50, -2.61, -2.35, 0.00, 27.59, 29.09 -CTUN, 906, 0.65, 5.48, 0.000000, 0, 0, 8, 898, 0 -ATT, 0.00, 0.32, -2.70, -2.35, 0.00, 29.60, 29.09 -CTUN, 910, 0.65, 5.41, 0.000000, 0, 0, 8, 911, 0 -ATT, 0.00, 0.40, -2.70, -2.34, 0.00, 31.70, 29.09 -CTUN, 912, 0.65, 5.38, 0.000000, 0, 0, 8, 912, 0 -ATT, 0.00, 0.06, -2.70, -2.43, 0.00, 33.45, 29.09 -CTUN, 910, 0.65, 5.34, 0.000000, 0, 0, 7, 912, 0 -ATT, 0.00, -0.60, -2.61, -2.31, 0.00, 34.97, 29.09 -CTUN, 907, 0.64, 5.31, 0.000000, 0, 0, 9, 907, 0 -DU32, 7, 166140 -CURR, 904, 2602254, 958, 2247, 5051, 1945.855600 -ATT, 0.00, -0.88, -2.70, -1.77, 0.00, 36.39, 29.09 -CTUN, 888, 0.64, 5.32, 0.000000, 0, 0, 8, 888, 0 -ATT, 0.00, -0.83, -2.52, -1.04, 0.00, 37.68, 29.09 -CTUN, 888, 0.63, 5.37, 0.000000, 0, 0, 2, 888, 0 -ATT, 0.00, -0.47, -2.70, -0.73, 0.00, 38.79, 29.09 -CTUN, 888, 0.63, 5.31, 0.000000, 0, 0, -5, 888, 0 -ATT, 0.00, 0.00, -2.61, -1.28, 0.00, 39.65, 29.65 -CTUN, 888, 0.62, 5.42, 0.000000, 0, 0, -15, 888, 0 -ATT, 0.00, 0.72, -2.61, -2.20, 0.00, 40.26, 30.26 -CTUN, 904, 0.62, 5.41, 0.000000, 0, 0, -17, 904, 0 -ATT, 0.00, 1.28, -2.61, -2.43, 0.00, 40.58, 30.58 -CTUN, 922, 0.60, 5.49, 0.000000, 0, 0, -22, 918, 0 -ATT, 0.00, 1.29, -2.70, -1.92, 0.00, 40.49, 30.59 -CTUN, 959, 0.60, 5.34, 0.000000, 0, 0, -24, 946, 0 -ATT, 0.00, 0.58, -2.52, -1.38, 0.00, 40.02, 30.59 -CTUN, 995, 0.54, 5.17, 0.000000, 0, 0, -28, 980, 0 -ATT, 0.00, 0.46, -2.52, -1.13, 0.00, 39.25, 30.59 -CTUN, 1000, 0.54, 5.16, 0.000000, 0, 0, -29, 1000, 0 -ATT, 0.00, 0.54, -2.42, -0.88, 0.00, 38.12, 30.59 -CTUN, 1000, 0.47, 5.11, 0.000000, 0, 0, -32, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2611534, 942, 2364, 5051, 1951.930900 -ATT, 0.00, 0.48, -2.42, -0.82, 0.00, 36.67, 30.59 -CTUN, 1000, 0.47, 5.11, 0.000000, 0, 0, -31, 1000, 0 -ATT, 0.00, 0.54, -2.52, 0.00, 0.00, 35.05, 30.59 -CTUN, 1000, 0.47, 4.75, 0.000000, 0, 0, -26, 1000, 0 -ATT, 0.00, 0.63, -2.52, 1.43, 0.00, 33.36, 30.59 -CTUN, 1000, 0.53, 4.99, 0.000000, 0, 0, -23, 1000, 0 -ATT, -1.23, 0.83, -2.52, 1.93, 0.00, 31.95, 30.59 -CTUN, 1000, 0.47, 4.91, 0.000000, 0, 0, -16, 1000, 0 -ATT, -4.26, 1.31, -2.42, 2.20, 0.00, 30.60, 30.59 -CTUN, 1000, 0.47, 4.86, 0.000000, 0, 0, -9, 1000, 0 -ATT, -6.91, 0.68, -2.42, 2.91, 0.00, 29.53, 30.59 -CTUN, 1000, 0.43, 4.81, 0.000000, 0, 0, -6, 1000, 0 -ATT, -8.52, -1.98, -2.52, 3.54, 0.00, 28.72, 30.59 -CTUN, 1000, 0.43, 4.81, 0.000000, 0, 0, -1, 1000, 0 -ATT, -11.17, -4.15, -2.80, 3.77, 0.00, 28.11, 30.59 -CTUN, 999, 0.37, 4.90, 0.000000, 0, 0, 3, 1000, 0 -ATT, -10.51, -5.71, -3.17, 3.16, 0.00, 27.57, 30.59 -CTUN, 1000, 0.37, 4.91, 0.000000, 0, 0, 8, 1000, 0 -ATT, -8.81, -7.61, -4.57, 2.26, 0.00, 27.01, 30.59 -CTUN, 1000, 0.34, 4.87, 0.000000, 0, 0, 18, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2621532, 930, 2722, 5028, 1958.944800 -ATT, -7.48, -8.03, -4.85, 1.66, 0.00, 26.39, 30.59 -CTUN, 1000, 0.34, 5.10, 0.000000, 0, 0, 27, 1000, 0 -ATT, -4.26, -7.25, -7.56, 0.81, 0.00, 25.88, 30.59 -CTUN, 1000, 0.34, 5.12, 0.000000, 0, 0, 29, 1000, 0 -ATT, -1.32, -5.35, -10.45, -1.52, 0.00, 25.69, 30.59 -CTUN, 1000, 0.34, 5.11, 0.000000, 0, 0, 38, 1000, 0 -ATT, 0.00, -2.60, -10.64, -4.77, 0.00, 25.82, 30.59 -CTUN, 1000, 0.34, 4.97, 0.000000, 0, 0, 43, 1000, 0 -ATT, 0.00, -0.23, -10.64, -7.82, 0.00, 26.36, 30.59 -CTUN, 952, 0.39, 4.92, 0.000000, 0, 9, 51, 968, 0 -ATT, 0.00, 1.00, -9.61, -9.03, 0.00, 27.37, 30.59 -CTUN, 909, 0.39, 4.88, 0.000000, 0, 9, 57, 931, 0 -ATT, 0.00, 1.32, -7.84, -8.10, 0.00, 28.92, 30.59 -PM, 0, 0, 0, 0, 1000, 10460, 0, 0 -CTUN, 847, 0.48, 4.72, 0.000000, 0, 6, 63, 869, 0 -ATT, 0.00, 0.96, -6.72, -5.63, 0.00, 31.11, 30.59 -CTUN, 801, 0.48, 4.81, 0.000000, 0, 2, 61, 806, 0 -ATT, 0.00, -0.01, -6.53, -3.98, 0.00, 33.06, 30.59 -CTUN, 789, 0.66, 5.00, 0.000000, 0, 1, 57, 790, 0 -ATT, 0.00, -0.83, -6.06, -3.69, 0.00, 34.63, 30.59 -CTUN, 808, 0.66, 4.91, 0.000000, 0, 1, 45, 802, 0 -DU32, 7, 166140 -CURR, 813, 2630769, 965, 2000, 5051, 1965.754800 -ATT, 0.00, -0.84, -6.06, -3.68, 0.00, 35.83, 30.59 -CTUN, 857, 0.70, 4.99, 0.000000, 0, 1, 36, 854, 0 -ATT, 0.00, -0.95, -6.06, -3.05, 0.00, 36.51, 30.59 -CTUN, 909, 0.70, 4.94, 0.000000, 0, 0, 31, 908, 0 -ATT, 0.00, -1.85, -5.97, -1.84, 0.00, 36.75, 30.59 -CTUN, 911, 0.76, 5.04, 0.000000, 0, 0, 24, 910, 0 -ATT, 0.09, -2.08, -4.85, -0.79, 0.00, 36.72, 30.59 -CTUN, 932, 0.76, 5.13, 0.000000, 0, 0, 19, 932, 0 -ATT, 0.46, -1.87, -3.73, -0.63, 0.00, 36.48, 30.59 -CTUN, 946, 0.78, 5.14, 0.000000, 0, 0, 17, 946, 0 -ATT, 0.46, -1.44, -2.70, -0.91, 0.00, 36.35, 30.59 -CTUN, 946, 0.78, 5.26, 0.000000, 0, 0, 14, 948, 0 -ATT, 0.46, -0.85, -2.61, -0.36, 0.00, 36.47, 30.59 -CTUN, 946, 0.78, 5.18, 0.000000, 0, 0, 11, 946, 0 -ATT, 1.03, -0.54, -2.70, 1.16, 0.00, 36.94, 30.59 -CTUN, 946, 0.78, 5.14, 0.000000, 0, 0, 2, 946, 0 -ATT, 3.46, -0.32, -2.52, 2.31, 0.00, 37.70, 30.59 -CTUN, 947, 0.78, 5.19, 0.000000, 0, 0, -1, 945, 0 -ATT, 5.06, 0.53, -2.24, 2.70, 0.00, 38.49, 30.59 -CTUN, 979, 0.78, 5.00, 0.000000, 0, 0, -9, 963, 0 -DU32, 7, 166140 -CURR, 979, 2640044, 962, 2088, 5051, 1971.824000 -ATT, 3.65, 2.40, -2.05, 1.99, 0.00, 39.27, 30.59 -CTUN, 992, 0.79, 4.97, 0.000000, 0, 1, -14, 993, 0 -ATT, 3.37, 4.07, -1.49, 1.48, 0.00, 40.00, 30.59 -CTUN, 1000, 0.79, 5.01, 0.000000, 0, 0, -24, 1000, 0 -ATT, 2.90, 4.89, -1.40, 1.52, 0.00, 40.57, 30.59 -CTUN, 1000, 0.94, 5.03, 0.000000, 0, 0, -36, 1000, 0 -ATT, 2.53, 4.24, -1.40, 1.71, 0.00, 40.57, 30.65 -CTUN, 1000, 0.89, 5.05, 0.000000, 0, 0, -45, 1000, 0 -ATT, 0.09, 3.31, -2.24, 1.12, 0.00, 40.07, 30.65 -CTUN, 1000, 0.89, 5.02, 0.000000, 0, 0, -51, 1000, 0 -ATT, 0.00, 2.67, -2.61, 0.38, 0.00, 39.12, 30.65 -CTUN, 1000, 0.83, 4.92, 0.000000, 0, 0, -58, 1000, 0 -ATT, 0.00, 1.99, -3.26, 0.01, 0.00, 37.90, 30.65 -CTUN, 1000, 0.83, 4.94, 0.000000, 0, 0, -61, 1000, 0 -ATT, 0.00, 1.70, -3.26, 0.15, 0.00, 36.28, 30.65 -CTUN, 1000, 0.68, 4.92, 0.000000, 0, 0, -66, 1000, 0 -ATT, 0.00, 2.35, -3.92, 0.70, 0.00, 34.30, 30.65 -CTUN, 1000, 0.68, 4.96, 0.000000, 0, 0, -63, 1000, 0 -ATT, 0.00, 2.95, -4.85, 1.29, 0.00, 31.99, 30.65 -CTUN, 1000, 0.52, 4.75, 0.000000, 0, 0, -61, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2650031, 943, 2463, 5028, 1977.792600 -ATT, 0.00, 2.71, -5.78, 0.95, 0.00, 29.62, 30.65 -CTUN, 1000, 0.52, 4.39, 0.000000, 0, 0, -58, 1000, 0 -ATT, 0.00, 1.03, -6.16, -0.68, 0.00, 27.54, 30.65 -CTUN, 1000, 0.35, 4.40, 0.000000, 0, 0, -45, 1000, 0 -ATT, -4.35, 0.17, -4.29, -2.77, 0.00, 26.11, 30.65 -CTUN, 1000, 0.35, 4.15, 0.000000, 0, 0, -21, 1000, 0 -ATT, -8.81, 0.21, -4.38, -4.29, 0.00, 25.26, 30.65 -CTUN, 1000, 0.22, 3.78, 0.000000, 0, 0, 0, 1000, 0 -ATT, -9.00, -1.46, -4.20, -4.38, 0.00, 24.93, 30.65 -CTUN, 1000, 0.22, 3.73, 0.000000, 0, 0, 20, 1000, 0 -ATT, -8.05, -2.69, -3.08, -2.98, 0.00, 24.98, 30.65 -CTUN, 1000, 0.20, 3.81, 0.000000, 0, 0, 36, 1000, 0 -ATT, -7.67, -3.66, -2.98, -0.85, 0.00, 25.35, 30.65 -CTUN, 1000, 0.20, 3.75, 0.000000, 0, 0, 46, 1000, 0 -ATT, -6.72, -5.27, -3.08, 0.15, 0.00, 26.03, 30.65 -CTUN, 1000, 0.20, 4.11, 0.000000, 0, 1, 56, 1000, 0 -ATT, -1.51, -6.40, -4.85, 1.00, 0.00, 26.88, 30.65 -CTUN, 986, 0.20, 4.30, 0.000000, 0, 5, 61, 991, 0 -ATT, 0.00, -5.43, -5.69, 1.70, 0.00, 27.85, 30.65 -CTUN, 930, 0.20, 4.34, 0.000000, 0, 2, 60, 934, 0 -DU32, 7, 166140 -CURR, 930, 2659978, 943, 2260, 5028, 1985.000500 -ATT, 0.00, -2.47, -6.53, 1.49, 0.00, 29.09, 30.65 -CTUN, 913, 0.26, 4.19, 0.000000, 0, 0, 55, 913, 0 -ATT, 0.00, -0.54, -6.06, 0.42, 0.00, 30.14, 30.65 -CTUN, 909, 0.26, 4.41, 0.000000, 0, 0, 50, 909, 0 -ATT, 0.00, -0.18, -4.38, -0.77, 0.00, 30.86, 30.65 -CTUN, 938, 0.33, 4.35, 0.000000, 0, 0, 50, 926, 0 -ATT, 0.00, 0.47, -2.52, -1.05, 0.00, 31.19, 30.65 -CTUN, 983, 0.33, 4.53, 0.000000, 0, 0, 52, 979, 0 -ATT, 0.00, 0.99, -2.52, 0.53, 0.00, 31.40, 30.65 -CTUN, 1000, 0.42, 4.58, 0.000000, 0, 0, 47, 1000, 0 -ATT, 0.00, 0.52, -2.52, 2.55, 0.00, 31.76, 30.65 -CTUN, 1000, 0.42, 4.48, 0.000000, 0, 1, 39, 1000, 0 -ATT, 0.00, -0.54, -2.52, 3.52, 0.00, 32.45, 30.65 -CTUN, 1000, 0.49, 4.54, 0.000000, 0, 1, 34, 1000, 0 -ATT, 0.00, -1.30, -2.52, 3.28, 0.00, 33.35, 30.65 -CTUN, 999, 0.49, 4.69, 0.000000, 0, 0, 30, 1000, 0 -ATT, 0.00, -0.83, -2.89, 2.61, 0.00, 34.21, 30.65 -CTUN, 984, 0.55, 4.71, 0.000000, 0, 0, 25, 986, 0 -ATT, 0.00, -0.67, -4.57, 1.98, 0.00, 34.90, 30.65 -CTUN, 979, 0.55, 4.66, 0.000000, 0, 0, 18, 979, 0 -DU32, 7, 166140 -CURR, 980, 2669643, 950, 2175, 5051, 1991.250400 -ATT, 0.00, -1.07, -4.85, 0.84, 0.00, 35.44, 30.65 -CTUN, 982, 0.59, 4.65, 0.000000, 0, 0, 13, 979, 0 -ATT, 0.00, -1.21, -6.81, -0.64, 0.00, 35.89, 30.65 -CTUN, 1000, 0.59, 4.75, 0.000000, 0, 0, 8, 1000, 0 -ATT, 0.00, -1.30, -7.84, -1.89, 0.00, 36.26, 30.65 -CTUN, 1000, 0.59, 4.60, 0.000000, 0, 0, 0, 1000, 0 -ATT, 0.00, -1.55, -8.21, -3.62, 0.00, 36.61, 30.65 -CTUN, 1000, 0.59, 4.68, 0.000000, 0, 0, -7, 1000, 0 -ATT, 0.00, -1.44, -8.30, -5.65, 0.00, 36.93, 30.65 -CTUN, 1000, 0.59, 4.58, 0.000000, 0, 0, -11, 1000, 0 -ATT, 0.00, -1.11, -8.02, -6.65, 0.00, 37.02, 30.65 -CTUN, 1000, 0.56, 4.48, 0.000000, 0, 0, -18, 1000, 0 -ATT, 0.09, -1.01, -7.84, -6.54, 0.00, 37.02, 30.65 -CTUN, 1000, 0.56, 4.48, 0.000000, 0, 0, -23, 1000, 0 -ATT, 0.37, -1.64, -5.32, -5.86, 0.00, 36.85, 30.65 -CTUN, 1000, 0.51, 4.60, 0.000000, 0, 0, -27, 1000, 0 -ATT, 0.28, -2.25, -2.42, -4.63, 0.00, 36.52, 30.65 -CTUN, 1000, 0.51, 4.36, 0.000000, 0, 0, -26, 1000, 0 -ATT, 0.28, -2.04, -2.52, -2.31, 0.00, 36.08, 30.65 -CTUN, 1000, 0.44, 4.25, 0.000000, 0, 0, -27, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2679612, 956, 2137, 5051, 1997.391200 -ATT, 2.34, -1.43, -2.05, 0.55, 0.00, 35.49, 30.65 -CTUN, 1000, 0.44, 4.38, 0.000000, 0, 0, -34, 1000, 0 -ATT, 4.68, -0.12, -2.05, 2.64, 0.00, 34.93, 30.65 -CTUN, 1000, 0.37, 4.39, 0.000000, 0, 0, -35, 1000, 0 -ATT, 4.59, 1.86, -2.05, 3.81, 0.00, 34.36, 30.65 -CTUN, 1000, 0.37, 4.33, 0.000000, 0, 0, -34, 1000, 0 -ATT, 3.93, 3.81, -2.24, 4.23, 0.00, 33.86, 30.65 -CTUN, 1000, 0.27, 4.23, 0.000000, 0, 0, -35, 1000, 0 -ATT, 3.18, 4.46, -2.52, 3.46, 0.00, 33.42, 30.65 -CTUN, 1000, 0.27, 4.18, 0.000000, 0, 1, -32, 1000, 0 -ATT, 0.28, 2.87, -2.52, 2.23, 0.00, 33.15, 30.65 -CTUN, 1000, 0.20, 3.30, 0.000000, 0, 0, -22, 1000, 0 -ATT, 0.00, 0.81, -2.52, 1.90, 0.00, 33.04, 30.65 -CTUN, 1000, 0.20, 2.63, 0.000000, 0, 0, -7, 1000, 0 -ATT, 0.00, -0.68, -2.33, 1.61, 0.00, 33.11, 30.65 -CTUN, 1000, 0.20, 1.91, 0.000000, 0, 0, 4, 1000, 0 -ATT, 0.00, -1.45, -2.42, 1.08, 0.00, 33.33, 30.65 -CTUN, 999, 0.20, 2.46, 0.000000, 0, 0, 18, 1000, 0 -ATT, 0.00, -2.04, -2.24, 0.78, 0.00, 33.50, 30.65 -CTUN, 1000, 0.20, 3.14, 0.000000, 0, 0, 25, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2689612, 937, 2374, 5051, 2003.771500 -ATT, 0.00, -2.28, -2.24, 0.40, 0.00, 33.69, 30.65 -CTUN, 1000, 0.20, 3.43, 0.000000, 0, 0, 33, 1000, 0 -ATT, 0.00, -2.14, -2.52, 0.88, 0.00, 33.97, 30.65 -CTUN, 1000, 0.20, 3.79, 0.000000, 0, 0, 37, 1000, 0 -ATT, 0.65, -1.75, -3.26, 1.26, 0.00, 34.43, 30.65 -CTUN, 1000, 0.20, 4.19, 0.000000, 0, 0, 37, 1000, 0 -ATT, 2.90, -1.39, -3.92, 1.02, 0.00, 35.18, 30.65 -CTUN, 982, 0.20, 4.24, 0.000000, 0, 0, 37, 986, 0 -ATT, 3.18, -0.39, -3.92, -0.50, 0.00, 36.04, 30.65 -CTUN, 982, 0.25, 4.23, 0.000000, 0, 0, 36, 982, 0 -ATT, 3.18, 1.61, -3.92, -1.84, 0.00, 36.84, 30.65 -CTUN, 983, 0.25, 4.33, 0.000000, 0, 1, 28, 983, 0 -ATT, 6.28, 2.83, -3.92, -1.71, 0.00, 37.52, 30.65 -CTUN, 986, 0.33, 4.34, 0.000000, 0, 1, 20, 987, 0 -ATT, 6.56, 3.39, -3.73, -0.96, 0.00, 37.89, 30.65 -CTUN, 994, 0.33, 4.33, 0.000000, 0, 2, 13, 995, 0 -ATT, 6.56, 4.52, -2.52, -0.30, 0.00, 37.99, 30.65 -CTUN, 998, 0.39, 4.49, 0.000000, 0, 3, 5, 999, 0 -ATT, 6.28, 5.49, -2.52, -0.12, 0.00, 37.85, 30.65 -CTUN, 999, 0.39, 4.56, 0.000000, 0, 1, -2, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2699548, 947, 2181, 5051, 2009.879200 -ATT, 3.00, 5.50, -2.80, -0.35, 0.00, 37.55, 30.65 -CTUN, 1000, 0.43, 4.53, 0.000000, 0, 1, -9, 1000, 0 -ATT, 0.00, 4.70, -3.73, -0.64, 0.00, 37.30, 30.65 -CTUN, 1000, 0.43, 4.58, 0.000000, 0, 0, -18, 1000, 0 -ATT, 0.00, 2.36, -4.38, -1.09, 0.00, 37.11, 30.65 -CTUN, 1000, 0.43, 4.38, 0.000000, 0, 0, -22, 1000, 0 -ATT, 0.00, -0.18, -4.85, -1.62, 0.00, 36.93, 30.65 -CTUN, 999, 0.43, 4.50, 0.000000, 0, 0, -24, 999, 0 -ATT, 0.00, -1.58, -4.76, -1.79, 0.00, 36.57, 30.65 -CTUN, 1000, 0.43, 4.42, 0.000000, 0, 0, -26, 1000, 0 -ATT, 0.00, -1.51, -4.76, -1.64, 0.00, 35.98, 30.65 -CTUN, 999, 0.41, 4.38, 0.000000, 0, 0, -27, 999, 0 -ATT, 0.00, -1.23, -4.76, -1.54, 0.00, 35.21, 30.65 -CTUN, 1000, 0.41, 4.46, 0.000000, 0, 0, -24, 1000, 0 -ATT, 0.00, -1.16, -4.85, -1.62, 0.00, 34.31, 30.65 -CTUN, 999, 0.38, 4.40, 0.000000, 0, 0, -22, 999, 0 -ATT, 0.00, -0.93, -4.20, -1.42, 0.00, 33.34, 30.65 -CTUN, 1000, 0.38, 4.54, 0.000000, 0, 0, -19, 1000, 0 -ATT, 0.00, -0.92, -2.24, -1.20, 0.00, 32.38, 30.65 -CTUN, 999, 0.34, 4.45, 0.000000, 0, 0, -14, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2709548, 936, 2532, 5028, 2016.295000 -ATT, 0.00, -1.21, -2.05, -0.26, 0.00, 31.40, 30.65 -CTUN, 1000, 0.34, 4.49, 0.000000, 0, 0, -14, 1000, 0 -ATT, 0.00, -0.88, -2.24, 0.68, 0.00, 30.48, 30.65 -CTUN, 999, 0.32, 4.34, 0.000000, 0, 0, -11, 1000, 0 -ATT, 0.00, -0.10, -2.14, 1.24, 0.00, 29.76, 30.65 -CTUN, 1000, 0.32, 4.53, 0.000000, 0, 0, -7, 1000, 0 -ATT, 0.00, 0.30, -2.24, 1.69, 0.00, 29.11, 30.65 -CTUN, 1000, 0.30, 4.37, 0.000000, 0, 0, -3, 1000, 0 -ATT, 0.00, -0.06, -2.24, 1.58, 0.00, 28.54, 30.65 -CTUN, 1000, 0.30, 4.36, 0.000000, 0, 0, 1, 1000, 0 -ATT, 0.00, -0.46, -3.64, 1.30, 0.00, 28.06, 30.65 -CTUN, 1000, 0.30, 4.33, 0.000000, 0, 0, 9, 1000, 0 -ATT, 0.00, -0.40, -4.76, 0.41, 0.00, 27.64, 30.65 -CTUN, 1000, 0.31, 4.32, 0.000000, 0, 0, 14, 1000, 0 -ATT, 0.00, -0.20, -6.44, -1.56, 0.00, 27.25, 30.65 -CTUN, 1000, 0.31, 4.46, 0.000000, 0, 0, 24, 1000, 0 -ATT, 0.00, 0.00, -6.72, -2.67, 0.00, 26.87, 30.65 -CTUN, 1000, 0.36, 4.39, 0.000000, 0, 0, 30, 1000, 0 -ATT, 0.00, -0.11, -7.84, -3.30, 0.00, 26.53, 30.65 -CTUN, 999, 0.36, 4.44, 0.000000, 0, 0, 37, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2719548, 924, 2655, 5051, 2023.431900 -ATT, 0.00, -0.53, -7.65, -3.53, 0.00, 26.43, 30.65 -CTUN, 1000, 0.42, 4.61, 0.000000, 0, 0, 45, 1000, 0 -ATT, 0.00, -0.92, -6.81, -3.35, 0.00, 26.42, 30.65 -CTUN, 982, 0.42, 4.66, 0.000000, 0, 1, 50, 990, 0 -ATT, 0.00, -0.98, -6.81, -2.90, 0.00, 26.48, 30.65 -CTUN, 977, 0.51, 4.72, 0.000000, 0, 0, 55, 979, 0 -ATT, 0.00, -0.89, -6.81, -2.26, 0.00, 26.56, 30.65 -CTUN, 951, 0.51, 4.82, 0.000000, 0, 0, 56, 953, 0 -ATT, 0.00, -0.73, -6.72, -1.73, 0.00, 26.56, 30.65 -CTUN, 928, 0.63, 4.88, 0.000000, 0, 0, 59, 928, 0 -ATT, 0.00, -0.68, -7.18, -1.71, 0.00, 26.37, 30.65 -CTUN, 902, 0.63, 4.95, 0.000000, 0, 0, 62, 902, 0 -ATT, 0.00, -0.08, -7.56, -1.99, 0.00, 25.96, 30.65 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 860, 0.77, 4.99, 0.000000, 0, 0, 65, 860, 0 -ATT, 0.00, 0.94, -7.84, -2.59, 0.00, 25.52, 30.65 -CTUN, 825, 0.77, 5.13, 0.000000, 0, 1, 66, 835, 0 -ATT, 0.00, 1.70, -7.84, -3.36, 0.00, 25.27, 30.65 -CTUN, 797, 0.92, 5.19, 0.000000, 0, 1, 61, 798, 0 -ATT, 0.00, 1.73, -7.84, -4.15, 0.00, 25.27, 30.65 -CTUN, 746, 0.92, 5.21, 0.000000, 0, 2, 53, 748, 0 -DU32, 7, 166140 -CURR, 746, 2728646, 961, 1949, 5051, 2030.237800 -ATT, 0.00, 1.70, -8.02, -4.68, 0.00, 25.44, 30.65 -CTUN, 735, 1.07, 5.29, 0.000000, 0, 2, 36, 740, 0 -ATT, 0.00, 1.67, -7.93, -5.02, 0.00, 25.72, 30.65 -CTUN, 737, 1.07, 5.35, 0.000000, 0, 2, 23, 739, 0 -ATT, 0.00, 1.40, -7.84, -5.32, 0.00, 26.16, 30.65 -CTUN, 777, 1.20, 5.30, 0.000000, 0, 3, 2, 770, 0 -ATT, 0.00, 1.02, -7.74, -5.46, 0.00, 26.66, 30.65 -CTUN, 877, 1.20, 5.36, 0.000000, 0, 3, -10, 824, 0 -ATT, 0.00, 0.51, -7.37, -5.18, 0.00, 27.25, 30.65 -CTUN, 939, 1.26, 5.34, 0.000000, 0, 2, -21, 941, 0 -ATT, 0.00, -0.13, -6.72, -4.52, 0.00, 28.00, 30.65 -CTUN, 998, 1.26, 5.31, 0.000000, 0, 2, -17, 1000, 0 -ATT, 0.00, -0.61, -6.81, -3.55, 0.00, 28.87, 30.65 -CTUN, 1000, 1.26, 5.52, 0.000000, 0, 0, -15, 1000, 0 -ATT, 0.00, -0.72, -6.72, -2.57, 0.00, 29.80, 30.65 -CTUN, 1000, 1.26, 5.41, 0.000000, 0, 0, -9, 1000, 0 -ATT, 0.00, -0.46, -6.81, -1.98, 0.00, 30.85, 30.65 -CTUN, 1000, 1.26, 5.54, 0.000000, 0, 0, -11, 1000, 0 -ATT, 0.00, -0.42, -6.72, -1.92, 0.00, 31.88, 30.65 -CTUN, 999, 1.26, 5.48, 0.000000, 0, 0, -8, 999, 0 -DU32, 7, 166140 -CURR, 979, 2737595, 946, 2302, 5051, 2036.258400 -ATT, 0.00, -0.51, -6.81, -2.20, 0.00, 32.83, 30.65 -CTUN, 944, 1.26, 5.49, 0.000000, 0, 0, -11, 946, 0 -ATT, 0.00, -0.35, -6.16, -2.59, 0.00, 33.68, 30.65 -CTUN, 954, 1.26, 5.56, 0.000000, 0, 0, -9, 954, 0 -ATT, 1.03, -0.36, -4.57, -2.43, 0.00, 34.45, 30.65 -CTUN, 993, 1.28, 5.58, 0.000000, 0, 0, -12, 984, 0 -ATT, 2.81, -0.49, -3.26, -1.62, 0.00, 35.21, 30.65 -CTUN, 999, 1.28, 5.59, 0.000000, 0, 0, -10, 999, 0 -ATT, 6.37, 0.70, -2.14, -0.44, 0.00, 36.00, 30.65 -CTUN, 1000, 1.28, 5.57, 0.000000, 0, 0, -15, 1000, 0 -ATT, 7.50, 3.10, -2.24, 0.73, 0.00, 36.67, 30.65 -CTUN, 1000, 1.28, 5.66, 0.000000, 0, 0, -20, 1000, 0 -ATT, 7.40, 5.74, -2.24, 1.30, 0.00, 37.27, 30.65 -CTUN, 1000, 1.28, 5.64, 0.000000, 0, 0, -27, 1000, 0 -ATT, 6.28, 7.36, -2.14, 1.25, 0.00, 37.63, 30.65 -CTUN, 1000, 1.27, 5.70, 0.000000, 0, 0, -34, 1000, 0 -ATT, 1.31, 7.44, -2.24, 0.59, 0.00, 37.75, 30.65 -CTUN, 1000, 1.27, 5.52, 0.000000, 0, 0, -41, 1000, 0 -ATT, 0.00, 5.57, -2.05, -0.40, 0.00, 37.59, 30.65 -CTUN, 999, 1.23, 5.61, 0.000000, 0, 0, -46, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2747472, 939, 2316, 5028, 2042.300800 -ATT, 0.00, 2.31, -1.68, -1.19, 0.00, 37.18, 30.65 -CTUN, 999, 1.23, 5.47, 0.000000, 0, 0, -42, 999, 0 -ATT, 0.00, 0.31, -2.52, -0.91, 0.00, 36.58, 30.65 -CTUN, 1000, 1.17, 5.41, 0.000000, 0, 0, -39, 1000, 0 -ATT, -0.94, 0.18, -2.70, 0.04, 0.00, 35.56, 30.65 -CTUN, 1000, 1.17, 5.33, 0.000000, 0, 0, -39, 1000, 0 -ATT, -5.49, 0.28, -2.61, 0.61, 0.00, 34.24, 30.65 -CTUN, 1000, 1.02, 5.24, 0.000000, 0, 0, -38, 1000, 0 -ATT, -6.72, -0.89, -2.70, 0.70, 0.00, 32.82, 30.65 -CTUN, 1000, 1.02, 5.22, 0.000000, 0, 0, -37, 1000, 0 -ATT, -6.72, -3.47, -2.61, 0.36, 0.00, 31.27, 30.65 -CTUN, 1000, 0.94, 5.17, 0.000000, 0, 0, -29, 1000, 0 -ATT, -6.91, -5.51, -2.61, 0.02, 0.00, 29.97, 30.65 -CTUN, 1000, 0.94, 5.16, 0.000000, 0, 0, -23, 1000, 0 -ATT, -6.63, -6.48, -2.70, 0.08, 0.00, 29.03, 30.65 -CTUN, 1000, 0.75, 5.19, 0.000000, 0, 0, -16, 1000, 0 -ATT, -6.25, -6.65, -2.61, 0.39, 0.00, 28.59, 30.65 -CTUN, 1000, 0.75, 5.04, 0.000000, 0, 1, -14, 1000, 0 -ATT, -1.42, -6.40, -3.08, 0.40, 0.00, 28.77, 30.65 -CTUN, 1000, 0.68, 5.16, 0.000000, 0, 1, -6, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2757469, 925, 2566, 5051, 2049.138200 -ATT, 0.00, -4.59, -3.26, 0.30, 0.00, 29.49, 30.65 -CTUN, 1000, 0.68, 5.23, 0.000000, 0, 0, -7, 1000, 0 -ATT, 0.00, -1.06, -2.42, 0.37, 0.00, 30.58, 30.65 -CTUN, 999, 0.68, 5.19, 0.000000, 0, 0, -8, 999, 0 -ATT, 0.00, 1.37, -2.42, 0.14, 4.32, 31.93, 31.57 -CTUN, 999, 0.77, 5.14, 0.000000, 0, 0, -10, 999, 0 -ATT, 0.00, 1.77, -2.52, -0.42, 7.88, 33.64, 34.39 -CTUN, 1000, 0.77, 5.23, 0.000000, 0, 0, -8, 1000, 0 -ATT, 0.00, 1.69, -2.52, -0.90, 9.51, 36.04, 38.41 -CTUN, 1000, 0.89, 5.12, 0.000000, 0, 0, 0, 999, 0 -ATT, 0.00, 1.87, -2.52, -0.89, 10.96, 39.27, 43.04 -CTUN, 1000, 0.89, 5.13, 0.000000, 0, 0, 9, 1000, 0 -ATT, 0.00, 2.00, -2.52, -0.46, 10.96, 43.26, 47.92 -CTUN, 1000, 0.89, 5.00, 0.000000, 0, 0, 17, 999, 0 -ATT, 0.00, 1.96, -2.52, -0.18, 11.15, 48.06, 52.83 -CTUN, 1000, 0.89, 5.05, 0.000000, 0, 0, 24, 1000, 0 -ATT, 0.00, 1.72, -2.52, -0.11, 9.51, 53.42, 57.42 -CTUN, 1000, 0.91, 5.15, 0.000000, 0, 0, 30, 999, 0 -ATT, 0.00, 1.25, -3.26, -0.29, 8.26, 59.24, 61.50 -CTUN, 946, 0.91, 5.17, 0.000000, 0, 0, 30, 977, 0 -DU32, 7, 166140 -CURR, 946, 2767466, 935, 2323, 5051, 2056.042000 -ATT, 0.00, 0.68, -3.26, -0.60, 7.30, 65.17, 64.80 -CTUN, 907, 0.91, 5.22, 0.000000, 0, 0, 29, 909, 0 -ATT, 0.00, 0.77, -3.26, -1.22, 5.09, 70.81, 67.51 -CTUN, 860, 0.91, 5.28, 0.000000, 0, 0, 19, 871, 0 -ATT, 0.00, 1.25, -3.26, -1.67, 0.00, 75.75, 68.13 -CTUN, 832, 0.91, 5.34, 0.000000, 0, 0, 5, 843, 0 -ATT, 0.00, 1.39, -3.08, -2.01, 0.00, 79.60, 69.60 -CTUN, 823, 0.91, 5.23, 0.000000, 0, 0, -11, 823, 0 -ATT, 0.00, 1.32, -2.70, -2.35, 0.00, 82.52, 72.52 -CTUN, 884, 0.93, 5.33, 0.000000, 0, 0, -28, 884, 0 -ATT, 0.00, 0.86, -2.52, -2.18, 0.00, 84.68, 74.68 -CTUN, 973, 0.91, 5.28, 0.000000, 0, 0, -42, 946, 0 -ATT, 0.00, 0.40, -2.52, -1.65, 0.00, 86.43, 76.43 -CTUN, 1000, 0.91, 5.38, 0.000000, 0, 0, -58, 1000, 0 -ATT, 0.00, -0.09, -2.24, -1.02, 0.00, 87.87, 77.87 -CTUN, 1000, 0.85, 5.43, 0.000000, 0, 0, -71, 1000, 0 -ATT, 0.00, -0.48, -2.24, -0.61, 0.00, 89.10, 79.10 -CTUN, 1000, 0.85, 5.38, 0.000000, 0, 0, -80, 1000, 0 -ATT, 0.00, -0.23, -2.24, 0.22, 0.00, 89.94, 79.94 -CTUN, 1000, 0.75, 5.15, 0.000000, 0, 0, -88, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2776727, 962, 1893, 5051, 2061.313500 -ATT, -3.97, 0.03, -1.30, 0.59, 0.00, 90.41, 80.41 -CTUN, 1000, 0.75, 4.94, 0.000000, 0, 0, -100, 1000, 0 -ATT, -7.67, -0.99, 0.00, 0.20, 0.00, 90.52, 80.55 -CTUN, 1000, 0.72, 4.84, 0.000000, 0, 0, -103, 1000, 0 -ATT, -8.81, -3.68, 0.37, 0.50, 0.00, 90.18, 80.55 -CTUN, 1000, 0.72, 4.78, 0.000000, 0, 0, -101, 1000, 0 -ATT, -12.97, -6.19, 8.02, 2.07, 0.00, 89.27, 80.55 -CTUN, 1000, 0.52, 4.75, 0.000000, 0, 0, -101, 1000, 0 -ATT, -12.78, -8.40, 9.14, 5.14, 0.00, 87.78, 80.55 -CTUN, 1000, 0.52, 4.55, 0.000000, 0, 0, -96, 1000, 0 -ATT, -7.48, -9.88, 4.20, 9.06, 0.00, 86.10, 80.55 -CTUN, 1000, 0.31, 4.04, 0.000000, 0, 0, -96, 1000, 0 -ATT, -4.54, -9.00, 0.56, 11.49, 0.00, 84.74, 80.55 -CTUN, 1000, 0.31, 1.15, 0.000000, 0, 0, -47, 1000, 0 -ATT, -1.80, -2.36, 0.00, -4.70, 0.00, 85.43, 80.55 -CTUN, 1000, 0.31, 0.58, 0.000000, 0, 0, 36, 1000, 0 -ATT, 0.00, 1.49, -1.58, 1.29, 0.00, 84.54, 80.55 -CTUN, 1000, 1.97, 2.15, 0.000000, 0, 0, 21, 1000, 0 -ATT, 0.00, 2.02, -3.26, 4.71, 0.00, 83.56, 80.55 -CTUN, 1000, 0.75, 1.83, 0.000000, 0, 1, 15, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2786726, 920, 2549, 5028, 2067.000000 -ATT, 0.00, -0.59, -2.61, 2.61, 0.00, 82.39, 80.55 -CTUN, 1000, 0.75, 2.06, 0.000000, 0, 0, 28, 1000, 0 -ATT, 0.00, -1.98, -2.52, 0.02, 0.00, 81.49, 80.55 -CTUN, 1000, 0.21, 3.26, 0.000000, 0, 0, 45, 1000, 0 -ATT, 0.00, -0.93, 0.00, -0.34, 0.00, 80.86, 80.55 -CTUN, 1000, 0.21, 3.93, 0.000000, 0, 0, 56, 1000, 0 -ATT, -3.97, 0.10, 0.00, 2.56, 0.00, 80.41, 80.55 -CTUN, 1000, 0.21, 4.44, 0.000000, 0, 0, 53, 1000, 0 -ATT, 0.00, -0.63, -2.24, 5.52, 0.00, 80.24, 80.55 -CTUN, 1000, 0.22, 4.38, 0.000000, 0, 0, 48, 1000, 0 -ATT, 0.00, -1.42, -3.26, 5.03, 0.00, 80.57, 80.55 -CTUN, 999, 0.22, 4.65, 0.000000, 0, 1, 41, 1000, 0 -ATT, 0.00, -1.76, -5.69, 2.13, 0.00, 81.23, 80.55 -CTUN, 996, 0.31, 4.60, 0.000000, 0, 0, 37, 998, 0 -ATT, 0.00, -0.70, -6.53, -1.28, 0.00, 81.81, 80.55 -CTUN, 997, 0.31, 4.69, 0.000000, 0, 0, 38, 996, 0 -ATT, 0.00, 0.94, -6.53, -3.35, 0.00, 82.19, 80.55 -CTUN, 1000, 0.41, 4.71, 0.000000, 0, 0, 29, 1000, 0 -ATT, 0.00, 0.68, -6.34, -4.65, 0.00, 82.47, 80.55 -CTUN, 999, 0.41, 4.81, 0.000000, 0, 0, 28, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2796722, 935, 2402, 5051, 2073.595500 -ATT, 0.00, -0.97, -6.81, -5.65, 0.00, 82.67, 80.55 -CTUN, 1000, 0.48, 4.79, 0.000000, 0, 0, 26, 1000, 0 -ATT, 0.00, -2.01, -8.12, -6.17, 0.00, 82.71, 80.55 -CTUN, 999, 0.48, 4.81, 0.000000, 0, 0, 24, 1000, 0 -ATT, -0.85, -1.45, -8.21, -6.05, 0.00, 82.66, 80.55 -CTUN, 1000, 0.54, 4.80, 0.000000, 0, 0, 20, 1000, 0 -ATT, -3.50, -0.51, -7.56, -5.38, 0.00, 82.50, 80.55 -CTUN, 999, 0.54, 5.03, 0.000000, 0, 0, 18, 1000, 0 -ATT, -4.16, -2.23, -4.10, -4.82, 0.00, 82.27, 80.55 -CTUN, 1000, 0.60, 4.84, 0.000000, 0, 1, 16, 1000, 0 -ATT, -5.58, -4.53, -3.36, -4.83, 0.00, 81.93, 80.55 -CTUN, 999, 0.60, 4.93, 0.000000, 0, 0, 18, 1000, 0 -ATT, -6.25, -5.77, -2.42, -3.62, 0.00, 81.42, 80.55 -CTUN, 1000, 0.64, 5.06, 0.000000, 0, 1, 17, 1000, 0 -ATT, -6.53, -6.17, -2.42, -0.49, 0.00, 80.76, 80.55 -CTUN, 999, 0.64, 5.00, 0.000000, 0, 0, 13, 1000, 0 -ATT, -5.11, -6.75, -2.42, 1.96, 0.00, 80.25, 80.55 -CTUN, 1000, 0.69, 4.97, 0.000000, 0, 1, 7, 1000, 0 -ATT, -2.55, -6.64, -2.52, 2.40, 0.00, 80.10, 80.55 -CTUN, 999, 0.69, 5.07, 0.000000, 0, 0, 4, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2806722, 934, 2391, 5028, 2080.121800 -ATT, -0.85, -5.45, -3.26, 2.08, 0.00, 80.29, 80.55 -CTUN, 1000, 0.71, 5.06, 0.000000, 0, 0, 0, 1000, 0 -ATT, 0.00, -3.71, -4.38, 1.87, 0.00, 80.69, 80.55 -CTUN, 1000, 0.71, 5.17, 0.000000, 0, 0, -5, 1000, 0 -ATT, 0.00, -2.30, -4.57, 1.44, 0.00, 81.22, 80.55 -CTUN, 1000, 0.73, 5.09, 0.000000, 0, 0, -15, 1000, 0 -ATT, 0.00, -1.57, -3.45, -0.13, 0.00, 81.86, 80.55 -CTUN, 1000, 0.72, 5.12, 0.000000, 0, 0, -16, 1000, 0 -ATT, 0.00, -1.32, -2.61, -1.35, 0.00, 82.42, 80.55 -CTUN, 1000, 0.72, 5.22, 0.000000, 0, 0, -20, 1000, 0 -ATT, 0.00, -1.59, -2.70, -1.44, 0.00, 83.03, 80.55 -CTUN, 1000, 0.71, 5.03, 0.000000, 0, 0, -23, 1000, 0 -ATT, 0.46, -2.30, -2.42, -1.45, 0.00, 83.83, 80.55 -CTUN, 999, 0.71, 4.98, 0.000000, 0, 0, -26, 1000, 0 -ATT, 1.40, -3.15, -2.42, -1.61, 0.00, 84.66, 80.55 -CTUN, 1000, 0.69, 5.07, 0.000000, 0, 0, -28, 1000, 0 -ATT, 1.78, -3.07, -2.70, -1.86, 0.00, 85.62, 80.55 -CTUN, 1000, 0.69, 5.08, 0.000000, 0, 0, -30, 1000, 0 -ATT, 2.34, -1.95, -2.70, -2.08, -2.73, 86.46, 79.98 -CTUN, 1000, 0.66, 5.02, 0.000000, 0, 0, -36, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2816722, 946, 2039, 5051, 2086.430200 -ATT, 2.90, -0.81, -2.70, -2.24, -3.30, 86.93, 78.54 -CTUN, 1000, 0.66, 4.95, 0.000000, 0, 0, -45, 1000, 0 -ATT, 3.75, 0.11, -2.52, -2.33, -4.33, 86.72, 76.78 -CTUN, 1000, 0.61, 4.88, 0.000000, 0, 0, -55, 1000, 0 -ATT, 5.43, 0.61, -2.70, -2.29, -4.43, 85.81, 75.81 -CTUN, 1000, 0.61, 4.76, 0.000000, 0, 0, -61, 1000, 0 -ATT, 5.34, 1.36, -2.61, -2.02, -4.43, 84.29, 74.29 -CTUN, 1000, 0.53, 4.65, 0.000000, 0, 0, -69, 1000, 0 -ATT, 5.43, 2.55, -3.08, -1.76, -4.52, 82.24, 72.30 -CTUN, 1000, 0.53, 4.78, 0.000000, 0, 0, -77, 1000, 0 -ATT, 5.06, 3.71, -3.92, -0.81, -4.52, 79.75, 70.19 -CTUN, 1000, 0.42, 4.75, 0.000000, 0, 0, -83, 1000, 0 -ATT, 4.96, 4.11, -4.38, 0.20, -4.43, 76.90, 68.13 -PM, 0, 0, 0, 0, 1000, 10480, 0, 0 -CTUN, 1000, 0.42, 4.43, 0.000000, 0, 0, -90, 1000, 0 -ATT, 3.75, 3.86, -5.69, -0.04, -4.33, 73.64, 66.13 -CTUN, 1000, 0.28, 3.93, 0.000000, 0, 1, -85, 1000, 0 -ATT, 3.18, 4.24, -7.65, -0.94, -3.39, 70.19, 64.35 -CTUN, 1000, 0.28, 2.20, 0.000000, 0, 0, -73, 1000, 0 -ATT, 0.65, 4.33, -10.92, -2.50, -2.73, 66.74, 62.96 -CTUN, 1000, 0.21, -0.58, 0.000000, 0, 0, -36, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2826721, 923, 2428, 5028, 2092.365700 -ATT, 0.00, -1.57, -10.82, -0.55, -2.07, 62.73, 61.82 -CTUN, 1000, 0.23, -1.41, 0.000000, 0, 0, 7, 1000, 0 -ATT, 0.09, 0.22, -10.82, -1.58, -1.98, 59.97, 60.91 -CTUN, 1000, 0.21, -0.10, 0.000000, 0, 0, 18, 1000, 0 -ATT, 0.00, -0.18, -10.82, -1.93, -1.79, 57.31, 60.04 -CTUN, 1000, 0.21, 1.38, 0.000000, 0, 0, 33, 1000, 0 -ATT, 0.00, 0.52, -10.64, -3.32, -1.79, 55.06, 59.14 -CTUN, 1000, 0.21, 2.60, 0.000000, 0, 1, 46, 1000, 0 -ATT, 0.00, 2.02, -10.64, -4.19, -1.22, 53.28, 58.37 -CTUN, 1000, 0.21, 4.34, 0.000000, 0, 0, 53, 1000, 0 -ATT, 0.00, 2.24, -10.82, -4.89, 0.00, 51.92, 58.31 -CTUN, 1000, 0.21, 4.51, 0.000000, 0, 1, 62, 1000, 0 -ATT, 0.00, 1.90, -12.88, -5.19, 0.00, 51.24, 58.31 -CTUN, 1000, 0.25, 4.55, 0.000000, 0, 0, 67, 1000, 0 -ATT, 0.00, 1.23, -14.28, -5.66, 0.00, 51.17, 58.31 -CTUN, 989, 0.25, 4.72, 0.000000, 0, 5, 72, 998, 0 -ATT, 0.00, 0.98, -14.56, -6.72, 0.00, 51.79, 58.31 -CTUN, 979, 0.43, 4.95, 0.000000, 0, 7, 73, 986, 0 -ATT, 0.00, 0.69, -14.37, -8.52, 0.00, 52.98, 58.31 -CTUN, 930, 0.43, 5.04, 0.000000, 0, 10, 73, 941, 0 -DU32, 7, 166140 -CURR, 930, 2836657, 911, 2610, 5051, 2099.576900 -ATT, 0.00, 0.53, -12.97, -9.61, 0.00, 54.27, 58.31 -CTUN, 906, 0.64, 5.02, 0.000000, 0, 10, 74, 916, 0 -ATT, 0.00, 0.39, -11.57, -8.91, 0.00, 55.64, 58.31 -CTUN, 804, 0.64, 5.22, 0.000000, 0, 6, 76, 833, 0 -ATT, 0.00, -0.42, -11.01, -7.04, 0.00, 56.79, 58.31 -CTUN, 746, 0.84, 5.28, 0.000000, 0, 3, 68, 758, 0 -ATT, 0.00, -1.12, -8.12, -5.60, 0.00, 57.77, 58.31 -CTUN, 740, 0.84, 5.41, 0.000000, 0, 2, 55, 742, 0 -ATT, 0.00, -1.84, -6.53, -5.31, 0.00, 58.65, 58.31 -CTUN, 740, 1.04, 5.49, 0.000000, 0, 2, 36, 741, 0 -ATT, 0.00, -1.30, -5.32, -5.08, 0.00, 59.58, 58.31 -CTUN, 759, 1.04, 5.62, 0.000000, 0, 1, 16, 760, 0 -ATT, 0.00, -0.53, -3.73, -3.73, 0.00, 60.59, 58.31 -CTUN, 828, 1.19, 5.61, 0.000000, 0, 0, 6, 821, 0 -ATT, 0.00, -0.02, -2.70, -2.27, 0.00, 61.48, 58.31 -CTUN, 855, 1.19, 5.87, 0.000000, 0, 0, 0, 855, 0 -ATT, 0.00, 0.96, -2.42, -0.80, 0.00, 62.16, 58.31 -CTUN, 898, 1.27, 5.82, 0.000000, 0, 0, -5, 892, 0 -ATT, 0.00, 1.64, -2.70, 0.61, 0.00, 62.60, 58.31 -CTUN, 911, 1.27, 5.86, 0.000000, 0, 0, -11, 911, 0 -DU32, 7, 166140 -CURR, 911, 2844885, 942, 2141, 5051, 2105.249000 -ATT, 0.00, 1.76, -2.61, 1.39, 0.00, 62.79, 58.31 -CTUN, 918, 1.31, 5.87, 0.000000, 0, 0, -15, 915, 0 -ATT, -0.18, 1.70, -2.52, 1.66, 0.00, 62.63, 58.31 -CTUN, 925, 1.27, 5.83, 0.000000, 0, 0, -15, 924, 0 -ATT, -0.94, 1.85, -2.70, 1.93, 0.00, 62.20, 58.31 -CTUN, 925, 1.27, 5.72, 0.000000, 0, 0, -21, 923, 0 -ATT, -2.46, 1.73, -2.42, 2.17, 0.00, 61.66, 58.31 -CTUN, 936, 1.26, 5.78, 0.000000, 0, 0, -23, 932, 0 -ATT, -4.35, 0.82, -2.52, 2.36, 0.00, 61.02, 58.31 -CTUN, 965, 1.26, 5.82, 0.000000, 0, 0, -23, 955, 0 -ATT, -4.73, -0.62, -2.42, 2.27, 0.00, 60.34, 58.31 -CTUN, 990, 1.18, 5.72, 0.000000, 0, 0, -23, 989, 0 -ATT, -5.87, -1.71, -2.70, 1.95, 0.00, 59.65, 58.31 -CTUN, 1000, 1.18, 5.77, 0.000000, 0, 0, -26, 1000, 0 -ATT, -46.04, -3.02, -2.42, 1.69, 0.00, 58.95, 58.31 -CTUN, 1000, 1.06, 5.77, 0.000000, 0, 0, -23, 1000, 0 -ATT, -1.13, -4.46, -1.12, 1.32, 0.00, 58.38, 58.31 -CTUN, 1000, 1.06, 5.81, 0.000000, 0, 0, -25, 1000, 0 -ATT, 0.00, -3.22, -2.70, 0.90, 0.00, 57.96, 58.31 -CTUN, 1000, 1.05, 5.81, 0.000000, 0, 0, -22, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2854495, 932, 2316, 5051, 2111.657200 -ATT, 0.00, -0.41, -3.17, 0.78, 0.00, 57.68, 58.31 -CTUN, 996, 1.05, 5.82, 0.000000, 0, 0, -22, 996, 0 -ATT, 0.00, 0.64, -3.26, 0.41, 0.00, 57.69, 58.31 -CTUN, 999, 1.04, 5.83, 0.000000, 0, 0, -21, 999, 0 -ATT, 0.00, 0.62, -3.45, -0.48, 0.00, 57.89, 58.31 -CTUN, 998, 1.05, 5.81, 0.000000, 0, 0, -17, 1000, 0 -ATT, 0.00, 1.07, -3.92, -1.62, 0.00, 58.41, 58.31 -CTUN, 997, 1.05, 5.79, 0.000000, 0, 0, -16, 997, 0 -ATT, 0.00, 1.35, -4.20, -2.21, 0.00, 59.28, 58.31 -CTUN, 997, 1.05, 5.75, 0.000000, 0, 0, -14, 997, 0 -ATT, 0.00, 0.86, -4.38, -2.37, 0.00, 60.45, 58.31 -CTUN, 992, 1.05, 5.88, 0.000000, 0, 0, -16, 993, 0 -ATT, 0.00, 0.03, -4.20, -2.28, 0.00, 61.54, 58.31 -CTUN, 990, 1.14, 5.84, 0.000000, 0, 0, -19, 990, 0 -ATT, 0.00, -0.48, -2.52, -2.18, 0.00, 62.67, 58.31 -CTUN, 990, 1.14, 5.93, 0.000000, 0, 0, -24, 990, 0 -ATT, 0.00, -0.95, -2.52, -2.03, 0.00, 63.63, 58.31 -CTUN, 990, 1.15, 5.84, 0.000000, 0, 0, -25, 990, 0 -ATT, 0.00, -1.15, -2.42, -1.46, 0.00, 64.33, 58.31 -CTUN, 990, 1.15, 5.79, 0.000000, 0, 0, -32, 990, 0 -DU32, 7, 166140 -CURR, 990, 2864437, 945, 2069, 5028, 2117.890100 -ATT, 0.00, -0.95, -2.70, -0.97, 0.00, 64.78, 58.31 -CTUN, 1000, 1.21, 5.65, 0.000000, 0, 0, -37, 1000, 0 -ATT, -3.31, -1.12, -3.26, -1.16, 0.00, 64.94, 58.31 -CTUN, 1000, 1.18, 5.60, 0.000000, 0, 0, -47, 999, 0 -ATT, -6.91, -2.04, -4.10, -1.81, 0.00, 64.87, 58.31 -CTUN, 1000, 1.18, 5.66, 0.000000, 0, 0, -51, 1000, 0 -ATT, -6.63, -4.34, -6.53, -2.46, 0.00, 64.72, 58.31 -CTUN, 1000, 1.14, 5.58, 0.000000, 0, 1, -59, 1000, 0 -ATT, -6.63, -6.62, -6.53, -3.46, 0.00, 64.52, 58.31 -CTUN, 1000, 1.14, 5.46, 0.000000, 0, 0, -64, 1000, 0 -ATT, -6.44, -7.12, -7.74, -4.66, 0.00, 64.21, 58.31 -CTUN, 1000, 1.04, 5.46, 0.000000, 0, 1, -65, 1000, 0 -ATT, -4.26, -6.37, -7.65, -5.35, 0.00, 63.75, 58.31 -CTUN, 1000, 1.04, 5.33, 0.000000, 0, 0, -70, 1000, 0 -ATT, -1.23, -5.03, -7.84, -5.27, 0.00, 63.03, 58.31 -CTUN, 1000, 0.90, 5.19, 0.000000, 0, 1, -76, 1000, 0 -ATT, -0.18, -2.45, -7.84, -4.42, 0.00, 62.19, 58.31 -CTUN, 1000, 0.90, 5.19, 0.000000, 0, 0, -80, 1000, 0 -ATT, 0.00, 0.37, -7.56, -3.50, 0.00, 61.25, 58.31 -CTUN, 1000, 0.73, 5.00, 0.000000, 0, 1, -87, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2874437, 949, 2056, 5051, 2123.841100 -ATT, 0.00, 2.40, -6.81, -2.37, 0.00, 60.28, 58.31 -CTUN, 1000, 0.73, 4.94, 0.000000, 0, 0, -90, 1000, 0 -ATT, 0.00, 2.99, -5.88, -1.47, 0.00, 59.45, 58.31 -CTUN, 1000, 0.55, 4.67, 0.000000, 0, 1, -94, 1000, 0 -ATT, 0.00, 2.39, -5.69, -0.68, 0.00, 58.80, 58.31 -CTUN, 999, 0.55, 4.79, 0.000000, 0, 0, -95, 1000, 0 -ATT, 0.00, 1.06, -6.16, 0.24, 0.00, 58.19, 58.31 -CTUN, 1000, 0.35, 4.28, 0.000000, 0, 0, -92, 999, 0 -ATT, 0.00, 0.69, -6.81, 0.36, 0.00, 57.75, 58.31 -CTUN, 1000, 0.35, 2.04, 0.000000, 0, 0, -85, 1000, 0 -ATT, -0.85, 1.79, -7.46, -0.67, 0.00, 57.44, 58.31 -CTUN, 999, 0.20, -1.20, 0.000000, 0, 0, 15, 1000, 0 -ATT, -0.85, 0.50, -7.84, -1.28, 0.00, 57.02, 58.31 -CTUN, 1000, 0.35, -0.07, 0.000000, 0, 0, 52, 1000, 0 -ATT, -0.94, -1.00, -7.84, -2.02, 0.00, 56.27, 58.31 -CTUN, 1000, 0.26, 2.13, 0.000000, 0, 0, 65, 1000, 0 -ATT, -0.85, -3.15, -7.56, -1.93, 0.00, 55.65, 58.31 -CTUN, 1000, 0.26, 4.41, 0.000000, 0, 0, 72, 1000, 0 -ATT, -1.23, -3.54, -7.56, -2.19, 0.00, 55.50, 58.31 -CTUN, 999, 0.22, 4.65, 0.000000, 0, 0, 78, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2884437, 916, 2473, 5051, 2130.398200 -ATT, -1.23, -3.17, -7.18, -3.12, 0.00, 55.55, 58.31 -CTUN, 1000, 0.26, 4.68, 0.000000, 0, 0, 81, 1000, 0 -ATT, -1.23, -3.87, -6.81, -4.39, 0.00, 55.55, 58.31 -CTUN, 999, 0.26, 4.94, 0.000000, 0, 0, 84, 1000, 0 -ATT, 0.00, -4.85, -7.09, -4.29, 0.00, 55.40, 58.31 -CTUN, 1000, 0.37, 4.84, 0.000000, 0, 0, 88, 1000, 0 -ATT, 0.00, -4.94, -6.25, -3.63, 0.00, 55.11, 58.31 -CTUN, 942, 0.37, 5.08, 0.000000, 0, 4, 86, 976, 0 -ATT, 0.00, -3.45, -5.78, -3.45, 0.00, 54.66, 58.31 -CTUN, 889, 0.56, 5.16, 0.000000, 0, 2, 85, 891, 0 -ATT, 0.00, -2.05, -4.76, -3.56, 0.00, 54.25, 58.31 -CTUN, 846, 0.56, 5.34, 0.000000, 0, 1, 88, 847, 0 -ATT, 0.00, -2.57, -2.52, -3.72, 0.00, 53.98, 58.31 -CTUN, 870, 0.73, 5.33, 0.000000, 0, 2, 83, 857, 0 -ATT, 0.09, -2.48, -2.42, -3.48, 0.00, 54.28, 58.31 -CTUN, 877, 0.73, 5.41, 0.000000, 0, 1, 77, 880, 0 -ATT, 2.81, -1.70, -2.42, -2.51, 0.00, 55.01, 58.31 -CTUN, 821, 0.93, 5.58, 0.000000, 0, 0, 77, 830, 0 -ATT, 6.28, -0.78, -2.52, -1.10, 0.00, 56.22, 58.31 -CTUN, 798, 0.93, 5.59, 0.000000, 0, 0, 70, 802, 0 -DU32, 7, 166140 -CURR, 798, 2893559, 937, 2055, 5051, 2137.215600 -ATT, 7.40, 1.12, -2.42, 0.15, 0.00, 57.77, 58.31 -CTUN, 796, 1.07, 5.59, 0.000000, 0, 0, 60, 798, 0 -ATT, 7.40, 3.66, -2.52, 0.26, 0.00, 59.77, 58.31 -CTUN, 798, 1.07, 5.65, 0.000000, 0, 2, 49, 800, 0 -ATT, 7.68, 5.26, -2.52, -0.26, 0.00, 61.92, 58.31 -CTUN, 800, 1.22, 5.65, 0.000000, 0, 3, 38, 801, 0 -ATT, 7.31, 6.15, -2.52, -0.77, 0.00, 63.72, 58.31 -CTUN, 816, 1.22, 5.69, 0.000000, 0, 4, 31, 813, 0 -ATT, 6.75, 6.77, -2.52, -1.12, 0.00, 65.09, 58.31 -CTUN, 864, 1.23, 5.67, 0.000000, 0, 5, 20, 860, 0 -ATT, 6.09, 6.89, -2.52, -1.35, 0.00, 66.12, 58.31 -CTUN, 918, 1.23, 5.82, 0.000000, 0, 5, 10, 923, 0 -ATT, 6.37, 6.24, -2.52, -1.63, 0.00, 66.77, 58.31 -CTUN, 946, 1.23, 5.78, 0.000000, 0, 4, 2, 949, 0 -ATT, 5.90, 5.70, -2.42, -1.92, 0.00, 67.13, 58.31 -CTUN, 946, 1.23, 5.79, 0.000000, 0, 4, -3, 950, 0 -ATT, 1.87, 5.30, -2.42, -2.07, 0.00, 67.31, 58.31 -CTUN, 947, 1.23, 5.72, 0.000000, 0, 3, -7, 950, 0 -ATT, 0.09, 3.51, -2.42, -1.95, 0.00, 67.37, 58.31 -CTUN, 957, 1.23, 5.86, 0.000000, 0, 0, -16, 950, 0 -DU32, 7, 166140 -CURR, 957, 2902293, 933, 2170, 5051, 2142.997100 -ATT, 0.00, 0.45, -2.52, -1.65, 0.00, 67.32, 58.31 -CTUN, 982, 1.29, 5.89, 0.000000, 0, 0, -18, 982, 0 -ATT, 0.00, -1.59, -2.42, -1.16, 0.00, 67.02, 58.31 -CTUN, 1000, 1.29, 5.92, 0.000000, 0, 0, -19, 1000, 0 -ATT, 0.00, -1.80, -2.52, -0.51, 0.00, 66.49, 58.31 -CTUN, 1000, 1.34, 5.87, 0.000000, 0, 0, -23, 1000, 0 -ATT, 0.00, -1.65, -2.42, -0.14, 0.00, 65.87, 58.31 -CTUN, 999, 1.32, 5.84, 0.000000, 0, 0, -28, 1000, 0 -ATT, 0.00, -1.49, -2.42, -0.25, 0.00, 65.23, 58.31 -CTUN, 1000, 1.32, 5.86, 0.000000, 0, 0, -27, 999, 0 -ATT, 0.00, -0.95, -2.52, -0.61, 0.00, 64.57, 58.31 -CTUN, 1000, 1.29, 5.79, 0.000000, 0, 0, -26, 999, 0 -ATT, 0.00, -0.30, -2.52, -0.80, 0.00, 63.90, 58.31 -CTUN, 1000, 1.29, 5.65, 0.000000, 0, 0, -28, 1000, 0 -ATT, 0.00, -0.46, -2.42, -0.91, 0.00, 63.35, 58.31 -CTUN, 999, 1.26, 5.76, 0.000000, 0, 0, -29, 1000, 0 -ATT, 0.00, -1.48, -2.52, -1.53, 0.00, 63.01, 58.31 -CTUN, 1000, 1.26, 5.72, 0.000000, 0, 0, -27, 1000, 0 -ATT, 0.00, -1.88, -2.52, -2.19, 0.00, 62.79, 58.31 -CTUN, 1000, 1.20, 5.77, 0.000000, 0, 0, -24, 1000, 0 -DU32, 7, 166140 -CURR, 999, 2912262, 922, 2391, 5028, 2149.382800 -ATT, 0.00, -1.63, -2.52, -2.49, 0.00, 62.73, 58.31 -CTUN, 1000, 1.20, 5.71, 0.000000, 0, 1, -21, 1000, 0 -ATT, 0.00, -1.32, -2.52, -2.60, 0.00, 62.75, 58.31 -CTUN, 999, 1.15, 5.66, 0.000000, 0, 0, -19, 1000, 0 -ATT, 0.00, -0.96, -2.52, -2.66, 0.00, 62.83, 58.31 -CTUN, 1000, 1.15, 5.59, 0.000000, 0, 1, -19, 1000, 0 -ATT, 2.43, -0.78, -2.70, -2.63, 0.00, 62.89, 58.31 -CTUN, 1000, 1.09, 5.61, 0.000000, 0, 0, -21, 1000, 0 -ATT, 3.18, 0.21, -2.61, -2.50, 0.00, 62.96, 58.31 -CTUN, 1000, 1.09, 5.53, 0.000000, 0, 0, -20, 1000, 0 -ATT, 4.50, 2.22, -2.42, -2.31, 0.00, 62.99, 58.31 -CTUN, 1000, 1.03, 5.54, 0.000000, 0, 0, -23, 1000, 0 -ATT, 7.12, 4.09, -2.24, -2.34, 0.00, 63.04, 58.31 -PM, 0, 0, 0, 0, 1000, 10496, 0, 0 -CTUN, 1000, 1.03, 5.55, 0.000000, 0, 0, -25, 1000, 0 -ATT, 7.31, 5.60, -2.52, -2.46, 0.00, 63.04, 58.31 -CTUN, 1000, 0.95, 5.49, 0.000000, 0, 0, -25, 1000, 0 -ATT, 7.21, 6.80, -2.24, -2.56, 0.00, 62.92, 58.31 -CTUN, 1000, 0.95, 5.55, 0.000000, 0, 0, -27, 1000, 0 -ATT, 3.93, 7.34, -2.24, -2.64, 0.00, 62.69, 58.31 -CTUN, 1000, 0.91, 5.50, 0.000000, 0, 0, -28, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2922261, 926, 2249, 5051, 2155.775600 -ATT, 0.00, 6.95, -2.33, -2.63, 0.00, 62.35, 58.31 -CTUN, 1000, 0.91, 5.43, 0.000000, 0, 0, -36, 1000, 0 -ATT, 0.00, 4.60, -2.52, -2.66, 0.00, 61.92, 58.31 -CTUN, 1000, 0.83, 5.34, 0.000000, 0, 0, -34, 1000, 0 -ATT, 0.00, 1.17, -2.05, -2.43, 0.00, 61.30, 58.31 -CTUN, 999, 0.83, 5.25, 0.000000, 0, 0, -32, 1000, 0 -ATT, -1.42, -0.97, -1.40, -1.90, 0.00, 60.65, 58.31 -CTUN, 1000, 0.76, 5.22, 0.000000, 0, 0, -28, 1000, 0 -ATT, -3.12, -1.74, -1.40, -1.16, 0.00, 60.03, 58.31 -CTUN, 1000, 0.76, 5.14, 0.000000, 0, 0, -24, 1000, 0 -ATT, -3.22, -2.43, -1.40, -0.52, 0.00, 59.39, 58.31 -CTUN, 1000, 0.70, 5.32, 0.000000, 0, 0, -17, 1000, 0 -ATT, -1.61, -3.65, -1.58, 0.14, 0.00, 58.76, 58.31 -CTUN, 1000, 0.70, 5.25, 0.000000, 0, 0, -14, 1000, 0 -ATT, 0.00, -4.17, -2.52, 0.68, 0.00, 58.18, 58.31 -CTUN, 1000, 0.64, 5.09, 0.000000, 0, 1, -11, 1000, 0 -ATT, 0.00, -3.51, -2.52, 0.75, 0.00, 57.56, 58.31 -CTUN, 1000, 0.64, 5.14, 0.000000, 0, 0, -8, 1000, 0 -ATT, 0.00, -2.68, -2.52, 0.51, 0.00, 56.87, 58.31 -CTUN, 1000, 0.59, 5.08, 0.000000, 0, 0, -6, 999, 0 -DU32, 7, 166140 -CURR, 1000, 2932261, 910, 2616, 5051, 2162.749000 -ATT, 0.00, -2.33, -2.42, 0.20, 0.00, 56.14, 58.31 -CTUN, 1000, 0.59, 5.15, 0.000000, 0, 0, -1, 1000, 0 -ATT, 0.46, -1.92, -2.52, -0.10, 0.00, 55.44, 58.31 -CTUN, 999, 0.56, 5.04, 0.000000, 0, 0, 6, 1000, 0 -ATT, 1.68, -0.91, -2.42, -0.11, 0.00, 54.87, 58.31 -CTUN, 1000, 0.56, 5.14, 0.000000, 0, 0, 15, 999, 0 -ATT, 2.15, 0.47, -2.61, 0.19, 0.00, 54.34, 58.31 -CTUN, 1000, 0.56, 5.16, 0.000000, 0, 0, 20, 1000, 0 -ATT, 2.34, 1.46, -2.61, 0.57, 0.00, 53.84, 58.31 -CTUN, 1000, 0.57, 5.03, 0.000000, 0, 0, 28, 1000, 0 -ATT, 2.53, 1.96, -2.61, 0.82, 0.00, 53.40, 58.31 -CTUN, 1000, 0.57, 5.17, 0.000000, 0, 0, 34, 1000, 0 -ATT, 2.53, 2.43, -3.26, 0.54, 0.00, 53.02, 58.31 -CTUN, 1000, 0.58, 5.13, 0.000000, 0, 0, 38, 1000, 0 -ATT, 0.75, 2.65, -4.48, -0.03, 0.00, 52.89, 58.31 -CTUN, 1000, 0.58, 5.27, 0.000000, 0, 0, 44, 1000, 0 -ATT, 0.09, 2.24, -6.81, -1.10, 0.00, 52.88, 58.31 -CTUN, 1000, 0.64, 5.14, 0.000000, 0, 0, 49, 1000, 0 -ATT, 0.09, 1.50, -7.84, -3.00, 0.00, 52.93, 58.31 -CTUN, 986, 0.64, 5.25, 0.000000, 0, 2, 54, 992, 0 -DU32, 7, 166140 -CURR, 986, 2942258, 899, 2774, 5028, 2170.217500 -ATT, 0.09, 0.92, -8.30, -5.01, 0.00, 53.19, 58.31 -CTUN, 977, 0.72, 5.12, 0.000000, 0, 4, 62, 981, 0 -ATT, 0.09, 0.50, -7.93, -6.56, 0.00, 53.63, 58.31 -CTUN, 966, 0.72, 5.31, 0.000000, 0, 6, 68, 972, 0 -ATT, 0.00, 0.44, -7.28, -7.53, 0.00, 54.18, 58.31 -CTUN, 958, 0.82, 5.37, 0.000000, 0, 7, 74, 965, 0 -ATT, 0.09, 0.47, -3.17, -7.60, 0.00, 54.84, 58.31 -CTUN, 930, 0.82, 5.35, 0.000000, 0, 5, 80, 935, 0 -ATT, 0.00, 0.46, -2.42, -5.99, 0.00, 55.50, 58.31 -CTUN, 858, 0.95, 5.50, 0.000000, 0, 2, 84, 892, 0 -ATT, 0.00, 0.65, -2.14, -2.76, 0.00, 56.07, 58.31 -CTUN, 788, 0.95, 5.66, 0.000000, 0, 0, 85, 788, 0 -ATT, 0.00, 0.72, -2.24, -0.12, 0.00, 56.61, 58.31 -CTUN, 759, 1.11, 5.70, 0.000000, 0, 0, 78, 761, 0 -ATT, 0.00, 1.09, -2.52, 0.78, 0.00, 57.01, 58.31 -CTUN, 759, 1.11, 5.84, 0.000000, 0, 0, 61, 759, 0 -ATT, 0.00, 1.59, -3.08, 1.06, 0.00, 57.16, 58.31 -CTUN, 746, 1.26, 5.93, 0.000000, 0, 0, 44, 746, 0 -ATT, 0.00, 1.76, -3.26, 0.75, 0.00, 56.94, 58.31 -CTUN, 759, 1.26, 5.93, 0.000000, 0, 0, 26, 759, 0 -DU32, 7, 166140 -CURR, 791, 2950893, 947, 1739, 5051, 2176.537100 -ATT, 0.00, 1.46, -2.70, 0.01, 0.00, 56.26, 58.31 -CTUN, 871, 1.37, 5.97, 0.000000, 0, 0, 12, 871, 0 -ATT, 0.00, 0.86, -2.61, -1.07, 0.00, 55.28, 58.31 -CTUN, 946, 1.37, 6.07, 0.000000, 0, 0, 4, 938, 0 -ATT, 0.00, 0.39, -2.61, -1.52, 0.00, 54.20, 58.31 -CTUN, 982, 1.40, 6.02, 0.000000, 0, 0, 7, 982, 0 -ATT, 0.00, 0.61, -2.80, -0.93, 0.00, 53.25, 58.31 -CTUN, 979, 1.37, 6.07, 0.000000, 0, 0, 14, 979, 0 -ATT, 0.00, 1.10, -2.80, -0.01, 0.00, 52.53, 58.31 -CTUN, 953, 1.40, 5.92, 0.000000, 0, 0, 25, 965, 0 -ATT, 0.00, 1.34, -2.89, 0.57, 0.00, 52.14, 58.31 -CTUN, 870, 1.40, 6.07, 0.000000, 0, 0, 35, 908, 0 -ATT, 0.00, 1.08, -2.61, 1.08, 0.00, 52.01, 58.31 -CTUN, 753, 1.48, 6.17, 0.000000, 0, 0, 49, 764, 0 -ATT, 0.00, 0.93, -3.08, 1.45, 0.00, 52.11, 58.31 -CTUN, 680, 1.48, 6.20, 0.000000, 0, 0, 40, 681, 0 -ATT, 0.00, 1.06, -3.08, 1.01, 0.00, 52.52, 58.31 -CTUN, 700, 1.54, 6.14, 0.000000, 0, 0, 19, 700, 0 -ATT, 0.00, 1.41, -3.08, -0.54, 0.00, 53.19, 58.31 -CTUN, 779, 1.48, 6.19, 0.000000, 0, 0, -3, 761, 0 -DU32, 7, 166140 -CURR, 779, 2959356, 961, 1577, 5051, 2182.645300 -ATT, 0.00, 1.92, -3.08, -2.10, 0.00, 53.97, 58.31 -CTUN, 855, 1.54, 6.01, 0.000000, 0, 1, -17, 848, 0 -ATT, 0.00, 2.15, -2.89, -2.73, 0.00, 54.73, 58.31 -CTUN, 908, 1.54, 6.27, 0.000000, 0, 1, -29, 906, 0 -ATT, 0.00, 1.60, -2.98, -2.35, 0.00, 55.45, 58.31 -CTUN, 940, 1.54, 6.06, 0.000000, 0, 0, -27, 938, 0 -ATT, 0.00, 0.78, -3.08, -1.56, 0.00, 55.97, 58.31 -CTUN, 946, 1.50, 5.99, 0.000000, 0, 0, -24, 946, 0 -ATT, 0.00, 0.32, -3.08, -1.05, 0.00, 56.33, 58.31 -CTUN, 938, 1.50, 6.13, 0.000000, 0, 0, -17, 943, 0 -ATT, 0.00, -0.24, -2.70, -1.03, 0.00, 56.45, 58.31 -CTUN, 921, 1.40, 6.03, 0.000000, 0, 0, -9, 923, 0 -ATT, -0.94, -0.61, -2.70, -1.12, 0.00, 56.45, 58.31 -CTUN, 903, 1.40, 6.05, 0.000000, 0, 0, -1, 903, 0 -ATT, -2.17, -1.10, -2.14, -1.21, 0.00, 56.39, 58.31 -CTUN, 864, 1.37, 6.03, 0.000000, 0, 0, 4, 872, 0 -ATT, -2.36, -2.28, -2.33, -1.06, 0.00, 56.35, 58.31 -CTUN, 855, 1.37, 5.89, 0.000000, 0, 0, 8, 854, 0 -ATT, -2.36, -2.88, -2.33, -0.79, 0.00, 56.33, 58.31 -CTUN, 871, 1.37, 6.01, 0.000000, 0, 0, 10, 864, 0 -DU32, 7, 166140 -CURR, 871, 2968318, 930, 2210, 5051, 2189.400900 -ATT, -2.36, -2.71, -2.33, -0.35, 0.00, 56.19, 58.31 -CTUN, 882, 1.42, 6.00, 0.000000, 0, 0, 11, 881, 0 -ATT, -2.93, -2.18, -2.89, -0.04, 0.00, 56.15, 58.31 -CTUN, 882, 1.42, 5.94, 0.000000, 0, 0, 10, 882, 0 -ATT, -3.22, -2.21, -3.26, 0.33, 0.00, 56.20, 58.31 -CTUN, 858, 1.42, 6.03, 0.000000, 0, 0, 11, 867, 0 -ATT, -2.84, -2.92, -2.98, 0.67, 0.00, 56.18, 58.31 -CTUN, 844, 1.38, 6.03, 0.000000, 0, 1, 12, 851, 0 -ATT, -2.36, -3.58, -4.10, 0.52, 0.00, 56.19, 58.31 -CTUN, 836, 1.40, 6.00, 0.000000, 0, 1, 12, 839, 0 -ATT, -1.13, -3.50, -4.85, -0.26, 0.00, 56.15, 58.31 -CTUN, 819, 1.38, 6.11, 0.000000, 0, 1, 8, 820, 0 -ATT, 0.00, -3.07, -6.25, -1.46, 0.00, 56.14, 58.31 -CTUN, 835, 1.38, 5.94, 0.000000, 0, 1, 0, 829, 0 -ATT, 0.00, -2.64, -6.81, -2.55, 0.00, 55.97, 58.31 -CTUN, 876, 1.38, 6.04, 0.000000, 0, 1, -2, 874, 0 -ATT, 0.00, -1.89, -6.34, -3.77, 0.00, 55.71, 58.31 -CTUN, 906, 1.47, 5.96, 0.000000, 0, 2, -4, 904, 0 -ATT, 0.00, -0.84, -5.13, -4.66, 0.00, 55.37, 58.31 -CTUN, 915, 1.47, 5.91, 0.000000, 0, 2, 0, 916, 0 -DU32, 7, 166140 -CURR, 915, 2976973, 908, 2595, 5028, 2195.807900 -ATT, 0.00, -0.13, -4.57, -4.38, 0.00, 55.09, 58.31 -CTUN, 912, 1.47, 6.00, 0.000000, 0, 1, 5, 913, 0 -ATT, 0.00, -0.55, -4.29, -2.89, 0.00, 54.80, 58.31 -CTUN, 871, 1.47, 6.05, 0.000000, 0, 0, 12, 890, 0 -ATT, 0.00, -0.82, -4.38, -1.62, 0.00, 54.71, 58.31 -CTUN, 829, 1.47, 6.03, 0.000000, 0, 0, 15, 829, 0 -ATT, 0.00, -0.81, -4.38, -1.06, 0.00, 54.93, 58.31 -CTUN, 773, 1.47, 6.00, 0.000000, 0, 0, 12, 780, 0 -ATT, 0.00, 0.05, -4.38, -0.98, 0.00, 55.39, 58.31 -CTUN, 764, 1.50, 6.09, 0.000000, 0, 0, 6, 765, 0 -ATT, 0.00, 1.00, -4.29, -1.41, 0.00, 56.00, 58.31 -CTUN, 765, 1.50, 6.11, 0.000000, 0, 0, -9, 766, 0 -ATT, 0.00, 0.95, -4.38, -2.60, 0.00, 56.78, 58.31 -CTUN, 819, 1.53, 6.19, 0.000000, 0, 1, -26, 800, 0 -ATT, 0.00, 0.02, -4.38, -4.05, 0.00, 57.86, 58.31 -CTUN, 881, 1.51, 6.14, 0.000000, 0, 2, -36, 867, 0 -ATT, 1.59, -0.52, -4.29, -5.28, 0.00, 59.45, 58.31 -CTUN, 932, 1.51, 6.26, 0.000000, 0, 3, -38, 928, 0 -ATT, 2.90, 0.20, -4.38, -5.72, 0.00, 61.32, 58.31 -CTUN, 961, 1.49, 6.09, 0.000000, 0, 4, -38, 958, 0 -DU32, 7, 166140 -CURR, 966, 2985447, 923, 2320, 5051, 2201.886700 -ATT, 3.93, 1.65, -4.38, -5.49, 0.00, 63.31, 58.31 -CTUN, 976, 1.49, 6.21, 0.000000, 0, 4, -41, 982, 0 -ATT, 5.90, 3.15, -4.38, -5.09, 0.00, 65.20, 58.31 -CTUN, 975, 1.43, 6.18, 0.000000, 0, 4, -40, 979, 0 -ATT, 6.00, 4.13, -3.92, -4.52, 0.00, 66.75, 58.31 -CTUN, 966, 1.43, 6.18, 0.000000, 0, 4, -46, 973, 0 -ATT, 4.12, 4.28, -2.42, -3.86, 0.00, 67.83, 58.31 -CTUN, 965, 1.36, 6.02, 0.000000, 0, 3, -54, 967, 0 -ATT, 0.46, 3.70, -2.05, -2.97, 0.00, 68.49, 58.49 -CTUN, 986, 1.36, 6.10, 0.000000, 0, 1, -61, 980, 0 -ATT, 0.00, 1.66, -1.21, -2.00, 0.00, 68.83, 58.83 -CTUN, 1000, 1.27, 6.03, 0.000000, 0, 0, -65, 1000, 0 -ATT, 0.00, -0.84, -0.18, -0.68, 0.00, 68.86, 58.89 -CTUN, 1000, 1.27, 5.97, 0.000000, 0, 0, -66, 1000, 0 -ATT, 0.00, -1.84, 0.00, 0.85, 0.00, 68.57, 58.89 -CTUN, 1000, 1.18, 5.78, 0.000000, 0, 0, -68, 1000, 0 -ATT, 0.00, -1.21, 0.00, 2.57, 0.00, 68.12, 58.89 -CTUN, 1000, 1.18, 5.77, 0.000000, 0, 0, -71, 1000, 0 -ATT, 0.00, 0.17, 0.00, 3.94, 0.00, 67.50, 58.89 -CTUN, 1000, 1.05, 5.72, 0.000000, 0, 0, -80, 1000, 0 -DU32, 7, 166140 -CURR, 1000, 2995322, 934, 2018, 5051, 2207.724600 -ATT, 0.00, 0.21, 0.00, 4.47, 0.00, 66.65, 58.89 -CTUN, 1000, 1.05, 5.81, 0.000000, 0, 0, -91, 1000, 0 -ATT, 0.00, -1.40, 0.00, 3.95, 0.00, 65.60, 58.89 -CTUN, 1000, 0.89, 5.68, 0.000000, 0, 0, -93, 1000, 0 -ATT, 0.00, -0.91, 0.00, 3.09, 0.00, 64.29, 58.89 -CTUN, 999, 0.89, 5.56, 0.000000, 0, 1, -98, 1000, 0 -ATT, 0.00, -0.81, 0.00, 2.62, 0.00, 62.98, 58.89 -CTUN, 1000, 0.71, 5.43, 0.000000, 0, 0, -97, 1000, 0 -ATT, 1.78, -1.14, 0.00, 2.35, 0.00, 61.75, 58.89 -CTUN, 999, 0.71, 5.25, 0.000000, 0, 0, -92, 1000, 0 -ATT, 3.37, -0.50, -1.02, 2.05, 0.00, 60.42, 58.89 -CTUN, 1000, 0.53, 5.06, 0.000000, 0, 0, -87, 1000, 0 -ATT, 4.50, 2.03, -1.21, 1.88, 0.00, 58.96, 58.89 -CTUN, 999, 0.53, 4.85, 0.000000, 0, 1, -80, 1000, 0 -ATT, 4.68, 4.54, -1.68, 0.82, 0.00, 57.61, 58.89 -CTUN, 1000, 0.36, 4.79, 0.000000, 0, 0, -69, 1000, 0 -ATT, 4.03, 5.29, -1.96, -0.75, 0.00, 56.06, 58.89 -CTUN, 999, 0.36, 4.51, 0.000000, 0, 0, -49, 1000, 0 -ATT, 3.18, 4.25, -2.05, -1.34, 0.00, 55.13, 58.89 -CTUN, 1000, 0.22, 4.27, 0.000000, 0, 1, -27, 997, 0 -DU32, 7, 166140 -CURR, 1000, 3005322, 900, 2736, 5051, 2214.745800 -ATT, 0.18, 2.23, -2.05, -0.90, 0.00, 54.79, 58.89 -CTUN, 1000, 0.22, 3.29, 0.000000, 0, 0, -4, 1000, 0 -ATT, 0.00, 0.97, -1.30, 0.34, 0.00, 54.92, 58.89 -CTUN, 999, 0.20, 3.49, 0.000000, 0, 0, 12, 1000, 0 -ATT, 0.00, 0.18, -1.58, 1.26, 0.00, 55.39, 58.89 -CTUN, 946, 0.20, 3.95, 0.000000, 0, 0, 27, 979, 0 -ATT, 0.00, -0.35, -2.42, 1.19, 0.00, 55.95, 58.89 -CTUN, 906, 0.20, 4.46, 0.000000, 0, 0, 36, 911, 0 -ATT, 0.00, -0.64, -2.70, 0.54, 0.00, 56.67, 58.89 -CTUN, 880, 0.20, 4.77, 0.000000, 0, 0, 47, 885, 0 -ATT, 0.00, -0.72, -4.29, 0.62, 0.00, 57.41, 58.89 -CTUN, 856, 0.20, 4.65, 0.000000, 0, 0, 48, 854, 0 -ATT, 0.00, -0.92, -5.88, 0.44, 0.00, 58.05, 58.89 -PM, 0, 0, 0, 0, 1000, 10472, 0, 0 -CTUN, 857, 0.25, 5.06, 0.000000, 0, 0, 45, 856, 0 -ATT, 0.00, -0.95, -6.72, -0.64, 0.00, 58.63, 58.89 -CTUN, 870, 0.25, 4.96, 0.000000, 0, 0, 38, 869, 0 -ATT, 0.00, -1.38, -7.28, -2.65, 0.00, 59.31, 58.89 -CTUN, 883, 0.34, 5.13, 0.000000, 0, 1, 31, 880, 0 -ATT, 0.18, -1.34, -7.93, -4.66, 0.00, 59.78, 58.89 -CTUN, 886, 0.34, 5.09, 0.000000, 0, 3, 29, 889, 0 -DU32, 7, 166140 -CURR, 885, 3014485, 910, 2438, 5051, 2221.523400 -ATT, 0.37, -0.02, -8.21, -5.55, 0.00, 59.89, 58.89 -CTUN, 890, 0.44, 5.10, 0.000000, 0, 3, 28, 889, 0 -ATT, 1.59, 0.14, -8.30, -6.03, 0.00, 59.52, 58.89 -CTUN, 900, 0.44, 5.19, 0.000000, 0, 4, 25, 902, 0 -ATT, 1.96, -0.02, -7.84, -6.59, 0.00, 58.78, 58.89 -CTUN, 904, 0.52, 5.34, 0.000000, 0, 5, 27, 908, 0 -ATT, 1.78, 0.84, -7.84, -6.56, 0.00, 57.91, 58.89 -CTUN, 911, 0.52, 5.22, 0.000000, 0, 4, 29, 912, 0 -ATT, 0.75, 1.79, -7.84, -5.84, 0.00, 56.97, 58.89 -CTUN, 909, 0.59, 5.24, 0.000000, 0, 4, 30, 913, 0 -ATT, 0.00, 1.66, -7.84, -5.24, 0.00, 56.16, 58.89 -CTUN, 909, 0.59, 5.30, 0.000000, 0, 3, 33, 912, 0 -ATT, 0.00, 0.88, -7.84, -4.69, 0.00, 55.44, 58.89 -CTUN, 902, 0.65, 5.28, 0.000000, 0, 2, 35, 906, 0 -ATT, 0.00, 0.53, -7.84, -4.18, 0.00, 54.97, 58.89 -CTUN, 888, 0.65, 5.38, 0.000000, 0, 1, 38, 889, 0 -ATT, 0.00, 0.85, -7.37, -3.79, 0.00, 54.68, 58.89 -CTUN, 876, 0.73, 5.29, 0.000000, 0, 1, 40, 877, 0 -ATT, 0.00, 1.35, -5.13, -3.56, 0.00, 54.68, 58.89 -CTUN, 876, 0.73, 5.39, 0.000000, 0, 1, 36, 876, 0 -DU32, 7, 166140 -CURR, 876, 3023470, 903, 2326, 5028, 2228.397500 -ATT, 0.00, 1.82, -2.52, -3.08, 0.00, 54.90, 58.89 -CTUN, 879, 0.83, 5.44, 0.000000, 0, 1, 34, 880, 0 -ATT, 0.00, 2.13, -2.42, -1.59, 0.00, 55.34, 58.89 -CTUN, 879, 0.83, 5.58, 0.000000, 0, 0, 33, 879, 0 -ATT, 0.00, 1.75, -2.52, 0.35, 0.00, 55.99, 58.89 -CTUN, 854, 0.90, 5.67, 0.000000, 0, 0, 31, 854, 0 -ATT, 0.00, 1.02, -2.33, 1.53, 0.00, 56.76, 58.89 -CTUN, 827, 0.90, 5.57, 0.000000, 0, 0, 25, 828, 0 -ATT, 0.00, 0.66, -2.52, 1.43, 0.00, 57.58, 58.89 -CTUN, 836, 0.99, 5.64, 0.000000, 0, 0, 16, 831, 0 -ATT, 0.00, 0.95, -2.52, 0.80, 0.00, 58.32, 58.89 -CTUN, 857, 0.99, 5.69, 0.000000, 0, 0, 7, 847, 0 -ATT, 0.00, 1.11, -2.24, 0.70, 0.00, 58.84, 58.89 -CTUN, 870, 1.06, 5.75, 0.000000, 0, 0, 0, 870, 0 -ATT, 0.00, 1.22, -2.33, 1.20, 0.00, 59.11, 58.89 -CTUN, 871, 1.06, 5.83, 0.000000, 0, 0, -4, 870, 0 -ATT, 0.00, 1.09, -2.33, 1.65, 0.00, 59.17, 58.89 -CTUN, 892, 1.10, 5.75, 0.000000, 0, 0, -4, 892, 0 -ATT, -0.94, 0.75, -0.93, 1.93, 0.00, 59.04, 58.89 -CTUN, 892, 1.06, 5.66, 0.000000, 0, 0, -6, 894, 0 -DU32, 7, 166140 -CURR, 892, 3032111, 902, 2412, 5028, 2234.753400 -ATT, -0.94, 0.25, -1.02, 2.22, 0.00, 58.76, 58.89 -CTUN, 888, 1.06, 5.82, 0.000000, 0, 0, -6, 888, 0 -ATT, -0.75, -0.46, -2.52, 2.75, 0.00, 58.34, 58.89 -CTUN, 879, 1.06, 5.84, 0.000000, 0, 0, -6, 879, 0 -ATT, -0.66, -0.71, -2.70, 2.72, 0.00, 57.89, 58.89 -CTUN, 879, 1.07, 5.77, 0.000000, 0, 0, -9, 880, 0 -ATT, -0.94, -0.74, -3.73, 2.23, 0.00, 57.48, 58.89 -CTUN, 880, 1.07, 5.86, 0.000000, 0, 0, -8, 880, 0 -ATT, 0.00, -0.82, -4.85, 1.62, 0.00, 57.02, 58.89 -CTUN, 879, 1.07, 5.93, 0.000000, 0, 0, -11, 879, 0 -ATT, 0.00, -0.55, -4.76, 0.84, 0.00, 56.63, 58.89 -CTUN, 880, 1.07, 5.95, 0.000000, 0, 0, -12, 879, 0 -ATT, 0.00, -0.15, -6.25, 0.32, 0.00, 56.24, 58.89 -CTUN, 880, 1.07, 5.91, 0.000000, 0, 0, -14, 879, 0 -ATT, 0.00, -0.32, -6.81, 0.11, 0.00, 56.00, 58.89 -CTUN, 880, 1.03, 5.79, 0.000000, 0, 0, -13, 880, 0 -ATT, 0.00, -1.08, -6.72, -0.20, 0.00, 55.94, 58.89 -CTUN, 879, 1.07, 5.89, 0.000000, 0, 0, -12, 879, 0 -ATT, 0.00, -1.27, -6.81, -0.65, 0.00, 56.05, 58.89 -CTUN, 879, 1.07, 5.82, 0.000000, 0, 0, -14, 879, 0 -DU32, 7, 166140 -CURR, 879, 3040919, 911, 2360, 5051, 2241.282200 -ATT, 0.00, -0.74, -6.72, -1.02, 0.00, 56.33, 58.89 -CTUN, 879, 1.10, 5.82, 0.000000, 0, 0, -16, 879, 0 -ATT, 0.00, 0.13, -6.72, -1.23, 0.00, 56.70, 58.89 -CTUN, 879, 1.10, 5.83, 0.000000, 0, 0, -16, 879, 0 -ATT, 0.00, 0.27, -6.53, -1.36, 0.00, 57.12, 58.89 -CTUN, 879, 1.14, 5.84, 0.000000, 0, 0, -13, 880, 0 -ATT, 0.00, -0.33, -6.53, -1.53, 0.00, 57.64, 58.89 -CTUN, 880, 1.14, 5.77, 0.000000, 0, 0, -15, 880, 0 -ATT, 0.00, -0.74, -6.53, -1.94, 0.00, 58.22, 58.89 -CTUN, 879, 1.14, 5.87, 0.000000, 0, 0, -15, 879, 0 -ATT, 0.00, -0.66, -6.53, -2.27, 0.00, 58.77, 58.89 -CTUN, 880, 1.13, 5.76, 0.000000, 0, 0, -15, 880, 0 -ATT, 0.00, -0.61, -6.62, -2.52, 0.00, 59.30, 58.89 -CTUN, 886, 1.13, 5.74, 0.000000, 0, 0, -15, 886, 0 -ATT, 0.00, -0.75, -6.81, -2.79, 0.00, 59.73, 58.89 -CTUN, 890, 1.13, 5.85, 0.000000, 0, 1, -14, 891, 0 -ATT, 0.00, -0.85, -6.53, -3.10, 0.00, 59.99, 58.89 -CTUN, 890, 1.13, 5.75, 0.000000, 0, 1, -12, 891, 0 -ATT, 0.00, -0.81, -6.53, -3.46, 0.00, 60.08, 58.89 -CTUN, 889, 1.12, 5.71, 0.000000, 0, 1, -11, 890, 0 -DU32, 7, 166140 -CURR, 888, 3049748, 904, 2409, 5051, 2247.876500 -ATT, 0.00, -0.72, -6.53, -3.64, 0.00, 59.94, 58.89 -CTUN, 888, 1.12, 5.81, 0.000000, 0, 1, -10, 889, 0 -ATT, 0.00, -0.01, -6.53, -3.62, 0.00, 59.58, 58.89 -CTUN, 885, 1.12, 5.91, 0.000000, 0, 1, -5, 886, 0 -ATT, 0.00, 0.62, -5.88, -3.45, 0.00, 59.03, 58.89 -CTUN, 886, 1.13, 5.79, 0.000000, 0, 1, -7, 887, 0 -ATT, 0.00, 1.03, -4.85, -2.92, 0.00, 58.35, 58.89 -CTUN, 885, 1.13, 5.91, 0.000000, 0, 0, -4, 886, 0 -ATT, 0.00, 1.20, -4.29, -1.66, 0.00, 57.70, 58.89 -CTUN, 886, 1.13, 5.72, 0.000000, 0, 0, -2, 886, 0 -ATT, 0.00, 0.79, -3.92, -0.17, 0.00, 57.16, 58.89 -CTUN, 884, 1.13, 5.80, 0.000000, 0, 0, -3, 885, 0 -ATT, -0.94, 0.07, -2.61, 1.17, 0.00, 56.60, 58.89 -CTUN, 885, 1.14, 5.77, 0.000000, 0, 0, -4, 885, 0 -ATT, -1.32, -0.34, -33.14, 2.14, 0.00, 56.09, 58.89 -CTUN, 885, 1.14, 5.77, 0.000000, 0, 0, -11, 885, 0 -ATT, -1.13, -0.68, -2.80, -1.94, 0.00, 55.71, 58.89 -CTUN, 885, 1.15, 5.97, 0.000000, 0, 2, -18, 888, 0 -ATT, -0.94, -1.48, -3.26, -6.31, 0.00, 55.37, 58.89 -CTUN, 886, 1.14, 5.73, 0.000000, 0, 5, -17, 890, 0 -DU32, 7, 166140 -CURR, 885, 3058615, 908, 2470, 5028, 2254.451200 -ATT, -0.94, -2.04, -3.45, -5.85, 0.00, 54.92, 58.89 -CTUN, 882, 1.14, 5.79, 0.000000, 0, 2, -17, 886, 0 -ATT, -0.37, -1.93, -3.73, -2.93, 0.00, 54.49, 58.89 -CTUN, 884, 1.14, 5.79, 0.000000, 0, 0, -17, 884, 0 -ATT, 0.00, -1.62, -3.08, 0.07, 0.00, 54.47, 58.89 -CTUN, 884, 1.14, 5.66, 0.000000, 0, 0, -21, 884, 0 -ATT, 0.00, -1.23, -2.98, 2.05, 0.00, 54.79, 58.89 -CTUN, 884, 1.12, 5.80, 0.000000, 0, 0, -21, 884, 0 -ATT, 0.00, -0.12, -2.80, 2.62, 0.00, 55.36, 58.89 -CTUN, 884, 1.12, 6.04, 0.000000, 0, 0, -20, 883, 0 -ATT, 0.00, 0.85, -2.70, 2.47, 0.00, 55.99, 58.89 -CTUN, 884, 1.10, 5.88, 0.000000, 0, 0, -21, 884, 0 -ATT, 0.00, 0.79, -2.70, 2.02, 0.00, 56.74, 58.89 -CTUN, 883, 1.10, 5.78, 0.000000, 0, 0, -23, 884, 0 -ATT, 0.00, 0.27, -2.80, 1.49, 0.00, 57.50, 58.89 -CTUN, 884, 1.07, 5.73, 0.000000, 0, 0, -25, 884, 0 -ATT, 0.00, 0.28, -3.08, 1.19, 0.00, 58.13, 58.89 -CTUN, 884, 1.07, 5.75, 0.000000, 0, 0, -25, 884, 0 -ATT, 0.00, 0.32, -2.98, 0.80, 0.00, 58.65, 58.89 -CTUN, 884, 1.04, 5.75, 0.000000, 0, 0, -26, 884, 0 -DU32, 7, 166140 -CURR, 884, 3067457, 894, 2358, 5051, 2261.026600 -ATT, 0.00, 0.03, -3.08, -0.17, 0.00, 59.19, 58.89 -CTUN, 883, 1.04, 5.78, 0.000000, 0, 0, -21, 884, 0 -ATT, 0.00, -0.19, -3.08, -1.26, 0.00, 59.76, 58.89 -CTUN, 884, 1.00, 5.66, 0.000000, 0, 0, -24, 883, 0 -ATT, 0.00, -0.16, -2.98, -2.56, 0.00, 60.43, 58.89 -CTUN, 884, 1.00, 5.67, 0.000000, 0, 1, -27, 885, 0 -ATT, 0.00, 0.02, -3.08, -3.27, 0.00, 61.23, 58.89 -CTUN, 884, 0.96, 5.72, 0.000000, 0, 1, -28, 885, 0 -ATT, 0.00, 0.07, -3.08, -3.04, 0.00, 62.02, 58.89 -CTUN, 884, 0.96, 5.71, 0.000000, 0, 1, -32, 885, 0 -ATT, 0.00, 0.35, -3.08, -2.78, 0.00, 62.75, 58.89 -CTUN, 884, 0.91, 5.76, 0.000000, 0, 0, -37, 884, 0 -ATT, 0.00, 0.91, -2.61, -2.63, 0.00, 63.45, 58.89 -ERR, 6, 1 -CTUN, 884, 0.91, 5.70, 0.000000, 0, 0, -43, 884, 0 -ATT, 0.00, 0.92, -2.42, -1.74, 0.00, 64.09, 58.89 -CTUN, 884, 0.86, 5.67, 0.000000, 0, 0, -50, 884, 0 -ATT, 0.00, 0.03, -2.42, -0.74, 0.00, 64.70, 58.89 -CTUN, 885, 0.86, 5.68, 0.000000, 0, 0, -55, 886, 0 -ATT, 0.00, -1.07, -2.52, -0.02, 0.00, 65.17, 58.89 -CTUN, 899, 0.77, 5.50, 0.000000, 0, 0, -62, 898, 0 -DU32, 7, 166396 -CURR, 899, 3076313, 911, 2183, 5051, 2267.302500 -ATT, 0.00, -1.43, -2.42, 0.32, 0.00, 65.37, 58.89 -CTUN, 902, 0.77, 5.45, 0.000000, 0, 0, -67, 900, 0 -ATT, 0.00, -1.59, -2.52, 0.56, 0.00, 65.49, 58.89 -CTUN, 904, 0.67, 5.62, 0.000000, 0, 0, -73, 903, 0 -ATT, 0.00, -1.44, -2.52, 0.80, 0.00, 65.40, 58.89 -CTUN, 904, 0.67, 5.43, 0.000000, 0, 0, -82, 904, 0 -ATT, 0.00, -1.13, -2.70, 0.16, 0.00, 65.26, 58.89 -CTUN, 904, 0.53, 5.13, 0.000000, 0, 0, -85, 904, 0 -ATT, 0.00, -1.09, -2.42, -0.77, 0.00, 65.01, 58.89 -CTUN, 904, 0.53, 5.13, 0.000000, 0, 0, -83, 904, 0 -ATT, 0.09, -1.10, -3.26, -1.63, 0.00, 64.69, 58.89 -CTUN, 904, 0.37, 4.85, 0.000000, 0, 0, -81, 904, 0 -ATT, 1.50, -0.59, -3.92, -1.68, 0.00, 64.18, 58.89 -CTUN, 904, 0.37, 4.59, 0.000000, 0, 0, -75, 904, 0 -ATT, 2.81, 0.63, -4.10, -1.47, 0.00, 63.36, 58.89 -CTUN, 904, 0.23, 2.69, 0.000000, 0, 0, -62, 904, 0 -ATT, 3.28, 2.09, -4.10, -2.48, 0.00, 62.25, 58.89 -CTUN, 905, 0.23, 0.58, 0.000000, 0, 1, -40, 905, 0 -ATT, 3.37, 0.93, -3.73, -1.07, 0.00, 62.15, 58.89 -CTUN, 871, 0.23, -0.45, 0.000000, 0, 0, 2, 889, 0 -DU32, 7, 166396 -CURR, 871, 3085348, 913, 1999, 5028, 2273.562300 -ATT, 3.37, 1.79, -3.26, 2.71, 0.00, 62.52, 58.89 -CTUN, 780, 5.20, 0.55, 0.000000, 0, 2, 7, 822, 0 -ATT, 3.09, 3.37, -2.42, 4.07, 0.00, 61.79, 58.89 -CTUN, 659, 5.20, 1.33, 0.000000, 0, 2, 5, 687, 0 -ATT, 3.09, 3.65, -2.42, 4.80, 0.00, 61.27, 58.89 -CTUN, 590, 5.20, 1.68, 0.000000, 0, 2, -8, 623, 0 -ATT, 3.09, 3.51, -2.70, 3.86, 0.00, 60.37, 58.89 -CTUN, 538, 2.43, 2.82, 0.000000, 0, 1, -31, 555, 0 -ATT, 3.09, 2.81, -2.42, 1.47, 0.00, 59.50, 58.89 -CTUN, 484, 2.43, 2.96, 0.000000, 0, 0, -62, 489, 0 -ATT, 3.18, 2.93, -2.52, -0.73, 0.00, 58.68, 58.89 -CTUN, 459, 0.22, 2.05, 0.000000, 0, 0, -57, 459, 0 -ATT, 3.09, 0.52, -2.52, -0.12, 0.00, 57.77, 58.89 -CTUN, 430, 2.43, 1.88, 0.000000, 0, 0, -32, 440, 0 -ATT, 3.09, 0.31, -2.42, -1.25, 0.00, 57.95, 58.89 -CTUN, 382, 2.43, 2.27, 0.000000, 0, 0, -30, 402, 0 -ATT, 3.00, 0.38, -2.42, 0.18, 0.00, 57.99, 58.89 -CTUN, 331, 7.37, 2.42, 0.000000, 0, 0, -31, 345, 0 -ATT, 3.00, 0.43, -2.70, 0.52, 0.00, 58.09, 58.89 -CTUN, 284, 7.37, 2.67, 0.000000, 0, 0, -35, 288, 0 -DU32, 7, 166396 -CURR, 267, 3090531, 1021, 340, 5028, 2276.218300 -ATT, 2.71, 0.44, -2.70, 0.50, 0.00, 58.14, 58.89 -CTUN, 205, 7.65, 2.71, 0.000000, 0, 0, -35, 229, 0 -ATT, 2.53, 0.44, -2.70, 0.52, 0.00, 58.21, 58.89 -CTUN, 0, 7.65, 2.92, 0.000000, 0, 0, -36, 141, 0 -ATT, 2.53, 0.44, -2.52, 0.49, -0.18, 58.31, 58.31 -CTUN, 0, 7.65, 3.40, 0.000000, 0, 0, -36, 0, 0 -ATT, 2.53, 0.43, -2.52, 0.49, -3.58, 58.39, 58.39 -CTUN, 0, 6.63, 3.72, 0.000000, 0, 0, -36, 0, 0 -ATT, 2.90, 0.44, -2.42, 0.51, -10.37, 58.47, 58.47 -CTUN, 0, 6.63, 3.92, 0.000000, 0, 0, -35, 0, 0 -ATT, 2.90, 0.44, -2.52, 0.49, -19.71, 58.55, 58.55 -CTUN, 0, 6.63, 3.84, 0.000000, 0, 0, -34, 0, 0 -ATT, 2.90, 0.44, -2.42, 0.49, -31.88, 58.67, 58.67 -PM, 0, 0, 0, 0, 1000, 10488, 0, 0 -CTUN, 0, 7.12, 4.17, 0.000000, 0, 0, -34, 0, 0 -ATT, 2.34, 0.44, -2.24, 0.47, -41.50, 58.75, 58.75 -CTUN, 0, 7.12, 4.23, 0.000000, 0, 0, -33, 0, 0 -ATT, 0.09, 0.44, -1.58, 0.47, -42.73, 58.86, 58.86 -CTUN, 0, 7.65, 4.31, 0.000000, 0, 0, -31, 0, 0 -ATT, 0.00, 0.44, -2.33, 0.47, -44.15, 58.93, 58.93 -CTUN, 0, 7.65, 4.31, 0.000000, 0, 0, -30, 0, 0 -DU32, 7, 166332 -CURR, 0, 3090912, 1043, 1, 5028, 2276.391800 -ATT, 0.00, 0.44, -2.24, 0.46, -42.83, 59.01, 59.01 -CTUN, 0, 7.65, 4.36, 0.000000, 0, 0, -29, 0, 0 -ATT, 0.00, 0.44, -2.52, 0.46, -42.73, 59.10, 59.10 -CTUN, 0, 7.65, 4.36, 0.000000, 0, 0, -27, 0, 0 -ATT, 0.00, 0.44, -2.42, 0.45, -42.73, 59.19, 59.19 -CTUN, 0, 7.65, 4.41, 0.000000, 0, 0, -26, 0, 0 -ATT, 0.00, 0.44, -2.52, 0.45, -42.73, 59.28, 59.28 -CTUN, 0, 7.65, 4.47, 0.000000, 0, 0, -25, 0, 0 -ATT, 0.00, 0.44, -2.52, 0.45, -42.83, 59.37, 59.37 -CTUN, 0, 7.65, 4.58, 0.000000, 0, 0, -23, 0, 0 -ATT, 0.00, 0.44, -2.42, 0.45, -42.73, 59.46, 59.46 -CTUN, 0, 7.65, 4.46, 0.000000, 0, 0, -22, 0, 0 -ATT, 0.00, 0.44, -2.52, 0.45, -42.73, 59.55, 59.55 -CTUN, 0, 7.65, 4.53, 0.000000, 0, 0, -21, 0, 0 -ATT, 0.00, 0.44, -2.52, 0.44, -42.83, 59.63, 59.63 -CTUN, 0, 2.94, 4.56, 0.000000, 0, 0, -20, 0, 0 -ATT, 0.00, 0.44, -2.33, 0.44, -42.83, 59.72, 59.72 -CTUN, 0, 7.14, 4.54, 0.000000, 0, 0, -19, 0, 0 -ATT, 0.00, 0.45, -2.52, 0.44, -42.83, 59.80, 59.80 -CTUN, 0, 7.14, 4.50, 0.000000, 0, 0, -18, 0, 0 -DU32, 7, 166332 -CURR, 0, 3090912, 1050, 1, 5051, 2276.397000 -ATT, 0.00, 0.45, -2.52, 0.44, -42.73, 59.88, 59.88 -CTUN, 0, 7.61, 4.64, 0.000000, 0, 0, -17, 0, 0 -ATT, 0.00, 0.45, -2.52, 0.43, -42.64, 59.97, 59.97 -CTUN, 0, 7.61, 4.54, 0.000000, 0, 0, -16, 0, 0 -ATT, 0.00, 0.45, -2.42, 0.43, -42.83, 60.05, 60.05 -CTUN, 0, 7.65, 4.58, 0.000000, 0, 0, -15, 0, 0 -ATT, 0.00, 0.45, -2.52, 0.43, -42.73, 60.13, 60.13 -CTUN, 0, 7.61, 4.56, 0.000000, 0, 0, -14, 0, 0 -ATT, 0.00, 0.45, -2.42, 0.43, -42.64, 60.21, 60.21 -CTUN, 0, 7.61, 4.56, 0.000000, 0, 0, -13, 0, 0 -ATT, 0.00, 0.45, -2.52, 0.43, -42.64, 60.29, 60.29 -CTUN, 0, 4.37, 4.58, 0.000000, 0, 0, -12, 0, 0 -ATT, 0.00, 0.45, -2.42, 0.42, -42.64, 60.37, 60.37 -EV, 11 -DU32, 7, 133564 -DU32, 7, 133564 -DU32, 7, 133564 -MODE, STABILIZE, 699 -DU32, 7, 133564 -DU32, 7, 133564 -DU32, 7, 133564 -DU32, 7, 133564 diff --git a/Tools/LogAnalyzer/tests/TestAutotune.py b/Tools/LogAnalyzer/tests/TestAutotune.py deleted file mode 100644 index 16c04e39cdc66d..00000000000000 --- a/Tools/LogAnalyzer/tests/TestAutotune.py +++ /dev/null @@ -1,135 +0,0 @@ -# AP_FLAKE8_CLEAN - -from LogAnalyzer import Test, TestResult -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, - ] -) - - -class TestAutotune(Test): - '''test for autotune success (copter only)''' - - 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] - - @property - def failure(self): - 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] - - def __repr__(self): - return "".format(self.linestart, self.linestop) - - def __init__(self): - Test.__init__(self) - self.name = "Autotune" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - if logdata.vehicleType != VehicleType.Copter: - self.result.status = TestResult.StatusType.NA - return - - for i in ['EV', 'ATDE', 'ATUN']: - r = False - if i not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No {} log data".format(i) - r = True - if r: - return - - events = list(filter(lambda x: x[1] in AUTOTUNE_EVENTS, logdata.channels["EV"]["Id"].listData)) - attempts = [] - - j = None - 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])) - j = i - - # last attempt - if j is not None: - 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 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 deleted file mode 100644 index a72281e965cdc7..00000000000000 --- a/Tools/LogAnalyzer/tests/TestBrownout.py +++ /dev/null @@ -1,47 +0,0 @@ -# AP_FLAKE8_CLEAN - -from LogAnalyzer import Test, TestResult - - -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 diff --git a/Tools/LogAnalyzer/tests/TestCompass.py b/Tools/LogAnalyzer/tests/TestCompass.py deleted file mode 100644 index b4e6dc5f5a9e95..00000000000000 --- a/Tools/LogAnalyzer/tests/TestCompass.py +++ /dev/null @@ -1,161 +0,0 @@ -# AP_FLAKE8_CLEAN - - -import math -from functools import reduce - -from LogAnalyzer import Test, TestResult - - -class TestCompass(Test): - '''test for compass offsets and throttle interference''' - - def __init__(self): - Test.__init__(self) - self.name = "Compass" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - def vec_len(x): - return math.sqrt(x[0] ** 2 + x[1] ** 2 + x[2] ** 2) - - def FAIL(): - self.result.status = TestResult.StatusType.FAIL - - def WARN(): - if self.result.status != TestResult.StatusType.FAIL: - self.result.status = TestResult.StatusType.WARN - - try: - warnOffset = 300 - failOffset = 500 - param_offsets = ( - logdata.parameters["COMPASS_OFS_X"], - logdata.parameters["COMPASS_OFS_Y"], - 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], - ) - 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], - ) - - 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) - - 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], - ) - 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], - ) - - # check for mag field length change, and length outside of recommended range - if "MAG" in logdata.channels: - percentDiffThresholdWARN = 0.25 - percentDiffThresholdFAIL = 0.35 - minMagFieldThreshold = 120.0 - maxMagFieldThreshold = 550.0 - index = 0 - length = len(logdata.channels["MAG"]["MagX"].listData) - magField = [] - (minMagField, maxMagField) = (None, None) - (minMagFieldLine, maxMagFieldLine) = (None, None) - zerosFound = False - while index < length: - mx = logdata.channels["MAG"]["MagX"].listData[index][1] - my = logdata.channels["MAG"]["MagY"].listData[index][1] - mz = logdata.channels["MAG"]["MagZ"].listData[index][1] - if ( - (mx == 0) and (my == 0) and (mz == 0) - ): # sometimes they're zero, not sure why, same reason as why we get NaNs as offsets? - zerosFound = True - else: - mf = math.sqrt(mx * mx + my * my + mz * mz) - magField.append(mf) - if mf < minMagField: - minMagField = mf - minMagFieldLine = logdata.channels["MAG"]["MagX"].listData[index][0] - if mf > maxMagField: - maxMagField = mf - maxMagFieldLine = logdata.channels["MAG"]["MagX"].listData[index][0] - if index == 0: - (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 - if percentDiff > percentDiffThresholdFAIL: - FAIL() - 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) - ) - else: - 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) - ) - if 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, - ) - 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" - ) - - except KeyError as e: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = str(e) + ' not found' diff --git a/Tools/LogAnalyzer/tests/TestDualGyroDrift.py b/Tools/LogAnalyzer/tests/TestDualGyroDrift.py deleted file mode 100644 index b2e91c7a1aba58..00000000000000 --- a/Tools/LogAnalyzer/tests/TestDualGyroDrift.py +++ /dev/null @@ -1,110 +0,0 @@ -from __future__ import print_function - -import DataflashLog -from LogAnalyzer import Test, TestResult - -# import scipy -# import pylab #### TEMP!!! only for dev -# from scipy import signal - - -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) diff --git a/Tools/LogAnalyzer/tests/TestDupeLogData.py b/Tools/LogAnalyzer/tests/TestDupeLogData.py deleted file mode 100644 index d570f579f4f240..00000000000000 --- a/Tools/LogAnalyzer/tests/TestDupeLogData.py +++ /dev/null @@ -1,73 +0,0 @@ -# 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 deleted file mode 100644 index e247702a5ed8b4..00000000000000 --- a/Tools/LogAnalyzer/tests/TestEmpty.py +++ /dev/null @@ -1,23 +0,0 @@ -# AP_FLAKE8_CLEAN - - -import DataflashLog -from LogAnalyzer import Test, TestResult - - -class TestEmpty(Test): - '''test for empty or near-empty logs''' - - def __init__(self): - Test.__init__(self) - self.name = "Empty" - - 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 diff --git a/Tools/LogAnalyzer/tests/TestEvents.py b/Tools/LogAnalyzer/tests/TestEvents.py deleted file mode 100644 index b8556b5baf81e4..00000000000000 --- a/Tools/LogAnalyzer/tests/TestEvents.py +++ /dev/null @@ -1,57 +0,0 @@ -# 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 + " " diff --git a/Tools/LogAnalyzer/tests/TestGPSGlitch.py b/Tools/LogAnalyzer/tests/TestGPSGlitch.py deleted file mode 100644 index 294351e2be1b16..00000000000000 --- a/Tools/LogAnalyzer/tests/TestGPSGlitch.py +++ /dev/null @@ -1,72 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from LogAnalyzer import Test, TestResult - - -class TestGPSGlitch(Test): - '''test for GPS glitch reporting or bad GPS data (satellite count, hdop)''' - - def __init__(self): - Test.__init__(self) - self.name = "GPS" - - def findSatsChan(self, channels): - for chan in "NSats", "NSat", "numSV": - if chan in channels: - return channels[chan] - - def findHDopChan(self, channels): - for chan in "HDop", "HDp", "EPH": - if chan in channels: - return channels[chan] - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - if "GPS" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No GPS log data" - return - - # glitch protection is currently copter-only, but might be - # added to other vehicle types later and there's no harm in - # 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) - 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 == 11 and (eCode == 2): - gpsGlitchCount += 1 - if gpsGlitchCount: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "GPS glitch errors found (%d)" % gpsGlitchCount - - # define and check different thresholds for WARN level and - # FAIL level - # TODO: for plane, only check after first instance of throttle - # > 0, or after takeoff if we can reliably detect it - minSatsWARN = 6 - minSatsFAIL = 5 - maxHDopWARN = 3.0 - maxHDopFAIL = 10.0 - satsChan = self.findSatsChan(logdata.channels["GPS"]) - hdopChan = self.findHDopChan(logdata.channels["GPS"]) - foundBadSatsWarn = satsChan.min() < minSatsWARN - foundBadHDopWarn = hdopChan.max() > maxHDopWARN - foundBadSatsFail = satsChan.min() < minSatsFAIL - foundBadHDopFail = hdopChan.max() > maxHDopFAIL - satsMsg = "Min satellites: %s, Max HDop: %s" % (satsChan.min(), hdopChan.max()) - if gpsGlitchCount: - self.result.statusMessage = "\n".join([self.result.statusMessage, satsMsg]) - if foundBadSatsFail or foundBadHDopFail: - if not gpsGlitchCount: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = satsMsg - elif foundBadSatsWarn or foundBadHDopWarn: - if not gpsGlitchCount: - self.result.status = TestResult.StatusType.WARN - self.result.statusMessage = satsMsg diff --git a/Tools/LogAnalyzer/tests/TestIMUMatch.py b/Tools/LogAnalyzer/tests/TestIMUMatch.py deleted file mode 100644 index e26c68756f0bdb..00000000000000 --- a/Tools/LogAnalyzer/tests/TestIMUMatch.py +++ /dev/null @@ -1,139 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from __future__ import print_function - -from math import sqrt - -from LogAnalyzer import Test, TestResult - - -class TestIMUMatch(Test): - '''test for empty or near-empty logs''' - - def __init__(self): - Test.__init__(self) - self.name = "IMU Mismatch" - - def run(self, logdata, verbose): - - # 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 ("IMU2" not in logdata.channels): - self.result.status = TestResult.StatusType.NA - self.result.statusMessage = "No IMU2" - return - - 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 - - imu1 = logdata.channels["IMU"] - imu2 = logdata.channels["IMU2"] - - timeLabel = None - for i in 'TimeMS', 'TimeUS', 'Time': - if i in logdata.channels["GPS"]: - timeLabel = i - break - imu1_timems = imu1[timeLabel].listData - imu1_accx = imu1["AccX"].listData - imu1_accy = imu1["AccY"].listData - imu1_accz = imu1["AccZ"].listData - - imu2_timems = imu2[timeLabel].listData - imu2_accx = imu2["AccX"].listData - imu2_accy = imu2["AccY"].listData - imu2_accz = imu2["AccZ"].listData - - imu_multiplier = 1.0e-3 - if timeLabel == 'TimeUS': - 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], - } - ) - - 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], - } - ) - - imu1.sort(key=lambda x: x['t']) - imu2.sort(key=lambda x: x['t']) - - imu2_index = 0 - - last_t = None - - xdiff_filtered = 0 - ydiff_filtered = 0 - zdiff_filtered = 0 - max_diff_filtered = 0 - - for i in range(len(imu1)): - # find closest imu2 value - t = imu1[i]['t'] - 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)): - next_imu2 = imu2[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) < abs(prev_imu2['t'] - t) else prev_imu2 - - xdiff = imu1[i]['x'] - closest_imu2['x'] - ydiff = imu1[i]['y'] - closest_imu2['y'] - zdiff = imu1[i]['z'] - closest_imu2['z'] - - xdiff_filtered += (xdiff - xdiff_filtered) * dt / filter_tc - ydiff_filtered += (ydiff - ydiff_filtered) * dt / filter_tc - zdiff_filtered += (zdiff - zdiff_filtered) * dt / filter_tc - - diff_filtered = sqrt(xdiff_filtered**2 + ydiff_filtered**2 + zdiff_filtered**2) - max_diff_filtered = max(max_diff_filtered, diff_filtered) - last_t = t - - if max_diff_filtered > 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.status = TestResult.StatusType.WARN - else: - 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 deleted file mode 100644 index 398d9941d3352b..00000000000000 --- a/Tools/LogAnalyzer/tests/TestMotorBalance.py +++ /dev/null @@ -1,85 +0,0 @@ -# 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" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - if logdata.vehicleType != VehicleType.Copter: - self.result.status = TestResult.StatusType.NA - return - - self.result.status = TestResult.StatusType.UNKNOWN - 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)) - - 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])) - if num_channels < len(ch[i]): - num_channels = len(ch[i]) - - if logdata.frame: - num_channels = logdata.num_motor_channels() - - if num_channels < 2: - return - - try: - 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 - - 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_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.status = TestResult.StatusType.GOOD - - if abs(min(avg_ch) - max(avg_ch)) > 75: - self.result.status = TestResult.StatusType.WARN - 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 deleted file mode 100644 index d53949a71ec0a0..00000000000000 --- a/Tools/LogAnalyzer/tests/TestNaN.py +++ /dev/null @@ -1,43 +0,0 @@ -# AP_FLAKE8_CLEAN - - -import math - -from LogAnalyzer import Test, TestResult - - -class TestNaN(Test): - '''test for NaNs present in log''' - - def __init__(self): - Test.__init__(self) - self.name = "NaNs" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - def FAIL(): - self.result.status = TestResult.StatusType.FAIL - - nans_ok = { - "CTUN": ["DSAlt", "TAlt"], - "POS": ["RelOriginAlt"], - } - - for channel in logdata.channels.keys(): - for field in logdata.channels[channel].keys(): - if channel in nans_ok and field in nans_ok[channel]: - continue - try: - for tupe in logdata.channels[channel][field].listData: - (ts, val) = tupe - if isinstance(val, float) and math.isnan(val): - FAIL() - self.result.statusMessage += "Found NaN in %s.%s\n" % ( - channel, - field, - ) - raise ValueError() - except ValueError: - continue diff --git a/Tools/LogAnalyzer/tests/TestOptFlow.py b/Tools/LogAnalyzer/tests/TestOptFlow.py deleted file mode 100644 index 32ef7251d8264a..00000000000000 --- a/Tools/LogAnalyzer/tests/TestOptFlow.py +++ /dev/null @@ -1,336 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from math import sqrt - -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. - # Note that the strobing effect from non incandescent artifical lighting can produce poor optical flow measurements. - # - # 1) Set LOG_DISARMED and FLOW_TYPE to 10 and verify that ATT and OF messages are being logged onboard - # 2) Place on level ground, apply power and wait for EKF to complete attitude alignment - # 3) Keeping the copter level, lift it to shoulder height and rock between +-20 and +-30 degrees - # in roll about an axis that passes through the flow sensor lens assembly. The time taken to rotate from - # maximum left roll to maximum right roll should be about 1 second. - # 4) Repeat 3) about the pitch axis - # 5) Holding the copter level, lower it to the ground and remove power - # 6) Transfer the logfile from the sdcard. - # 7) Open a terminal and cd to the ardupilot/Tools/LogAnalyzer directory - # 8) Enter to run the analysis 'python LogAnalyzer.py ' - # 9) Check the OpticalFlow test status printed to the screen. The analysis plots are saved to - # flow_calibration.pdf and the recommended scale factors to flow_calibration.param - - def __init__(self): - Test.__init__(self) - self.name = "OpticalFlow" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - def FAIL(): - self.result.status = TestResult.StatusType.FAIL - - def WARN(): - if self.result.status != TestResult.StatusType.FAIL: - self.result.status = TestResult.StatusType.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) - # 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"] - flow_fyscaler = logdata.parameters["FLOW_FYSCALER"] - - # load required optical flow data - 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] - - 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] - - 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] - - 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] - - 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] - - 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] - - else: - FAIL() - self.result.statusMessage = "FAIL: no optical flow data\n" - return - - # load required attitude data - 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] - - 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] - - 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] - - else: - FAIL() - self.result.statusMessage = "FAIL: no attitude data\n" - return - - # calculate the start time for the roll calibration - startTime = int(0) - startRollIndex = int(0) - for i in range(len(Roll)): - if abs(Roll[i]) > tilt_threshold: - startTime = att_time_us[i] - break - for i in range(len(flow_time_us)): - if flow_time_us[i] > startTime: - startRollIndex = i - break - - # calculate the end time for the roll calibration - endTime = int(0) - endRollIndex = int(0) - 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): - if flow_time_us[i] < endTime: - endRollIndex = i - break - - # check we have enough roll data points - if endRollIndex - startRollIndex <= min_num_points: - FAIL() - self.result.statusMessage = "FAIL: insufficient roll data pointsa\n" - return - - # resample roll test data excluding data before first movement and after last movement - # also exclude data where there is insufficient angular rate - flowX_resampled = [] - 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) - ): - flowX_resampled.append(flowX[i]) - bodyX_resampled.append(bodyX[i]) - flowX_time_us_resampled.append(flow_time_us[i]) - - # calculate the start time for the pitch calibration - startTime = 0 - startPitchIndex = int(0) - for i in range(len(Pitch)): - if abs(Pitch[i]) > tilt_threshold: - startTime = att_time_us[i] - break - for i in range(len(flow_time_us)): - if flow_time_us[i] > startTime: - startPitchIndex = i - break - - # calculate the end time for the pitch calibration - endTime = 0 - endPitchIndex = int(0) - 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): - if flow_time_us[i] < endTime: - endPitchIndex = i - break - - # check we have enough pitch data points - if endPitchIndex - startPitchIndex <= min_num_points: - FAIL() - self.result.statusMessage = "FAIL: insufficient pitch data pointsa\n" - return - - # resample pitch test data excluding data before first movement and after last movement - # also exclude data where there is insufficient or too much angular rate - flowY_resampled = [] - 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) - ): - 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 - ) - - # 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]))) - ) - - # 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) - ) - - # 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])), - ) - ) - - # calculate fit display data - 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) - flowY_display = fit_coef_y(body_rate_display) - - # 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.title('X axis flow rate vs gyro rate') - plt.ylabel('flow rate (rad/s)') - plt.xlabel('gyro rate (rad/sec)') - plt.grid() - 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.title('Y axis flow rate vs gyro rate') - plt.ylabel('flow rate (rad/s)') - plt.xlabel('gyro rate (rad/sec)') - plt.grid() - plt.legend(loc='upper left') - - 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.title('X axis flow and body rate vs time') - plt.ylabel('rate (rad/s)') - plt.xlabel('time (usec)') - plt.grid() - 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.title('Y axis flow and body rate vs time') - plt.ylabel('rate (rad/s)') - plt.xlabel('time (usec)') - plt.grid() - plt.legend(loc='upper left') - - pp.savefig() - - # close the pdf file - pp.close() - - # close all figures - plt.close("all") - - # 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.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 deleted file mode 100644 index aedcf762166c56..00000000000000 --- a/Tools/LogAnalyzer/tests/TestParams.py +++ /dev/null @@ -1,81 +0,0 @@ -# AP_FLAKE8_CLEAN - - -import math # for isnan() - -from LogAnalyzer import Test, TestResult -from VehicleType import VehicleType - - -class TestParams(Test): - '''test for any obviously bad parameters in the config''' - - 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), - ) - - 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), - ) - - 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), - ) - - 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(): - 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 - if logdata.vehicleType == VehicleType.Copter: - 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) - # TODO: add more parameter tests, these are just an example... - elif logdata.vehicleType == VehicleType.Plane: - # TODO: add parameter checks for plane... - pass - elif logdata.vehicleType == VehicleType.Rover: - # TODO: add parameter checks for rover... - pass - - if self.result.status == TestResult.StatusType.FAIL: - self.result.statusMessage = "Bad parameters found:\n" + self.result.statusMessage - except KeyError as e: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = str(e) + ' not found' diff --git a/Tools/LogAnalyzer/tests/TestPerformance.py b/Tools/LogAnalyzer/tests/TestPerformance.py deleted file mode 100644 index a4e2ebddc2ac15..00000000000000 --- a/Tools/LogAnalyzer/tests/TestPerformance.py +++ /dev/null @@ -1,73 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from __future__ import print_function - -from LogAnalyzer import Test, TestResult -from VehicleType import VehicleType - - -class TestPerformance(Test): - '''check performance monitoring messages (PM) for issues with slow loops, etc''' - - def __init__(self): - Test.__init__(self) - self.name = "PM" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - # this test should be valid for all vehicle types, just need to figure out why PM logging data is different in each - if logdata.vehicleType != VehicleType.Copter: - 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. - # 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: - # if (ev == 10) or (ev == 11): - # armingLines.append(line) - # ignoreMaxTLines = [] - # for maxT in logdata.channels["PM"]["MaxT"].listData: - # if not armingLines: - # break - # if maxT[0] > armingLines[0]: - # ignoreMaxTLines.append(maxT[0]) - # armingLines.pop(0) - - if "PM" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No PM log data" - return - - # check for slow loops, i.e. NLon greater than 6% of NLoop - maxPercentSlow = 0 - maxPercentSlowLine = 0 - slowLoopLineCount = 0 - for i in range(len(logdata.channels["PM"]["NLon"].listData)): - (line, nLon) = logdata.channels["PM"]["NLon"].listData[i] - (line, nLoop) = logdata.channels["PM"]["NLoop"].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 (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.status = TestResult.StatusType.WARN - 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 deleted file mode 100644 index 1da9f6df809cb8..00000000000000 --- a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py +++ /dev/null @@ -1,163 +0,0 @@ -# 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 - - def __init__(self): - Test.__init__(self) - self.name = "Pitch/Roll" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - if logdata.vehicleType != VehicleType.Copter: - self.result.status = TestResult.StatusType.NA - return - - if "ATT" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No ATT log data" - return - - 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' - - # 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 - 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 - prevLine = 0 - mode = "" - 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)) - prevLine = line - isAuto = True - elif mode in manualModes: - if isAuto: - autoSegments.append((prevLine, line - 1)) - prevLine = line - isAuto = False - elif mode in ignoreModes: - if isAuto: - autoSegments.append((prevLine, line - 1)) - else: - 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)) - elif mode in manualModes: - 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 - - # 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) - (maxPitch, maxPitchLine) = (0.0, 0) - 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) - 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())) - 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) - ): - lit = DataflashLog.LogIterator(logdata, startLine) - assert lit.currentLine == startLine - while lit.currentLine <= endLine: - relativeAlt = lit["CTUN"][self.ctun_baralt_att] - if relativeAlt > minAltThreshold: - roll = lit["ATT"]["Roll"] - pitch = lit["ATT"]["Pitch"] - 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): - maxPitch = pitch - maxPitchLine = lit.currentLine - next(lit) - # check for breaking max lean angles - 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, - ) - return - if maxPitch: - self.result.status = TestResult.StatusType.FAIL - 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 deleted file mode 100644 index c33ebc9cb03c20..00000000000000 --- a/Tools/LogAnalyzer/tests/TestThrust.py +++ /dev/null @@ -1,90 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from __future__ import print_function - -from LogAnalyzer import Test, TestResult -from VehicleType import VehicleType - - -class TestThrust(Test): - '''test for sufficient thrust (copter only for now)''' - - def __init__(self): - Test.__init__(self) - self.name = "Thrust" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - if logdata.vehicleType != VehicleType.Copter: - self.result.status = TestResult.StatusType.NA - return - - if "CTUN" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No CTUN log data" - return - if "ATT" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No ATT log data" - return - - throut_key = None - for key in "ThO", "ThrOut": - if key in logdata.channels["CTUN"]: - throut_key = key - break - if throut_key is None: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "Could not find throttle out column" - return - - # 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 - 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 - start = None - data = logdata.channels["CTUN"][throut_key].listData - 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) - if (abs(roll) > tiltThreshold) or (abs(pitch) > tiltThreshold): - isBelowTiltThreshold = False - if (value > highThrottleThreshold) and isBelowTiltThreshold: - if start is None: - start = i - elif start is not None: - if (i - start) > minSampleLength: - highThrottleSegments.append((start, i)) - start = None - - climbRate = "CRate" - if "CRate" not in logdata.channels["CTUN"]: - climbRate = "CRt" - - # 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() - if avgClimbRate < climbThresholdFAIL: - self.result.status = TestResult.StatusType.FAIL - 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) diff --git a/Tools/LogAnalyzer/tests/TestVCC.py b/Tools/LogAnalyzer/tests/TestVCC.py deleted file mode 100644 index fedef39d16e1cf..00000000000000 --- a/Tools/LogAnalyzer/tests/TestVCC.py +++ /dev/null @@ -1,43 +0,0 @@ -# AP_FLAKE8_CLEAN - -from LogAnalyzer import Test, TestResult - - -class TestVCC(Test): - '''test for VCC within recommendations, or abrupt end to log in flight''' - - def __init__(self): - Test.__init__(self) - self.name = "VCC" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - 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: - 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 - 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) - 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), - ) diff --git a/Tools/LogAnalyzer/tests/TestVibration.py b/Tools/LogAnalyzer/tests/TestVibration.py deleted file mode 100644 index ac7d6e9979ba8f..00000000000000 --- a/Tools/LogAnalyzer/tests/TestVibration.py +++ /dev/null @@ -1,76 +0,0 @@ -# AP_FLAKE8_CLEAN - - -from __future__ import print_function - -import DataflashLog -import numpy -from LogAnalyzer import Test, TestResult -from VehicleType import VehicleType - - -class TestVibration(Test): - '''test for accelerometer vibration (accX/accY/accZ) within recommendations''' - - def __init__(self): - Test.__init__(self) - self.name = "Vibration" - - def run(self, logdata, verbose): - self.result = TestResult() - - if logdata.vehicleType != VehicleType.Copter: - self.result.status = TestResult.StatusType.NA - return - - # constants - aimRangeWarnXY = 1.5 - aimRangeFailXY = 3.0 - aimRangeWarnZ = 2.0 # gravity +/- aim range - aimRangeFailZ = 5.0 # gravity +/- aim range - - if "IMU" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No IMU log data" - return - - # find some stable LOITER data to analyze, at least 10 seconds - 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" - 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: accumulate all LOITER chunks over min size, or just use the largest one? - startLine = chunks[0][0] - endLine = chunks[0][1] - - 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)) - 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) - 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, - ) - else: - self.result.status = TestResult.StatusType.GOOD - self.result.statusMessage = "Good vibration values (X:%.2fg, Y:%.2fg, Z:%.2fg)" % ( - stdDevX, - stdDevY, - stdDevZ, - ) diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 9a84053ab81ada..0691cff6b4c199 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -24,9 +24,9 @@ extern struct user_parameter *user_parameters; LogReader::LogReader(struct LogStructure *log_structure, NavEKF2 &_ekf2, NavEKF3 &_ekf3) : AP_LoggerFileReader(), - _log_structure(log_structure), ekf2(_ekf2), - ekf3(_ekf3) + ekf3(_ekf3), + _log_structure(log_structure) { } @@ -61,71 +61,71 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f) // map from format name to a parser subclass: if (streq(name, "PARM")) { - msgparser[f.type] = new LR_MsgHandler_PARM(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_PARM(formats[f.type]); } else if (streq(name, "RFRH")) { - msgparser[f.type] = new LR_MsgHandler_RFRH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRH(formats[f.type]); } else if (streq(name, "RFRF")) { - msgparser[f.type] = new LR_MsgHandler_RFRF(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRF(formats[f.type], ekf2, ekf3); } else if (streq(name, "RFRN")) { - msgparser[f.type] = new LR_MsgHandler_RFRN(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RFRN(formats[f.type]); } else if (streq(name, "REV2")) { - msgparser[f.type] = new LR_MsgHandler_REV2(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REV2(formats[f.type], ekf2, ekf3); } else if (streq(name, "RSO2")) { - msgparser[f.type] = new LR_MsgHandler_RSO2(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSO2(formats[f.type], ekf2, ekf3); } else if (streq(name, "RWA2")) { - msgparser[f.type] = new LR_MsgHandler_RWA2(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWA2(formats[f.type], ekf2, ekf3); } else if (streq(name, "REV3")) { - msgparser[f.type] = new LR_MsgHandler_REV3(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REV3(formats[f.type], ekf2, ekf3); } else if (streq(name, "RSO3")) { - msgparser[f.type] = new LR_MsgHandler_RSO3(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSO3(formats[f.type], ekf2, ekf3); } else if (streq(name, "RWA3")) { - msgparser[f.type] = new LR_MsgHandler_RWA3(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWA3(formats[f.type], ekf2, ekf3); } else if (streq(name, "REY3")) { - msgparser[f.type] = new LR_MsgHandler_REY3(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REY3(formats[f.type], ekf2, ekf3); } else if (streq(name, "RISH")) { - msgparser[f.type] = new LR_MsgHandler_RISH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RISH(formats[f.type]); } else if (streq(name, "RISI")) { - msgparser[f.type] = new LR_MsgHandler_RISI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RISI(formats[f.type]); } else if (streq(name, "RASH")) { - msgparser[f.type] = new LR_MsgHandler_RASH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RASH(formats[f.type]); } else if (streq(name, "RASI")) { - msgparser[f.type] = new LR_MsgHandler_RASI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RASI(formats[f.type]); } else if (streq(name, "RBRH")) { - msgparser[f.type] = new LR_MsgHandler_RBRH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBRH(formats[f.type]); } else if (streq(name, "RBRI")) { - msgparser[f.type] = new LR_MsgHandler_RBRI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBRI(formats[f.type]); } else if (streq(name, "RRNH")) { - msgparser[f.type] = new LR_MsgHandler_RRNH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RRNH(formats[f.type]); } else if (streq(name, "RRNI")) { - msgparser[f.type] = new LR_MsgHandler_RRNI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RRNI(formats[f.type]); } else if (streq(name, "RGPH")) { - msgparser[f.type] = new LR_MsgHandler_RGPH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPH(formats[f.type]); } else if (streq(name, "RGPI")) { - msgparser[f.type] = new LR_MsgHandler_RGPI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPI(formats[f.type]); } else if (streq(name, "RGPJ")) { - msgparser[f.type] = new LR_MsgHandler_RGPJ(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RGPJ(formats[f.type]); } else if (streq(name, "RMGH")) { - msgparser[f.type] = new LR_MsgHandler_RMGH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RMGH(formats[f.type]); } else if (streq(name, "RMGI")) { - msgparser[f.type] = new LR_MsgHandler_RMGI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RMGI(formats[f.type]); } else if (streq(name, "RBCH")) { - msgparser[f.type] = new LR_MsgHandler_RBCH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBCH(formats[f.type]); } else if (streq(name, "RBCI")) { - msgparser[f.type] = new LR_MsgHandler_RBCI(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBCI(formats[f.type]); } else if (streq(name, "RVOH")) { - msgparser[f.type] = new LR_MsgHandler_RVOH(formats[f.type]); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RVOH(formats[f.type]); } else if (streq(name, "ROFH")) { - msgparser[f.type] = new LR_MsgHandler_ROFH(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_ROFH(formats[f.type], ekf2, ekf3); } else if (streq(name, "REPH")) { - msgparser[f.type] = new LR_MsgHandler_REPH(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REPH(formats[f.type], ekf2, ekf3); } else if (streq(name, "RSLL")) { - msgparser[f.type] = new LR_MsgHandler_RSLL(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RSLL(formats[f.type], ekf2, ekf3); } else if (streq(name, "REVH")) { - msgparser[f.type] = new LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3); } else if (streq(name, "RWOH")) { - msgparser[f.type] = new LR_MsgHandler_RWOH(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RWOH(formats[f.type], ekf2, ekf3); } else if (streq(name, "RBOH")) { - msgparser[f.type] = new LR_MsgHandler_RBOH(formats[f.type], ekf2, ekf3); + msgparser[f.type] = NEW_NOTHROW LR_MsgHandler_RBOH(formats[f.type], ekf2, ekf3); } else { // debug(" No parser for (%s)\n", name); } diff --git a/Tools/Replay/MsgHandler.cpp b/Tools/Replay/MsgHandler.cpp index 22651b1597eaac..3e0855f55397b8 100644 --- a/Tools/Replay/MsgHandler.cpp +++ b/Tools/Replay/MsgHandler.cpp @@ -45,7 +45,7 @@ struct MsgHandler::format_field_info *MsgHandler::find_field_info(const char *la return &field_info[i]; } } - return NULL; + return nullptr; } MsgHandler::MsgHandler(const struct log_Format &_f) : next_field(0), f(_f) @@ -83,7 +83,6 @@ void MsgHandler::parse_format_fields() while ((next_label = strtok(arg, ",")) != NULL) { if (label_offset > strlen(format)) { - free(labels); printf("too few field times for labels %s (format=%s) (labels=%s)\n", f.name, format, labels); exit(1); @@ -108,7 +107,7 @@ void MsgHandler::parse_format_fields() bool MsgHandler::field_value(uint8_t *msg, const char *label, char *ret, uint8_t retlen) { struct format_field_info *info = find_field_info(label); - if (info == NULL) { + if (info == nullptr) { ::printf("No info for (%s)\n",label); exit(1); } @@ -129,8 +128,7 @@ bool MsgHandler::field_value(uint8_t *msg, const char *label, char *ret, uint8_t bool MsgHandler::field_value(uint8_t *msg, const char *label, Vector3f &ret) { const char *axes = "XYZ"; - uint8_t i; - for(i=0; iname, gopt.optarg, eq-gopt.optarg); u->value = atof(eq+1); u->next = user_parameters; @@ -297,26 +297,27 @@ bool Replay::parse_param_line(char *line, char **vname, float &value) */ void Replay::load_param_file(const char *pfilename) { - FILE *f = fopen(pfilename, "r"); - if (f == NULL) { + auto &fs = AP::FS(); + int fd = fs.open(pfilename, O_RDONLY, true); + if (fd == -1) { printf("Failed to open parameter file: %s\n", pfilename); exit(1); } char line[100]; - while (fgets(line, sizeof(line)-1, f)) { + while (fs.fgets(line, sizeof(line)-1, fd)) { char *pname; float value; if (!parse_param_line(line, &pname, value)) { continue; } - struct user_parameter *u = new user_parameter; + struct user_parameter *u = NEW_NOTHROW user_parameter; strncpy_noterm(u->name, pname, sizeof(u->name)); u->value = value; u->next = user_parameters; user_parameters = u; } - fclose(f); + fs.close(fd); } Replay replay(replayvehicle); diff --git a/Tools/Replay/wscript b/Tools/Replay/wscript index 936707364ec844..0e3b9c28ba508d 100644 --- a/Tools/Replay/wscript +++ b/Tools/Replay/wscript @@ -17,9 +17,6 @@ def build(bld): name=vehicle + '_libs', ap_vehicle=vehicle, ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AP_Beacon', - 'AP_Arming', - 'AP_RCMapper', 'AP_OSD', 'AP_Avoidance', ], diff --git a/Tools/ardupilotwaf/ap_library.py b/Tools/ardupilotwaf/ap_library.py index 67cb61428248b8..9d0971c1e816f7 100644 --- a/Tools/ardupilotwaf/ap_library.py +++ b/Tools/ardupilotwaf/ap_library.py @@ -29,7 +29,7 @@ import os import re -from waflib import Errors, Task, Utils +from waflib import Errors, Task, Utils, Logs from waflib.Configure import conf from waflib.TaskGen import after_method, before_method, feature from waflib.Tools import c_preproc @@ -206,6 +206,8 @@ def scan(self): # force dependency scan, if necessary self.compiled_task.signature() + if not self.compiled_task.uid() in self.generator.bld.node_deps: + return r, [] for n in self.generator.bld.node_deps[self.compiled_task.uid()]: # using common Node methods doesn't work here p = n.abspath() @@ -319,6 +321,125 @@ def ap_library_register_for_check(self): tsk = self.create_task('ap_library_check_headers') tsk.compiled_task = t +def write_compilation_database(bld): + """ + Write the compilation database as JSON + """ + database_file = bld.bldnode.find_or_declare('compile_commands.json') + # don't remove the file at clean + + Logs.info('Build commands will be stored in %s', database_file.path_from(bld.path)) + try: + root = database_file.read_json() + except IOError: + root = [] + compile_cmd_db = dict((x['file'], x) for x in root) + for task in bld.compilation_database_tasks: + try: + cmd = task.last_cmd + except AttributeError: + continue + f_node = task.inputs[0] + filename = f_node.path_from(task.get_cwd()) + entry = { + "directory": task.get_cwd().abspath(), + "arguments": cmd, + "file": filename, + } + compile_cmd_db[filename] = entry + root = list(compile_cmd_db.values()) + database_file.write_json(root) + +def target_list_changed(bld, targets): + """ + Check if the list of targets has changed recorded in target_list file + """ + # target_list file is in the root build directory + target_list_file = bld.bldnode.find_or_declare('target_list') + try: + with open(target_list_file.abspath(), 'r') as f: + old_targets = f.read().strip().split(',') + except IOError: + Logs.info('No target_list file found, creating') + old_targets = [] + if old_targets != targets: + with open(target_list_file.abspath(), 'w') as f: + f.write(','.join(targets)) + return True + return False + +@conf +def remove_target_list(cfg): + target_list_file = cfg.bldnode.make_node(cfg.options.board + '/target_list') + try: + Logs.info('Removing target_list file %s', target_list_file.abspath()) + os.remove(target_list_file.abspath()) + except OSError: + pass + +@feature('cxxprogram', 'cxxstlib') +@after_method('propagate_uselib_vars') +def dry_run_compilation_database(self): + if not hasattr(self, 'bld'): + return + bld = self.bld + bld.compilation_database_tasks = [] + targets = bld.targets.split(',') + use = self.use + if isinstance(use, str): + use = [use] + # if targets have not changed and neither has configuration, + # we can skip compilation database generation + if not target_list_changed(bld, targets + use): + Logs.info('Targets have not changed, skipping compilation database compile_commands.json generation') + return + Logs.info('Generating compile_commands.json') + # we need only to generate last_cmd, so override + # exec_command temporarily + def exec_command(bld, *k, **kw): + return 0 + + for g in bld.groups: + for tg in g: + # we only care to list targets and library objects + if not hasattr(tg, 'name'): + continue + if (tg.name not in targets) and (tg.name not in self.use): + continue + try: + f = tg.post + except AttributeError: + pass + else: + f() + + if isinstance(tg, Task.Task): + lst = [tg] + else: + lst = tg.tasks + for tsk in lst: + if tsk.__class__.__name__ == "swig": + tsk.runnable_status() + if hasattr(tsk, 'more_tasks'): + lst.extend(tsk.more_tasks) + # Not all dynamic tasks can be processed, in some cases + # one may have to call the method "run()" like this: + # elif tsk.__class__.__name__ == 'src2c': + # tsk.run() + # if hasattr(tsk, 'more_tasks'): + # lst.extend(tsk.more_tasks) + + tup = tuple(y for y in [Task.classes.get(x) for x in ('c', 'cxx')] if y) + if isinstance(tsk, tup): + bld.compilation_database_tasks.append(tsk) + tsk.nocache = True + old_exec = tsk.exec_command + tsk.exec_command = exec_command + tsk.run() + tsk.exec_command = old_exec + + write_compilation_database(bld) + def configure(cfg): cfg.env.AP_LIBRARIES_OBJECTS_KW = dict() cfg.env.AP_LIB_EXTRA_SOURCES = dict() diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index 0e8da6da66ee24..3b1187d198d22b 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -1,12 +1,14 @@ # encoding: utf-8 from __future__ import print_function -from waflib import Build, ConfigSet, Configure, Context, Errors, Logs, Options, Utils +from waflib import Build, ConfigSet, Configure, Context, Errors, Logs, Options, Utils, Task from waflib.Configure import conf from waflib.Scripting import run_command -from waflib.TaskGen import before_method, feature +from waflib.TaskGen import before_method, after_method, feature import os.path, os +from pathlib import Path from collections import OrderedDict +import subprocess import ap_persistent @@ -16,6 +18,13 @@ '*.cpp', ] +COMMON_VEHICLE_DEPENDENT_CAN_LIBRARIES = [ + 'AP_CANManager', + 'AP_KDECAN', + 'AP_PiccoloCAN', + 'AP_PiccoloCAN/piccolo_protocol', +] + COMMON_VEHICLE_DEPENDENT_LIBRARIES = [ 'AP_Airspeed', 'AP_AccelCal', @@ -26,15 +35,14 @@ 'AP_BattMonitor', 'AP_BoardConfig', 'AP_Camera', - 'AP_CANManager', 'AP_Common', 'AP_Compass', 'AP_Declination', 'AP_GPS', + 'AP_GSOF', 'AP_HAL', 'AP_HAL_Empty', 'AP_InertialSensor', - 'AP_KDECAN', 'AP_Math', 'AP_Mission', 'AP_DAL', @@ -66,6 +74,7 @@ 'AP_ICEngine', 'AP_Networking', 'AP_Frsky_Telem', + 'AP_IBus_Telem', 'AP_FlashStorage', 'AP_Relay', 'AP_ServoRelayEvents', @@ -73,8 +82,6 @@ 'AP_SBusOut', 'AP_IOMCU', 'AP_Parachute', - 'AP_PiccoloCAN', - 'AP_PiccoloCAN/piccolo_protocol', 'AP_RAMTRON', 'AP_RCProtocol', 'AP_Radio', @@ -119,6 +126,10 @@ 'AP_CheckFirmware', 'AP_ExternalControl', 'AP_JSON', + 'AP_Beacon', + 'AP_Arming', + 'AP_RCMapper', + 'AP_MultiHeap', ] def get_legacy_defines(sketch_name, bld): @@ -246,16 +257,89 @@ def ap_get_all_libraries(bld): def ap_common_vehicle_libraries(bld): libraries = COMMON_VEHICLE_DEPENDENT_LIBRARIES - if bld.env.DEST_BINFMT == 'pe': - libraries += [ - 'AC_Fence', - 'AC_AttitudeControl', - ] + if bld.env.with_can or bld.env.HAL_NUM_CAN_IFACES: + libraries.extend(COMMON_VEHICLE_DEPENDENT_CAN_LIBRARIES) return libraries _grouped_programs = {} + +class upload_fw_blueos(Task.Task): + def run(self): + # this is rarely used, so we import requests here to avoid the overhead + import requests + binary_path = self.inputs[0].abspath() + # check if .apj file exists for chibios builds + if Path(binary_path + ".apj").exists(): + binary_path = binary_path + ".apj" + bld = self.generator.bld + board = bld.bldnode.name.capitalize() + print(f"Uploading {binary_path} to BlueOS at {bld.options.upload_blueos} for board {board}") + url = f'{bld.options.upload_blueos}/ardupilot-manager/v1.0/install_firmware_from_file?board_name={board}' + files = { + 'binary': open(binary_path, 'rb') + } + response = requests.post(url, files=files, verify=False) + if response.status_code != 200: + raise Errors.WafError(f"Failed to upload firmware to BlueOS: {response.status_code}: {response.text}") + print("Upload complete") + + def keyword(self): + return "Uploading to BlueOS" + +class check_elf_symbols(Task.Task): + color='CYAN' + always_run = True + def keyword(self): + return "checking symbols" + + def run(self): + ''' + check for disallowed symbols in elf file, such as C++ exceptions + ''' + elfpath = self.inputs[0].abspath() + + if not self.env.CHECK_SYMBOLS: + # checking symbols disabled on this build + return + + if not self.env.vehicle_binary or self.env.SIM_ENABLED: + # we only want to check symbols for vehicle binaries, allowing examples + # to use C++ exceptions. We also allow them in simulator builds + return + + # we use string find on these symbols, so this catches all types of throw + # calls this should catch all uses of exceptions unless the compiler + # manages to inline them + blacklist = ['std::__throw', + 'operator new[](unsigned int)', + 'operator new[](unsigned long)', + 'operator new(unsigned int)', + 'operator new(unsigned long)'] + + nmout = subprocess.getoutput("%s -C %s" % (self.env.get_flat('NM'), elfpath)) + for b in blacklist: + if nmout.find(b) != -1: + raise Errors.WafError("Disallowed symbol in %s: %s" % (elfpath, b)) + + +@feature('post_link') +@after_method('process_source') +def post_link(self): + ''' + setup tasks to run after link stage + ''' + self.link_task.always_run = True + + link_output = self.link_task.outputs[0] + + check_elf_task = self.create_task('check_elf_symbols', src=link_output) + check_elf_task.set_run_after(self.link_task) + if self.bld.options.upload_blueos and self.env["BOARD_CLASS"] == "LINUX": + _upload_task = self.create_task('upload_fw_blueos', src=link_output) + _upload_task.set_run_after(self.link_task) + @conf def ap_program(bld, program_groups='bin', @@ -277,7 +361,7 @@ def ap_program(bld, if use_legacy_defines: kw['defines'].extend(get_legacy_defines(bld.path.name, bld)) - kw['features'] = kw.get('features', []) + bld.env.AP_PROGRAM_FEATURES + kw['features'] = kw.get('features', []) + bld.env.AP_PROGRAM_FEATURES + ['post_link'] program_groups = Utils.to_list(program_groups) @@ -538,13 +622,14 @@ def _select_programs_from_group(bld): else: groups = ['bin'] + possible_groups = list(_grouped_programs.keys()) + possible_groups.remove('bin') # Remove `bin` so as not to duplicate all items in bin if 'all' in groups: - groups = list(_grouped_programs.keys()) - groups.remove('bin') # Remove `bin` so as not to duplicate all items in bin + groups = possible_groups for group in groups: if group not in _grouped_programs: - bld.fatal('Group %s not found' % group) + bld.fatal(f'Group {group} not found, possible groups: {possible_groups}') target_names = _grouped_programs[group].keys() @@ -587,6 +672,13 @@ def options(opt): help='''Specify the port to be used with the --upload option. For example a port of /dev/ttyS10 indicates that serial port 10 shuld be used. ''') + g.add_option('--upload-blueos', + action='store', + dest='upload_blueos', + default=None, + help='''Automatically upload to a BlueOS device. The argument is the url for the device. http://blueos.local for example. +''') + g.add_option('--upload-force', action='store_true', help='''Override board type check and continue loading. Same as using uploader.py --force. diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 9b6824fc676795..0e692be45a6fec 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -4,6 +4,7 @@ import re import sys, os import fnmatch +import platform import waflib from waflib import Utils @@ -12,6 +13,11 @@ _board_classes = {} _board = None +# modify our search path: +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../libraries/AP_HAL_ChibiOS/hwdef/scripts')) +import chibios_hwdef +import build_options + class BoardMeta(type): def __init__(cls, name, bases, dct): super(BoardMeta, cls).__init__(name, bases, dct) @@ -38,13 +44,20 @@ def __init__(self): def configure(self, cfg): cfg.env.TOOLCHAIN = cfg.options.toolchain or self.toolchain cfg.env.ROMFS_FILES = [] - cfg.load('toolchain') + if hasattr(self,'configure_toolchain'): + self.configure_toolchain(cfg) + else: + cfg.load('toolchain') cfg.load('cxx_checks') + # don't check elf symbols by default + cfg.env.CHECK_SYMBOLS = False + env = waflib.ConfigSet.ConfigSet() def srcpath(path): return cfg.srcnode.make_node(path).abspath() env.SRCROOT = srcpath('') + self.configure_env(cfg, env) # Setup scripting: @@ -148,15 +161,26 @@ def srcpath(path): ) cfg.msg("Enabled custom controller", 'no', color='YELLOW') - if cfg.options.enable_ppp: - env.CXXFLAGS += ['-DAP_NETWORKING_BACKEND_PPP=1'] + # support enabling any option in build_options.py + for opt in build_options.BUILD_OPTIONS: + enable_option = opt.config_option().replace("-","_") + disable_option = "disable_" + enable_option[len("enable-"):] + if getattr(cfg.options, enable_option, False): + env.CXXFLAGS += ['-D%s=1' % opt.define] + cfg.msg("Enabled %s" % opt.label, 'yes', color='GREEN') + elif getattr(cfg.options, disable_option, False): + env.CXXFLAGS += ['-D%s=0' % opt.define] + cfg.msg("Enabled %s" % opt.label, 'no', color='YELLOW') if cfg.options.disable_networking: env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=0'] if cfg.options.enable_networking_tests: env.CXXFLAGS += ['-DAP_NETWORKING_TESTS_ENABLED=1'] - + + if cfg.options.enable_iomcu_profiled_support: + env.CXXFLAGS += ['-DAP_IOMCU_PROFILED_SUPPORT_ENABLED=1'] + d = env.get_merged_dict() # Always prepend so that arguments passed in the command line get # the priority. @@ -179,7 +203,7 @@ def srcpath(path): cfg.env.prepend_value('INCLUDES', [ cfg.srcnode.find_dir('libraries/AP_Common/missing').abspath() ]) - if os.path.exists(os.path.join(env.SRCROOT, '.vscode/c_cpp_properties.json')): + if os.path.exists(os.path.join(env.SRCROOT, '.vscode/c_cpp_properties.json')) and 'AP_NO_COMPILE_COMMANDS' not in os.environ: # change c_cpp_properties.json configure the VSCode Intellisense env c_cpp_properties = json.load(open(os.path.join(env.SRCROOT, '.vscode/c_cpp_properties.json'))) for config in c_cpp_properties['configurations']: @@ -190,6 +214,8 @@ def srcpath(path): cfg.msg("Configured VSCode Intellisense:", 'no', color='YELLOW') def cc_version_gte(self, cfg, want_major, want_minor): + if cfg.env.TOOLCHAIN == "custom": + return True (major, minor, patchlevel) = cfg.env.CC_VERSION return (int(major) > want_major or (int(major) == want_major and int(minor) >= want_minor)) @@ -199,6 +225,8 @@ def configure_env(self, cfg, env): # make easy to override them. Convert back to list before consumption. env.DEFINES = {} + env.with_can = self.with_can + # 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]: @@ -272,7 +300,6 @@ def configure_env(self, cfg, env): '-Werror=implicit-fallthrough', ] env.CXXFLAGS += [ - '-fcheck-new', '-fsingle-precision-constant', '-Wno-psabi', ] @@ -337,10 +364,10 @@ def configure_env(self, cfg, env): '-Wpointer-arith', '-Wno-unused-parameter', '-Wno-missing-field-initializers', - '-Wno-reorder', '-Wno-redundant-decls', '-Wno-unknown-pragmas', '-Wno-expansion-to-defined', + '-Werror=reorder', '-Werror=cast-align', '-Werror=attributes', '-Werror=format-security', @@ -416,6 +443,13 @@ def configure_env(self, cfg, env): env.CXXFLAGS += [ '-Werror=sizeof-pointer-div', ] + if self.cc_version_gte(cfg, 13, 2): + env.CXXFLAGS += [ + '-Werror=use-after-free', + ] + env.CFLAGS += [ + '-Werror=use-after-free', + ] if cfg.options.Werror: errors = ['-Werror', @@ -433,9 +467,14 @@ def configure_env(self, cfg, env): ] if cfg.env.DEST_OS == 'darwin': - env.LINKFLAGS += [ - '-Wl,-dead_strip', - ] + if self.cc_version_gte(cfg, 15, 0): + env.LINKFLAGS += [ + '-Wl,-dead_strip,-ld_classic', + ] + else: + env.LINKFLAGS += [ + '-Wl,-dead_strip', + ] else: env.LINKFLAGS += [ '-fno-exceptions', @@ -468,12 +507,6 @@ def configure_env(self, cfg, env): # We always want to use PRI format macros cfg.define('__STDC_FORMAT_MACROS', 1) - if cfg.options.enable_ekf2: - env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=1'] - - if cfg.options.disable_ekf3: - env.CXXFLAGS += ['-DHAL_NAVEKF3_AVAILABLE=0'] - if cfg.options.postype_single: env.CXXFLAGS += ['-DHAL_WITH_POSTYPE_DOUBLE=0'] @@ -537,6 +570,14 @@ def embed_ROMFS_files(self, ctx): if not embed.create_embedded_h(header, ctx.env.ROMFS_FILES, ctx.env.ROMFS_UNCOMPRESSED): ctx.fatal("Failed to created ap_romfs_embedded.h") + ctx.env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] + + # Allow lua to load from ROMFS if any lua files are added + for file in ctx.env.ROMFS_FILES: + if file[0].startswith("scripts") and file[0].endswith(".lua"): + ctx.env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] + break + Board = BoardMeta('Board', Board.__bases__, dict(Board.__dict__)) def add_dynamic_boards_chibios(): @@ -590,21 +631,13 @@ def get_ap_periph_boards(): continue hwdef = os.path.join(dirname, d, 'hwdef.dat') if os.path.exists(hwdef): - with open(hwdef, "r") as f: - content = f.read() - if 'AP_PERIPH' in content: + ch = chibios_hwdef.ChibiOSHWDef(hwdef=[hwdef], quiet=True) + try: + if ch.is_periph_fw_unprocessed(): list_ap.append(d) - continue - # process any include lines: - m = re.match(r"include\s+([^\s]*)", content) - if m is None: - continue - include_path = os.path.join(os.path.dirname(hwdef), m.group(1)) - with open(include_path, "r") as g: - content = g.read() - if 'AP_PERIPH' in content: - list_ap.append(d) - continue + except chibios_hwdef.ChibiOSHWDefIncludeNotFoundException as e: + print(f"{e.includer} includes {e.hwdef} which does not exist") + sys.exit(1) list_ap = list(set(list_ap)) return list_ap @@ -666,6 +699,12 @@ def configure_env(self, cfg, env): cfg.define('AP_NOTIFY_LP5562_BUS', 2) cfg.define('AP_NOTIFY_LP5562_ADDR', 0x30) + # turn on fencepoint and rallypoint protocols so they're still tested: + env.CXXFLAGS.extend([ + '-DAP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED=HAL_GCS_ENABLED&&HAL_RALLY_ENABLED', + '-DAC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT=HAL_GCS_ENABLED&&AP_FENCE_ENABLED' + ]) + try: env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=0') except ValueError: @@ -744,6 +783,13 @@ def configure_env(self, cfg, env): 'SITL', ] + # wrap malloc to ensure memory is zeroed + if cfg.env.DEST_OS == 'cygwin': + # on cygwin we need to wrap _malloc_r instead + env.LINKFLAGS += ['-Wl,--wrap,_malloc_r'] + elif platform.system() != 'Darwin': + env.LINKFLAGS += ['-Wl,--wrap,malloc'] + if cfg.options.enable_sfml: if not cfg.check_SFML(env): cfg.fatal("Failed to find SFML libraries") @@ -772,14 +818,6 @@ def configure_env(self, cfg, env): if fnmatch.fnmatch(f, "*.lua"): env.ROMFS_FILES += [('scripts/'+f,'ROMFS/scripts/'+f)] - if len(env.ROMFS_FILES) > 0: - # Allow lua to load from ROMFS if any lua files are added - for file in env.ROMFS_FILES: - if file[0].startswith("scripts") and file[0].endswith(".lua"): - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] - break - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] - if cfg.options.sitl_rgbled: env.CXXFLAGS += ['-DWITH_SITL_RGBLED'] @@ -915,6 +953,7 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_BATTERY = 1, HAL_PERIPH_ENABLE_EFI = 1, HAL_PERIPH_ENABLE_RPM = 1, + HAL_PERIPH_ENABLE_RPM_STREAM = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, @@ -922,6 +961,7 @@ def configure_env(self, cfg, env): AP_BATTERY_ESC_ENABLED = 1, HAL_PWM_COUNT = 32, HAL_WITH_ESC_TELEM = 1, + AP_EXTENDED_ESC_TELEM_ENABLED = 1, AP_TERRAIN_AVAILABLE = 1, ) @@ -938,6 +978,19 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_GPS = 1, ) +class sitl_periph_battmon(sitl_periph): + def configure_env(self, cfg, env): + cfg.env.AP_PERIPH = 1 + super(sitl_periph_battmon, self).configure_env(cfg, env) + env.DEFINES.update( + HAL_BUILD_AP_PERIPH = 1, + PERIPH_FW = 1, + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_battmon"', + APJ_BOARD_ID = 101, + + HAL_PERIPH_ENABLE_BATTERY = 1, + ) + class esp32(Board): abstract = True toolchain = 'xtensa-esp32-elf' @@ -959,10 +1012,9 @@ def expand_path(p): ) tt = self.name[5:] #leave off 'esp32' so we just get 'buzz','diy','icarus, etc - + # this makes sure we get the correct subtype env.DEFINES.update( - ENABLE_HEAP = 0, CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_ESP32_%s' % tt.upper() , HAL_HAVE_HARDWARE_DOUBLE = '1', ) @@ -976,6 +1028,9 @@ def expand_path(p): else: env.DEFINES.update(AP_SIM_ENABLED = 0) + # FreeRTOS component from esp-idf expects this define + env.DEFINES.update(ESP_PLATFORM = 1) + env.AP_LIBRARIES += [ 'AP_HAL_ESP32', ] @@ -1000,11 +1055,12 @@ def expand_path(p): '-fno-inline-functions', '-mlongcalls', '-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f - '-fno-threadsafe-statics', - '-DCYGWIN_BUILD'] + '-fno-threadsafe-statics'] env.CXXFLAGS.remove('-Werror=undef') env.CXXFLAGS.remove('-Werror=shadow') + # wrap malloc to ensure memory is zeroed + env.LINKFLAGS += ['-Wl,--wrap,malloc'] env.INCLUDES += [ cfg.srcnode.find_dir('libraries/AP_HAL_ESP32/boards').abspath(), @@ -1258,6 +1314,16 @@ def configure_env(self, cfg, env): cfg.msg("Checking for intelhex module:", 'disabled', color='YELLOW') env.HAVE_INTEL_HEX = False + if cfg.options.enable_new_checking: + env.CHECK_SYMBOLS = True + else: + # disable new checking on ChibiOS by default to save flash + # we enable it in a CI test to catch incorrect usage + env.CXXFLAGS += [ + "-DNEW_NOTHROW=new", + "-fcheck-new", # rely on -fcheck-new ensuring nullptr checks + ] + def build(self, bld): super(chibios, self).build(bld) bld.ap_version_append_str('CHIBIOS_GIT_VERSION', bld.git_submodule_head_hash('ChibiOS', short=True)) @@ -1314,6 +1380,9 @@ def configure_env(self, cfg, env): 'AP_HAL_Linux', ] + # wrap malloc to ensure memory is zeroed + env.LINKFLAGS += ['-Wl,--wrap,malloc'] + if cfg.options.force_32bit: env.DEFINES.update( HAL_FORCE_32BIT = 1, @@ -1351,13 +1420,6 @@ def configure_env(self, cfg, env): env.DEFINES.update( HAL_PARAM_DEFAULTS_PATH='"@ROMFS/defaults.parm"', ) - if len(env.ROMFS_FILES) > 0: - # Allow lua to load from ROMFS if any lua files are added - for file in env.ROMFS_FILES: - if file[0].startswith("scripts") and file[0].endswith(".lua"): - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] - break - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] def build(self, bld): super(linux, self).build(bld) @@ -1381,6 +1443,17 @@ def configure_env(self, cfg, env): CONFIG_HAL_BOARD_SUBTYPE='HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR', ) +class navigator64(linux): + toolchain = 'aarch64-linux-gnu' + + def configure_env(self, cfg, env): + super(navigator64, self).configure_env(cfg, env) + + env.DEFINES.update( + CONFIG_HAL_BOARD_SUBTYPE='HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR', + ) + + class erleboard(linux): toolchain = 'arm-linux-gnueabihf' @@ -1619,3 +1692,99 @@ class SITL_x86_64_linux_gnu(SITL_static): class SITL_arm_linux_gnueabihf(SITL_static): toolchain = 'arm-linux-gnueabihf' + +class QURT(Board): + '''support for QURT based boards''' + toolchain = 'custom' + + def __init__(self): + self.with_can = False + + def configure_toolchain(self, cfg): + cfg.env.CXX_NAME = 'gcc' + cfg.env.HEXAGON_SDK_DIR = "/opt/hexagon-sdk/4.1.0.4-lite" + cfg.env.CC_VERSION = ('4','1','0') + cfg.env.TOOLCHAIN_DIR = cfg.env.HEXAGON_SDK_DIR + "/tools/HEXAGON_Tools/8.4.05/Tools" + cfg.env.COMPILER_CC = cfg.env.TOOLCHAIN_DIR + "/bin/hexagon-clang" + cfg.env.COMPILER_CXX = cfg.env.TOOLCHAIN_DIR + "/bin/hexagon-clang++" + cfg.env.LINK_CXX = cfg.env.HEXAGON_SDK_DIR + "/tools/HEXAGON_Tools/8.4.05/Tools/bin/hexagon-link" + cfg.env.CXX = ["ccache", cfg.env.COMPILER_CXX] + cfg.env.CC = ["ccache", cfg.env.COMPILER_CC] + cfg.env.CXX_TGT_F = ['-c', '-o'] + cfg.env.CC_TGT_F = ['-c', '-o'] + cfg.env.CCLNK_SRC_F = [] + cfg.env.CXXLNK_SRC_F = [] + cfg.env.CXXLNK_TGT_F = ['-o'] + cfg.env.CCLNK_TGT_F = ['-o'] + cfg.env.CPPPATH_ST = '-I%s' + cfg.env.DEFINES_ST = '-D%s' + cfg.env.AR = cfg.env.HEXAGON_SDK_DIR + "/tools/HEXAGON_Tools/8.4.05/Tools/bin/hexagon-ar" + cfg.env.ARFLAGS = 'rcs' + cfg.env.cxxstlib_PATTERN = 'lib%s.a' + cfg.env.cstlib_PATTERN = 'lib%s.a' + cfg.env.LIBPATH_ST = '-L%s' + cfg.env.LIB_ST = '-l%s' + cfg.env.SHLIB_MARKER = '' + cfg.env.STLIBPATH_ST = '-L%s' + cfg.env.STLIB_MARKER = '' + cfg.env.STLIB_ST = '-l%s' + cfg.env.LDFLAGS = [ + '-lgcc', + cfg.env.TOOLCHAIN_DIR + '/target/hexagon/lib/v66/G0/pic/finiS.o' + ] + + def configure_env(self, cfg, env): + super(QURT, self).configure_env(cfg, env) + + env.BOARD_CLASS = "QURT" + env.HEXAGON_APP = "libardupilot.so" + env.INCLUDES += [cfg.env.HEXAGON_SDK_DIR + "/rtos/qurt/computev66/include/qurt"] + env.INCLUDES += [cfg.env.HEXAGON_SDK_DIR + "/rtos/qurt/computev66/include/posix"] + + CFLAGS = "-MD -mv66 -fPIC -mcpu=hexagonv66 -G0 -fdata-sections -ffunction-sections -fomit-frame-pointer -fmerge-all-constants -fno-signed-zeros -fno-trapping-math -freciprocal-math -fno-math-errno -fno-strict-aliasing -fvisibility=hidden -fno-rtti -fmath-errno" + env.CXXFLAGS += CFLAGS.split() + env.CFLAGS += CFLAGS.split() + + env.DEFINES.update( + CONFIG_HAL_BOARD = 'HAL_BOARD_QURT', + CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_NONE', + AP_SIM_ENABLED = 0, + ) + + env.LINKFLAGS = [ + "-march=hexagon", + "-mcpu=hexagonv66", + "-shared", + "-call_shared", + "-G0", + cfg.env.TOOLCHAIN_DIR + "/target/hexagon/lib/v66/G0/pic/initS.o", + f"-L{cfg.env.TOOLCHAIN_DIR}/target/hexagon/lib/v66/G0/pic", + "-Bsymbolic", + cfg.env.TOOLCHAIN_DIR + "/target/hexagon/lib/v66/G0/pic/libgcc.a", + "--wrap=malloc", + "--wrap=calloc", + "--wrap=free", + "--wrap=realloc", + "--wrap=printf", + "--wrap=strdup", + "--wrap=__stack_chk_fail", + "-lc" + ] + + if not cfg.env.DEBUG: + env.CXXFLAGS += [ + '-O3', + ] + + env.AP_LIBRARIES += [ + 'AP_HAL_QURT', + ] + + def build(self, bld): + super(QURT, self).build(bld) + bld.load('qurt') + + def get_name(self): + # get name of class + return self.__class__.__name__ + diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 532e75a4b3a331..785bce15bcee55 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -19,7 +19,11 @@ _dynamic_env_data = {} def _load_dynamic_env_data(bld): bldnode = bld.bldnode.make_node('modules/ChibiOS') - tmp_str = bldnode.find_node('include_dirs').read() + include_dirs_node = bldnode.find_node('include_dirs') + if include_dirs_node is None: + _dynamic_env_data['include_dirs'] = [] + return + tmp_str = include_dirs_node.read() tmp_str = tmp_str.replace(';\n','') tmp_str = tmp_str.replace('-I','') #remove existing -I flags # split, coping with separator @@ -144,27 +148,6 @@ def run(self): defaults.save() -def check_elf_symbols(task): - ''' - check for disallowed symbols in elf file, such as C++ exceptions - ''' - elfpath = task.inputs[0].abspath() - - if not task.env.vehicle_binary or task.env.SIM_ENABLED: - # we only want to check symbols for vehicle binaries, allowing examples - # to use C++ exceptions. We also allow them in simulator builds - return - - # we use string find on these symbols, so this catches all types of throw - # calls this should catch all uses of exceptions unless the compiler - # manages to inline them - blacklist = ['std::__throw'] - - nmout = subprocess.getoutput("%s -C %s" % (task.env.get_flat('NM'), elfpath)) - for b in blacklist: - if nmout.find(b) != -1: - raise Errors.WafError("Disallowed symbol in %s: %s" % (elfpath, b)) - class generate_bin(Task.Task): color='CYAN' # run_str="${OBJCOPY} -O binary ${SRC} ${TGT}" @@ -176,8 +159,6 @@ class generate_bin(Task.Task): def keyword(self): return "Generating" def run(self): - check_elf_symbols(self) - if self.env.HAS_EXTERNAL_FLASH_SECTIONS: ret = self.split_sections() if (ret < 0): @@ -257,8 +238,13 @@ def sign_firmware(image, private_keyfile): try: import monocypher except ImportError: - Logs.error("Please install monocypher with: python3 -m pip install pymonocypher") + Logs.error("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") return None + + if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") + return None + try: key = open(private_keyfile, 'r').read() except Exception as ex: @@ -287,12 +273,14 @@ def run(self): else: descriptor = b'\x40\xa2\xe4\xf1\x64\x68\x91\x06' - img = open(self.inputs[0].abspath(), 'rb').read() + elf_file = self.inputs[0].abspath() + bin_file = self.inputs[1].abspath() + img = open(bin_file, 'rb').read() offset = img.find(descriptor) if offset == -1: Logs.info("No APP_DESCRIPTOR found") return - offset += 8 + offset += len(descriptor) # next 8 bytes is 64 bit CRC. We set first 4 bytes to # CRC32 of image before descriptor and 2nd 4 bytes # to CRC32 of image after descriptor. This is very efficient @@ -324,7 +312,19 @@ def run(self): desc = struct.pack('RTL fails into land mode due to bad position.") self.set_parameter('FS_THR_ENABLE', 4) self.takeoffAndMoveAway() - self.set_parameter('SIM_GPS_DISABLE', 1) + self.set_parameter('SIM_GPS1_ENABLE', 0) self.delay_sim_time(5) self.set_parameter("SIM_RC_FAIL", 1) self.wait_mode("LAND") self.wait_landed_and_disarmed() self.set_parameter("SIM_RC_FAIL", 0) - self.set_parameter('SIM_GPS_DISABLE', 0) + self.set_parameter('SIM_GPS1_ENABLE', 1) self.wait_ekf_happy() self.end_subtest("Completed Radio failsafe SmartRTL->RTL fails into land mode due to bad position.") @@ -590,13 +582,13 @@ def ThrottleFailsafe(self, side=60, timeout=360): self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to bad position.") self.set_parameter('FS_THR_ENABLE', 5) self.takeoffAndMoveAway() - self.set_parameter('SIM_GPS_DISABLE', 1) + self.set_parameter('SIM_GPS1_ENABLE', 0) self.delay_sim_time(5) self.set_parameter("SIM_RC_FAIL", 1) self.wait_mode("LAND") self.wait_landed_and_disarmed() self.set_parameter("SIM_RC_FAIL", 0) - self.set_parameter('SIM_GPS_DISABLE', 0) + self.set_parameter('SIM_GPS1_ENABLE', 1) self.wait_ekf_happy() self.end_subtest("Completed Radio failsafe SmartRTL->LAND fails into land mode due to bad position.") @@ -605,9 +597,9 @@ def ThrottleFailsafe(self, side=60, timeout=360): self.start_subtest("Radio failsafe SmartRTL->RTL fails into RTL mode due to no path.") self.set_parameter('FS_THR_ENABLE', 4) self.takeoffAndMoveAway() - self.set_parameter('SIM_GPS_DISABLE', 1) + self.set_parameter('SIM_GPS1_ENABLE', 0) self.wait_statustext("SmartRTL deactivated: bad position", timeout=60) - self.set_parameter('SIM_GPS_DISABLE', 0) + self.set_parameter('SIM_GPS1_ENABLE', 1) self.wait_ekf_happy() self.delay_sim_time(5) self.set_parameter("SIM_RC_FAIL", 1) @@ -621,9 +613,9 @@ def ThrottleFailsafe(self, side=60, timeout=360): self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to no path.") self.set_parameter('FS_THR_ENABLE', 5) self.takeoffAndMoveAway() - self.set_parameter('SIM_GPS_DISABLE', 1) + self.set_parameter('SIM_GPS1_ENABLE', 0) self.wait_statustext("SmartRTL deactivated: bad position", timeout=60) - self.set_parameter('SIM_GPS_DISABLE', 0) + self.set_parameter('SIM_GPS1_ENABLE', 1) self.wait_ekf_happy() self.delay_sim_time(5) self.set_parameter("SIM_RC_FAIL", 1) @@ -969,21 +961,6 @@ def CustomController(self, timeout=300): # Tests all actions and logic behind the battery failsafe def BatteryFailsafe(self, timeout=300): '''Fly Battery Failsafe''' - self.context_push() - ex = None - try: - self.test_battery_failsafe(timeout=timeout) - except Exception as e: - self.print_exception_caught(e) - self.disarm_vehicle(force=True) - ex = e - self.context_pop() - self.reboot_sitl() - - if ex is not None: - raise ex - - def test_battery_failsafe(self, timeout=300): self.progress("Configure battery failsafe parameters") self.set_parameters({ 'SIM_SPEEDUP': 4, @@ -1123,6 +1100,43 @@ def test_battery_failsafe(self, timeout=300): self.progress("All Battery failsafe tests complete") + def BatteryMissing(self): + ''' Test battery health pre-arm and missing failsafe''' + self.context_push() + + # Should be good to arm with no changes + self.wait_ready_to_arm() + + # Make monitor unhealthy, this should result in unhealthy prearm + self.set_parameters({ + 'BATT_VOLT_PIN': -1, + }) + + self.drain_mav() + + # Battery should go unhealthy immediately + self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False) + + # Return monitor to health + self.context_pop() + self.context_push() + + self.wait_ready_to_arm() + + # take off and then trigger in flight + self.takeoff(10, mode="LOITER") + self.set_parameters({ + 'BATT_VOLT_PIN': -1, + }) + + # Should trigger missing failsafe + self.wait_statustext("Battery 1 is missing") + + # Done, reset params and reboot to clear failsafe + self.land_and_disarm() + self.context_pop() + self.reboot_sitl() + def VibrationFailsafe(self): '''Test Vibration Failsafe''' self.context_push() @@ -1425,7 +1439,7 @@ def fly_fence_avoid_test_radius_check(self, timeout=180, avoid_behave=avoid_beha self.wait_altitude(10, 100, relative=True) self.set_rc(3, 1500) self.set_rc(2, 1400) - self.wait_distance_to_home(12, 20) + self.wait_distance_to_home(12, 20, timeout=30) tstart = self.get_sim_time() push_time = 70 # push against barrier for 60 seconds failed_max = False @@ -1484,7 +1498,7 @@ def HorizontalFence(self, timeout=180): self.load_fence("fence-in-middle-of-nowhere.txt") self.delay_sim_time(5) # let fence check run so it loads-from-eeprom - self.assert_prearm_failure("vehicle outside fence") + self.assert_prearm_failure("Vehicle breaching Polygon fence") self.progress("Failed to arm outside fence (good!)") self.clear_fence() self.delay_sim_time(5) # let fence breach clear @@ -1494,7 +1508,7 @@ def HorizontalFence(self, timeout=180): self.start_subtest("ensure we can't arm with bad radius") self.context_push() self.set_parameter("FENCE_RADIUS", -1) - self.assert_prearm_failure("Invalid FENCE_RADIUS value") + self.assert_prearm_failure("Invalid Circle FENCE_RADIUS value") self.context_pop() self.progress("Failed to arm with bad radius") self.drain_mav() @@ -1576,6 +1590,7 @@ def MaxAltFence(self): "FENCE_ENABLE": 1, "AVOID_ENABLE": 0, "FENCE_TYPE": 1, + "FENCE_ENABLE" : 1, }) self.change_alt(10) @@ -1603,6 +1618,58 @@ def MaxAltFence(self): self.zero_throttle() + # MaxAltFence - fly up and make sure fence action does not trigger + # Also check that the vehicle will not try and descend too fast when trying to backup from a max alt fence due to avoidance + def MaxAltFenceAvoid(self): + '''Test Max Alt Fence Avoidance''' + self.takeoff(10, mode="LOITER") + """Hold loiter position.""" + + # enable fence, only max altitude, defualt is 100m + # No action, rely on avoidance to prevent the breach + self.set_parameters({ + "FENCE_ENABLE": 1, + "FENCE_TYPE": 1, + "FENCE_ACTION": 0, + }) + + # Try and fly past the fence + self.set_rc(3, 1920) + + # Avoid should prevent the vehicle flying past the fence, so the altitude wait should timeouts + try: + self.wait_altitude(140, 150, timeout=90, relative=True) + raise NotAchievedException("Avoid should prevent reaching altitude") + except AutoTestTimeoutException: + pass + except Exception as e: + raise e + + # Check descent is not too fast, allow 10% above the configured backup speed + max_descent_rate = -self.get_parameter("AVOID_BACKUP_SPD") * 1.1 + + def get_climb_rate(mav, m): + m_type = m.get_type() + if m_type != 'VFR_HUD': + return + if m.climb < max_descent_rate: + raise NotAchievedException("Decending too fast want %f got %f" % (max_descent_rate, m.climb)) + + self.context_push() + self.install_message_hook_context(get_climb_rate) + + # Reduce fence alt, this will result in a fence breach, but there is no action. + # Avoid should then backup the vehicle to be under the new fence alt. + self.set_parameters({ + "FENCE_ALT_MAX": 50, + }) + self.wait_altitude(40, 50, timeout=90, relative=True) + + self.context_pop() + + self.set_rc(3, 1500) + self.do_RTL() + # fly_alt_min_fence_test - fly down until you hit the fence floor def MinAltFence(self): '''Test Min Alt Fence''' @@ -1611,6 +1678,7 @@ def MinAltFence(self): # enable fence, disable avoidance self.set_parameters({ "AVOID_ENABLE": 0, + "FENCE_ENABLE" : 1, "FENCE_TYPE": 8, "FENCE_ALT_MIN": 20, }) @@ -1647,6 +1715,59 @@ def MinAltFence(self): self.zero_throttle() + # MinAltFenceAvoid - fly down and make sure fence action does not trigger + # Also check that the vehicle will not try and ascend too fast when trying to backup from a min alt fence due to avoidance + def MinAltFenceAvoid(self): + '''Test Min Alt Fence Avoidance''' + self.takeoff(30, mode="LOITER") + """Hold loiter position.""" + + # enable fence, only min altitude + # No action, rely on avoidance to prevent the breach + self.set_parameters({ + "FENCE_ENABLE": 1, + "FENCE_TYPE": 8, + "FENCE_ALT_MIN": 20, + "FENCE_ACTION": 0, + }) + + # Try and fly past the fence + self.set_rc(3, 1120) + + # Avoid should prevent the vehicle flying past the fence, so the altitude wait should timeouts + try: + self.wait_altitude(10, 15, timeout=90, relative=True) + raise NotAchievedException("Avoid should prevent reaching altitude") + except AutoTestTimeoutException: + pass + except Exception as e: + raise e + + # Check ascent is not too fast, allow 10% above the configured backup speed + max_ascent_rate = self.get_parameter("AVOID_BACKUP_SPD") * 1.1 + + def get_climb_rate(mav, m): + m_type = m.get_type() + if m_type != 'VFR_HUD': + return + if m.climb > max_ascent_rate: + raise NotAchievedException("Ascending too fast want %f got %f" % (max_ascent_rate, m.climb)) + + self.context_push() + self.install_message_hook_context(get_climb_rate) + + # Reduce fence alt, this will result in a fence breach, but there is no action. + # Avoid should then backup the vehicle to be over the new fence alt. + self.set_parameters({ + "FENCE_ALT_MIN": 30, + }) + self.wait_altitude(30, 40, timeout=90, relative=True) + + self.context_pop() + + self.set_rc(3, 1500) + self.do_RTL() + def FenceFloorEnabledLanding(self): """Ensures we can initiate and complete an RTL while the fence is enabled. @@ -1656,18 +1777,71 @@ def FenceFloorEnabledLanding(self): self.progress("Test Landing while fence floor enabled") self.set_parameters({ "AVOID_ENABLE": 0, + "FENCE_ENABLE" : 1, "FENCE_TYPE": 15, + "FENCE_ALT_MIN": 20, + "FENCE_ALT_MAX": 30, + }) + + self.change_mode("GUIDED") + self.wait_ready_to_arm() + self.arm_vehicle() + self.user_takeoff(alt_min=25) + + # Check fence is enabled + self.assert_fence_enabled() + + # Change to RC controlled mode + self.change_mode('LOITER') + + self.set_rc(3, 1800) + + self.wait_mode('RTL', timeout=120) + # center throttle + self.set_rc(3, 1500) + + # wait until we are below the fence floor and re-enter loiter + self.wait_altitude(5, 15, relative=True) + self.change_mode('LOITER') + # wait for manual recovery to expire + self.delay_sim_time(15) + + # lower throttle and try and land + self.set_rc(3, 1300) + self.wait_altitude(0, 2, relative=True) + self.zero_throttle() + self.wait_landed_and_disarmed() + self.assert_fence_enabled() + # must not be in RTL + self.assert_mode("LOITER") + + # Assert fence is healthy since it was enabled automatically + self.assert_sensor_state(fence_bit, healthy=True) + + # Disable the fence using mavlink command to ensure cleaned up SITL state + self.do_fence_disable() + self.assert_fence_disabled() + + def FenceFloorAutoDisableLanding(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") + self.set_parameters({ + "AVOID_ENABLE": 0, + "FENCE_TYPE": 11, "FENCE_ALT_MIN": 10, "FENCE_ALT_MAX": 20, + "FENCE_AUTOENABLE" : 1, }) self.change_mode("GUIDED") self.wait_ready_to_arm() self.arm_vehicle() - self.user_takeoff(alt_min=15) + self.takeoff(alt_min=15, mode="GUIDED") # Check fence is enabled - self.do_fence_enable() self.assert_fence_enabled() # Change to RC controlled mode @@ -1676,14 +1850,57 @@ def FenceFloorEnabledLanding(self): self.set_rc(3, 1800) self.wait_mode('RTL', timeout=120) - self.wait_landed_and_disarmed() + + self.wait_landed_and_disarmed(0) + # the breach should have cleared since we auto-disable the + # fence on landing + self.assert_fence_disabled() + + # Assert fences have gone now that we have landed and disarmed + self.assert_sensor_state(fence_bit, present=True, enabled=False) + + def FenceFloorAutoEnableOnArming(self): + """Ensures we can auto-enable fences on arming and still takeoff and land""" + + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE + + self.set_parameters({ + "AVOID_ENABLE": 0, + "FENCE_TYPE": 11, + "FENCE_ALT_MIN": 10, + "FENCE_ALT_MAX": 20, + "FENCE_AUTOENABLE" : 3, + }) + + self.change_mode("GUIDED") + # Check fence is not enabled + self.assert_fence_disabled() + + self.wait_ready_to_arm() + self.arm_vehicle() + self.takeoff(alt_min=15, mode="GUIDED") + + # Check fence is enabled self.assert_fence_enabled() - # Assert fence is not healthy + # Change to RC controlled mode + self.change_mode('LOITER') + + self.set_rc(3, 1800) + + self.wait_mode('RTL', timeout=120) + # Assert fence is not healthy now that we are in RTL self.assert_sensor_state(fence_bit, healthy=False) + self.wait_landed_and_disarmed(0) + # the breach should have cleared since we auto-disable the + # fence on landing + self.assert_fence_disabled() + + # Assert fences have gone now that we have landed and disarmed + self.assert_sensor_state(fence_bit, present=True, enabled=False) + # Disable the fence using mavlink command to ensure cleaned up SITL state - self.do_fence_disable() self.assert_fence_disabled() def GPSGlitchLoiter(self, timeout=30, max_distance=20): @@ -1741,8 +1958,8 @@ def GPSGlitchLoiter(self, timeout=30, max_distance=20): glitch_current = 0 self.progress("Apply first glitch") self.set_parameters({ - "SIM_GPS_GLITCH_X": glitch_lat[glitch_current], - "SIM_GPS_GLITCH_Y": glitch_lon[glitch_current], + "SIM_GPS1_GLTCH_X": glitch_lat[glitch_current], + "SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current], }) # record position for 30 seconds @@ -1756,15 +1973,15 @@ def GPSGlitchLoiter(self, timeout=30, max_distance=20): glitch_current = -1 self.progress("Completed Glitches") self.set_parameters({ - "SIM_GPS_GLITCH_X": 0, - "SIM_GPS_GLITCH_Y": 0, + "SIM_GPS1_GLTCH_X": 0, + "SIM_GPS1_GLTCH_Y": 0, }) else: self.progress("Applying glitch %u" % glitch_current) # move onto the next glitch self.set_parameters({ - "SIM_GPS_GLITCH_X": glitch_lat[glitch_current], - "SIM_GPS_GLITCH_Y": glitch_lon[glitch_current], + "SIM_GPS1_GLTCH_X": glitch_lat[glitch_current], + "SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current], }) # start displaying distance moved after all glitches applied @@ -1785,8 +2002,8 @@ def GPSGlitchLoiter(self, timeout=30, max_distance=20): # disable gps glitch if glitch_current != -1: self.set_parameters({ - "SIM_GPS_GLITCH_X": 0, - "SIM_GPS_GLITCH_Y": 0, + "SIM_GPS1_GLTCH_X": 0, + "SIM_GPS1_GLTCH_Y": 0, }) if self.use_map: self.show_gps_and_sim_positions(False) @@ -1807,7 +2024,7 @@ def GPSGlitchLoiter2(self): self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=1) # apply glitch - self.set_parameter("SIM_GPS_GLITCH_X", 0.001) + self.set_parameter("SIM_GPS1_GLTCH_X", 0.001) # check lean angles remain stable for 20 seconds tstart = self.get_sim_time() @@ -1878,6 +2095,22 @@ def GPSGlitchAuto(self, timeout=180): self.show_gps_and_sim_positions(False) raise e + # stop and test loss of GPS for a short time - it should resume GPS use without falling back into a non aiding mode + self.change_mode("LOITER") + self.set_parameters({ + "SIM_GPS1_ENABLE": 0, + }) + self.delay_sim_time(2) + self.set_parameters({ + "SIM_GPS1_ENABLE": 1, + }) + # regaining GPS should not result in it falling back to a non-navigation mode + self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=1) + # It should still be navigating after enougnh time has passed for any pending timeouts to activate. + self.delay_sim_time(10) + self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=1) + self.change_mode("AUTO") + # record time and position tstart = self.get_sim_time() @@ -1885,8 +2118,8 @@ def GPSGlitchAuto(self, timeout=180): glitch_current = 0 self.progress("Apply first glitch") self.set_parameters({ - "SIM_GPS_GLITCH_X": glitch_lat[glitch_current], - "SIM_GPS_GLITCH_Y": glitch_lon[glitch_current], + "SIM_GPS1_GLTCH_X": glitch_lat[glitch_current], + "SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current], }) # record position for 30 seconds @@ -1899,15 +2132,15 @@ def GPSGlitchAuto(self, timeout=180): if glitch_current < glitch_num: self.progress("Applying glitch %u" % glitch_current) self.set_parameters({ - "SIM_GPS_GLITCH_X": glitch_lat[glitch_current], - "SIM_GPS_GLITCH_Y": glitch_lon[glitch_current], + "SIM_GPS1_GLTCH_X": glitch_lat[glitch_current], + "SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current], }) # turn off glitching self.progress("Completed Glitches") self.set_parameters({ - "SIM_GPS_GLITCH_X": 0, - "SIM_GPS_GLITCH_Y": 0, + "SIM_GPS1_GLTCH_X": 0, + "SIM_GPS1_GLTCH_Y": 0, }) # continue with the mission @@ -2055,6 +2288,67 @@ def ModeCircle(self, holdtime=36): self.do_RTL() + def CompassMot(self): + '''test code that adjust mag field for motor interference''' + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + 0, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + 0, # p5 + 1, # p6 + 0 # p7 + ) + self.context_collect("STATUSTEXT") + self.wait_statustext("Starting calibration", check_context=True) + self.wait_statustext("Current", check_context=True) + rc3_min = self.get_parameter('RC3_MIN') + rc3_max = self.get_parameter('RC3_MAX') + rc3_dz = self.get_parameter('RC3_DZ') + + def set_rc3_for_throttle_pct(thr_pct): + value = int((rc3_min+rc3_dz) + (thr_pct/100.0) * (rc3_max-(rc3_min+rc3_dz))) + self.progress("Setting rc3 to %u" % value) + self.set_rc(3, value) + + throttle_in_pct = 0 + set_rc3_for_throttle_pct(throttle_in_pct) + self.assert_received_message_field_values("COMPASSMOT_STATUS", { + "interference": 0, + "throttle": throttle_in_pct + }, verbose=True, very_verbose=True) + tstart = self.get_sim_time() + delta = 5 + while True: + if self.get_sim_time_cached() - tstart > 60: + raise NotAchievedException("did not run through entire range") + throttle_in_pct += delta + self.progress("Using throttle %f%%" % throttle_in_pct) + set_rc3_for_throttle_pct(throttle_in_pct) + self.wait_message_field_values("COMPASSMOT_STATUS", { + "throttle": throttle_in_pct * 10.0, + }, verbose=True, very_verbose=True, epsilon=1) + if throttle_in_pct == 0: + # finished counting down + break + if throttle_in_pct == 100: + # start counting down + delta = -delta + + m = self.wait_message_field_values("COMPASSMOT_STATUS", { + "throttle": 0, + }, verbose=True) + for axis in "X", "Y", "Z": + fieldname = "Compensation" + axis + if getattr(m, fieldname) <= 0: + raise NotAchievedException("Expected non-zero %s" % fieldname) + + # it's kind of crap - but any command-ack will stop the + # calibration + self.mav.mav.command_ack_send(0, 1) + self.wait_statustext("Calibration successful") + def MagFail(self): '''test failover of compass in EKF''' # we want both EK2 and EK3 @@ -2108,46 +2402,36 @@ def MagFail(self): def ModeFlip(self): '''Fly Flip Mode''' - ex = None - try: - self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 100) + self.context_set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 100) - self.takeoff(20) - self.hover() - old_speedup = self.get_parameter("SIM_SPEEDUP") - self.set_parameter('SIM_SPEEDUP', 1) - self.progress("Flipping in roll") - self.set_rc(1, 1700) - self.send_cmd_do_set_mode('FLIP') # don't wait for success - self.wait_attitude(despitch=0, desroll=45, tolerance=30) - self.wait_attitude(despitch=0, desroll=90, tolerance=30) - self.wait_attitude(despitch=0, desroll=-45, tolerance=30) - self.progress("Waiting for level") - self.set_rc(1, 1500) # can't change quickly enough! - self.wait_attitude(despitch=0, desroll=0, tolerance=5) - - self.progress("Regaining altitude") - self.change_mode('ALT_HOLD') - self.wait_altitude(19, 60, relative=True) - - self.progress("Flipping in pitch") - self.set_rc(2, 1700) - self.send_cmd_do_set_mode('FLIP') # don't wait for success - self.wait_attitude(despitch=45, desroll=0, tolerance=30) - # can't check roll here as it flips from 0 to -180.. - self.wait_attitude(despitch=90, tolerance=30) - self.wait_attitude(despitch=-45, tolerance=30) - self.progress("Waiting for level") - self.set_rc(2, 1500) # can't change quickly enough! - self.wait_attitude(despitch=0, desroll=0, tolerance=5) - self.set_parameter('SIM_SPEEDUP', old_speedup) - self.do_RTL() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 0) - if ex is not None: - raise ex + self.takeoff(20) + + self.progress("Flipping in roll") + self.set_rc(1, 1700) + self.send_cmd_do_set_mode('FLIP') # don't wait for success + self.wait_attitude(despitch=0, desroll=45, tolerance=30) + self.wait_attitude(despitch=0, desroll=90, tolerance=30) + self.wait_attitude(despitch=0, desroll=-45, tolerance=30) + self.progress("Waiting for level") + self.set_rc(1, 1500) # can't change quickly enough! + self.wait_attitude(despitch=0, desroll=0, tolerance=5) + + self.progress("Regaining altitude") + self.change_mode('ALT_HOLD') + self.wait_altitude(19, 60, relative=True) + + self.progress("Flipping in pitch") + self.set_rc(2, 1700) + self.send_cmd_do_set_mode('FLIP') # don't wait for success + self.wait_attitude(despitch=45, desroll=0, tolerance=30) + # can't check roll here as it flips from 0 to -180.. + self.wait_attitude(despitch=90, tolerance=30) + self.wait_attitude(despitch=-45, tolerance=30) + self.progress("Waiting for level") + self.set_rc(2, 1500) # can't change quickly enough! + self.wait_attitude(despitch=0, desroll=0, tolerance=5) + + self.do_RTL() def configure_EKFs_to_use_optical_flow_instead_of_GPS(self): '''configure EKF to use optical flow instead of GPS''' @@ -2190,10 +2474,10 @@ def OpticalFlow(self): '''test OpticalFlow in flight''' self.start_subtest("Make sure no crash if no rangefinder") - self.context_push() - - self.set_parameter("SIM_FLOW_ENABLE", 1) - self.set_parameter("FLOW_TYPE", 10) + self.set_parameters({ + "SIM_FLOW_ENABLE": 1, + "FLOW_TYPE": 10, + }) self.set_analog_rangefinder_parameters() @@ -2237,75 +2521,58 @@ def check_optical_flow(mav, m): self.fly_generic_mission("CMAC-copter-navtest.txt") - self.context_pop() - - self.reboot_sitl() - def OpticalFlowLimits(self): '''test EKF navigation limiting''' - ex = None - self.context_push() - try: - - self.set_parameter("SIM_FLOW_ENABLE", 1) - self.set_parameter("FLOW_TYPE", 10) + self.set_parameters({ + "SIM_FLOW_ENABLE": 1, + "FLOW_TYPE": 10, + "SIM_GPS1_ENABLE": 0, + "SIM_TERRAIN": 0, + }) - self.configure_EKFs_to_use_optical_flow_instead_of_GPS() + self.configure_EKFs_to_use_optical_flow_instead_of_GPS() - self.set_analog_rangefinder_parameters() + self.set_analog_rangefinder_parameters() - self.set_parameter("SIM_GPS_DISABLE", 1) - self.set_parameter("SIM_TERRAIN", 0) + self.reboot_sitl() - self.reboot_sitl() - - # we can't takeoff in loiter as we need flow healthy - self.takeoff(alt_min=5, mode='ALT_HOLD', require_absolute=False, takeoff_throttle=1800) - self.change_mode('LOITER') - - # speed should be limited to <10m/s - self.set_rc(2, 1000) - - tstart = self.get_sim_time() - timeout = 60 - started_climb = False - while self.get_sim_time_cached() - tstart < timeout: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - spd = math.sqrt(m.vx**2 + m.vy**2) * 0.01 - alt = m.relative_alt*0.001 - - # calculate max speed from altitude above the ground - margin = 2.0 - max_speed = alt * 1.5 + margin - self.progress("%0.1f: Low Speed: %f (want <= %u) alt=%.1f" % - (self.get_sim_time_cached() - tstart, - spd, - max_speed, alt)) - if spd > max_speed: - raise NotAchievedException(("Speed should be limited by" - "EKF optical flow limits")) - - # after 30 seconds start climbing - if not started_climb and self.get_sim_time_cached() - tstart > 30: - started_climb = True - self.set_rc(3, 1900) - self.progress("Moving higher") - - # check altitude is not climbing above 35m - if alt > 35: - raise NotAchievedException("Alt should be limited by EKF optical flow limits") + # we can't takeoff in loiter as we need flow healthy + self.takeoff(alt_min=5, mode='ALT_HOLD', require_absolute=False, takeoff_throttle=1800) + self.change_mode('LOITER') - except Exception as e: - self.print_exception_caught(e) - ex = e + # speed should be limited to <10m/s + self.set_rc(2, 1000) - self.set_rc(2, 1500) - self.context_pop() + tstart = self.get_sim_time() + timeout = 60 + started_climb = False + while self.get_sim_time_cached() - tstart < timeout: + m = self.assert_receive_message('GLOBAL_POSITION_INT') + spd = math.sqrt(m.vx**2 + m.vy**2) * 0.01 + alt = m.relative_alt*0.001 + + # calculate max speed from altitude above the ground + margin = 2.0 + max_speed = alt * 1.5 + margin + self.progress("%0.1f: Low Speed: %f (want <= %u) alt=%.1f" % + (self.get_sim_time_cached() - tstart, + spd, + max_speed, alt)) + if spd > max_speed: + raise NotAchievedException(("Speed should be limited by" + "EKF optical flow limits")) + + # after 30 seconds start climbing + if not started_climb and self.get_sim_time_cached() - tstart > 30: + started_climb = True + self.set_rc(3, 1900) + self.progress("Moving higher") + + # check altitude is not climbing above 35m + if alt > 35: + raise NotAchievedException("Alt should be limited by EKF optical flow limits") self.reboot_sitl(force=True) - if ex is not None: - raise ex - def OpticalFlowCalibration(self): '''test optical flow calibration''' ex = None @@ -2382,8 +2649,8 @@ def OpticalFlowCalibration(self): self.print_exception_caught(e) ex = e - self.context_pop() self.disarm_vehicle(force=True) + self.context_pop() self.reboot_sitl() if ex is not None: @@ -2480,16 +2747,39 @@ def AutoTuneSwitch(self): "RC8_OPTION": 17, "ATC_RAT_RLL_FLTT": 20, }) - rlld = self.get_parameter("ATC_RAT_RLL_D") - rlli = self.get_parameter("ATC_RAT_RLL_I") - rllp = self.get_parameter("ATC_RAT_RLL_P") - rllt = self.get_parameter("ATC_RAT_RLL_FLTT") - self.progress("AUTOTUNE pre-gains are P:%f I:%f D:%f" % - (self.get_parameter("ATC_RAT_RLL_P"), - self.get_parameter("ATC_RAT_RLL_I"), - self.get_parameter("ATC_RAT_RLL_D"))) + self.takeoff(10, mode='LOITER') + def print_gains(name, gains): + self.progress(f"AUTOTUNE {name} gains are P:%f I:%f D:%f" % ( + gains["ATC_RAT_RLL_P"], + gains["ATC_RAT_RLL_I"], + gains["ATC_RAT_RLL_D"] + )) + + def get_roll_gains(name): + ret = self.get_parameters([ + "ATC_RAT_RLL_D", + "ATC_RAT_RLL_I", + "ATC_RAT_RLL_P", + ], verbose=False) + print_gains(name, ret) + return ret + + def gains_same(gains1, gains2): + for c in 'P', 'I', 'D': + p_name = f"ATC_RAT_RLL_{c}" + if abs(gains1[p_name] - gains2[p_name]) > 0.00001: + return False + return True + + self.progress("Take a copy of original gains") + original_gains = get_roll_gains("pre-tuning") + scaled_original_gains = copy.copy(original_gains) + scaled_original_gains["ATC_RAT_RLL_I"] *= 0.1 + + pre_rllt = self.get_parameter("ATC_RAT_RLL_FLTT") + # hold position in loiter and run autotune self.set_rc(8, 1850) self.wait_mode('AUTOTUNE') @@ -2505,46 +2795,60 @@ def AutoTuneSwitch(self): if m is None: continue self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text)) + if "Determination Failed" in m.text: + break if "AutoTune: Success" in m.text: self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - # Check original gains are re-instated + post_gains = get_roll_gains("post") + if gains_same(original_gains, post_gains): + raise NotAchievedException("AUTOTUNE gains not changed") + + # because of the way AutoTune works, once autotune is + # complete we return the original parameters via + # parameter-fetching, but fly on the tuned parameters + # (both sets with the I term scaled down). This test + # makes sure that's still the case. It would be nice + # if the PIDs parameters were `set` on success, but + # they aren't... Note that if we use the switch to + # restore the original gains and then start testing + # again (with the switch) then we see the new gains! + + # gains are scaled during the testing phase: + if not gains_same(scaled_original_gains, post_gains): + raise NotAchievedException("AUTOTUNE gains were reported as just original gains in test-mode. If you're fixing this, good!") # noqa + + self.progress("Check original gains are re-instated by switch") self.set_rc(8, 1100) self.delay_sim_time(1) - self.progress("AUTOTUNE original gains are P:%f I:%f D:%f" % - (self.get_parameter("ATC_RAT_RLL_P"), self.get_parameter("ATC_RAT_RLL_I"), - self.get_parameter("ATC_RAT_RLL_D"))) - if (rlld != self.get_parameter("ATC_RAT_RLL_D") or - rlli != self.get_parameter("ATC_RAT_RLL_I") or - rllp != self.get_parameter("ATC_RAT_RLL_P")): - raise NotAchievedException("AUTOTUNE gains still present") - # Use autotuned gains + current_gains = get_roll_gains("set-original") + if not gains_same(original_gains, current_gains): + raise NotAchievedException("AUTOTUNE original gains not restored") + + self.progress("Use autotuned gains") self.set_rc(8, 1850) self.delay_sim_time(1) - self.progress("AUTOTUNE testing gains are P:%f I:%f D:%f" % - (self.get_parameter("ATC_RAT_RLL_P"), self.get_parameter("ATC_RAT_RLL_I"), - self.get_parameter("ATC_RAT_RLL_D"))) - if (rlld == self.get_parameter("ATC_RAT_RLL_D") or - rlli == self.get_parameter("ATC_RAT_RLL_I") or - rllp == self.get_parameter("ATC_RAT_RLL_P")): - raise NotAchievedException("AUTOTUNE gains not present in pilot testing") - # land without changing mode + tuned_gains = get_roll_gains("tuned") + if gains_same(tuned_gains, original_gains): + raise NotAchievedException("AUTOTUNE tuned gains same as pre gains") + if gains_same(tuned_gains, scaled_original_gains): + raise NotAchievedException("AUTOTUNE tuned gains same as scaled pre gains") + + self.progress("land without changing mode") self.set_rc(3, 1000) self.wait_altitude(-1, 5, relative=True) self.wait_disarmed() - # Check gains are still there after disarm - if (rlld == self.get_parameter("ATC_RAT_RLL_D") or - rlli == self.get_parameter("ATC_RAT_RLL_I") or - rllp == self.get_parameter("ATC_RAT_RLL_P")): + self.progress("Check gains are still there after disarm") + disarmed_gains = get_roll_gains("post-disarm") + if not gains_same(tuned_gains, disarmed_gains): raise NotAchievedException("AUTOTUNE gains not present on disarm") self.reboot_sitl() - # Check gains are still there after reboot - if (rlld == self.get_parameter("ATC_RAT_RLL_D") or - rlli == self.get_parameter("ATC_RAT_RLL_I") or - rllp == self.get_parameter("ATC_RAT_RLL_P")): + self.progress("Check gains are still there after reboot") + reboot_gains = get_roll_gains("post-reboot") + if not gains_same(tuned_gains, reboot_gains): raise NotAchievedException("AUTOTUNE gains not present on reboot") - # Check FLTT is unchanged - if rllt != self.get_parameter("ATC_RAT_RLL_FLTT"): + self.progress("Check FLTT is unchanged") + if pre_rllt != self.get_parameter("ATC_RAT_RLL_FLTT"): raise NotAchievedException("AUTOTUNE FLTT was modified") return @@ -2654,6 +2958,46 @@ def CopterMission(self): self.progress("Auto mission completed: passed!") + def set_origin(self, loc, timeout=60): + '''set the GPS global origin to loc''' + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise AutoTestTimeoutException("Did not get non-zero lat") + target_system = 1 + self.mav.mav.set_gps_global_origin_send( + target_system, + int(loc.lat * 1e7), + int(loc.lng * 1e7), + int(loc.alt * 1e3) + ) + gpi = self.assert_receive_message('GLOBAL_POSITION_INT') + self.progress("gpi=%s" % str(gpi)) + if gpi.lat != 0: + break + + def FarOrigin(self): + '''fly a mission far from the vehicle origin''' + # Fly mission #1 + self.set_parameters({ + "SIM_GPS1_ENABLE": 0, + }) + self.reboot_sitl() + nz = mavutil.location(-43.730171, 169.983118, 1466.3, 270) + self.set_origin(nz) + self.set_parameters({ + "SIM_GPS1_ENABLE": 1, + }) + self.progress("# Load copter_mission") + # load the waypoint count + num_wp = self.load_mission("copter_mission.txt", strict=False) + if not num_wp: + raise NotAchievedException("load copter_mission failed") + + self.fly_loaded_mission(num_wp) + + self.progress("Auto mission completed: passed!") + def fly_loaded_mission(self, num_wp): '''fly mission loaded on vehicle. FIXME: get num_wp from vehicle''' self.progress("test: Fly a mission from 1 to %u" % num_wp) @@ -2684,8 +3028,8 @@ def CANGPSCopterMission(self): "GPS1_TYPE": 9, "GPS2_TYPE": 9, # disable simulated GPS, so only via DroneCAN - "SIM_GPS_DISABLE": 1, - "SIM_GPS2_DISABLE": 1, + "SIM_GPS1_ENABLE": 0, + "SIM_GPS2_ENABLE": 0, # this ensures we use DroneCAN baro and compass "SIM_BARO_COUNT" : 0, "SIM_MAG1_DEVID" : 0, @@ -2862,7 +3206,7 @@ def GuidedEKFLaneChange(self): "EK3_SRC1_POSZ": 3, "EK3_AFFINITY" : 1, "GPS2_TYPE" : 1, - "SIM_GPS2_DISABLE" : 0, + "SIM_GPS2_ENABLE" : 1, "SIM_GPS2_GLTCH_Z" : -30 }) self.reboot_sitl() @@ -2900,122 +3244,109 @@ def GuidedEKFLaneChange(self): self.disarm_vehicle(force=True) self.reboot_sitl() - def MotorFail(self, fail_servo=0, fail_mul=0.0, holdtime=30): + def MotorFail(self, ): """Test flight with reduced motor efficiency""" - # we only expect an octocopter to survive ATM: - servo_counts = { - # 2: 6, # hexa - 3: 8, # octa - # 5: 6, # Y6 - } - frame_class = int(self.get_parameter("FRAME_CLASS")) - if frame_class not in servo_counts: - self.progress("Test not relevant for frame_class %u" % frame_class) - return - - servo_count = servo_counts[frame_class] + self.MotorFail_test_frame('octa', 8, frame_class=3) + # self.MotorFail_test_frame('hexa', 6, frame_class=2) + # self.MotorFail_test_frame('y6', 6, frame_class=5) - if fail_servo < 0 or fail_servo > servo_count: - raise ValueError('fail_servo outside range for frame class') - - self.takeoff(10, mode="LOITER") + def MotorFail_test_frame(self, model, servo_count, frame_class, fail_servo=0, fail_mul=0.0, holdtime=30): + self.set_parameters({ + 'FRAME_CLASS': frame_class, + }) + self.customise_SITL_commandline([], model=model) - self.change_alt(alt_min=50) + self.takeoff(25, mode="LOITER") # Get initial values - start_hud = self.mav.recv_match(type='VFR_HUD', blocking=True) - start_attitude = self.mav.recv_match(type='ATTITUDE', blocking=True) + start_hud = self.assert_receive_message('VFR_HUD') + start_attitude = self.assert_receive_message('ATTITUDE') hover_time = 5 - try: - tstart = self.get_sim_time() - int_error_alt = 0 - int_error_yaw_rate = 0 - int_error_yaw = 0 - self.progress("Hovering for %u seconds" % hover_time) - failed = False - while True: - now = self.get_sim_time_cached() - if now - tstart > holdtime + hover_time: - break + tstart = self.get_sim_time() + int_error_alt = 0 + int_error_yaw_rate = 0 + int_error_yaw = 0 + self.progress("Hovering for %u seconds" % hover_time) + failed = False + while True: + now = self.get_sim_time_cached() + if now - tstart > holdtime + hover_time: + break - servo = self.mav.recv_match(type='SERVO_OUTPUT_RAW', - blocking=True) - hud = self.mav.recv_match(type='VFR_HUD', blocking=True) - attitude = self.mav.recv_match(type='ATTITUDE', blocking=True) + servo = self.assert_receive_message('SERVO_OUTPUT_RAW') + hud = self.assert_receive_message('VFR_HUD') + attitude = self.assert_receive_message('ATTITUDE') - if not failed and now - tstart > hover_time: - self.progress("Killing motor %u (%u%%)" % - (fail_servo+1, fail_mul)) - self.set_parameters({ - "SIM_ENGINE_FAIL": fail_servo, - "SIM_ENGINE_MUL": fail_mul, - }) - failed = True + if not failed and now - tstart > hover_time: + self.progress("Killing motor %u (%u%%)" % + (fail_servo+1, fail_mul)) + self.set_parameters({ + "SIM_ENGINE_FAIL": fail_servo, + "SIM_ENGINE_MUL": fail_mul, + }) + failed = True - if failed: - self.progress("Hold Time: %f/%f" % (now-tstart, holdtime)) - - servo_pwm = [servo.servo1_raw, - servo.servo2_raw, - servo.servo3_raw, - servo.servo4_raw, - servo.servo5_raw, - servo.servo6_raw, - servo.servo7_raw, - servo.servo8_raw] - - self.progress("PWM output per motor") - for i, pwm in enumerate(servo_pwm[0:servo_count]): - if pwm > 1900: - state = "oversaturated" - elif pwm < 1200: - state = "undersaturated" - else: - state = "OK" + if failed: + self.progress("Hold Time: %f/%f" % (now-tstart, holdtime)) + + servo_pwm = [ + servo.servo1_raw, + servo.servo2_raw, + servo.servo3_raw, + servo.servo4_raw, + servo.servo5_raw, + servo.servo6_raw, + servo.servo7_raw, + servo.servo8_raw, + ] - if failed and i == fail_servo: - state += " (failed)" + self.progress("PWM output per motor") + for i, pwm in enumerate(servo_pwm[0:servo_count]): + if pwm > 1900: + state = "oversaturated" + elif pwm < 1200: + state = "undersaturated" + else: + state = "OK" - self.progress("servo %u [pwm=%u] [%s]" % (i+1, pwm, state)) + if failed and i == fail_servo: + state += " (failed)" - alt_delta = hud.alt - start_hud.alt - yawrate_delta = attitude.yawspeed - start_attitude.yawspeed - yaw_delta = attitude.yaw - start_attitude.yaw + self.progress("servo %u [pwm=%u] [%s]" % (i+1, pwm, state)) - self.progress("Alt=%fm (delta=%fm)" % (hud.alt, alt_delta)) - self.progress("Yaw rate=%f (delta=%f) (rad/s)" % - (attitude.yawspeed, yawrate_delta)) - self.progress("Yaw=%f (delta=%f) (deg)" % - (attitude.yaw, yaw_delta)) + alt_delta = hud.alt - start_hud.alt + yawrate_delta = attitude.yawspeed - start_attitude.yawspeed + yaw_delta = attitude.yaw - start_attitude.yaw - dt = self.get_sim_time() - now - int_error_alt += abs(alt_delta/dt) - int_error_yaw_rate += abs(yawrate_delta/dt) - int_error_yaw += abs(yaw_delta/dt) - self.progress("## Error Integration ##") - self.progress(" Altitude: %fm" % int_error_alt) - self.progress(" Yaw rate: %f rad/s" % int_error_yaw_rate) - self.progress(" Yaw: %f deg" % int_error_yaw) - self.progress("----") + self.progress("Alt=%fm (delta=%fm)" % (hud.alt, alt_delta)) + self.progress("Yaw rate=%f (delta=%f) (rad/s)" % + (attitude.yawspeed, yawrate_delta)) + self.progress("Yaw=%f (delta=%f) (deg)" % + (attitude.yaw, yaw_delta)) - if int_error_yaw_rate > 0.1: - raise NotAchievedException("Vehicle is spinning") + dt = self.get_sim_time() - now + int_error_alt += abs(alt_delta/dt) + int_error_yaw_rate += abs(yawrate_delta/dt) + int_error_yaw += abs(yaw_delta/dt) + self.progress("## Error Integration ##") + self.progress(" Altitude: %fm" % int_error_alt) + self.progress(" Yaw rate: %f rad/s" % int_error_yaw_rate) + self.progress(" Yaw: %f deg" % int_error_yaw) + self.progress("----") - if alt_delta < -20: - raise NotAchievedException("Vehicle is descending") + if int_error_yaw > 5: + raise NotAchievedException("Vehicle is spinning") - self.set_parameters({ - "SIM_ENGINE_FAIL": 0, - "SIM_ENGINE_MUL": 1.0, - }) - except Exception as e: - self.set_parameters({ - "SIM_ENGINE_FAIL": 0, - "SIM_ENGINE_MUL": 1.0, - }) - raise e + if alt_delta < -20: + raise NotAchievedException("Vehicle is descending") + + self.progress("Fixing motors") + self.set_parameters({ + "SIM_ENGINE_FAIL": 0, + "SIM_ENGINE_MUL": 1.0, + }) self.do_RTL() @@ -3033,82 +3364,67 @@ def hover_for_interval(self, hover_time): def MotorVibration(self): """Test flight with motor vibration""" - self.context_push() - - ex = None - try: - self.set_rc_default() - # magic tridge EKF type that dramatically speeds up the test - self.set_parameters({ - "AHRS_EKF_TYPE": 10, - "INS_LOG_BAT_MASK": 3, - "INS_LOG_BAT_OPT": 0, - "LOG_BITMASK": 958, - "LOG_DISARMED": 0, - "SIM_VIB_MOT_MAX": 350, - # these are real values taken from a 180mm Quad: - "SIM_GYR1_RND": 20, - "SIM_ACC1_RND": 5, - "SIM_ACC2_RND": 5, - "SIM_INS_THR_MIN": 0.1, - }) - self.reboot_sitl() - - # do a simple up-and-down flight to gather data: - self.takeoff(15, mode="ALT_HOLD") - 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 - freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] - if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 180 or freq > 300: - raise NotAchievedException( - "Did not detect a motor peak, found %f at %f dB" % - (freq, numpy.amax(psd["X"][ignore_bins:]))) - else: - self.progress("Detected motor peak at %fHz" % freq) - - # now add a notch and check that post-filter the peak is squashed below 40dB - self.set_parameters({ - "INS_LOG_BAT_OPT": 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, tend, hover_throttle = self.hover_for_interval(15) - self.set_parameter("SIM_VIB_MOT_MAX", 0) - self.do_RTL() + # magic tridge EKF type that dramatically speeds up the test + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 0, + "LOG_BITMASK": 958, + "LOG_DISARMED": 0, + "SIM_VIB_MOT_MAX": 350, + # these are real values taken from a 180mm Quad: + "SIM_GYR1_RND": 20, + "SIM_ACC1_RND": 5, + "SIM_ACC2_RND": 5, + "SIM_INS_THR_MIN": 0.1, + }) + self.reboot_sitl() - 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:]) - if peakdB < -23: - self.progress("Did not detect a motor peak, found %f at %f dB" % (freq, peakdB)) - else: - raise NotAchievedException("Detected peak %.1f Hz %.2f dB" % (freq, peakdB)) - except Exception as e: - self.print_exception_caught(e) - ex = e - self.disarm_vehicle(force=True) + # do a simple up-and-down flight to gather data: + self.takeoff(15, mode="ALT_HOLD") + 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() - self.context_pop() + 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 + # it should be at about 190Hz, each bin is 1000/1024Hz wide + ignore_bins = int(100 * 1.024) # start at 100Hz to be safe + freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] + if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 100 or freq > 300: + raise NotAchievedException( + "Did not detect a motor peak, found %f at %f dB" % + (freq, numpy.amax(psd["X"][ignore_bins:]))) + else: + self.progress("Detected motor peak at %fHz" % freq) + # now add a notch and check that post-filter the peak is squashed below 40dB + self.set_parameters({ + "INS_LOG_BAT_OPT": 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() - if ex is not None: - raise ex + # do a simple up-and-down flight to gather data: + self.takeoff(15, mode="ALT_HOLD") + 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:]) + if peakdB < -23: + self.progress("Did not detect a motor peak, found %f at %f dB" % (freq, peakdB)) + else: + raise NotAchievedException("Detected peak %.1f Hz %.2f dB" % (freq, peakdB)) def VisionPosition(self): """Disable GPS navigation, enable Vicon input.""" @@ -3122,91 +3438,62 @@ def VisionPosition(self): old_pos = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) print("old_pos=%s" % str(old_pos)) - self.context_push() - - ex = None - try: - # configure EKF to use external nav instead of GPS - ahrs_ekf_type = self.get_parameter("AHRS_EKF_TYPE") - if ahrs_ekf_type == 2: - self.set_parameter("EK2_GPS_TYPE", 3) - if ahrs_ekf_type == 3: - self.set_parameters({ - "EK3_SRC1_POSXY": 6, - "EK3_SRC1_VELXY": 6, - "EK3_SRC1_POSZ": 6, - "EK3_SRC1_VELZ": 6, - }) + # configure EKF to use external nav instead of GPS + ahrs_ekf_type = self.get_parameter("AHRS_EKF_TYPE") + if ahrs_ekf_type == 2: + self.set_parameter("EK2_GPS_TYPE", 3) + if ahrs_ekf_type == 3: self.set_parameters({ - "GPS1_TYPE": 0, - "VISO_TYPE": 1, - "SERIAL5_PROTOCOL": 1, + "EK3_SRC1_POSXY": 6, + "EK3_SRC1_VELXY": 6, + "EK3_SRC1_POSZ": 6, + "EK3_SRC1_VELZ": 6, }) - self.reboot_sitl() - # without a GPS or some sort of external prompting, AP - # doesn't send system_time messages. So prompt it: - self.mav.mav.system_time_send(int(time.time() * 1000000), 0) - self.progress("Waiting for non-zero-lat") - tstart = self.get_sim_time() - while True: - self.mav.mav.set_gps_global_origin_send(1, - old_pos.lat, - old_pos.lon, - old_pos.alt) - gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) - self.progress("gpi=%s" % str(gpi)) - if gpi.lat != 0: - break - - if self.get_sim_time_cached() - tstart > 60: - raise AutoTestTimeoutException("Did not get non-zero lat") - - self.takeoff() - self.set_rc(1, 1600) - tstart = self.get_sim_time() - while True: - vicon_pos = self.mav.recv_match(type='VISION_POSITION_ESTIMATE', - blocking=True) - # print("vpe=%s" % str(vicon_pos)) - self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) - # self.progress("gpi=%s" % str(gpi)) - if vicon_pos.x > 40: - break - - if self.get_sim_time_cached() - tstart > 100: - raise AutoTestTimeoutException("Vicon showed no movement") - - # recenter controls: - self.set_rc(1, 1500) - self.progress("# Enter RTL") - self.change_mode('RTL') - self.set_rc(3, 1500) - tstart = self.get_sim_time() - while True: - if self.get_sim_time_cached() - tstart > 200: - raise NotAchievedException("Did not disarm") - self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) - # print("gpi=%s" % str(gpi)) - self.mav.recv_match(type='SIMSTATE', - blocking=True) - # print("ss=%s" % str(ss)) - # wait for RTL disarm: - if not self.armed(): - break + self.set_parameters({ + "GPS1_TYPE": 0, + "VISO_TYPE": 1, + "SERIAL5_PROTOCOL": 1, + }) + self.reboot_sitl() + # without a GPS or some sort of external prompting, AP + # doesn't send system_time messages. So prompt it: + self.mav.mav.system_time_send(int(time.time() * 1000000), 0) + self.progress("Waiting for non-zero-lat") + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 60: + raise AutoTestTimeoutException("Did not get non-zero lat") + self.mav.mav.set_gps_global_origin_send(1, + old_pos.lat, + old_pos.lon, + old_pos.alt) + gpi = self.assert_receive_message('GLOBAL_POSITION_INT') + self.progress("gpi=%s" % str(gpi)) + if gpi.lat != 0: + break - except Exception as e: - self.print_exception_caught(e) - ex = e + self.takeoff() + self.set_rc(1, 1600) + tstart = self.get_sim_time() + while True: + vicon_pos = self.assert_receive_message('VISION_POSITION_ESTIMATE') + # print("vpe=%s" % str(vicon_pos)) + # gpi = self.assert_receive_message('GLOBAL_POSITION_INT') + # self.progress("gpi=%s" % str(gpi)) + if vicon_pos.x > 40: + break - self.context_pop() - self.zero_throttle() - self.reboot_sitl() + if self.get_sim_time_cached() - tstart > 100: + raise AutoTestTimeoutException("Vicon showed no movement") - if ex is not None: - raise ex + # recenter controls: + self.set_rc(1, 1500) + self.progress("# Enter RTL") + self.change_mode('RTL') + self.set_rc(3, 1500) + tstart = self.get_sim_time() + # self.install_messageprinter_handlers_context(['SIMSTATE', 'GLOBAL_POSITION_INT']) + self.wait_disarmed(timeout=200) def BodyFrameOdom(self): """Disable GPS navigation, enable input of VISION_POSITION_DELTA.""" @@ -3355,82 +3642,68 @@ def InvalidJumpTags(self): def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" + """Setup parameters including switching to EKF3""" + self.set_parameters({ + "VISO_TYPE": 2, # enable vicon + "SERIAL5_PROTOCOL": 2, + "EK3_ENABLE": 1, + "EK3_SRC2_POSXY": 6, # External Nav + "EK3_SRC2_POSZ": 6, # External Nav + "EK3_SRC2_VELXY": 6, # External Nav + "EK3_SRC2_VELZ": 6, # External Nav + "EK3_SRC2_YAW": 6, # External Nav + "RC7_OPTION": 80, # RC aux switch 7 set to Viso Align + "RC8_OPTION": 90, # RC aux switch 8 set to EKF source selector + "EK2_ENABLE": 0, + "AHRS_EKF_TYPE": 3, + }) self.customise_SITL_commandline(["--serial5=sim:vicon:"]) - """Setup parameters including switching to EKF3""" - self.context_push() - ex = None - try: - self.set_parameters({ - "VISO_TYPE": 2, # enable vicon - "SERIAL5_PROTOCOL": 2, - "EK3_ENABLE": 1, - "EK3_SRC2_POSXY": 6, # External Nav - "EK3_SRC2_POSZ": 6, # External Nav - "EK3_SRC2_VELXY": 6, # External Nav - "EK3_SRC2_VELZ": 6, # External Nav - "EK3_SRC2_YAW": 6, # External Nav - "RC7_OPTION": 80, # RC aux switch 7 set to Viso Align - "RC8_OPTION": 90, # RC aux switch 8 set to EKF source selector - "EK2_ENABLE": 0, - "AHRS_EKF_TYPE": 3, - }) - self.reboot_sitl() + # switch to use GPS + self.set_rc(8, 1000) - # switch to use GPS - self.set_rc(8, 1000) + # ensure we can get a global position: + self.poll_home_position(timeout=120) - # ensure we can get a global position: - self.poll_home_position(timeout=120) + # record starting position + old_pos = self.get_global_position_int() + print("old_pos=%s" % str(old_pos)) - # record starting position - old_pos = self.get_global_position_int() - print("old_pos=%s" % str(old_pos)) + # align vicon yaw with ahrs heading + self.set_rc(7, 2000) - # align vicon yaw with ahrs heading - self.set_rc(7, 2000) + # takeoff to 10m in Loiter + self.progress("Moving to ensure location is tracked") + self.takeoff(10, mode="LOITER", require_absolute=True, timeout=720) - # takeoff to 10m in Loiter - self.progress("Moving to ensure location is tracked") - self.takeoff(10, mode="LOITER", require_absolute=True, timeout=720) + # fly forward in Loiter + self.set_rc(2, 1300) - # fly forward in Loiter - self.set_rc(2, 1300) + # disable vicon + self.set_parameter("SIM_VICON_FAIL", 1) - # disable vicon - self.set_parameter("SIM_VICON_FAIL", 1) + # ensure vehicle remain in Loiter for 15 seconds + tstart = self.get_sim_time() + while self.get_sim_time() - tstart < 15: + if not self.mode_is('LOITER'): + raise NotAchievedException("Expected to stay in loiter for >15 seconds") - # ensure vehicle remain in Loiter for 15 seconds - tstart = self.get_sim_time() - while self.get_sim_time() - tstart < 15: - if not self.mode_is('LOITER'): - raise NotAchievedException("Expected to stay in loiter for >15 seconds") - - # re-enable vicon - self.set_parameter("SIM_VICON_FAIL", 0) - - # switch to vicon, disable GPS and wait 10sec to ensure vehicle remains in Loiter - self.set_rc(8, 1500) - self.set_parameter("GPS1_TYPE", 0) + # re-enable vicon + self.set_parameter("SIM_VICON_FAIL", 0) - # ensure vehicle remain in Loiter for 15 seconds - tstart = self.get_sim_time() - while self.get_sim_time() - tstart < 15: - if not self.mode_is('LOITER'): - raise NotAchievedException("Expected to stay in loiter for >15 seconds") + # switch to vicon, disable GPS and wait 10sec to ensure vehicle remains in Loiter + self.set_rc(8, 1500) + self.set_parameter("GPS1_TYPE", 0) - # RTL and check vehicle arrives within 10m of home - self.set_rc(2, 1500) - self.do_RTL() + # ensure vehicle remain in Loiter for 15 seconds + tstart = self.get_sim_time() + while self.get_sim_time() - tstart < 15: + if not self.mode_is('LOITER'): + raise NotAchievedException("Expected to stay in loiter for >15 seconds") - 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 + # RTL and check vehicle arrives within 10m of home + self.set_rc(2, 1500) + self.do_RTL() def RTLSpeed(self): """Test RTL Speed parameters""" @@ -3510,9 +3783,6 @@ def NavDelay(self): def RangeFinder(self): '''Test RangeFinder Basic Functionality''' - ex = None - self.context_push() - self.progress("Making sure we don't ordinarily get RANGEFINDER") m = self.mav.recv_match(type='RANGEFINDER', blocking=True, @@ -3528,68 +3798,59 @@ def RangeFinder(self): if self.current_onboard_log_contains_message("RFND"): raise NotAchievedException("Found unexpected RFND message") - try: - self.set_analog_rangefinder_parameters() - self.set_parameter("RC9_OPTION", 10) # rangefinder - self.set_rc(9, 2000) - - self.reboot_sitl() + self.set_analog_rangefinder_parameters() + self.set_parameter("RC9_OPTION", 10) # rangefinder + self.set_rc(9, 2000) - self.progress("Making sure we now get RANGEFINDER messages") - m = self.assert_receive_message('RANGEFINDER', timeout=10) + self.reboot_sitl() - self.progress("Checking RangeFinder is marked as enabled in mavlink") - m = self.mav.recv_match(type='SYS_STATUS', - blocking=True, - timeout=10) - flags = m.onboard_control_sensors_enabled - if not flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: - raise NotAchievedException("Laser not enabled in SYS_STATUS") - self.progress("Disabling laser using switch") - self.set_rc(9, 1000) - self.delay_sim_time(1) - self.progress("Checking RangeFinder is marked as disabled in mavlink") - m = self.mav.recv_match(type='SYS_STATUS', - blocking=True, - timeout=10) - flags = m.onboard_control_sensors_enabled - if flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: - raise NotAchievedException("Laser enabled in SYS_STATUS") + self.progress("Making sure we now get RANGEFINDER messages") + m = self.assert_receive_message('RANGEFINDER', timeout=10) - self.progress("Re-enabling rangefinder") - self.set_rc(9, 2000) - self.delay_sim_time(1) - m = self.mav.recv_match(type='SYS_STATUS', - blocking=True, - timeout=10) - flags = m.onboard_control_sensors_enabled - if not flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: - raise NotAchievedException("Laser not enabled in SYS_STATUS") + self.progress("Checking RangeFinder is marked as enabled in mavlink") + m = self.mav.recv_match(type='SYS_STATUS', + blocking=True, + timeout=10) + flags = m.onboard_control_sensors_enabled + if not flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: + raise NotAchievedException("Laser not enabled in SYS_STATUS") + self.progress("Disabling laser using switch") + self.set_rc(9, 1000) + self.delay_sim_time(1) + self.progress("Checking RangeFinder is marked as disabled in mavlink") + m = self.mav.recv_match(type='SYS_STATUS', + blocking=True, + timeout=10) + flags = m.onboard_control_sensors_enabled + if flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: + raise NotAchievedException("Laser enabled in SYS_STATUS") - self.takeoff(10, mode="LOITER") + self.progress("Re-enabling rangefinder") + self.set_rc(9, 2000) + self.delay_sim_time(1) + m = self.mav.recv_match(type='SYS_STATUS', + blocking=True, + timeout=10) + flags = m.onboard_control_sensors_enabled + if not flags & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_LASER_POSITION: + raise NotAchievedException("Laser not enabled in SYS_STATUS") - m_r = self.mav.recv_match(type='RANGEFINDER', - blocking=True) - m_p = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) + self.takeoff(10, mode="LOITER") - if abs(m_r.distance - m_p.relative_alt/1000) > 1: - raise NotAchievedException( - "rangefinder/global position int mismatch %0.2f vs %0.2f" % - (m_r.distance, m_p.relative_alt/1000)) + m_r = self.mav.recv_match(type='RANGEFINDER', + blocking=True) + m_p = self.mav.recv_match(type='GLOBAL_POSITION_INT', + blocking=True) - self.land_and_disarm() + if abs(m_r.distance - m_p.relative_alt/1000) > 1: + raise NotAchievedException( + "rangefinder/global position int mismatch %0.2f vs %0.2f" % + (m_r.distance, m_p.relative_alt/1000)) - if not self.current_onboard_log_contains_message("RFND"): - raise NotAchievedException("Did not see expected RFND message") + self.land_and_disarm() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.reboot_sitl() - if ex is not None: - raise ex + if not self.current_onboard_log_contains_message("RFND"): + raise NotAchievedException("Did not see expected RFND message") def SplineTerrain(self): '''Test Splines and Terrain''' @@ -3665,7 +3926,7 @@ def WPNAV_SPEED_DN(self): minimum_duration = 5 - self.takeoff(500, timeout=60) + self.takeoff(500, timeout=70) self.change_mode('AUTO') start_speed_ms = self.get_parameter('WPNAV_SPEED_DN') / 100.0 @@ -4348,75 +4609,52 @@ def ModeZigZag(self): def SetModesViaModeSwitch(self): '''Set modes via modeswitch''' - self.context_push() - ex = None - try: - fltmode_ch = 5 - self.set_parameter("FLTMODE_CH", fltmode_ch) - self.set_rc(fltmode_ch, 1000) # PWM for mode1 - testmodes = [("FLTMODE1", 4, "GUIDED", 1165), - ("FLTMODE2", 2, "ALT_HOLD", 1295), - ("FLTMODE3", 6, "RTL", 1425), - ("FLTMODE4", 7, "CIRCLE", 1555), - ("FLTMODE5", 1, "ACRO", 1685), - ("FLTMODE6", 17, "BRAKE", 1815), - ] - for mode in testmodes: - (parm, parm_value, name, pwm) = mode - self.set_parameter(parm, parm_value) - - for mode in reversed(testmodes): - (parm, parm_value, name, pwm) = mode - self.set_rc(fltmode_ch, pwm) - self.wait_mode(name) - - for mode in testmodes: - (parm, parm_value, name, pwm) = mode - self.set_rc(fltmode_ch, pwm) - self.wait_mode(name) - - for mode in reversed(testmodes): - (parm, parm_value, name, pwm) = mode - self.set_rc(fltmode_ch, pwm) - self.wait_mode(name) - - except Exception as e: - self.print_exception_caught(e) - ex = e - - self.context_pop() - - if ex is not None: - raise ex + fltmode_ch = 5 + self.set_parameter("FLTMODE_CH", fltmode_ch) + self.set_rc(fltmode_ch, 1000) # PWM for mode1 + testmodes = [("FLTMODE1", 4, "GUIDED", 1165), + ("FLTMODE2", 2, "ALT_HOLD", 1295), + ("FLTMODE3", 6, "RTL", 1425), + ("FLTMODE4", 7, "CIRCLE", 1555), + ("FLTMODE5", 1, "ACRO", 1685), + ("FLTMODE6", 17, "BRAKE", 1815), + ] + for mode in testmodes: + (parm, parm_value, name, pwm) = mode + self.set_parameter(parm, parm_value) + + for mode in reversed(testmodes): + (parm, parm_value, name, pwm) = mode + self.set_rc(fltmode_ch, pwm) + self.wait_mode(name) + + for mode in testmodes: + (parm, parm_value, name, pwm) = mode + self.set_rc(fltmode_ch, pwm) + self.wait_mode(name) + + for mode in reversed(testmodes): + (parm, parm_value, name, pwm) = mode + self.set_rc(fltmode_ch, pwm) + self.wait_mode(name) def SetModesViaAuxSwitch(self): '''"Set modes via auxswitch"''' - self.context_push() - ex = None - try: - fltmode_ch = int(self.get_parameter("FLTMODE_CH")) - self.set_rc(fltmode_ch, 1000) - self.wait_mode("CIRCLE") - self.set_rc(9, 1000) - self.set_rc(10, 1000) - self.set_parameters({ - "RC9_OPTION": 18, # land - "RC10_OPTION": 55, # guided - }) - self.set_rc(9, 1900) - self.wait_mode("LAND") - self.set_rc(10, 1900) - self.wait_mode("GUIDED") - self.set_rc(10, 1000) # this re-polls the mode switch - self.wait_mode("CIRCLE") - except Exception as e: - self.print_exception_caught(e) - ex = e - - self.context_pop() - - if ex is not None: - raise ex + fltmode_ch = int(self.get_parameter("FLTMODE_CH")) + self.set_rc(fltmode_ch, 1000) + self.wait_mode("CIRCLE") + self.set_rc(9, 1000) + self.set_rc(10, 1000) + self.set_parameters({ + "RC9_OPTION": 18, # land + "RC10_OPTION": 55, # guided + }) + self.set_rc(9, 1900) + self.wait_mode("LAND") + self.set_rc(10, 1900) + self.wait_mode("GUIDED") + self.set_rc(10, 1000) # this re-polls the mode switch + self.wait_mode("CIRCLE") def fly_guided_stop(self, timeout=20, @@ -4453,10 +4691,7 @@ def fly_guided_stop(self, m.climb < climb_tolerance): break - def fly_guided_move_global_relative_alt(self, lat, lon, alt): - startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) - + def send_set_position_target_global_int(self, lat, lon, alt): self.mav.mav.set_position_target_global_int_send( 0, # timestamp 1, # target system_id @@ -4476,6 +4711,12 @@ def fly_guided_move_global_relative_alt(self, lat, lon, alt): 0, # yawrate ) + def fly_guided_move_global_relative_alt(self, lat, lon, alt): + startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT', + blocking=True) + + self.send_set_position_target_global_int(lat, lon, alt) + tstart = self.get_sim_time() while True: if self.get_sim_time_cached() - tstart > 200: @@ -4736,59 +4977,52 @@ def precision_loiter_to_pos(self, x, y, z, timeout=40): 0.01 # size of target in radians, Y-axis ) + def set_servo_gripper_parameters(self): + self.set_parameters({ + "GRIP_ENABLE": 1, + "GRIP_TYPE": 1, + "SIM_GRPS_ENABLE": 1, + "SIM_GRPS_PIN": 8, + "SERVO8_FUNCTION": 28, + }) + def PayloadPlaceMission(self): """Test payload placing in auto.""" self.context_push() - ex = None - try: - self.set_analog_rangefinder_parameters() - self.set_parameters({ - "GRIP_ENABLE": 1, - "GRIP_TYPE": 1, - "SIM_GRPS_ENABLE": 1, - "SIM_GRPS_PIN": 8, - "SERVO8_FUNCTION": 28, - }) - self.reboot_sitl() - - self.load_mission("copter_payload_place.txt") - if self.mavproxy is not None: - self.mavproxy.send('wp list\n') + self.set_analog_rangefinder_parameters() + self.set_servo_gripper_parameters() + self.reboot_sitl() - self.set_parameter("AUTO_OPTIONS", 3) - self.change_mode('AUTO') - self.wait_ready_to_arm() + self.load_mission("copter_payload_place.txt") + if self.mavproxy is not None: + self.mavproxy.send('wp list\n') - self.arm_vehicle() + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() - 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.arm_vehicle() - self.wait_disarmed() + 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)) - except Exception as e: - self.print_exception_caught(e) - self.disarm_vehicle(force=True) - ex = e + self.wait_disarmed() self.context_pop() self.reboot_sitl() self.progress("All done") - if ex is not None: - raise ex - def Weathervane(self): '''Test copter weathervaning''' # We test nose into wind code paths and yaw direction here and test side into wind @@ -4950,47 +5184,28 @@ def GuidedSubModeChange(self): def TestGripperMission(self): '''Test Gripper mission items''' - self.context_push() - ex = None - try: - self.load_mission("copter-gripper-mission.txt") - self.change_mode('LOITER') - self.wait_ready_to_arm() - self.assert_vehicle_location_is_at_startup_location() - self.arm_vehicle() - self.change_mode('AUTO') - self.set_rc(3, 1500) - self.wait_statustext("Gripper Grabbed", timeout=60) - self.wait_statustext("Gripper Released", timeout=60) - except Exception as e: - self.print_exception_caught(e) - self.change_mode('LAND') - ex = e - self.context_pop() + num_wp = self.load_mission("copter-gripper-mission.txt") + self.change_mode('LOITER') + self.wait_ready_to_arm() + self.assert_vehicle_location_is_at_startup_location() + self.arm_vehicle() + self.change_mode('AUTO') + self.set_rc(3, 1500) + self.wait_statustext("Gripper Grabbed", timeout=60) + self.wait_statustext("Gripper Released", timeout=60) + self.wait_waypoint(num_wp-1, num_wp-1) self.wait_disarmed() - if ex is not None: - raise ex def SplineLastWaypoint(self): '''Test Spline as last waypoint''' - self.context_push() - ex = None - try: - self.load_mission("copter-spline-last-waypoint.txt") - self.change_mode('LOITER') - self.wait_ready_to_arm() - self.arm_vehicle() - self.change_mode('AUTO') - self.set_rc(3, 1500) - self.wait_altitude(10, 3000, relative=True) - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() + self.load_mission("copter-spline-last-waypoint.txt") + self.change_mode('LOITER') + self.wait_ready_to_arm() + self.arm_vehicle() + self.change_mode('AUTO') + self.set_rc(3, 1500) + self.wait_altitude(10, 3000, relative=True) self.do_RTL() - self.wait_disarmed() - if ex is not None: - raise ex def ManualThrottleModeChange(self): '''Check manual throttle mode changes denied on high throttle''' @@ -5024,18 +5239,28 @@ def ManualThrottleModeChange(self): self.run_cmd_do_set_mode("ACRO") self.wait_disarmed() - def test_mount_pitch(self, despitch, despitch_tolerance, mount_mode, timeout=10, hold=0): + def constrained_mount_pitch(self, pitch_angle_deg, mount_instance=1): + PITCH_MIN = self.get_parameter("MNT%u_PITCH_MIN" % mount_instance) + PITCH_MAX = self.get_parameter("MNT%u_PITCH_MAX" % mount_instance) + return min(max(pitch_angle_deg, PITCH_MIN), PITCH_MAX) + + def test_mount_pitch(self, despitch, despitch_tolerance, mount_mode, timeout=10, hold=0, constrained=True): tstart = self.get_sim_time() success_start = 0 + while True: now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException("Mount pitch not achieved") + # We expect to achieve the desired pitch angle unless constrained by mount limits + if constrained: + despitch = self.constrained_mount_pitch(despitch) + '''retrieve latest angles from GIMBAL_DEVICE_ATTITUDE_STATUS''' - mount_roll, mount_pitch, mount_yaw = self.get_mount_roll_pitch_yaw_deg() + mount_roll, mount_pitch, mount_yaw, mount_yaw_is_absolute = self.get_mount_roll_pitch_yaw_deg() - self.progress("despitch=%f roll=%f pitch=%f yaw=%f" % (despitch, mount_roll, mount_pitch, mount_yaw)) + # 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)) @@ -5091,10 +5316,11 @@ def get_mount_roll_pitch_yaw_deg(self): # wait for gimbal attitude message m = self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5) + yaw_is_absolute = m.flags & mavutil.mavlink.GIMBAL_DEVICE_FLAGS_YAW_LOCK # 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]) + return math.degrees(euler[0]), math.degrees(euler[1]), math.degrees(euler[2]), yaw_is_absolute def set_mount_mode(self, mount_mode): '''set mount mode''' @@ -5111,9 +5337,9 @@ def set_mount_mode(self, mount_mode): p3=0, # stabilize pitch (unsupported) ) - def test_mount_rc_targetting(self): + def test_mount_rc_targetting(self, pitch_rc_neutral=1500, do_rate_tests=True): '''called in multipleplaces to make sure that mount RC targetting works''' - try: + if True: self.context_push() self.set_parameters({ 'RC6_OPTION': 0, @@ -5173,66 +5399,50 @@ def test_mount_rc_targetting(self): self.set_rc(12, 1500) + if do_rate_tests: + self.test_mount_rc_targetting_rate_control() + + self.context_pop() + + def test_mount_rc_targetting_rate_control(self, pitch_rc_neutral=1500): + if True: self.progress("Testing RC rate control") self.set_parameter('MNT1_RC_RATE', 10) self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + # Note that we don't constrain the desired angle in the following so that we don't + # timeout due to fetching Mount pitch limit params. self.set_rc(12, 1300) - self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(-10, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(-15, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(-20, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(-10, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(-15, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(-20, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) self.set_rc(12, 1700) - self.test_mount_pitch(-15, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(-10, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_pitch(5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(-15, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(-10, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) + self.test_mount_pitch(5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, constrained=False) self.progress("Reverting to angle mode") 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) - self.context_pop() - - except Exception as e: - self.print_exception_caught(e) - self.context_pop() - raise e - - def Mount(self): - '''Test Camera/Antenna Mount''' - ex = None - self.context_push() - old_srcSystem = self.mav.mav.srcSystem - self.mav.mav.srcSystem = 250 - self.set_parameter("DISARM_DELAY", 0) - try: - '''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''' - self.set_parameter("FS_GCS_ENABLE", 0) - - # setup mount parameters - self.setup_servo_mount() - self.reboot_sitl() # to handle MNT_TYPE changing - + def mount_test_body(self, pitch_rc_neutral=1500, do_rate_tests=True, constrain_sysid_target=True): + '''Test Camera/Antenna Mount - assumes a camera is set up and ready to go''' + if True: # make sure we're getting gimbal device attitude status - self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5) + self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5, very_verbose=True) # change mount to neutral mode (point forward, not stabilising) self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) - # test pitch is not stabilising - mount_roll_deg, mount_pitch_deg, mount_yaw_deg = self.get_mount_roll_pitch_yaw_deg() + # test pitch is not neutral to start with + mount_roll_deg, mount_pitch_deg, mount_yaw_deg, mount_yaw_is_absolute = 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") + raise NotAchievedException("Mount not neutral") - self.change_mode('GUIDED') - self.wait_ready_to_arm() - self.arm_vehicle() - - self.user_takeoff() + self.takeoff(30, mode='GUIDED') # pitch vehicle back and confirm gimbal is still not stabilising despitch = 10 @@ -5244,13 +5454,13 @@ def Mount(self): self.wait_pitch(despitch, despitch_tolerance) # check gimbal is still not stabilising - mount_roll_deg, mount_pitch_deg, mount_yaw_deg = self.get_mount_roll_pitch_yaw_deg() + mount_roll_deg, mount_pitch_deg, mount_yaw_deg, mount_yaw_is_absolute = 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") # 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_rc(6, pitch_rc_neutral) self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) # pitch vehicle back and confirm gimbal is stabilising @@ -5277,32 +5487,6 @@ def Mount(self): ) self.test_mount_pitch(angle, 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.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) - - start = self.mav.location() - self.progress("start=%s" % str(start)) - (t_lat, t_lon) = mavextra.gps_offset(start.lat, start.lng, 10, 20) - t_alt = 0 - - self.progress("loc %f %f %f" % (start.lat, start.lng, start.alt)) - self.progress("targetting %f %f %f" % (t_lat, t_lon, t_alt)) - self.do_pitch(despitch) - self.mav.mav.mount_control_send( - 1, # target system - 1, # target component - int(t_lat * 1e7), # lat - int(t_lon * 1e7), # lon - t_alt * 100, # alt - 0 # save position - ) - self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT) - # this is a one-off; ArduCopter *will* time out this directive! self.progress("Levelling aircraft") self.mav.mav.set_attitude_target_send( @@ -5322,7 +5506,10 @@ def Mount(self): self.progress("Testing mount RC targetting") self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.test_mount_rc_targetting() + self.test_mount_rc_targetting( + pitch_rc_neutral=pitch_rc_neutral, + do_rate_tests=do_rate_tests, + ) self.progress("Testing mount ROI behaviour") self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) @@ -5460,27 +5647,65 @@ def Mount(self): 0, # vz 0 # heading ) - self.test_mount_pitch(68, 5, mavutil.mavlink.MAV_MOUNT_MODE_SYSID_TARGET, hold=2) + self.test_mount_pitch( + 68, + 5, + mavutil.mavlink.MAV_MOUNT_MODE_SYSID_TARGET, + hold=2, + constrained=constrain_sysid_target, + ) 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: - self.print_exception_caught(e) - ex = e + self.disarm_vehicle(force=True) - self.context_pop() + self.test_mount_body_yaw() - self.mav.mav.srcSystem = old_srcSystem - self.disarm_vehicle(force=True) - self.reboot_sitl() # to handle MNT1_TYPE changing + def test_mount_body_yaw(self): + '''check reporting of yaw''' + # change mount to neutral mode (point forward, not stabilising) + self.takeoff(10, mode='GUIDED') - if ex is not None: - raise ex + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) + + for heading in 30, 45, 150: + self.guided_achieve_heading(heading) + + r, p , y, yaw_is_absolute = self.get_mount_roll_pitch_yaw_deg() + + if yaw_is_absolute: + raise NotAchievedException("Expected a relative yaw") + + if y > 1: + raise NotAchievedException("Bad yaw (y=%f)") + + self.do_RTL() + + def Mount(self): + '''test servo mount''' + self.setup_servo_mount() + self.reboot_sitl() # to handle MNT_TYPE changing + self.mount_test_body() + + def MountSolo(self): + '''test type=2, a "Solo" mount''' + self.set_parameters({ + "MNT1_TYPE": 2, + "RC6_OPTION": 213, # MOUNT1_PITCH + }) + self.customise_SITL_commandline([ + "--gimbal" # connects on port 5762 + ]) + self.mount_test_body( + pitch_rc_neutral=1818, + do_rate_tests=False, # solo can't do rate control (yet?) + constrain_sysid_target=False, # not everything constrains all angles + ) def assert_mount_rpy(self, r, p, y, tolerance=1): '''assert mount atttiude in degrees''' - got_r, got_p, got_y = self.get_mount_roll_pitch_yaw_deg() + got_r, got_p, got_y, yaw_is_absolute = self.get_mount_roll_pitch_yaw_deg() for (want, got, name) in (r, got_r, "roll"), (p, got_p, "pitch"), (y, got_y, "yaw"): if abs(want - got) > tolerance: raise NotAchievedException("%s incorrect; want=%f got=%f" % @@ -5600,21 +5825,64 @@ def MAV_CMD_DO_MOUNT_CONTROL(self): self.context_pop() self.reboot_sitl() - def MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE(self): - '''test MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE mavlink command''' + def AutoYawDO_MOUNT_CONTROL(self): + '''test AutoYaw behaviour when MAV_CMD_DO_MOUNT_CONTROL sent to Mount without Yaw control''' + # setup mount parameters self.context_push() - self.setup_servo_mount() - self.reboot_sitl() # to handle MNT_TYPE changing - self.context_set_message_rate_hz('GIMBAL_MANAGER_STATUS', 10) - self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { - "gimbal_device_id": 1, - "primary_control_sysid": 0, - "primary_control_compid": 0, + yaw_servo = 7 + self.setup_servo_mount(roll_servo=5, pitch_servo=6, yaw_servo=yaw_servo) + # Disable Mount Yaw servo + self.set_parameters({ + "SERVO%u_FUNCTION" % yaw_servo: 0, }) + self.reboot_sitl() # to handle MNT_TYPE changing - for method in self.run_cmd, self.run_cmd_int: + self.takeoff(20, mode='GUIDED') + + for mount_yaw in [-45, 0, 45]: + heading = 330 + self.guided_achieve_heading(heading) + self.assert_heading(heading) + + self.neutralise_gimbal() + + r = 15 + p = 20 + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p1=p, + p2=r, + p3=mount_yaw, + p7=mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, + ) + self.delay_sim_time(5) + # We have disabled yaw servo, so expect mount yaw to be zero + self.assert_mount_rpy(r, p, 0) + # But we expect the copter to yaw instead + self.assert_heading(heading + mount_yaw) + + self.do_RTL() + + self.context_pop() + self.reboot_sitl() + + def MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE(self): + '''test MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE mavlink command''' + # setup mount parameters + self.context_push() + self.setup_servo_mount() + self.reboot_sitl() # to handle MNT_TYPE changing + + self.context_set_message_rate_hz('GIMBAL_MANAGER_STATUS', 10) + self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + "gimbal_device_id": 1, + "primary_control_sysid": 0, + "primary_control_compid": 0, + }) + + for method in self.run_cmd, self.run_cmd_int: self.start_subtest("set_sysid-compid") method( mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, @@ -5784,8 +6052,9 @@ def ThrowMode(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, takeoff=True): + def hover_and_check_matched_frequency_with_fft_and_psd(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, + reverse=None, takeoff=True, instance=0): + '''Takeoff and hover, checking the noise against the provided db level and returning psd''' # find a motor peak if takeoff: self.takeoff(10, mode="ALT_HOLD") @@ -5793,7 +6062,7 @@ def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, max tstart, tend, hover_throttle = self.hover_for_interval(15) self.do_RTL() - psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) + psd = self.mavfft_fttd(1, instance, 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"][minhz:maxhz]) + minhz] * (1000. / 1024.) @@ -5812,8 +6081,35 @@ def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, max self.progress("Detected motor peak at %fHz, throttle %f%%, %fdB" % (freq, hover_throttle, peakdb)) + return freq, hover_throttle, peakdb, psd + + def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, + reverse=None, takeoff=True, instance=0): + '''Takeoff and hover, checking the noise against the provided db level and returning peak db''' + freq, hover_throttle, peakdb, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(dblevel, minhz, + maxhz, peakhz, reverse, takeoff, instance) return freq, hover_throttle, peakdb + def get_average_esc_frequency(self): + mlog = self.dfreader_for_current_onboard_log() + rpm_total = 0 + rpm_count = 0 + tho = 0 + while True: + m = mlog.recv_match() + if m is None: + break + msg_type = m.get_type() + if msg_type == "CTUN": + tho = m.ThO + elif msg_type == "ESC" and tho > 0.1: + rpm_total += m.RPM + rpm_count += 1 + + esc_hz = rpm_total / (rpm_count * 60) + return esc_hz + def DynamicNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with dynamic notches") @@ -5850,13 +6146,15 @@ def DynamicNotches(self): }) self.reboot_sitl() - freq, hover_throttle, 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, hover_throttle, 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: @@ -5868,7 +6166,8 @@ def DynamicNotches(self): 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) + 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: @@ -5894,7 +6193,7 @@ def DynamicRpmNotches(self): "AHRS_EKF_TYPE": 10, "INS_LOG_BAT_MASK": 3, "INS_LOG_BAT_OPT": 0, - "INS_GYRO_FILTER": 100, # set gyro filter high so we can observe behaviour + "INS_GYRO_FILTER": 300, # set gyro filter high so we can observe behaviour "LOG_BITMASK": 958, "LOG_DISARMED": 0, "SIM_VIB_MOT_MAX": 350, @@ -5905,12 +6204,14 @@ def DynamicRpmNotches(self): self.takeoff(10, mode="ALT_HOLD") - # find a motor peak - freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) + # find a motor peak, the peak is at about 190Hz, so checking between 50 and 320Hz should be safe. + # there is a second harmonic at 380Hz which should be avoided to make the test reliable + # detect at -5dB so we don't pick some random noise as the peak. The actual peak is about +15dB + freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-5, 50, 320) # now add a dynamic notch and check that the peak is squashed self.set_parameters({ - "INS_LOG_BAT_OPT": 2, + "INS_LOG_BAT_OPT": 4, "INS_HNTCH_ENABLE": 1, "INS_HNTCH_FREQ": 80, "INS_HNTCH_REF": 1.0, @@ -5921,19 +6222,34 @@ def DynamicRpmNotches(self): }) self.reboot_sitl() - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + # -10dB is pretty conservative - actual is about -25dB + freq, hover_throttle, peakdb1, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb1 = psd["X"][int(esc_hz)] # now add notch-per motor and check that the peak is squashed self.set_parameter("INS_HNTCH_OPTS", 2) self.reboot_sitl() - freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb2 = psd["X"][int(esc_hz)] - # notch-per-motor should do better, but check for within 10%. ( its mostly within 5%, but does vary a bit) - if peakdb2 * 1.10 > peakdb1: + # notch-per-motor will be better at the average ESC frequency + if esc_peakdb2 > esc_peakdb1: raise NotAchievedException( "Notch-per-motor peak was higher than single-notch peak %fdB > %fdB" % - (peakdb2, peakdb1)) + (esc_peakdb2, esc_peakdb1)) + + # check that the noise is being squashed at all. this needs to be an aggresive check so that failure happens easily + # testing shows this to be -58dB on average + if esc_peakdb2 > -25: + raise NotAchievedException( + "Notch-per-motor had a peak of %fdB there should be none" % esc_peakdb2) # Now do it again for an octacopter self.context_push() @@ -5946,20 +6262,29 @@ def DynamicRpmNotches(self): defaults_filepath=','.join(self.model_defaults_filepath("octa")), model="octa" ) - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb1 = psd["X"][int(esc_hz)] # 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, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-15, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb2 = psd["X"][int(esc_hz)] - # notch-per-motor should do better, but check for within 5% - if peakdb2 * 1.05 > peakdb1: + # notch-per-motor will be better at the average ESC frequency + if esc_peakdb2 > esc_peakdb1: raise NotAchievedException( "Notch-per-motor peak was higher than single-notch peak %fdB > %fdB" % - (peakdb2, peakdb1)) + (esc_peakdb2, esc_peakdb1)) + except Exception as e: self.print_exception_caught(e) ex = e @@ -6034,90 +6359,87 @@ def extract_median_FTN1_PkAvg_from_current_onboard_log(self, tstart, tend): def PIDNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with PID notches") - self.context_push() - - ex = None - try: - self.set_parameters({ - "FILT1_TYPE": 1, - "AHRS_EKF_TYPE": 10, - "INS_LOG_BAT_MASK": 3, - "INS_LOG_BAT_OPT": 0, - "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour - "LOG_BITMASK": 65535, - "LOG_DISARMED": 0, - "SIM_VIB_FREQ_X": 120, # roll - "SIM_VIB_FREQ_Y": 120, # pitch - "SIM_VIB_FREQ_Z": 180, # yaw - "FILT1_NOTCH_FREQ": 120, - "ATC_RAT_RLL_NEF": 1, - "ATC_RAT_PIT_NEF": 1, - "ATC_RAT_YAW_NEF": 1, - "SIM_GYR1_RND": 5, - }) - self.reboot_sitl() - - self.takeoff(10, mode="ALT_HOLD") - - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(5, 20, 350, reverse=True) + self.set_parameters({ + "FILT1_TYPE": 1, + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 0, + "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour + "LOG_BITMASK": 65535, + "LOG_DISARMED": 0, + "SIM_VIB_FREQ_X": 120, # roll + "SIM_VIB_FREQ_Y": 120, # pitch + "SIM_VIB_FREQ_Z": 180, # yaw + "FILT1_NOTCH_FREQ": 120, + "ATC_RAT_RLL_NEF": 1, + "ATC_RAT_PIT_NEF": 1, + "ATC_RAT_YAW_NEF": 1, + "SIM_GYR1_RND": 5, + }) + self.reboot_sitl() - except Exception as e: - self.print_exception_caught(e) - ex = e + self.hover_and_check_matched_frequency_with_fft(dblevel=5, minhz=20, maxhz=350, reverse=True) - self.context_pop() + def StaticNotches(self): + """Use static harmonic notch to control motor noise.""" + self.progress("Flying with Static notches") + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 4, + "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour + "LOG_BITMASK": 65535, + "LOG_DISARMED": 0, + "SIM_VIB_FREQ_X": 120, # roll + "SIM_VIB_FREQ_Y": 120, # pitch + "SIM_VIB_FREQ_Z": 120, # yaw + "SIM_VIB_MOT_MULT": 0, + "SIM_GYR1_RND": 5, + "INS_HNTCH_ENABLE": 1, + "INS_HNTCH_FREQ": 120, + "INS_HNTCH_REF": 1.0, + "INS_HNTCH_HMNCS": 3, # first and second harmonic + "INS_HNTCH_ATT": 50, + "INS_HNTCH_BW": 40, + "INS_HNTCH_MODE": 0, # static notch + }) + self.reboot_sitl() - if ex is not None: - raise ex + self.hover_and_check_matched_frequency_with_fft(dblevel=-15, minhz=20, maxhz=350, reverse=True, instance=2) def ThrottleGainBoost(self): """Use PD and Angle P boost for anti-gravity.""" # basic gyro sample rate test self.progress("Flying with Throttle-Gain Boost") - self.context_push() - - ex = None - try: - # magic tridge EKF type that dramatically speeds up the test - self.set_parameters({ - "AHRS_EKF_TYPE": 10, - "EK2_ENABLE": 0, - "EK3_ENABLE": 0, - "INS_FAST_SAMPLE": 0, - "LOG_BITMASK": 959, - "LOG_DISARMED": 0, - "ATC_THR_G_BOOST": 5.0, - }) - - self.reboot_sitl() - - 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) - - # 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() + # magic tridge EKF type that dramatically speeds up the test + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "EK2_ENABLE": 0, + "EK3_ENABLE": 0, + "INS_FAST_SAMPLE": 0, + "LOG_BITMASK": 959, + "LOG_DISARMED": 0, + "ATC_THR_G_BOOST": 5.0, + }) - except Exception as e: - self.print_exception_caught(e) - ex = e + self.reboot_sitl() - self.context_pop() + 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.assert_receive_message('ATTITUDE') - # must reboot after we move away from EKF type 10 to EKF2 or EKF3 - self.reboot_sitl() + # 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) - if ex is not None: - raise ex + self.do_RTL() def test_gyro_fft_harmonic(self, averaging): """Use dynamic harmonic notch to control motor noise with harmonic matching of the first harmonic.""" @@ -6881,55 +7203,41 @@ def AltTypes(self): def PrecisionLoiterCompanion(self): """Use Companion PrecLand backend precision messages to loiter.""" - self.context_push() - - ex = None - try: - 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() - self.reboot_sitl() - - self.progress("Waiting for location") - self.change_mode('LOITER') - self.wait_ready_to_arm() + 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() + self.reboot_sitl() - # we should be doing precision loiter at this point - start = self.assert_receive_message('LOCAL_POSITION_NED') + self.progress("Waiting for location") + self.change_mode('LOITER') + self.wait_ready_to_arm() - self.takeoff(20, mode='ALT_HOLD') + # we should be doing precision loiter at this point + start = self.assert_receive_message('LOCAL_POSITION_NED') - # move away a little - self.set_rc(2, 1550) - self.wait_distance(5, accuracy=1) - self.set_rc(2, 1500) - self.change_mode('LOITER') + self.takeoff(20, mode='ALT_HOLD') - # turn precision loiter on: - self.context_collect('STATUSTEXT') - self.set_rc(7, 2000) + # move away a little + self.set_rc(2, 1550) + self.wait_distance(5, accuracy=1) + self.set_rc(2, 1500) + self.change_mode('LOITER') - # try to drag aircraft to a position 5 metres north-east-east: - 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) + # turn precision loiter on: + self.context_collect('STATUSTEXT') + self.set_rc(7, 2000) - except Exception as e: - self.print_exception_caught(e) - ex = e + # try to drag aircraft to a position 5 metres north-east-east: + 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) - self.context_pop() self.disarm_vehicle(force=True) - self.reboot_sitl() - self.progress("All done") - - if ex is not None: - raise ex def loiter_requires_position(self): # ensure we can't switch to LOITER without position @@ -6937,7 +7245,7 @@ def loiter_requires_position(self): self.context_push() self.set_parameters({ "GPS1_TYPE": 2, - "SIM_GPS_DISABLE": 1, + "SIM_GPS1_ENABLE": 0, }) # if there is no GPS at all then we must direct EK3 to not use # it at all. Otherwise it will never initialise, as it wants @@ -6986,57 +7294,39 @@ def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() - ex = None - try: - self.set_parameter("PILOT_TKOFF_ALT", 700) - self.change_mode('POSHOLD') - self.set_rc(3, 1000) - self.wait_ready_to_arm() - self.arm_vehicle() - self.delay_sim_time(2) - # check we are still on the ground... - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - if abs(m.relative_alt) > 100: - raise NotAchievedException("Took off prematurely") - - self.progress("Pushing throttle up") - self.set_rc(3, 1710) - self.delay_sim_time(0.5) - self.progress("Bringing back to hover throttle") - self.set_rc(3, 1500) + self.set_parameter("PILOT_TKOFF_ALT", 700) + self.change_mode('POSHOLD') + self.set_rc(3, 1000) + self.wait_ready_to_arm() + self.arm_vehicle() + self.delay_sim_time(2) + # check we are still on the ground... + relative_alt = self.get_altitude(relative=True) + if relative_alt > 0.1: + raise NotAchievedException("Took off prematurely") - # make sure we haven't already reached alt: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - max_initial_alt = 2000 - if abs(m.relative_alt) > max_initial_alt: - raise NotAchievedException("Took off too fast (%f > %f" % - (abs(m.relative_alt), max_initial_alt)) + self.progress("Pushing throttle up") + self.set_rc(3, 1710) + self.delay_sim_time(0.5) + self.progress("Bringing back to hover throttle") + self.set_rc(3, 1500) - self.progress("Monitoring takeoff-to-alt") - self.wait_altitude(6.9, 8, relative=True) + # make sure we haven't already reached alt: + relative_alt = self.get_altitude(relative=True) + max_initial_alt = 2.0 + if abs(relative_alt) > max_initial_alt: + raise NotAchievedException("Took off too fast (%f > %f" % + (relative_alt, max_initial_alt)) - self.progress("Making sure we stop at our takeoff altitude") - tstart = self.get_sim_time() - while self.get_sim_time() - tstart < 5: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - delta = abs(7000 - m.relative_alt) - self.progress("alt=%f delta=%f" % (m.relative_alt/1000, - delta/1000)) - if delta > 1000: - raise NotAchievedException("Failed to maintain takeoff alt") - self.progress("takeoff OK") - except Exception as e: - self.print_exception_caught(e) - ex = e + self.progress("Monitoring takeoff-to-alt") + self.wait_altitude(6.9, 8, relative=True, minimum_duration=10) + self.progress("takeoff OK") self.land_and_disarm() self.set_rc(8, 1000) self.context_pop() - if ex is not None: - raise ex - def initial_mode(self): return "STABILIZE" @@ -7189,33 +7479,28 @@ def OBSTACLE_DISTANCE_3D(self): def AC_Avoidance_Proximity(self): '''Test proximity avoidance slide behaviour''' + self.context_push() - ex = None - try: - self.load_fence("copter-avoidance-fence.txt") - self.set_parameters({ - "FENCE_ENABLE": 1, - "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") + self.load_fence("copter-avoidance-fence.txt") + self.set_parameters({ + "FENCE_ENABLE": 1, + "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 - self.context_pop() - self.clear_fence() self.disarm_vehicle(force=True) + + self.context_pop() self.reboot_sitl() - if ex is not None: - raise ex def ProximitySensors(self): '''ensure proximity sensors return appropriate data''' @@ -7364,8 +7649,8 @@ def shove(a, b): self.progress("Caught exception: %s" % self.get_exception_stacktrace(e)) ex = e - self.context_pop() self.disarm_vehicle(force=True) + self.context_pop() self.reboot_sitl() if ex is not None: raise ex @@ -7376,18 +7661,53 @@ def AC_Avoidance_Fence(self): self.set_parameter("FENCE_ENABLE", 1) self.check_avoidance_corners() - def global_position_int_for_location(self, loc, time_boot, heading=0): - return self.mav.mav.global_position_int_encode( - int(time_boot * 1000), # time_boot_ms - int(loc.lat * 1e7), - int(loc.lng * 1e7), - int(loc.alt * 1000), # alt in mm - 20, # relative alt - urp. - vx=0, - vy=0, - vz=0, - hdg=heading - ) + def AvoidanceAltFence(self): + '''Test fence avoidance at minimum and maximum altitude''' + ex = None + try: + self.set_parameters({ + "FENCE_ENABLE": 1, + "FENCE_TYPE": 9, # min and max alt fence + "FENCE_ALT_MIN": 10, + "FENCE_ALT_MAX": 30, + }) + + self.change_mode('LOITER') + self.wait_ekf_happy() + + tstart = self.get_sim_time() + self.takeoff(15, mode='LOITER') + self.progress("Increasing throttle, vehicle should stay below 30m") + self.set_rc(3, 1920) + + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 20: + break + alt = self.get_altitude(relative=True) + self.progress("Altitude %s" % alt) + if alt > 30: + raise NotAchievedException("Breached maximum altitude (%s)" % (str(alt),)) + + self.progress("Decreasing, vehicle should stay above 10m") + self.set_rc(3, 1080) + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 20: + break + alt = self.get_altitude(relative=True) + self.progress("Altitude %s" % alt) + if alt < 10: + raise NotAchievedException("Breached minimum altitude (%s)" % (str(alt),)) + + except Exception as e: + self.progress("Caught exception: %s" % + self.get_exception_stacktrace(e)) + ex = e + self.land_and_disarm() + self.disarm_vehicle(force=True) + if ex is not None: + raise ex def ModeFollow(self): '''Fly follow mode''' @@ -7399,6 +7719,7 @@ def ModeFollow(self): "FOLL_OFS_TYPE": 1, # relative to other vehicle heading }) self.takeoff(10, mode="LOITER") + self.context_push() self.set_parameter("SIM_SPEEDUP", 1) self.change_mode("FOLLOW") new_loc = self.mav.location() @@ -7418,6 +7739,8 @@ def ModeFollow(self): (expected_loc.lat, expected_loc.lng)) self.progress("expected_loc: %s" % str(expected_loc)) + origin = self.poll_message('GPS_GLOBAL_ORIGIN') + last_sent = 0 tstart = self.get_sim_time() while True: @@ -7425,9 +7748,17 @@ def ModeFollow(self): if now - tstart > 60: raise NotAchievedException("Did not FOLLOW") if now - last_sent > 0.5: - gpi = self.global_position_int_for_location(new_loc, - now, - heading=heading) + gpi = self.mav.mav.global_position_int_encode( + int(now * 1000), # time_boot_ms + int(new_loc.lat * 1e7), + int(new_loc.lng * 1e7), + int(new_loc.alt * 1000), # alt in mm + int(new_loc.alt * 1000 - origin.altitude), # relative alt - urp. + vx=0, + vy=0, + vz=0, + hdg=heading + ) gpi.pack(self.mav.mav) self.mav.mav.send(gpi) self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) @@ -7437,6 +7768,7 @@ def ModeFollow(self): self.progress("position delta=%f (want <%f)" % (delta, max_delta)) if delta < max_delta: break + self.context_pop() self.do_RTL() def get_global_position_int(self, timeout=30): @@ -7460,87 +7792,69 @@ def BeaconPosition(self): old_pos = self.get_global_position_int() print("old_pos=%s" % str(old_pos)) - self.context_push() - ex = None - try: - self.set_parameters({ - "BCN_TYPE": 10, - "BCN_LATITUDE": SITL_START_LOCATION.lat, - "BCN_LONGITUDE": SITL_START_LOCATION.lng, - "BCN_ALT": SITL_START_LOCATION.alt, - "BCN_ORIENT_YAW": 0, - "AVOID_ENABLE": 4, - "GPS1_TYPE": 0, - "EK3_ENABLE": 1, - "EK3_SRC1_POSXY": 4, # Beacon - "EK3_SRC1_POSZ": 1, # Baro - "EK3_SRC1_VELXY": 0, # None - "EK3_SRC1_VELZ": 0, # None - "EK2_ENABLE": 0, - "AHRS_EKF_TYPE": 3, - }) - self.reboot_sitl() + self.set_parameters({ + "BCN_TYPE": 10, + "BCN_LATITUDE": SITL_START_LOCATION.lat, + "BCN_LONGITUDE": SITL_START_LOCATION.lng, + "BCN_ALT": SITL_START_LOCATION.alt, + "BCN_ORIENT_YAW": 0, + "AVOID_ENABLE": 4, + "GPS1_TYPE": 0, + "EK3_ENABLE": 1, + "EK3_SRC1_POSXY": 4, # Beacon + "EK3_SRC1_POSZ": 1, # Baro + "EK3_SRC1_VELXY": 0, # None + "EK3_SRC1_VELZ": 0, # None + "EK2_ENABLE": 0, + "AHRS_EKF_TYPE": 3, + }) + self.reboot_sitl() - # turn off GPS arming checks. This may be considered a - # bug that we need to do this. - old_arming_check = int(self.get_parameter("ARMING_CHECK")) - if old_arming_check == 1: - old_arming_check = 1 ^ 25 - 1 - new_arming_check = int(old_arming_check) & ~(1 << 3) - self.set_parameter("ARMING_CHECK", new_arming_check) + # turn off GPS arming checks. This may be considered a + # bug that we need to do this. + old_arming_check = int(self.get_parameter("ARMING_CHECK")) + if old_arming_check == 1: + old_arming_check = 1 ^ 25 - 1 + new_arming_check = int(old_arming_check) & ~(1 << 3) + self.set_parameter("ARMING_CHECK", new_arming_check) - self.reboot_sitl() + self.reboot_sitl() - # require_absolute=True infers a GPS is present - self.wait_ready_to_arm(require_absolute=False) + # require_absolute=True infers a GPS is present + self.wait_ready_to_arm(require_absolute=False) - tstart = self.get_sim_time() - timeout = 20 - while True: - if self.get_sim_time_cached() - tstart > timeout: - raise NotAchievedException("Did not get new position like old position") - self.progress("Fetching location") - new_pos = self.get_global_position_int() - pos_delta = self.get_distance_int(old_pos, new_pos) - max_delta = 1 - self.progress("delta=%u want <= %u" % (pos_delta, max_delta)) - if pos_delta <= max_delta: - break + tstart = self.get_sim_time() + timeout = 20 + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise NotAchievedException("Did not get new position like old position") + self.progress("Fetching location") + new_pos = self.get_global_position_int() + pos_delta = self.get_distance_int(old_pos, new_pos) + max_delta = 1 + self.progress("delta=%u want <= %u" % (pos_delta, max_delta)) + if pos_delta <= max_delta: + break - self.progress("Moving to ensure location is tracked") - self.takeoff(10, mode="STABILIZE") - self.change_mode("CIRCLE") + self.progress("Moving to ensure location is tracked") + self.takeoff(10, mode="STABILIZE") + self.change_mode("CIRCLE") - tstart = self.get_sim_time() - max_delta = 0 - max_allowed_delta = 10 - while True: - if self.get_sim_time_cached() - tstart > timeout: - break + self.context_push() + validator = vehicle_test_suite.TestSuite.ValidateGlobalPositionIntAgainstSimState(self, max_allowed_divergence=10) + self.install_message_hook_context(validator) - pos_delta = self.get_distance_int(self.sim_location_int(), self.get_global_position_int()) - self.progress("pos_delta=%f max_delta=%f max_allowed_delta=%f" % (pos_delta, max_delta, max_allowed_delta)) - if pos_delta > max_delta: - max_delta = pos_delta - if pos_delta > max_allowed_delta: - raise NotAchievedException("Vehicle location not tracking simulated location (%f > %f)" % - (pos_delta, max_allowed_delta)) - self.progress("Tracked location just fine (max_delta=%f)" % max_delta) - self.change_mode("LOITER") - self.wait_groundspeed(0, 0.3, timeout=120) - self.land_and_disarm() + self.delay_sim_time(20) + self.progress("Tracked location just fine") + self.context_pop() - self.assert_current_onboard_log_contains_message("BCN") + self.change_mode("LOITER") + 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 self.disarm_vehicle(force=True) - self.reboot_sitl() - self.context_pop() - self.reboot_sitl() - if ex is not None: - raise ex def AC_Avoidance_Beacon(self): '''Test beacon avoidance slide behaviour''' @@ -7591,7 +7905,8 @@ def BaroWindCorrection(self): ex = None try: self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('Callisto'))], + [], + defaults_filepath=self.model_defaults_filepath('Callisto'), model="octa-quad:@ROMFS/models/Callisto.json", wipe=True, ) @@ -8373,6 +8688,14 @@ def MaxBotixI2CXL(self): if ex is not None: raise ex + def fly_rangefinder_sitl(self): + self.set_parameters({ + "RNGFND1_TYPE": 100, + }) + self.reboot_sitl() + self.fly_rangefinder_drivers_fly([("unused", "sitl")]) + self.wait_disarmed() + def RangeFinderDrivers(self): '''Test rangefinder drivers''' self.set_parameters({ @@ -8426,6 +8749,7 @@ def RangeFinderDrivers(self): self.context_pop() self.fly_rangefinder_mavlink() + self.fly_rangefinder_sitl() # i.e. type 100 i2c_drivers = [ ("maxbotixi2cxl", 2), @@ -8662,7 +8986,7 @@ def test_replay_gps_bit(self): "RNGFND1_POS_Y": -0.07, "RNGFND1_POS_Z": -0.005, "SIM_SONAR_SCALE": 30, - "SIM_GPS2_DISABLE": 0, + "SIM_GPS2_ENABLE": 1, }) self.reboot_sitl() @@ -8708,7 +9032,7 @@ def test_replay_optical_flow_bit(self): print("log difference: %s" % str(log_difference)) return log_difference[0] - def GPSBlending(self): + def GPSBlendingLog(self): '''Test GPS Blending''' '''ensure we get dataflash log messages for blended instance''' @@ -8721,7 +9045,7 @@ def GPSBlending(self): self.set_parameters({ "GPS2_TYPE": 1, "SIM_GPS2_TYPE": 1, - "SIM_GPS2_DISABLE": 0, + "SIM_GPS2_ENABLE": 1, "GPS_AUTO_SWITCH": 2, }) self.reboot_sitl() @@ -8783,10 +9107,209 @@ def GPSBlending(self): if ex is not None: raise ex + def GPSBlending(self): + '''Test GPS Blending''' + '''ensure we get dataflash log messages for blended instance''' + + # configure: + self.set_parameters({ + "WP_YAW_BEHAVIOR": 0, # do not yaw + "GPS2_TYPE": 1, + "SIM_GPS2_TYPE": 1, + "SIM_GPS2_ENABLE": 1, + "SIM_GPS1_POS_X": 1.0, + "SIM_GPS1_POS_Y": -1.0, + "SIM_GPS2_POS_X": -1.0, + "SIM_GPS2_POS_Y": 1.0, + "GPS_AUTO_SWITCH": 2, + }) + self.reboot_sitl() + + alt = 10 + self.takeoff(alt, mode='GUIDED') + self.fly_guided_move_local(30, 0, alt) + self.fly_guided_move_local(30, 30, alt) + self.fly_guided_move_local(0, 30, alt) + self.fly_guided_move_local(0, 0, alt) + self.change_mode('LAND') + + current_log_file = self.dfreader_for_current_onboard_log() + + self.wait_disarmed() + + # ensure that the blended solution is always about half-way + # between the two GPSs: + current_ts = None + while True: + m = current_log_file.recv_match(type='GPS') + if m is None: + break + if current_ts is None: + if m.I != 0: # noqa + continue + current_ts = m.TimeUS + measurements = {} + if m.TimeUS != current_ts: + current_ts = None + continue + measurements[m.I] = (m.Lat, m.Lng) + if len(measurements) == 3: + # check lat: + for n in 0, 1: + expected_blended = (measurements[0][n] + measurements[1][n])/2 + epsilon = 0.0000002 + error = abs(measurements[2][n] - expected_blended) + if error > epsilon: + raise NotAchievedException("Blended diverged") + current_ts = None + + if len(measurements) != 3: + raise NotAchievedException("Did not see three GPS measurements!") + + def GPSWeightedBlending(self): + '''Test GPS Weighted Blending''' + + self.context_push() + + # configure: + self.set_parameters({ + "WP_YAW_BEHAVIOR": 0, # do not yaw + "GPS2_TYPE": 1, + "SIM_GPS2_TYPE": 1, + "SIM_GPS2_ENABLE": 1, + "SIM_GPS1_POS_X": 1.0, + "SIM_GPS1_POS_Y": -1.0, + "SIM_GPS2_POS_X": -1.0, + "SIM_GPS2_POS_Y": 1.0, + "GPS_AUTO_SWITCH": 2, + }) + # configure velocity errors such that the 1st GPS should be + # 4/5, second GPS 1/5 of result (0.5**2)/((0.5**2)+(1.0**2)) + self.set_parameters({ + "SIM_GPS1_VERR_X": 0.3, # m/s + "SIM_GPS1_VERR_Y": 0.4, + "SIM_GPS2_VERR_X": 0.6, # m/s + "SIM_GPS2_VERR_Y": 0.8, + "GPS_BLEND_MASK": 4, # use only speed for blend calculations + }) + self.reboot_sitl() + + alt = 10 + self.takeoff(alt, mode='GUIDED') + self.fly_guided_move_local(30, 0, alt) + self.fly_guided_move_local(30, 30, alt) + self.fly_guided_move_local(0, 30, alt) + self.fly_guided_move_local(0, 0, alt) + self.change_mode('LAND') + + current_log_file = self.dfreader_for_current_onboard_log() + + self.wait_disarmed() + + # ensure that the blended solution is always about half-way + # between the two GPSs: + current_ts = None + while True: + m = current_log_file.recv_match(type='GPS') + if m is None: + break + if current_ts is None: + if m.I != 0: # noqa + continue + current_ts = m.TimeUS + measurements = {} + if m.TimeUS != current_ts: + current_ts = None + continue + measurements[m.I] = (m.Lat, m.Lng, m.Alt) + if len(measurements) == 3: + # check lat: + for n in 0, 1, 2: + expected_blended = 0.8*measurements[0][n] + 0.2*measurements[1][n] + axis_epsilons = [0.0000002, 0.0000002, 0.2] + epsilon = axis_epsilons[n] + error = abs(measurements[2][n] - expected_blended) + if error > epsilon: + raise NotAchievedException(f"Blended diverged {n=} {measurements[0][n]=} {measurements[1][n]=}") + current_ts = None + + self.context_pop() + self.reboot_sitl() + + def GPSBlendingAffinity(self): + '''test blending when affinity in use''' + # configure: + self.set_parameters({ + "WP_YAW_BEHAVIOR": 0, # do not yaw + "GPS2_TYPE": 1, + "SIM_GPS2_TYPE": 1, + "SIM_GPS2_ENABLE": 1, + "SIM_GPS1_POS_X": 1.0, + "SIM_GPS1_POS_Y": -1.0, + "SIM_GPS2_POS_X": -1.0, + "SIM_GPS2_POS_Y": 1.0, + "GPS_AUTO_SWITCH": 2, + + "EK3_AFFINITY" : 1, + "EK3_IMU_MASK": 7, + "SIM_IMU_COUNT": 3, + "INS_ACC3OFFS_X": 0.001, + "INS_ACC3OFFS_Y": 0.001, + "INS_ACC3OFFS_Z": 0.001, + }) + # force-calibration of accel: + self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, p5=76) + self.reboot_sitl() + + alt = 10 + self.takeoff(alt, mode='GUIDED') + self.fly_guided_move_local(30, 0, alt) + self.fly_guided_move_local(30, 30, alt) + self.fly_guided_move_local(0, 30, alt) + self.fly_guided_move_local(0, 0, alt) + self.change_mode('LAND') + + current_log_file = self.dfreader_for_current_onboard_log() + + self.wait_disarmed() + + # ensure that the blended solution is always about half-way + # between the two GPSs: + current_ts = None + max_errors = [0, 0, 0] + while True: + m = current_log_file.recv_match(type='XKF1') + if m is None: + break + if current_ts is None: + if m.C != 0: # noqa + continue + current_ts = m.TimeUS + measurements = {} + if m.TimeUS != current_ts: + current_ts = None + continue + measurements[m.C] = (m.PN, m.PE, m.PD) + if len(measurements) == 3: + # check lat: + for n in 0, 1, 2: + expected_blended = 0.5*measurements[0][n] + 0.5*measurements[1][n] + axis_epsilons = [0.02, 0.02, 0.03] + epsilon = axis_epsilons[n] + error = abs(measurements[2][n] - expected_blended) + # self.progress(f"{n=} {error=}") + if error > max_errors[n]: + max_errors[n] = error + if error > epsilon: + raise NotAchievedException(f"Blended diverged {n=} {measurements[0][n]=} {measurements[1][n]=} {measurements[2][n]=} {error=}") # noqa:E501 + current_ts = None + self.progress(f"{max_errors=}") + def Callisto(self): '''Test Callisto''' self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ], + [], + defaults_filepath=self.model_defaults_filepath('Callisto'), model="octa-quad:@ROMFS/models/Callisto.json", wipe=True, ) @@ -8820,12 +9343,12 @@ def FlyEachFrame(self): # the model string for Callisto has crap in it.... we # should really have another entry in the vehicleinfo data # to carry the path to the JSON. - actual_model = model.split(":")[0] - defaults = self.model_defaults_filepath(actual_model) + defaults = self.model_defaults_filepath(frame) if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) @@ -8872,6 +9395,10 @@ def Replay(self): '''test replay correctness''' self.progress("Building Replay") util.build_SITL('tool/Replay', clean=False, configure=False) + self.set_parameters({ + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, + }) bits = [ ('GPS', self.test_replay_gps_bit), @@ -8891,17 +9418,12 @@ def test_replay_bit(self, bit): (current_log_filepath, os.path.getsize(current_log_filepath)) )) - util.run_cmd( - ['build/sitl/tool/Replay', current_log_filepath], - directory=util.topdir(), - checkfail=True, - show=True, - output=True, - ) + self.run_replay(current_log_filepath) + + replay_log_filepath = self.current_onboard_log_filepath() self.context_pop() - replay_log_filepath = self.current_onboard_log_filepath() self.progress("Replay log path: %s" % str(replay_log_filepath)) check_replay = util.load_local_module("Tools/Replay/check_replay.py") @@ -9308,28 +9830,32 @@ def RefindGPS(self): def GPSForYaw(self): '''Moving baseline GPS yaw''' - self.context_push() self.load_default_params_file("copter-gps-for-yaw.parm") self.reboot_sitl() - ex = None - try: - self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True) - m = self.assert_receive_message("GPS2_RAW") - self.progress(self.dump_message_verbose(m)) - want = 27000 - if abs(m.yaw - want) > 500: - raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw)) - self.wait_ready_to_arm() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() + self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True) + m = self.assert_receive_message("GPS2_RAW", very_verbose=True) + want = 27000 + if abs(m.yaw - want) > 500: + raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw)) + self.wait_ready_to_arm() - self.reboot_sitl() + def SMART_RTL_EnterLeave(self): + '''check SmartRTL behaviour when entering/leaving''' + # we had a bug where we would consume points when re-entering smartrtl - if ex is not None: - raise ex + self.upload_simple_relhome_mission([ + # N E U + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.set_parameter('AUTO_OPTIONS', 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.change_mode('ALT_HOLD') + self.change_mode('SMART_RTL') + self.change_mode('ALT_HOLD') + self.change_mode('SMART_RTL') def GPSForYawCompassLearn(self): '''Moving baseline GPS yaw - with compass learning''' @@ -9714,6 +10240,8 @@ def ATTITUDE_FAST(self): self.set_parameters({ "LOG_BITMASK": new, "LOG_DISARMED": 1, + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, }) path = self.generate_rate_sample_log() @@ -9731,11 +10259,15 @@ def ATTITUDE_FAST(self): self.delay_sim_time(10) # NFI why this is required self.check_dflog_message_rates(path, { - 'ATT': 400, + 'ANG': 400, }) def BaseLoggingRates(self): '''ensure messages come out at specific rates''' + self.set_parameters({ + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, + }) path = self.generate_rate_sample_log() self.delay_sim_time(10) # NFI why this is required self.check_dflog_message_rates(path, { @@ -10070,9 +10602,10 @@ def Sprayer(self): self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.disarm_vehicle(force=True) + self.context_pop() - self.disarm_vehicle(force=True) self.reboot_sitl() self.progress("Sprayer OK") @@ -10118,6 +10651,7 @@ def tests1c(self): '''return list of all tests''' ret = ([ self.BatteryFailsafe, + self.BatteryMissing, self.VibrationFailsafe, self.EK3AccelBias, self.StabilityPatch, @@ -10126,6 +10660,7 @@ def tests1c(self): self.AC_Avoidance_Proximity_AVOID_ALT_MIN, self.AC_Avoidance_Fence, self.AC_Avoidance_Beacon, + self.AvoidanceAltFence, self.BaroWindCorrection, self.SetpointGlobalPos, self.ThrowDoubleDrop, @@ -10133,6 +10668,7 @@ def tests1c(self): self.SetpointBadVel, self.SplineTerrain, self.TakeoffCheck, + self.GainBackoffTakeoff, ]) return ret @@ -10142,8 +10678,12 @@ def tests1d(self): self.HorizontalFence, self.HorizontalAvoidFence, self.MaxAltFence, + self.MaxAltFenceAvoid, self.MinAltFence, + self.MinAltFenceAvoid, self.FenceFloorEnabledLanding, + self.FenceFloorAutoDisableLanding, + self.FenceFloorAutoEnableOnArming, self.AutoTuneSwitch, self.GPSGlitchLoiter, self.GPSGlitchLoiter2, @@ -10183,6 +10723,7 @@ def tests1e(self): self.MountYawVehicleForMountROI, self.MAV_CMD_DO_MOUNT_CONTROL, self.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, + self.AutoYawDO_MOUNT_CONTROL, self.Button, self.ShipTakeoff, self.RangeFinder, @@ -10254,6 +10795,58 @@ def ScriptMountPOI(self): self.context_pop() self.reboot_sitl() + def ScriptCopterPosOffsets(self): + '''test the copter-posoffset.lua example script''' + self.context_push() + + # enable scripting and arming/takingoff in Auto mode + self.set_parameters({ + "SCR_ENABLE": 1, + "AUTO_OPTIONS": 3, + "RC12_OPTION": 300 + }) + self.reboot_sitl() + + # install copter-posoffset script + self.install_example_script_context('copter-posoffset.lua') + self.reboot_sitl() + + # create simple mission with a single takeoff command + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20) + ]) + + # switch to loiter to wait for position estimate (aka GPS lock) + self.change_mode('LOITER') + self.wait_ready_to_arm() + + # arm and takeoff in Auto mode + self.change_mode('AUTO') + self.arm_vehicle() + + # wait for vehicle to climb to at least 10m + self.wait_altitude(8, 12, relative=True) + + # add position offset to East and confirm vehicle moves + self.set_parameter("PSC_OFS_POS_E", 20) + self.set_rc(12, 2000) + self.wait_distance(18) + + # remove position offset and wait for vehicle to return home + self.set_parameter("PSC_OFS_POS_E", 0) + self.wait_distance_to_home(distance_min=0, distance_max=4, timeout=20) + + # add velocity offset and confirm vehicle moves + self.set_parameter("PSC_OFS_VEL_N", 5) + self.wait_groundspeed(4.8, 5.2, minimum_duration=5, timeout=20) + + # remove velocity offset and switch to RTL + self.set_parameter("PSC_OFS_VEL_N", 0) + self.set_rc(12, 1000) + self.do_RTL() + self.context_pop() + self.reboot_sitl() + def AHRSTrimLand(self): '''test land detector with significant AHRS trim''' self.context_push() @@ -10268,6 +10861,126 @@ def AHRSTrimLand(self): self.context_pop() self.reboot_sitl() + def GainBackoffTakeoff(self): + '''test gain backoff on takeoff''' + self.context_push() + self.progress("Test gains are fully backed off") + self.set_parameters({ + "ATC_LAND_R_MULT": 0.0, + "ATC_LAND_P_MULT": 0.0, + "ATC_LAND_Y_MULT": 0.0, + "GCS_PID_MASK" : 7, + "LOG_BITMASK": 180222, + }) + self.reboot_sitl() + self.wait_ready_to_arm() + self.change_mode('ALT_HOLD') + + class ValidatePDZero(vehicle_test_suite.TestSuite.MessageHook): + '''asserts correct values in PID_TUNING''' + + def __init__(self, suite, axis): + super(ValidatePDZero, self).__init__(suite) + self.pid_tuning_count = 0 + self.p_sum = 0 + self.d_sum = 0 + self.i_sum = 0 + self.axis = axis + + def hook_removed(self): + if self.pid_tuning_count == 0: + raise NotAchievedException("Did not get PID_TUNING") + if self.i_sum == 0: + raise ValueError("I sum is zero") + print(f"ValidatePDZero: PID_TUNING count: {self.pid_tuning_count}") + + def process(self, mav, m): + if m.get_type() != 'PID_TUNING' or m.axis != self.axis: + return + self.pid_tuning_count += 1 + self.p_sum += m.P + self.d_sum += m.D + self.i_sum += m.I + if self.p_sum > 0: + raise ValueError("P sum is not zero") + if self.d_sum > 0: + raise ValueError("D sum is not zero") + + self.progress("Check that PD values are zero") + self.install_message_hook_context(ValidatePDZero(self, mavutil.mavlink.PID_TUNING_ROLL)) + self.install_message_hook_context(ValidatePDZero(self, mavutil.mavlink.PID_TUNING_PITCH)) + self.install_message_hook_context(ValidatePDZero(self, mavutil.mavlink.PID_TUNING_YAW)) + # until the context pop happens, all received PID_TUNINGS will be verified as good + self.arm_vehicle() + self.set_rc(3, 1500) + self.delay_sim_time(2) + self.set_rc(2, 1250) + self.delay_sim_time(5) + self.assert_receive_message('PID_TUNING', timeout=5) + self.set_rc_default() + self.zero_throttle() + self.disarm_vehicle() + self.context_pop() + + self.context_push() + self.progress("Test gains are not backed off") + self.set_parameters({ + "ATC_LAND_R_MULT": 1.0, + "ATC_LAND_P_MULT": 1.0, + "ATC_LAND_Y_MULT": 1.0, + "GCS_PID_MASK" : 7, + "LOG_BITMASK": 180222, + }) + self.reboot_sitl() + self.wait_ready_to_arm() + self.change_mode('ALT_HOLD') + + class ValidatePDNonZero(vehicle_test_suite.TestSuite.MessageHook): + '''asserts correct values in PID_TUNING''' + + def __init__(self, suite, axis): + super(ValidatePDNonZero, self).__init__(suite) + self.pid_tuning_count = 0 + self.p_sum = 0 + self.d_sum = 0 + self.i_sum = 0 + self.axis = axis + + def hook_removed(self): + if self.pid_tuning_count == 0: + raise NotAchievedException("Did not get PID_TUNING") + if self.p_sum == 0: + raise ValueError("P sum is zero") + if self.i_sum == 0: + raise ValueError("I sum is zero") + print(f"ValidatePDNonZero: PID_TUNING count: {self.pid_tuning_count}") + + def process(self, mav, m): + if m.get_type() != 'PID_TUNING' or m.axis != self.axis: + return + self.pid_tuning_count += 1 + self.p_sum += m.P + self.d_sum += m.D + self.i_sum += m.I + + self.progress("Check that PD values are non-zero") + self.install_message_hook_context(ValidatePDNonZero(self, mavutil.mavlink.PID_TUNING_ROLL)) + self.install_message_hook_context(ValidatePDNonZero(self, mavutil.mavlink.PID_TUNING_PITCH)) + self.install_message_hook_context(ValidatePDNonZero(self, mavutil.mavlink.PID_TUNING_YAW)) + # until the context pop happens, all received PID_TUNINGS will be verified as good + self.arm_vehicle() + self.set_rc(3, 1500) + self.delay_sim_time(2) + self.set_rc(2, 1250) + self.delay_sim_time(5) + self.assert_receive_message('PID_TUNING', timeout=5) + self.set_rc_default() + self.zero_throttle() + self.disarm_vehicle() + + self.context_pop() + self.reboot_sitl() + def turn_safety_x(self, value): self.mav.mav.set_mode_send( self.mav.target_system, @@ -10726,6 +11439,7 @@ def MAV_CMD_NAV_TAKEOFF_command_int(self): def Ch6TuningWPSpeed(self): '''test waypoint speed can be changed via Ch6 tuning knob''' self.set_parameters({ + "RC6_OPTION": 219, # RC6 used for tuning "TUNE": 10, # 10 is waypoint speed "TUNE_MIN": 0.02, # 20cm/s "TUNE_MAX": 1000, # 10m/s @@ -10864,48 +11578,628 @@ def GuidedModeThrust(self): self.wait_altitude(0.5, 100, relative=True, timeout=10) self.do_RTL() - def tests2b(self): # this block currently around 9.5mins here - '''return list of all tests''' - ret = ([ - self.MotorVibration, - Test(self.DynamicNotches, attempts=4), - self.PositionWhenGPSIsZero, - Test(self.DynamicRpmNotches, attempts=4), - self.PIDNotches, - self.RefindGPS, - Test(self.GyroFFT, attempts=1, speedup=8), - Test(self.GyroFFTHarmonic, attempts=4, speedup=8), - Test(self.GyroFFTAverage, attempts=1, speedup=8), - Test(self.GyroFFTContinuousAveraging, attempts=4, speedup=8), - self.GyroFFTPostFilter, - self.GyroFFTMotorNoiseCheck, - self.CompassReordering, - self.CRSF, - self.MotorTest, - self.AltEstimation, - self.EKFSource, - self.GSF, - self.GSF_reset, - 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.MISSION_START, - self.AUTO_LAND_TO_BRAKE, - self.WPNAV_SPEED, - self.WPNAV_SPEED_UP, - self.WPNAV_SPEED_DN, + def AutoRTL(self): + '''Test Auto RTL mode using do land start and return path start mission items''' + alt = 50 + guided_loc = self.home_relative_loc_ne(1000, 0) + guided_loc.alt += alt + + # Arm, take off and fly to guided location + self.takeoff(mode='GUIDED') + self.fly_guided_move_to(guided_loc, timeout=240) + + # Try auto RTL mode, should fail with no mission + try: + self.change_mode('AUTO_RTL', timeout=10) + raise NotAchievedException("Should not change mode with no mission") + except WaitModeTimeout: + pass + except Exception as e: + raise e + + # pymavlink does not understand the new return path command yet, at some point it will + cmd_return_path_start = 188 # mavutil.mavlink.MAV_CMD_DO_RETURN_PATH_START + + # Do land start and do return path should both fail as commands too + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Load mission with do land start + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, alt), # 1 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 750, 0, alt), # 2 + self.create_MISSION_ITEM_INT(mavutil.mavlink.MAV_CMD_DO_LAND_START), # 3 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, alt), # 4 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 250, 0, alt), # 5 + ]) + + # Return path should still fail + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Do land start should jump to the waypoint following the item + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(4) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # mode change to Auto RTL should do the same + self.change_mode('AUTO_RTL') + self.drain_mav() + self.assert_current_waypoint(4) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # Add a return path item + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1250, 0, alt), # 1 + self.create_MISSION_ITEM_INT(cmd_return_path_start), # 2 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 900, 0, alt), # 3 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 750, 0, alt), # 4 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 550, 0, alt), # 5 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, alt), # 6 + self.create_MISSION_ITEM_INT(mavutil.mavlink.MAV_CMD_DO_LAND_START), # 7 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 250, 0, alt), # 8 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -250, 0, alt), # 9 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -500, 0, alt), # 10 + ]) + + # Return path should now work + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(3) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # mode change to Auto RTL should join the return path + self.change_mode('AUTO_RTL') + self.drain_mav() + self.assert_current_waypoint(3) + + # do land start should still work + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(8) + + # Move a bit closer in guided + return_path_test = self.home_relative_loc_ne(600, 0) + return_path_test.alt += alt + self.change_mode('GUIDED') + self.fly_guided_move_to(return_path_test, timeout=100) + + # check the mission is joined further along + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(5) + + # fly over home + home = self.home_relative_loc_ne(0, 0) + home.alt += alt + self.change_mode('GUIDED') + self.fly_guided_move_to(home, timeout=140) + + # Should never join return path after do land start + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(6) + + # Done + self.land_and_disarm() + + def EK3_OGN_HGT_MASK(self): + '''test baraometer-alt-compensation based on long-term GPS readings''' + self.context_push() + self.set_parameters({ + 'EK3_OGN_HGT_MASK': 1, # compensate baro drift using GPS + }) + self.reboot_sitl() + + expected_alt = 10 + + self.change_mode('GUIDED') + self.wait_ready_to_arm() + current_alt = self.get_altitude() + + expected_alt_abs = current_alt + expected_alt + + self.takeoff(expected_alt, mode='GUIDED') + self.delay_sim_time(5) + + self.set_parameter("SIM_BARO_DRIFT", 0.01) # 1cm/second + + def check_altitude(mav, m): + m_type = m.get_type() + epsilon = 10 # in metres + if m_type == 'GPS_RAW_INT': + got_gps_alt = m.alt * 0.001 + if abs(expected_alt_abs - got_gps_alt) > epsilon: + raise NotAchievedException(f"Bad GPS altitude (got={got_gps_alt} want={expected_alt_abs})") + elif m_type == 'GLOBAL_POSITION_INT': + got_canonical_alt = m.relative_alt * 0.001 + if abs(expected_alt - got_canonical_alt) > epsilon: + raise NotAchievedException(f"Bad canonical altitude (got={got_canonical_alt} want={expected_alt})") + + self.install_message_hook_context(check_altitude) + + self.delay_sim_time(1500) + + self.disarm_vehicle(force=True) + + self.context_pop() + + self.reboot_sitl(force=True) + + def GuidedForceArm(self): + '''ensure Guided acts appropriately when force-armed''' + self.set_parameters({ + "EK3_SRC2_VELXY": 5, + "SIM_GPS1_ENABLE": 0, + }) + self.load_default_params_file("copter-optflow.parm") + self.reboot_sitl() + self.delay_sim_time(30) + self.change_mode('GUIDED') + self.arm_vehicle(force=True) + self.takeoff(20, mode='GUIDED') + location = self.offset_location_ne(self.sim_location(), metres_north=0, metres_east=-300) + self.progress("Ensure we don't move for 10 seconds") + tstart = self.get_sim_time() + startpos = self.sim_location_int() + while True: + now = self.get_sim_time_cached() + if now - tstart > 10: + break + self.send_set_position_target_global_int(int(location.lat*1e7), int(location.lng*1e7), 10) + dist = self.get_distance_int(startpos, self.sim_location_int()) + if dist > 10: + raise NotAchievedException("Wandered too far from start position") + self.delay_sim_time(1) + + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def EK3_OGN_HGT_MASK_climbing(self): + '''check combination of height bits doesn't cause climb''' + self.context_push() + self.set_parameters({ + 'EK3_OGN_HGT_MASK': 5, + }) + self.reboot_sitl() + + expected_alt = 10 + + self.change_mode('GUIDED') + self.wait_ready_to_arm() + current_alt = self.get_altitude() + + expected_alt_abs = current_alt + expected_alt + + self.takeoff(expected_alt, mode='GUIDED') + self.delay_sim_time(5) + + def check_altitude(mav, m): + m_type = m.get_type() + epsilon = 10 # in metres + if m_type == 'GPS_RAW_INT': + got_gps_alt = m.alt * 0.001 + if abs(expected_alt_abs - got_gps_alt) > epsilon: + raise NotAchievedException(f"Bad GPS altitude (got={got_gps_alt} want={expected_alt_abs})") + elif m_type == 'GLOBAL_POSITION_INT': + if abs(expected_alt - m.relative_alt * 0.001) > epsilon: + raise NotAchievedException("Bad canonical altitude") + + self.install_message_hook_context(check_altitude) + + self.delay_sim_time(1500) + + self.disarm_vehicle(force=True) + + self.context_pop() + self.reboot_sitl(force=True) + + def GuidedWeatherVane(self): + '''check Copter Guided mode weathervane option''' + self.set_parameters({ + 'SIM_WIND_SPD': 10, + 'SIM_WIND_DIR': 90, + 'WVANE_ENABLE': 1, + }) + self.takeoff(20, mode='GUIDED') + self.guided_achieve_heading(0) + + self.set_parameter("GUID_OPTIONS", 128) + self.wait_heading(90, timeout=60, minimum_duration=10) + self.do_RTL() + + def Clamp(self): + '''test Copter docking clamp''' + clamp_ch = 11 + self.set_parameters({ + "SIM_CLAMP_CH": clamp_ch, + }) + + self.takeoff(1, mode='LOITER') + + self.context_push() + self.context_collect('STATUSTEXT') + self.progress("Ensure can't take off with clamp in place") + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000) + self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True) + self.arm_vehicle() + self.set_rc(3, 2000) + self.wait_altitude(0, 5, minimum_duration=5, relative=True) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000) + self.wait_statustext("SITL: Clamp: released vehicle", check_context=True) + self.wait_altitude(5, 5000, minimum_duration=1, relative=True) + self.do_RTL() + self.set_rc(3, 1000) + self.change_mode('LOITER') + self.context_pop() + + self.progress("Same again for repeatability") + self.context_push() + self.context_collect('STATUSTEXT') + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000) + self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True) + self.arm_vehicle() + self.set_rc(3, 2000) + self.wait_altitude(0, 1, minimum_duration=5, relative=True) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000) + self.wait_statustext("SITL: Clamp: released vehicle", check_context=True) + self.wait_altitude(5, 5000, minimum_duration=1, relative=True) + self.do_RTL() + self.set_rc(3, 1000) + self.change_mode('LOITER') + self.context_pop() + + here = self.mav.location() + loc = self.offset_location_ne(here, 10, 0) + self.takeoff(5, mode='GUIDED') + self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL) + self.wait_location(loc, timeout=120) + self.land_and_disarm() + + # explicitly set home so we RTL to the right spot + self.set_home(here) + + self.context_push() + self.context_collect('STATUSTEXT') + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000) + self.wait_statustext("SITL: Clamp: missed vehicle", check_context=True) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000) + self.context_pop() + + self.takeoff(5, mode='GUIDED') + self.do_RTL() + + self.takeoff(5, mode='GUIDED') + self.land_and_disarm() + + self.context_push() + self.context_collect('STATUSTEXT') + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000) + self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True) + self.context_pop() + + self.reboot_sitl() # because we set home + + def GripperReleaseOnThrustLoss(self): + '''tests that gripper is released on thrust loss if option set''' + + self.context_push() + self.set_servo_gripper_parameters() + self.reboot_sitl() + + self.takeoff(30, mode='LOITER') + self.context_push() + self.context_collect('STATUSTEXT') + self.set_parameters({ + "SIM_ENGINE_FAIL": 1, + "SIM_ENGINE_MUL": 0.5, + "FLIGHT_OPTIONS": 4, + }) + + self.wait_statustext("Gripper Load Released", timeout=60) + self.context_pop() + + self.do_RTL() + self.context_pop() + self.reboot_sitl() + + def assert_home_position_not_set(self): + try: + self.poll_home_position() + except NotAchievedException: + return + + # if home.lng != 0: etc + + raise NotAchievedException("Home is set when it shouldn't be") + + def REQUIRE_POSITION_FOR_ARMING(self): + '''check FlightOption::REQUIRE_POSITION_FOR_ARMING works''' + self.context_push() + self.set_parameters({ + "SIM_GPS1_NUMSATS": 3, # EKF does not like < 6 + }) + self.reboot_sitl() + self.change_mode('STABILIZE') + self.wait_prearm_sys_status_healthy() + self.assert_home_position_not_set() + self.arm_vehicle() + self.disarm_vehicle() + self.change_mode('LOITER') + self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False) + + self.change_mode('STABILIZE') + self.set_parameters({ + "FLIGHT_OPTIONS": 8, + }) + self.assert_prearm_failure("Need Position Estimate", other_prearm_failures_fatal=False) + self.context_pop() + self.reboot_sitl() + + def AutoContinueOnRCFailsafe(self): + '''check LOITER when entered after RC failsafe is ignored in auto''' + self.set_parameters({ + "FS_OPTIONS": 1, # 1 is "RC continue if in auto" + }) + + self.upload_simple_relhome_mission([ + # N E U + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 40, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 120, 0, 10), + ]) + + self.takeoff(mode='LOITER') + self.set_rc(1, 1200) + self.delay_sim_time(1) # build up some pilot desired stuff + self.change_mode('AUTO') + self.wait_waypoint(2, 2) + self.set_parameters({ + 'SIM_RC_FAIL': 1, + }) +# self.set_rc(1, 1500) # note we are still in RC fail! + self.wait_waypoint(3, 3) + self.assert_mode_is('AUTO') + self.change_mode('LOITER') + self.wait_groundspeed(0, 0.1, minimum_duration=30, timeout=450) + self.do_RTL() + + def MissionRTLYawBehaviour(self): + '''check end-of-mission yaw behaviour''' + self.set_parameters({ + "AUTO_OPTIONS": 3, + }) + + self.start_subtest("behaviour with WP_YAW_BEHAVE set to next-waypoint-except-RTL") + self.upload_simple_relhome_mission([ + # N E U + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.change_mode('AUTO') + self.wait_ready_to_arm() + original_heading = self.get_heading() + if abs(original_heading) < 5: + raise NotAchievedException(f"Bad original heading {original_heading}") + self.arm_vehicle() + self.wait_current_waypoint(3) + self.wait_rtl_complete() + self.wait_disarmed() + if abs(self.get_heading()) > 5: + raise NotAchievedException("Should have yaw zero without option") + + # must change out of auto and back in again to reset state machine: + self.change_mode('LOITER') + self.change_mode('AUTO') + + self.start_subtest("behaviour with WP_YAW_BEHAVE set to next-waypoint") + self.upload_simple_relhome_mission([ + # N E U + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 20, 20), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.set_parameters({ + "WP_YAW_BEHAVIOR": 1, # look at next waypoint (including in RTL) + }) + self.change_mode('AUTO') + self.wait_ready_to_arm() + original_heading = self.get_heading() + if abs(original_heading) > 1: + raise NotAchievedException("Bad original heading") + self.arm_vehicle() + self.wait_current_waypoint(3) + self.wait_rtl_complete() + self.wait_disarmed() + new_heading = self.get_heading() + if abs(new_heading - original_heading) > 5: + raise NotAchievedException(f"Should return to original heading want={original_heading} got={new_heading}") + + def BatteryInternalUseOnly(self): + '''batteries marked as internal use only should not appear over mavlink''' + self.set_parameters({ + "BATT_MONITOR": 4, # 4 is analog volt+curr + "BATT2_MONITOR": 4, + }) + self.reboot_sitl() + self.wait_message_field_values('BATTERY_STATUS', { + "id": 0, + }) + self.wait_message_field_values('BATTERY_STATUS', { + "id": 1, + }) + self.progress("Making battery private") + self.set_parameters({ + "BATT_OPTIONS": 256, + }) + self.wait_message_field_values('BATTERY_STATUS', { + "id": 1, + }) + for i in range(10): + self.assert_received_message_field_values('BATTERY_STATUS', { + "id": 1 + }) + + def MAV_CMD_MISSION_START_p1_p2(self): + '''make sure we deny MAV_CMD_MISSION_START if either p1 or p2 non-zero''' + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20), + ]) + self.set_parameters({ + "AUTO_OPTIONS": 3, + }) + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.run_cmd( + mavutil.mavlink.MAV_CMD_MISSION_START, + p1=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + + self.run_cmd( + mavutil.mavlink.MAV_CMD_MISSION_START, + p2=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + + self.run_cmd( + mavutil.mavlink.MAV_CMD_MISSION_START, + p1=1, + p2=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + + def ScriptingAHRSSource(self): + '''test ahrs-source.lua script''' + self.install_example_script_context("ahrs-source.lua") + self.set_parameters({ + "RC10_OPTION": 90, + "SCR_ENABLE": 1, + "SCR_USER1": 10, # something else + "SCR_USER2": 10, # GPS something + "SCR_USER3": 0.2, # ExtNav innovation + }) + self.set_rc(10, 2000) + self.reboot_sitl() + self.context_collect('STATUSTEXT') + self.set_rc(10, 1000) + self.wait_statustext('Using EKF Source Set 1', check_context=True) + self.set_rc(10, 1500) + self.wait_statustext('Using EKF Source Set 2', check_context=True) + self.set_rc(10, 2000) + self.wait_statustext('Using EKF Source Set 3', check_context=True) + + def CommonOrigin(self): + """Test common origin between EKF2 and EKF3""" + self.context_push() + + # start on EKF2 + self.set_parameters({ + 'AHRS_EKF_TYPE': 2, + 'EK2_ENABLE': 1, + 'EK3_CHECK_SCALE': 1, # make EK3 slow to get origin + }) + self.reboot_sitl() + + self.context_collect('STATUSTEXT') + + self.wait_statustext("EKF2 IMU0 origin set", timeout=60, check_context=True) + self.wait_statustext("EKF2 IMU0 is using GPS", timeout=60, check_context=True) + self.wait_statustext("EKF2 active", timeout=60, check_context=True) + + self.context_collect('GPS_GLOBAL_ORIGIN') + + # get EKF2 origin + self.run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION) + ek2_origin = self.assert_receive_message('GPS_GLOBAL_ORIGIN', check_context=True) + + # switch to EKF3 + self.set_parameters({ + 'SIM_GPS1_GLTCH_X' : 0.001, # about 100m + 'EK3_CHECK_SCALE' : 100, + 'AHRS_EKF_TYPE' : 3}) + + self.wait_statustext("EKF3 IMU0 is using GPS", timeout=60, check_context=True) + self.wait_statustext("EKF3 active", timeout=60, check_context=True) + + self.run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION) + ek3_origin = self.assert_receive_message('GPS_GLOBAL_ORIGIN', check_context=True) + + self.progress("Checking origins") + if ek2_origin.time_usec == ek3_origin.time_usec: + raise NotAchievedException("Did not get a new GPS_GLOBAL_ORIGIN message") + + print(ek2_origin, ek3_origin) + + if (ek2_origin.latitude != ek3_origin.latitude or + ek2_origin.longitude != ek3_origin.longitude or + ek2_origin.altitude != ek3_origin.altitude): + raise NotAchievedException("Did not get matching EK2 and EK3 origins") + + self.context_pop() + + # restart GPS driver + self.reboot_sitl() + + def tests2b(self): # this block currently around 9.5mins here + '''return list of all tests''' + ret = ([ + self.MotorVibration, + Test(self.DynamicNotches, attempts=4), + self.PositionWhenGPSIsZero, + self.DynamicRpmNotches, # Do not add attempts to this - failure is sign of a bug + self.PIDNotches, + self.StaticNotches, + self.RefindGPS, + Test(self.GyroFFT, attempts=1, speedup=8), + Test(self.GyroFFTHarmonic, attempts=4, speedup=8), + Test(self.GyroFFTAverage, attempts=1, speedup=8), + Test(self.GyroFFTContinuousAveraging, attempts=4, speedup=8), + self.GyroFFTPostFilter, + self.GyroFFTMotorNoiseCheck, + self.CompassReordering, + self.CRSF, + self.MotorTest, + self.AltEstimation, + self.EKFSource, + self.GSF, + self.GSF_reset, + self.AP_Avoidance, + self.SMART_RTL, + self.SMART_RTL_EnterLeave, + self.RTL_TO_RALLY, + self.FlyEachFrame, + self.GPSBlending, + self.GPSWeightedBlending, + self.GPSBlendingLog, + self.GPSBlendingAffinity, + 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.MISSION_START, + self.AUTO_LAND_TO_BRAKE, + self.WPNAV_SPEED, + self.WPNAV_SPEED_UP, + self.WPNAV_SPEED_DN, self.DO_WINCH, self.SensorErrorFlags, self.GPSForYaw, @@ -10915,16 +12209,20 @@ def tests2b(self): # this block currently around 9.5mins here self.WatchAlts, self.GuidedEKFLaneChange, self.Sprayer, + self.AutoContinueOnRCFailsafe, self.EK3_RNG_USE_HGT, self.TerrainDBPreArm, self.ThrottleGainBoost, self.ScriptMountPOI, + self.ScriptCopterPosOffsets, + self.MountSolo, self.FlyMissionTwice, self.FlyMissionTwiceWithReset, self.MissionIndexValidity, self.InvalidJumpTags, self.IMUConsistency, self.AHRSTrimLand, + self.IBus, self.GuidedYawRate, self.NoArmWithoutMissionItems, self.DO_CHANGE_SPEED_in_guided, @@ -10944,6 +12242,22 @@ def tests2b(self): # this block currently around 9.5mins here self.CameraLogMessages, self.LoiterToGuidedHomeVSOrigin, self.GuidedModeThrust, + self.CompassMot, + self.AutoRTL, + self.EK3_OGN_HGT_MASK_climbing, + self.EK3_OGN_HGT_MASK, + self.FarOrigin, + self.GuidedForceArm, + self.GuidedWeatherVane, + self.Clamp, + self.GripperReleaseOnThrustLoss, + self.REQUIRE_POSITION_FOR_ARMING, + self.LoggingFormat, + self.MissionRTLYawBehaviour, + self.BatteryInternalUseOnly, + self.MAV_CMD_MISSION_START_p1_p2, + self.ScriptingAHRSSource, + self.CommonOrigin, ]) return ret @@ -10954,6 +12268,57 @@ def testcan(self): ]) return ret + def BattCANSplitAuxInfo(self): + '''test CAN battery periphs''' + self.start_subtest("Swap UAVCAN backend at runtime") + self.set_parameters({ + "CAN_P1_DRIVER": 1, + "BATT_MONITOR": 4, # 4 is ananlog volt+curr + "BATT2_MONITOR": 8, # 8 is UAVCAN_BatteryInfo + "BATT_SERIAL_NUM": 0, + "BATT2_SERIAL_NUM": 0, + "BATT_OPTIONS": 128, # allow split auxinfo + "BATT2_OPTIONS": 128, # allow split auxinfo + }) + self.reboot_sitl() + self.delay_sim_time(2) + self.set_parameters({ + "BATT_MONITOR": 8, # 8 is UAVCAN_BatteryInfo + "BATT2_MONITOR": 4, # 8 is UAVCAN_BatteryInfo + }) + self.delay_sim_time(2) + self.set_parameters({ + "BATT_MONITOR": 4, # 8 is UAVCAN_BatteryInfo + "BATT2_MONITOR": 8, # 8 is UAVCAN_BatteryInfo + }) + self.delay_sim_time(2) + self.set_parameters({ + "BATT_MONITOR": 8, # 8 is UAVCAN_BatteryInfo + "BATT2_MONITOR": 4, # 8 is UAVCAN_BatteryInfo + }) + self.delay_sim_time(2) + + def BattCANReplaceRuntime(self): + '''test CAN battery periphs''' + self.start_subtest("Replace UAVCAN backend at runtime") + self.set_parameters({ + "CAN_P1_DRIVER": 1, + "BATT_MONITOR": 11, # 4 is ananlog volt+curr + }) + self.reboot_sitl() + self.delay_sim_time(2) + self.set_parameters({ + "BATT_MONITOR": 8, # 4 is UAVCAN batterinfo + }) + self.delay_sim_time(2) + + def testcanbatt(self): + ret = ([ + self.BattCANReplaceRuntime, + self.BattCANSplitAuxInfo, + ]) + return ret + def tests(self): ret = [] ret.extend(self.tests1a()) @@ -10968,13 +12333,13 @@ def tests(self): def disabled_tests(self): return { "Parachute": "See https://github.com/ArduPilot/ardupilot/issues/4702", - "HorizontalAvoidFence": "See https://github.com/ArduPilot/ardupilot/issues/11525", "AltEstimation": "See https://github.com/ArduPilot/ardupilot/issues/15191", "GroundEffectCompensation_takeOffExpected": "Flapping", "GroundEffectCompensation_touchDownExpected": "Flapping", "FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561", "GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion", - "GuidedModeThrust": "land detector raises internal error as we're not saying we're about to take off but just did", + "CompassMot": "Cuases an arithmetic exception in the EKF", + "SMART_RTL_EnterLeave": "Causes a panic", } @@ -11017,3 +12382,9 @@ class AutoTestCAN(AutoTestCopter): def tests(self): return self.testcan() + + +class AutoTestBattCAN(AutoTestCopter): + + def tests(self): + return self.testcanbatt() diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index e0382402528d0f..0ce13e5c3e3275 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -5,10 +5,10 @@ ''' from __future__ import print_function +import copy import math import os import signal -import time from pymavlink import quaternion from pymavlink import mavutil @@ -174,7 +174,7 @@ def fly_left_circuit(self): def fly_RTL(self): """Fly to home.""" self.progress("Flying home in RTL") - target_loc = self.homeloc + target_loc = self.home_position_as_mav_location() target_loc.alt += 100 self.change_mode('RTL') self.wait_location(target_loc, @@ -186,7 +186,7 @@ def fly_RTL(self): 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.set_parameter("SIM_GPS_DISABLE", 1) + self.set_parameter("SIM_GPS1_ENABLE", 0) self.context_collect("STATUSTEXT") tstart = self.get_sim_time() success = False @@ -202,7 +202,7 @@ def NeedEKFToArm(self): except AutoTestTimeoutException: pass - self.set_parameter("SIM_GPS_DISABLE", 0) + self.set_parameter("SIM_GPS1_ENABLE", 1) self.wait_ready_to_arm() def fly_LOITER(self, num_circles=4): @@ -276,8 +276,10 @@ def wait_level_flight(self, accuracy=5, timeout=30): return raise NotAchievedException("Failed to attain level flight") - def change_altitude(self, altitude, accuracy=30): + def change_altitude(self, altitude, accuracy=30, relative=False): """Get to a given altitude.""" + if relative: + altitude += self.home_position_as_mav_location().alt self.change_mode('FBWA') alt_error = self.mav.messages['VFR_HUD'].alt - altitude if alt_error > 0: @@ -294,7 +296,7 @@ def axial_left_roll(self, count=1): """Fly a left axial roll.""" # full throttle! self.set_rc(3, 2000) - self.change_altitude(self.homeloc.alt+300) + self.change_altitude(300, relative=True) # fly the roll in manual self.change_mode('MANUAL') @@ -321,7 +323,7 @@ def inside_loop(self, count=1): """Fly a inside loop.""" # full throttle! self.set_rc(3, 2000) - self.change_altitude(self.homeloc.alt+300) + self.change_altitude(300, relative=True) # fly the loop in manual self.change_mode('MANUAL') @@ -433,7 +435,7 @@ def test_stabilize(self, count=1): # full throttle! self.set_rc(3, 2000) self.set_rc(2, 1300) - self.change_altitude(self.homeloc.alt+300) + self.change_altitude(300, relative=True) self.set_rc(2, 1500) self.change_mode('STABILIZE') @@ -459,7 +461,7 @@ def test_acro(self, count=1): # full throttle! self.set_rc(3, 2000) self.set_rc(2, 1300) - self.change_altitude(self.homeloc.alt+300) + self.change_altitude(300, relative=True) self.set_rc(2, 1500) self.change_mode('ACRO') @@ -916,7 +918,8 @@ def DO_CHANGE_SPEED_mavlink(self, run_cmd_method): mavutil.mavlink.MAV_CMD_DO_REPOSITION, p5=12345, # lat* 1e7 p6=12345, # lon* 1e7 - p7=100 # alt + p7=100, # alt + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, ) self.delay_sim_time(10) self.progress("Ensuring initial speed is known and relatively constant") @@ -1032,95 +1035,61 @@ def fly_home_land_and_disarm(self, timeout=120): def TestFlaps(self): """Test flaps functionality.""" filename = "flaps.txt" - self.context_push() - ex = None - try: + flaps_ch = 5 + flaps_ch_min = 1000 + flaps_ch_trim = 1500 + flaps_ch_max = 2000 - flaps_ch = 5 - flaps_ch_min = 1000 - flaps_ch_trim = 1500 - flaps_ch_max = 2000 + servo_ch = 5 + servo_ch_min = 1200 + servo_ch_trim = 1300 + servo_ch_max = 1800 - servo_ch = 5 - servo_ch_min = 1200 - servo_ch_trim = 1300 - servo_ch_max = 1800 + self.set_parameters({ + "SERVO%u_FUNCTION" % servo_ch: 3, # flapsauto + "RC%u_OPTION" % flaps_ch: 208, # Flaps RCx_OPTION + "LAND_FLAP_PERCNT": 50, + "LOG_DISARMED": 1, + "RTL_AUTOLAND": 1, - self.set_parameters({ - "SERVO%u_FUNCTION" % servo_ch: 3, # flapsauto - "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, - "RC%u_TRIM" % flaps_ch: flaps_ch_trim, - - "SERVO%u_MIN" % servo_ch: servo_ch_min, - "SERVO%u_MAX" % servo_ch: servo_ch_max, - "SERVO%u_TRIM" % servo_ch: servo_ch_trim, - }) + "RC%u_MIN" % flaps_ch: flaps_ch_min, + "RC%u_MAX" % flaps_ch: flaps_ch_max, + "RC%u_TRIM" % flaps_ch: flaps_ch_trim, - self.progress("check flaps are not deployed") - self.set_rc(flaps_ch, flaps_ch_min) - self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=3) - self.progress("deploy the flaps") - self.set_rc(flaps_ch, flaps_ch_max) - tstart = self.get_sim_time() - self.wait_servo_channel_value(servo_ch, servo_ch_max) - tstop = self.get_sim_time_cached() - delta_time = tstop - tstart - delta_time_min = 0.5 - delta_time_max = 1.5 - if delta_time < delta_time_min or delta_time > delta_time_max: - raise NotAchievedException(( - "Flaps Slew not working (%f seconds)" % (delta_time,))) - self.progress("undeploy flaps") - self.set_rc(flaps_ch, flaps_ch_min) - self.wait_servo_channel_value(servo_ch, servo_ch_min) - - self.progress("Flying mission %s" % filename) - self.load_mission(filename) - self.set_current_waypoint(1) - self.change_mode('AUTO') - self.wait_ready_to_arm() - self.arm_vehicle() - last_mission_current_msg = 0 - last_seq = None - while self.armed(): - m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True) - time_delta = (self.get_sim_time_cached() - - last_mission_current_msg) - if (time_delta > 1 or m.seq != last_seq): - dist = None - x = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None) - if x is not None: - dist = x.wp_dist - self.progress("MISSION_CURRENT.seq=%u (dist=%s)" % - (m.seq, str(dist))) - last_mission_current_msg = self.get_sim_time_cached() - last_seq = m.seq - # flaps should undeploy at the end - self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=30) - - # do a short flight in FBWA, watching for flaps - # self.mavproxy.send('switch 4\n') - # self.wait_mode('FBWA') - # self.delay_sim_time(10) - # self.mavproxy.send('switch 6\n') - # self.wait_mode('MANUAL') - # self.delay_sim_time(10) - - self.progress("Flaps OK") - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - if ex: - if self.armed(): - self.disarm_vehicle() - raise ex + "SERVO%u_MIN" % servo_ch: servo_ch_min, + "SERVO%u_MAX" % servo_ch: servo_ch_max, + "SERVO%u_TRIM" % servo_ch: servo_ch_trim, + }) + + self.progress("check flaps are not deployed") + self.set_rc(flaps_ch, flaps_ch_min) + self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=3) + self.progress("deploy the flaps") + self.set_rc(flaps_ch, flaps_ch_max) + tstart = self.get_sim_time() + self.wait_servo_channel_value(servo_ch, servo_ch_max) + tstop = self.get_sim_time_cached() + delta_time = tstop - tstart + delta_time_min = 0.5 + delta_time_max = 1.5 + if delta_time < delta_time_min or delta_time > delta_time_max: + raise NotAchievedException(( + "Flaps Slew not working (%f seconds)" % (delta_time,))) + self.progress("undeploy flaps") + self.set_rc(flaps_ch, flaps_ch_min) + self.wait_servo_channel_value(servo_ch, servo_ch_min) + + self.progress("Flying mission %s" % filename) + self.load_mission(filename) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + # flaps should deploy for landing (RC input value used for position?!) + self.wait_servo_channel_value(servo_ch, flaps_ch_trim, timeout=300) + # flaps should undeploy at the end + self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=30) + + self.progress("Flaps OK") def TestRCRelay(self): '''Test Relay RC Channel Option''' @@ -1285,32 +1254,25 @@ def ThrottleFailsafe(self): self.progress("Ensure long failsafe can trigger when short failsafe disabled") self.context_push() self.context_collect("STATUSTEXT") - ex = None - try: - self.set_parameters({ - "FS_SHORT_ACTN": 3, # 3 means disabled - "SIM_RC_FAIL": 1, - }) - self.wait_statustext("Long failsafe on", check_context=True) - self.wait_mode("RTL") + self.set_parameters({ + "FS_SHORT_ACTN": 3, # 3 means disabled + "SIM_RC_FAIL": 1, + }) + 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 Failsafe Cleared", check_context=True) - self.change_mode("MANUAL") + self.set_parameter("SIM_RC_FAIL", 0) + self.wait_text("Long Failsafe Cleared", check_context=True) + self.change_mode("MANUAL") - self.progress("Trying again with THR_FS_VALUE") - self.set_parameters({ - "THR_FS_VALUE": 960, - "SIM_RC_FAIL": 2, - }) - self.wait_statustext("Long Failsafe on", check_context=True) - self.wait_mode("RTL") - except Exception as e: - self.print_exception_caught(e) - ex = e + self.progress("Trying again with THR_FS_VALUE") + self.set_parameters({ + "THR_FS_VALUE": 960, + "SIM_RC_FAIL": 2, + }) + self.wait_statustext("Long Failsafe on", check_context=True) + self.wait_mode("RTL") self.context_pop() - if ex is not None: - raise ex self.start_subtest("Not use RC throttle input when THR_FAILSAFE==2") self.takeoff(100) @@ -1433,24 +1395,15 @@ def GCSFailsafe(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') - self.wait_ready_to_arm() - self.arm_vehicle() - self.wait_statustext("Gripper Grabbed", timeout=60) - self.wait_statustext("Gripper Released", timeout=60) - self.wait_statustext("Auto disarmed", timeout=60) - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - if ex is not None: - raise ex + self.set_parameter("RTL_AUTOLAND", 1) + self.load_mission("plane-gripper-mission.txt") + self.set_current_waypoint(1) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_statustext("Gripper Grabbed", timeout=60) + self.wait_statustext("Gripper Released", timeout=60) + self.wait_statustext("Auto disarmed", timeout=60) def assert_fence_sys_status(self, present, enabled, health): self.delay_sim_time(1) @@ -1539,220 +1492,166 @@ def MODE_SWITCH_RESET(self): def FenceStatic(self): '''Test Basic Fence Functionality''' - ex = None - try: - self.progress("Checking for bizarre healthy-when-not-present-or-enabled") - self.set_parameter("FENCE_TYPE", 4) # Start by only setting polygon fences, otherwise fence will report present - self.assert_fence_sys_status(False, False, True) - self.load_fence("CMAC-fence.txt") - m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) - if m is not None: - raise NotAchievedException("Got FENCE_STATUS unexpectedly") - self.set_parameter("FENCE_ACTION", 0) # report only - self.assert_fence_sys_status(True, False, True) - self.set_parameter("FENCE_ACTION", 1) # RTL - self.assert_fence_sys_status(True, False, True) - self.do_fence_enable() - self.assert_fence_sys_status(True, True, True) - m = self.assert_receive_message('FENCE_STATUS', timeout=2) - if m.breach_status: - raise NotAchievedException("Breached fence unexpectedly (%u)" % - (m.breach_status)) - self.do_fence_disable() - self.assert_fence_sys_status(True, False, True) - self.set_parameter("FENCE_ACTION", 1) - self.assert_fence_sys_status(True, False, True) - self.set_parameter("FENCE_ACTION", 0) - self.assert_fence_sys_status(True, False, True) - self.clear_fence() - if self.get_parameter("FENCE_TOTAL") != 0: - raise NotAchievedException("Expected zero points remaining") - self.assert_fence_sys_status(False, False, True) - self.progress("Trying to enable fence with no points") - self.do_fence_enable(want_result=mavutil.mavlink.MAV_RESULT_FAILED) - - # test a rather unfortunate behaviour: - self.progress("Killing a live fence with fence-clear") - self.load_fence("CMAC-fence.txt") - self.set_parameter("FENCE_ACTION", 1) # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4 - self.do_fence_enable() - self.assert_fence_sys_status(True, True, True) - self.clear_fence() - self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, False, False, True) - if self.get_parameter("FENCE_TOTAL") != 0: - raise NotAchievedException("Expected zero points remaining") - self.assert_fence_sys_status(False, False, True) - self.do_fence_disable() + self.progress("Checking for bizarre healthy-when-not-present-or-enabled") + self.set_parameter("FENCE_TYPE", 4) # Start by only setting polygon fences, otherwise fence will report present + self.assert_fence_sys_status(False, False, True) + self.load_fence("CMAC-fence.txt") + m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) + if m is not None: + raise NotAchievedException("Got FENCE_STATUS unexpectedly") + self.set_parameter("FENCE_ACTION", 0) # report only + self.assert_fence_sys_status(True, False, True) + self.set_parameter("FENCE_ACTION", 1) # RTL + self.assert_fence_sys_status(True, False, True) + self.do_fence_enable() + self.assert_fence_sys_status(True, True, True) + m = self.assert_receive_message('FENCE_STATUS', timeout=2) + if m.breach_status: + raise NotAchievedException("Breached fence unexpectedly (%u)" % + (m.breach_status)) + self.do_fence_disable() + self.assert_fence_sys_status(True, False, True) + self.set_parameter("FENCE_ACTION", 1) + self.assert_fence_sys_status(True, False, True) + self.set_parameter("FENCE_ACTION", 0) + self.assert_fence_sys_status(True, False, True) + self.clear_fence() + if self.get_parameter("FENCE_TOTAL") != 0: + raise NotAchievedException("Expected zero points remaining") + self.assert_fence_sys_status(False, False, True) + self.progress("Trying to enable fence with no points") + self.do_fence_enable(want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # test a rather unfortunate behaviour: + self.progress("Killing a live fence with fence-clear") + self.load_fence("CMAC-fence.txt") + self.set_parameter("FENCE_ACTION", 1) # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4 + self.do_fence_enable() + self.assert_fence_sys_status(True, True, True) + self.clear_fence() + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, False, False, True) + if self.get_parameter("FENCE_TOTAL") != 0: + raise NotAchievedException("Expected zero points remaining") + self.assert_fence_sys_status(False, False, True) + self.do_fence_disable() - # ensure that a fence is present if it is tin can, min alt or max alt - self.progress("Test other fence types (tin-can, min alt, max alt") - self.set_parameter("FENCE_TYPE", 1) # max alt - self.assert_fence_sys_status(True, False, True) - self.set_parameter("FENCE_TYPE", 8) # min alt - self.assert_fence_sys_status(True, False, True) - self.set_parameter("FENCE_TYPE", 2) # tin can - self.assert_fence_sys_status(True, False, True) - - # Test cannot arm if outside of fence and fence is enabled - self.progress("Test Arming while vehicle below FENCE_ALT_MIN") - default_fence_alt_min = self.get_parameter("FENCE_ALT_MIN") - self.set_parameter("FENCE_ALT_MIN", 50) - self.set_parameter("FENCE_TYPE", 8) # Enables minimum altitude breaches - self.do_fence_enable() - self.delay_sim_time(2) # Allow breach to propagate - self.assert_fence_enabled() + # ensure that a fence is present if it is tin can, min alt or max alt + self.progress("Test other fence types (tin-can, min alt, max alt") + self.set_parameter("FENCE_TYPE", 1) # max alt + self.assert_fence_sys_status(True, False, True) + self.set_parameter("FENCE_TYPE", 8) # min alt + self.assert_fence_sys_status(True, False, True) + self.set_parameter("FENCE_TYPE", 2) # tin can + self.assert_fence_sys_status(True, False, True) + + # Test cannot arm if outside of fence and fence is enabled + self.progress("Test Arming while vehicle below FENCE_ALT_MIN") + default_fence_alt_min = self.get_parameter("FENCE_ALT_MIN") + self.set_parameter("FENCE_ALT_MIN", 50) + self.set_parameter("FENCE_TYPE", 8) # Enables minimum altitude breaches + self.do_fence_enable() + self.delay_sim_time(2) # Allow breach to propagate + self.assert_fence_enabled() - self.try_arm(False, "vehicle outside fence") - self.do_fence_disable() - self.set_parameter("FENCE_ALT_MIN", default_fence_alt_min) + self.try_arm(False, "Vehicle breaching Min Alt fence") + self.do_fence_disable() + self.set_parameter("FENCE_ALT_MIN", default_fence_alt_min) - # Test arming outside inclusion zone - self.progress("Test arming while vehicle outside of inclusion zone") - self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types - locs = [ + # Test arming outside inclusion zone + self.progress("Test arming while Vehicle breaching of inclusion zone") + self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types + self.upload_fences_from_locations([( + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ mavutil.location(1.000, 1.000, 0, 0), mavutil.location(1.000, 1.001, 0, 0), mavutil.location(1.001, 1.001, 0, 0), mavutil.location(1.001, 1.000, 0, 0) ] - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - locs - ] - ) - self.delay_sim_time(10) # let fence check run so it loads-from-eeprom - self.do_fence_enable() - self.assert_fence_enabled() - self.delay_sim_time(2) # Allow breach to propagate - self.try_arm(False, "vehicle outside fence") - self.do_fence_disable() - self.clear_fence() - - self.progress("Test arming while vehicle inside exclusion zone") - self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types - home_loc = self.mav.location() - locs = [ - mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0), - mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0), - mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0), - mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0), - ] - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - locs - ] - ) - self.delay_sim_time(10) # let fence check run so it loads-from-eeprom - self.do_fence_enable() - self.assert_fence_enabled() - self.delay_sim_time(2) # Allow breach to propagate - self.try_arm(False, "vehicle outside fence") - self.do_fence_disable() - self.clear_fence() - - except Exception as e: - self.print_exception_caught(e) - ex = e + )]) + self.delay_sim_time(10) # let fence check run so it loads-from-eeprom + self.do_fence_enable() + self.assert_fence_enabled() + self.delay_sim_time(2) # Allow breach to propagate + self.try_arm(False, "Vehicle breaching Polygon fence") + self.do_fence_disable() self.clear_fence() - if ex is not None: - raise ex - - def test_fence_breach_circle_at(self, loc, disable_on_breach=False): - ex = None - try: - self.load_fence("CMAC-fence.txt") - want_radius = 100 - # when ArduPlane is fixed, remove this fudge factor - REALLY_BAD_FUDGE_FACTOR = 1.16 - expected_radius = REALLY_BAD_FUDGE_FACTOR * want_radius - self.set_parameters({ - "RTL_RADIUS": want_radius, - "NAVL1_LIM_BANK": 60, - "FENCE_ACTION": 1, # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4 - }) - self.wait_ready_to_arm() # need an origin to load fence - - self.do_fence_enable() - self.assert_fence_sys_status(True, True, True) + self.progress("Test arming while vehicle inside exclusion zone") + self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types + home_loc = self.mav.location() + locs = [ + mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0), + mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0), + mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0), + mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0), + ] + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, locs), + ]) + self.delay_sim_time(10) # let fence check run so it loads-from-eeprom + self.do_fence_enable() + self.assert_fence_enabled() + self.delay_sim_time(2) # Allow breach to propagate + self.try_arm(False, "Vehicle breaching Polygon fence") + self.do_fence_disable() - self.takeoff(alt=45, alt_max=300) + def test_fence_breach_circle_at(self, loc, disable_on_breach=False): + self.load_fence("CMAC-fence.txt") + want_radius = 100 + # when ArduPlane is fixed, remove this fudge factor + REALLY_BAD_FUDGE_FACTOR = 1.16 + expected_radius = REALLY_BAD_FUDGE_FACTOR * want_radius + self.set_parameters({ + "RTL_RADIUS": want_radius, + "NAVL1_LIM_BANK": 60, + "FENCE_ACTION": 1, # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4 + }) - tstart = self.get_sim_time() - while True: - if self.get_sim_time() - tstart > 30: - raise NotAchievedException("Did not breach fence") - m = self.assert_receive_message('FENCE_STATUS', timeout=2) - if m.breach_status == 0: - continue + self.wait_ready_to_arm() # need an origin to load fence - # we've breached; check our state; - if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY: - raise NotAchievedException("Unexpected breach type %u" % - (m.breach_type,)) - if m.breach_count == 0: - raise NotAchievedException("Unexpected breach count %u" % - (m.breach_count,)) - self.assert_fence_sys_status(True, True, False) - break + self.do_fence_enable() + self.assert_fence_sys_status(True, True, True) - if disable_on_breach: - self.do_fence_disable() + self.takeoff(alt=45, alt_max=300) - self.wait_circling_point_with_radius(loc, expected_radius) + tstart = self.get_sim_time() + while True: + if self.get_sim_time() - tstart > 30: + raise NotAchievedException("Did not breach fence") + m = self.assert_receive_message('FENCE_STATUS', timeout=2) + if m.breach_status == 0: + continue - self.disarm_vehicle(force=True) - self.reboot_sitl() + # we've breached; check our state; + if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY: + raise NotAchievedException("Unexpected breach type %u" % + (m.breach_type,)) + if m.breach_count == 0: + raise NotAchievedException("Unexpected breach count %u" % + (m.breach_count,)) + self.assert_fence_sys_status(True, True, False) + break - except Exception as e: - self.print_exception_caught(e) - ex = e - self.clear_fence() - if ex is not None: - raise ex + self.wait_circling_point_with_radius(loc, expected_radius) + self.do_fence_disable() + self.disarm_vehicle(force=True) + self.reboot_sitl() 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) + self.test_fence_breach_circle_at(self.home_position_as_mav_location()) def FenceRTLRally(self): '''Test Fence RTL Rally''' - ex = None - target_system = 1 - target_component = 1 - try: - self.progress("Testing FENCE_ACTION_RTL with rally point") + self.progress("Testing FENCE_ACTION_RTL with rally point") - self.wait_ready_to_arm() - loc = self.home_relative_loc_ne(50, -50) - - self.set_parameter("RALLY_TOTAL", 1) - self.mav.mav.rally_point_send(target_system, - target_component, - 0, # sequence number - 1, # total count - int(loc.lat * 1e7), - int(loc.lng * 1e7), - 15, - 0, # "break" alt?! - 0, # "land dir" - 0) # flags - self.delay_sim_time(1) - if self.mavproxy is not None: - self.mavproxy.send("rally list\n") - self.test_fence_breach_circle_at(loc) - except Exception as e: - self.print_exception_caught(e) - ex = e - self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY) - if ex is not None: - raise ex + self.wait_ready_to_arm() + loc = self.home_relative_loc_ne(50, -50) + self.upload_rally_points_from_locations([loc]) + self.test_fence_breach_circle_at(loc) def FenceRetRally(self): """ Tests the FENCE_RET_RALLY flag, either returning to fence return point, @@ -1762,7 +1661,6 @@ def FenceRetRally(self): self.progress("Testing FENCE_ACTION_RTL with fence rally point") self.wait_ready_to_arm() - self.homeloc = self.mav.location() # Grab a location for fence return point, and upload it. fence_loc = self.home_position_as_mav_location() @@ -1792,18 +1690,7 @@ def FenceRetRally(self): # Grab a location for rally point, and upload it. rally_loc = self.home_relative_loc_ne(-50, 50) - self.set_parameter("RALLY_TOTAL", 1) - self.mav.mav.rally_point_send(target_system, - target_component, - 0, # sequence number - 1, # total count - int(rally_loc.lat * 1e7), - int(rally_loc.lng * 1e7), - 15, - 0, # "break" alt?! - 0, # "land dir" - 0) # flags - self.delay_sim_time(1) + self.upload_rally_points_from_locations([rally_loc]) return_radius = 100 return_alt = 80 @@ -1829,7 +1716,7 @@ def FenceRetRally(self): 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.change_altitude(30, relative=True) self.set_parameters({ "FENCE_RET_RALLY": 0, "FENCE_ALT_MIN": 60, @@ -1875,12 +1762,12 @@ def terrain_wait_path(loc1, loc2, steps): self.progress("Got required terrain") self.wait_ready_to_arm() - self.homeloc = self.mav.location() + homeloc = self.mav.location() - guided_loc = mavutil.location(-35.39723762, 149.07284612, self.homeloc.alt+99.0, 0) - rally_loc = mavutil.location(-35.3654952000, 149.1558698000, self.homeloc.alt+100, 0) + guided_loc = mavutil.location(-35.39723762, 149.07284612, homeloc.alt+99.0, 0) + rally_loc = mavutil.location(-35.3654952000, 149.1558698000, homeloc.alt+100, 0) - terrain_wait_path(self.homeloc, rally_loc, 10) + terrain_wait_path(homeloc, rally_loc, 10) # set a rally point to the west of home self.upload_rally_points_from_locations([rally_loc]) @@ -1896,7 +1783,7 @@ def terrain_wait_path(loc1, loc2, steps): self.install_message_hook_context(terrain_following_above_80m) self.change_mode("GUIDED") - self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) + self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) self.progress("Flying to guided location") self.wait_location( guided_loc, @@ -1919,7 +1806,7 @@ def terrain_wait_path(loc1, loc2, steps): # Fly back to guided location self.change_mode("GUIDED") - self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) + self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) self.progress("Flying to back to guided location") # Disable terrain following and re-load rally point with relative to terrain altitude @@ -2007,20 +1894,8 @@ def run_subtest(self, desc, func): def fly_ahrs2_test(self): '''check secondary estimator is looking OK''' - ahrs2 = self.mav.recv_match(type='AHRS2', blocking=True, timeout=1) - if ahrs2 is None: - raise NotAchievedException("Did not receive AHRS2 message") - self.progress("AHRS2: %s" % str(ahrs2)) - - # check location - gpi = self.mav.recv_match( - type='GLOBAL_POSITION_INT', - blocking=True, - timeout=5 - ) - if gpi is None: - raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message") - self.progress("GPI: %s" % str(gpi)) + ahrs2 = self.assert_receive_message('AHRS2', verbose=1) + gpi = self.assert_receive_message('GLOBAL_POSITION_INT', verbose=1) if self.get_distance_int(gpi, ahrs2) > 10: raise NotAchievedException("Secondary location looks bad") @@ -2033,10 +1908,6 @@ def MainFlight(self): self.progress("Asserting we do support transfer of fence via mission item protocol") self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) - # grab home position: - self.mav.recv_match(type='HOME_POSITION', blocking=True) - self.homeloc = self.mav.location() - self.run_subtest("Takeoff", self.takeoff) self.run_subtest("Set Attitude Target", self.set_attitude_target) @@ -2136,36 +2007,18 @@ def AIRSPEED_AUTOCAL(self): self.fly_home_land_and_disarm() def deadreckoning_main(self, disable_airspeed_sensor=False): + self.context_push() + self.set_parameter("EK3_OPTIONS", 1) + self.set_parameter("AHRS_OPTIONS", 3) + self.set_parameter("LOG_REPLAY", 1) self.reboot_sitl() self.wait_ready_to_arm() - self.gpi = None - self.simstate = None - self.last_print = 0 - self.max_divergence = 0 - - def validate_global_position_int_against_simstate(mav, m): - if m.get_type() == 'GLOBAL_POSITION_INT': - self.gpi = m - elif m.get_type() == 'SIMSTATE': - self.simstate = m - if self.gpi is None: - return - if self.simstate is None: - return - divergence = self.get_distance_int(self.gpi, self.simstate) - max_allowed_divergence = 200 - if (time.time() - self.last_print > 1 or - divergence > self.max_divergence): - self.progress("position-estimate-divergence=%fm" % (divergence,)) - self.last_print = time.time() - if divergence > self.max_divergence: - self.max_divergence = divergence - if divergence > max_allowed_divergence: - raise NotAchievedException( - "global-position-int diverged from simstate by %fm (max=%fm" % - (divergence, max_allowed_divergence,)) - self.install_message_hook(validate_global_position_int_against_simstate) + if disable_airspeed_sensor: + max_allowed_divergence = 300 + else: + max_allowed_divergence = 150 + self.install_message_hook_context(vehicle_test_suite.TestSuite.ValidateGlobalPositionIntAgainstSimState(self, max_allowed_divergence=max_allowed_divergence)) # noqa try: # wind is from the West: @@ -2188,20 +2041,49 @@ def validate_global_position_int_against_simstate(mav, m): frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, ) self.wait_location(loc, accuracy=100) - self.progress("Stewing") - self.delay_sim_time(20) - self.set_parameter("SIM_GPS_DISABLE", 1) - self.progress("Roasting") + self.progress("Orbit with GPS and learn wind") + # allow longer to learn wind if there is no airspeed sensor + if disable_airspeed_sensor: + self.delay_sim_time(60) + else: + self.delay_sim_time(20) + self.set_parameter("SIM_GPS1_ENABLE", 0) + self.progress("Continue orbit without GPS") self.delay_sim_time(20) self.change_mode("RTL") self.wait_distance_to_home(100, 200, timeout=200) - self.set_parameter("SIM_GPS_DISABLE", 0) + # go into LOITER to create additonal time for a GPS re-enable test + self.change_mode("LOITER") + self.set_parameter("SIM_GPS1_ENABLE", 1) + t_enabled = self.get_sim_time() + # The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning + # to prevent bad GPS being used when coming back after loss of lock due to interence. + self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=15) + if self.get_sim_time() < (t_enabled+9): + raise NotAchievedException("GPS use re-started too quickly") + # wait for EKF and vehicle position to stabilise, then test response to jamming + self.delay_sim_time(20) + + self.set_parameter("AHRS_OPTIONS", 1) + self.set_parameter("SIM_GPS1_JAM", 1) self.delay_sim_time(10) + self.set_parameter("SIM_GPS1_JAM", 0) + t_enabled = self.get_sim_time() + # The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning + # to prevent bad GPS being used when coming back after loss of lock due to interence. + # The EKF_STATUS_REPORT does not tell us when the good to align check passes, so the minimum time + # value of 3.0 seconds is an arbitrary value set on inspection of dataflash logs from this test + self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=15) + time_since_jamming_stopped = self.get_sim_time() - t_enabled + if time_since_jamming_stopped < 3: + raise NotAchievedException("GPS use re-started %f sec after jamming stopped" % time_since_jamming_stopped) self.set_rc(3, 1000) self.fly_home_land_and_disarm() - self.progress("max-divergence: %fm" % (self.max_divergence,)) finally: - self.remove_message_hook(validate_global_position_int_against_simstate) + pass + + self.context_pop() + self.reboot_sitl() def Deadreckoning(self): '''Test deadreckoning support''' @@ -2319,9 +2201,8 @@ def sample_enable_parameter(self): def RangeFinder(self): '''Test RangeFinder Basic Functionality''' - self.context_push() self.progress("Making sure we don't ordinarily get RANGEFINDER") - self.assert_not_receive_message('RANGEFDINDER') + self.assert_not_receive_message('RANGEFINDER') self.set_analog_rangefinder_parameters() @@ -2335,12 +2216,8 @@ def RangeFinder(self): self.wait_ready_to_arm() self.arm_vehicle() self.wait_waypoint(5, 5, max_dist=100) - rf = self.mav.recv_match(type="RANGEFINDER", timeout=1, blocking=True) - if rf is None: - raise NotAchievedException("Did not receive rangefinder message") - gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=1) - if gpi is None: - raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message") + rf = self.assert_receive_message('RANGEFINDER') + gpi = self.assert_receive_message('GLOBAL_POSITION_INT') if abs(rf.distance - gpi.relative_alt/1000.0) > 3: raise NotAchievedException( "rangefinder alt (%s) disagrees with global-position-int.relative_alt (%s)" % @@ -2351,9 +2228,6 @@ def RangeFinder(self): if not self.current_onboard_log_contains_message("RFND"): raise NotAchievedException("No RFND messages in log") - self.context_pop() - self.reboot_sitl() - def rc_defaults(self): ret = super(AutoTestPlane, self).rc_defaults() ret[3] = 1000 @@ -2426,12 +2300,7 @@ def SimADSB(self): self.reboot_sitl() self.assert_receive_message('ADSB_VEHICLE', timeout=30) - 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): + def ADSBResumeActionResumeLoiter(self): '''ensure we resume auto mission or enter loiter''' self.set_parameters({ "ADSB_TYPE": 1, @@ -2469,68 +2338,58 @@ def ADSB_r_action_resume_or_loiter(self): self.fly_home_land_and_disarm() - def ADSB_f_action_rtl(self): - self.context_push() - ex = None - try: - # message ADSB_VEHICLE 37 -353632614 1491652305 0 584070 0 0 0 "bob" 3 1 255 17 - self.set_parameter("RC12_OPTION", 38) # avoid-adsb - self.set_rc(12, 2000) - self.set_parameters({ - "ADSB_TYPE": 1, - "AVD_ENABLE": 1, - "AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_RTL, - }) - self.reboot_sitl() - self.wait_ready_to_arm() - here = self.mav.location() - self.change_mode("FBWA") - self.delay_sim_time(2) # TODO: work out why this is required... - self.test_adsb_send_threatening_adsb_message(here) - self.progress("Waiting for collision message") - m = self.assert_receive_message('COLLISION', timeout=4) - if m.threat_level != 2: - raise NotAchievedException("Expected some threat at least") - if m.action != mavutil.mavlink.MAV_COLLISION_ACTION_RTL: - raise NotAchievedException("Incorrect action; want=%u got=%u" % - (mavutil.mavlink.MAV_COLLISION_ACTION_RTL, m.action)) - self.wait_mode("RTL") - - self.progress("Sending far-away ABSD_VEHICLE message") - self.mav.mav.adsb_vehicle_send( - 37, # ICAO address - int(here.lat+1 * 1e7), - int(here.lng * 1e7), - mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH, - int(here.alt*1000 + 10000), # 10m up - 0, # heading in cdeg - 0, # horizontal velocity cm/s - 0, # vertical velocity cm/s - "bob".encode("ascii"), # callsign - mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT, - 1, # time since last communication - 65535, # flags - 17 # squawk - ) - self.wait_for_collision_threat_to_clear() - self.change_mode("FBWA") + def ADSBFailActionRTL(self): + '''test ADSB avoidance action of RTL''' + # message ADSB_VEHICLE 37 -353632614 1491652305 0 584070 0 0 0 "bob" 3 1 255 17 + self.set_parameter("RC12_OPTION", 38) # avoid-adsb + self.set_rc(12, 2000) + self.set_parameters({ + "ADSB_TYPE": 1, + "AVD_ENABLE": 1, + "AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_RTL, + }) + self.reboot_sitl() + self.wait_ready_to_arm() + here = self.mav.location() + self.change_mode("FBWA") + self.delay_sim_time(2) # TODO: work out why this is required... + self.test_adsb_send_threatening_adsb_message(here) + self.progress("Waiting for collision message") + m = self.assert_receive_message('COLLISION', timeout=4) + if m.threat_level != 2: + raise NotAchievedException("Expected some threat at least") + if m.action != mavutil.mavlink.MAV_COLLISION_ACTION_RTL: + raise NotAchievedException("Incorrect action; want=%u got=%u" % + (mavutil.mavlink.MAV_COLLISION_ACTION_RTL, m.action)) + self.wait_mode("RTL") - self.progress("Disabling ADSB-avoidance with RC channel") - self.set_rc(12, 1000) - self.delay_sim_time(1) # let the switch get polled - self.test_adsb_send_threatening_adsb_message(here) - m = self.mav.recv_match(type='COLLISION', blocking=True, timeout=4) - self.progress("Got (%s)" % str(m)) - if m is not None: - raise NotAchievedException("Got collision message when I shouldn't have") + self.progress("Sending far-away ABSD_VEHICLE message") + self.mav.mav.adsb_vehicle_send( + 37, # ICAO address + int(here.lat+1 * 1e7), + int(here.lng * 1e7), + mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH, + int(here.alt*1000 + 10000), # 10m up + 0, # heading in cdeg + 0, # horizontal velocity cm/s + 0, # vertical velocity cm/s + "bob".encode("ascii"), # callsign + mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT, + 1, # time since last communication + 65535, # flags + 17 # squawk + ) + self.wait_for_collision_threat_to_clear() + self.change_mode("FBWA") - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.reboot_sitl() - if ex is not None: - raise ex + self.progress("Disabling ADSB-avoidance with RC channel") + self.set_rc(12, 1000) + self.delay_sim_time(1) # let the switch get polled + self.test_adsb_send_threatening_adsb_message(here) + m = self.mav.recv_match(type='COLLISION', blocking=True, timeout=4) + self.progress("Got (%s)" % str(m)) + if m is not None: + raise NotAchievedException("Got collision message when I shouldn't have") def GuidedRequest(self, target_system=1, target_component=1): '''Test handling of MISSION_ITEM in guided mode''' @@ -2631,9 +2490,7 @@ def LOITER(self): now = self.get_sim_time_cached() if now - tstart > 60: break - m = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=5) - if m is None: - raise NotAchievedException("Did not get VFR_HUD") + m = self.assert_receive_message('VFR_HUD') new_throttle = m.throttle alt = m.alt m = self.assert_receive_message('ATTITUDE', timeout=5) @@ -3013,7 +2870,7 @@ def record_maxalt(mav, m): if m.relative_alt/1000.0 > max_alt: max_alt = m.relative_alt/1000.0 - self.install_message_hook(record_maxalt) + self.install_message_hook_context(record_maxalt) self.fly_mission_waypoints(num_wp-1, mission_timeout=600) @@ -3068,6 +2925,7 @@ def Terrain(self): def TerrainLoiter(self): '''Test terrain following in loiter''' self.context_push() + self.install_terrain_handlers_context() 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 @@ -3104,7 +2962,7 @@ def TerrainLoiter(self): self.fly_home_land_and_disarm(240) def fly_external_AHRS(self, sim, eahrs_type, mission): - """Fly with external AHRS (VectorNav)""" + """Fly with external AHRS""" self.customise_SITL_commandline(["--serial4=sim:%s" % sim]) self.set_parameters({ @@ -3228,25 +3086,74 @@ def InertialLabsEAHRS(self): '''Test InertialLabs EAHRS support''' self.fly_external_AHRS("ILabs", 5, "ap1.txt") - def get_accelvec(self, m): - return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 + def GpsSensorPreArmEAHRS(self): + '''Test pre-arm checks related to EAHRS_SENSORS using the MicroStrain7 driver''' + self.customise_SITL_commandline(["--serial4=sim:MicroStrain7"]) - def get_gyrovec(self, m): - return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1) + self.set_parameters({ + "EAHRS_TYPE": 7, + "SERIAL4_PROTOCOL": 36, + "SERIAL4_BAUD": 230400, + "GPS1_TYPE": 0, # Disabled (simulate user setup error) + "GPS2_TYPE": 0, # Disabled (simulate user setup error) + "AHRS_EKF_TYPE": 11, + "INS_GYR_CAL": 1, + "EAHRS_SENSORS": 13, # GPS is enabled + }) + self.reboot_sitl() + self.delay_sim_time(5) + self.progress("Running accelcal") + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=4, + timeout=5, + ) + + self.assert_prearm_failure("ExternalAHRS: Incorrect number", # Cut short due to message limits. + timeout=30, + other_prearm_failures_fatal=False) - def IMUTempCal(self): - '''Test IMU temperature calibration''' - self.progress("Setting up SITL temperature profile") self.set_parameters({ - "SIM_IMUT1_ENABLE" : 1, - "SIM_IMUT1_ACC1_X" : 120000.000000, - "SIM_IMUT1_ACC1_Y" : -190000.000000, - "SIM_IMUT1_ACC1_Z" : 1493.864746, - "SIM_IMUT1_ACC2_X" : -51.624416, - "SIM_IMUT1_ACC2_Y" : 10.364172, - "SIM_IMUT1_ACC2_Z" : -7878.000000, - "SIM_IMUT1_ACC3_X" : -0.514242, - "SIM_IMUT1_ACC3_Y" : 0.862218, + "EAHRS_TYPE": 7, + "SERIAL4_PROTOCOL": 36, + "SERIAL4_BAUD": 230400, + "GPS1_TYPE": 1, # Auto + "GPS2_TYPE": 21, # EARHS + "AHRS_EKF_TYPE": 11, + "INS_GYR_CAL": 1, + "EAHRS_SENSORS": 13, # GPS is enabled + }) + self.reboot_sitl() + self.delay_sim_time(5) + self.progress("Running accelcal") + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=4, + timeout=5, + ) + # Check prearm success with MicroStrain when the first GPS is occupied by another GPS. + # This supports the use case of comparing MicroStrain dual antenna to another GPS. + self.wait_ready_to_arm() + + def get_accelvec(self, m): + return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 + + def get_gyrovec(self, m): + return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1) + + def IMUTempCal(self): + '''Test IMU temperature calibration''' + self.progress("Setting up SITL temperature profile") + self.set_parameters({ + "SIM_IMUT1_ENABLE" : 1, + "SIM_IMUT1_ACC1_X" : 120000.000000, + "SIM_IMUT1_ACC1_Y" : -190000.000000, + "SIM_IMUT1_ACC1_Z" : 1493.864746, + "SIM_IMUT1_ACC2_X" : -51.624416, + "SIM_IMUT1_ACC2_Y" : 10.364172, + "SIM_IMUT1_ACC2_Z" : -7878.000000, + "SIM_IMUT1_ACC3_X" : -0.514242, + "SIM_IMUT1_ACC3_Y" : 0.862218, "SIM_IMUT1_ACC3_Z" : -234.000000, "SIM_IMUT1_GYR1_X" : -5122.513817, "SIM_IMUT1_GYR1_Y" : -3250.470428, @@ -3411,9 +3318,6 @@ def IMUTempCal(self): def EKFlaneswitch(self): '''Test EKF3 Affinity and Lane Switching''' - self.context_push() - ex = None - # new lane swtich available only with EK3 self.set_parameters({ "EK3_ENABLE": 1, @@ -3422,7 +3326,7 @@ def EKFlaneswitch(self): "EK3_AFFINITY": 15, # enable affinity for all sensors "EK3_IMU_MASK": 3, # use only 2 IMUs "GPS2_TYPE": 1, - "SIM_GPS2_DISABLE": 0, + "SIM_GPS2_ENABLE": 1, "SIM_BARO_COUNT": 2, "SIM_BAR2_DISABLE": 0, "ARSPD2_TYPE": 2, @@ -3444,165 +3348,150 @@ def statustext_hook(mav, message): return newlane = int(message.text[-1]) self.lane_switches.append(newlane) - self.install_message_hook(statustext_hook) + self.install_message_hook_context(statustext_hook) # get flying self.takeoff(alt=50) self.change_mode('CIRCLE') - try: - ################################################################### - self.progress("Checking EKF3 Lane Switching trigger from all sensors") - ################################################################### - self.start_subtest("ACCELEROMETER: Change z-axis offset") - # create an accelerometer error by changing the Z-axis offset - self.context_collect("STATUSTEXT") - old_parameter = self.get_parameter("INS_ACCOFFS_Z") - self.wait_statustext( - text="EKF3 lane switch", - timeout=30, - the_function=self.set_parameter("INS_ACCOFFS_Z", old_parameter + 5), - check_context=True) - if self.lane_switches != [1]: - raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.set_parameter("INS_ACCOFFS_Z", old_parameter) - self.context_clear_collection("STATUSTEXT") - self.wait_heading(0, accuracy=10, timeout=60) - self.wait_heading(180, accuracy=10, timeout=60) - ################################################################### - self.start_subtest("BAROMETER: Freeze to last measured value") - self.context_collect("STATUSTEXT") - # create a barometer error by inhibiting any pressure change while changing altitude - old_parameter = self.get_parameter("SIM_BAR2_FREEZE") - self.set_parameter("SIM_BAR2_FREEZE", 1) - self.wait_statustext( - text="EKF3 lane switch", - timeout=30, - the_function=lambda: self.set_rc(2, 2000), - check_context=True) - if self.lane_switches != [1, 0]: - raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.set_rc(2, 1500) - self.set_parameter("SIM_BAR2_FREEZE", old_parameter) - self.context_clear_collection("STATUSTEXT") - self.wait_heading(0, accuracy=10, timeout=60) - self.wait_heading(180, accuracy=10, timeout=60) - ################################################################### - self.start_subtest("GPS: Apply GPS Velocity Error in NED") - self.context_push() - self.context_collect("STATUSTEXT") - - # create a GPS velocity error by adding a random 2m/s - # noise on each axis - def sim_gps_verr(): - self.set_parameters({ - "SIM_GPS_VERR_X": self.get_parameter("SIM_GPS_VERR_X") + 2, - "SIM_GPS_VERR_Y": self.get_parameter("SIM_GPS_VERR_Y") + 2, - "SIM_GPS_VERR_Z": self.get_parameter("SIM_GPS_VERR_Z") + 2, - }) - self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True) - if self.lane_switches != [1, 0, 1]: - raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.context_pop() - self.context_clear_collection("STATUSTEXT") - self.wait_heading(0, accuracy=10, timeout=60) - self.wait_heading(180, accuracy=10, timeout=60) - ################################################################### - self.start_subtest("MAGNETOMETER: Change X-Axis Offset") - self.context_collect("STATUSTEXT") - # create a magnetometer error by changing the X-axis offset - old_parameter = self.get_parameter("SIM_MAG2_OFS_X") - self.wait_statustext( - text="EKF3 lane switch", - timeout=30, - the_function=self.set_parameter("SIM_MAG2_OFS_X", old_parameter + 150), - check_context=True) - if self.lane_switches != [1, 0, 1, 0]: - raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.set_parameter("SIM_MAG2_OFS_X", old_parameter) - self.context_clear_collection("STATUSTEXT") - self.wait_heading(0, accuracy=10, timeout=60) - self.wait_heading(180, accuracy=10, timeout=60) - ################################################################### - self.start_subtest("AIRSPEED: Fail to constant value") - self.context_push() - self.context_collect("STATUSTEXT") - - old_parameter = self.get_parameter("SIM_ARSPD_FAIL") - - def fail_speed(): - self.change_mode("GUIDED") - loc = self.mav.location() - self.run_cmd_int( - mavutil.mavlink.MAV_CMD_DO_REPOSITION, - p5=int(loc.lat * 1e7), - p6=int(loc.lng * 1e7), - p7=50, # alt - ) - self.delay_sim_time(5) - # create an airspeed sensor error by freezing to the - # current airspeed then changing the airspeed demand - # to a higher value and waiting for the TECS speed - # loop to diverge - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - self.set_parameter("SIM_ARSPD_FAIL", m.airspeed) - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, - p1=0, # airspeed - p2=30, - p3=-1, # throttle / no change - p4=0, # absolute values - ) - self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True) - if self.lane_switches != [1, 0, 1, 0, 1]: - raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.set_parameter("SIM_ARSPD_FAIL", old_parameter) - self.change_mode('CIRCLE') - self.context_pop() - self.context_clear_collection("STATUSTEXT") - self.wait_heading(0, accuracy=10, timeout=60) - self.wait_heading(180, accuracy=10, timeout=60) - ################################################################### - self.progress("GYROSCOPE: Change Y-Axis Offset") - self.context_collect("STATUSTEXT") - # create a gyroscope error by changing the Y-axis offset - old_parameter = self.get_parameter("INS_GYR2OFFS_Y") - self.wait_statustext( - text="EKF3 lane switch", - timeout=30, - the_function=self.set_parameter("INS_GYR2OFFS_Y", old_parameter + 1), - check_context=True) - if self.lane_switches != [1, 0, 1, 0, 1, 0]: - raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) - # Cleanup - self.set_parameter("INS_GYR2OFFS_Y", old_parameter) - self.context_clear_collection("STATUSTEXT") - ################################################################### - - self.disarm_vehicle(force=True) + ################################################################### + self.progress("Checking EKF3 Lane Switching trigger from all sensors") + ################################################################### + self.start_subtest("ACCELEROMETER: Change z-axis offset") + # create an accelerometer error by changing the Z-axis offset + self.context_collect("STATUSTEXT") + old_parameter = self.get_parameter("INS_ACCOFFS_Z") + self.wait_statustext( + text="EKF3 lane switch", + timeout=30, + the_function=self.set_parameter("INS_ACCOFFS_Z", old_parameter + 5), + check_context=True) + if self.lane_switches != [1]: + raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.set_parameter("INS_ACCOFFS_Z", old_parameter) + self.context_clear_collection("STATUSTEXT") + self.wait_heading(0, accuracy=10, timeout=60) + self.wait_heading(180, accuracy=10, timeout=60) + ################################################################### + self.start_subtest("BAROMETER: Freeze to last measured value") + self.context_collect("STATUSTEXT") + # create a barometer error by inhibiting any pressure change while changing altitude + old_parameter = self.get_parameter("SIM_BAR2_FREEZE") + self.set_parameter("SIM_BAR2_FREEZE", 1) + self.wait_statustext( + text="EKF3 lane switch", + timeout=30, + the_function=lambda: self.set_rc(2, 2000), + check_context=True) + if self.lane_switches != [1, 0]: + raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.set_rc(2, 1500) + self.set_parameter("SIM_BAR2_FREEZE", old_parameter) + self.context_clear_collection("STATUSTEXT") + self.wait_heading(0, accuracy=10, timeout=60) + self.wait_heading(180, accuracy=10, timeout=60) + ################################################################### + self.start_subtest("GPS: Apply GPS Velocity Error in NED") + self.context_push() + self.context_collect("STATUSTEXT") - except Exception as e: - self.print_exception_caught(e) - ex = e + # create a GPS velocity error by adding a random 2m/s + # noise on each axis + def sim_gps_verr(): + self.set_parameters({ + "SIM_GPS1_VERR_X": self.get_parameter("SIM_GPS1_VERR_X") + 2, + "SIM_GPS1_VERR_Y": self.get_parameter("SIM_GPS1_VERR_Y") + 2, + "SIM_GPS1_VERR_Z": self.get_parameter("SIM_GPS1_VERR_Z") + 2, + }) + self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True) + if self.lane_switches != [1, 0, 1]: + raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.context_pop() + self.context_clear_collection("STATUSTEXT") + self.wait_heading(0, accuracy=10, timeout=60) + self.wait_heading(180, accuracy=10, timeout=60) + ################################################################### + self.start_subtest("MAGNETOMETER: Change X-Axis Offset") + self.context_collect("STATUSTEXT") + # create a magnetometer error by changing the X-axis offset + old_parameter = self.get_parameter("SIM_MAG2_OFS_X") + self.wait_statustext( + text="EKF3 lane switch", + timeout=30, + the_function=self.set_parameter("SIM_MAG2_OFS_X", old_parameter + 150), + check_context=True) + if self.lane_switches != [1, 0, 1, 0]: + raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.set_parameter("SIM_MAG2_OFS_X", old_parameter) + self.context_clear_collection("STATUSTEXT") + self.wait_heading(0, accuracy=10, timeout=60) + self.wait_heading(180, accuracy=10, timeout=60) + ################################################################### + self.start_subtest("AIRSPEED: Fail to constant value") + self.context_push() + self.context_collect("STATUSTEXT") - self.remove_message_hook(statustext_hook) + old_parameter = self.get_parameter("SIM_ARSPD_FAIL") + def fail_speed(): + self.change_mode("GUIDED") + loc = self.mav.location() + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_REPOSITION, + p5=int(loc.lat * 1e7), + p6=int(loc.lng * 1e7), + p7=50, # alt + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + ) + self.delay_sim_time(5) + # create an airspeed sensor error by freezing to the + # current airspeed then changing the airspeed demand + # to a higher value and waiting for the TECS speed + # loop to diverge + m = self.mav.recv_match(type='VFR_HUD', blocking=True) + self.set_parameter("SIM_ARSPD_FAIL", m.airspeed) + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=0, # airspeed + p2=30, + p3=-1, # throttle / no change + p4=0, # absolute values + ) + self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True) + if self.lane_switches != [1, 0, 1, 0, 1]: + raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.set_parameter("SIM_ARSPD_FAIL", old_parameter) + self.change_mode('CIRCLE') self.context_pop() + self.context_clear_collection("STATUSTEXT") + self.wait_heading(0, accuracy=10, timeout=60) + self.wait_heading(180, accuracy=10, timeout=60) + ################################################################### + self.progress("GYROSCOPE: Change Y-Axis Offset") + self.context_collect("STATUSTEXT") + # create a gyroscope error by changing the Y-axis offset + old_parameter = self.get_parameter("INS_GYR2OFFS_Y") + self.wait_statustext( + text="EKF3 lane switch", + timeout=30, + the_function=self.set_parameter("INS_GYR2OFFS_Y", old_parameter + 1), + check_context=True) + if self.lane_switches != [1, 0, 1, 0, 1, 0]: + raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1])) + # Cleanup + self.set_parameter("INS_GYR2OFFS_Y", old_parameter) + self.context_clear_collection("STATUSTEXT") + ################################################################### - # some parameters need reboot to take effect - self.reboot_sitl() - - if ex is not None: - raise ex + self.disarm_vehicle(force=True) 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 "FENCE_ACTION": 0, # Set action to report @@ -3611,40 +3500,421 @@ def FenceAltCeilFloor(self): }) # Grab Home Position - self.mav.recv_match(type='HOME_POSITION', blocking=True) - self.homeloc = self.mav.location() + self.wait_ready_to_arm() + startpos = self.mav.location() cruise_alt = 150 self.takeoff(cruise_alt) + # note that while we enable the fence here, since the action + # is set to report-only the fence continues to show as + # not-enabled in the assert calls below self.do_fence_enable() self.progress("Fly above ceiling and check for breach") - self.change_altitude(self.homeloc.alt + cruise_alt + 80) + self.change_altitude(startpos.alt + cruise_alt + 80) + self.assert_fence_sys_status(True, False, False) + + self.progress("Return to cruise alt") + self.change_altitude(startpos.alt + cruise_alt) + + self.progress("Ensure breach has clearned") + self.assert_fence_sys_status(True, False, True) + + self.progress("Fly below floor and check for breach") + self.change_altitude(startpos.alt + cruise_alt - 80) + + self.progress("Ensure breach has clearned") + self.assert_fence_sys_status(True, False, False) + + self.do_fence_disable() + + self.fly_home_land_and_disarm(timeout=150) + + def FenceMinAltAutoEnable(self): + '''Tests autoenablement of the alt min fence and fences on arming''' + self.set_parameters({ + "FENCE_TYPE": 9, # Set fence type to min alt and max alt + "FENCE_ACTION": 1, # Set action to RTL + "FENCE_ALT_MIN": 25, + "FENCE_ALT_MAX": 100, + "FENCE_AUTOENABLE": 3, + "FENCE_ENABLE" : 0, + "RTL_AUTOLAND" : 2, + }) + + # check we can takeoff again + for i in [1, 2]: + # Grab Home Position + self.wait_ready_to_arm() + self.arm_vehicle() + # max alt fence should now be enabled + if i == 1: + self.assert_fence_enabled() + + self.takeoff(alt=50, mode='TAKEOFF') + self.change_mode("FBWA") + self.set_rc(3, 1100) # lower throttle + + self.progress("Waiting for RTL") + tstart = self.get_sim_time() + mode = "RTL" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + self.fly_home_land_and_disarm() + self.change_mode("FBWA") + self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL) + self.set_current_waypoint(0, check_afterwards=False) + self.set_rc(3, 1000) # lower throttle + + def FenceMinAltEnableAutoland(self): + '''Tests autolanding when alt min fence is enabled''' + self.set_parameters({ + "FENCE_TYPE": 12, # Set fence type to min alt and max alt + "FENCE_ACTION": 1, # Set action to RTL + "FENCE_ALT_MIN": 20, + "FENCE_AUTOENABLE": 0, + "FENCE_ENABLE" : 1, + "RTL_AUTOLAND" : 2, + }) + + # Grab Home Position + self.wait_ready_to_arm() + self.arm_vehicle() + + self.takeoff(alt=50, mode='TAKEOFF') + self.change_mode("FBWA") + self.set_rc(3, 1100) # lower throttle + + self.progress("Waiting for RTL") + tstart = self.get_sim_time() + mode = "RTL" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + # switch to FBWA + self.change_mode("FBWA") + self.set_rc(3, 1500) # raise throttle + self.wait_altitude(25, 35, timeout=50, relative=True) + self.set_rc(3, 1000) # lower throttle + # Now check we can land + self.fly_home_land_and_disarm() + + def FenceMinAltAutoEnableAbort(self): + '''Tests autoenablement of the alt min fence and fences on arming''' + self.set_parameters({ + "FENCE_TYPE": 8, # Set fence type to min alt + "FENCE_ACTION": 1, # Set action to RTL + "FENCE_ALT_MIN": 25, + "FENCE_ALT_MAX": 100, + "FENCE_AUTOENABLE": 3, + "FENCE_ENABLE" : 0, + "RTL_AUTOLAND" : 2, + }) + + self.wait_ready_to_arm() + self.arm_vehicle() + + self.takeoff(alt=50, mode='TAKEOFF') + self.change_mode("FBWA") + # min alt fence should now be enabled + self.assert_fence_enabled() + self.set_rc(3, 1100) # lower throttle + + self.progress("Waiting for RTL") + tstart = self.get_sim_time() + mode = "RTL" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + + self.load_generic_mission("flaps.txt") + self.change_mode("AUTO") + self.wait_distance_to_waypoint(8, 100, 10000000) + self.set_current_waypoint(8) + # abort the landing + self.wait_altitude(10, 20, timeout=200, relative=True) + self.change_mode("CRUISE") + self.set_rc(2, 1200) + # self.set_rc(3, 1600) # raise throttle + self.wait_altitude(30, 40, timeout=200, relative=True) + # min alt fence should now be re-enabled + self.assert_fence_enabled() + + self.change_mode("AUTO") + self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL) + self.fly_home_land_and_disarm(timeout=150) + + def FenceAutoEnableDisableSwitch(self): + '''Tests autoenablement of regular fences and manual disablement''' + self.set_parameters({ + "FENCE_TYPE": 11, # Set fence type to min alt + "FENCE_ACTION": 1, # Set action to RTL + "FENCE_ALT_MIN": 50, + "FENCE_ALT_MAX": 100, + "FENCE_AUTOENABLE": 2, + "FENCE_OPTIONS" : 1, + "FENCE_ENABLE" : 1, + "FENCE_RADIUS" : 300, + "FENCE_RET_ALT" : 0, + "FENCE_RET_RALLY" : 0, + "FENCE_TOTAL" : 0, + "TKOFF_ALT" : 75, + "RC7_OPTION" : 11, # AC_Fence uses Aux switch functionality + }) + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE + # Grab Home Position + self.mav.recv_match(type='HOME_POSITION', blocking=True) + self.set_rc_from_map({7: 1000}) # Turn fence off with aux function + + self.wait_ready_to_arm() + cruise_alt = 75 + self.takeoff(cruise_alt, mode='TAKEOFF') + + self.progress("Fly above ceiling and check there is no breach") + self.set_rc(3, 2000) + self.change_altitude(cruise_alt + 80, relative=True) m = self.mav.recv_match(type='SYS_STATUS', blocking=True) self.progress("Got (%s)" % str(m)) - if ((m.onboard_control_sensors_health & fence_bit)): - raise NotAchievedException("Fence Ceiling did not breach") + if (not (m.onboard_control_sensors_health & fence_bit)): + raise NotAchievedException("Fence Ceiling breached") - self.progress("Return to cruise alt and check for breach clear") - self.change_altitude(self.homeloc.alt + cruise_alt) + self.progress("Return to cruise alt") + self.set_rc(3, 1500) + self.change_altitude(cruise_alt, relative=True) + self.progress("Fly below floor and check for no breach") + self.change_altitude(25, relative=True) m = self.mav.recv_match(type='SYS_STATUS', blocking=True) self.progress("Got (%s)" % str(m)) if (not (m.onboard_control_sensors_health & fence_bit)): - raise NotAchievedException("Fence breach did not clear") + raise NotAchievedException("Fence Ceiling breached") - self.progress("Fly below floor and check for breach") - self.change_altitude(self.homeloc.alt + cruise_alt - 80) + self.progress("Fly above floor and check fence is not re-enabled") + self.set_rc(3, 2000) + self.change_altitude(75, relative=True) + m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.progress("Got (%s)" % str(m)) + if (m.onboard_control_sensors_enabled & fence_bit): + raise NotAchievedException("Fence Ceiling re-enabled") + + self.progress("Return to cruise alt") + self.set_rc(3, 1500) + self.change_altitude(cruise_alt, relative=True) + self.fly_home_land_and_disarm(timeout=250) + + def FenceCircleExclusionAutoEnable(self): + '''Tests autolanding when alt min fence is enabled''' + self.set_parameters({ + "FENCE_TYPE": 2, # Set fence type to circle + "FENCE_ACTION": 1, # Set action to RTL + "FENCE_AUTOENABLE": 2, + "FENCE_ENABLE" : 0, + "RTL_AUTOLAND" : 2, + }) + + fence_loc = self.home_position_as_mav_location() + self.location_offset_ne(fence_loc, 300, 0) + + self.upload_fences_from_locations([( + mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION, { + "radius" : 100, + "loc" : fence_loc + } + )]) + + self.takeoff(alt=50, mode='TAKEOFF') + self.change_mode("FBWA") + self.set_rc(3, 1100) # lower throttle + + self.progress("Waiting for RTL") + self.wait_mode('RTL') + # Now check we can land + self.fly_home_land_and_disarm() + + def FenceEnableDisableSwitch(self): + '''Tests enablement and disablement of fences on a switch''' + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE + self.set_parameters({ + "FENCE_TYPE": 4, # Set fence type to polyfence + "FENCE_ACTION": 6, # Set action to GUIDED + "FENCE_ALT_MIN": 10, + "FENCE_ENABLE" : 0, + "RC7_OPTION" : 11, # AC_Fence uses Aux switch functionality + }) + + self.progress("Checking fence is not present before being configured") m = self.mav.recv_match(type='SYS_STATUS', blocking=True) self.progress("Got (%s)" % str(m)) - if ((m.onboard_control_sensors_health & fence_bit)): - raise NotAchievedException("Fence Floor did not breach") + if (m.onboard_control_sensors_enabled & fence_bit): + raise NotAchievedException("Fence enabled before being configured") - self.do_fence_disable() + self.wait_ready_to_arm() + # takeoff at a lower altitude to avoid immediately breaching polyfence + self.takeoff(alt=25) + self.change_mode("FBWA") + + self.load_fence("CMAC-fence.txt") + + self.set_rc_from_map({ + 3: 1500, + 7: 2000, + }) # Turn fence on with aux function + + m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) + self.progress("Got (%s)" % str(m)) + if m is None: + raise NotAchievedException("Got FENCE_STATUS unexpectedly") + + self.progress("Checking fence is initially OK") + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, + present=True, + enabled=True, + healthy=True, + verbose=False, + timeout=30) + + self.progress("Waiting for GUIDED") + tstart = self.get_sim_time() + mode = "GUIDED" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + # check we are in breach + self.assert_fence_enabled() + + self.set_rc_from_map({ + 7: 1000, + }) # Turn fence off with aux function + + # wait to no longer be in breach + self.delay_sim_time(5) + self.assert_fence_disabled() + + self.fly_home_land_and_disarm(timeout=250) + self.do_fence_disable() # Ensure the fence is disabled after test + + def FenceEnableDisableAux(self): + '''Tests enablement and disablement of fences via aux command''' + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE + + enable = 0 + self.set_parameters({ + "FENCE_TYPE": 12, # Set fence type to polyfence + AltMin + "FENCE_ALT_MIN": 10, + "FENCE_ENABLE" : enable, + }) + + if not enable: + self.progress("Checking fence is not present before being configured") + m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.progress("Got (%s)" % str(m)) + if (m.onboard_control_sensors_enabled & fence_bit): + raise NotAchievedException("Fence enabled before being configured") + + self.load_fence("CMAC-fence.txt") + + self.wait_ready_to_arm() + # takeoff at a lower altitude to avoid immediately breaching polyfence + self.takeoff(alt=25) + self.change_mode("CRUISE") + self.wait_distance(150, accuracy=20) + + self.run_auxfunc( + 11, + 2, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED + ) + + m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) + self.progress("Got (%s)" % str(m)) + if m is None: + raise NotAchievedException("Got FENCE_STATUS unexpectedly") + + self.progress("Checking fence is initially OK") + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, + present=True, + enabled=True, + healthy=True, + verbose=False, + timeout=30) + + self.progress("Waiting for RTL") + tstart = self.get_sim_time() + mode = "RTL" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + # check we are in breach + self.assert_fence_enabled() + self.assert_fence_sys_status(True, True, False) + + # wait until we get home + self.wait_distance_to_home(50, 100, timeout=200) + # now check we are now not in breach + self.assert_fence_sys_status(True, True, True) + # Turn fence off with aux function + self.run_auxfunc( + 11, + 0, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED + ) + # switch back to cruise + self.change_mode("CRUISE") + self.wait_distance(150, accuracy=20) + + # re-enable the fences + self.run_auxfunc( + 11, + 2, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED + ) + + m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) + self.progress("Got (%s)" % str(m)) + if m is None: + raise NotAchievedException("Got FENCE_STATUS unexpectedly") - self.fly_home_land_and_disarm(timeout=150) + self.progress("Waiting for RTL") + tstart = self.get_sim_time() + mode = "RTL" + while not self.mode_is(mode, drain_mav=False): + self.mav.messages['HEARTBEAT'].custom_mode + self.progress("mav.flightmode=%s Want=%s Alt=%f" % ( + self.mav.flightmode, mode, self.get_altitude(relative=True))) + if (self.get_sim_time_cached() > tstart + 120): + raise WaitModeTimeout("Did not change mode") + self.progress("Got mode %s" % mode) + + # wait to no longer be in breach + self.wait_distance_to_home(50, 100, timeout=200) + self.assert_fence_sys_status(True, True, True) + + # fly home and land with fences still enabled + self.fly_home_land_and_disarm(timeout=250) + self.do_fence_disable() # Ensure the fence is disabled after test def FenceBreachedChangeMode(self): '''Tests manual mode change after fence breach, as set with FENCE_OPTIONS''' @@ -3661,12 +3931,9 @@ def FenceBreachedChangeMode(self): mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0), mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0), ] - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - locs - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs), + ]) self.delay_sim_time(1) self.wait_ready_to_arm() self.takeoff(alt=50) @@ -3724,12 +3991,9 @@ def FenceNoFenceReturnPoint(self): mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.003, 0, 0), mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0), ] - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - locs - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs), + ]) self.delay_sim_time(1) self.wait_ready_to_arm() self.takeoff(alt=50) @@ -3896,6 +4160,8 @@ def FlyEachFrame(self): "plane-ice" : "needs ICE control channel for ignition", "quadplane-ice" : "needs ICE control channel for ignition", "quadplane-can" : "needs CAN periph", + "stratoblimp" : "not expected to fly normally", + "glider" : "needs balloon lift", } for frame in sorted(vinfo_options["frames"].keys()): self.start_subtest("Testing frame (%s)" % str(frame)) @@ -3917,7 +4183,8 @@ def FlyEachFrame(self): if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) @@ -4002,111 +4269,596 @@ def WatchdogHome(self): self.print_exception_caught(e) ex = e - self.reboot_sitl() + self.reboot_sitl() + + if ex is not None: + raise ex + + def AUTOTUNE(self): + '''Test AutoTune mode''' + self.takeoff(100) + self.change_mode('AUTOTUNE') + self.context_collect('STATUSTEXT') + tstart = self.get_sim_time() + axis = "Roll" + rc_value = 1000 + while True: + timeout = 600 + if self.get_sim_time() - tstart > timeout: + raise NotAchievedException("Did not complete within %u seconds" % timeout) + try: + m = self.wait_statustext("%s: Finished" % axis, check_context=True, timeout=0.1) + self.progress("Got %s" % str(m)) + if axis == "Roll": + axis = "Pitch" + elif axis == "Pitch": + break + else: + raise ValueError("Bug: %s" % axis) + except AutoTestTimeoutException: + pass + self.delay_sim_time(1) + + if rc_value == 1000: + rc_value = 2000 + elif rc_value == 2000: + rc_value = 1000 + elif rc_value == 1000: + rc_value = 2000 + else: + raise ValueError("Bug") + + if axis == "Roll": + self.set_rc(1, rc_value) + self.set_rc(2, 1500) + elif axis == "Pitch": + self.set_rc(1, 1500) + self.set_rc(2, rc_value) + else: + raise ValueError("Bug") + + tdelta = self.get_sim_time() - tstart + self.progress("Finished in %0.1f seconds" % (tdelta,)) + + self.set_rc(1, 1500) + self.set_rc(2, 1500) + + self.change_mode('FBWA') + self.fly_home_land_and_disarm(timeout=tdelta+240) + + def AutotuneFiltering(self): + '''Test AutoTune mode with filter updates disabled''' + self.set_parameters({ + "AUTOTUNE_OPTIONS": 3, + # some filtering is required for autotune to complete + "RLL_RATE_FLTD": 10, + "PTCH_RATE_FLTD": 10, + "RLL_RATE_FLTT": 20, + "PTCH_RATE_FLTT": 20, + }) + self.AUTOTUNE() + + def LandingDrift(self): + '''Circuit with baro drift''' + self.customise_SITL_commandline([], wipe=True) + + self.set_analog_rangefinder_parameters() + + self.set_parameters({ + "SIM_BARO_DRIFT": -0.02, + "SIM_TERRAIN": 0, + "RNGFND_LANDING": 1, + "LAND_SLOPE_RCALC": 2, + "LAND_ABORT_DEG": 1, + }) + + self.reboot_sitl() + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Load and start mission + self.load_mission("ap-circuit.txt", strict=True) + self.set_current_waypoint(1, check_afterwards=True) + self.change_mode('AUTO') + self.wait_current_waypoint(1, timeout=5) + self.wait_groundspeed(0, 10, timeout=5) + + # Wait for landing waypoint + self.wait_current_waypoint(9, timeout=1200) + + # Wait for landing restart + self.wait_current_waypoint(5, timeout=60) + + # Wait for landing waypoint (second attempt) + self.wait_current_waypoint(9, timeout=1200) + + self.wait_disarmed(timeout=180) + + def TakeoffAuto1(self): + '''Test the behaviour of an AUTO takeoff, pt1.''' + ''' + Conditions: + - ARSPD_USE=1 + - TKOFF_OPTIONS[0]=0 + - TKOFF_THR_MAX < THR_MAX + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 1.0, + "THR_MAX": 100.0, + "TKOFF_THR_MAX": 80.0, + "TKOFF_THR_MINACC": 3.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + "RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item. + }) + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.wait_ready_to_arm() + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.load_mission("catapult.txt", strict=True) + self.change_mode('AUTO') + + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Wait until we're midway through the climb. + test_alt = 50 + self.wait_altitude(test_alt, test_alt+2, relative=True) + + # Ensure that by then the aircraft still goes at max allowed throttle. + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Wait for landing waypoint. + self.wait_current_waypoint(11, timeout=1200) + self.wait_disarmed(120) + + def TakeoffAuto2(self): + '''Test the behaviour of an AUTO takeoff, pt2.''' + ''' + Conditions: + - ARSPD_USE=0 + - TKOFF_OPTIONS[0]=0 + - TKOFF_THR_MAX > THR_MAX + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 0.0, + "THR_MAX": 80.0, + "TKOFF_THR_MAX": 100.0, + "TKOFF_THR_MINACC": 3.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + "RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item. + }) + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.wait_ready_to_arm() + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.load_mission("catapult.txt", strict=True) + self.change_mode('AUTO') + + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Wait until we're midway through the climb. + test_alt = 50 + self.wait_altitude(test_alt, test_alt+2, relative=True) + + # Ensure that by then the aircraft still goes at max allowed throttle. + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Wait for landing waypoint. + self.wait_current_waypoint(11, timeout=1200) + self.wait_disarmed(120) + + def TakeoffAuto3(self): + '''Test the behaviour of an AUTO takeoff, pt3.''' + ''' + Conditions: + - ARSPD_USE=1 + - TKOFF_OPTIONS[0]=1 + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 1.0, + "THR_MAX": 80.0, + "THR_MIN": 0.0, + "TKOFF_OPTIONS": 1.0, + "TKOFF_THR_MAX": 100.0, + "TKOFF_THR_MINACC": 3.0, + "TECS_PITCH_MAX": 35.0, + "TKOFF_THR_MAX_T": 3.0, + "PTCH_LIM_MAX_DEG": 35.0, + "RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item. + }) + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.wait_ready_to_arm() + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.load_mission("catapult.txt", strict=True) + self.change_mode('AUTO') + + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Ensure that TKOFF_THR_MAX_T is respected. + self.delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Ensure that after that the aircraft does not go full throttle anymore. + test_alt = 50 + self.wait_altitude(test_alt, test_alt+2, relative=True) + w = vehicle_test_suite.WaitAndMaintainServoChannelValue( + self, + 3, # throttle + 1000+10*self.get_parameter("TKOFF_THR_MAX")-10, + comparator=operator.lt, + minimum_duration=1, + ) + w.run() + + # Wait for landing waypoint. + self.wait_current_waypoint(11, timeout=1200) + self.wait_disarmed(120) + + def TakeoffAuto4(self): + '''Test the behaviour of an AUTO takeoff, pt4.''' + ''' + Conditions: + - ARSPD_USE=0 + - TKOFF_OPTIONS[0]=1 + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 0.0, + "THR_MAX": 80.0, + "THR_MIN": 0.0, + "TKOFF_OPTIONS": 1.0, + "TKOFF_THR_MAX": 100.0, + "TKOFF_THR_MINACC": 3.0, + "TECS_PITCH_MAX": 35.0, + "TKOFF_THR_MAX_T": 3.0, + "PTCH_LIM_MAX_DEG": 35.0, + "RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item. + }) + + self.wait_ready_to_arm() + + # Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m. + self.load_mission("catapult.txt", strict=True) + self.change_mode('AUTO') + + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Ensure that TKOFF_THR_MAX_T is respected. + self.delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Ensure that after that the aircraft still goes to maximum throttle. + test_alt = 50 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Wait for landing waypoint. + self.wait_current_waypoint(11, timeout=1200) + self.wait_disarmed(120) + + def TakeoffTakeoff1(self): + '''Test the behaviour of a takeoff in TAKEOFF mode, pt1.''' + ''' + Conditions: + - ARSPD_USE=1 + - TKOFF_OPTIONS[0]=0 + - TKOFF_THR_MAX < THR_MAX + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 1.0, + "THR_MAX": 100.0, + "TKOFF_LVL_ALT": 30.0, + "TKOFF_ALT": 80.0, + "TKOFF_OPTIONS": 0.0, + "TKOFF_THR_MINACC": 3.0, + "TKOFF_THR_MAX": 80.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Check whether we're at max throttle below TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")-10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Check whether we're still at max throttle past TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")+10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-5, target_alt, relative=True) + + # Wait a bit for the Takeoff altitude to settle. + self.delay_sim_time(5) + + self.fly_home_land_and_disarm() + + def TakeoffTakeoff2(self): + '''Test the behaviour of a takeoff in TAKEOFF mode, pt2.''' + ''' + Conditions: + - ARSPD_USE=1 + - TKOFF_OPTIONS[0]=1 + - TKOFF_THR_MAX < THR_MAX + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 1.0, + "THR_MAX": 100.0, + "TKOFF_LVL_ALT": 30.0, + "TKOFF_ALT": 80.0, + "TKOFF_OPTIONS": 1.0, + "TKOFF_THR_MINACC": 3.0, + "TKOFF_THR_MAX": 80.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Check whether we're at max throttle below TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")-10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Check whether we've receded from max throttle past TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")+10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + thr_min = 1000+10*(self.get_parameter("TKOFF_THR_MIN"))-1 + thr_max = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))-10 + self.assert_servo_channel_range(3, thr_min, thr_max) + + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-5, target_alt, relative=True) + + # Wait a bit for the Takeoff altitude to settle. + self.delay_sim_time(5) + + self.fly_home_land_and_disarm() + + def TakeoffTakeoff3(self): + '''Test the behaviour of a takeoff in TAKEOFF mode, pt3.''' + ''' + This is the same as case #1, but with disabled airspeed sensor. + + Conditions: + - ARSPD_USE=0 + - TKOFF_OPTIONS[0]=0 + - TKOFF_THR_MAX < THR_MAX + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 0.0, + "THR_MAX": 100.0, + "TKOFF_DIST": 400.0, + "TKOFF_LVL_ALT": 30.0, + "TKOFF_ALT": 100.0, + "TKOFF_OPTIONS": 0.0, + "TKOFF_THR_MINACC": 3.0, + "TKOFF_THR_MAX": 80.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # we expect to maintain this throttle level past the takeoff + # altitude through to our takeoff altitude: + expected_takeoff_throttle = 1000+10*self.get_parameter("TKOFF_THR_MAX") + + # Check whether we're at max throttle below TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")-10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + w = vehicle_test_suite.WaitAndMaintainServoChannelValue( + self, + 3, # throttle + expected_takeoff_throttle, + epsilon=10, + minimum_duration=1, + ) + w.run() + + # Check whether we're still at max throttle past TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")+10 + self.wait_altitude(test_alt, test_alt+2, relative=True) - if ex is not None: - raise ex + w = vehicle_test_suite.WaitAndMaintainServoChannelValue( + self, + 3, # throttle + expected_takeoff_throttle, + epsilon=10, + minimum_duration=1, + ) + w.run() - def AUTOTUNE(self): - '''Test AutoTune mode''' - self.takeoff(100) - self.change_mode('AUTOTUNE') - self.context_collect('STATUSTEXT') - tstart = self.get_sim_time() - axis = "Roll" - rc_value = 1000 - while True: - timeout = 600 - if self.get_sim_time() - tstart > timeout: - raise NotAchievedException("Did not complete within %u seconds" % timeout) - try: - m = self.wait_statustext("%s: Finished" % axis, check_context=True, timeout=0.1) - self.progress("Got %s" % str(m)) - if axis == "Roll": - axis = "Pitch" - elif axis == "Pitch": - break - else: - raise ValueError("Bug: %s" % axis) - except AutoTestTimeoutException: - pass - self.delay_sim_time(1) + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-2.5, target_alt+2.5, relative=True, minimum_duration=10, timeout=30) - if rc_value == 1000: - rc_value = 2000 - elif rc_value == 2000: - rc_value = 1000 - elif rc_value == 1000: - rc_value = 2000 - else: - raise ValueError("Bug") + self.reboot_sitl(force=True) - if axis == "Roll": - self.set_rc(1, rc_value) - self.set_rc(2, 1500) - elif axis == "Pitch": - self.set_rc(1, 1500) - self.set_rc(2, rc_value) - else: - raise ValueError("Bug") + def TakeoffTakeoff4(self): + '''Test the behaviour of a takeoff in TAKEOFF mode, pt4.''' + ''' + This is the same as case #3, but with almost stock parameters and without a catapult. - tdelta = self.get_sim_time() - tstart - self.progress("Finished in %0.1f seconds" % (tdelta,)) + Conditions: + - ARSPD_USE=0 + ''' - self.set_rc(1, 1500) - self.set_rc(2, 1500) + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "ARSPD_USE": 0.0, + }) + self.change_mode("TAKEOFF") - self.change_mode('FBWA') - self.fly_home_land_and_disarm(timeout=tdelta+240) + self.wait_ready_to_arm() + self.arm_vehicle() + + # Check whether we're at max throttle below TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")-10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Check whether we're still at max throttle past TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT")+10 + self.wait_altitude(test_alt, test_alt+2, relative=True) + target_throttle = 1000+10*(self.get_parameter("THR_MAX")) + self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10) + + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-5, target_alt, relative=True) + + # Wait a bit for the Takeoff altitude to settle. + self.delay_sim_time(5) + + self.fly_home_land_and_disarm() + + def TakeoffGround(self): + '''Test a rolling TAKEOFF.''' - def AutotuneFiltering(self): - '''Test AutoTune mode with filter updates disabled''' self.set_parameters({ - "AUTOTUNE_OPTIONS": 3, - # some filtering is required for autotune to complete - "RLL_RATE_FLTD": 10, - "PTCH_RATE_FLTD": 10, - "RLL_RATE_FLTT": 20, - "PTCH_RATE_FLTT": 20, + "TKOFF_ROTATE_SPD": 15.0, }) - self.AUTOTUNE() + self.change_mode("TAKEOFF") - def LandingDrift(self): - '''Circuit with baro drift''' - self.customise_SITL_commandline([], wipe=True) + self.wait_ready_to_arm() + self.arm_vehicle() - self.set_analog_rangefinder_parameters() + # Check that we demand minimum pitch below rotation speed. + self.wait_groundspeed(8, 10) + m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=5) + nav_pitch = m.nav_pitch + if nav_pitch > 5.1 or nav_pitch < 4.9: + raise NotAchievedException(f"Did not achieve correct takeoff pitch ({nav_pitch}).") + + # Check whether we've achieved correct target pitch after rotation. + self.wait_groundspeed(23, 24) + m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=5) + nav_pitch = m.nav_pitch + if nav_pitch > 15.1 or nav_pitch < 14.9: + raise NotAchievedException(f"Did not achieve correct takeoff pitch ({nav_pitch}).") + + self.fly_home_land_and_disarm() + def TakeoffIdleThrottle(self): + '''Apply idle throttle before takeoff.''' + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) self.set_parameters({ - "SIM_BARO_DRIFT": -0.02, - "SIM_TERRAIN": 0, - "RNGFND_LANDING": 1, - "LAND_SLOPE_RCALC": 2, - "LAND_ABORT_DEG": 1, + "TKOFF_THR_IDLE": 20.0, + "TKOFF_THR_MINSPD": 3.0, }) - - self.reboot_sitl() + self.change_mode("TAKEOFF") self.wait_ready_to_arm() self.arm_vehicle() - # Load and start mission - self.load_mission("ap-circuit.txt", strict=True) - self.set_current_waypoint(1, check_afterwards=True) - self.change_mode('AUTO') - self.wait_current_waypoint(1, timeout=5) - self.wait_groundspeed(0, 10, timeout=5) - - # Wait for landing waypoint - self.wait_current_waypoint(9, timeout=1200) + # Ensure that the throttle rises to idle throttle. + expected_idle_throttle = 1000+10*self.get_parameter("TKOFF_THR_IDLE") + self.assert_servo_channel_range(3, expected_idle_throttle-10, expected_idle_throttle+10) - # Wait for landing restart - self.wait_current_waypoint(5, timeout=60) + # Launch the catapult + self.set_servo(6, 1000) - # Wait for landing waypoint (second attempt) - self.wait_current_waypoint(9, timeout=1200) + self.delay_sim_time(5) + self.change_mode('RTL') - self.wait_disarmed(timeout=180) + self.fly_home_land_and_disarm() def DCMFallback(self): '''Really annoy the EKF and force fallback''' @@ -4119,8 +4871,8 @@ def DCMFallback(self): self.context_collect('STATUSTEXT') self.set_parameters({ "EK3_POS_I_GATE": 0, - "SIM_GPS_HZ": 1, - "SIM_GPS_LAG_MS": 1000, + "SIM_GPS1_HZ": 1, + "SIM_GPS1_LAG_MS": 1000, }) self.wait_statustext("DCM Active", check_context=True, timeout=60) self.wait_statustext("EKF3 Active", check_context=True) @@ -4471,8 +5223,8 @@ def AerobaticsScripting(self): wipe=True) self.context_push() - self.install_applet_script(applet_script) - self.install_applet_script(airshow, install_name=trick72) + self.install_applet_script_context(applet_script) + self.install_applet_script_context(airshow, install_name=trick72) self.context_collect('STATUSTEXT') self.reboot_sitl() @@ -4518,8 +5270,6 @@ def AerobaticsScripting(self): self.progress("Finished trick, max error=%.1fm" % highest_error) self.disarm_vehicle(force=True) - self.remove_installed_script(applet_script) - self.remove_installed_script(trick72) messages = self.context_collection('STATUSTEXT') self.context_pop() self.reboot_sitl() @@ -4781,8 +5531,8 @@ def MissionJumpTags(self): 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, + "SIM_GPS1_GLTCH_Z": 0, + "SIM_GPS1_ACC": 0.3, }) self.wait_ready_to_arm() @@ -4792,8 +5542,8 @@ def AltResetBadGPS(self): raise NotAchievedException("Bad relative alt %.1f" % relalt) self.progress("Setting low accuracy, glitching GPS") - self.set_parameter("SIM_GPS_ACC", 40) - self.set_parameter("SIM_GPS_GLITCH_Z", -47) + self.set_parameter("SIM_GPS1_ACC", 40) + self.set_parameter("SIM_GPS1_GLTCH_Z", -47) self.progress("Waiting 10s for height update") self.delay_sim_time(10) @@ -4864,6 +5614,8 @@ def RunMissionScript(self): def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self): '''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE''' + self.install_terrain_handlers_context() + self.start_subtest("set home relative altitude") self.takeoff(30, relative=True) self.change_mode('GUIDED') for alt in 50, 70: @@ -4875,6 +5627,7 @@ def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self): self.wait_altitude(alt-1, alt+1, timeout=30, relative=True) # test for #24535 + self.start_subtest("switch to loiter and resume guided maintains home relative altitude") self.change_mode('LOITER') self.delay_sim_time(5) self.change_mode('GUIDED') @@ -4885,6 +5638,55 @@ def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self): timeout=30, relative=True, ) + # test that this works if switching between RELATIVE (HOME) and GLOBAL(AMSL) + self.start_subtest("set global/AMSL altitude, switch to loiter and resume guided") + alt = 625 + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE, + p7=alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL, + ) + self.wait_altitude(alt-3, alt+3, timeout=30, relative=False) + self.change_mode('LOITER') + self.delay_sim_time(5) + self.change_mode('GUIDED') + self.wait_altitude( + alt-5, # NOTE: reuse of alt from above CHANGE_ALTITUDE + alt+5, + minimum_duration=10, + timeout=30, + relative=False, + ) + # test that this works if switching between RELATIVE (HOME) and terrain + self.start_subtest("set terrain altitude, switch to loiter and resume guided") + self.change_mode('GUIDED') + alt = 100 + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE, + p7=alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT, + ) + self.wait_altitude( + alt-5, # NOTE: reuse of alt from abovE + alt+5, # use a 5m buffer as the plane needs to go up and down a bit to maintain terrain distance + minimum_duration=10, + timeout=30, + relative=False, + altitude_source="TERRAIN_REPORT.current_height" + ) + self.change_mode('LOITER') + self.delay_sim_time(5) + self.change_mode('GUIDED') + self.wait_altitude( + alt-5, # NOTE: reuse of alt from abovE + alt+5, # use a 5m buffer as the plane needs to go up and down a bit to maintain terrain distance + minimum_duration=10, + timeout=30, + relative=False, + altitude_source="TERRAIN_REPORT.current_height" + ) + + self.delay_sim_time(5) self.fly_home_land_and_disarm() def _MAV_CMD_PREFLIGHT_CALIBRATION(self, command): @@ -5124,18 +5926,23 @@ def MAV_CMD_NAV_ALTITUDE_WAIT(self): ) ]) + # Set initial conditions for servo wiggle testing + servo_wiggled = {1: False, 2: False, 4: False} + def look_for_wiggle(mav, m): if m.get_type() == 'SERVO_OUTPUT_RAW': # Throttle must be zero if m.servo3_raw != 1000: raise NotAchievedException( "Throttle must be 0 in altitude wait, got %f" % m.servo3_raw) - # Aileron, elevator and rudder must all be the same - # However, aileron is revered, so we must un-reverse it - value = 1500 - (m.servo1_raw - 1500) - if (m.servo2_raw != value) or (m.servo4_raw != value): - raise NotAchievedException( - "Aileron, elevator and rudder must be the same") + + # Check if all servos wiggle + if m.servo1_raw != 1500: + servo_wiggled[1] = True + if m.servo2_raw != 1500: + servo_wiggled[2] = True + if m.servo4_raw != 1500: + servo_wiggled[4] = True # Start mission self.change_mode('AUTO') @@ -5155,6 +5962,10 @@ def look_for_wiggle(mav, m): if not self.mode_is('AUTO'): raise NotAchievedException("Must still be in AUTO") + # Raise error if not all servos have wiggled + if not all(servo_wiggled.values()): + raise NotAchievedException("Not all servos have moved within the test frame") + self.disarm_vehicle() def start_flying_simple_rehome_mission(self, items): @@ -5288,8 +6099,267 @@ def MinThrottle(self): self.drain_mav() self.assert_servo_channel_value(3, servo_min) + def ClimbThrottleSaturation(self): + '''check what happens when throttle is saturated in GUIDED''' + self.set_parameters({ + "TECS_CLMB_MAX": 30, + "TKOFF_ALT": 1000, + }) + + self.change_mode("TAKEOFF") + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_message_field_values('VFR_HUD', { + "throttle": 100, + }, minimum_duration=30, timeout=90) + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def GuidedAttitudeNoGPS(self): + '''test that guided-attitude still works with no GPS''' + self.takeoff(50) + self.change_mode('GUIDED') + self.context_push() + self.set_parameter('SIM_GPS1_ENABLE', 0) + self.delay_sim_time(30) + self.set_attitude_target() + self.context_pop() + self.fly_home_land_and_disarm() + + def ScriptStats(self): + '''test script stats logging''' + self.context_push() + self.set_parameters({ + 'SCR_ENABLE': 1, + 'SCR_DEBUG_OPTS': 8, # runtime memory usage and time + }) + self.install_test_scripts_context([ + "math.lua", + "strings.lua", + ]) + self.install_example_script_context('simple_loop.lua') + self.context_collect('STATUSTEXT') + + self.reboot_sitl() + + self.wait_statustext('hello, world') + delay = 20 + self.delay_sim_time(delay, reason='gather some stats') + self.wait_statustext("math.lua exceeded time limit", check_context=True, timeout=0) + + dfreader = self.dfreader_for_current_onboard_log() + seen_hello_world = False +# runtime = None + while True: + m = dfreader.recv_match(type=['SCR']) + if m is None: + break + if m.Name == "simple_loop.lua": + seen_hello_world = True +# if m.Name == "math.lua": +# runtime = m.Runtime + + if not seen_hello_world: + raise NotAchievedException("Did not see simple_loop.lua script") + +# self.progress(f"math took {runtime} seconds to run over {delay} seconds") +# if runtime == 0: +# raise NotAchievedException("Expected non-zero runtime for math") + + self.context_pop() + self.reboot_sitl() + + def GPSPreArms(self): + '''ensure GPS prearm checks work''' + self.wait_ready_to_arm() + self.start_subtest('DroneCAN sanity checks') + self.set_parameter('GPS1_TYPE', 9) + self.set_parameter('GPS2_TYPE', 9) + self.set_parameter('GPS1_CAN_OVRIDE', 130) + self.set_parameter('GPS2_CAN_OVRIDE', 130) + self.assert_prearm_failure( + "set for multiple GPS", + other_prearm_failures_fatal=False, + ) + + def SetHomeAltChange(self): + '''check modes retain altitude when home alt changed''' + for mode in 'FBWB', 'CRUISE', 'LOITER': + self.wait_ready_to_arm() + home = self.home_position_as_mav_location() + self.takeoff(20) + higher_home = home + higher_home.alt += 40 + self.set_home(higher_home) + self.change_mode(mode) + self.wait_altitude(15, 25, relative=True, minimum_duration=10) + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def SetHomeAltChange2(self): + '''ensure TECS operates predictably as home altitude changes continuously''' + ''' + This can happen when performing a ship landing, where the home + coordinates are continuously set by the ship GNSS RX. + ''' + self.set_parameter('TRIM_THROTTLE', 70) + self.wait_ready_to_arm() + home = self.home_position_as_mav_location() + target_alt = 20 + self.takeoff(target_alt, mode="TAKEOFF") + self.change_mode("LOITER") + self.delay_sim_time(20) # Let the plane settle. + + tstart = self.get_sim_time() + test_time = 10 # Run the test for 10s. + pub_freq = 10 + for i in range(test_time*pub_freq): + tnow = self.get_sim_time() + higher_home = copy.copy(home) + # Produce 1Hz sine waves in home altitude change. + higher_home.alt += 40*math.sin((tnow-tstart)*(2*math.pi)) + self.set_home(higher_home) + if tnow-tstart > test_time: + break + self.delay_sim_time(1.0/pub_freq) + + # Test if the altitude is still within bounds. + self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=1, timeout=2) + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def ForceArm(self): + '''check force-arming functionality''' + self.set_parameter("SIM_GPS1_ENABLE", 0) + # 21196 is the mavlink standard, 2989 is legacy + for magic_value in 21196, 2989: + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, + present=True, + enabled=True, + healthy=False, + ) + self.run_cmd( + mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + p1=1, # ARM + p2=0, + want_result=mavutil.mavlink.MAV_RESULT_FAILED, + ) + self.run_cmd( + mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + p1=1, # ARM + p2=magic_value, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED, + ) + self.disarm_vehicle() + + def _MAV_CMD_EXTERNAL_WIND_ESTIMATE(self, command): + self.reboot_sitl() + + def cmp_with_variance(a, b, p): + return abs(a - b) < p + + def check_eq(speed, direction, ret_dir, timeout=1): + command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=speed, p3=direction) + + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise NotAchievedException( + f"Failed to set wind speed or/and direction: speed != {speed} or direction != {direction}") + + m = self.assert_receive_message("WIND") + if cmp_with_variance(m.speed, speed, 0.5) and cmp_with_variance(m.direction, ret_dir, 5): + return True + + check_eq(1, 45, 45) + check_eq(2, 90, 90) + check_eq(3, 120, 120) + check_eq(4, 180, -180) + check_eq(5, 240, -120) + check_eq(6, 320, -40) + check_eq(7, 360, 0) + + command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=90, want_result=mavutil.mavlink.MAV_RESULT_DENIED) + command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED) + command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED) + command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=2, p3=370, want_result=mavutil.mavlink.MAV_RESULT_DENIED) + + def MAV_CMD_EXTERNAL_WIND_ESTIMATE(self): + '''test MAV_CMD_EXTERNAL_WIND_ESTIMATE as a mavlink command''' + self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd) + self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd_int) + + def GliderPullup(self): + '''test pullup of glider after ALTITUDE_WAIT''' + self.start_subtest("test glider pullup") + + self.customise_SITL_commandline( + [], + model="glider", + defaults_filepath="Tools/autotest/default_params/glider.parm", + wipe=True) + + self.set_parameter('LOG_DISARMED', 1) + + self.set_parameters({ + "PUP_ENABLE": 1, + "SERVO6_FUNCTION": 0, # balloon lift + "SERVO10_FUNCTION": 156, # lift release + "EK3_IMU_MASK": 1, # lane switches just make log harder to read + "AHRS_OPTIONS": 4, # don't disable airspeed based on EKF checks + "ARSPD_OPTIONS": 0, # don't disable airspeed + "ARSPD_WIND_GATE": 0, + }) + + self.set_servo(6, 1000) + + self.load_mission("glider-pullup-mission.txt") + self.change_mode("AUTO") + self.wait_ready_to_arm() + self.arm_vehicle() + self.context_collect('STATUSTEXT') + + self.progress("Start balloon lift") + self.set_servo(6, 2000) + + self.wait_text("Reached altitude", check_context=True, timeout=1000) + self.wait_text("Start pullup airspeed", check_context=True) + self.wait_text("Pullup airspeed", check_context=True) + self.wait_text("Pullup pitch", check_context=True) + self.wait_text("Pullup level", check_context=True) + self.wait_text("Loiter to alt complete", check_context=True, timeout=1000) + self.wait_text("Flare", check_context=True, timeout=400) + self.wait_text("Auto disarmed", check_context=True, timeout=200) + + def BadRollChannelDefined(self): + '''ensure we don't die with a bad Roll channel defined''' + self.set_parameter("RCMAP_ROLL", 17) + + def MAV_CMD_NAV_LOITER_TO_ALT(self): + '''test loiter to alt mission item''' + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 500), + (mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 100), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0), + ]) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_altitude(450, 475, relative=True, timeout=600) + self.wait_altitude(75, 125, relative=True, timeout=600) + self.wait_current_waypoint(4) + self.fly_home_land_and_disarm() + def tests(self): '''return list of all tests''' + ret = [] + ret.extend(self.tests1a()) + ret.extend(self.tests1b()) + return ret + + def tests1a(self): + ret = [] ret = super(AutoTestPlane, self).tests() ret.extend([ self.AuxModeSwitch, @@ -5315,11 +6385,19 @@ def tests(self): self.FenceRTLRally, self.FenceRetRally, self.FenceAltCeilFloor, + self.FenceMinAltAutoEnable, + self.FenceMinAltEnableAutoland, + self.FenceMinAltAutoEnableAbort, + self.FenceAutoEnableDisableSwitch, + Test(self.FenceCircleExclusionAutoEnable, speedup=20), + self.FenceEnableDisableSwitch, + self.FenceEnableDisableAux, self.FenceBreachedChangeMode, self.FenceNoFenceReturnPoint, self.FenceNoFenceReturnPointInclusion, self.FenceDisableUnderAction, - self.ADSB, + self.ADSBFailActionRTL, + self.ADSBResumeActionResumeLoiter, self.SimADSB, self.Button, self.FRSkySPort, @@ -5332,17 +6410,24 @@ def tests(self): self.AdvancedFailsafe, self.LOITER, self.MAV_CMD_NAV_LOITER_TURNS, + self.MAV_CMD_NAV_LOITER_TO_ALT, self.DeepStall, self.WatchdogHome, self.LargeMissions, self.Soaring, self.Terrain, self.TerrainMission, + ]) + return ret + + def tests1b(self): + return [ self.TerrainLoiter, self.VectorNavEAHRS, self.MicroStrainEAHRS5, self.MicroStrainEAHRS7, self.InertialLabsEAHRS, + self.GpsSensorPreArmEAHRS, self.Deadreckoning, self.DeadreckoningNoAirSpeed, self.EKFlaneswitch, @@ -5357,6 +6442,16 @@ def tests(self): self.AHRS_ORIENTATION, self.AHRSTrim, self.LandingDrift, + self.TakeoffAuto1, + self.TakeoffAuto2, + self.TakeoffAuto3, + self.TakeoffAuto4, + self.TakeoffTakeoff1, + self.TakeoffTakeoff2, + self.TakeoffTakeoff3, + self.TakeoffTakeoff4, + self.TakeoffGround, + self.TakeoffIdleThrottle, self.ForcedDCM, self.DCMFallback, self.MAVFTP, @@ -5396,11 +6491,32 @@ def tests(self): self.MAV_CMD_NAV_LOITER_UNLIM, self.MAV_CMD_NAV_RETURN_TO_LAUNCH, self.MinThrottle, - ]) - return ret + self.ClimbThrottleSaturation, + self.GuidedAttitudeNoGPS, + self.ScriptStats, + self.GPSPreArms, + self.SetHomeAltChange, + self.SetHomeAltChange2, + self.ForceArm, + self.MAV_CMD_EXTERNAL_WIND_ESTIMATE, + self.GliderPullup, + self.BadRollChannelDefined, + ] def disabled_tests(self): return { "LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", "InteractTest": "requires user interaction", + "ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass", + "SetHomeAltChange": "https://github.com/ArduPilot/ardupilot/issues/5672", } + + +class AutoTestPlaneTests1a(AutoTestPlane): + def tests(self): + return self.tests1a() + + +class AutoTestPlaneTests1b(AutoTestPlane): + def tests(self): + return self.tests1b() diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index bca38d192b90c9..309c22b8c48d27 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -36,6 +36,22 @@ class Joystick(): Lateral = 6 +# Values for EK3_MAG_CAL +class MagCal(): + WHEN_FLYING = 0 + WHEN_MANOEUVRING = 1 + NEVER = 2 + AFTER_FIRST_CLIMB = 3 + ALWAYS = 4 + + +# Values for XKFS.MAG_FUSION +class MagFuseSel(): + NOT_FUSING = 0 + FUSE_YAW = 1 + FUSE_MAG = 2 + + class AutoTestSub(vehicle_test_suite.TestSuite): @staticmethod def get_not_armable_mode_list(): @@ -271,7 +287,7 @@ def Surftrak(self): self.disarm_vehicle() self.context_pop() - def prepare_synthetic_seafloor_test(self, sea_floor_depth): + def prepare_synthetic_seafloor_test(self, sea_floor_depth, rf_target): self.set_parameters({ "SCR_ENABLE": 1, "RNGFND1_TYPE": 36, @@ -281,6 +297,7 @@ def prepare_synthetic_seafloor_test(self, sea_floor_depth): "SCR_USER1": 2, # Configuration bundle "SCR_USER2": sea_floor_depth, # Depth in meters "SCR_USER3": 101, # Output log records + "SCR_USER4": rf_target, # Rangefinder target in meters }) self.install_example_script_context("sub_test_synthetic_seafloor.lua") @@ -343,7 +360,7 @@ def SimTerrainSurftrak(self): validation_delta = 1.5 # Largest allowed distance between sub height and desired height self.context_push() - self.prepare_synthetic_seafloor_test(sea_floor_depth) + self.prepare_synthetic_seafloor_test(sea_floor_depth, match_distance) self.change_mode('MANUAL') self.arm_vehicle() @@ -374,7 +391,7 @@ def SimTerrainSurftrak(self): self.set_rc(Joystick.Forward, 1650) self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=60) - # The mission ends at end_altitude. Do a check to insure that the sub is at this altitude + # The mission ends at end_altitude. Do a check to ensure that the sub is at this altitude self.wait_altitude(altitude_min=end_altitude-validation_delta/2, altitude_max=end_altitude+validation_delta/2, relative=False, timeout=1) @@ -382,6 +399,7 @@ def SimTerrainSurftrak(self): self.disarm_vehicle() self.context_pop() + self.reboot_sitl() # e.g. revert rangefinder configuration def SimTerrainMission(self): """Mission at a constant height above synthetic sea floor""" @@ -393,7 +411,7 @@ def SimTerrainMission(self): validation_delta = 1.5 # Largest allowed distance between sub height and desired height self.context_push() - self.prepare_synthetic_seafloor_test(sea_floor_depth) + self.prepare_synthetic_seafloor_test(sea_floor_depth, match_distance) # The synthetic seafloor has an east-west ridge south of the sub. # The mission contained in terrain_mission.txt instructs the sub @@ -415,12 +433,13 @@ def SimTerrainMission(self): self.change_mode('AUTO') self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=500.0, final_waypoint=4) - # The mission ends at end_altitude. Do a check to insure that the sub is at this altitude. + # The mission ends at end_altitude. Do a check to ensure that the sub is at this altitude. self.wait_altitude(altitude_min=end_altitude-validation_delta/2, altitude_max=end_altitude+validation_delta/2, relative=False, timeout=1) self.disarm_vehicle() self.context_pop() + self.reboot_sitl() # e.g. revert rangefinder configuration def ModeChanges(self, delta=0.2): """Check if alternating between ALTHOLD, STABILIZE, POSHOLD and SURFTRAK (mode 21) affects altitude""" @@ -662,7 +681,7 @@ def MAV_CMD_NAV_LAND(self): self.assert_mode('SURFACE') def MAV_CMD_MISSION_START(self): - '''test handling of MAV_CMD_NAV_LAND received via mavlink''' + '''test handling of MAV_CMD_MISSION_START received via mavlink''' self.upload_simple_relhome_mission([ (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0), (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), @@ -737,6 +756,35 @@ def MAV_CMD_CONDITION_YAW(self): self._MAV_CMD_CONDITION_YAW(self.run_cmd) self._MAV_CMD_CONDITION_YAW(self.run_cmd_int) + def MAV_CMD_DO_REPOSITION(self): + """Move vehicle using MAV_CMD_DO_REPOSITION""" + self.wait_ready_to_arm() + self.arm_vehicle() + + # Dive so that rangefinder is in range, required for MAV_FRAME_GLOBAL_TERRAIN_ALT + start_altitude = -25 + pwm = 1300 if self.get_altitude(relative=True) > start_altitude else 1700 + self.set_rc(Joystick.Throttle, pwm) + self.wait_altitude(altitude_min=start_altitude-1, altitude_max=start_altitude, relative=False, timeout=120) + self.set_rc(Joystick.Throttle, 1500) + self.change_mode('GUIDED') + + loc = self.mav.location() + + # Reposition, alt relative to surface + loc = self.offset_location_ne(loc, 10, 10) + loc.alt = start_altitude + self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT) + self.wait_location(loc, timeout=120) + + # Reposition, alt relative to seafloor + loc = self.offset_location_ne(loc, 10, 10) + loc.alt = -start_altitude + self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) + self.wait_location(loc, timeout=120) + + self.disarm_vehicle() + def TerrainMission(self): """Mission using surface tracking""" @@ -819,6 +867,86 @@ def SetGlobalOrigin(self): # restart GPS driver self.reboot_sitl() + def BackupOrigin(self): + """Test ORIGIN_LAT and ORIGIN_LON parameters""" + + self.context_push() + self.set_parameters({ + 'GPS1_TYPE': 0, # Disable GPS + 'EK3_SRC1_POSXY': 0, # Make sure EK3_SRC parameters do not refer to GPS + 'EK3_SRC1_VELXY': 0, # Make sure EK3_SRC parameters do not refer to GPS + 'ORIGIN_LAT': 47.607584, + 'ORIGIN_LON': -122.343911, + }) + self.reboot_sitl() + self.context_collect('STATUSTEXT') + + # Wait for the EKF to be happy in constant position mode + self.wait_ready_to_arm_const_pos() + + if self.current_onboard_log_contains_message('ORGN'): + raise NotAchievedException("Found unexpected ORGN message") + + # This should set the origin and write a record to ORGN + self.arm_vehicle() + + self.wait_statustext('Using backup location', check_context=True) + + if not self.current_onboard_log_contains_message('ORGN'): + raise NotAchievedException("Did not find expected ORGN message") + + self.disarm_vehicle() + self.context_pop() + + def assert_mag_fusion_selection(self, expect_sel): + """Get the most recent XKFS message and check the MAG_FUSION value""" + self.progress("Expect mag fusion selection %d" % expect_sel) + mlog = self.dfreader_for_current_onboard_log() + found_sel = MagFuseSel.NOT_FUSING + while True: + m = mlog.recv_match(type='XKFS') + if m is None: + break + found_sel = m.MAG_FUSION + if found_sel != expect_sel: + raise NotAchievedException("Expected mag fusion selection %d, found %d" % (expect_sel, found_sel)) + + def FuseMag(self): + """Test EK3_MAG_CAL values""" + + # WHEN_FLYING: switch to FUSE_MAG after sub is armed for 5 seconds; switch to FUSE_YAW on disarm + self.set_parameters({'EK3_MAG_CAL': MagCal.WHEN_FLYING}) + self.reboot_sitl() + self.wait_ready_to_arm() + self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW) + self.arm_vehicle() + self.delay_sim_time(10) + self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG) + self.disarm_vehicle() + self.delay_sim_time(1) + self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW) + + # AFTER_FIRST_CLIMB: switch to FUSE_MAG after sub is armed and descends 0.5m; switch to FUSE_YAW on disarm + self.set_parameters({'EK3_MAG_CAL': MagCal.AFTER_FIRST_CLIMB}) + self.reboot_sitl() + self.wait_ready_to_arm() + self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW) + altitude = self.get_altitude(relative=True) + self.arm_vehicle() + self.set_rc(Joystick.Throttle, 1300) + self.wait_altitude(altitude_min=altitude-4, altitude_max=altitude-3, relative=False, timeout=60) + self.set_rc(Joystick.Throttle, 1500) + self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG) + self.disarm_vehicle() + self.delay_sim_time(1) + self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW) + + # ALWAYS + self.set_parameters({'EK3_MAG_CAL': MagCal.ALWAYS}) + self.reboot_sitl() + self.wait_ready_to_arm() + self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG) + def tests(self): '''return list of all tests''' ret = super(AutoTestSub, self).tests() @@ -839,13 +967,17 @@ def tests(self): self.SET_POSITION_TARGET_GLOBAL_INT, self.TestLogDownloadMAVProxy, self.TestLogDownloadMAVProxyNetwork, + self.TestLogDownloadLogRestart, self.MAV_CMD_NAV_LOITER_UNLIM, self.MAV_CMD_NAV_LAND, self.MAV_CMD_MISSION_START, self.MAV_CMD_DO_CHANGE_SPEED, self.MAV_CMD_CONDITION_YAW, + self.MAV_CMD_DO_REPOSITION, self.TerrainMission, self.SetGlobalOrigin, + self.BackupOrigin, + self.FuseMag, ]) return ret diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 52bb3aac1e95e2..296c930d4faf7e 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -278,6 +278,9 @@ def should_run_step(step): "CopterTests2b": "arducopter", "Plane": "arduplane", + "PlaneTests1a": "arduplane", + "PlaneTests1b": "arduplane", + "Rover": "ardurover", "Tracker": "antennatracker", "Helicopter": "arducopter-heli", @@ -287,7 +290,9 @@ def should_run_step(step): "BalanceBot": "ardurover", "Sailboat": "ardurover", "SITLPeriphUniversal": ("sitl_periph_universal", "AP_Periph"), + "SITLPeriphBattMon": ("sitl_periph_battmon", "AP_Periph"), "CAN": "arducopter", + "BattCAN": "arducopter", } @@ -350,6 +355,8 @@ def find_specific_test_to_run(step): "test.CopterTests2a": arducopter.AutoTestCopterTests2a, # 8m23s "test.CopterTests2b": arducopter.AutoTestCopterTests2b, # 8m18s "test.Plane": arduplane.AutoTestPlane, + "test.PlaneTests1a": arduplane.AutoTestPlaneTests1a, + "test.PlaneTests1b": arduplane.AutoTestPlaneTests1b, "test.QuadPlane": quadplane.AutoTestQuadPlane, "test.Rover": rover.AutoTestRover, "test.BalanceBot": balancebot.AutoTestBalanceBot, @@ -358,11 +365,15 @@ def find_specific_test_to_run(step): "test.Sub": ardusub.AutoTestSub, "test.Tracker": antennatracker.AutoTestTracker, "test.CAN": arducopter.AutoTestCAN, + "test.BattCAN": arducopter.AutoTestBattCAN, } supplementary_test_binary_map = { "test.CAN": ["sitl_periph_universal:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 "sitl_periph_universal:AP_Periph:1:Tools/autotest/default_params/periph.parm"], + "test.BattCAN": [ + "sitl_periph_battmon:AP_Periph:0:Tools/autotest/default_params/periph-battmon.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 + ], } @@ -445,6 +456,10 @@ def run_step(step): vehicle_binary = 'bin/AP_Periph' board = 'sitl_periph_universal' + if step == 'build.SITLPeriphBattMon': + vehicle_binary = 'bin/AP_Periph' + board = 'sitl_periph_battmon' + if step == 'build.Replay': return util.build_replay(board='SITL') @@ -497,7 +512,6 @@ def run_step(step): "gdbserver": opts.gdbserver, "breakpoints": opts.breakpoint, "disable_breakpoints": opts.disable_breakpoints, - "frame": opts.frame, "_show_test_timings": opts.show_test_timings, "force_ahrs_type": opts.force_ahrs_type, "num_aux_imus" : opts.num_aux_imus, @@ -507,6 +521,7 @@ def run_step(step): "reset_after_every_test": opts.reset_after_every_test, "build_opts": copy.copy(build_opts), "generate_junit": opts.junit, + "enable_fgview": opts.enable_fgview, } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup @@ -853,6 +868,9 @@ def format_epilog(self, formatter): parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to') + parser.add_option("--enable-fgview", + action='store_true', + help="Enable FlightGear output") parser.add_option("--map", action='store_true', default=False, @@ -865,10 +883,6 @@ def format_epilog(self, formatter): default=None, type='int', help='maximum runtime in seconds') - parser.add_option("--frame", - type='string', - default=None, - help='specify frame type') parser.add_option("--show-test-timings", action="store_true", default=False, @@ -1086,6 +1100,9 @@ def format_epilog(self, formatter): 'build.SITLPeriphUniversal', 'test.CAN', + 'build.SITLPeriphBattMon', + 'test.BattCAN', + # convertgps disabled as it takes 5 hours # 'convertgpx', ] @@ -1100,6 +1117,9 @@ def format_epilog(self, formatter): 'test.CopterTests2a', 'test.CopterTests2b', + 'test.PlaneTests1a', + 'test.PlaneTests1b', + 'clang-scan-build', ] diff --git a/Tools/autotest/bisect-helper.py b/Tools/autotest/bisect-helper.py index 3858a53fb6b3a8..90f74dec69ed1a 100755 --- a/Tools/autotest/bisect-helper.py +++ b/Tools/autotest/bisect-helper.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 '''A helper script for bisecting common problems when working with ArduPilot diff --git a/Tools/autotest/default_params/airsim-quadX.parm b/Tools/autotest/default_params/airsim-quadX.parm index a8987896f8a847..c0636c5205c37a 100644 --- a/Tools/autotest/default_params/airsim-quadX.parm +++ b/Tools/autotest/default_params/airsim-quadX.parm @@ -18,7 +18,7 @@ WPNAV_SPEED_DN 300 WPNAV_SPEED 2000 RTL_ALT 2500 ANGLE_MAX 3000 -SIM_GPS_LAG_MS 0 +SIM_GPS1_LAG_MS 0 GPS_DELAY_MS 20 INS_GYRO_FILTER 50 INS_ACCEL_FILTER 50 diff --git a/Tools/autotest/default_params/blimp.parm b/Tools/autotest/default_params/blimp.parm index a790eec33454f5..0eeca63cef7890 100644 --- a/Tools/autotest/default_params/blimp.parm +++ b/Tools/autotest/default_params/blimp.parm @@ -1,7 +1,4 @@ -ARSPD_PIN 1 -ARSPD_BUS 2 EK2_ENABLE 1 -FRAME_TYPE 0 FS_THR_ENABLE 1 BATT_MONITOR 4 COMPASS_OFS_X 5 diff --git a/Tools/autotest/default_params/copter-X.parm b/Tools/autotest/default_params/copter-X.parm index ee06ded19b212e..06081beef07ee9 100644 --- a/Tools/autotest/default_params/copter-X.parm +++ b/Tools/autotest/default_params/copter-X.parm @@ -1,3 +1 @@ -FRAME_CLASS 1 FRAME_TYPE 1 - diff --git a/Tools/autotest/default_params/copter-gps-for-yaw-nmea.parm b/Tools/autotest/default_params/copter-gps-for-yaw-nmea.parm index 41af6fa868b915..6ec6add79623ff 100644 --- a/Tools/autotest/default_params/copter-gps-for-yaw-nmea.parm +++ b/Tools/autotest/default_params/copter-gps-for-yaw-nmea.parm @@ -1,5 +1,5 @@ # SITL GPS-for-yaw using a single simulated NMEA GPS EK3_SRC1_YAW 2 GPS1_TYPE 5 -SIM_GPS_TYPE 5 -SIM_GPS_HDG 1 +SIM_GPS1_TYPE 5 +SIM_GPS1_HDG 1 diff --git a/Tools/autotest/default_params/copter-gps-for-yaw.parm b/Tools/autotest/default_params/copter-gps-for-yaw.parm index 231fb84e8ecece..1e54532f4f6b13 100644 --- a/Tools/autotest/default_params/copter-gps-for-yaw.parm +++ b/Tools/autotest/default_params/copter-gps-for-yaw.parm @@ -5,7 +5,8 @@ GPS1_TYPE 17 GPS2_TYPE 18 GPS1_POS_Y -0.2 GPS2_POS_Y 0.2 -SIM_GPS_POS_Y -0.2 +SIM_GPS1_POS_Y -0.2 SIM_GPS2_POS_Y 0.2 -SIM_GPS2_DISABLE 0 +SIM_GPS2_ENABLE 1 SIM_GPS2_HDG 1 +SIM_GPS1_HDG 4 diff --git a/Tools/autotest/default_params/copter-heli-dual.parm b/Tools/autotest/default_params/copter-heli-dual.parm index 5b5e58adda58a6..38d6818e41377a 100644 --- a/Tools/autotest/default_params/copter-heli-dual.parm +++ b/Tools/autotest/default_params/copter-heli-dual.parm @@ -1,9 +1,9 @@ FRAME_CLASS 11 ATC_ANG_PIT_P 4.5 ATC_ANG_YAW_P 4.5 -ATC_RAT_PIT_D 0.0005 -ATC_RAT_PIT_P 0.02 -ATC_RAT_PIT_FF 0.0 +ATC_RAT_PIT_D 0.005 +ATC_RAT_PIT_P 0.15 +ATC_RAT_PIT_FF 0.44 ATC_RAT_YAW_D 0.0015 ATC_RAT_YAW_P 0.14685 ATC_HOVR_ROL_TRM 0 diff --git a/Tools/autotest/default_params/glider.parm b/Tools/autotest/default_params/glider.parm new file mode 100644 index 00000000000000..a64d9686edb83a --- /dev/null +++ b/Tools/autotest/default_params/glider.parm @@ -0,0 +1,89 @@ + +THR_MAX 0 +THR_FAILSAFE 2 +STALL_PREVENTION 0 +RTL_RADIUS 175 +WP_RADIUS 90 +KFF_RDDRMIX 0.07 + +# fixed wing tuning +PTCH_LIM_MAX_DEG 10 +PTCH_LIM_MIN_DEG -15 +ROLL_LIMIT_DEG 30 + +RLL_RATE_FF 0.6 +RLL_RATE_P 0.5 +RLL_RATE_I 0.14 +RLL_RATE_D 0.01 +RLL_RATE_IMAX 0.67 +RLL2SRV_TCONST 0.7 +RLL2SRV_RMAX 30 + +PTCH_RATE_FF 0.5 +PTCH_RATE_P 0.3 +PTCH_RATE_I 0.9 +PTCH_RATE_D 0.01 +PTCH_RATE_IMAX 0.67 +PTCH2SRV_TCONST 0.45 +PTCH2SRV_RMAX_UP 75 +PTCH2SRV_RMAX_DN 75 + +AIRSPEED_CRUISE 38 +AIRSPEED_MIN 17 +AIRSPEED_MAX 45 +ARSPD_USE 1 + +HOME_RESET_ALT -1 + +TECS_INTEG_GAIN 0.25 +TECS_SPDWEIGHT 1.7 # allow some altitude control +TECS_PTCH_DAMP 0.6 +TECS_SINK_MAX 8.5 +TECS_PITCH_MAX 10 +TECS_PITCH_MIN -15 +TECS_OPTIONS 3 +TECS_PTCH_FF_V0 25 +TECS_HDEM_TCONST 2 + +NAVL1_PERIOD 20 +NAVL1_LIM_BANK 30 + +SCHED_LOOP_RATE 200 + +WP_LOITER_RAD 230 + +CHUTE_ENABLED 1.000000 +CHUTE_TYPE 10.000000 +CHUTE_SERVO_ON 1900.000000 +CHUTE_OPTIONS 1.000000 + +INS_ACCSCAL_X 1.001000 +INS_ACCSCAL_Y 1.001000 +INS_ACCSCAL_Z 1.001000 +INS_ACCOFFS_X 0.001000 +INS_ACCOFFS_Y 0.001000 +INS_ACCOFFS_Z 0.001000 +INS_ACC2SCAL_X 1.001000 +INS_ACC2SCAL_Y 1.001000 +INS_ACC2SCAL_Z 1.001000 +INS_ACC2OFFS_X 0.001000 +INS_ACC2OFFS_Y 0.001000 +INS_ACC2OFFS_Z 0.001000 + +SIM_SERVO_SPEED 0.110000 +SIM_SERVO_DELAY 0.010000 +SIM_SERVO_FILTER 10 + +SIM_GLD_BLN_BRST 50000 + +SERVO1_MIN 1000 +SERVO1_MAX 2000 +SERVO1_FUNCTION 0 +SERVO2_FUNCTION 4 +SERVO3_TRIM 1460.000000 +SERVO3_REVERSED 1 +SERVO3_FUNCTION 19 +SERVO4_REVERSED 1 +SERVO5_FUNCTION 4 +SERVO6_FUNCTION 56 +SERVO9_FUNCTION 27 diff --git a/Tools/autotest/default_params/plane-ice.parm b/Tools/autotest/default_params/plane-ice.parm index 28b135b98e2b99..e6cb59cad0102c 100644 --- a/Tools/autotest/default_params/plane-ice.parm +++ b/Tools/autotest/default_params/plane-ice.parm @@ -2,6 +2,6 @@ ICE_ENABLE 1 ICE_RPM_CHAN 1 SERVO13_FUNCTION 67 SERVO14_FUNCTION 69 -ICE_START_CHAN 7 +RC11_OPTION 179 RPM1_TYPE 10 SERVO3_REVERSED 1 diff --git a/Tools/autotest/default_params/quadplane-cl84.parm b/Tools/autotest/default_params/quadplane-cl84.parm index fee738bef83beb..500a34e5b4d5b1 100644 --- a/Tools/autotest/default_params/quadplane-cl84.parm +++ b/Tools/autotest/default_params/quadplane-cl84.parm @@ -1,7 +1,6 @@ Q_FRAME_CLASS 7 Q_TILT_ENABLE 1 Q_TILT_MASK 3 -Q_TILT_RATE 13 Q_TILT_TYPE 1 # 7 seconds to move servo diff --git a/Tools/autotest/default_params/quadplane-copter_tailsitter.parm b/Tools/autotest/default_params/quadplane-copter_tailsitter.parm index 6cafdcb50c220c..a936774c6ce33b 100644 --- a/Tools/autotest/default_params/quadplane-copter_tailsitter.parm +++ b/Tools/autotest/default_params/quadplane-copter_tailsitter.parm @@ -17,21 +17,31 @@ Q_A_RATE_R_MAX 0.000000 Q_A_RATE_Y_MAX 0.000000 Q_A_RAT_PIT_D 0.004973 Q_A_RAT_PIT_FF 0.000000 -Q_A_RAT_PIT_FILT 10.000000 Q_A_RAT_PIT_I 0.528246 Q_A_RAT_PIT_IMAX 0.500000 Q_A_RAT_PIT_P 0.528246 Q_A_RAT_RLL_D 0.001000 Q_A_RAT_RLL_FF 0.000000 -Q_A_RAT_RLL_FILT 10.000000 Q_A_RAT_RLL_I 0.541613 Q_A_RAT_RLL_IMAX 0.500000 Q_A_RAT_RLL_P 0.541613 Q_A_RAT_YAW_D 0.000000 Q_A_RAT_YAW_FF 0.000000 -Q_A_RAT_YAW_FILT 1.073194 Q_A_RAT_YAW_I 0.039192 Q_A_RAT_YAW_IMAX 0.500000 Q_A_RAT_YAW_P 0.391919 -Q_TAILSIT_THSCMX 1.5 Q_TRANS_DECEL 8 + +# setup rangefinder for tailsitter +SIM_SONAR_ROT 4 +SIM_SONAR_SCALE 10 +RNGFND1_TYPE 100 +RNGFND1_PIN 0 +RNGFND1_SCALING 10 +RNGFND1_MIN_CM 10 +RNGFND1_MAX_CM 5000 +RNGFND1_ORIENT 12 +RNGFND_LANDING 1 +RNGFND_LND_ORNT 12 + + diff --git a/Tools/autotest/default_params/quadplane.parm b/Tools/autotest/default_params/quadplane.parm index 62c5225d052d52..9da3368889f2f4 100644 --- a/Tools/autotest/default_params/quadplane.parm +++ b/Tools/autotest/default_params/quadplane.parm @@ -70,10 +70,16 @@ Q_M_PWM_MIN 1000 Q_M_PWM_MAX 2000 Q_M_BAT_VOLT_MAX 12.8 Q_M_BAT_VOLT_MIN 9.6 -Q_A_RAT_RLL_P 0.15 -Q_A_RAT_PIT_P 0.15 -Q_A_RAT_RLL_D 0.002 -Q_A_RAT_PIT_D 0.002 +Q_A_RAT_RLL_P 0.108 +Q_A_RAT_RLL_I 0.108 +Q_A_RAT_RLL_D 0.001 +Q_A_RAT_PIT_P 0.103 +Q_A_RAT_PIT_I 0.103 +Q_A_RAT_PIT_D 0.001 +Q_A_RAT_YAW_P 0.2 +Q_A_RAT_YAW_P 0.02 +Q_A_ANG_RLL_P 6 +Q_A_ANG_PIT_P 6 RTL_ALTITUDE 20.00 PTCH_RATE_FF 1.407055 RLL_RATE_FF 0.552741 diff --git a/Tools/autotest/default_params/rover-omni3mecanum.parm b/Tools/autotest/default_params/rover-omni3mecanum.parm new file mode 100644 index 00000000000000..3b5bfb1feb9fa8 --- /dev/null +++ b/Tools/autotest/default_params/rover-omni3mecanum.parm @@ -0,0 +1,25 @@ +ACRO_TURN_RATE 300.000000 +ATC_SPEED_P 0.200000 +ATC_SPEED_D 0.000010 +ATC_STR_RAT_D 0.000010 +ATC_STR_RAT_FF 0.100000 +ATC_STR_RAT_I 0.010000 +ATC_STR_RAT_MAX 360.000000 +ATC_STR_RAT_P 0.030000 +CRUISE_SPEED 1.0 +CRUISE_THROTTLE 42.0 +FRAME_TYPE 4 +PSC_VEL_P 0.500000 +RC2_MAX 2000 +RC2_MIN 1000 +RC4_MAX 2000 +RC4_MIN 1000 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO2_MAX 2000 +SERVO2_MIN 1000 +SERVO3_FUNCTION 35 +WP_PIVOT_RATE 120.0 +WP_SPEED 1.0 + + diff --git a/Tools/autotest/default_params/stratoblimp.parm b/Tools/autotest/default_params/stratoblimp.parm new file mode 100644 index 00000000000000..a055cddb0aa333 --- /dev/null +++ b/Tools/autotest/default_params/stratoblimp.parm @@ -0,0 +1,46 @@ +# parameters for default StratoBlimp +SERVO1_FUNCTION 19 +SERVO2_FUNCTION 19 + +SERVO3_FUNCTION 73 +SERVO3_MIN 1000 +SERVO3_MAX 2000 + +SERVO4_FUNCTION 74 +SERVO4_MIN 1000 +SERVO4_MAX 2000 + +# no need for high loop rate +SIM_RATE_HZ 100 + +# avoid IMU cal +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 +INS_ACC3OFFS_X 0.000 +INS_ACC3OFFS_Y 0.000 +INS_ACC3OFFS_Z 0.000 +INS_ACC3SCAL_X 1.000 +INS_ACC3SCAL_Y 1.000 +INS_ACC3SCAL_Z 1.000 + +# crude rudder control +RUDD_DT_GAIN 100 +NAVL1_PERIOD 35 + +RLL_RATE_I 0 +RLL_RATE_D 0 +RLL_RATE_FF 0.03 +ROLL_LIMIT_DEG 5 +PTCH_LIMIT_MAX_DEG 5 +PTCH_LIMIT_MIN_DEG -5 + diff --git a/Tools/autotest/default_params/tracker-gps-for-yaw.parm b/Tools/autotest/default_params/tracker-gps-for-yaw.parm index 231fb84e8ecece..1e54532f4f6b13 100644 --- a/Tools/autotest/default_params/tracker-gps-for-yaw.parm +++ b/Tools/autotest/default_params/tracker-gps-for-yaw.parm @@ -5,7 +5,8 @@ GPS1_TYPE 17 GPS2_TYPE 18 GPS1_POS_Y -0.2 GPS2_POS_Y 0.2 -SIM_GPS_POS_Y -0.2 +SIM_GPS1_POS_Y -0.2 SIM_GPS2_POS_Y 0.2 -SIM_GPS2_DISABLE 0 +SIM_GPS2_ENABLE 1 SIM_GPS2_HDG 1 +SIM_GPS1_HDG 4 diff --git a/Tools/autotest/default_params/vee-gull_005.param b/Tools/autotest/default_params/vee-gull_005.param index 7a2e5bf48474dc..ab340c7eaf020c 100644 --- a/Tools/autotest/default_params/vee-gull_005.param +++ b/Tools/autotest/default_params/vee-gull_005.param @@ -628,19 +628,12 @@ SIM_FLOW_POS_X,0 SIM_FLOW_POS_Y,0 SIM_FLOW_POS_Z,0 SIM_FLOW_RATE,10 -SIM_GP2_GLITCH_X,0 -SIM_GP2_GLITCH_Y,0 -SIM_GP2_GLITCH_Z,0 -SIM_GPS_BYTELOSS,0 -SIM_GPS_DISABLE,0 -SIM_GPS_DRIFTALT,0 -SIM_GPS_GLITCH_X,0 -SIM_GPS_GLITCH_Y,0 -SIM_GPS_GLITCH_Z,0 -SIM_GPS_HZ,5 -SIM_GPS_NOISE,0 -SIM_GPS_NUMSATS,10 -SIM_GPS_TYPE,1 +SIM_GPS1_BYTELOSS,0 +SIM_GPS1_DRIFTALT,0 +SIM_GPS1_HZ,5 +SIM_GPS1_NOISE,0 +SIM_GPS1_NUMSATS,10 +SIM_GPS1_TYPE,1 SIM_GPS2_ENABLE,0 SIM_IMU_POS_X,0 SIM_IMU_POS_Y,0 diff --git a/Tools/autotest/fg_plane_view.sh b/Tools/autotest/fg_plane_view.sh index 88bdd31a9e536a..0ba7c9fe097020 100755 --- a/Tools/autotest/fg_plane_view.sh +++ b/Tools/autotest/fg_plane_view.sh @@ -7,7 +7,7 @@ nice fgfs \ --fdm=external \ --aircraft=Rascal110-JSBSim \ --fg-aircraft="$AUTOTESTDIR/aircraft" \ - --airport=YKRY \ + --airport=KSFO \ --geometry=650x550 \ --bpp=32 \ --disable-hud-3d \ diff --git a/Tools/autotest/fg_quad_view.sh b/Tools/autotest/fg_quad_view.sh index 3a1b52ad5bc443..d93b21306b1adf 100755 --- a/Tools/autotest/fg_quad_view.sh +++ b/Tools/autotest/fg_quad_view.sh @@ -7,7 +7,7 @@ nice fgfs \ --fdm=external \ --aircraft=arducopter \ --fg-aircraft="$AUTOTESTDIR/aircraft" \ - --airport=YKRY \ + --airport=KSFO \ --geometry=650x550 \ --bpp=32 \ --disable-hud-3d \ diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 0da15f1c91e4f1..c02608dbb2e3e5 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -15,6 +15,7 @@ from pysim import vehicleinfo import copy +import operator class AutoTestHelicopter(AutoTestCopter): @@ -91,7 +92,6 @@ def RotorRunup(self): raise NotAchievedException("Takeoff initiated before runup time complete %u" % runup_time) self.progress("Runup time %u" % runup_time) self.zero_throttle() - self.set_rc(8, 1000) self.land_and_disarm() self.mav.wait_heartbeat() @@ -199,25 +199,25 @@ def FlyEachFrame(self): if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def governortest(self): '''Test Heli Internal Throttle Curve and Governor''' self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('heli-gas')), ], + [], + defaults_filepath=self.model_defaults_filepath('heli-gas'), model="heli-gas", wipe=True, ) self.set_parameter("H_RSC_MODE", 4) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def hover(self): self.progress("Setting hover collective") @@ -225,103 +225,67 @@ def hover(self): def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" - self.context_push() - - ex = None - try: - self.set_parameter("PILOT_TKOFF_ALT", 700) - self.change_mode('POSHOLD') - self.zero_throttle() - self.set_rc(8, 1000) - self.wait_ready_to_arm() - # Arm - self.arm_vehicle() - self.progress("Raising rotor speed") - self.set_rc(8, 2000) - self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1659, timeout=10) - self.delay_sim_time(20) - # check we are still on the ground... - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - max_relalt_mm = 1000 - if abs(m.relative_alt) > max_relalt_mm: - raise NotAchievedException("Took off prematurely (abs(%f)>%f)" % - (m.relative_alt, max_relalt_mm)) - - self.progress("Pushing collective past half-way") - self.set_rc(3, 1600) - self.delay_sim_time(0.5) - self.hover() - - # make sure we haven't already reached alt: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - max_initial_alt = 1500 - if abs(m.relative_alt) > max_initial_alt: - raise NotAchievedException("Took off too fast (%f > %f" % - (abs(m.relative_alt), max_initial_alt)) - - self.progress("Monitoring takeoff-to-alt") - self.wait_altitude(6.9, 8, relative=True) - - self.progress("Making sure we stop at our takeoff altitude") - tstart = self.get_sim_time() - while self.get_sim_time() - tstart < 5: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - delta = abs(7000 - m.relative_alt) - self.progress("alt=%f delta=%f" % (m.relative_alt/1000, - delta/1000)) - if delta > 1000: - raise NotAchievedException("Failed to maintain takeoff alt") - self.progress("takeoff OK") - except Exception as e: - self.print_exception_caught(e) - ex = e - - self.land_and_disarm() + self.set_parameter("PILOT_TKOFF_ALT", 700) + self.change_mode('POSHOLD') + self.zero_throttle() self.set_rc(8, 1000) + self.wait_ready_to_arm() + # Arm + self.arm_vehicle() + self.progress("Raising rotor speed") + self.set_rc(8, 2000) + self.progress("wait for rotor runup to complete") + self.wait_servo_channel_value(8, 1659, timeout=10) + self.delay_sim_time(20) + # check we are still on the ground... + max_relalt = 1 # metres + relative_alt = self.get_altitude(relative=True) + if abs(relative_alt) > max_relalt: + raise NotAchievedException("Took off prematurely (abs(%f)>%f)" % + (relative_alt, max_relalt)) + + self.progress("Pushing collective past half-way") + self.set_rc(3, 1600) + self.delay_sim_time(0.5) + self.hover() - self.context_pop() + # make sure we haven't already reached alt: + relative_alt = self.get_altitude(relative=True) + max_initial_alt = 1.5 # metres + if abs(relative_alt) > max_initial_alt: + raise NotAchievedException("Took off too fast (%f > %f" % + (abs(relative_alt), max_initial_alt)) + + self.progress("Monitoring takeoff-to-alt") + self.wait_altitude(6, 8, relative=True, minimum_duration=5) + self.progress("takeoff OK") - if ex is not None: - raise ex + self.land_and_disarm() def StabilizeTakeOff(self): """Fly stabilize takeoff""" - self.context_push() - - ex = None - try: - self.change_mode('STABILIZE') - self.set_rc(3, 1000) - self.set_rc(8, 1000) - self.wait_ready_to_arm() - self.arm_vehicle() - self.set_rc(8, 2000) - self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1659, timeout=10) - self.delay_sim_time(20) - # check we are still on the ground... - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - if abs(m.relative_alt) > 100: - raise NotAchievedException("Took off prematurely") - self.progress("Pushing throttle past half-way") - self.set_rc(3, 1650) + self.change_mode('STABILIZE') + self.set_rc(3, 1000) + self.set_rc(8, 1000) + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(8, 2000) + self.progress("wait for rotor runup to complete") + self.wait_servo_channel_value(8, 1659, timeout=10) + self.delay_sim_time(20) + # check we are still on the ground... + relative_alt = self.get_altitude(relative=True) + if abs(relative_alt) > 0.1: + raise NotAchievedException("Took off prematurely") + self.progress("Pushing throttle past half-way") + self.set_rc(3, 1650) - self.progress("Monitoring takeoff") - self.wait_altitude(6.9, 8, relative=True) + self.progress("Monitoring takeoff") + self.wait_altitude(6.9, 8, relative=True) - self.progress("takeoff OK") - except Exception as e: - self.print_exception_caught(e) - ex = e + self.progress("takeoff OK") self.land_and_disarm() - self.set_rc(8, 1000) - - self.context_pop() - - if ex is not None: - raise ex def SplineWaypoint(self, timeout=600): """ensure basic spline functionality works""" @@ -334,21 +298,19 @@ def SplineWaypoint(self, timeout=600): self.delay_sim_time(20) self.change_mode("AUTO") self.set_rc(3, 1500) - tstart = self.get_sim_time() - while True: - if self.get_sim_time() - tstart > timeout: - raise AutoTestTimeoutException("Vehicle did not disarm after mission") - if not self.armed(): - break - self.delay_sim_time(1) + self.wait_disarmed(timeout=600) self.progress("Lowering rotor speed") self.set_rc(8, 1000) - def AutoRotation(self, timeout=600): + def Autorotation(self, timeout=600): """Check engine-out behaviour""" - self.set_parameter("AROT_ENABLE", 1) + self.context_push() start_alt = 100 # metres - self.set_parameter("PILOT_TKOFF_ALT", start_alt * 100) + self.set_parameters({ + "AROT_ENABLE": 1, + "H_RSC_AROT_ENBL": 1, + }) + bail_out_time = self.get_parameter('H_RSC_AROT_RUNUP') self.change_mode('POSHOLD') self.set_rc(3, 1000) self.set_rc(8, 1000) @@ -364,79 +326,169 @@ def AutoRotation(self, timeout=600): relative=True, timeout=timeout) self.context_collect('STATUSTEXT') - self.progress("Triggering autorotate by raising interlock") + + # Reset collective to enter hover + self.set_rc(3, 1500) + + # Change to the autorotation flight mode + self.progress("Triggering autorotate mode") + self.change_mode('AUTOROTATE') + self.delay_sim_time(2) + + # Disengage the interlock to remove power self.set_rc(8, 1000) + + # Ensure we have progressed through the mode's state machine self.wait_statustext("SS Glide Phase", check_context=True) + + self.progress("Testing bailout from autorotation") + self.set_rc(8, 2000) + # See if the output ramps to a value close to expected with the prescribed time + self.wait_servo_channel_value(8, 1659, timeout=bail_out_time+1, comparator=operator.ge) + + # Successfully bailed out, disengage the interlock and allow autorotation to progress + self.set_rc(8, 1000) self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", check_context=True, regex=True) speed = float(self.re_match.group(1)) if speed > 30: raise NotAchievedException("Hit too hard") + + # Set throttle low to trip auto disarm + self.set_rc(3, 1000) + self.wait_disarmed() + self.context_pop() - def ManAutoRotation(self, timeout=600): + def ManAutorotation(self, timeout=600): """Check autorotation power recovery behaviour""" - RAMP_TIME = 4 - AROT_RAMP_TIME = 2 - self.set_parameter("H_RSC_AROT_MN_EN", 1) - self.set_parameter("H_RSC_AROT_ENG_T", AROT_RAMP_TIME) - self.set_parameter("H_RSC_AROT_IDLE", 20) - self.set_parameter("H_RSC_RAMP_TIME", RAMP_TIME) - self.set_parameter("H_RSC_IDLE", 0) - start_alt = 100 # metres - self.set_parameter("PILOT_TKOFF_ALT", start_alt * 100) - self.change_mode('POSHOLD') - self.set_rc(3, 1000) - self.set_rc(8, 1000) - self.wait_ready_to_arm() - self.arm_vehicle() - self.set_rc(8, 2000) - self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1659, timeout=10) - self.delay_sim_time(20) - self.set_rc(3, 2000) - self.wait_altitude(start_alt - 1, - (start_alt + 5), - relative=True, - timeout=timeout) - self.context_collect('STATUSTEXT') - self.change_mode('STABILIZE') - self.progress("Triggering manual autorotation by disabling interlock") - self.set_rc(3, 1000) - self.set_rc(8, 1000) - self.wait_servo_channel_value(8, 1199, timeout=3) - self.progress("channel 8 set to autorotation window") + RSC_CHAN = 8 - # wait to establish autorotation - self.delay_sim_time(2) + def check_rsc_output(self, throttle, timeout): + # Check we get a sensible throttle output + expected_pwm = int(throttle * 0.01 * 1000 + 1000) - self.set_rc(8, 2000) - self.wait_servo_channel_value(8, 1659, timeout=AROT_RAMP_TIME * 1.1) + # Help out the detection by accepting some margin + margin = 2 - # give time for engine to power up - self.set_rc(3, 1400) - self.delay_sim_time(2) + # See if the output ramps to a value close to expected with the prescribed time + self.wait_servo_channel_in_range(RSC_CHAN, expected_pwm-margin, expected_pwm+margin, timeout=timeout) - self.progress("in-flight power recovery") - self.set_rc(3, 1500) - self.delay_sim_time(5) + def TestAutorotationConfig(self, rsc_idle, arot_ramp_time, arot_idle, cool_down): + RAMP_TIME = 10 + RUNUP_TIME = 15 + AROT_RUNUP_TIME = arot_ramp_time + 4 + RSC_SETPOINT = 66 + self.set_parameters({ + "H_RSC_AROT_ENBL": 1, + "H_RSC_AROT_RAMP": arot_ramp_time, + "H_RSC_AROT_RUNUP": AROT_RUNUP_TIME, + "H_RSC_AROT_IDLE": arot_idle, + "H_RSC_RAMP_TIME": RAMP_TIME, + "H_RSC_RUNUP_TIME": RUNUP_TIME, + "H_RSC_IDLE": rsc_idle, + "H_RSC_SETPOINT": RSC_SETPOINT, + "H_RSC_CLDWN_TIME": cool_down + }) - # initiate autorotation again - self.set_rc(3, 1000) - self.set_rc(8, 1000) + # Check the RSC config so we know what to expect on the throttle output + if self.get_parameter("H_RSC_MODE") != 2: + self.set_parameter("H_RSC_MODE", 2) + self.reboot_sitl() - self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", - check_context=True, - regex=True) - speed = float(self.re_match.group(1)) - if speed > 30: - raise NotAchievedException("Hit too hard") + self.change_mode('POSHOLD') + self.set_rc(3, 1000) + self.set_rc(8, 1000) + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(8, 2000) + self.progress("wait for rotor runup to complete") + check_rsc_output(self, RSC_SETPOINT, RUNUP_TIME+1) - self.set_rc(3, 1000) - # verify servo 8 resets to RSC_IDLE after land complete - self.wait_servo_channel_value(8, 1000, timeout=3) - self.wait_disarmed() + self.delay_sim_time(20) + self.set_rc(3, 2000) + self.wait_altitude(100, + 105, + relative=True, + timeout=timeout) + self.context_collect('STATUSTEXT') + self.change_mode('STABILIZE') + + self.progress("Triggering manual autorotation by disabling interlock") + self.set_rc(3, 1000) + self.set_rc(8, 1000) + + self.wait_statustext(r"RSC: In Autorotation", check_context=True) + + # Check we are using the correct throttle output. This should happen instantly on ramp down. + idle_thr = rsc_idle + if (arot_idle > 0): + idle_thr = arot_idle + + check_rsc_output(self, idle_thr, 1) + + self.progress("RSC is outputting correct idle throttle") + + # Wait to establish autorotation. + self.delay_sim_time(2) + + # Re-engage interlock to start bailout sequence + self.set_rc(8, 2000) + + # Ensure we see the bailout state + self.wait_statustext("RSC: Bailing Out", check_context=True) + + # Check we are back up to flight throttle. Autorotation ramp up time should be used + check_rsc_output(self, RSC_SETPOINT, arot_ramp_time+1) + + # Give time for engine to power up + self.set_rc(3, 1400) + self.delay_sim_time(2) + + self.progress("in-flight power recovery") + self.set_rc(3, 1500) + self.delay_sim_time(5) + + # Initiate autorotation again + self.set_rc(3, 1000) + self.set_rc(8, 1000) + + self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", + check_context=True, + regex=True) + speed = float(self.re_match.group(1)) + if speed > 30: + raise NotAchievedException("Hit too hard") + + # Check that cool down is still used correctly if set + # First wait until we are out of the autorotation state + self.wait_statustext("RSC: Autorotation Stopped") + if (cool_down > 0): + check_rsc_output(self, rsc_idle*1.5, cool_down) + + # Verify RSC output resets to RSC_IDLE after land complete + check_rsc_output(self, rsc_idle, 20) + self.wait_disarmed() + + # We test the bailout behavior of two different configs + # First we test config with a regular throttle curve + self.progress("testing autorotation with throttle curve config") + self.context_push() + TestAutorotationConfig(self, rsc_idle=5.0, arot_ramp_time=2.0, arot_idle=0, cool_down=0) + + # Now we test a config that would be used with an ESC with internal governor and an autorotation window + self.progress("testing autorotation with ESC autorotation window config") + TestAutorotationConfig(self, rsc_idle=0.0, arot_ramp_time=0.0, arot_idle=20.0, cool_down=0) + + # Check rsc output behavior when using the cool down feature + self.progress("testing autorotation with cool down enabled and zero autorotation idle") + TestAutorotationConfig(self, rsc_idle=5.0, arot_ramp_time=2.0, arot_idle=0, cool_down=5.0) + + self.progress("testing that H_RSC_AROT_IDLE is used over RSC_IDLE when cool down is enabled") + TestAutorotationConfig(self, rsc_idle=5.0, arot_ramp_time=2.0, arot_idle=10, cool_down=5.0) + + self.context_pop() def mission_item_home(self, target_system, target_component): '''returns a mission_item_int which can be used as home in a mission''' @@ -656,6 +708,48 @@ def NastyMission(self): self.change_mode('LOITER') self.fly_mission_points(self.scurve_nasty_up_mission()) + def MountFailsafeAction(self): + """Fly Mount Failsafe action""" + self.context_push() + + self.progress("Setting up servo mount") + roll_servo = 12 + pitch_servo = 11 + yaw_servo = 10 + open_servo = 9 + roll_limit = 50 + self.set_parameters({ + "MNT1_TYPE": 1, + "SERVO%u_MIN" % roll_servo: 1000, + "SERVO%u_MAX" % roll_servo: 2000, + "SERVO%u_FUNCTION" % yaw_servo: 6, # yaw + "SERVO%u_FUNCTION" % pitch_servo: 7, # roll + "SERVO%u_FUNCTION" % roll_servo: 8, # pitch + "SERVO%u_FUNCTION" % open_servo: 9, # mount open + "MNT1_OPTIONS": 2, # retract + "MNT1_DEFLT_MODE": 3, # RC targettting + "MNT1_ROLL_MIN": -roll_limit, + "MNT1_ROLL_MAX": roll_limit, + }) + + self.reboot_sitl() + + retract_roll = 25.0 + self.set_parameter("MNT1_NEUTRAL_X", retract_roll) + self.progress("Killing RC") + self.set_parameter("SIM_RC_FAIL", 2) + self.delay_sim_time(10) + want_servo_channel_value = int(1500 + 500*retract_roll/roll_limit) + self.wait_servo_channel_value(roll_servo, want_servo_channel_value, epsilon=1) + + self.progress("Resurrecting RC") + self.set_parameter("SIM_RC_FAIL", 0) + self.wait_servo_channel_value(roll_servo, 1500) + + self.context_pop() + + self.reboot_sitl() + def set_rc_default(self): super(AutoTestHelicopter, self).set_rc_default() self.progress("Lowering rotor speed") @@ -679,7 +773,14 @@ def fly_mission(self, filename, strict=True): def AirspeedDrivers(self, timeout=600): '''Test AirSpeed drivers''' + # Copter's airspeed sensors are off by default + self.set_parameters({ + "ARSPD_ENABLE": 1, + "ARSPD_TYPE": 2, # Analog airspeed driver + "ARSPD_PIN": 1, # Analog airspeed driver pin for SITL + }) # 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 self.customise_SITL_commandline(["--home", "%s,%s,%s,%s" % (-35.362881, 149.165222, 582.000000, 90.0)]) @@ -702,12 +803,6 @@ def check_airspeeds(mav, m): if delta > 3: raise NotAchievedException("Airspeed mismatch (as1=%f as2=%f)" % (airspeed[0], airspeed[1])) - # Copter's airspeed sensors are off by default - self.set_parameter("ARSPD_ENABLE", 1) - self.set_parameter("ARSPD_TYPE", 2) # Analog airspeed driver - self.set_parameter("ARSPD_PIN", 1) # Analog airspeed driver pin for SITL - self.reboot_sitl() - airspeed_sensors = [ ("MS5525", 3, 1), ("DLVR", 7, 2), @@ -728,11 +823,59 @@ def check_airspeeds(mav, m): raise NotAchievedException("Never saw an airspeed1") if airspeed[1] is None: raise NotAchievedException("Never saw an airspeed2") - self.context_pop() if not self.current_onboard_log_contains_message("ARSP"): raise NotAchievedException("Expected ARSP log message") + self.disarm_vehicle() + self.context_pop() - self.reboot_sitl() + def TurbineCoolDown(self, timeout=200): + """Check Turbine Cool Down Feature""" + self.context_push() + # set option for Turbine + RAMP_TIME = 4 + SETPOINT = 66 + IDLE = 15 + COOLDOWN_TIME = 5 + self.set_parameters({"RC6_OPTION": 161, + "H_RSC_RAMP_TIME": RAMP_TIME, + "H_RSC_SETPOINT": SETPOINT, + "H_RSC_IDLE": IDLE, + "H_RSC_CLDWN_TIME": COOLDOWN_TIME}) + self.set_rc(3, 1000) + self.set_rc(8, 1000) + + self.progress("Starting turbine") + self.wait_ready_to_arm() + self.context_collect("STATUSTEXT") + self.arm_vehicle() + + self.set_rc(6, 2000) + self.wait_statustext('Turbine startup', check_context=True) + + # Engage interlock to run up to head speed + self.set_rc(8, 2000) + + # Check throttle gets to setpoint + expected_thr = SETPOINT * 0.01 * 1000 + 1000 - 1 # servo end points are 1000 to 2000 + self.wait_servo_channel_value(8, expected_thr, timeout=RAMP_TIME+1, comparator=operator.ge) + + self.progress("Checking cool down behaviour, idle x 1.5") + self.set_rc(8, 1000) + tstart = self.get_sim_time() + expected_thr = IDLE * 1.5 * 0.01 * 1000 + 1000 + 1 + self.wait_servo_channel_value(8, expected_thr, timeout=2, comparator=operator.le) + + # Check that the throttle drops to idle after cool down time + expected_thr = IDLE * 0.01 * 1000 + 1000 + 1 + self.wait_servo_channel_value(8, expected_thr, timeout=COOLDOWN_TIME+1, comparator=operator.le) + + measured_time = self.get_sim_time() - tstart + if (abs(measured_time - COOLDOWN_TIME) > 1.0): + raise NotAchievedException('Throttle did not reduce to idle within H_RSC_CLDWN_TIME') + + self.set_rc(6, 1000) + self.wait_disarmed(timeout=20) + self.context_pop() def TurbineStart(self, timeout=200): """Check Turbine Start Feature""" @@ -804,43 +947,203 @@ def TurbineStart(self, timeout=200): def PIDNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with PID notches") - self.context_push() + self.set_parameters({ + "FILT1_TYPE": 1, + "FILT2_TYPE": 1, + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 0, + "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour + "LOG_BITMASK": 65535, + "LOG_DISARMED": 0, + "SIM_VIB_FREQ_X": 120, # roll + "SIM_VIB_FREQ_Y": 120, # pitch + "SIM_VIB_FREQ_Z": 180, # yaw + "FILT1_NOTCH_FREQ": 120, + "FILT2_NOTCH_FREQ": 180, + "ATC_RAT_RLL_NEF": 1, + "ATC_RAT_PIT_NEF": 1, + "ATC_RAT_YAW_NEF": 2, + "SIM_GYR1_RND": 5, + }) + self.reboot_sitl() - ex = None - try: - self.set_parameters({ - "FILT1_TYPE": 1, - "FILT2_TYPE": 1, - "AHRS_EKF_TYPE": 10, - "INS_LOG_BAT_MASK": 3, - "INS_LOG_BAT_OPT": 0, - "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour - "LOG_BITMASK": 65535, - "LOG_DISARMED": 0, - "SIM_VIB_FREQ_X": 120, # roll - "SIM_VIB_FREQ_Y": 120, # pitch - "SIM_VIB_FREQ_Z": 180, # yaw - "FILT1_NOTCH_FREQ": 120, - "FILT2_NOTCH_FREQ": 180, - "ATC_RAT_RLL_NEF": 1, - "ATC_RAT_PIT_NEF": 1, - "ATC_RAT_YAW_NEF": 2, - "SIM_GYR1_RND": 5, + self.hover_and_check_matched_frequency_with_fft(5, 20, 350, reverse=True, takeoff=True) + + def AutoTune(self): + """Test autotune mode""" + # test roll and pitch FF tuning + self.set_parameters({ + "ATC_ANG_RLL_P": 4.5, + "ATC_RAT_RLL_P": 0, + "ATC_RAT_RLL_I": 0.1, + "ATC_RAT_RLL_D": 0, + "ATC_RAT_RLL_FF": 0.15, + "ATC_ANG_PIT_P": 4.5, + "ATC_RAT_PIT_P": 0, + "ATC_RAT_PIT_I": 0.1, + "ATC_RAT_PIT_D": 0, + "ATC_RAT_PIT_FF": 0.15, + "ATC_ANG_YAW_P": 4.5, + "ATC_RAT_YAW_P": 0.18, + "ATC_RAT_YAW_I": 0.024, + "ATC_RAT_YAW_D": 0.003, + "ATC_RAT_YAW_FF": 0.024, + "AUTOTUNE_AXES": 3, + "AUTOTUNE_SEQ": 1, }) - self.reboot_sitl() - self.takeoff(10, mode="ALT_HOLD") + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(5, 20, 350, reverse=True) + # hold position in loiter + self.change_mode('AUTOTUNE') - except Exception as e: - self.print_exception_caught(e) - ex = e + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # test pitch rate P and Rate D tuning + self.set_parameters({ + "AUTOTUNE_AXES": 2, + "AUTOTUNE_SEQ": 2, + "AUTOTUNE_GN_MAX": 1.8, + }) - self.context_pop() + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # test Roll rate P and Rate D tuning + self.set_parameters({ + "AUTOTUNE_AXES": 1, + "AUTOTUNE_SEQ": 2, + "AUTOTUNE_GN_MAX": 1.6, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") - if ex is not None: - raise ex + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # test Roll and pitch angle P tuning + self.set_parameters({ + "AUTOTUNE_AXES": 3, + "AUTOTUNE_SEQ": 4, + "AUTOTUNE_FRQ_MIN": 5, + "AUTOTUNE_FRQ_MAX": 50, + "AUTOTUNE_GN_MAX": 1.6, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # test yaw FF and rate P and Rate D + self.set_parameters({ + "AUTOTUNE_AXES": 4, + "AUTOTUNE_SEQ": 3, + "AUTOTUNE_FRQ_MIN": 10, + "AUTOTUNE_FRQ_MAX": 70, + "AUTOTUNE_GN_MAX": 1.4, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # test yaw angle P tuning + self.set_parameters({ + "AUTOTUNE_AXES": 4, + "AUTOTUNE_SEQ": 4, + "AUTOTUNE_FRQ_MIN": 5, + "AUTOTUNE_FRQ_MAX": 50, + "AUTOTUNE_GN_MAX": 1.5, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # tune check + self.set_parameters({ + "AUTOTUNE_AXES": 7, + "AUTOTUNE_SEQ": 16, + "AUTOTUNE_FRQ_MIN": 10, + "AUTOTUNE_FRQ_MAX": 80, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + def autotune_land_and_save_gains(self): + self.set_rc(3, 1000) + self.context_collect('STATUSTEXT') + self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", + check_context=True, + regex=True) + self.set_rc(8, 1000) + self.wait_disarmed() + + def land_and_disarm(self, **kwargs): + super(AutoTestHelicopter, self).land_and_disarm(**kwargs) + self.progress("Killing rotor speed") + self.set_rc(8, 1000) + + def do_RTL(self, **kwargs): + super(AutoTestHelicopter, self).do_RTL(**kwargs) + self.progress("Killing rotor speed") + self.set_rc(8, 1000) def tests(self): '''return list of all tests''' @@ -851,14 +1154,17 @@ def tests(self): self.PosHoldTakeOff, self.StabilizeTakeOff, self.SplineWaypoint, - self.AutoRotation, - self.ManAutoRotation, + self.Autorotation, + self.ManAutorotation, self.governortest, self.FlyEachFrame, self.AirspeedDrivers, self.TurbineStart, + self.TurbineCoolDown, self.NastyMission, self.PIDNotches, + self.AutoTune, + self.MountFailsafeAction, ]) return ret diff --git a/Tools/autotest/locations.txt b/Tools/autotest/locations.txt index e1f845d5f4acce..3e92209330057c 100644 --- a/Tools/autotest/locations.txt +++ b/Tools/autotest/locations.txt @@ -54,9 +54,10 @@ Yachiyo=35.770481,140.107929,36,90 Tyndall=30.0142232,-85.4984701,7,0 Elvenes=68.871422,17.986690,17,256 Kawachi=35.879129,140.339683,7,0 -SpringValley=-35.280252,149.005821,597.3,5 +SpringValley=-35.280252,149.005821,580.8,5 SpringValley2=-35.28240059,149.00542037,582,10 SpringValley3=-35.28240515,149.00716878,579,12.6 +SpringValley4=-35.2824768,149.0071759,594.99,0 SpringValleyRoad=-35.28899126,149.00553365,603,162.7 Pyramid=29.9764,31.1339,0,0 AAMEastField=39.842288,-105.212928,1809,106 @@ -96,6 +97,8 @@ 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 +Madera=36.9287648,-119.8498046,82,290 +Peg=36.7099085,-119.4076592,141,289 SFO_Bay=37.62561973,-122.33235387,0.0,0 Egge=60.215720,10.324071,198,303 Gundaroo=-35.02349196,149.26496411,576.8,0 @@ -104,3 +107,4 @@ Fulcrum=41.841650,-71.371763,0,290 Hueneme=34.154695,-119.227468,0,270 LiSound=41.307040,-71.910669,0.0,0 Alpena=45.05576,-83.42650,0.0,90 +UCSB=34.413963,-119.848946,0,0 diff --git a/Tools/autotest/logger_metadata/enum_parse.py b/Tools/autotest/logger_metadata/enum_parse.py index 99227a211e9766..3f37a9837f4432 100755 --- a/Tools/autotest/logger_metadata/enum_parse.py +++ b/Tools/autotest/logger_metadata/enum_parse.py @@ -1,5 +1,9 @@ #!/usr/bin/env python +''' +AP_FLAKE8_CLEAN +''' + from __future__ import print_function import argparse @@ -10,6 +14,7 @@ topdir = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../') topdir = os.path.realpath(topdir) + class EnumDocco(object): vehicle_map = { @@ -35,35 +40,35 @@ def match_enum_line(self, line): # attempts to extract name, value and comment from line. # Match: " FRED, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+)\s*,? *(?://[/>]* *(.*) *)?$", line) + m = re.match(r"\s*([A-Z0-9_a-z]+)\s*,? *(?://[/>]* *(.*) *)?$", line) if m is not None: return (m.group(1), None, m.group(2)) # Match: " FRED, /* optional comment */" - m = re.match("\s*([A-Z0-9_a-z]+)\s*,? *(?:/[*] *(.*) *[*]/ *)?$", line) + m = re.match(r"\s*([A-Z0-9_a-z]+)\s*,? *(?:/[*] *(.*) *[*]/ *)?$", line) if m is not None: return (m.group(1), None, m.group(2)) # Match: " FRED = 17, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+)\s*=\s*([-0-9]+)\s*,?(?:\s*//[/<]*\s*(.*) *)?$", + m = re.match(r"\s*([A-Z0-9_a-z]+)\s*=\s*([-0-9]+)\s*,?(?:\s*//[/<]*\s*(.*) *)?$", line) if m is not None: return (m.group(1), m.group(2), m.group(3)) # Match: " FRED = 17, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *([-0-9]+) *,?(?: */* *(.*) *)? *[*]/ *$", + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *([-0-9]+) *,?(?: */* *(.*) *)? *[*]/ *$", line) if m is not None: return (m.group(1), m.group(2), m.group(3)) # Match: " FRED = 1U<<0, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *[(]?1U? *[<][<] *(\d+)(?:, *// *(.*) *)?", + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *[(]?1U? *[<][<] *(\d+)(?:, *// *(.*) *)?", line) if m is not None: return (m.group(1), 1 << int(m.group(2)), m.group(3)) # Match: " FRED = 0xabc, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *(?:0[xX]([0-9A-Fa-f]+))(?:, *// *(.*) *)?", + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *(?:0[xX]([0-9A-Fa-f]+))(?:, *// *(.*) *)?", line) if m is not None: return (m.group(1), int(m.group(2), 16), m.group(3)) @@ -71,23 +76,27 @@ def match_enum_line(self, line): '''start discarded matches - lines we understand but can't do anything with:''' # Match: " FRED = 17, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *(\w+) *,?(?: *// *(.*) *)?$", + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *(\w+) *,?(?: *// *(.*) *)?$", line) if m is not None: return (None, None, None) # Match: " FRED = FOO(17), // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *(\w+) *\\( *(\w+) *\\) *,?(?: *// *(.*) *)?$", + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *(\w+) *\\( *(\w+) *\\) *,?(?: *// *(.*) *)?$", line) if m is not None: return (None, None, None) - - # Match: " FRED = 1U<<0, // optional comment" - m = re.match("\s*([A-Z0-9_a-z]+) *= *[(]?3U? *[<][<] *(\d+)(?:, *// *(.*) *)?", + # Match: " FRED = 1U<<0, // optional comment" + m = re.match(r"\s*([A-Z0-9_a-z]+) *= *[(]?3U? *[<][<] *(\d+)(?:, *// *(.*) *)?", line) if m is not None: return (m.group(1), 1 << int(m.group(2)), m.group(3)) + # Match: "#define FRED 1 // optional comment" + m = re.match(r"#define\s*([A-Z0-9_a-z]+)\s+(-?\d+) *(// *(.*) *)?$", line) + if m is not None: + return (m.group(1), m.group(2), m.group(4)) + if m is None: raise ValueError("Failed to match (%s)" % line) @@ -112,21 +121,27 @@ def debug(x): break line = line.rstrip() # print("state=%s line: %s" % (state, line)) - if re.match("\s*//.*", line): + # Skip single-line comments - unless they contain LoggerEnum tags + if re.match(r"\s*//.*", line) and "LoggerEnum" not in line: + continue + # Skip multi-line comments + if re.match(r"\s*/\*.*", line): + while "*/" not in line: + line = f.readline() continue if state == "outside": if re.match("class .*;", line) is not None: # forward-declaration of a class continue - m = re.match("class *([:\w]+)", line) + m = re.match(r"class *([:\w]+)", line) if m is not None: in_class = m.group(1) continue - m = re.match("namespace *(\w+)", line) + m = re.match(r"namespace *(\w+)", line) if m is not None: in_class = m.group(1) continue - m = re.match(".*enum\s*(class)? *([\w]+)\s*(?::.*_t)? *{(.*)};", line) + m = re.match(r".*enum\s*(class)? *([\w]+)\s*(?::.*_t)? *{(.*)};", line) if m is not None: # all one one line! Thanks! enum_name = m.group(2) @@ -142,7 +157,7 @@ def debug(x): enumerations.append(new_enumeration) continue - m = re.match(".*enum\s*(class)? *([\w]+)\s*(?::.*_t)? *{", line) + m = re.match(r".*enum\s*(class)? *([\w]+)\s*(?::.*_t)? *{", line) if m is not None: enum_name = m.group(2) debug("%s: %s" % (source_file, enum_name)) @@ -150,17 +165,30 @@ def debug(x): last_value = None state = state_inside skip_enumeration = False + continue + + # // @LoggerEnum: NAME - can be used around for #define sets + m = re.match(r".*@LoggerEnum: *([\w]+)", line) + if m is not None: + enum_name = m.group(1) + debug("%s: %s" % (source_file, enum_name)) + entries = [] + last_value = None + state = state_inside + skip_enumeration = False + continue + continue if state == "inside": - if re.match("\s*$", line): + if re.match(r"\s*$", line): continue - if re.match("#if", line): + if re.match(r"#if", line): continue - if re.match("#endif", line): + if re.match(r"#endif", line): continue - if re.match("#else", line): + if re.match(r"#else", line): continue - if re.match(".*}\s*\w*(\s*=\s*[\w:]+)?;", line): + if re.match(r".*}\s*\w*(\s*=\s*[\w:]+)?;", line) or "@LoggerEnumEnd" in line: # potential end of enumeration if not skip_enumeration: if enum_name is None: @@ -189,7 +217,7 @@ def debug(x): else: value = int(value) last_value = value -# print("entry=%s value=%s comment=%s" % (name, value, comment)) + # print("entry=%s value=%s comment=%s" % (name, value, comment)) entries.append(EnumDocco.EnumEntry(name, value, comment)) return enumerations @@ -219,6 +247,9 @@ def search_for_files(self, dirs_to_search): continue if filepath.endswith("libraries/AP_HAL/utility/getopt_cpp.h"): continue + # Failed to match ( IOEVENT_PWM = EVENT_MASK(1),) + if filepath.endswith("libraries/AP_IOMCU/iofirmware/iofirmware.cpp"): + continue self.files.append(filepath) if len(_next): self.search_for_files(_next) @@ -253,4 +284,3 @@ def run(self): sys.exit(1) s.run() -# print("Enumerations: %s" % s.enumerations) diff --git a/Tools/autotest/logger_metadata/parse.py b/Tools/autotest/logger_metadata/parse.py index 2f7517d2182f46..b56b7ad2662cd0 100755 --- a/Tools/autotest/logger_metadata/parse.py +++ b/Tools/autotest/logger_metadata/parse.py @@ -1,5 +1,9 @@ #!/usr/bin/env python +''' +AP_FLAKE8_CLEAN +''' + from __future__ import print_function import argparse @@ -33,7 +37,11 @@ # Regular expressions for finding message definitions in structure format re_start_messagedef = re.compile(r"^\s*{?\s*LOG_[A-Z0-9_]+_[MSGTA]+[A-Z0-9_]*\s*,") re_deffield = r'[\s\\]*"?([\w\-#?%]+)"?\s*' -re_full_messagedef = re.compile(r'\s*LOG_\w+\s*,\s*\w+\([^)]+\)[\s\\]*,' + f'{re_deffield},{re_deffield},' + r'[\s\\]*"?([\w,]+)"?[\s\\]*,' + f'{re_deffield},{re_deffield}' , re.MULTILINE) +re_full_messagedef = re.compile(r'\s*LOG_\w+\s*,\s*\w+\([^)]+\)[\s\\]*,' + + f'{re_deffield},{re_deffield},' + + r'[\s\\]*"?([\w,]+)"?[\s\\]*,' + + f'{re_deffield},{re_deffield}', + re.MULTILINE) re_fmt_define = re.compile(r'#define\s+(\w+_FMT)\s+"([\w\-#?%]+)"') re_units_define = re.compile(r'#define\s+(\w+_UNITS)\s+"([\w\-#?%]+)"') re_mults_define = re.compile(r'#define\s+(\w+_MULTS)\s+"([\w\-#?%]+)"') @@ -41,7 +49,9 @@ # Regular expressions for finding message definitions in Write calls re_start_writecall = re.compile(r"\s*[AP:]*logger[\(\)]*.Write[StreamingCrcl]*\(") re_writefield = r'\s*"([\w\-#?%,]+)"\s*' -re_full_writecall = re.compile(r'\s*[AP:]*logger[\(\)]*.Write[StreamingCrcl]*\(' + f'{re_writefield},{re_writefield},{re_writefield},({re_writefield},{re_writefield})?' , re.MULTILINE) +re_full_writecall = re.compile(r'\s*[AP:]*logger[\(\)]*.Write[StreamingCrcl]*\(' + + f'{re_writefield},{re_writefield},{re_writefield},({re_writefield},{re_writefield})?', + re.MULTILINE) # Regular expression for extracting unit and multipliers from structure re_units_mults_struct = re.compile(r"^\s*{\s*'([\w\-#?%!/])',"+r'\s*"?([\w\-#?%./]*)"?\s*}') @@ -64,6 +74,7 @@ 1e-9: "n" # nano- } + class LoggerDocco(object): vehicle_map = { @@ -93,7 +104,7 @@ class Docco(object): def __init__(self, name): self.name = name self.url = None - if isinstance(name,list): + if isinstance(name, list): self.description = [None] * len(name) else: self.description = None @@ -104,15 +115,15 @@ def __init__(self, name): def add_name(self, name): # If self.name/description aren't lists, convert them - if isinstance(self.name,str): + if isinstance(self.name, str): self.name = [self.name] self.description = [self.description] # Replace any existing empty descriptions with empty strings - for i in range(0,len(self.description)): + for i in range(0, len(self.description)): if self.description[i] is None: self.description[i] = "" # Extend the name and description lists - if isinstance(name,list): + if isinstance(name, list): self.name.extend(name) self.description.extend([None] * len(name)) else: @@ -120,8 +131,8 @@ def add_name(self, name): self.description.append(None) def set_description(self, desc): - if isinstance(self.description,list): - for i in range(0,len(self.description)): + if isinstance(self.description, list): + for i in range(0, len(self.description)): if self.description[i] is None: self.description[i] = desc else: @@ -147,7 +158,7 @@ def set_field_bits(self, field, bits): count = 0 entries = [] for bit in bits: - entries.append(EnumDocco.EnumEntry(bit, 1< 2: raise NotAchievedException("too far from target %.1fm" % error) - self.context_pop() - self.remove_installed_script(applet_script) - self.reboot_sitl() - def ShipLanding(self): '''ship landing test''' - applet_script = "plane_ship_landing.lua" - - self.install_applet_script(applet_script) + self.install_applet_script_context("plane_ship_landing.lua") self.set_parameters({ "SCR_ENABLE": 1, @@ -1416,7 +1574,6 @@ def ShipLanding(self): self.reboot_sitl(check_position=False) - self.context_push() self.context_collect('STATUSTEXT') self.set_parameters({ "SHIP_ENABLE" : 1, @@ -1445,10 +1602,6 @@ def ShipLanding(self): # with the deck self.wait_groundspeed(4.8, 5.2) - self.context_pop() - self.remove_installed_script(applet_script) - self.reboot_sitl(check_position=False) - def RCDisableAirspeedUse(self): '''check disabling airspeed using RC switch''' self.set_parameter("RC9_OPTION", 106) @@ -1557,6 +1710,56 @@ def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self): self.fly_home_land_and_disarm() + def TransitionMinThrottle(self): + '''Ensure that TKOFF_THR_MIN is applied during the forward transition''' + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.check_mission_upload_download(wps) + self.set_parameter('TKOFF_THR_MIN', 80) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.wait_current_waypoint(2) + # Wait for 5 seconds into the transition. + self.delay_sim_time(5) + # Ensure TKOFF_THR_MIN is still respected. + thr_min = self.get_parameter('TKOFF_THR_MIN') + self.wait_servo_channel_value(3, 1000+thr_min*10, comparator=operator.eq) + + self.fly_home_land_and_disarm() + + def BackTransitionMinThrottle(self): + '''Ensure min throttle is applied during back transition.''' + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.check_mission_upload_download(wps) + self.set_parameter('Q_RTL_MODE', 1) + + trim_pwm = 1000 + 10*self.get_parameter("TRIM_THROTTLE") + min_pwm = 1000 + 10*self.get_parameter("THR_MIN") + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.context_collect('STATUSTEXT') + + self.wait_statustext("VTOL airbrake", check_context=True, timeout=300) + self.wait_servo_channel_value(3, trim_pwm, comparator=operator.le, timeout=1) + + self.wait_statustext("VTOL position1", check_context=True, timeout=10) + self.wait_servo_channel_value(3, min_pwm+10, comparator=operator.le, timeout=1) + + self.wait_disarmed(timeout=60) + def MAV_CMD_NAV_TAKEOFF(self): '''test issuing takeoff command via mavlink''' self.change_mode('GUIDED') @@ -1650,8 +1853,8 @@ def DCMClimbRate(self): # Kill any GPSs self.set_parameters({ - 'SIM_GPS_DISABLE': 1, - 'SIM_GPS2_DISABLE': 1, + 'SIM_GPS1_ENABLE': 0, + 'SIM_GPS2_ENABLE': 0, }) self.delay_sim_time(5) @@ -1725,6 +1928,141 @@ def reposition_to_loc(self, loc, accuracy=100): timeout=120, ) + def AHRSFlyForwardFlag(self): + '''ensure FlyForward flag is set appropriately''' + self.set_parameters({ + "LOG_DISARMED": 1, + "LOG_REPLAY": 1, + }) + self.reboot_sitl() + + self.assert_mode_is('FBWA') + self.delay_sim_time(10) + self.change_mode('QHOVER') + self.delay_sim_time(10) + + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(3, 2000) + self.wait_altitude(20, 50, relative=True) + self.context_collect('STATUSTEXT') + self.change_mode('CRUISE') + self.set_rc(3, 1500) + self.wait_statustext('Transition started airspeed', check_context=True) + self.wait_statustext('Transition airspeed reached', check_context=True) + self.wait_statustext('Transition done', check_context=True) + self.delay_sim_time(5) + self.change_mode('QHOVER') + self.wait_airspeed(0, 5) + self.delay_sim_time(5) + mlog_path = self.current_onboard_log_filepath() + self.fly_home_land_and_disarm(timeout=600) + + mlog = self.dfreader_for_path(mlog_path) + + stage_require_fbwa = "require_fbwa" + stage_wait_qhover = "wait_qhover" + stage_verify_qhover_ff = "verify_qhover_ff" + stage_wait_cruise = "wait_cruise" + stage_cruise_wait_ff = "cruise_wait_ff" + stage_qhover2 = "qhover2" + stage_done = "done" + stage = stage_require_fbwa + msgs = {} + seen_flag_set_in_cruise = False + FF_BIT_MASK = (1 << 2) + while stage != stage_done: + m = mlog.recv_match() + if m is None: + raise NotAchievedException(f"Stuck in stage {stage}") + m_type = m.get_type() + msgs[m_type] = m + + if stage == stage_require_fbwa: + if m_type == 'MODE': + if m.ModeNum == self.get_mode_from_mode_mapping('MANUAL'): + # manual to start with + continue + fbwa_num = self.get_mode_from_mode_mapping('FBWA') + print(f"{m.ModeNum=} {fbwa_num=}") + if m.ModeNum != fbwa_num: + raise ValueError(f"wanted mode={fbwa_num} got={m.ModeNum}") + continue + if m_type == 'RFRN': + if not m.Flags & FF_BIT_MASK: + raise ValueError("Expected FF to be set in FBWA") + stage = stage_wait_qhover + continue + continue + + if stage == stage_wait_qhover: + if m_type == 'MODE': + qhover_num = self.get_mode_from_mode_mapping('QHOVER') + print(f"want={qhover_num} got={m.ModeNum}") + if m.ModeNum == qhover_num: + stage = stage_verify_qhover_ff + continue + continue + continue + + if stage == stage_verify_qhover_ff: + if m_type == 'RFRN': + if m.Flags & FF_BIT_MASK: + raise ValueError("Expected FF to be unset in QHOVER") + stage = stage_wait_cruise + continue + continue + + if stage == stage_wait_cruise: + if m_type == 'MODE': + want_num = self.get_mode_from_mode_mapping('CRUISE') + if m.ModeNum == want_num: + stage = stage_cruise_wait_ff + cruise_wait_ff_start = msgs['ATT'].TimeUS*1e-6 + continue + continue + continue + + if stage == stage_cruise_wait_ff: + if m_type == 'MODE': + want_num = self.get_mode_from_mode_mapping('CRUISE') + if want_num != m.ModeNum: + if not seen_flag_set_in_cruise: + raise ValueError("Never saw FF get set") + if m.ModeNum == self.get_mode_from_mode_mapping('QHOVER'): + stage = stage_qhover2 + continue + continue + if m_type == 'RFRN': + flag_set = m.Flags & FF_BIT_MASK + now = msgs['ATT'].TimeUS*1e-6 + delta_t = now - cruise_wait_ff_start + if delta_t < 8: + if flag_set: + raise ValueError("Should not see bit set") + if delta_t > 10: + if not flag_set and not seen_flag_set_in_cruise: + raise ValueError("Should see bit set") + seen_flag_set_in_cruise = True + continue + continue + + if stage == stage_qhover2: + '''bit should stay low for qhover 2''' + if m_type == 'RFRN': + flag_set = m.Flags & FF_BIT_MASK + if flag_set: + raise ValueError("ff should be low in qhover") + continue + if m_type == 'MODE': + if m.ModeNum != self.get_mode_from_mode_mapping('QHOVER'): + stage = stage_done + continue + continue + continue + + raise NotAchievedException("Bad stage") + def RTL_AUTOLAND_1_FROM_GUIDED(self): '''test behaviour when RTL_AUTOLAND==1 and entering from guided''' @@ -1771,6 +2109,58 @@ def RTL_AUTOLAND_1_FROM_GUIDED(self): self.fly_home_land_and_disarm() + def WindEstimateConsistency(self): + '''test that DCM and EKF3 roughly agree on wind speed and direction''' + self.set_parameters({ + 'SIM_WIND_SPD': 10, # metres/second + 'SIM_WIND_DIR': 315, # from the North-West + }) + self.change_mode('TAKEOFF') + self.wait_ready_to_arm() + self.arm_vehicle() + self.delay_sim_time(180) + mlog = self.dfreader_for_current_onboard_log() + self.fly_home_land_and_disarm() + + self.progress("Inspecting dataflash log") + match_start_time = None + dcm = None + xkf2 = None + while True: + m = mlog.recv_match( + type=['DCM', 'XKF2'], + blocking=True, + ) + if m is None: + raise NotAchievedException("Did not see wind estimates match") + + m_type = m.get_type() + if m_type == 'DCM': + dcm = m + else: + xkf2 = m + if dcm is None or xkf2 is None: + continue + + now = m.TimeUS * 1e-6 + + matches_east = abs(dcm.VWE-xkf2.VWE) < 1.5 + matches_north = abs(dcm.VWN-xkf2.VWN) < 1.5 + + matches = matches_east and matches_north + + if not matches: + match_start_time = None + continue + + if match_start_time is None: + match_start_time = now + continue + + if now - match_start_time > 60: + self.progress("Wind estimates correlated") + break + def tests(self): '''return list of all tests''' @@ -1790,6 +2180,7 @@ def tests(self): self.QAssist, self.GyroFFT, self.Tailsitter, + self.CopterTailsitter, self.ICEngine, self.ICEngineMission, self.MAV_CMD_DO_ENGINE_CONTROL, @@ -1797,10 +2188,12 @@ def tests(self): self.GUIDEDToAUTO, self.BootInAUTO, self.Ship, + self.WindEstimateConsistency, self.MAV_CMD_NAV_LOITER_TO_ALT, self.LoiterAltQLand, self.VTOLLandSpiral, self.VTOLQuicktune, + self.VTOLQuicktune_CPP, self.PrecisionLanding, self.ShipLanding, Test(self.MotorTest, kwargs={ # tests motors 4 and 2 @@ -1812,10 +2205,13 @@ def tests(self): self.RCDisableAirspeedUse, self.mission_MAV_CMD_DO_VTOL_TRANSITION, self.mavlink_MAV_CMD_DO_VTOL_TRANSITION, + self.TransitionMinThrottle, + self.BackTransitionMinThrottle, self.MAV_CMD_NAV_TAKEOFF, self.Q_GUIDED_MODE, self.DCMClimbRate, self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence + self.AHRSFlyForwardFlag, ]) return ret diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index b08e1ebed3003f..af876bdece7c80 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -86,86 +86,76 @@ def get_stick_arming_channel(self): def DriveSquare(self, side=50): """Learn/Drive Square with Ch7 option""" - self.context_push() - ex = None - try: - self.progress("TEST SQUARE") - self.set_parameters({ - "RC7_OPTION": 7, - "RC9_OPTION": 58, - }) + self.progress("TEST SQUARE") + self.set_parameters({ + "RC7_OPTION": 7, + "RC9_OPTION": 58, + }) - self.change_mode('MANUAL') + self.change_mode('MANUAL') - self.wait_ready_to_arm() - self.arm_vehicle() + self.wait_ready_to_arm() + self.arm_vehicle() - self.clear_wp(9) - - # first aim north - self.progress("\nTurn right towards north") - self.reach_heading_manual(10) - # save bottom left corner of box as home AND waypoint - self.progress("Save HOME") - self.save_wp() - - self.progress("Save WP") - self.save_wp() - - # pitch forward to fly north - self.progress("\nGoing north %u meters" % side) - self.reach_distance_manual(side) - # save top left corner of square as waypoint - self.progress("Save WP") - self.save_wp() - - # roll right to fly east - self.progress("\nGoing east %u meters" % side) - self.reach_heading_manual(100) - self.reach_distance_manual(side) - # save top right corner of square as waypoint - self.progress("Save WP") - self.save_wp() - - # pitch back to fly south - self.progress("\nGoing south %u meters" % side) - self.reach_heading_manual(190) - self.reach_distance_manual(side) - # save bottom right corner of square as waypoint - self.progress("Save WP") - self.save_wp() - - # roll left to fly west - self.progress("\nGoing west %u meters" % side) - self.reach_heading_manual(280) - self.reach_distance_manual(side) - # save bottom left corner of square (should be near home) as waypoint - self.progress("Save WP") - self.save_wp() - - self.progress("Checking number of saved waypoints") - mavproxy = self.start_mavproxy() - num_wp = self.save_mission_to_file_using_mavproxy( - mavproxy, - os.path.join(testdir, "ch7_mission.txt")) - self.stop_mavproxy(mavproxy) - expected = 7 # home + 6 toggled in - if num_wp != expected: - raise NotAchievedException("Did not get %u waypoints; got %u" % - (expected, num_wp)) + self.clear_wp(9) + + # first aim north + self.progress("\nTurn right towards north") + self.reach_heading_manual(10) + # save bottom left corner of box as home AND waypoint + self.progress("Save HOME") + self.save_wp() + + self.progress("Save WP") + self.save_wp() + + # pitch forward to fly north + self.progress("\nGoing north %u meters" % side) + self.reach_distance_manual(side) + # save top left corner of square as waypoint + self.progress("Save WP") + self.save_wp() + + # roll right to fly east + self.progress("\nGoing east %u meters" % side) + self.reach_heading_manual(100) + self.reach_distance_manual(side) + # save top right corner of square as waypoint + self.progress("Save WP") + self.save_wp() + + # pitch back to fly south + self.progress("\nGoing south %u meters" % side) + self.reach_heading_manual(190) + self.reach_distance_manual(side) + # save bottom right corner of square as waypoint + self.progress("Save WP") + self.save_wp() + + # roll left to fly west + self.progress("\nGoing west %u meters" % side) + self.reach_heading_manual(280) + self.reach_distance_manual(side) + # save bottom left corner of square (should be near home) as waypoint + self.progress("Save WP") + self.save_wp() + + self.progress("Checking number of saved waypoints") + mavproxy = self.start_mavproxy() + num_wp = self.save_mission_to_file_using_mavproxy( + mavproxy, + os.path.join(testdir, "ch7_mission.txt")) + self.stop_mavproxy(mavproxy) + expected = 7 # home + 6 toggled in + if num_wp != expected: + raise NotAchievedException("Did not get %u waypoints; got %u" % + (expected, num_wp)) - # TODO: actually drive the mission + # TODO: actually drive the mission - self.clear_wp(9) - except Exception as e: - self.print_exception_caught(e) - ex = e + self.clear_wp(9) self.disarm_vehicle() - self.context_pop() - - if ex: - raise ex def drive_left_circuit(self): """Drive a left circuit, 50m on a side.""" @@ -237,108 +227,98 @@ def drive_left_circuit(self): def Sprayer(self): """Test sprayer functionality.""" - self.context_push() - ex = None - try: - rc_ch = 5 - pump_ch = 5 - spinner_ch = 6 - pump_ch_min = 1050 - pump_ch_trim = 1520 - pump_ch_max = 1950 - spinner_ch_min = 975 - spinner_ch_trim = 1510 - spinner_ch_max = 1975 + rc_ch = 5 + pump_ch = 5 + spinner_ch = 6 + pump_ch_min = 1050 + pump_ch_trim = 1520 + pump_ch_max = 1950 + spinner_ch_min = 975 + spinner_ch_trim = 1510 + spinner_ch_max = 1975 - self.set_parameters({ - "SPRAY_ENABLE": 1, + self.set_parameters({ + "SPRAY_ENABLE": 1, - "SERVO%u_FUNCTION" % pump_ch: 22, - "SERVO%u_MIN" % pump_ch: pump_ch_min, - "SERVO%u_TRIM" % pump_ch: pump_ch_trim, - "SERVO%u_MAX" % pump_ch: pump_ch_max, + "SERVO%u_FUNCTION" % pump_ch: 22, + "SERVO%u_MIN" % pump_ch: pump_ch_min, + "SERVO%u_TRIM" % pump_ch: pump_ch_trim, + "SERVO%u_MAX" % pump_ch: pump_ch_max, - "SERVO%u_FUNCTION" % spinner_ch: 23, - "SERVO%u_MIN" % spinner_ch: spinner_ch_min, - "SERVO%u_TRIM" % spinner_ch: spinner_ch_trim, - "SERVO%u_MAX" % spinner_ch: spinner_ch_max, + "SERVO%u_FUNCTION" % spinner_ch: 23, + "SERVO%u_MIN" % spinner_ch: spinner_ch_min, + "SERVO%u_TRIM" % spinner_ch: spinner_ch_trim, + "SERVO%u_MAX" % spinner_ch: spinner_ch_max, - "SIM_SPR_ENABLE": 1, - "SIM_SPR_PUMP": pump_ch, - "SIM_SPR_SPIN": spinner_ch, + "SIM_SPR_ENABLE": 1, + "SIM_SPR_PUMP": pump_ch, + "SIM_SPR_SPIN": spinner_ch, - "RC%u_OPTION" % rc_ch: 15, - "LOG_DISARMED": 1, - }) + "RC%u_OPTION" % rc_ch: 15, + "LOG_DISARMED": 1, + }) - self.reboot_sitl() + self.reboot_sitl() - self.wait_ready_to_arm() - self.arm_vehicle() + self.wait_ready_to_arm() + self.arm_vehicle() - self.progress("test bootup state - it's zero-output!") - self.wait_servo_channel_value(spinner_ch, 0) - self.wait_servo_channel_value(pump_ch, 0) + self.progress("test bootup state - it's zero-output!") + self.wait_servo_channel_value(spinner_ch, 0) + self.wait_servo_channel_value(pump_ch, 0) - self.progress("Enable sprayer") - self.set_rc(rc_ch, 2000) + self.progress("Enable sprayer") + self.set_rc(rc_ch, 2000) - self.progress("Testing zero-speed state") - self.wait_servo_channel_value(spinner_ch, spinner_ch_min) - self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.progress("Testing zero-speed state") + self.wait_servo_channel_value(spinner_ch, spinner_ch_min) + self.wait_servo_channel_value(pump_ch, pump_ch_min) - self.progress("Testing turning it off") - self.set_rc(rc_ch, 1000) - self.wait_servo_channel_value(spinner_ch, spinner_ch_min) - self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.progress("Testing turning it off") + self.set_rc(rc_ch, 1000) + self.wait_servo_channel_value(spinner_ch, spinner_ch_min) + self.wait_servo_channel_value(pump_ch, pump_ch_min) - self.progress("Testing turning it back on") - self.set_rc(rc_ch, 2000) - self.wait_servo_channel_value(spinner_ch, spinner_ch_min) - self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.progress("Testing turning it back on") + self.set_rc(rc_ch, 2000) + self.wait_servo_channel_value(spinner_ch, spinner_ch_min) + self.wait_servo_channel_value(pump_ch, pump_ch_min) - self.progress("Testing speed-ramping") - self.set_rc(3, 1700) # start driving forward + self.progress("Testing speed-ramping") + self.set_rc(3, 1700) # start driving forward - # this is somewhat empirical... - self.wait_servo_channel_value(pump_ch, 1695, timeout=60) + # this is somewhat empirical... + self.wait_servo_channel_value(pump_ch, 1695, timeout=60) - self.progress("Turning it off again") - self.set_rc(rc_ch, 1000) - self.wait_servo_channel_value(spinner_ch, spinner_ch_min) - self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.progress("Turning it off again") + self.set_rc(rc_ch, 1000) + self.wait_servo_channel_value(spinner_ch, spinner_ch_min) + self.wait_servo_channel_value(pump_ch, pump_ch_min) - self.start_subtest("Sprayer Mission") - self.load_mission("sprayer-mission.txt") - self.change_mode("AUTO") + self.start_subtest("Sprayer Mission") + self.load_mission("sprayer-mission.txt") + self.change_mode("AUTO") # self.send_debug_trap() - self.progress("Waiting for sprayer to start") - 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) + self.progress("Waiting for sprayer to start") + 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) - self.start_subtest("Checking mavlink commands") - self.change_mode("MANUAL") - self.progress("Starting Sprayer") - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) - - self.progress("Testing speed-ramping") - self.set_rc(3, 1700) # start driving forward - self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt) - self.start_subtest("Stopping Sprayer") - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0) - self.wait_servo_channel_value(pump_ch, pump_ch_min) - self.set_rc(3, 1000) # start driving forward - - self.progress("Sprayer OK") - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.disarm_vehicle(force=True) - self.reboot_sitl() - if ex: - raise ex + self.start_subtest("Checking mavlink commands") + self.change_mode("MANUAL") + self.progress("Starting Sprayer") + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) + + self.progress("Testing speed-ramping") + self.set_rc(3, 1700) # start driving forward + self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt) + self.start_subtest("Stopping Sprayer") + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0) + self.wait_servo_channel_value(pump_ch, pump_ch_min) + self.set_rc(3, 1000) # stop driving forward + + self.progress("Sprayer OK") + self.disarm_vehicle() def DriveMaxRCIN(self, timeout=30): """Drive rover at max RC inputs""" @@ -525,44 +505,53 @@ def DriveRTL(self, timeout=120): self.disarm_vehicle() self.progress("RTL Mission OK (%fm)" % home_distance) + def RTL_SPEED(self, timeout=120): + '''Test RTL_SPEED is honoured''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 0, 0), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 0), + ]) + + self.wait_ready_to_arm() + self.arm_vehicle() + + self.change_mode('AUTO') + self.wait_current_waypoint(2, timeout=120) + for speed in 1, 5.5, 1.5, 7.5: + self.set_parameter("RTL_SPEED", speed) + self.change_mode('RTL') + self.wait_groundspeed(speed-0.1, speed+0.1, minimum_duration=10) + self.change_mode('HOLD') + self.do_RTL() + self.disarm_vehicle() + def AC_Avoidance(self): '''Test AC Avoidance switch''' - self.context_push() - ex = None - try: - self.load_fence("rover-fence-ac-avoid.txt") - 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() - self.arm_vehicle() - # first make sure we can breach the fence: - self.set_rc(10, 1000) - self.change_mode("ACRO") - self.set_rc(3, 1550) - self.wait_distance_to_home(25, 100000, timeout=60) - self.change_mode("RTL") - self.wait_statustext("Reached destination", timeout=60) - # now enable avoidance and make sure we can't: - self.set_rc(10, 2000) - self.change_mode("ACRO") - self.wait_groundspeed(0, 0.7, timeout=60) - # watch for speed zero - self.wait_groundspeed(0, 0.2, timeout=120) - - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE) - self.disarm_vehicle(force=True) + self.load_fence("rover-fence-ac-avoid.txt") + self.set_parameters({ + "FENCE_ENABLE": 0, + "PRX1_TYPE": 10, + "RC10_OPTION": 40, # proximity-enable + }) self.reboot_sitl() - if ex: - raise ex + # start = self.mav.location() + self.wait_ready_to_arm() + self.arm_vehicle() + # first make sure we can breach the fence: + self.set_rc(10, 1000) + self.change_mode("ACRO") + self.set_rc(3, 1550) + self.wait_distance_to_home(25, 100000, timeout=60) + self.change_mode("RTL") + self.wait_statustext("Reached destination", timeout=60) + # now enable avoidance and make sure we can't: + self.set_rc(10, 2000) + self.change_mode("ACRO") + self.wait_groundspeed(0, 0.7, timeout=60) + # watch for speed zero + self.wait_groundspeed(0, 0.2, timeout=120) + self.disarm_vehicle() def ServoRelayEvents(self): '''Test ServoRelayEvents''' @@ -734,75 +723,53 @@ def MAVProxy_SetModeUsingMode(self): def ModeSwitch(self): ''''Set modes via modeswitch''' - self.context_push() - ex = None - try: - self.set_parameter("MODE_CH", 8) - self.set_rc(8, 1000) - # mavutil.mavlink.ROVER_MODE_HOLD: - self.set_parameter("MODE6", 4) - # mavutil.mavlink.ROVER_MODE_ACRO - self.set_parameter("MODE5", 1) - self.set_rc(8, 1800) # PWM for mode6 - self.wait_mode("HOLD") - self.set_rc(8, 1700) # PWM for mode5 - self.wait_mode("ACRO") - self.set_rc(8, 1800) # PWM for mode6 - self.wait_mode("HOLD") - self.set_rc(8, 1700) # PWM for mode5 - self.wait_mode("ACRO") - except Exception as e: - self.print_exception_caught(e) - ex = e - - self.context_pop() - - if ex is not None: - raise ex + self.set_parameter("MODE_CH", 8) + self.set_rc(8, 1000) + # mavutil.mavlink.ROVER_MODE_HOLD: + self.set_parameter("MODE6", 4) + # mavutil.mavlink.ROVER_MODE_ACRO + self.set_parameter("MODE5", 1) + self.set_rc(8, 1800) # PWM for mode6 + self.wait_mode("HOLD") + self.set_rc(8, 1700) # PWM for mode5 + self.wait_mode("ACRO") + self.set_rc(8, 1800) # PWM for mode6 + self.wait_mode("HOLD") + self.set_rc(8, 1700) # PWM for mode5 + self.wait_mode("ACRO") def AuxModeSwitch(self): '''Set modes via auxswitches''' - self.context_push() - ex = None - try: - # from mavproxy_rc.py - mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815] - self.set_parameter("MODE1", 1) # acro - self.set_rc(8, mapping[1]) - self.wait_mode('ACRO') - - self.set_rc(9, 1000) - self.set_rc(10, 1000) - 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) - self.wait_mode("HOLD") - - # reset both switches - should go back to ACRO - self.set_rc(9, 1000) - self.set_rc(10, 1000) - self.wait_mode("ACRO") - - self.set_rc(9, 1900) - self.wait_mode("STEERING") - self.set_rc(10, 1900) - self.wait_mode("HOLD") - - self.set_rc(10, 1000) # this re-polls the mode switch - self.wait_mode("ACRO") - self.set_rc(9, 1000) - except Exception as e: - self.print_exception_caught(e) - ex = e + # from mavproxy_rc.py + mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815] + self.set_parameter("MODE1", 1) # acro + self.set_rc(8, mapping[1]) + self.wait_mode('ACRO') - self.context_pop() + self.set_rc(9, 1000) + self.set_rc(10, 1000) + 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) + self.wait_mode("HOLD") + + # reset both switches - should go back to ACRO + self.set_rc(9, 1000) + self.set_rc(10, 1000) + self.wait_mode("ACRO") - if ex is not None: - raise ex + self.set_rc(9, 1900) + self.wait_mode("STEERING") + self.set_rc(10, 1900) + self.wait_mode("HOLD") + + self.set_rc(10, 1000) # this re-polls the mode switch + self.wait_mode("ACRO") + self.set_rc(9, 1000) def RCOverridesCancel(self): '''Test RC overrides Cancel''' @@ -877,337 +844,314 @@ def RCOverridesCancel(self): def RCOverrides(self): '''Test RC overrides''' - self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) - ex = None - try: - self.set_parameter("RC12_OPTION", 46) - self.reboot_sitl() - - self.change_mode('MANUAL') - self.wait_ready_to_arm() - self.set_rc(3, 1500) # throttle at zero - self.arm_vehicle() - # start moving forward a little: - normal_rc_throttle = 1700 - self.set_rc(3, normal_rc_throttle) - self.wait_groundspeed(5, 100) - - # allow overrides: - self.set_rc(12, 2000) - - # now override to stop: - throttle_override = 1500 + self.set_parameter("RC12_OPTION", 46) + self.reboot_sitl() - tstart = self.get_sim_time_cached() - while True: - if self.get_sim_time_cached() - tstart > 10: - raise AutoTestTimeoutException("Did not reach speed") - self.progress("Sending throttle of %u" % (throttle_override,)) - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - 65535, # chan1_raw - 65535, # chan2_raw - throttle_override, # chan3_raw - 65535, # chan4_raw - 65535, # chan5_raw - 65535, # chan6_raw - 65535, # chan7_raw - 65535) # chan8_raw - - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - want_speed = 2.0 - self.progress("Speed=%f want=<%f" % (m.groundspeed, want_speed)) - if m.groundspeed < want_speed: - break + self.change_mode('MANUAL') + self.wait_ready_to_arm() + self.set_rc(3, 1500) # throttle at zero + self.arm_vehicle() + # start moving forward a little: + normal_rc_throttle = 1700 + self.set_rc(3, normal_rc_throttle) + self.wait_groundspeed(5, 100) - # now override to stop - but set the switch on the RC - # transmitter to deny overrides; this should send the - # speed back up to 5 metres/second: - self.set_rc(12, 1000) + # allow overrides: + self.set_rc(12, 2000) - throttle_override = 1500 - tstart = self.get_sim_time_cached() - while True: - if self.get_sim_time_cached() - tstart > 10: - raise AutoTestTimeoutException("Did not speed back up") - self.progress("Sending throttle of %u" % (throttle_override,)) - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - 65535, # chan1_raw - 65535, # chan2_raw - throttle_override, # chan3_raw - 65535, # chan4_raw - 65535, # chan5_raw - 65535, # chan6_raw - 65535, # chan7_raw - 65535) # chan8_raw - - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - want_speed = 5.0 - self.progress("Speed=%f want=>%f" % (m.groundspeed, want_speed)) - - if m.groundspeed > want_speed: - break + # now override to stop: + throttle_override = 1500 - # re-enable RC overrides - self.set_rc(12, 2000) - - # check we revert to normal RC inputs when gcs overrides cease: - self.progress("Waiting for RC to revert to normal RC input") - self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10) - - self.start_subtest("Check override time of zero disables overrides") - old = self.get_parameter("RC_OVERRIDE_TIME") - ch = 2 - self.set_rc(ch, 1000) - channels = [65535] * 18 - ch_override_value = 1700 - channels[ch-1] = ch_override_value - channels[7] = 1234 # that's channel 8! - self.progress("Sending override message %u" % ch_override_value) - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - *channels - ) - # long timeout required here as we may have sent a lot of - # things via MAVProxy... - self.wait_rc_channel_value(ch, ch_override_value, timeout=30) - self.set_parameter("RC_OVERRIDE_TIME", 0) - self.wait_rc_channel_value(ch, 1000) - self.set_parameter("RC_OVERRIDE_TIME", old) - self.wait_rc_channel_value(ch, ch_override_value) - - ch_override_value = 1720 - channels[ch-1] = ch_override_value - self.progress("Sending override message %u" % ch_override_value) + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > 10: + raise AutoTestTimeoutException("Did not reach speed") + self.progress("Sending throttle of %u" % (throttle_override,)) self.mav.mav.rc_channels_override_send( 1, # target system 1, # targe component - *channels - ) - self.wait_rc_channel_value(ch, ch_override_value, timeout=10) - self.set_parameter("RC_OVERRIDE_TIME", 0) - self.wait_rc_channel_value(ch, 1000) - self.set_parameter("RC_OVERRIDE_TIME", old) + 65535, # chan1_raw + 65535, # chan2_raw + throttle_override, # chan3_raw + 65535, # chan4_raw + 65535, # chan5_raw + 65535, # chan6_raw + 65535, # chan7_raw + 65535) # chan8_raw - self.progress("Ensuring timeout works") - self.wait_rc_channel_value(ch, 1000, timeout=5) - self.delay_sim_time(10) + m = self.mav.recv_match(type='VFR_HUD', blocking=True) + want_speed = 2.0 + self.progress("Speed=%f want=<%f" % (m.groundspeed, want_speed)) + if m.groundspeed < want_speed: + break - self.set_parameter("RC_OVERRIDE_TIME", 10) - self.progress("Sending override message") + # now override to stop - but set the switch on the RC + # transmitter to deny overrides; this should send the + # speed back up to 5 metres/second: + self.set_rc(12, 1000) - ch_override_value = 1730 - channels[ch-1] = ch_override_value - self.progress("Sending override message %u" % ch_override_value) - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - *channels - ) - self.wait_rc_channel_value(ch, ch_override_value, timeout=10) - tstart = self.get_sim_time() - self.progress("Waiting for channel to revert to 1000 in ~10s") - self.wait_rc_channel_value(ch, 1000, timeout=15) - delta = self.get_sim_time() - tstart - if delta > 12: - raise NotAchievedException("Took too long to revert RC channel value (delta=%f)" % delta) - min_delta = 9 - if delta < min_delta: - raise NotAchievedException("Didn't take long enough to revert RC channel value (delta=%f want>=%f)" % - (delta, min_delta)) - self.progress("Disabling RC override timeout") - self.set_parameter("RC_OVERRIDE_TIME", -1) - ch_override_value = 1740 - channels[ch-1] = ch_override_value - self.progress("Sending override message %u" % ch_override_value) + throttle_override = 1500 + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > 10: + raise AutoTestTimeoutException("Did not speed back up") + self.progress("Sending throttle of %u" % (throttle_override,)) self.mav.mav.rc_channels_override_send( 1, # target system 1, # targe component - *channels - ) - self.wait_rc_channel_value(ch, ch_override_value, timeout=10) - tstart = self.get_sim_time() - while True: - # warning: this is get_sim_time() and can slurp messages on you! - delta = self.get_sim_time() - tstart - if delta > 20: - break - m = self.assert_receive_message('RC_CHANNELS', timeout=1) - channel_field = "chan%u_raw" % ch - m_value = getattr(m, channel_field) - if m_value != ch_override_value: - raise NotAchievedException("Value reverted after %f seconds when it should not have (got=%u) (want=%u)" % (delta, m_value, ch_override_value)) # noqa - self.set_parameter("RC_OVERRIDE_TIME", old) + 65535, # chan1_raw + 65535, # chan2_raw + throttle_override, # chan3_raw + 65535, # chan4_raw + 65535, # chan5_raw + 65535, # chan6_raw + 65535, # chan7_raw + 65535) # chan8_raw - self.delay_sim_time(10) + m = self.mav.recv_match(type='VFR_HUD', blocking=True) + want_speed = 5.0 + self.progress("Speed=%f want=>%f" % (m.groundspeed, want_speed)) - self.start_subtest("Checking higher-channel semantics") - self.context_push() - self.set_parameter("RC_OVERRIDE_TIME", 30) + if m.groundspeed > want_speed: + break - ch = 11 - rc_value = 1010 - self.set_rc(ch, rc_value) + # re-enable RC overrides + self.set_rc(12, 2000) + + # check we revert to normal RC inputs when gcs overrides cease: + self.progress("Waiting for RC to revert to normal RC input") + self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10) + + self.start_subtest("Check override time of zero disables overrides") + old = self.get_parameter("RC_OVERRIDE_TIME") + ch = 2 + self.set_rc(ch, 1000) + channels = [65535] * 18 + ch_override_value = 1700 + channels[ch-1] = ch_override_value + channels[7] = 1234 # that's channel 8! + self.progress("Sending override message %u" % ch_override_value) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + # long timeout required here as we may have sent a lot of + # things via MAVProxy... + self.wait_rc_channel_value(ch, ch_override_value, timeout=30) + self.set_parameter("RC_OVERRIDE_TIME", 0) + self.wait_rc_channel_value(ch, 1000) + self.set_parameter("RC_OVERRIDE_TIME", old) + self.wait_rc_channel_value(ch, ch_override_value) + + ch_override_value = 1720 + channels[ch-1] = ch_override_value + self.progress("Sending override message %u" % ch_override_value) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + self.set_parameter("RC_OVERRIDE_TIME", 0) + self.wait_rc_channel_value(ch, 1000) + self.set_parameter("RC_OVERRIDE_TIME", old) - channels = [65535] * 18 - ch_override_value = 1234 - channels[ch-1] = ch_override_value - self.progress("Sending override message ch%u=%u" % (ch, ch_override_value)) - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - *channels - ) - self.progress("Wait for override value") - self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + self.progress("Ensuring timeout works") + self.wait_rc_channel_value(ch, 1000, timeout=5) + self.delay_sim_time(10) - self.progress("Sending return-to-RC-input value") - channels[ch-1] = 65534 - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - *channels - ) - self.wait_rc_channel_value(ch, rc_value, timeout=10) + self.set_parameter("RC_OVERRIDE_TIME", 10) + self.progress("Sending override message") + + ch_override_value = 1730 + channels[ch-1] = ch_override_value + self.progress("Sending override message %u" % ch_override_value) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + tstart = self.get_sim_time() + self.progress("Waiting for channel to revert to 1000 in ~10s") + self.wait_rc_channel_value(ch, 1000, timeout=15) + delta = self.get_sim_time() - tstart + if delta > 12: + raise NotAchievedException("Took too long to revert RC channel value (delta=%f)" % delta) + min_delta = 9 + if delta < min_delta: + raise NotAchievedException("Didn't take long enough to revert RC channel value (delta=%f want>=%f)" % + (delta, min_delta)) + self.progress("Disabling RC override timeout") + self.set_parameter("RC_OVERRIDE_TIME", -1) + ch_override_value = 1740 + channels[ch-1] = ch_override_value + self.progress("Sending override message %u" % ch_override_value) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + tstart = self.get_sim_time() + while True: + # warning: this is get_sim_time() and can slurp messages on you! + delta = self.get_sim_time() - tstart + if delta > 20: + break + m = self.assert_receive_message('RC_CHANNELS', timeout=1) + channel_field = "chan%u_raw" % ch + m_value = getattr(m, channel_field) + if m_value != ch_override_value: + raise NotAchievedException("Value reverted after %f seconds when it should not have (got=%u) (want=%u)" % (delta, m_value, ch_override_value)) # noqa + self.set_parameter("RC_OVERRIDE_TIME", old) + + self.delay_sim_time(10) - channels[ch-1] = ch_override_value - self.progress("Sending override message ch%u=%u" % (ch, ch_override_value)) + self.start_subtest("Checking higher-channel semantics") + self.context_push() + self.set_parameter("RC_OVERRIDE_TIME", 30) + + ch = 11 + rc_value = 1010 + self.set_rc(ch, rc_value) + + channels = [65535] * 18 + ch_override_value = 1234 + channels[ch-1] = ch_override_value + self.progress("Sending override message ch%u=%u" % (ch, ch_override_value)) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.progress("Wait for override value") + self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + + self.progress("Sending return-to-RC-input value") + channels[ch-1] = 65534 + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.wait_rc_channel_value(ch, rc_value, timeout=10) + + channels[ch-1] = ch_override_value + self.progress("Sending override message ch%u=%u" % (ch, ch_override_value)) + self.mav.mav.rc_channels_override_send( + 1, # target system + 1, # targe component + *channels + ) + self.progress("Wait for override value") + self.wait_rc_channel_value(ch, ch_override_value, timeout=10) + + # make we keep the override vaue for at least 10 seconds: + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 10: + break + # try both ignore values: + ignore_value = 0 + if self.get_sim_time_cached() - tstart > 5: + ignore_value = 65535 + self.progress("Sending ignore value %u" % ignore_value) + channels[ch-1] = ignore_value self.mav.mav.rc_channels_override_send( 1, # target system 1, # targe component *channels ) - self.progress("Wait for override value") - self.wait_rc_channel_value(ch, ch_override_value, timeout=10) - - # make we keep the override vaue for at least 10 seconds: - tstart = self.get_sim_time() - while True: - if self.get_sim_time_cached() - tstart > 10: - break - # try both ignore values: - ignore_value = 0 - if self.get_sim_time_cached() - tstart > 5: - ignore_value = 65535 - self.progress("Sending ignore value %u" % ignore_value) - channels[ch-1] = ignore_value - self.mav.mav.rc_channels_override_send( - 1, # target system - 1, # targe component - *channels - ) - if self.get_rc_channel_value(ch) != ch_override_value: - raise NotAchievedException("Did not maintain value") - - self.context_pop() + if self.get_rc_channel_value(ch) != ch_override_value: + raise NotAchievedException("Did not maintain value") - self.end_subtest("Checking higher-channel semantics") + self.context_pop() - except Exception as e: - self.print_exception_caught(e) - ex = e + self.end_subtest("Checking higher-channel semantics") - self.context_pop() self.disarm_vehicle() - self.reboot_sitl() - - if ex is not None: - raise ex def MANUAL_CONTROL(self): '''Test mavlink MANUAL_CONTROL''' - self.context_push() - self.set_parameter("SYSID_MYGCS", self.mav.source_system) - ex = None - try: - self.set_parameter("RC12_OPTION", 46) # enable/disable rc overrides - self.reboot_sitl() - - self.change_mode("MANUAL") - self.wait_ready_to_arm() - self.zero_throttle() - self.arm_vehicle() - self.progress("start moving forward a little") - normal_rc_throttle = 1700 - self.set_rc(3, normal_rc_throttle) - self.wait_groundspeed(5, 100) - - self.progress("allow overrides") - self.set_rc(12, 2000) + self.set_parameters({ + "SYSID_MYGCS": self.mav.source_system, + "RC12_OPTION": 46, # enable/disable rc overrides + }) + self.reboot_sitl() - self.progress("now override to stop") - throttle_override_normalized = 0 - expected_throttle = 0 # in VFR_HUD + self.change_mode("MANUAL") + self.wait_ready_to_arm() + self.arm_vehicle() + self.progress("start moving forward a little") + normal_rc_throttle = 1700 + self.set_rc(3, normal_rc_throttle) + self.wait_groundspeed(5, 100) - tstart = self.get_sim_time_cached() - while True: - if self.get_sim_time_cached() - tstart > 10: - raise AutoTestTimeoutException("Did not reach speed") - self.progress("Sending normalized throttle of %d" % (throttle_override_normalized,)) - self.mav.mav.manual_control_send( - 1, # target system - 32767, # x (pitch) - 32767, # y (roll) - throttle_override_normalized, # z (thrust) - 32767, # r (yaw) - 0) # button mask - - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - want_speed = 2.0 - self.progress("Speed=%f want=<%f throttle=%u want=%u" % - (m.groundspeed, want_speed, m.throttle, expected_throttle)) - if m.groundspeed < want_speed and m.throttle == expected_throttle: - break + self.progress("allow overrides") + self.set_rc(12, 2000) - self.progress("now override to stop - but set the switch on the RC transmitter to deny overrides; this should send the speed back up to 5 metres/second") # noqa - self.set_rc(12, 1000) + self.progress("now override to stop") + throttle_override_normalized = 0 + expected_throttle = 0 # in VFR_HUD - throttle_override_normalized = 500 - expected_throttle = 36 # in VFR_HUD, corresponding to normal_rc_throttle adjusted for channel min/max + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > 10: + raise AutoTestTimeoutException("Did not reach speed") + self.progress("Sending normalized throttle of %d" % (throttle_override_normalized,)) + self.mav.mav.manual_control_send( + 1, # target system + 32767, # x (pitch) + 32767, # y (roll) + throttle_override_normalized, # z (thrust) + 32767, # r (yaw) + 0) # button mask + + m = self.mav.recv_match(type='VFR_HUD', blocking=True) + want_speed = 2.0 + self.progress("Speed=%f want=<%f throttle=%u want=%u" % + (m.groundspeed, want_speed, m.throttle, expected_throttle)) + if m.groundspeed < want_speed and m.throttle == expected_throttle: + break - tstart = self.get_sim_time_cached() - while True: - if self.get_sim_time_cached() - tstart > 10: - raise AutoTestTimeoutException("Did not stop") - self.progress("Sending normalized throttle of %u" % (throttle_override_normalized,)) - self.mav.mav.manual_control_send( - 1, # target system - 32767, # x (pitch) - 32767, # y (roll) - throttle_override_normalized, # z (thrust) - 32767, # r (yaw) - 0) # button mask - - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - want_speed = 5.0 - - self.progress("Speed=%f want=>%f throttle=%u want=%u" % - (m.groundspeed, want_speed, m.throttle, expected_throttle)) - if m.groundspeed > want_speed and m.throttle == expected_throttle: - break + self.progress("now override to stop - but set the switch on the RC transmitter to deny overrides; this should send the speed back up to 5 metres/second") # noqa + self.set_rc(12, 1000) - # re-enable RC overrides - self.set_rc(12, 2000) + throttle_override_normalized = 500 + expected_throttle = 36 # in VFR_HUD, corresponding to normal_rc_throttle adjusted for channel min/max - # check we revert to normal RC inputs when gcs overrides cease: - self.progress("Waiting for RC to revert to normal RC input") - self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10) + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > 10: + raise AutoTestTimeoutException("Did not stop") + self.progress("Sending normalized throttle of %u" % (throttle_override_normalized,)) + self.mav.mav.manual_control_send( + 1, # target system + 32767, # x (pitch) + 32767, # y (roll) + throttle_override_normalized, # z (thrust) + 32767, # r (yaw) + 0) # button mask + + m = self.mav.recv_match(type='VFR_HUD', blocking=True) + want_speed = 5.0 + + self.progress("Speed=%f want=>%f throttle=%u want=%u" % + (m.groundspeed, want_speed, m.throttle, expected_throttle)) + if m.groundspeed > want_speed and m.throttle == expected_throttle: + break - except Exception as e: - self.print_exception_caught(e) - ex = e + # re-enable RC overrides + self.set_rc(12, 2000) - self.context_pop() - self.disarm_vehicle() - self.reboot_sitl() + # check we revert to normal RC inputs when gcs overrides cease: + self.progress("Waiting for RC to revert to normal RC input") + self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10) - if ex is not None: - raise ex + self.disarm_vehicle() def CameraMission(self): '''Test Camera Mission Items''' @@ -2587,7 +2531,7 @@ def assert_receive_mission_ack(self, mission_type, raise NotAchievedException("Unexpected mission type %u want=%u" % (m.mission_type, mission_type)) if m.type != want_type: - raise NotAchievedException("Expected ack type got %u got %u" % + raise NotAchievedException("Expected ack type %u got %u" % (want_type, m.type)) def assert_filepath_content(self, filepath, want): @@ -3652,8 +3596,75 @@ def drain_self_mav_fn(): raise e self.reboot_sitl() + def ClearMission(self, target_system=1, target_component=1): + '''check mission clearing''' + + self.start_subtest("Clear via mission_clear_all message") + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + ]) + self.set_current_waypoint(3) + + self.mav.mav.mission_clear_all_send( + target_system, + target_component, + mavutil.mavlink.MAV_MISSION_TYPE_MISSION + ) + + self.assert_current_waypoint(0) + + self.drain_mav() + + self.start_subtest("No clear mission while it is being uploaded by a different node") + mav2 = mavutil.mavlink_connection("tcp:localhost:5763", + robust_parsing=True, + source_system=7, + source_component=7) + self.context_push() + self.context_collect("MISSION_REQUEST") + mav2.mav.mission_count_send(target_system, + target_component, + 17, + mavutil.mavlink.MAV_MISSION_TYPE_MISSION) + ack = self.assert_receive_message('MISSION_REQUEST', check_context=True, mav=mav2) + self.context_pop() + + self.context_push() + self.context_collect("MISSION_ACK") + self.mav.mav.mission_clear_all_send( + target_system, + target_component, + mavutil.mavlink.MAV_MISSION_TYPE_MISSION + ) + ack = self.assert_receive_message('MISSION_ACK', check_context=True) + self.assert_message_field_values(ack, { + "type": mavutil.mavlink.MAV_MISSION_DENIED, + }) + self.context_pop() + + self.progress("Test cancel upload from second connection") + self.context_push() + self.context_collect("MISSION_ACK") + mav2.mav.mission_clear_all_send( + target_system, + target_component, + mavutil.mavlink.MAV_MISSION_TYPE_MISSION + ) + ack = self.assert_receive_message('MISSION_ACK', mav=mav2, check_context=True) + self.assert_message_field_values(ack, { + "type": mavutil.mavlink.MAV_MISSION_ACCEPTED, + }) + self.context_pop() + mav2.close() + del mav2 + def GCSMission(self): '''check MAVProxy's waypoint handling of missions''' + target_system = 1 target_component = 1 mavproxy = self.start_mavproxy() @@ -3661,7 +3672,7 @@ def GCSMission(self): self.delay_sim_time(1) if self.get_parameter("MIS_TOTAL") != 0: raise NotAchievedException("Failed to clear mission") - m = self.assert_receive_message('MISSION_CURRENT', timeout=5) + m = self.assert_receive_message('MISSION_CURRENT', timeout=5, verbose=True) if m.seq != 0: raise NotAchievedException("Bad mission current") self.load_mission_using_mavproxy(mavproxy, "rover-gripper-mission.txt") @@ -3675,7 +3686,7 @@ def GCSMission(self): # oldalt = downloaded_items[changealt_item].z want_newalt = 37.2 mavproxy.send('wp changealt %u %f\n' % (changealt_item, want_newalt)) - self.delay_sim_time(5) + self.delay_sim_time(15) downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) if abs(downloaded_items[changealt_item].z - want_newalt) > 0.0001: raise NotAchievedException( @@ -3931,11 +3942,11 @@ def drive_somewhere_breach_boundary_and_rtl(self, loc, target_system=1, target_c continue t = m.get_type() if t == "POSITION_TARGET_GLOBAL_INT": - print("Target: (%s)" % str(m)) + self.progress("Target: (%s)" % str(m)) elif t == "GLOBAL_POSITION_INT": - print("Position: (%s)" % str(m)) + self.progress("Position: (%s)" % str(m)) elif t == "FENCE_STATUS": - print("Fence: %s" % str(m)) + self.progress("Fence: %s" % str(m)) if m.breach_status != 0: seen_fence_breach = True self.progress("Fence breach detected!") @@ -4040,6 +4051,9 @@ def test_poly_fence_noarms(self, target_system=1, target_component=1): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, target_system=target_system, target_component=target_component) + self.set_parameters({ + "FENCE_TYPE": 2, # circle only + }) self.delay_sim_time(5) # let breaches clear # FIXME: should we allow this? self.progress("Ensure we can arm with no poly in place") @@ -4047,6 +4061,9 @@ def test_poly_fence_noarms(self, target_system=1, target_component=1): self.wait_ready_to_arm() self.arm_vehicle() self.disarm_vehicle() + self.set_parameters({ + "FENCE_TYPE": 6, # polyfence + circle + }) self.test_poly_fence_noarms_exclusion_circle(target_system=target_system, target_component=target_component) @@ -4174,22 +4191,22 @@ def test_poly_fence_noarms_exclusion_polyfence(self, target_system=1, target_com here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # over the top of the vehicle - self.offset_location_ne(here, -50, -50), # bl - self.offset_location_ne(here, -50, 50), # br - self.offset_location_ne(here, 50, 50), # tr - self.offset_location_ne(here, 50, -50), # tl, - ] - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ]), + ]) self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz self.drain_mav() self.assert_fence_breached() @@ -4210,22 +4227,22 @@ def test_poly_fence_noarms_inclusion_polyfence(self, target_system=1, target_com here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # over the top of the vehicle - self.offset_location_ne(here, -50, -50), # bl - self.offset_location_ne(here, -50, 50), # br - self.offset_location_ne(here, 50, 50), # tr - self.offset_location_ne(here, 50, -50), # tl, - ] - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ]), + ]) self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz self.drain_mav() self.assert_fence_breached() @@ -4584,22 +4601,22 @@ def test_poly_fence_compatability(self, target_system=1, target_component=1): def test_poly_fence_reboot_survivability(self): here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # over the top of the vehicle - self.offset_location_ne(here, -50, -50), # bl - self.offset_location_ne(here, -50, 50), # br - self.offset_location_ne(here, 50, 50), # tr - self.offset_location_ne(here, 50, -50), # tl, - ] - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ]), + ]) self.reboot_sitl() downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE) downloaded_len = len(downloaded_items) @@ -4642,18 +4659,16 @@ def PolyFence(self): def test_poly_fence_inclusion_overlapping_inclusion_circles(self, here, target_system=1, target_component=1): self.start_subtest("Overlapping circular inclusion") - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, - [ - { - "radius": 30, - "loc": self.offset_location_ne(here, -20, 0), - }, - { - "radius": 30, - "loc": self.offset_location_ne(here, 20, 0), - }, - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, { + "radius": 30, + "loc": self.offset_location_ne(here, -20, 0), + }), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, { + "radius": 30, + "loc": self.offset_location_ne(here, 20, 0), + }), + ]) if self.mavproxy is not None: # handy for getting pretty pictures self.mavproxy.send("fence list\n") @@ -4681,20 +4696,18 @@ def test_poly_fence_inclusion(self, here, target_system=1, target_component=1): target_system=target_system, target_component=target_component) - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - [ - self.offset_location_ne(here, -40, -20), # tl - self.offset_location_ne(here, 50, -20), # tr - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, -40, 20), # bl, - ], - { - "radius": 30, - "loc": self.offset_location_ne(here, -20, 0), - }, - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + self.offset_location_ne(here, -40, -20), # tl + self.offset_location_ne(here, 50, -20), # tr + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, -40, 20), # bl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, { + "radius": 30, + "loc": self.offset_location_ne(here, -20, 0), + }), + ]) self.delay_sim_time(5) if self.mavproxy is not None: @@ -4714,22 +4727,20 @@ def test_poly_fence_inclusion(self, here, target_system=1, target_component=1): target_system=target_system, target_component=target_component) - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - [ - self.offset_location_ne(here, -20, -25), # tl - self.offset_location_ne(here, 50, -25), # tr - self.offset_location_ne(here, 50, 15), # br - self.offset_location_ne(here, -20, 15), # bl, - ], - [ - self.offset_location_ne(here, 20, -20), # tl - self.offset_location_ne(here, -50, -20), # tr - self.offset_location_ne(here, -50, 20), # br - self.offset_location_ne(here, 20, 20), # bl, - ], - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + self.offset_location_ne(here, -20, -25), # tl + self.offset_location_ne(here, 50, -25), # tr + self.offset_location_ne(here, 50, 15), # br + self.offset_location_ne(here, -20, 15), # bl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + self.offset_location_ne(here, 20, -20), # tl + self.offset_location_ne(here, -50, -20), # tr + self.offset_location_ne(here, -50, 20), # br + self.offset_location_ne(here, 20, 20), # bl, + ]), + ]) self.delay_sim_time(5) if self.mavproxy is not None: @@ -4751,24 +4762,26 @@ def test_poly_fence_inclusion(self, here, target_system=1, target_component=1): def test_poly_fence_exclusion(self, here, target_system=1, target_component=1): - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # west - self.offset_location_ne(here, -50, -20), # tl - self.offset_location_ne(here, 50, -20), # tr - self.offset_location_ne(here, 50, -40), # br - self.offset_location_ne(here, -50, -40), # bl, - ], { - "radius": 30, - "loc": self.offset_location_ne(here, -60, 0), - }, - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # west + self.offset_location_ne(here, -50, -20), # tl + self.offset_location_ne(here, 50, -20), # tr + self.offset_location_ne(here, 50, -40), # br + self.offset_location_ne(here, -50, -40), # bl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION, { + "radius": 30, + "loc": self.offset_location_ne(here, -60, 0), + }), + ]) self.delay_sim_time(5) if self.mavproxy is not None: self.mavproxy.send("fence list\n") @@ -4848,54 +4861,41 @@ def MotorTest(self): self.wait_servo_channel_value(3, self.get_parameter("RC3_TRIM", 5), timeout=10) self.wait_disarmed() - def test_poly_fence_object_avoidance_guided(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceGuided(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - guided mode''' if not self.mavproxy_can_do_mision_item_protocols(): return self.test_poly_fence_object_avoidance_guided_pathfinding( target_system=target_system, target_component=target_component) - return - # twosquares is currently disabled because of the requirement to have an inclusion fence (which it doesn't have ATM) - # self.test_poly_fence_object_avoidance_guided_two_squares( - # target_system=target_system, - # target_component=target_component) + self.test_poly_fence_object_avoidance_guided_two_squares( + target_system=target_system, + target_component=target_component) - def test_poly_fence_object_avoidance_auto(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceAuto(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - auto mode''' mavproxy = self.start_mavproxy() self.load_fence_using_mavproxy(mavproxy, "rover-path-planning-fence.txt") self.stop_mavproxy(mavproxy) # self.load_fence("rover-path-planning-fence.txt") self.load_mission("rover-path-planning-mission.txt") - self.context_push() - ex = None - try: - 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() - self.arm_vehicle() - self.set_parameter("FENCE_ENABLE", 1) - if self.mavproxy is not None: - self.mavproxy.send("fence list\n") - # target_loc is copied from the mission file - target_loc = mavutil.location(40.073799, -105.229156) - self.wait_location(target_loc, height_accuracy=None, timeout=300) - # mission has RTL as last item - self.wait_distance_to_home(3, 7, timeout=300) - self.disarm_vehicle() - except Exception as e: - self.disarm_vehicle(force=True) - self.print_exception_caught(e) - ex = e - self.context_pop() + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 2, + "FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + }) self.reboot_sitl() - if ex is not None: - raise ex + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_parameter("FENCE_ENABLE", 1) + # target_loc is copied from the mission file + target_loc = mavutil.location(40.073799, -105.229156) + self.wait_location(target_loc, height_accuracy=None, timeout=300) + # mission has RTL as last item + self.wait_distance_to_home(3, 7, timeout=300) + self.disarm_vehicle() def send_guided_mission_item(self, loc, target_system=1, target_component=1): self.mav.mav.mission_item_send( @@ -4917,93 +4917,72 @@ def send_guided_mission_item(self, loc, target_system=1, target_component=1): def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, target_component=1): self.load_fence("rover-path-planning-fence.txt") - self.context_push() - ex = None - try: - 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() - self.arm_vehicle() - self.set_parameter("FENCE_ENABLE", 1) - if self.mavproxy is not None: - self.mavproxy.send("fence list\n") - target_loc = mavutil.location(40.073800, -105.229172) - self.send_guided_mission_item(target_loc, - target_system=target_system, - target_component=target_component) - self.wait_location(target_loc, timeout=300) - self.do_RTL(timeout=300) - self.disarm_vehicle() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 2, + "FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + }) self.reboot_sitl() - if ex is not None: - raise ex + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_parameter("FENCE_ENABLE", 1) + target_loc = mavutil.location(40.073800, -105.229172) + self.send_guided_mission_item(target_loc, + target_system=target_system, + target_component=target_component) + self.wait_location(target_loc, timeout=300) + self.do_RTL(timeout=300) + self.disarm_vehicle() def WheelEncoders(self): '''make sure wheel encoders are generally working''' - ex = None - try: - 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() - self.change_mode("MANUAL") - self.arm_vehicle() - self.set_rc(3, 1600) + 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() + self.change_mode("MANUAL") + self.arm_vehicle() + self.set_rc(3, 1600) - m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5) + m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5) - tstart = self.get_sim_time() - while True: - if self.get_sim_time_cached() - tstart > 10: - break - dist_home = self.distance_to_home(use_cached_home=True) - m = self.mav.messages.get("WHEEL_DISTANCE") - delta = abs(m.distance[0] - dist_home) - self.progress("dist-home=%f wheel-distance=%f delta=%f" % - (dist_home, m.distance[0], delta)) - if delta > 5: - raise NotAchievedException("wheel distance incorrect") - self.disarm_vehicle() - except Exception as e: - self.print_exception_caught(e) - self.disarm_vehicle() - ex = e - self.reboot_sitl() - if ex is not None: - raise ex + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 10: + break + dist_home = self.distance_to_home(use_cached_home=True) + m = self.mav.messages.get("WHEEL_DISTANCE") + delta = abs(m.distance[0] - dist_home) + self.progress("dist-home=%f wheel-distance=%f delta=%f" % + (dist_home, m.distance[0], delta)) + if delta > 5: + raise NotAchievedException("wheel distance incorrect") + self.disarm_vehicle() def test_poly_fence_object_avoidance_guided_two_squares(self, target_system=1, target_component=1): self.start_subtest("Ensure we can steer around obstacles in guided mode") here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 10), # tl - self.offset_location_ne(here, 50, 30), # tr - self.offset_location_ne(here, -50, 40), # br, - ], - [ # further east (and south - self.offset_location_ne(here, -60, 60), # bl - self.offset_location_ne(here, 40, 70), # tl - self.offset_location_ne(here, 40, 90), # tr - self.offset_location_ne(here, -60, 80), # br, - ], - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 10), # tl + self.offset_location_ne(here, 50, 30), # tr + self.offset_location_ne(here, -50, 40), # br, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # further east (and south + self.offset_location_ne(here, -60, 60), # bl + self.offset_location_ne(here, 40, 70), # tl + self.offset_location_ne(here, 40, 90), # tr + self.offset_location_ne(here, -60, 80), # br, + ]), + ]) if self.mavproxy is not None: self.mavproxy.send("fence list\n") self.context_push() @@ -5040,24 +5019,26 @@ def test_poly_fence_object_avoidance_guided_two_squares(self, target_system=1, t def test_poly_fence_avoidance_dont_breach_exclusion(self, target_system=1, target_component=1): self.start_subtest("Ensure we stop before breaching an exclusion fence") here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # west - self.offset_location_ne(here, -50, -20), # tl - self.offset_location_ne(here, 50, -20), # tr - self.offset_location_ne(here, 50, -40), # br - self.offset_location_ne(here, -50, -40), # bl, - ], { - "radius": 30, - "loc": self.offset_location_ne(here, -60, 0), - }, - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # west + self.offset_location_ne(here, -50, -20), # tl + self.offset_location_ne(here, 50, -20), # tr + self.offset_location_ne(here, 50, -40), # br + self.offset_location_ne(here, -50, -40), # bl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, { + "radius": 30, + "loc": self.offset_location_ne(here, -60, 0), + }), + ]) if self.mavproxy is not None: self.mavproxy.send("fence list\n") self.set_parameters({ @@ -5087,165 +5068,92 @@ def PolyFenceAvoidance(self, target_system=1, target_component=1): self.arm_vehicle() self.change_mode("MANUAL") self.reach_heading_manual(180, turn_right=False) - self.change_mode("GUIDED") - - self.test_poly_fence_avoidance_dont_breach_exclusion(target_system=target_system, target_component=target_component) - - self.disarm_vehicle() - - def test_poly_fence_object_avoidance_guided_bendy_ruler(self, target_system=1, target_component=1): - if not self.mavproxy_can_do_mision_item_protocols(): - return - self.load_fence("rover-path-bendyruler-fence.txt") - self.context_push() - ex = None - try: - 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_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) - self.send_guided_mission_item(target_loc, - target_system=target_system, - target_component=target_component) - # FIXME: we don't get within WP_RADIUS of our target?! - self.wait_location(target_loc, timeout=300, accuracy=15) - self.do_RTL(timeout=300) - self.disarm_vehicle() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.disarm_vehicle() - self.reboot_sitl() - if ex is not None: - raise ex - - 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( - target_system=target_system, target_component=target_component) - self.test_poly_fence_object_avoidance_guided_bendy_ruler_easier( - target_system=target_system, target_component=target_component) - - def test_poly_fence_object_avoidance_guided_bendy_ruler_easier(self, target_system=1, target_component=1): - '''finish-line issue means we can't complete the harder one. This - test can go away once we've nailed that one. The only - difference here is the target point. - ''' - if not self.mavproxy_can_do_mision_item_protocols(): - return - self.load_fence("rover-path-bendyruler-fence.txt") - self.context_push() - ex = None - try: - 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_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) - self.send_guided_mission_item(target_loc, - target_system=target_system, - target_component=target_component) - # FIXME: we don't get within WP_RADIUS of our target?! - self.wait_location(target_loc, timeout=300, accuracy=15) - self.do_RTL(timeout=300) - self.disarm_vehicle() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() + self.change_mode("GUIDED") + + self.test_poly_fence_avoidance_dont_breach_exclusion(target_system=target_system, target_component=target_component) + self.disarm_vehicle() + + def PolyFenceObjectAvoidanceBendyRuler(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - bendy ruler''' + self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt") + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) self.reboot_sitl() - if ex is not None: - raise ex + self.set_parameters({ + "OA_BR_LOOKAHEAD": 50, + }) + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + target_loc = mavutil.location(40.071060, -105.227734, 1584, 0) + self.send_guided_mission_item(target_loc, + target_system=target_system, + target_component=target_component) + # FIXME: we don't get within WP_RADIUS of our target?! + self.wait_location(target_loc, timeout=300, accuracy=15) + self.do_RTL(timeout=300) + self.disarm_vehicle() - def test_poly_fence_object_avoidance_auto_bendy_ruler_easier(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceBendyRulerEasierGuided(self, target_system=1, target_component=1): '''finish-line issue means we can't complete the harder one. This test can go away once we've nailed that one. The only difference here is the target point. ''' - if not self.mavproxy_can_do_mision_item_protocols(): - return - - self.load_fence("rover-path-bendyruler-fence.txt") - self.load_mission("rover-path-bendyruler-mission-easier.txt") - self.context_push() - ex = None - try: - 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_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) - # target_loc is copied from the mission file - self.wait_location(target_loc, timeout=300) - # mission has RTL as last item - self.wait_distance_to_home(3, 7, timeout=300) - self.disarm_vehicle() - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() - self.disarm_vehicle() + self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt") + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) self.reboot_sitl() - if ex is not None: - raise ex + self.set_parameters({ + "OA_BR_LOOKAHEAD": 60, + }) + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + target_loc = mavutil.location(40.071260, -105.227000, 1584, 0) + self.send_guided_mission_item(target_loc, + target_system=target_system, + target_component=target_component) + # FIXME: we don't get within WP_RADIUS of our target?! + self.wait_location(target_loc, timeout=300, accuracy=15) + self.do_RTL(timeout=300) + self.disarm_vehicle() - def PolyFenceObjectAvoidance(self, target_system=1, target_component=1): - '''PolyFence object avoidance tests''' - self.test_poly_fence_object_avoidance_auto( - target_system=target_system, - target_component=target_component) - self.test_poly_fence_object_avoidance_guided( - target_system=target_system, - target_component=target_component) + def PolyFenceObjectAvoidanceBendyRulerEasierAuto(self, target_system=1, target_component=1): + '''finish-line issue means we can't complete the harder one. This + test can go away once we've nailed that one. The only + difference here is the target point. + ''' + self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt") + self.load_mission("rover-path-bendyruler-mission-easier.txt") - 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 - # it gets a simpler test: - self.test_poly_fence_object_avoidance_guided_bendy_ruler( - target_system=target_system, - target_component=target_component, - ) + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, # BendyRuler + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) + self.reboot_sitl() + self.set_parameters({ + "OA_BR_LOOKAHEAD": 60, + }) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + target_loc = mavutil.location(40.071260, -105.227000, 1584, 0) + # target_loc is copied from the mission file + self.wait_location(target_loc, timeout=300) + # mission has RTL as last item + self.wait_distance_to_home(3, 7, timeout=300) + self.disarm_vehicle() def test_scripting_simple_loop(self): self.start_subtest("Scripting simple loop") @@ -5290,13 +5198,14 @@ def test_scripting_internal_test(self): }) self.install_test_modules_context() self.install_mavlink_module_context() - for script in [ - "scripting_test.lua", - "math.lua", - "strings.lua", - "mavlink_test.lua", - ]: - self.install_test_script_context(script) + + self.install_test_scripts_context([ + "scripting_test.lua", + "scripting_require_test_2.lua", + "math.lua", + "strings.lua", + "mavlink_test.lua", + ]) self.context_collect('STATUSTEXT') self.context_collect('NAMED_VALUE_FLOAT') @@ -5305,6 +5214,7 @@ def test_scripting_internal_test(self): for success_text in [ "Internal tests passed", + "Require test 2 passed", "Math tests passed", "String tests passed", "Received heartbeat from" @@ -5407,6 +5317,28 @@ def test_scripting_set_home_to_vehicle_location(self): self.context_pop() self.reboot_sitl() + def test_scripting_serial_loopback(self): + self.start_subtest("Scripting serial loopback test") + + self.context_push() + self.context_collect('STATUSTEXT') + self.set_parameters({ + "SCR_ENABLE": 1, + "SCR_SDEV_EN": 1, + "SCR_SDEV1_PROTO": 28, + }) + self.install_test_script_context("serial_loopback.lua") + self.reboot_sitl() + + for success_text in [ + "driver -> device good", + "device -> driver good", + ]: + self.wait_statustext(success_text, check_context=True) + + self.context_pop() + self.reboot_sitl() + def Scripting(self): '''Scripting test''' self.test_scripting_set_home_to_vehicle_location() @@ -5415,6 +5347,7 @@ def Scripting(self): self.test_scripting_simple_loop() self.test_scripting_internal_test() self.test_scripting_auxfunc() + self.test_scripting_serial_loopback() def test_mission_frame(self, frame, target_system=1, target_component=1): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, @@ -5544,65 +5477,55 @@ def send_obstacle_distances_expect_distance_sensor_messages(self, obstacle_dista def AP_Proximity_MAV(self): '''Test MAV proximity backend''' - self.context_push() - ex = None - try: - 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: - self.send_obstacle_distances_expect_distance_sensor_messages( - { - "distances": [234], - "increment_f": 10, - "angle_offset": 0.0, - "min_distance": 0, - "max_distance": 1000, # cm - }, [ - {"orientation": 0, "distance": 234}, - ]) - - # 5 lasers at front of vehicle, spread over 40 degrees: - self.send_obstacle_distances_expect_distance_sensor_messages( - { - "distances": [111, 222, 333, 444, 555], - "increment_f": 10, - "angle_offset": -20.0, - "min_distance": 0, - "max_distance": 1000, # cm - }, [ - {"orientation": 0, "distance": 111}, - ]) - - # lots of dense readings (e.g. vision camera: - distances = [0] * 72 - for i in range(0, 72): - distances[i] = 1000 + 10*abs(36-i) - - self.send_obstacle_distances_expect_distance_sensor_messages( - { - "distances": distances, - "increment_f": 90/72.0, - "angle_offset": -45.0, - "min_distance": 0, - "max_distance": 2000, # cm - }, [ - {"orientation": 0, "distance": 1000}, - {"orientation": 1, "distance": 1190}, - {"orientation": 7, "distance": 1190}, - ]) - except Exception as e: - self.print_exception_caught(e) - ex = e - self.context_pop() + self.set_parameters({ + "PRX1_TYPE": 2, # AP_Proximity_MAV + "OA_TYPE": 2, # dijkstra + "OA_DB_OUTPUT": 3, # send all items + }) self.reboot_sitl() - if ex is not None: - raise ex + + # 1 laser pointing straight forward: + self.send_obstacle_distances_expect_distance_sensor_messages( + { + "distances": [234], + "increment_f": 10, + "angle_offset": 0.0, + "min_distance": 0, + "max_distance": 1000, # cm + }, [ + {"orientation": 0, "distance": 234}, + ]) + + # 5 lasers at front of vehicle, spread over 40 degrees: + self.send_obstacle_distances_expect_distance_sensor_messages( + { + "distances": [111, 222, 333, 444, 555], + "increment_f": 10, + "angle_offset": -20.0, + "min_distance": 0, + "max_distance": 1000, # cm + }, [ + {"orientation": 0, "distance": 111}, + ]) + + # lots of dense readings (e.g. vision camera: + distances = [0] * 72 + for i in range(0, 72): + distances[i] = 1000 + 10*abs(36-i) + + self.send_obstacle_distances_expect_distance_sensor_messages( + { + "distances": distances, + "increment_f": 90/72.0, + "angle_offset": -45.0, + "min_distance": 0, + "max_distance": 2000, # cm + }, [ + {"orientation": 0, "distance": 1000}, + {"orientation": 1, "distance": 1190}, + {"orientation": 7, "distance": 1190}, + ]) def SendToComponents(self): '''Test ArduPilot send_to_components function''' @@ -6104,10 +6027,10 @@ def FRAMStorage(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) + home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 231) rangefinder_params = { - "SIM_SONAR_ROT": 6, + "SIM_SONAR_ROT": 0, } rangefinder_params.update(self.analog_rangefinder_parameters()) @@ -6122,7 +6045,7 @@ def RangeFinder(self): if m.voltage == 0: raise NotAchievedException("Did not get non-zero voltage") want_range = 10 - if abs(m.distance - want_range) > 0.1: + if abs(m.distance - want_range) > 0.5: raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance)) def DepthFinder(self): @@ -6247,8 +6170,6 @@ def StickMixingAuto(self): def AutoDock(self): '''Test automatic docking of rover for multiple FOVs of simulated beacon''' - self.context_push() - self.set_parameters({ "PLND_ENABLED": 1, "PLND_TYPE": 4, @@ -6274,40 +6195,27 @@ def AutoDock(self): }) 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.change_mode('GUIDED') - self.wait_ready_to_arm() - self.arm_vehicle() - initial_position = self.offset_location_ne(target, -20, -2) - self.drive_to_location(initial_position) - self.change_mode(8) # DOCK mode - max_delta = 1 - self.wait_distance_to_location(target, 0, max_delta, timeout=180) - 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) - if delta > max_delta: - raise NotAchievedException("Did not dock close enough to stopping point (%fm > %fm" % (delta, max_delta)) - - if not self.current_onboard_log_contains_message("PL"): - raise NotAchievedException("Did not see expected PL message") - - except Exception as e: - self.print_exception_caught(e) - ex = e - break - - self.context_pop() + self.set_parameter("SIM_PLD_TYPE", type) + self.reboot_sitl() + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + initial_position = self.offset_location_ne(target, -20, -2) + self.drive_to_location(initial_position) + self.change_mode(8) # DOCK mode + max_delta = 1 + self.wait_distance_to_location(target, 0, max_delta, timeout=180) + 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) + if delta > max_delta: + raise NotAchievedException("Did not dock close enough to stopping point (%fm > %fm" % (delta, max_delta)) - if ex is not None: - raise ex + if not self.current_onboard_log_contains_message("PL"): + raise NotAchievedException("Did not see expected PL message") - self.reboot_sitl() self.progress("All done") def PrivateChannel(self): @@ -6587,22 +6495,22 @@ def MAV_CMD_DO_FENCE_ENABLE(self): '''ensure MAV_CMD_DO_FENCE_ENABLE mavlink command works''' here = self.mav.location() - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, - [ - [ # east - self.offset_location_ne(here, -50, 20), # bl - self.offset_location_ne(here, 50, 20), # br - self.offset_location_ne(here, 50, 40), # tr - self.offset_location_ne(here, -50, 40), # tl, - ], [ # over the top of the vehicle - self.offset_location_ne(here, -50, -50), # bl - self.offset_location_ne(here, -50, 50), # br - self.offset_location_ne(here, 50, 50), # tr - self.offset_location_ne(here, 50, -50), # tl, - ] - ] - ) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + self.offset_location_ne(here, -50, 40), # tl, + ]), + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ]), + ]) # enable: self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1) @@ -6695,7 +6603,7 @@ def NetworkingWebServerPPP(self): self.progress('rebuilding rover with ppp enabled') import shutil shutil.copy('build/sitl/bin/ardurover', 'build/sitl/bin/ardurover.noppp') - util.build_SITL('bin/ardurover', clean=False, configure=True, extra_configure_args=['--enable-ppp', '--debug']) + util.build_SITL('bin/ardurover', clean=False, configure=True, extra_configure_args=['--enable-PPP', '--debug']) self.reboot_sitl() @@ -6728,6 +6636,315 @@ def NetworkingWebServerPPP(self): shutil.copy('build/sitl/bin/ardurover.noppp', 'build/sitl/bin/ardurover') self.reboot_sitl() + def FenceFullAndPartialTransfer(self, target_system=1, target_component=1): + '''ensure starting a fence transfer then a partial transfer behaves + appropriately''' + # start uploading a 10 item list: + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + # change our mind and try a partial mission upload: + self.mav.mav.mission_write_partial_list_send( + target_system, + target_component, + 3, + 3, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE) + # should get denied for that one: + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_DENIED, + ) + # now wait for the original upload to be "cancelled" + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED, + ) + + def MissionRetransfer(self, target_system=1, target_component=1): + '''torture-test with MISSION_COUNT''' +# self.send_debug_trap() + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + self.context_push() + self.context_collect('STATUSTEXT') + self.mav.mav.mission_count_send( + target_system, + target_component, + 10000, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.wait_statustext('Only [0-9]+ items are supported', regex=True, check_context=True) + self.context_pop() + self.assert_not_receive_message('MISSION_REQUEST') + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED, + ) + + def MissionPolyEnabledPreArm(self): + '''check Polygon porearm checks''' + self.set_parameters({ + 'FENCE_ENABLE': 1, + }) + self.progress("Ensure that we can arm if polyfence is enabled but we have no polyfence") + self.assert_parameter_value('FENCE_TYPE', 6) + self.wait_ready_to_arm() + self.reboot_sitl() + self.wait_ready_to_arm() + + self.progress("Ensure we can arm when we have an inclusion fence we are inside of") + here = self.mav.location() + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, -50, -50), # bl + self.offset_location_ne(here, -50, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, -50), # tl, + ]), + ]) + self.delay_sim_time(5) + self.wait_ready_to_arm() + + self.reboot_sitl() + self.wait_ready_to_arm() + + self.progress("Ensure we can't arm when we are in breacnh of a polyfence") + self.clear_fence() + + self.progress("Now create a fence we are in breach of") + here = self.mav.location() + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ]), + ]) + + self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False) + self.reboot_sitl() + + self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120) + + self.progress("Ensure we can arm when a polyfence fence is cleared when we've previously been in breach") + self.clear_fence() + self.wait_ready_to_arm() + + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ]), + ]) + self.reboot_sitl() + self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120) + self.clear_fence() + self.wait_ready_to_arm() + + self.progress("Ensure we can arm after clearing polygon fence type enabled") + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [ + # over the top of the vehicle + self.offset_location_ne(here, 20, 20), # bl + self.offset_location_ne(here, 20, 50), # br + self.offset_location_ne(here, 50, 50), # tr + self.offset_location_ne(here, 50, 20), # tl, + ]), + ]) + self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120) + self.set_parameter('FENCE_TYPE', 2) + self.wait_ready_to_arm() + self.set_parameter('FENCE_TYPE', 6) + self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120) + + def OpticalFlow(self): + '''lightly test OpticalFlow''' + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, False, False, False, verbose=True) + + self.context_push() + self.set_parameter("SIM_FLOW_ENABLE", 1) + self.set_parameter("FLOW_TYPE", 10) + + self.reboot_sitl() + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, True, True, True, verbose=True) + + self.context_pop() + self.reboot_sitl() + + def RCDuplicateOptionsExist(self): + '''ensure duplicate RC option detection works''' + self.wait_ready_to_arm() + self.set_parameters({ + "RC6_OPTION": 118, + "RC7_OPTION": 118, + }) + self.assert_arm_failure("Duplicate Aux Switch Options") + + def JammingSimulation(self): + '''Test jamming simulation works''' + self.wait_ready_to_arm() + start_loc = self.assert_receive_message('GPS_RAW_INT') + self.set_parameter("SIM_GPS1_JAM", 1) + + class Requirement(): + def __init__(self, field, min_value): + self.field = field + self.min_value = min_value + + def met(self, m): + return getattr(m, self.field) > self.min_value + + requirements = set([ + Requirement('v_acc', 50000), + Requirement('h_acc', 50000), + Requirement('vel_acc', 1000), + Requirement('vel', 10000), + ]) + low_sats_seen = False + seen_bad_loc = False + tstart = self.get_sim_time() + + while True: + if self.get_sim_time() - tstart > 120: + raise NotAchievedException("Did not see all jamming") + m = self.assert_receive_message('GPS_RAW_INT') + new_requirements = copy.copy(requirements) + for requirement in requirements: + if requirement.met(m): + new_requirements.remove(requirement) + requirements = new_requirements + if m.satellites_visible < 6: + low_sats_seen = True + here = self.assert_receive_message('GPS_RAW_INT') + if self.get_distance_int(start_loc, here) > 100: + seen_bad_loc = True + + if len(requirements) == 0 and low_sats_seen and seen_bad_loc: + break + + def BatteryInvalid(self): + '''check Battery prearms report useful data to user''' + self.start_subtest("Changing battery types makes no difference") + self.set_parameter("BATT_MONITOR", 0) + self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False) + self.set_parameter("BATT_MONITOR", 4) + self.wait_ready_to_arm() + + self.start_subtest("No battery monitor should be armable") + self.set_parameter("BATT_MONITOR", 0) + self.reboot_sitl() + self.wait_ready_to_arm() + + self.set_parameter("BATT_MONITOR", 4) + self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False) + self.reboot_sitl() + self.wait_ready_to_arm() + + self.start_subtest("Invalid backend should have a clear error") + self.set_parameter("BATT_MONITOR", 98) + self.reboot_sitl() + self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False) + + self.start_subtest("Switching from an invalid backend to a valid backend should require a reboot") + self.set_parameter("BATT_MONITOR", 4) + self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False) + + self.start_subtest("Switching to None should NOT require a reboot") + self.set_parameter("BATT_MONITOR", 0) + self.wait_ready_to_arm() + + # this method modified from cmd_addpoly in the MAVProxy code: + def generate_polyfence(self, centre_loc, command, radius, count, rotation=0): + '''adds a number of waypoints equally spaced around a circle + + ''' + if count < 3: + raise ValueError("Invalid count (%s)" % str(count)) + if radius <= 0: + raise ValueError("Invalid radius (%s)" % str(radius)) + + latlon = (centre_loc.lat, centre_loc.lng) + + items = [] + for i in range(0, count): + (lat, lon) = mavextra.gps_newpos(latlon[0], + latlon[1], + 360/float(count)*i + rotation, + radius) + + m = mavutil.mavlink.MAVLink_mission_item_int_message( + 1, # target system + 1, # target component + 0, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL, # frame + command, # command + 0, # current + 0, # autocontinue + count, # param1, + 0.0, # param2, + 0.0, # param3 + 0.0, # param4 + int(lat*1e7), # x (latitude) + int(lon*1e7), # y (longitude) + 0, # z (altitude) + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + ) + items.append(m) + + return items + + def SDPolyFence(self): + '''test storage of fence on SD card''' + self.set_parameters({ + 'BRD_SD_FENCE': 32767, + }) + self.reboot_sitl() + + home = self.home_position_as_mav_location() + fence = self.generate_polyfence( + home, + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, + radius=100, + count=100, + ) + + for bearing in range(0, 359, 60): + x = self.offset_location_heading_distance(home, bearing, 100) + fence.extend(self.generate_polyfence( + x, + mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, + radius=100, + count=100, + )) + + self.correct_wp_seq_numbers(fence) + self.check_fence_upload_download(fence) + + self.delay_sim_time(1000) + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6779,11 +6996,14 @@ def tests(self): self.DataFlash, self.SkidSteer, self.PolyFence, + self.SDPolyFence, self.PolyFenceAvoidance, - self.PolyFenceObjectAvoidance, + self.PolyFenceObjectAvoidanceAuto, + self.PolyFenceObjectAvoidanceGuided, self.PolyFenceObjectAvoidanceBendyRuler, self.SendToComponents, - self.PolyFenceObjectAvoidanceBendyRulerEasier, + self.PolyFenceObjectAvoidanceBendyRulerEasierGuided, + self.PolyFenceObjectAvoidanceBendyRulerEasierAuto, self.SlewRate, self.Scripting, self.ScriptingSteeringAndThrottle, @@ -6814,12 +7034,23 @@ def tests(self): self.MAV_CMD_BATTERY_RESET, self.NetworkingWebServer, self.NetworkingWebServerPPP, + self.RTL_SPEED, + self.MissionRetransfer, + self.FenceFullAndPartialTransfer, + self.MissionPolyEnabledPreArm, + self.OpticalFlow, + self.RCDuplicateOptionsExist, + self.ClearMission, + self.JammingSimulation, + self.BatteryInvalid, ]) return ret def disabled_tests(self): return { "SlewRate": "got timing report failure on CI", + "MAV_CMD_NAV_SET_YAW_SPEED": "compiled out of code by default", + "PolyFenceObjectAvoidanceBendyRuler": "unreliable", } def rc_defaults(self): diff --git a/Tools/autotest/run_in_terminal_window.sh b/Tools/autotest/run_in_terminal_window.sh index 343f745b157bd7..7eccc9412dd5d5 100755 --- a/Tools/autotest/run_in_terminal_window.sh +++ b/Tools/autotest/run_in_terminal_window.sh @@ -28,7 +28,7 @@ if [ -n "$SITL_RITW_TERMINAL" ]; then printf "%q " "$@" >>"$FILEPATH" chmod +x "$FILEPATH" $SITL_RITW_TERMINAL "$FILEPATH" & -elif [ "$TERM" = "screen" ] && [ -n "$TMUX" ]; then +elif [ -n "$TMUX" ]; then tmux new-window -dn "$name" "$*" elif [ -n "$DISPLAY" -a -n "$(which osascript)" ]; then osascript -e 'tell application "Terminal" to do script "'"cd $(pwd) && clear && $* "'"' diff --git a/Tools/autotest/run_mission.py b/Tools/autotest/run_mission.py index 53721d76ee2c1e..05f8e5e6f3151e 100755 --- a/Tools/autotest/run_mission.py +++ b/Tools/autotest/run_mission.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 ''' Run a mission in SITL diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 80e19d40ae49f2..6899e55e9912cd 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -379,10 +379,10 @@ def do_build(opts, frame_options): cmd_configure.append("--enable-math-check-indexes") if opts.enable_ekf2: - cmd_configure.append("--enable-ekf2") + cmd_configure.append("--enable-EKF2") if opts.disable_ekf3: - cmd_configure.append("--disable-ekf3") + cmd_configure.append("--disable-EKF3") if opts.postype_single: cmd_configure.append("--postype-single") @@ -415,7 +415,7 @@ def do_build(opts, frame_options): cmd_configure.append("--disable-networking") if opts.enable_ppp: - cmd_configure.append("--enable-ppp") + cmd_configure.append("--enable-PPP") if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") @@ -775,6 +775,8 @@ def start_vehicle(binary, opts, stuff, spawns=None): cmd.extend(["--sysid", str(opts.sysid)]) if opts.slave is not None: cmd.extend(["--slave", str(opts.slave)]) + if opts.enable_fgview: + cmd.extend(["--enable-fgview"]) if opts.sitl_instance_args: # this could be a lot better: cmd.extend(opts.sitl_instance_args.split(" ")) @@ -962,6 +964,8 @@ def start_mavproxy(opts, stuff): cmd.extend(['--aircraft', opts.aircraft]) if opts.moddebug: cmd.append('--moddebug=%u' % opts.moddebug) + if opts.mavcesium: + cmd.extend(["--load-module", "cesium"]) if opts.fresh_params: # these were built earlier: @@ -984,6 +988,17 @@ def start_mavproxy(opts, stuff): run_cmd_blocking("Run MavProxy", cmd, env=env) progress("MAVProxy exited") + if opts.gdb: + # in the case that MAVProxy exits (as opposed to being + # killed), restart it if we are running under GDB. This + # allows ArduPilot to stop (eg. via a very early panic call) + # and have you debugging session not be killed. + while True: + progress("Running under GDB; restarting MAVProxy") + run_cmd_blocking("Run MavProxy", cmd, env=env) + progress("MAVProxy exited; sleeping 10") + time.sleep(10) + vehicle_options_string = '|'.join(vinfo.options.keys()) @@ -1340,6 +1355,8 @@ def generate_frame_help(): help="Enable PPP networking") group_sim.add_option("--enable-networking-tests", action='store_true', help="Enable networking tests") +group_sim.add_option("--enable-fgview", action='store_true', + help="Enable FlightGear output") parser.add_option_group(group_sim) @@ -1358,6 +1375,11 @@ def generate_frame_help(): default=False, action='store_true', help="load map module on startup") +group.add_option("", "--mavcesium", + default=False, + action='store_true', + help="load MAVCesium module on startup") + group.add_option("", "--console", default=False, action='store_true', diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index 9d4b3f1dd411cc..7cbc005c310aa6 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -24,6 +24,7 @@ import optparse import os import pathlib +import re import sys from pysim import util @@ -53,6 +54,7 @@ def __init__(self, board="CubeOrange", # DevEBoxH7v2 also works extra_hwdef=None, emit_disable_all_defines=None, + resume=False, ): self.extra_hwdef = extra_hwdef self.sizes_nothing_disabled = None @@ -67,6 +69,7 @@ def __init__(self, self.build_targets = self.all_targets() self._board = board self.emit_disable_all_defines = emit_disable_all_defines + self.resume = resume self.results = {} self.enable_in_turn_results = {} @@ -147,7 +150,7 @@ def get_disable_defines(self, feature, options): if f.define not in ret: continue - print("%s requires %s" % (option.define, f.define), file=sys.stderr) + # print("%s requires %s" % (option.define, f.define), file=sys.stderr) added_one = True ret[option.define] = 0 break @@ -187,6 +190,9 @@ def test_disable_feature(self, feature, options): self.test_compile_with_defines(defines) + self.assert_feature_not_in_code(defines, feature) + + def assert_feature_not_in_code(self, defines, feature): # if the feature is truly disabled then extract_features.py # should say so: for target in self.build_targets: @@ -198,8 +204,7 @@ def test_disable_feature(self, feature, options): # or all vehicles: feature_define_whitelist = set([ 'AP_RANGEFINDER_ENABLED', # only at vehicle level ATM - 'BEACON_ENABLED', # Rover doesn't obey this (should also be AP_BEACON_ENABLED) - 'WINCH_ENABLED', # Copter doesn't use this; should use AP_WINCH_ENABLED + 'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # no symbol ]) if define in compiled_in_feature_defines: error = f"feature gated by {define} still compiled into ({target}); extract_features.py bug?" @@ -220,6 +225,177 @@ def test_enable_feature(self, feature, options): self.test_compile_with_defines(defines) + self.assert_feature_in_code(defines, feature) + + def define_is_whitelisted_for_feature_in_code(self, target, define): + '''returns true if we can not expect the define to be extracted from + the binary''' + # the following defines are known not to work on some + # or all vehicles: + feature_define_whitelist = set([ + 'AP_RANGEFINDER_ENABLED', # only at vehicle level ATM + 'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # no symbol + 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', # broken, no subscriber + # Baro drivers either come in because you have + # external-probing enabled or you have them specified in + # your hwdef. If you're not probing and its not in your + # hwdef then the code will be elided as unreachable + 'AP_BARO_ICM20789_ENABLED', + 'AP_BARO_ICP101XX_ENABLED', + 'AP_BARO_ICP201XX_ENABLED', + 'AP_BARO_BMP085_ENABLED', + 'AP_BARO_BMP280_ENABLED', + 'AP_BARO_BMP388_ENABLED', + 'AP_BARO_BMP581_ENABLED', + 'AP_BARO_DPS280_ENABLED', + 'AP_BARO_FBM320_ENABLED', + 'AP_BARO_KELLERLD_ENABLED', + 'AP_BARO_LPS2XH_ENABLED', + 'AP_BARO_MS56XX_ENABLED', + 'AP_BARO_SPL06_ENABLED', + 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', # elided unless AP_CAMERA_SEND_FOV_STATUS_ENABLED + 'AP_COMPASS_LSM9DS1_ENABLED', # must be in hwdef, not probed + 'AP_COMPASS_MAG3110_ENABLED', # must be in hwdef, not probed + 'AP_COMPASS_MMC5XX3_ENABLED', # must be in hwdef, not probed + 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', # completely elided + 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', # no symbol available + 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', # no symbol available + 'HAL_MSP_SENSORS_ENABLED', # no symbol available + 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', # FIXME: need a new define/feature + 'HAL_OSD_SIDEBAR_ENABLE', # FIXME: need a new define/feature + 'HAL_PLUSCODE_ENABLE', # FIXME: need a new define/feature + 'AP_SERIALMANAGER_REGISTER_ENABLED', # completely elided without a caller + 'AP_OPTICALFLOW_ONBOARD_ENABLED', # only instantiated on Linux + 'HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', # entirely elided if no user + 'AP_PLANE_BLACKBOX_LOGGING', # entirely elided if no user + ]) + if target.lower() != "copter": + feature_define_whitelist.add('MODE_ZIGZAG_ENABLED') + feature_define_whitelist.add('MODE_SYSTEMID_ENABLED') + feature_define_whitelist.add('MODE_SPORT_ENABLED') + feature_define_whitelist.add('MODE_FOLLOW_ENABLED') + feature_define_whitelist.add('MODE_TURTLE_ENABLED') + feature_define_whitelist.add('MODE_GUIDED_NOGPS_ENABLED') + feature_define_whitelist.add('MODE_FLOWHOLD_ENABLED') + feature_define_whitelist.add('MODE_FLIP_ENABLED') + feature_define_whitelist.add('MODE_BRAKE_ENABLED') + feature_define_whitelist.add('AP_TEMPCALIBRATION_ENABLED') + feature_define_whitelist.add('AC_PAYLOAD_PLACE_ENABLED') + feature_define_whitelist.add('AP_AVOIDANCE_ENABLED') + feature_define_whitelist.add('AP_WINCH_ENABLED') + feature_define_whitelist.add('AP_WINCH_DAIWA_ENABLED') + feature_define_whitelist.add('AP_WINCH_PWM_ENABLED') + feature_define_whitelist.add(r'AP_MOTORS_FRAME_.*_ENABLED') + feature_define_whitelist.add('AP_COPTER_ADVANCED_FAILSAFE_ENABLED') + + if target.lower() != "plane": + # only on Plane: + feature_define_whitelist.add('AP_ICENGINE_ENABLED') + feature_define_whitelist.add('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED') + feature_define_whitelist.add('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED') + feature_define_whitelist.add('AP_ADVANCEDFAILSAFE_ENABLED') + feature_define_whitelist.add('AP_TUNING_ENABLED') + feature_define_whitelist.add('HAL_LANDING_DEEPSTALL_ENABLED') + feature_define_whitelist.add('HAL_SOARING_ENABLED') + feature_define_whitelist.add('AP_PLANE_BLACKBOX_LOGGING') + feature_define_whitelist.add('QAUTOTUNE_ENABLED') + feature_define_whitelist.add('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED') + feature_define_whitelist.add('HAL_QUADPLANE_ENABLED') + feature_define_whitelist.add('AP_BATTERY_WATT_MAX_ENABLED') + + if target.lower() not in ["plane", "copter"]: + feature_define_whitelist.add('HAL_ADSB_ENABLED') + feature_define_whitelist.add('AP_LANDINGGEAR_ENABLED') + # only Plane and Copter instantiate Parachute + feature_define_whitelist.add('HAL_PARACHUTE_ENABLED') + # only Plane and Copter have AP_Motors: + + if target.lower() not in ["rover", "copter"]: + # only Plane and Copter instantiate Beacon + feature_define_whitelist.add('AP_BEACON_ENABLED') + + if target.lower() != "rover": + # only on Rover: + feature_define_whitelist.add('HAL_TORQEEDO_ENABLED') + feature_define_whitelist.add('AP_ROVER_ADVANCED_FAILSAFE_ENABLED') + if target.lower() != "sub": + # only on Sub: + feature_define_whitelist.add('AP_BARO_KELLERLD_ENABLED') + if target.lower() not in frozenset(["rover", "sub"]): + # only Rover and Sub get nmea airspeed + feature_define_whitelist.add('AP_AIRSPEED_NMEA_ENABLED') + if target.lower() not in frozenset(["copter", "rover"]): + feature_define_whitelist.add('HAL_SPRAYER_ENABLED') + feature_define_whitelist.add('HAL_PROXIMITY_ENABLED') + feature_define_whitelist.add('AP_PROXIMITY_.*_ENABLED') + feature_define_whitelist.add('AP_OAPATHPLANNER_ENABLED') + + if target.lower() in ["blimp", "antennatracker"]: + # no airspeed on blimp/tracker + feature_define_whitelist.add(r'AP_AIRSPEED_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MOUNT_ENABLED') + feature_define_whitelist.add(r'AP_MOUNT_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MOUNT_.*_ENABLED') + feature_define_whitelist.add(r'HAL_SOLO_GIMBAL_ENABLED') + feature_define_whitelist.add(r'AP_OPTICALFLOW_ENABLED') + feature_define_whitelist.add(r'AP_OPTICALFLOW_.*_ENABLED') + feature_define_whitelist.add(r'HAL_MSP_OPTICALFLOW_ENABLED') + # missing calls to fence.check(): + feature_define_whitelist.add(r'AP_FENCE_ENABLED') + # RPM not instantiated on Blimp or Rover: + feature_define_whitelist.add(r'AP_RPM_ENABLED') + feature_define_whitelist.add(r'AP_RPM_.*_ENABLED') + # rangefinder init is not called: + feature_define_whitelist.add(r'HAL_MSP_RANGEFINDER_ENABLED') + # these guys don't instantiate anything which uses sd-card storage: + feature_define_whitelist.add(r'AP_SDCARD_STORAGE_ENABLED') + feature_define_whitelist.add(r'AP_RANGEFINDER_ENABLED') + feature_define_whitelist.add(r'AP_RANGEFINDER_.*_ENABLED') + + if target.lower() in ["blimp", "antennatracker", "sub"]: + # no OSD on Sub/blimp/tracker + feature_define_whitelist.add(r'OSD_ENABLED') + feature_define_whitelist.add(r'OSD_PARAM_ENABLED') + # AP_OSD is not instantiated, , so no MSP backend: + feature_define_whitelist.add(r'HAL_WITH_MSP_DISPLAYPORT') + # camera instantiated in specific vehicles: + feature_define_whitelist.add(r'AP_CAMERA_ENABLED') + feature_define_whitelist.add(r'AP_CAMERA_.*_ENABLED') + # button update is not called in these vehicles + feature_define_whitelist.add(r'HAL_BUTTON_ENABLED') + # precland not instantiated on these vehicles + feature_define_whitelist.add(r'AC_PRECLAND_ENABLED') + feature_define_whitelist.add(r'AC_PRECLAND_.*_ENABLED') + # RSSI is not initialised - probably should be for some + feature_define_whitelist.add(r'AP_RSSI_ENABLED') + + if target.lower() in ["antennatracker", "sub"]: + # missing the init call to the relay library: + feature_define_whitelist.add(r'AP_RELAY_ENABLED') + feature_define_whitelist.add(r'AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED') + + for some_re in feature_define_whitelist: + if re.match(some_re, define): + return True + + def assert_feature_in_code(self, defines, feature): + # if the feature is truly disabled then extract_features.py + # should say so: + for target in self.build_targets: + path = self.target_to_elf_path(target) + extracter = extract_features.ExtractFeatures(path) + (compiled_in_feature_defines, not_compiled_in_feature_defines) = extracter.extract() + for define in defines: + if not defines[define]: + continue + if define in compiled_in_feature_defines: + continue + error = f"feature gated by {define} not compiled into ({target}); extract_features.py bug?" + if self.define_is_whitelisted_for_feature_in_code(target, define): + print("warn: " + error) + continue + raise ValueError(error) + def board(self): '''returns board to build for''' return self._board @@ -314,13 +490,19 @@ def disable_in_turn_check_sizes(self, feature, sizes_nothing_disabled): f.write(self.csv_for_results(self.results)) def run_disable_in_turn(self): + progress_file = pathlib.Path("/tmp/run-disable-in-turn-progress") + resume_number = self.resume_number_from_progress_Path(progress_file) options = self.get_build_options_from_ardupilot_tree() count = 1 for feature in sorted(options, key=lambda x : x.define): + if resume_number is not None: + if count < resume_number: + count += 1 + continue if self.match_glob is not None: if not fnmatch.fnmatch(feature.define, self.match_glob): continue - with open("/tmp/run-disable-in-turn-progress", "w") as f: + with open(progress_file, "w") as f: f.write(f"{count}/{len(options)} {feature.define}\n") # if feature.define < "WINCH_ENABLED": # count += 1 @@ -351,16 +533,35 @@ def enable_in_turn_check_sizes(self, feature, sizes_everything_disabled): with open("/tmp/enable-in-turn.csv", "w") as f: f.write(self.csv_for_results(self.enable_in_turn_results)) + def resume_number_from_progress_Path(self, progress_file): + if not self.resume: + return None + try: + content = progress_file.read_text().rstrip() + m = re.match(r"(\d+)/\d+ \w+", content) + if m is None: + raise ValueError(f"{progress_file} not matched") + return int(m.group(1)) + except FileNotFoundError: + pass + return None + def run_enable_in_turn(self): + progress_file = pathlib.Path("/tmp/run-enable-in-turn-progress") + resume_number = self.resume_number_from_progress_Path(progress_file) options = self.get_build_options_from_ardupilot_tree() count = 1 for feature in options: + if resume_number is not None: + if count < resume_number: + count += 1 + continue if self.match_glob is not None: if not fnmatch.fnmatch(feature.define, self.match_glob): continue self.progress("Enabling feature %s(%s) (%u/%u)" % (feature.label, feature.define, count, len(options))) - with open("/tmp/run-enable-in-turn-progress", "w") as f: + with open(progress_file, "w") as f: f.write(f"{count}/{len(options)} {feature.define}\n") self.test_enable_feature(feature, options) count += 1 @@ -482,11 +683,14 @@ def run(self): help="file containing extra hwdef information") parser.add_option("--board", type='string', - default="DevEBoxH7v2", + default="CubeOrange", help='board to build for') parser.add_option("--emit-disable-all-defines", action='store_true', help='emit defines used for disabling all features then exit') + parser.add_option("--resume", + action='store_true', + help='resume from previous progress file') opts, args = parser.parse_args() @@ -501,6 +705,7 @@ def run(self): board=opts.board, extra_hwdef=opts.extra_hwdef, emit_disable_all_defines=opts.emit_disable_all_defines, + resume=opts.resume, ) tbo.run() diff --git a/Tools/autotest/test_param_upgrade.py b/Tools/autotest/test_param_upgrade.py index 4728e84856a927..c1d11723a2fae1 100755 --- a/Tools/autotest/test_param_upgrade.py +++ b/Tools/autotest/test_param_upgrade.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 ''' Test parameter upgrade, master vs branch @@ -14,6 +14,7 @@ import argparse import subprocess import time +import shutil import string import pathlib @@ -50,10 +51,18 @@ def vehicleinfo_key(self): return "ArduCopter" raise ValueError("Can't determine vehicleinfo_key from binary path") + def model(self): + path = self.binary.lower() + if "plane" in path: + return "quadplane" + if "copter" in path: + return "X" + raise ValueError("Can't determine vehicleinfo_key from binary path") + def run(self): self.start_SITL( binary=self.binary, - model="novehicle", + model=self.model(), wipe=True, sitl_home="1,1,1,1", ) @@ -90,10 +99,18 @@ def vehicleinfo_key(self): return "ArduCopter" raise ValueError("Can't determine vehicleinfo_key from binary path") + def model(self): + path = self.binary.lower() + if "plane" in path: + return "quadplane" + if "copter" in path: + return "X" + raise ValueError("Can't determine vehicleinfo_key from binary path") + def run(self): self.start_SITL( binary=self.binary, - model="novehicle", + model=self.model(), sitl_home="1,1,1,1", wipe=False, ) @@ -243,6 +260,7 @@ def run(self): self.run_git(["checkout", master_commit], show_output=False) self.run_git(["submodule", "update", "--recursive"], show_output=False) + shutil.rmtree("build", ignore_errors=True) board = "sitl" if "AP_Periph" in self.vehicle: board = "sitl_periph_universal" @@ -257,6 +275,7 @@ def run(self): self.run_git(["checkout", branch], show_output=False) self.run_git(["submodule", "update", "--recursive"], show_output=False) + shutil.rmtree("build", ignore_errors=True) util.build_SITL( self.build_target_name(self.vehicle), board=board, @@ -281,12 +300,14 @@ def __init__(self, vehicles=None, run_eedump_before=False, run_eedump_after=False, + master_branch="master", ): self.vehicles = vehicles self.param_changes = param_changes self.vehicles = vehicles self.run_eedump_before = run_eedump_before self.run_eedump_after = run_eedump_after + self.master_branch = master_branch if self.vehicles is None: self.vehicles = self.all_vehicles() @@ -310,6 +331,7 @@ def run(self): self.param_changes, run_eedump_before=self.run_eedump_before, run_eedump_after=self.run_eedump_after, + master_branch=self.master_branch, ) s.run() @@ -346,7 +368,12 @@ def run(self): default=False, help="run the (already-compiled) eedump tool on eeprom.bin after doing conversion", ) - + parser.add_argument( + "--master-branch", + type=str, + default="master", + help="master branch to use", + ) args = parser.parse_args() param_changes = [] @@ -374,5 +401,6 @@ def run(self): vehicles=vehicles, run_eedump_before=args.run_eedump_before, run_eedump_after=args.run_eedump_after, + master_branch=args.master_branch, ) x.run() diff --git a/Tools/autotest/unittest/annotate_params_unittest.py b/Tools/autotest/unittest/annotate_params_unittest.py index e9db5f794a8fbb..26dd0ad09a5630 100755 --- a/Tools/autotest/unittest/annotate_params_unittest.py +++ b/Tools/autotest/unittest/annotate_params_unittest.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 ''' These are the unit tests for the python script that fetches online ArduPilot diff --git a/Tools/autotest/unittest/extract_param_defaults_unittest.py b/Tools/autotest/unittest/extract_param_defaults_unittest.py index fe539655470f29..b3e6e3c1d0054d 100755 --- a/Tools/autotest/unittest/extract_param_defaults_unittest.py +++ b/Tools/autotest/unittest/extract_param_defaults_unittest.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 ''' Extracts parameter default values from an ArduPilot .bin log file. Unittests. diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 2b9755f25a2154..3c08f0939652b0 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -34,6 +34,7 @@ import tempfile import threading import enum +from inspect import currentframe, getframeinfo from pathlib import Path from MAVProxy.modules.lib import mp_util @@ -204,6 +205,7 @@ class Context(object): def __init__(self): self.parameters = [] self.sitl_commandline_customised = False + self.reboot_sitl_was_done = False self.message_hooks = [] self.collections = {} self.heartbeat_interval_ms = 1000 @@ -339,7 +341,129 @@ def update(self): if not self.connected: if not self.connect(): return - self.update_read() + return self.update_read() + + +class IBusMessage(object): + def checksum_bytes(self, out): + checksum = 0xFFFF + for b in iter(out): + checksum -= b + return checksum + + +class IBusResponse(IBusMessage): + def __init__(self, some_bytes): + self.len = some_bytes[0] + checksum = self.checksum_bytes(some_bytes[:self.len-2]) + if checksum >> 8 != some_bytes[self.len-1]: + raise ValueError("Checksum bad (-1)") + if checksum & 0xff != some_bytes[self.len-2]: + raise ValueError("Checksum bad (-2)") + self.address = some_bytes[1] & 0x0F + self.handle_payload_bytes(some_bytes[2:self.len-2]) + + +class IBusResponse_DISCOVER(IBusResponse): + def handle_payload_bytes(self, payload_bytes): + if len(payload_bytes): + raise ValueError("Not expecting payload bytes (%u)" % + (len(payload_bytes), )) + + +class IBusResponse_GET_SENSOR_TYPE(IBusResponse): + def handle_payload_bytes(self, payload_bytes): + if len(payload_bytes) != 2: + raise ValueError("Expected 2 payload bytes") + self.sensor_type = payload_bytes[0] + self.sensor_length = payload_bytes[1] + + +class IBusResponse_GET_SENSOR_VALUE(IBusResponse): + def handle_payload_bytes(self, payload_bytes): + self.sensor_value = payload_bytes + + def get_sensor_value(self): + '''returns an integer based off content''' + ret = 0 + for i in range(len(self.sensor_value)): + x = self.sensor_value[i] + if sys.version_info.major < 3: + x = ord(x) + ret = ret | (x << (i*8)) + return ret + + +class IBusRequest(IBusMessage): + def __init__(self, command, address): + self.command = command + self.address = address + + def payload_bytes(self): + '''most requests don't have a payload''' + return bytearray() + + def for_wire(self): + out = bytearray() + payload_bytes = self.payload_bytes() + payload_length = len(payload_bytes) + length = 1 + 1 + payload_length + 2 # len+cmd|adr+payloadlen+cksum + format_string = '> 8)) + return out + + +class IBusRequest_DISCOVER(IBusRequest): + def __init__(self, address): + super(IBusRequest_DISCOVER, self).__init__(0x08, address) + + +class IBusRequest_GET_SENSOR_TYPE(IBusRequest): + def __init__(self, address): + super(IBusRequest_GET_SENSOR_TYPE, self).__init__(0x09, address) + + +class IBusRequest_GET_SENSOR_VALUE(IBusRequest): + def __init__(self, address): + super(IBusRequest_GET_SENSOR_VALUE, self).__init__(0x0A, address) + + +class IBus(Telem): + def __init__(self, destination_address): + super(IBus, self).__init__(destination_address) + + def progress_tag(self): + return "IBus" + + def packet_from_buffer(self, buffer): + t = buffer[1] >> 4 + if sys.version_info.major < 3: + t = ord(t) + if t == 0x08: + return IBusResponse_DISCOVER(buffer) + if t == 0x09: + return IBusResponse_GET_SENSOR_TYPE(buffer) + if t == 0x0A: + return IBusResponse_GET_SENSOR_VALUE(buffer) + raise ValueError("Unknown response type (%u)" % t) + + def update_read(self): + self.buffer += self.do_read() + while len(self.buffer): + msglen = self.buffer[0] + if sys.version_info.major < 3: + msglen = ord(msglen) + if len(self.buffer) < msglen: + return + packet = self.packet_from_buffer(self.buffer[:msglen]) + self.buffer = self.buffer[msglen:] + return packet class WaitAndMaintain(object): @@ -348,13 +472,17 @@ def __init__(self, minimum_duration=None, progress_print_interval=1, timeout=30, + epsilon=None, + comparator=None, ): self.test_suite = test_suite self.minimum_duration = minimum_duration self.achieving_duration_start = None self.timeout = timeout + self.epsilon = epsilon self.last_progress_print = 0 self.progress_print_interval = progress_print_interval + self.comparator = comparator def run(self): self.announce_test_start() @@ -369,6 +497,7 @@ def run(self): # check for timeout if now - tstart > self.timeout: + self.print_failure_text(now, current_value) raise self.timeoutexception() # handle the case where we are are achieving our value: @@ -400,11 +529,22 @@ def print_progress(self, now, value): text += f" (maintain={delta:.1f}/{self.minimum_duration})" self.progress(text) + def print_failure_text(self, now, value): + '''optionally print a more detailed error string''' + pass + def progress_text(self, value): return f"want={self.get_target_value()} got={value}" def validate_value(self, value): - return value == self.get_target_value() + target_value = self.get_target_value() + if self.comparator is not None: + return self.comparator(value, target_value) + + if self.epsilon is not None: + return (abs(value - target_value) <= self.epsilon) + + return value == target_value def timeoutexception(self): return AutoTestTimeoutException("Failed to attain or maintain value") @@ -465,6 +605,76 @@ def progress_text(self, current_value): return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}") +class WaitAndMaintainEKFFlags(WaitAndMaintain): + '''Waits for EKF status flags to include required_flags and have + error_bits *not* set.''' + def __init__(self, test_suite, required_flags, error_bits, **kwargs): + super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs) + self.required_flags = required_flags + self.error_bits = error_bits + self.last_EKF_STATUS_REPORT = None + + def announce_start_text(self): + return f"Waiting for EKF value {self.required_flags}" + + def get_current_value(self): + self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10) + return self.last_EKF_STATUS_REPORT.flags + + def validate_value(self, value): + if value & self.error_bits: + return False + + if (value & self.required_flags) != self.required_flags: + return False + + return True + + def success_text(self): + return "EKF Flags OK" + + def timeoutexception(self): + self.progress("Last EKF status report:") + self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT)) + + return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}") + + def progress_text(self, current_value): + error_bits = current_value & self.error_bits + return (f"Want={self.required_flags} got={current_value} errors={error_bits}") + + def ekf_flags_string(self, bits): + ret = [] + for i in range(0, 16): + bit = 1 << i + try: + if not bits & bit: + continue + name = mavutil.mavlink.enums["ESTIMATOR_STATUS_FLAGS"][bit].name + trimmed_name = name.removeprefix("ESTIMATOR_") + ret.append(trimmed_name) + except KeyError: + ret.append(str(bit)) + return "|".join(ret) + + def failure_text(self, now, current_value): + components = [] + components.append(("want", self.ekf_flags_string(self.required_flags))) + + missing_bits = self.required_flags & ~current_value + if missing_bits: + components.append(("missing", self.ekf_flags_string(missing_bits))) + + error_bits = current_value & self.error_bits + if error_bits: + components.append(("errors", self.ekf_flags_string(error_bits))) + + return " ".join([f"{n}={v}" for (n, v) in components]) + + def print_failure_text(self, now, current_value): + self.progress(self.failure_text(now, current_value)) + + class WaitAndMaintainArmed(WaitAndMaintain): def get_current_value(self): return self.test_suite.armed() @@ -476,6 +686,35 @@ def announce_start_text(self): return "Ensuring vehicle remains armed" +class WaitAndMaintainServoChannelValue(WaitAndMaintain): + def __init__(self, test_suite, channel, value, **kwargs): + super(WaitAndMaintainServoChannelValue, self).__init__(test_suite, **kwargs) + self.channel = channel + self.value = value + + def announce_start_text(self): + str_operator = "" + if self.comparator == operator.lt: + str_operator = "less than " + elif self.comparator == operator.gt: + str_operator = "more than " + + return f"Waiting for SERVO_OUTPUT_RAW.servo{self.channel}_value value {str_operator}{self.value}" + + def get_target_value(self): + return self.value + + def get_current_value(self): + m = self.test_suite.assert_receive_message('SERVO_OUTPUT_RAW', timeout=10) + channel_field = "servo%u_raw" % self.channel + m_value = getattr(m, channel_field, None) + if m_value is None: + raise ValueError(f"message ({str(m)}) has no field {channel_field}") + + self.last_SERVO_OUTPUT_RAW = m + return m_value + + class MSP_Generic(Telem): def __init__(self, destination_address): super(MSP_Generic, self).__init__(destination_address) @@ -1625,6 +1864,16 @@ def __str__(self): return ret +class ValgrindFailedResult(Result): + '''a custom Result to allow passing of Vaglrind failures around''' + def __init__(self): + super(ValgrindFailedResult, self).__init__(None) + self.passed = False + + def __str__(self): + return "Valgrind error detected" + + class TestSuite(ABC): """Base abstract class. It implements the common function for all vehicle types. @@ -1656,6 +1905,7 @@ def __init__(self, num_aux_imus=0, dronecan_tests=False, generate_junit=False, + enable_fgview=False, build_opts={}): self.start_time = time.time() @@ -1722,6 +1972,7 @@ def __init__(self, self.last_heartbeat_time_wc_s = 0 self.in_drain_mav = False self.tlog = None + self.enable_fgview = enable_fgview self.rc_thread = None self.rc_thread_should_quit = False @@ -1746,6 +1997,7 @@ def __init__(self, self.terrain_data_messages_sent = 0 # count of messages back self.dronecan_tests = dronecan_tests self.statustext_id = 1 + self.message_hooks = [] # functions or MessageHook instances def __del__(self): if self.rc_thread is not None: @@ -1851,9 +2103,9 @@ def mavproxy_options(self): def vehicleinfo_key(self): return self.log_name() - def repeatedly_apply_parameter_file(self, filepath): + def repeatedly_apply_parameter_filepath(self, filepath): if False: - return self.repeatedly_apply_parameter_file_mavproxy(filepath) + return self.repeatedly_apply_parameter_filepath_mavproxy(filepath) parameters = mavparm.MAVParmDict() # correct_parameters = set() if not parameters.load(filepath): @@ -1863,7 +2115,7 @@ def repeatedly_apply_parameter_file(self, filepath): param_dict[p] = parameters[p] self.set_parameters(param_dict) - def repeatedly_apply_parameter_file_mavproxy(self, filepath): + def repeatedly_apply_parameter_filepath_mavproxy(self, filepath): '''keep applying a parameter file until no parameters changed''' for i in range(0, 3): self.mavproxy.send("param load %s\n" % filepath) @@ -1884,7 +2136,7 @@ def apply_defaultfile_parameters(self): if self.params is None: self.params = self.model_defaults_filepath(self.frame) for x in self.params: - self.repeatedly_apply_parameter_file(x) + self.repeatedly_apply_parameter_filepath(x) def count_lines_in_filepath(self, filepath): return len([i for i in open(filepath)]) @@ -1992,6 +2244,8 @@ def roundtrip_fence_using_fencepoint_protocol(self, loc_list, target_system=1, t def load_fence(self, filename): filepath = os.path.join(testdir, self.current_test_name_directory, filename) + if not os.path.exists(filepath): + filepath = self.generic_mission_filepath_for_filename(filename) self.progress("Loading fence from (%s)" % str(filepath)) locs = [] for line in open(filepath, 'rb'): @@ -2018,11 +2272,17 @@ def load_fence(self, filename): locs2.append(copy.copy(locs2[1])) return self.roundtrip_fence_using_fencepoint_protocol(locs2) - self.upload_fences_from_locations( - mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, - [ - locs - ]) + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs), + ]) + + def load_fence_using_mavwp(self, filename): + filepath = os.path.join(testdir, self.current_test_name_directory, filename) + if not os.path.exists(filepath): + filepath = self.generic_mission_filepath_for_filename(filename) + self.progress("Loading fence from (%s)" % str(filepath)) + items = self.mission_item_protocol_items_from_filepath(mavwp.MissionItemProtocol_Fence, filepath) + self.check_fence_upload_download(items) def send_reboot_command(self): self.mav.mav.command_long_send(self.sysid_thismav(), @@ -2136,7 +2396,13 @@ def send_cmd_enter_cpu_lockup(self): 0, 0) - def reboot_sitl(self, required_bootcount=None, force=False, check_position=True): + def reboot_sitl(self, + required_bootcount=None, + force=False, + check_position=True, + mark_context=True, + startup_location_dist_max=1, + ): """Reboot SITL instance and wait for it to reconnect.""" if self.armed() and not force: raise NotAchievedException("Reboot attempted while armed") @@ -2144,7 +2410,9 @@ def reboot_sitl(self, required_bootcount=None, force=False, check_position=True) self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force) self.do_heartbeats(force=True) if check_position and self.frame != 'sailboat': # sailboats drift with wind! - self.assert_simstate_location_is_at_startup_location() + self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max) + if mark_context: + self.context_get().reboot_sitl_was_done = True def reboot_sitl_mavproxy(self, required_bootcount=None): """Reboot SITL instance using MAVProxy and wait for it to reconnect.""" @@ -2291,72 +2559,15 @@ def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None): def get_sim_parameter_documentation_get_whitelist(self): # common parameters ret = set([ - "SIM_ACC1_RND", - "SIM_ACC2_RND", - "SIM_ACC3_RND", - "SIM_ACC4_RND", - "SIM_ACC5_RND", - "SIM_ACC_FILE_RW", "SIM_ACC_TRIM_X", "SIM_ACC_TRIM_Y", "SIM_ACC_TRIM_Z", - "SIM_ADSB_ALT", - "SIM_ADSB_COUNT", - "SIM_ADSB_RADIUS", - "SIM_ADSB_TX", "SIM_ARSPD2_OFS", "SIM_ARSPD2_RND", "SIM_ARSPD_OFS", "SIM_ARSPD_RND", - "SIM_BAR2_DELAY", - "SIM_BAR2_DISABLE", - "SIM_BAR2_DRIFT", - "SIM_BAR2_FREEZE", - "SIM_BAR2_WCF_BAK", - "SIM_BAR2_WCF_DN", - "SIM_BAR2_WCF_FWD", - "SIM_BAR2_WCF_LFT", - "SIM_BAR2_WCF_RGT", - "SIM_BAR2_WCF_UP", - "SIM_BAR3_DELAY", - "SIM_BAR3_DISABLE", - "SIM_BAR3_DRIFT", - "SIM_BAR3_FREEZE", - "SIM_BAR3_WCF_BAK", - "SIM_BAR3_WCF_DN", - "SIM_BAR3_WCF_FWD", - "SIM_BAR3_WCF_LFT", - "SIM_BAR3_WCF_RGT", - "SIM_BAR3_WCF_UP", - "SIM_BARO_COUNT", - "SIM_BARO_DELAY", - "SIM_BARO_DISABLE", - "SIM_BARO_DRIFT", - "SIM_BARO_FREEZE", - "SIM_BARO_WCF_BAK", - "SIM_BARO_WCF_DN", - "SIM_BARO_WCF_FWD", - "SIM_BARO_WCF_LFT", - "SIM_BARO_WCF_RGT", - "SIM_BARO_WCF_UP", - "SIM_BATT_CAP_AH", - "SIM_BAUDLIMIT_EN", - "SIM_DRIFT_SPEED", - "SIM_DRIFT_TIME", - "SIM_EFI_TYPE", - "SIM_ENGINE_FAIL", - "SIM_ENGINE_MUL", - "SIM_ESC_ARM_RPM", "SIM_FTOWESC_ENA", "SIM_FTOWESC_POW", - "SIM_GND_BEHAV", - "SIM_GYR1_RND", - "SIM_GYR2_RND", - "SIM_GYR3_RND", - "SIM_GYR4_RND", - "SIM_GYR5_RND", - "SIM_GYR_FAIL_MSK", - "SIM_GYR_FILE_RW", "SIM_IE24_ENABLE", "SIM_IE24_ERROR", "SIM_IE24_STATE", @@ -2465,15 +2676,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_IMUT5_GYR3_Z", "SIM_IMUT5_TMAX", "SIM_IMUT5_TMIN", - "SIM_IMUT_END", - "SIM_IMUT_FIXED", - "SIM_IMUT_START", - "SIM_IMUT_TCONST", - "SIM_INS_THR_MIN", - "SIM_LED_LAYOUT", - "SIM_LOOP_DELAY", - "SIM_MAG1_SCALING", - "SIM_MAG2_DEVID", "SIM_MAG2_DIA_X", "SIM_MAG2_DIA_Y", "SIM_MAG2_DIA_Z", @@ -2483,9 +2685,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_MAG2_OFS_X", "SIM_MAG2_OFS_Y", "SIM_MAG2_OFS_Z", - "SIM_MAG2_ORIENT", - "SIM_MAG2_SCALING", - "SIM_MAG3_DEVID", "SIM_MAG3_DIA_X", "SIM_MAG3_DIA_Y", "SIM_MAG3_DIA_Z", @@ -2495,18 +2694,9 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_MAG3_OFS_X", "SIM_MAG3_OFS_Y", "SIM_MAG3_OFS_Z", - "SIM_MAG3_ORIENT", - "SIM_MAG3_SCALING", - "SIM_MAG4_DEVID", - "SIM_MAG5_DEVID", - "SIM_MAG6_DEVID", - "SIM_MAG7_DEVID", - "SIM_MAG8_DEVID", - "SIM_MAG_ALY_HGT", "SIM_MAG_ALY_X", "SIM_MAG_ALY_Y", "SIM_MAG_ALY_Z", - "SIM_MAG_DELAY", "SIM_MAG1_DIA_X", "SIM_MAG1_DIA_Y", "SIM_MAG1_DIA_Z", @@ -2519,19 +2709,10 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_MAG1_OFS_X", "SIM_MAG1_OFS_Y", "SIM_MAG1_OFS_Z", - "SIM_MAG1_ORIENT", - "SIM_MAG_RND", - "SIM_ODOM_ENABLE", "SIM_PARA_ENABLE", "SIM_PARA_PIN", - "SIM_PIN_MASK", - "SIM_PLD_ALT_LMT", - "SIM_PLD_DIST_LMT", - "SIM_RATE_HZ", - "SIM_RC_CHANCOUNT", "SIM_RICH_CTRL", "SIM_RICH_ENABLE", - "SIM_SERVO_SPEED", "SIM_SHIP_DSIZE", "SIM_SHIP_ENABLE", "SIM_SHIP_OFS_X", @@ -2540,45 +2721,13 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_SHIP_PSIZE", "SIM_SHIP_SPEED", "SIM_SHIP_SYSID", - "SIM_SHOVE_TIME", - "SIM_SHOVE_X", - "SIM_SHOVE_Y", - "SIM_SHOVE_Z", - "SIM_SONAR_GLITCH", "SIM_SONAR_POS_X", "SIM_SONAR_POS_Y", "SIM_SONAR_POS_Z", - "SIM_SONAR_RND", - "SIM_SONAR_ROT", - "SIM_SONAR_SCALE", "SIM_TA_ENABLE", - "SIM_TEMP_BFACTOR", - "SIM_TEMP_BRD_OFF", - "SIM_TEMP_START", - "SIM_TEMP_TCONST", - "SIM_TERRAIN", - "SIM_THML_SCENARI", - "SIM_TIDE_DIR", - "SIM_TIDE_SPEED", - "SIM_TIME_JITTER", - "SIM_TWIST_TIME", - "SIM_TWIST_X", - "SIM_TWIST_Y", - "SIM_TWIST_Z", "SIM_VIB_FREQ_X", "SIM_VIB_FREQ_Y", "SIM_VIB_FREQ_Z", - "SIM_VIB_MOT_HMNC", - "SIM_VIB_MOT_MASK", - "SIM_VIB_MOT_MAX", - "SIM_VIB_MOT_MULT", - "SIM_WAVE_AMP", - "SIM_WAVE_DIR", - "SIM_WAVE_ENABLE", - "SIM_WAVE_LENGTH", - "SIM_WAVE_SPEED", - "SIM_WIND_DIR_Z", - "SIM_WIND_T", ]) vinfo_key = self.vehicleinfo_key() @@ -2818,7 +2967,7 @@ def all_log_format_ids(self): continue if "#if AC_PRECLAND_ENABLED" in line: continue - if "#if OFFBOARD_GUIDED == ENABLED" in line: + if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line: continue if "#end" in line: continue @@ -3103,6 +3252,9 @@ def customise_SITL_commandline(self, def default_parameter_list(self): ret = { 'LOG_DISARMED': 1, + # also lower logging rate to reduce log sizes + 'LOG_DARM_RATEMAX': 5, + 'LOG_FILE_RATEMAX': 10, } if self.force_ahrs_type is not None: if self.force_ahrs_type == 2: @@ -3152,26 +3304,6 @@ def stop_SITL(self): util.pexpect_close(self.sitl) self.sitl = None - def close(self): - """Tidy up after running all tests.""" - - if self.mav is not None: - self.mav.close() - self.mav = None - self.stop_SITL() - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - files = glob.glob("*" + valgrind_log) - for valgrind_log in files: - os.chmod(valgrind_log, 0o644) - if os.path.getsize(valgrind_log) > 0: - target = self.buildlogs_path("%s-%s" % ( - self.log_name(), - os.path.basename(valgrind_log))) - self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target)) - shutil.move(valgrind_log, target) - def start_test(self, description): self.progress("##################################################################################") self.progress("########## %s ##########" % description) @@ -3186,7 +3318,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 link: %s => %s, " + self.progress("Problem: Failed to create link: %s => %s, " "will copy tlog manually to target location" % (self.logfile, self.buildlog)) self.copy_tlog = True @@ -3262,6 +3394,71 @@ def idle_hook(self, mav): return self.drain_all_pexpects() + class MessageHook(): + '''base class for objects that watch the message stream and check for + validity of fields''' + def __init__(self, suite): + self.suite = suite + + def process(self): + pass + + def progress_prefix(self): + return "" + + def progress(self, string): + string = self.progress_prefix() + string + self.suite.progress(string) + + class ValidateIntPositionAgainstSimState(MessageHook): + '''monitors a message containing a position containing lat/lng in 1e7, + makes sure it stays close to SIMSTATE''' + def __init__(self, suite, other_int_message_name, max_allowed_divergence=150): + super(TestSuite.ValidateIntPositionAgainstSimState, self).__init__(suite) + self.other_int_message_name = other_int_message_name + self.max_allowed_divergence = max_allowed_divergence + self.max_divergence = 0 + self.gpi = None + self.simstate = None + self.last_print = 0 + self.min_print_interval = 1 # seconds + + def progress_prefix(self): + return "VIPASS: " + + def process(self, mav, m): + if m.get_type() == self.other_int_message_name: + self.gpi = m + elif m.get_type() == 'SIMSTATE': + self.simstate = m + if self.gpi is None: + return + if self.simstate is None: + return + + divergence = self.suite.get_distance_int(self.gpi, self.simstate) + if (time.time() - self.last_print > self.min_print_interval or + divergence > self.max_divergence): + self.progress(f"distance(SIMSTATE,{self.other_int_message_name})={divergence:.5f}m") + self.last_print = time.time() + if divergence > self.max_divergence: + self.max_divergence = divergence + if divergence > self.max_allowed_divergence: + raise NotAchievedException( + "%s diverged from simstate by %fm (max=%fm" % + (self.other_int_message_name, divergence, self.max_allowed_divergence,)) + + def hook_removed(self): + self.progress(f"Maximum divergence was {self.max_divergence}m (max={self.max_allowed_divergence}m)") + + class ValidateGlobalPositionIntAgainstSimState(ValidateIntPositionAgainstSimState): + def __init__(self, suite, **kwargs): + super(TestSuite.ValidateGlobalPositionIntAgainstSimState, self).__init__(suite, 'GLOBAL_POSITION_INT', **kwargs) + + class ValidateAHRS3AgainstSimState(ValidateIntPositionAgainstSimState): + def __init__(self, suite, **kwargs): + super(TestSuite.ValidateAHRS3AgainstSimState, self).__init__(suite, 'AHRS3', **kwargs) + def message_hook(self, mav, msg): """Called as each mavlink msg is received.""" # print("msg: %s" % str(msg)) @@ -3273,6 +3470,13 @@ def message_hook(self, mav, msg): self.idle_hook(mav) self.do_heartbeats() + for h in self.message_hooks: + if isinstance(h, TestSuite.MessageHook): + h.process(mav, msg) + continue + # assume it's a function + h(mav, msg) + def send_message_hook(self, msg, x): self.write_msg_to_tlog(msg) @@ -3459,7 +3663,7 @@ def HIGH_LATENCY2(self): if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0: raise NotAchievedException("Expected GPS to be OK") self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True) - self.set_parameter("SIM_GPS_TYPE", 0) + self.set_parameter("SIM_GPS1_TYPE", 0) self.delay_sim_time(10) self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False) m = self.poll_message("HIGH_LATENCY2") @@ -3468,7 +3672,7 @@ def HIGH_LATENCY2(self): raise NotAchievedException("Expected GPS to be failed") self.start_subtest("HIGH_LATENCY2 location") - self.set_parameter("SIM_GPS_TYPE", 1) + self.set_parameter("SIM_GPS1_TYPE", 1) self.delay_sim_time(10) m = self.poll_message("HIGH_LATENCY2") self.progress(self.dump_message_verbose(m)) @@ -3609,7 +3813,7 @@ def download_full_log_list(self, print_logs=True): raise NotAchievedException("Sequence not increasing") if m.num_logs != num_logs: raise NotAchievedException("Number of logs changed") - if m.time_utc < 1000: + if m.time_utc < 1000 and m.id != m.num_logs: raise NotAchievedException("Bad timestamp") if m.id != m.last_log_num: if m.size == 0: @@ -3910,6 +4114,55 @@ def TestLogDownload(self): # raise NotAchievedException("Size delta: actual=%u vs downloaded=%u" % # (len(actual_bytes), len(backwards_data_downloaded))) + def download_log(self, log_id, timeout=360): + tstart = self.get_sim_time() + data_downloaded = [] + bytes_read = 0 + last_print = 0 + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise NotAchievedException("Did not download log in good time") + self.mav.mav.log_request_data_send( + self.sysid_thismav(), + 1, # target component + log_id, + bytes_read, + 90 + ) + m = self.assert_receive_message('LOG_DATA', timeout=2) + if m.ofs != bytes_read: + raise NotAchievedException(f"Unexpected offset {bytes_read=} {self.dump_message_verbose(m)}") + if m.id != log_id: + raise NotAchievedException(f"Unexpected id {log_id=} {self.dump_message_verbose(m)}") + data_downloaded.extend(m.data[0:m.count]) + bytes_read += m.count + if m.count < 90: # FIXME: constant + break + # self.progress("Read %u bytes at offset %u" % (m.count, m.ofs)) + if time.time() - last_print > 10: + last_print = time.time() + self.progress(f"{bytes_read=}") + return data_downloaded + + def TestLogDownloadLogRestart(self): + '''test logging restarts after log download''' +# self.delay_sim_time(30) + self.set_parameters({ + "LOG_FILE_RATEMAX": 1, + }) + self.reboot_sitl() + number = self.current_onboard_log_number() + content = self.download_log(number) + print(f"Content is of length {len(content)}") + # current_log_filepath = self.current_onboard_log_filepath() + self.delay_sim_time(5) + new_number = self.current_onboard_log_number() + if number == new_number: + raise NotAchievedException("Did not start logging again") + new_content = self.download_log(new_number) + if len(new_content) == 0: + raise NotAchievedException(f"Unexpected length {len(new_content)=}") + ################################################# # SIM UTILITIES ################################################# @@ -4186,6 +4439,7 @@ def wait_message_field_values(self, tstart = self.get_sim_time_cached() pass_start = None + last_debug = 0 while True: now = self.get_sim_time_cached() if now - tstart > timeout: @@ -4201,8 +4455,14 @@ def wait_message_field_values(self, if pass_start is None: pass_start = now continue - if now - pass_start < minimum_duration: + delta = now - pass_start + if now - last_debug >= 1: + last_debug = now + self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)") + if delta < minimum_duration: continue + else: + self.progress("Reached field values") return m pass_start = None @@ -4380,6 +4640,63 @@ def Logging(self): self.onboard_logging_log_disarmed() self.onboard_logging_not_log_disarmed() + def LoggingFormatSanityChecks(self, path): + dfreader = self.dfreader_for_path(path) + first_message = dfreader.recv_match() + if first_message.get_type() != 'FMT': + raise NotAchievedException("Expected first message to be a FMT message") + if first_message.Name != 'FMT': + raise NotAchievedException("Expected first message to be the FMT FMT message") + + self.progress("Ensuring DCM format is received") # it's a WriteStreaming message... + while True: + m = dfreader.recv_match(type='FMT') + if m is None: + raise NotAchievedException("Did not find DCM format") + if m.Name != 'DCM': + continue + self.progress("Found DCM format") + break + + self.progress("No message should appear before its format") + dfreader.rewind() + seen_formats = set() + while True: + m = dfreader.recv_match() + if m is None: + break + m_type = m.get_type() + if m_type == 'FMT': + seen_formats.add(m.Name) + continue + if m_type not in seen_formats: + raise ValueError(f"{m_type} seen before its format") + # print(f"{m_type} OK") + + def LoggingFormat(self): + '''ensure formats are emmitted appropriately''' + + self.context_push() + self.set_parameter('LOG_FILE_DSRMROT', 1) + self.wait_ready_to_arm() + for i in range(3): + self.arm_vehicle() + self.delay_sim_time(5) + path = self.current_onboard_log_filepath() + self.disarm_vehicle() + self.LoggingFormatSanityChecks(path) + self.context_pop() + + self.context_push() + for i in range(3): + self.set_parameter("LOG_DISARMED", 1) + self.reboot_sitl() + self.delay_sim_time(5) + path = self.current_onboard_log_filepath() + self.set_parameter("LOG_DISARMED", 0) + self.LoggingFormatSanityChecks(path) + self.context_pop() + def TestLogDownloadMAVProxy(self, upload_logs=False): """Download latest log.""" filename = "MAVProxy-downloaded-log.BIN" @@ -4573,14 +4890,14 @@ def mission_count(filename): return wploader.count() def install_message_hook(self, hook): - self.mav.message_hooks.append(hook) + self.message_hooks.append(hook) def install_message_hook_context(self, hook): '''installs a message hook which will be removed when the context goes away''' if self.mav is None: return - self.mav.message_hooks.append(hook) + self.message_hooks.append(hook) self.context_get().message_hooks.append(hook) def remove_message_hook(self, hook): @@ -4588,7 +4905,9 @@ def remove_message_hook(self, hook): once''' if self.mav is None: return - self.mav.message_hooks.remove(hook) + self.message_hooks.remove(hook) + if isinstance(hook, TestSuite.MessageHook): + hook.hook_removed() def install_example_script_context(self, scriptname): '''installs an example script which will be removed when the context goes @@ -4596,11 +4915,18 @@ def install_example_script_context(self, scriptname): self.install_example_script(scriptname) self.context_get().installed_scripts.append(scriptname) - def install_test_script_context(self, scriptname): + def install_test_script_context(self, scriptnames): '''installs an test script which will be removed when the context goes away''' - self.install_test_script(scriptname) - self.context_get().installed_scripts.append(scriptname) + if isinstance(scriptnames, str): + scriptnames = [scriptnames] + for scriptname in scriptnames: + self.install_test_script(scriptname) + self.context_get().installed_scripts.extend(scriptnames) + + def install_test_scripts_context(self, *args, **kwargs): + '''same as install_test_scripts_context - just pluralised name''' + return self.install_test_script_context(*args, **kwargs) def install_test_modules_context(self): '''installs test modules which will be removed when the context goes @@ -4614,10 +4940,10 @@ def install_mavlink_module_context(self): self.install_mavlink_module() self.context_get().installed_modules.append("mavlink") - def install_applet_script_context(self, scriptname): + def install_applet_script_context(self, scriptname, **kwargs): '''installs an applet script which will be removed when the context goes away''' - self.install_applet_script(scriptname) + self.install_applet_script(scriptname, **kwargs) self.context_get().installed_scripts.append(scriptname) def rootdir(self): @@ -4913,7 +5239,7 @@ def load_mission(self, filename, strict=True): os.path.join(testdir, self.current_test_name_directory, filename), strict=strict) - def wp_to_mission_item_int(self, wp): + def wp_to_mission_item_int(self, wp, mission_type): '''convert a MISSION_ITEM to a MISSION_ITEM_INT. We always send as MISSION_ITEM_INT to give cm level accuracy Swiped from mavproxy_wp.py @@ -4934,19 +5260,35 @@ def wp_to_mission_item_int(self, wp): wp.param4, int(wp.x*1.0e7), int(wp.y*1.0e7), - wp.z) + wp.z, + mission_type, + ) return wp_int - def mission_from_filepath(self, filepath, target_system=1, target_component=1): + def mission_item_protocol_items_from_filepath(self, + loaderclass, + filepath, + target_system=1, + target_component=1, + ): '''returns a list of mission-item-ints from filepath''' - print("filepath: %s" % filepath) - self.progress("Loading mission (%s)" % os.path.basename(filepath)) - wploader = mavwp.MAVWPLoader( + # self.progress("filepath: %s" % filepath) + self.progress("Loading {loaderclass.itemstype()} (%s)" % os.path.basename(filepath)) + wploader = loaderclass( target_system=target_system, target_component=target_component ) wploader.load(filepath) - return [self.wp_to_mission_item_int(x) for x in wploader.wpoints] + return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:502 + + def mission_from_filepath(self, filepath, target_system=1, target_component=1): + '''returns a list of mission-item-ints from filepath''' + return self.mission_item_protocol_items_from_filepath( + mavwp.MAVWPLoader, + filepath, + target_system=target_system, + target_component=target_component, + ) def sitl_home_string_from_mission(self, filename): '''return a string of the form "lat,lng,yaw,alt" from the home @@ -4967,6 +5309,10 @@ def get_home_tuple_from_mission(self, filename): os.path.join(testdir, self.current_test_name_directory, filename) ) + def get_home_location_from_mission(self, filename): + (home_lat, home_lon, home_alt, heading) = self.get_home_tuple_from_mission("rover-path-planning-mission.txt") + return mavutil.location(home_lat, home_lon) + def get_home_tuple_from_mission_filepath(self, filepath): '''gets item 0 from the mission file, returns a tuple suitable for passing to customise_SITL_commandline as --home. Yaw will be @@ -5360,6 +5706,10 @@ def set_rc(self, chan, pwm, timeout=20): """Setup a simulated RC control to a PWM value""" self.set_rc_from_map({chan: pwm}, timeout=timeout) + def set_servo(self, chan, pwm): + """Replicate the functionality of MAVProxy: servo set """ + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm) + def location_offset_ne(self, location, north, east): '''move location in metres''' print("old: %f %f" % (location.lat, location.lng)) @@ -5373,6 +5723,12 @@ def home_relative_loc_ne(self, n, e): self.location_offset_ne(ret, n, e) return ret + def home_relative_loc_neu(self, n, e, u): + ret = self.home_position_as_mav_location() + self.location_offset_ne(ret, n, e) + ret.alt += u + return ret + def zero_throttle(self): """Set throttle to zero.""" if self.is_rover(): @@ -5732,7 +6088,7 @@ def arm_motors_with_rc_input(self, timeout=20): self.set_output_to_trim(self.get_stick_arming_channel()) self.progress("Arm in %ss" % tdelta) # TODO check arming time return - print("Not armed after %f seconds" % (tdelta)) + self.progress("Not armed after %f seconds" % (tdelta)) if tdelta > timeout: break self.set_output_to_trim(self.get_stick_arming_channel()) @@ -5991,11 +6347,11 @@ def get_parameter_mavproxy(self, mavproxy, name, attempts=1, timeout=60): pass raise NotAchievedException("Failed to retrieve parameter (%s)" % name) - def get_parameters(self, some_list): + def get_parameters(self, some_list, **kwargs): ret = {} for n in some_list: - ret[n] = self.get_parameter(n) + ret[n] = self.get_parameter(n, **kwargs) return ret @@ -6045,17 +6401,18 @@ def context_stop_collecting(self, msg_type): del context.collections[msg_type] return ret - def context_pop(self, process_interaction_allowed=True): + def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False): """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 not hooks_already_removed: + for hook in dead.message_hooks: + self.remove_message_hook(hook) for script in dead.installed_scripts: self.remove_installed_script(script) - for (message_id, interval_us) in dead.overridden_message_rates.items(): - self.set_message_interval(message_id, interval_us) + for (message_id, rate_hz) in dead.overridden_message_rates.items(): + self.set_message_rate_hz(message_id, rate_hz) for module in dead.installed_modules: print("Removing module (%s)" % module) self.remove_installed_modules(module) @@ -6075,6 +6432,9 @@ def context_pop(self, process_interaction_allowed=True): f.close() self.start_SITL(wipe=False) self.set_streamrate(self.sitl_streamrate()) + elif dead.reboot_sitl_was_done: + self.progress("Doing implicit context-pop reboot") + self.reboot_sitl(mark_context=False) # the following method is broken under Python2; can't **build_opts # def context_start_custom_binary(self, extra_defines={}): @@ -6189,19 +6549,20 @@ def run_cmd_int(self, command_name = mavutil.mavlink.enums["MAV_CMD"][command].name except KeyError: command_name = "UNKNOWNu" - self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f)" % - ( - target_sysid, - target_compid, - command_name, - command, - p1, - p2, - p3, - p4, - x, - y, - z)) + self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f f=%u)" % ( + target_sysid, + target_compid, + command_name, + command, + p1, + p2, + p3, + p4, + x, + y, + z, + frame + )) mav.mav.command_int_send(target_sysid, target_compid, frame, @@ -6381,6 +6742,12 @@ def verify_parameter_values(self, parameter_stuff, max_delta=0.0): ################################################# # UTILITIES ################################################# + def lineno(self): + '''return line number''' + frameinfo = getframeinfo(currentframe().f_back) + # print(frameinfo.filename, frameinfo.lineno) + return frameinfo.lineno + @staticmethod def longitude_scale(lat): ret = math.cos(lat * (math.radians(1))) @@ -6606,6 +6973,18 @@ def get_mode_from_mode_mapping(self, mode): self.progress("No mode (%s); available modes '%s'" % (mode, mode_map)) raise ErrorException("Unknown mode '%s'" % mode) + def get_mode_string_for_mode(self, mode): + if isinstance(mode, str): + return mode + mode_map = self.mav.mode_mapping() + if mode_map is None: + return f"mode={mode}" + for (n, v) in mode_map.items(): + if v == mode: + return n + self.progress(f"No mode ({mode} {type(mode)}); available modes '{mode_map}'") + raise ErrorException("Unknown mode '%s'" % mode) + def run_cmd_do_set_mode(self, mode, timeout=30, @@ -6756,22 +7135,17 @@ def do_set_relay_mavproxy(self, relay_num, on_off): self.mavproxy.expect("Loaded module relay") self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off)) - def do_fence_en_or_dis_able(self, value, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - if value: - p1 = 1 - else: - p1 = 0 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, - p1=p1, # param1 - want_result=want_result, - ) - def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.do_fence_en_or_dis_able(True, want_result=want_result) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result) def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.do_fence_en_or_dis_able(False, want_result=want_result) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result) + + def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result) + + def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result) ################################################# # WAIT UTILITIES @@ -6803,6 +7177,10 @@ def get_altitude(self, relative=False, timeout=30, altitude_source=None): altitude_source = "GLOBAL_POSITION_INT.relative_alt" else: altitude_source = "GLOBAL_POSITION_INT.alt" + if altitude_source == "TERRAIN_REPORT.current_height": + terrain = self.assert_receive_message('TERRAIN_REPORT') + return terrain.current_height + (msg, field) = altitude_source.split('.') msg = self.poll_message(msg, quiet=True) divisor = 1000.0 # mm is pretty common in mavlink @@ -6928,13 +7306,13 @@ def validator(value2, target2=None): self.wait_and_maintain( value_name="Altitude", - target=altitude_min, + target=(altitude_min + altitude_max)*0.5, current_value_getter=lambda: self.get_altitude( relative=relative, timeout=timeout, altitude_source=altitude_source, ), - accuracy=(altitude_max - altitude_min), + accuracy=(altitude_max - altitude_min)*0.5, validator=lambda value2, target2: validator(value2, target2), timeout=timeout, **kwargs @@ -7059,8 +7437,8 @@ def wait_and_maintain(self, value_name, target, current_value_getter, validator= ) return self.wait_and_maintain_range( value_name, - minimum=target - accuracy/2, - maximum=target + accuracy/2, + minimum=target - accuracy, + maximum=target + accuracy, current_value_getter=current_value_getter, validator=validator, timeout=timeout, @@ -7377,6 +7755,23 @@ def validator(value2, target2): **kwargs ) + def wait_distance_between(self, series1, series2, min_distance, max_distance, timeout=30, **kwargs): + """Wait for distance between two position series to be between two thresholds.""" + def get_distance(): + self.drain_mav() + m1 = self.mav.messages[series1] + m2 = self.mav.messages[series2] + return self.get_distance_int(m1, m2) + + self.wait_and_maintain_range( + value_name=f"Distance({series1}, {series2})", + minimum=min_distance, + maximum=max_distance, + current_value_getter=lambda: get_distance(), + timeout=timeout, + **kwargs + ) + def wait_distance(self, distance, accuracy=2, timeout=30, **kwargs): """Wait for flight of a given distance.""" start = self.mav.location() @@ -7542,7 +7937,7 @@ def get_servo_channel_value(self, channel, timeout=2): (str(m), channel_field)) return m_value - def wait_servo_channel_value(self, channel, value, timeout=2, comparator=operator.eq): + def wait_servo_channel_value(self, channel, value, epsilon=0, timeout=2, comparator=operator.eq): """wait for channel value comparison (default condition is equality)""" channel_field = "servo%u_raw" % channel opstring = ("%s" % comparator)[-3:-1] @@ -7560,11 +7955,36 @@ def wait_servo_channel_value(self, channel, value, timeout=2, comparator=operato if m_value is None: raise ValueError("message (%s) has no field %s" % (str(m), channel_field)) - self.progress("want SERVO_OUTPUT_RAW.%s=%u %s %u" % + self.progress("SERVO_OUTPUT_RAW.%s got=%u %s want=%u" % (channel_field, m_value, opstring, value)) + if comparator == operator.eq: + if abs(m_value - value) <= epsilon: + return m_value if comparator(m_value, value): return m_value + def wait_servo_channel_in_range(self, channel, v_min, v_max, timeout=2): + """wait for channel value to be within acceptable range""" + channel_field = "servo%u_raw" % channel + tstart = self.get_sim_time() + while True: + remaining = timeout - (self.get_sim_time_cached() - tstart) + if remaining <= 0: + raise NotAchievedException("Channel value condition not met") + m = self.mav.recv_match(type='SERVO_OUTPUT_RAW', + blocking=True, + timeout=remaining) + if m is None: + continue + 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("want %u <= SERVO_OUTPUT_RAW.%s <= %u, got value = %u" % + (v_min, channel_field, v_max, m_value)) + if (v_min <= m_value) and (m_value <= v_max): + 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 @@ -7580,6 +8000,20 @@ def assert_servo_channel_value(self, channel, value, comparator=operator.eq): return m_value raise NotAchievedException("Wrong value") + def assert_servo_channel_range(self, channel, value_min, value_max): + """assert channel value is within the range [value_min, value_max]""" + channel_field = "servo%u_raw" % channel + 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 in [%u, %u]" % + (channel_field, m_value, value_min, value_max)) + if m_value >= value_min and m_value <= value_max: + 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 @@ -7622,9 +8056,9 @@ def assert_rc_channel_value(self, channel, value): raise NotAchievedException("Expected %s to be %u got %u" % (channel, value, m_value)) - def do_reposition(self, - loc, - frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT): + def send_do_reposition(self, + loc, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT): '''send a DO_REPOSITION command for a location''' self.run_cmd_int( mavutil.mavlink.MAV_CMD_DO_REPOSITION, @@ -7680,7 +8114,8 @@ def wait_waypoint(self, wpnum_end, allow_skip=True, max_dist=2, - timeout=400): + timeout=400, + ignore_RTL_mode_change=False): """Wait for waypoint ranges.""" tstart = self.get_sim_time() # this message arrives after we set the current WP @@ -7703,8 +8138,11 @@ def wait_waypoint(self, m = self.assert_receive_message('VFR_HUD') # if we changed mode, fail - if self.mav.flightmode != mode: - raise WaitWaypointTimeout('Exited %s mode' % mode) + if not self.mode_is('AUTO'): + self.progress(f"{self.mav.flightmode} vs {self.get_mode_from_mode_mapping(mode)}") + if not ignore_RTL_mode_change or not self.mode_is('RTL', cached=True): + new_mode_str = self.get_mode_string_for_mode(self.get_mode()) + raise WaitWaypointTimeout(f'Exited {mode} mode to {new_mode_str} ignore={ignore_RTL_mode_change}') if self.get_sim_time_cached() - last_wp_msg > 1: self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u," @@ -7735,9 +8173,9 @@ def get_cached_message(self, message_type): '''returns the most-recently received instance of message_type''' return self.mav.messages[message_type] - def mode_is(self, mode, cached=False, drain_mav=True): + def mode_is(self, mode, cached=False, drain_mav=True, drain_mav_quietly=True): if not cached: - self.wait_heartbeat(drain_mav=drain_mav) + self.wait_heartbeat(drain_mav=drain_mav, quiet=drain_mav_quietly) try: return self.get_mode_from_mode_mapping(self.mav.flightmode) == self.get_mode_from_mode_mapping(mode) except Exception: @@ -7762,6 +8200,12 @@ def assert_mode_is(self, mode): if not self.mode_is(mode): raise NotAchievedException("Expected mode %s" % str(mode)) + def get_mode(self, cached=False, drain_mav=True): + '''return numeric custom mode''' + if not cached: + self.wait_heartbeat(drain_mav=drain_mav) + return self.mav.messages['HEARTBEAT'].custom_mode + def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30): self.progress("Waiting for GPS health") tstart = self.get_sim_time() @@ -7995,8 +8439,10 @@ def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x): if m.get_srcSystem() == self.sysid_thismav(): return m - def wait_ekf_happy(self, timeout=45, require_absolute=True): + def wait_ekf_happy(self, require_absolute=True, **kwargs): """Wait for EKF to be happy""" + if "timeout" not in kwargs: + kwargs["timeout"] = 45 """ if using SITL estimates directly """ if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10): @@ -8016,39 +8462,14 @@ def wait_ekf_happy(self, timeout=45, require_absolute=True): mavutil.mavlink.ESTIMATOR_POS_VERT_ABS | mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS) error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH - self.wait_ekf_flags(required_value, error_bits, timeout=timeout) + WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run() - def wait_ekf_flags(self, required_value, error_bits, timeout=30): - self.progress("Waiting for EKF value %u" % required_value) - last_print_time = 0 - tstart = self.get_sim_time() - m = None - while timeout is None or self.get_sim_time_cached() < tstart + timeout: - m = self.mav.recv_match(type='EKF_STATUS_REPORT', blocking=True, timeout=timeout) - if m is None: - continue - current = m.flags - errors = current & error_bits - everything_ok = (errors == 0 and - current & required_value == required_value) - if everything_ok or self.get_sim_time_cached() - last_print_time > 1: - self.progress("Wait EKF.flags: required:%u current:%u errors=%u" % - (required_value, current, errors)) - last_print_time = self.get_sim_time_cached() - if everything_ok: - self.progress("EKF Flags OK") - return True - m_str = str(m) - if m is not None: - m_str = self.dump_message_verbose(m) - self.progress("Last EKF_STATUS_REPORT message:") - self.progress(m_str) - raise AutoTestTimeoutException("Failed to get EKF.flags=%u" % - required_value) + def wait_ekf_flags(self, required_value, error_bits, **kwargs): + WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run() def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30): """Disable GPS and wait for EKF to report the end of assistance from GPS.""" - self.set_parameter("SIM_GPS_DISABLE", 1) + self.set_parameter("SIM_GPS1_ENABLE", 0) tstart = self.get_sim_time() """ if using SITL estimates directly """ @@ -8181,6 +8602,20 @@ def install_script(self, source, scriptname, install_name=None): self.progress("Copying (%s) to (%s)" % (source, dest)) shutil.copy(source, dest) + def installed_script_module_path(self, modulename): + return os.path.join("scripts", "modules", os.path.basename(modulename)) + + def install_script_module(self, source, modulename, install_name=None): + if install_name is not None: + dest = self.installed_script_module_path(install_name) + else: + dest = self.installed_script_module_path(modulename) + + destdir = os.path.dirname(dest) + os.makedirs(destdir, exist_ok=True) + self.progress("Copying (%s) to (%s)" % (source, dest)) + shutil.copy(source, dest) + def install_test_modules(self): source = os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", "modules", "test") dest = os.path.join("scripts", "modules", "test") @@ -8215,6 +8650,10 @@ def remove_installed_script(self, scriptname): except OSError: pass + def remove_installed_script_module(self, modulename): + path = self.installed_script_module_path(modulename) + os.unlink(path) + def remove_installed_modules(self, modulename): dest = os.path.join("scripts", "modules", modulename) try: @@ -8409,7 +8848,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout) - start_message_hooks = self.mav.message_hooks + start_message_hooks = copy.copy(self.message_hooks) prettyname = "%s (%s)" % (name, desc) self.start_test(prettyname) @@ -8421,6 +8860,8 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= orig_speedup = None + hooks_removed = False + ex = None try: self.check_rc_defaults() @@ -8441,9 +8882,10 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= 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: + for h in copy.copy(self.message_hooks): if h not in start_message_hooks: - self.mav.message_hooks.remove(h) + self.message_hooks.remove(h) + hooks_removed = True self.test_timings[desc] = time.time() - start_time reset_needed = self.contexts[-1].sitl_commandline_customised @@ -8470,7 +8912,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= reset_needed = True try: - self.context_pop(process_interaction_allowed=ardupilot_alive) + self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed) except Exception as e: self.print_exception_caught(e, send_statustext=False) passed = False @@ -8482,6 +8924,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= if ex is None: ex = ArmedAtEndOfTestException("Still armed at end of test") self.progress("Armed at end of test; force-rebooting SITL") + self.set_rc_default() # otherwise we might start calibrating ESCs... try: self.disarm_vehicle(force=True) except AutoTestTimeoutException: @@ -8492,7 +8935,8 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= self.reset_SITL_commandline() else: self.progress("Force-rebooting SITL") - self.reboot_sitl() # that'll learn it + self.zero_throttle() + self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it passed = False elif ardupilot_alive and not passed: # implicit reboot after a failed test: self.progress("Test failed but ArduPilot process alive; rebooting") @@ -8522,15 +8966,15 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= # pop off old contexts to clean up message hooks etc while len(self.contexts) > old_contexts_length: try: - self.context_pop(process_interaction_allowed=ardupilot_alive) + self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed) 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) != len(start_message_hooks): + if len(self.message_hooks) != len(start_message_hooks): self.progress("Stray message listeners: %s vs start %s" % - (str(self.mav.message_hooks), str(start_message_hooks))) + (str(self.message_hooks), str(start_message_hooks))) passed = False if passed: @@ -8636,6 +9080,7 @@ def start_SITL(self, binary=None, sitl_home=None, **sitl_args): "valgrind": self.valgrind, "callgrind": self.callgrind, "wipe": True, + "enable_fgview": self.enable_fgview, } start_sitl_args.update(**sitl_args) if ("defaults_filepath" not in start_sitl_args or @@ -8797,8 +9242,7 @@ def upload_using_mission_protocol(self, mission_type, items): m.mission_type == 0): # this is just MAVProxy trying to screw us up continue - else: - raise NotAchievedException("Received unexpected mission ack %s" % str(m)) + raise NotAchievedException(f"Received unexpected mission ack {self.dump_message_verbose(m)}") self.progress("Handling request for item %u/%u" % (m.seq, len(items)-1)) self.progress("Item (%s)" % str(items[m.seq])) @@ -8813,7 +9257,7 @@ def upload_using_mission_protocol(self, mission_type, items): raise NotAchievedException("received request for item from wrong mission type") if items[m.seq].mission_type != mission_type: - raise NotAchievedException("supplied item not of correct mission type") + raise NotAchievedException(f"supplied item not of correct mission type (want={mission_type} got={items[m.seq].mission_type}") # noqa:501 if items[m.seq].target_system != target_system: raise NotAchievedException("supplied item not of correct target system") if items[m.seq].target_component != target_component: @@ -8984,6 +9428,20 @@ def offset_location_ne(self, location, metres_north, metres_east): location.alt, location.heading) + def offset_location_heading_distance(self, location, bearing, distance): + (target_lat, target_lng) = mavextra.gps_newpos( + location.lat, + location.lng, + bearing, + distance + ) + return mavutil.location( + target_lat, + target_lng, + location.alt, + location.heading + ) + def monitor_groundspeed(self, want, tolerance=0.5, timeout=5): tstart = self.get_sim_time() while True: @@ -9788,13 +10246,13 @@ def DataFlashOverMAVLink(self): self.arm_vehicle() tstart = self.get_sim_time() last_status = 0 + mavproxy.send('repeat add 1 dataflash_logger status\n') while True: now = self.get_sim_time() if now - tstart > 60: break if now - last_status > 5: last_status = now - mavproxy.send('dataflash_logger status\n') # seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:0 mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)") rate = float(mavproxy.match.group(1)) @@ -9805,11 +10263,11 @@ def DataFlashOverMAVLink(self): if rate < desired_rate: raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate)) self.disarm_vehicle() + mavproxy.send('repeat remove 0\n') except Exception as e: self.print_exception_caught(e) self.disarm_vehicle() ex = e - self.context_pop() self.mavproxy_unload_module(mavproxy, 'dataflash_logger') # the following things won't work - but they shouldn't die either: @@ -9829,6 +10287,8 @@ def DataFlashOverMAVLink(self): self.mavproxy_unload_module(mavproxy, 'log') + self.context_pop() + self.stop_mavproxy(mavproxy) self.reboot_sitl() if ex is not None: @@ -10235,7 +10695,7 @@ def ArmFeatures(self): p1=1, # ARM want_result=mavutil.mavlink.MAV_RESULT_FAILED, ) - self.set_parameter("SIM_GPS_DISABLE", 0) + self.set_parameter("SIM_GPS1_ENABLE", 1) self.wait_ekf_happy() # EKF may stay unhappy for a while self.progress("PASS not able to arm without Position in mode : %s" % mode) if mode in self.get_no_position_not_settable_modes_list(): @@ -10245,10 +10705,10 @@ def ArmFeatures(self): try: self.change_mode(mode, timeout=15) except AutoTestTimeoutException: - self.set_parameter("SIM_GPS_DISABLE", 0) + self.set_parameter("SIM_GPS1_ENABLE", 1) self.progress("PASS not able to set mode without Position : %s" % mode) except ValueError: - self.set_parameter("SIM_GPS_DISABLE", 0) + self.set_parameter("SIM_GPS1_ENABLE", 1) self.progress("PASS not able to set mode without Position : %s" % mode) if mode == "FOLLOW": self.set_parameter("FOLL_ENABLE", 0) @@ -10457,6 +10917,14 @@ def MESSAGE_INTERVAL_COMMAND_INT(self): if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1: raise NotAchievedException("Did not set rate") + # Try setting a rate well beyond SCHED_LOOP_RATE + self.run_cmd( + mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, + p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD, + p2=self.rate_to_interval_us(800), + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT") # 148 is AUTOPILOT_VERSION: self.context_collect('AUTOPILOT_VERSION') @@ -10571,13 +11039,17 @@ def send_poll_message(self, message_id, target_sysid=None, target_compid=None, q mav=mav, ) - def poll_message(self, message_id, timeout=10, quiet=False, mav=None): + def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None): if mav is None: mav = self.mav + if target_sysid is None: + target_sysid = self.sysid_thismav() + if target_compid is None: + target_compid = 1 if isinstance(message_id, str): message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id) tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work - self.send_poll_message(message_id, quiet=quiet, mav=mav) + self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid) self.run_cmd_get_ack( mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, mavutil.mavlink.MAV_RESULT_ACCEPTED, @@ -10596,6 +11068,9 @@ def poll_message(self, message_id, timeout=10, quiet=False, mav=None): continue if m.id != message_id: continue + if (m.get_srcSystem() != target_sysid or + m.get_srcComponent() != target_compid): + continue return m def get_messages_frame(self, msg_names): @@ -11611,26 +12086,19 @@ def initial_mode_switch_mode(self): '''return mode vehicle should start in with default RC inputs set''' return None - def upload_fences_from_locations(self, - vertex_type, - list_of_list_of_locs, - target_system=1, - target_component=1): + def upload_fences_from_locations(self, fences, target_system=1, target_component=1): seq = 0 items = [] - for locs in list_of_list_of_locs: + + for (vertex_type, locs) in fences: if isinstance(locs, dict): # circular fence - if vertex_type == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION: - v = mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION - else: - v = mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION item = self.mav.mav.mission_item_int_encode( target_system, target_component, seq, # seq mavutil.mavlink.MAV_FRAME_GLOBAL, - v, + vertex_type, 0, # current 0, # autocontinue locs["radius"], # p1 @@ -11740,6 +12208,10 @@ def last_onboard_log(self): self.stop_mavproxy(mavproxy) return num_log + def current_onboard_log_number(self): + logs = self.download_full_log_list(print_logs=False) + return sorted(logs.keys())[-1] + def current_onboard_log_filepath(self): '''return filepath to currently open dataflash log. We assume that's the latest log...''' @@ -11806,7 +12278,28 @@ def run_tests(self, tests) -> List[Result]: self.rc_thread_should_quit = True self.rc_thread.join() self.rc_thread = None - self.close() + + if self.mav is not None: + self.mav.close() + self.mav = None + + self.stop_SITL() + + valgrind_log = util.valgrind_log_filepath(binary=self.binary, + model=self.frame) + files = glob.glob("*" + valgrind_log) + valgrind_failed = False + for valgrind_log in files: + os.chmod(valgrind_log, 0o644) + if os.path.getsize(valgrind_log) > 0: + target = self.buildlogs_path("%s-%s" % ( + self.log_name(), + os.path.basename(valgrind_log))) + self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target)) + shutil.move(valgrind_log, target) + valgrind_failed = True + if valgrind_failed: + result_list.append(ValgrindFailedResult()) return result_list @@ -11832,6 +12325,7 @@ def download_parameters(self, target_system, target_component): expected_count = 0 seen_ids = {} self.progress("Downloading parameters") + debug = False while True: now = self.get_sim_time_cached() if not start_done or now - last_parameter_received > 10: @@ -11842,6 +12336,7 @@ def download_parameters(self, target_system, target_component): elif attempt_count != 0: self.progress("Download failed; retrying") self.delay_sim_time(1) + debug = True self.drain_mav() self.mav.mav.param_request_list_send(target_system, target_component) attempt_count += 1 @@ -11856,8 +12351,8 @@ def download_parameters(self, target_system, target_component): if m.param_index == 65535: self.progress("volunteered parameter: %s" % str(m)) continue - if False: - self.progress(" received (%4u/%4u %s=%f" % + if debug: + self.progress(" received id=%4u param_count=%4u %s=%f" % (m.param_index, m.param_count, m.param_id, m.param_value)) if m.param_index >= m.param_count: raise ValueError("parameter index (%u) gte parameter count (%u)" % @@ -12050,7 +12545,7 @@ def AdvancedFailsafe(self): self.context_collect("STATUSTEXT") self.set_parameters({ "AFS_MAX_GPS_LOSS": 1, - "SIM_GPS_DISABLE": 1, + "SIM_GPS1_ENABLE": 0, }) self.wait_statustext("AFS State: GPS_LOSS", check_context=True) self.context_pop() @@ -13627,6 +14122,17 @@ def CompassPrearms(self): # heading seemingly indefinitely. self.reboot_sitl() + def run_replay(self, filepath): + '''runs replay in filepath, returns filepath to Replay logfile''' + util.run_cmd( + ['build/sitl/tool/Replay', filepath], + directory=util.topdir(), + checkfail=True, + show=True, + output=True, + ) + return self.current_onboard_log_filepath() + def AHRS_ORIENTATION(self): '''test AHRS_ORIENTATION parameter works''' self.context_push() @@ -13651,15 +14157,16 @@ def GPSTypes(self): '''check each simulated GPS works''' self.reboot_sitl() orig = self.poll_home_position(timeout=60) - # (sim_gps_type, name, gps_type, detection name) - # if gps_type is None we auto-detect sim_gps = [ + # (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) + # if gps_type is None we auto-detect # (0, "NONE"), (1, "UBLOX", None, "u-blox", 5, 'probing'), (5, "NMEA", 5, "NMEA", 5, 'probing'), (6, "SBP", None, "SBP", 5, 'probing'), - # (7, "SBP2", 9, "SBP2", 5), # broken, "waiting for config data" (8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS + (9, "SBP2", None, "SBP2", 5, 'probing'), + (10, "SBF", 10, 'SBF', 5, 'probing'), (11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS (19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS # (9, "FILE"), @@ -13667,7 +14174,7 @@ def GPSTypes(self): self.context_collect("STATUSTEXT") for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps: self.start_subtest("Checking GPS type %s" % name) - self.set_parameter("SIM_GPS_TYPE", sim_gps_type) + self.set_parameter("SIM_GPS1_TYPE", sim_gps_type) self.set_parameter("SERIAL3_PROTOCOL", serial_protocol) if gps_type is None: gps_type = 1 # auto-detect @@ -13682,7 +14189,7 @@ def GPSTypes(self): n = self.poll_home_position(timeout=120) distance = self.get_distance_int(orig, n) if distance > 1: - raise NotAchievedException("gps type %u misbehaving" % name) + raise NotAchievedException(f"gps type {name} misbehaving") def assert_gps_satellite_count(self, messagename, count): m = self.assert_receive_message(messagename) @@ -13772,7 +14279,7 @@ def MultipleGPS(self): self.start_subtest("Ensure detection when sim gps connected") self.set_parameter("SIM_GPS2_TYPE", 1) - self.set_parameter("SIM_GPS2_DISABLE", 0) + self.set_parameter("SIM_GPS2_ENABLE", 1) # a reboot is required after setting GPS2_TYPE. We start # sending GPS2_RAW out, once the parameter is set, but a # reboot is required because _port[1] is only set in @@ -13788,9 +14295,9 @@ def MultipleGPS(self): raise NotAchievedException("Incorrect fix type") self.start_subtest("Check parameters are per-GPS") - self.assert_parameter_value("SIM_GPS_NUMSATS", 10) + self.assert_parameter_value("SIM_GPS1_NUMSATS", 10) self.assert_gps_satellite_count("GPS_RAW_INT", 10) - self.set_parameter("SIM_GPS_NUMSATS", 13) + self.set_parameter("SIM_GPS1_NUMSATS", 13) self.assert_gps_satellite_count("GPS_RAW_INT", 13) self.assert_parameter_value("SIM_GPS2_NUMSATS", 10) @@ -13818,7 +14325,7 @@ def MultipleGPS(self): if abs(gpi_alt - new_gpi_alt) > 100: raise NotAchievedException("alt moved unexpectedly") self.progress("Killing first GPS") - self.set_parameter("SIM_GPS_DISABLE", 1) + self.set_parameter("SIM_GPS1_ENABLE", 0) self.delay_sim_time(1) self.progress("Checking altitude now matches second GPS") m = self.assert_receive_message("GLOBAL_POSITION_INT") @@ -14031,6 +14538,115 @@ def MotorTest(self, timeout=60, **kwargs): self._MotorTest(self.run_cmd, **kwargs) self._MotorTest(self.run_cmd_int, **kwargs) + def test_ibus_voltage(self, message): + batt = self.mav.recv_match( + type='BATTERY_STATUS', + blocking=True, + timeout=5, + condition="BATTERY_STATUS.id==0" + ) + if batt is None: + raise NotAchievedException("Did not get BATTERY_STATUS message") + want = int(batt.voltages[0] * 0.1) + + if want != message.get_sensor_value(): + raise NotAchievedException("Bad voltage (want=%u got=%u)" % + (want, message.get_sensor_value())) + self.progress("iBus voltage OK") + + def test_ibus_armed(self, message): + got = message.get_sensor_value() + want = 1 if self.armed() else 0 + if got != want: + raise NotAchievedException("Expected armed %u got %u" % + (want, got)) + self.progress("iBus armed OK") + + def test_ibus_mode(self, message): + got = message.get_sensor_value() + want = self.mav.messages['HEARTBEAT'].custom_mode + if got != want: + raise NotAchievedException("Expected mode %u got %u" % + (want, got)) + self.progress("iBus mode OK") + + def test_ibus_get_response(self, ibus, timeout=5): + tstart = self.get_sim_time() + while True: + now = self.get_sim_time() + if now - tstart > timeout: + raise AutoTestTimeoutException("Failed to get ibus data") + packet = ibus.update() + if packet is not None: + return packet + + def IBus(self): + '''test the IBus protocol''' + self.set_parameter("SERIAL5_PROTOCOL", 49) + self.customise_SITL_commandline([ + "--serial5=tcp:6735" # serial5 spews to localhost:6735 + ]) + ibus = IBus(("127.0.0.1", 6735)) + ibus.connect() + + # expected_sensors should match the list created in AP_IBus_Telem + expected_sensors = { + # sensor id : (len, IBUS_MEAS_TYPE_*, test_function) + 1: (2, 0x15, self.test_ibus_armed), + 2: (2, 0x16, self.test_ibus_mode), + 5: (2, 0x03, self.test_ibus_voltage), + } + + for (sensor_addr, results) in expected_sensors.items(): + # first make sure it is present: + request = IBusRequest_DISCOVER(sensor_addr) + ibus.port.sendall(request.for_wire()) + + packet = self.test_ibus_get_response(ibus) + if packet.address != sensor_addr: + raise ValueError("Unexpected sensor address %u" % + (packet.address,)) + + (expected_length, expected_type, validator) = results + + self.progress("Getting sensor (%x) type" % (sensor_addr)) + request = IBusRequest_GET_SENSOR_TYPE(sensor_addr) + ibus.port.sendall(request.for_wire()) + + packet = self.test_ibus_get_response(ibus) + if packet.address != sensor_addr: + raise ValueError("Unexpected sensor address %u" % + (packet.address,)) + + if packet.sensor_type != expected_type: + raise ValueError("Unexpected sensor type want=%u got=%u" % + (expected_type, packet.sensor_type)) + + if packet.sensor_length != expected_length: + raise ValueError("Unexpected sensor len want=%u got=%u" % + (expected_length, packet.sensor_length)) + + self.progress("Getting sensor (%x) value" % (sensor_addr)) + request = IBusRequest_GET_SENSOR_VALUE(sensor_addr) + ibus.port.sendall(request.for_wire()) + + packet = self.test_ibus_get_response(ibus) + validator(packet) + + # self.progress("Ensure we cover all sensors") + # for i in range(1, 17): # zero is special + # if i in expected_sensors: + # continue + # request = IBusRequest_DISCOVER(i) + # ibus.port.sendall(request.for_wire()) + + # try: + # packet = self.test_ibus_get_response(ibus, timeout=1) + # except AutoTestTimeoutException: + # continue + # self.progress("Received packet (%s)" % str(packet)) + # raise NotAchievedException("IBus sensor %u is untested" % i) + def tests(self): return [ self.PIDTuning, @@ -14205,6 +14821,8 @@ def add_fftd(self, fftd): sample_rate = 0 counts = 0 window = numpy.hanning(fft_len) + # The returned float array f contains the frequency bin centers in cycles per unit of the + # sample spacing (with zero at the start). freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz) # calculate NEBW constant @@ -14258,7 +14876,12 @@ def model_defaults_filepath(self, model): 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) + self.repeatedly_apply_parameter_filepath(filepath) + + def load_params_file(self, filename): + '''load a file from test-specific directory''' + filepath = os.path.join(testdir, self.current_test_name_directory, filename) + self.repeatedly_apply_parameter_filepath(filepath) def send_pause_command(self): '''pause AUTO/GUIDED modes''' diff --git a/Tools/bootloaders/3DRControlZeroG_bl.bin b/Tools/bootloaders/3DRControlZeroG_bl.bin new file mode 100644 index 00000000000000..51184c0a0b1567 Binary files /dev/null and b/Tools/bootloaders/3DRControlZeroG_bl.bin differ diff --git a/Tools/bootloaders/3DRControlZeroG_bl.hex b/Tools/bootloaders/3DRControlZeroG_bl.hex new file mode 100644 index 00000000000000..ca781103d1cf13 --- /dev/null +++ b/Tools/bootloaders/3DRControlZeroG_bl.hex @@ -0,0 +1,1212 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008D92E0008FA +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008414400086D44000880 +:1000600099440008C5440008F14400082D11000817 +:100070005511000881110008AD110008D9110008C0 +:10008000011200082D120008E3020008E302000834 +:10009000E3020008E3020008E30200081D4500082F +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008F5450008E302000817 +:1000E00081450008E3020008E3020008E30200087B +:1000F000E3020008E3020008E302000859120008C6 +:10010000E3020008E302000809460008E3020008D1 +:10011000E3020008E3020008E3020008E30200082B +:1001200085120008AD120008D91200080513000856 +:1001300031130008E3020008E3020008E3020008AC +:10014000E3020008E3020008E3020008E3020008FB +:100150005913000885130008B1130008E3020008D2 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008C53A0008E3020008E3020008B1 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008B13A0008E3020008E302000865 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F026FE4A +:1003500003F034FE4FF055301F491B4A91423CBF19 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F03EFE03F092FE88 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F026BE000600200022002040 +:1003D0000000000808ED00E00000002000060020FA +:1003E000304B0008002200206422002068220020F8 +:1003F00044480020E0020008E0020008E002000893 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002002F0DAF8FEE702F023 +:1004300069F800DFFEE7000038B500F045FC00F089 +:1004400009FE02F009FD054602F03CFD0446C0B974 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F000FD0CB100F03C +:1004700075F800F08DFD284600F01EF900F06EF8CA +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0E5FBA0F120035842584108BD23 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000F5FB03B05DF804FB38B5302383F31188F6 +:1004C000174803680BB102F057F90023154A4FF49F +:1004D0007A71134802F046F9002383F31188124C15 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0A8FC322363602B78032B07D16368CB +:100510002BB9022000F09EFC4FF47A73636038BD63 +:1005200068220020B90400088823002080220020CF +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F079BC022000F066BC024B0022C1 +:100550005A6070478022002088230020F8B5504B55 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0B4FB0220FFF7CBFF454B0021D3F85E +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F00BFCB14A8F +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB102F047F80023AB4A4FF4BE +:1006F0007A71A94802F036F8002383F31188009B31 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F087FB24B19C4B1B6844 +:10073000002B00F02682002000F092FA0390039B29 +:10074000002BF2DB012000F067FB039B213B1F2BFA +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F04FFA91E785 +:100800004FF47A7000F02CFA071EEBDB0220FFF7A2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F034FA17E004215548F9E704215A483A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F055FA0421059005A800F01EFADE +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F080FB26B10BF015 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F024FA0220FFF73BFE1FFA86F84046BC +:1008C00000F02CFA0446B0B1039940460136A1F17C +:1008D00040025142514100F031FA0028EDD1BA46B0 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0D4F916E725460120FFF719FE244B36 +:100900009B68AB4207D9284600F0FAF9013040F065 +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940008FF9B0F10008FFF64DAF18F003077FF400 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F074F90390039A002AFFF69E +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200208423002068220020B9040008DF +:1009A000882300208022002004220020082200202A +:1009B0000C22002084220020C820FFF769FD074692 +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F05AFA019AFF217F4800F07BFA4FEAA3 +:1009F000A803C8F387027C492846019300F07AFADD +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0ACF902 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F055FB8046E7E7384600F050F9D0 +:100A60000590F2E7CDF81480042105A800F016F9EE +:100A700002E70023642104A8049300F005F900288C +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F067F90590E6E70023642104A8B4 +:100AA000049300F0F1F800287FF49CAE0220FFF7D9 +:100AB000EFFC00283FF496AE049800F055F9EAE701 +:100AC0000220FFF7E5FC00283FF48CAE00F064F94B +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F05FF907460421049004A800F0E8 +:100AF000D5F83946B9E7322000F0B2F8071EFFF604 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0E4F80421059005A800F08B +:100B4000ADF8F1E74FF47A70FFF7A2FC00283FF40C +:100B500049AE00F011F9002844D00A9B01330BD0B4 +:100B600008220AA9002000F0C5F900283AD0202266 +:100B7000FF210AA800F0B6F9FFF792FC1C4801F02B +:100B800035FD13B0BDE8F08F002E3FF42BAE0BF017 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F072F8074600287FF41CAE0220FFF721 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F013FD059800F022FA46463C46B5 +:100BD00000F0D4F9A6E506464EE64FF0000901E61E +:100BE000BA467EE637467CE68422002000220020BA +:100BF000A08601002DE9F84F4FF47A7306460D46A2 +:100C0000002402FB03F7DFF85080DFF8509098F9DA +:100C100000305FFA84FA5A1C01D0A34212D159F86D +:100C200024002A4631460368D3F820B03B46D84713 +:100C3000854207D1074B012083F800A0BDE8F88F5B +:100C40000124E4E7002CFBD04FF4FA7001F0CEFC55 +:100C50000020F3E7D42300201022002014220020DB +:100C6000002307B5024601210DF107008DF807307A +:100C7000FFF7C0FF20B19DF8070003B05DF804FB4B +:100C80004FF0FF30F9E700000A46042108B5FFF7EE +:100C9000B1FF80F00100C0B2404208BD074B0A46D8 +:100CA00030B41978064B53F821400146236820469A +:100CB000DD69044BAC4630BC604700BFD423002044 +:100CC00014220020A086010070B50A4E00240A4DAF +:100CD00001F0AAFF308028683388834208D901F0E8 +:100CE0009FFF2B6804440133B4F5003F2B60F2D31F +:100CF00070BD00BFD62300209023002002F062B810 +:100D000000F1006000F500300068704700F10060FD +:100D1000920000F5003001F0E3BF0000054B1A68B7 +:100D2000054B1B889B1A834202D9104401F078BFFF +:100D30000020704790230020D623002038B50446B9 +:100D4000074D29B128682044BDE8384001F080BF34 +:100D50002868204401F06AFF0028F3D038BD00BFA6 +:100D6000902300200020704700F1FF5000F58F1005 +:100D7000D0F8000870470000064991F8243033B1DC +:100D800000230822086A81F82430FFF7BFBF012042 +:100D9000704700BF94230020014B1868704700BFC4 +:100DA0000010005C194B01380322084470B51D681F +:100DB000174BC5F30B042D0C1E88A6420BD15C68A3 +:100DC0000A46013C824213460FD214F9016F4EB11C +:100DD00002F8016BF6E7013A03F10803ECD1814216 +:100DE0000B4602D22C2203F8012B0424094A168850 +:100DF000AE4204D1984284BF967803F8016B013C5F +:100E000002F10402F3D1581A70BD00BF0010005C5B +:100E10001C2200200C470008022804D1054B4FF08B +:100E200000629A6170470128FCD1024B4FF40032F6 +:100E3000F7E700BF00040258022804D1044B4FF426 +:100E400000629A6170470128FCD1014B0222F8E749 +:100E500000040258022805D1064A536983F400634E +:100E6000536170470128FCD1024A536983F00203A1 +:100E7000F6E700BF0004025870B504464FF47A76D6 +:100E80004CB1412C254628BF412506FB05F0641BCB +:100E900001F0ACFBF4E770BD002310B5934203D022 +:100EA000CC5CC4540133F9E710BD0000013810B523 +:100EB00010F9013F3BB191F900409C4203D11AB1B6 +:100EC0000131013AF4E71AB191F90020981A10BDE6 +:100ED0001046FCE703460246D01A12F9011B00290E +:100EE000FAD1704702440346934202D003F8011B33 +:100EF000FAE770472DE9F8431F4D14460746884628 +:100F000095F8242052BBDFF870909CB395F82430FC +:100F10002BB92022FF2148462F62FFF7E3FF95F807 +:100F200024004146C0F1080205EB8000A24228BF20 +:100F30002246D6B29200FFF7AFFF95F82430A41BEB +:100F400017441E449044E4B2F6B2082E85F824609B +:100F5000DBD1FFF711FF0028D7D108E02B6A03EBA4 +:100F600082038342CFD0FFF707FF0028CBD10020B8 +:100F7000BDE8F8830120FBE794230020024B1A7898 +:100F8000024B1A70704700BFD423002010220020AB +:100F900038B51A4C1A4D204600F07CFE29462046F2 +:100FA00000F0A4FE2D684FF47A70D5F89020D2F8A6 +:100FB000043843F00203C2F80438FFF75DFF11491B +:100FC000284600F0A1FFD5F890200F4DD2F8043844 +:100FD000286823F002030D49A042C2F804384FF4F8 +:100FE000E1330B6001D000F0B3FD6868A04204D08B +:100FF0000649BDE8384000F0ABBD38BD382B0020B5 +:10100000004900080849000814220020BC230020E1 +:101010000C4B70B50C4D04461E780C4B55F8262031 +:101020009A420DD00A4B002118221846FFF75AFFAA +:101030000460014655F82600BDE8704000F088BD08 +:1010400070BD00BFD423002014220020382B0020C4 +:10105000BC230020F0B5A1B071B60023012000240C +:1010600080261A46194600F04BFA4FF4D067214A01 +:101070003D25136923BBD2F810310BBB036804F183 +:10108000006199600368C3F80CD003685E60036870 +:101090001F6001680B6843F001030B6001680B6877 +:1010A00023F01E030B6001680B68DB07FCD4037B95 +:1010B0008034416805FA03F3B4F5001F0B60D8D102 +:1010C00000F05EFAB4F5001F11D000240A4E0B4D5B +:1010D000012001F077FE3388A34205D92868204417 +:1010E000013401F0B5FDF6E7002001F06BFE61B6BA +:1010F00021B0F0BD00200052D62300209023002014 +:1011000030B50A44084D91420DD011F8013B5840CA +:10111000082340F30004013B2C4013F0FF0384EA52 +:101120005000F6D1EFE730BD2083B8ED08B5074B8E +:10113000074A196801F03D01996053680BB1906846 +:101140009847BDE8084001F0FFBE00BF0000024024 +:10115000D823002008B5084B1968890901F03D0122 +:101160008A019A60054AD3680BB110699847BDE8B7 +:10117000084001F0E9BE00BF00000240D823002073 +:1011800008B5084B1968090C01F03D010A049A6082 +:10119000054A53690BB190699847BDE8084001F0D2 +:1011A000D3BE00BF00000240D823002008B5084B82 +:1011B0001968890D01F03D018A059A60054AD369D5 +:1011C0000BB1106A9847BDE8084001F0BDBE00BFF2 +:1011D00000000240D823002008B5074B074A596891 +:1011E00001F03D01D960536A0BB1906A9847BDE8A0 +:1011F000084001F0A9BE00BF00000240D823002033 +:1012000008B5084B5968890901F03D018A01DA6087 +:10121000054AD36A0BB1106B9847BDE8084001F04E +:1012200093BE00BF00000240D823002008B5084B41 +:101230005968090C01F03D010A04DA60054A536B54 +:101240000BB1906B9847BDE8084001F07DBE00BF30 +:1012500000000240D823002008B5084B5968890DCA +:1012600001F03D018A05DA60054AD36B0BB1106CC1 +:101270009847BDE8084001F067BE00BF000002408B +:10128000D823002008B5074B074A196801F03D0133 +:101290009960536C0BB1906C9847BDE8084001F021 +:1012A00053BE00BF00040240D823002008B5084BFD +:1012B0001968890901F03D018A019A60054AD36CD9 +:1012C0000BB1106D9847BDE8084001F03DBE00BF6E +:1012D00000040240D823002008B5084B1968090C07 +:1012E00001F03D010A049A60054A536D0BB1906DFF +:1012F0009847BDE8084001F027BE00BF0004024047 +:10130000D823002008B5084B1968890D01F03D016C +:101310008A059A60054AD36D0BB1106E9847BDE8F7 +:10132000084001F011BE00BF00040240D823002095 +:1013300008B5074B074A596801F03D01D960536E63 +:101340000BB1906E9847BDE8084001F0FDBD00BFAD +:1013500000040240D823002008B5084B59688909C9 +:1013600001F03D018A01DA60054AD36E0BB1106FBE +:101370009847BDE8084001F0E7BD00BF0004024007 +:10138000D823002008B5084B5968090C01F03D012D +:101390000A04DA60054A536F0BB1906F9847BDE8B5 +:1013A000084001F0D1BD00BF00040240D823002056 +:1013B00008B5084B5968890D01F03D018A05DA60CE +:1013C000054AD36F13B1D2F880009847BDE80840B2 +:1013D00001F0BABD00040240D823002000230C49CC +:1013E00010B51A460B4C0B6054F82300026001EB59 +:1013F000430004334260402BF6D1074A4FF0FF33DD +:101400009360D360C2F80834C2F80C3410BD00BF3A +:10141000D82300201C470008000002400F28F8B520 +:1014200010D9102810D0112811D0122808D10F245B +:101430000720DFF8C8E00126DEF80050A04208D9F6 +:10144000002653E00446F4E70F240020F1E70724C8 +:10145000FBE706FA00F73D424AD1264C4FEA001C52 +:101460003D4304EB00160EEBC000CEF80050C0E97F +:101470000123FBB273B12048D0F8D83043F0010308 +:10148000C0F8D830D0F8003143F00103C0F8003183 +:10149000D0F8003117F47F4F0ED01748D0F8D8306D +:1014A00043F00203C0F8D830D0F8003143F0020313 +:1014B000C0F80031D0F8003154F80C00036823F074 +:1014C0001F030360056815F00105FBD104EB0C0355 +:1014D0003D2493F80CC05F6804FA0CF43C602124AE +:1014E0000560446112B1987B00F066F93046F8BDA2 +:1014F0000130A3E71C47000800440258D82300200D +:1015000010B5302484F31188FFF788FF002383F39C +:10151000118810BD10B50446807B00F063F90123EB +:101520001549627B03FA02F20B6823EA0203DAB27E +:101530000B6072B9114AD2F8D81021F00101C2F83B +:10154000D810D2F8001121F00101C2F80011D2F830 +:10155000002113F47F4F0ED1084BD3F8D82022F08E +:101560000202C3F8D820D3F8002122F00202C3F807 +:101570000021D3F8003110BDD823002000440258C8 +:1015800008B5302383F31188FFF7C4FF002383F3EA +:10159000118808BD026843681143016003B1184710 +:1015A00070470000024A136843F0C003136070479D +:1015B0000044004013B50E4C204600F0BDFA04F183 +:1015C000140000234FF400720A49009400F07AF9E5 +:1015D000094B4FF40072094904F13800009400F0FF +:1015E000F3F9074A074BC4E9172302B010BD00BF47 +:1015F0005C240020C8240020A5150008C82600206F +:101600000044004000E1F505037C30B5244C00297E +:1016100018BF0C46012B11D1224B98420ED1224B00 +:10162000D3F8E82042F40032C3F8E820D3F81021C0 +:1016300042F40032C3F81021D3F810312268036E4F +:10164000C16D03EB52038466B3FBF2F362681504C9 +:1016500042BF23F0070503F0070343EA4503CB60CD +:10166000A36843F040034B60E36843F001038B60E1 +:1016700042F4967343F001030B604FF0FF330B62AB +:10168000510505D512F0102205D0B2F1805F04D0CB +:1016900080F8643030BD7F23FAE73F23F8E700BFCE +:1016A0001C4800085C240020004402582DE9F04743 +:1016B000C66D05463768F469210734621AD014F004 +:1016C000080118BF4FF48071E20748BF41F02001C4 +:1016D000A3074FF0300348BF41F04001600748BF07 +:1016E00041F0800183F31188281DFFF753FF002389 +:1016F00083F31188E2050AD5302383F311884FF470 +:101700008061281DFFF746FF002383F311884FF007 +:1017100030094FF0000A14F0200838D13B0616D5E6 +:101720004FF0300905F1380A200610D589F31188E9 +:10173000504600F07DF9002836DA0821281DFFF711 +:1017400029FF27F080033360002383F31188790693 +:1017500014D5620612D5302383F31188D5E91323FB +:101760009A4208D12B6C33B127F040071021281D75 +:10177000FFF710FF3760002383F31188E30618D5C5 +:10178000AA6E1369ABB15069BDE8F047184789F3F9 +:101790001188736A284695F86410194000F0E6F93C +:1017A0008AF31188F469B6E7B06288F31188F469A6 +:1017B000BAE7BDE8F0870000090100F160430122AB +:1017C00003F56143C9B283F8001300F01F039A4088 +:1017D00043099B0003F1604303F56143C3F8802193 +:1017E0001A60704700F01F0301229A40430900F17C +:1017F00060409B0000F5614003F1604303F56143E5 +:10180000C3F88020C3F88021002380F8003370479C +:10181000F8B51546826804460B46AA4200D2856890 +:10182000A1692669761AB5420BD218462A46FFF7F7 +:1018300033FBA3692B44A3612846A3685B1BA36009 +:10184000F8BD0CD9AF1B18463246FFF725FB3A46C8 +:10185000E1683044FFF720FBE3683B44EBE71846C0 +:101860002A46FFF719FBE368E5E700008368934227 +:10187000F7B50446154600D28568D4E90460361AE7 +:10188000B5420BD22A46FFF707FB63692B4463611D +:101890002846A3685B1BA36003B0F0BD0DD9324698 +:1018A000AF1B0191FFF7F8FA01993A46E06831441D +:1018B000FFF7F2FAE3683B44E9E72A46FFF7ECFA60 +:1018C000E368E4E710B50A440024C361029B846026 +:1018D000C16002610362C0E90000C0E9051110BDEA +:1018E00008B5D0E90532934201D1826882B9826895 +:1018F000013282605A1C426119700021D0E9043221 +:101900009A4224BFC368436100F08CFE002008BDEA +:101910004FF0FF30FBE7000070B5302304460E4661 +:1019200083F31188A568A5B1A368A269013BA360F0 +:10193000531CA36115782269934224BFE368A36115 +:10194000E3690BB120469847002383F311882846AA +:1019500007E03146204600F055FE0028E2DA85F324 +:10196000118870BD2DE9F74F04460E46174698467C +:10197000D0F81C904FF0300A8AF311884FF0000B1A +:10198000154665B12A4631462046FFF741FF03461A +:1019900060B94146204600F035FE0028F1D0002312 +:1019A00083F31188781B03B0BDE8F08FB9F1000F05 +:1019B00003D001902046C847019B8BF31188ED1A94 +:1019C0001E448AF31188DCE7C160C361009B82601A +:1019D0000362C0E905111144C0E9000001617047CC +:1019E000F8B504460D461646302383F31188A768E0 +:1019F000A7B1A368013BA36063695A1C62611D70B3 +:101A0000D4E904329A4224BFE3686361E3690BB10D +:101A100020469847002080F3118807E03146204691 +:101A200000F0F0FD0028E2DA87F31188F8BD00002D +:101A3000D0E9052310B59A4201D182687AB982684B +:101A40000021013282605A1C82611C7803699A422B +:101A500024BFC368836100F0E5FD204610BD4FF050 +:101A6000FF30FBE72DE9F74F04460E461746984630 +:101A7000D0F81C904FF0300A8AF311884FF0000B19 +:101A8000154665B12A4631462046FFF7EFFE03466C +:101A900060B94146204600F0B5FD0028F1D0002392 +:101AA00083F31188781B03B0BDE8F08FB9F1000F04 +:101AB00003D001902046C847019B8BF31188ED1A93 +:101AC0001E448AF31188DCE7026843681143016011 +:101AD00003B11847704700001430FFF743BF000000 +:101AE0004FF0FF331430FFF73DBF00003830FFF7F1 +:101AF000B9BF00004FF0FF333830FFF7B3BF00002D +:101B00001430FFF709BF00004FF0FF311430FFF72A +:101B100003BF00003830FFF763BF00004FF0FF3213 +:101B20003830FFF75DBF0000012914BF6FF01300CC +:101B300000207047FFF73EBD044B03600023436065 +:101B4000C0E9023301230374704700BF3448000822 +:101B500010B53023044683F31188FFF755FD0223A7 +:101B60000020237480F3118810BD000038B5C369CC +:101B700004460D461BB904210844FFF7A5FF29467A +:101B800004F11400FFF7ACFE002806DA201D4FF424 +:101B90000061BDE83840FFF797BF38BD0268436871 +:101BA0001143016003B118477047000013B5406B43 +:101BB00000F58054D4F8A4381A681178042914D197 +:101BC000017C022911D11979012312898B4013421A +:101BD0000BD101A94C3002F0A7F8D4F8A448024672 +:101BE000019B2179206800F0DFF902B010BD0000F0 +:101BF000143002F029B800004FF0FF33143002F027 +:101C000023B800004C3002F0FBB800004FF0FF3367 +:101C10004C3002F0F5B80000143001F0F7BF0000BE +:101C20004FF0FF31143001F0F1BF00004C3002F0F2 +:101C3000C7B800004FF0FF324C3002F0C1B80000CE +:101C40000020704710B500F58054D4F8A4381A6805 +:101C50001178042917D1017C022914D15979012363 +:101C600052898B4013420ED1143001F089FF024695 +:101C700048B1D4F8A4484FF4407361792068BDE8B6 +:101C8000104000F07FB910BD406BFFF7DBBF0000D4 +:101C9000704700007FB5124B0125042604460360FF +:101CA0000023057400F1840243602946C0E9023331 +:101CB0000C4B0290143001934FF44073009601F0E6 +:101CC0003BFF094B04F69442294604F14C00029470 +:101CD000CDE900634FF4407302F002F804B070BD28 +:101CE0005C480008891C0008AD1B00080A68302306 +:101CF00083F311880B790B3342F823004B791333AC +:101D000042F823008B7913B10B3342F8230000F51E +:101D10008053C3F8A41802230374002080F31188B1 +:101D20007047000038B5037F044613B190F8543073 +:101D3000ABB90125201D0221FFF730FF04F114008B +:101D40006FF00101257700F079FC04F14C0084F874 +:101D500054506FF00101BDE8384000F06FBC38BD51 +:101D600010B5012104460430FFF718FF0023237744 +:101D700084F8543010BD000038B5044600251430F6 +:101D800001F0F2FE04F14C00257701F0C1FF201DA7 +:101D900084F854500121FFF701FF2046BDE8384088 +:101DA000FFF750BF90F8803003F06003202B06D17E +:101DB00090F881200023212A03D81F2A06D800206A +:101DC0007047222AFBD1C0E91D3303E0034A426772 +:101DD00007228267C3670120704700BF34220020BA +:101DE00037B500F58055D5F8A4381A68117804295C +:101DF0001AD1017C022917D11979012312898B404C +:101E0000134211D100F14C04204602F041F858B1C0 +:101E100001A9204601F088FFD5F8A4480246019B9D +:101E20002179206800F0C0F803B030BD01F10B0348 +:101E3000F0B550F8236085B004460D46FEB130235E +:101E400083F3118804EB8507301D0821FFF7A6FEF8 +:101E5000FB6806F14C005B691B681BB1019001F047 +:101E600071FF019803A901F05FFF024648B1039B8F +:101E70002946204600F098F8002383F3118805B026 +:101E8000F0BDFB685A691268002AF5D01B8A013B35 +:101E90001340F1D104F18002EAE70000133138B5B4 +:101EA00050F82140ECB1302383F3118804F58053BE +:101EB000D3F8A4281368527903EB8203DB689B698B +:101EC0005D6845B104216018FFF768FE294604F1FA +:101ED000140001F05FFE2046FFF7B4FE002383F3F9 +:101EE000118838BD7047000001F02CB90123402251 +:101EF000002110B5044600F8303BFEF7F3FF002345 +:101F0000C4E9013310BD000010B53023044683F34B +:101F100011882422416000210C30FEF7E3FF2046A7 +:101F200001F032F902230020237080F3118810BDE4 +:101F300070B500EB8103054650690E461446DA6021 +:101F400018B110220021FEF7CDFFA06918B11022B0 +:101F50000021FEF7C7FF31462846BDE8704001F07A +:101F600019BA000083682022002103F0011310B584 +:101F7000044683601030FEF7B5FF2046BDE81040F0 +:101F800001F094BAF0B4012500EB810447898D403B +:101F9000E4683D43A469458123600023A260636037 +:101FA000F0BC01F0B1BA0000F0B4012500EB8104EF +:101FB00007898D40E4683D436469058123600023FF +:101FC000A2606360F0BC01F027BB000070B5022383 +:101FD00000250446242203702946C0F888500C309E +:101FE00040F8045CFEF77EFF204684F8705001F054 +:101FF00065F963681B6823B129462046BDE8704037 +:10200000184770BD0378052B10B504460AD080F838 +:102010008C300523037043681B680BB1042198477B +:102020000023A36010BD00000178052906D190F8B7 +:102030008C20436802701B6803B11847704700008A +:1020400070B590F87030044613B1002380F87030FA +:1020500004F18002204601F04DFA63689B68B3B931 +:1020600094F8803013F0600535D00021204601F04F +:102070003FFD0021204601F02FFD63681B6813B16E +:10208000062120469847062384F8703070BD20460C +:1020900098470028E4D0B4F88630A26F9A4288BFEF +:1020A000A36794F98030A56F002B4FF0300380F2C6 +:1020B0000381002D00F0F280092284F8702083F360 +:1020C000118800212046D4E91D23FFF76DFF00236E +:1020D00083F31188DAE794F8812003F07F0343EA61 +:1020E000022340F20232934200F0C58021D8B3F5BA +:1020F000807F48D00DD8012B3FD0022B00F0938079 +:10210000002BB2D104F1880262670222A267E36762 +:10211000C1E7B3F5817F00F09B80B3F5407FA4D188 +:1021200094F88230012BA0D1B4F8883043F0020338 +:1021300032E0B3F5006F4DD017D8B3F5A06F31D0B2 +:10214000A3F5C063012B90D86368204694F88220E1 +:102150005E6894F88310B4F88430B047002884D0C7 +:10216000436863670368A3671AE0B3F5106F36D05E +:1021700040F6024293427FF478AF5C4B63670223E0 +:10218000A3670023C3E794F88230012B7FF46DAF7F +:10219000B4F8883023F00203A4F88830C4E91D5550 +:1021A000E56778E7B4F88030B3F5A06F0ED194F806 +:1021B0008230204684F88A3001F0DEF863681B68BC +:1021C00013B1012120469847032323700023C4E95B +:1021D0001D339CE704F18B0363670123C3E7237876 +:1021E000042B10D1302383F311882046FFF7BAFE69 +:1021F00085F311880321636884F88B5021701B6874 +:102200000BB12046984794F88230002BDED084F83A +:102210008B300423237063681B68002BD6D0022107 +:1022200020469847D2E794F8843020461D0603F0F4 +:102230000F010AD501F050F9012804D002287FF4DB +:1022400014AF2B4B9AE72B4B98E701F037F9F3E7E4 +:1022500094F88230002B7FF408AF94F8843013F0A8 +:102260000F01B3D01A06204602D501F059FCADE7A4 +:1022700001F04AFCAAE794F88230002B7FF4F5AE17 +:1022800094F8843013F00F01A0D01B06204602D52D +:1022900001F02EFC9AE701F01FFC97E7142284F866 +:1022A000702083F311882B462A4629462046FFF7E3 +:1022B00069FE85F31188E9E65DB1152284F8702086 +:1022C00083F3118800212046D4E91D23FFF75AFE2D +:1022D000FDE60B2284F8702083F311882B462A46F2 +:1022E00029462046FFF760FEE3E700BF8C48000860 +:1022F000844800088848000838B590F870300446D3 +:10230000002B3ED0063BDAB20F2A34D80F2B32D83E +:10231000DFE803F0373131082232313131313131E8 +:1023200031313737856FB0F886309D4214D2C3689B +:102330001B8AB5FBF3F203FB12556DB9302383F30F +:1023400011882B462A462946FFF72EFE85F3118871 +:102350000A2384F870300EE0142384F870303023A0 +:1023600083F31188002320461A461946FFF70AFE18 +:10237000002383F3118838BDC36F03B1984700234E +:10238000E7E70021204601F0B3FB0021204601F0E1 +:10239000A3FB63681B6813B10621204698470623F8 +:1023A000D7E7000010B590F870300446142B29D000 +:1023B00017D8062B05D001D81BB110BD093B022B45 +:1023C000FBD80021204601F093FB0021204601F0BC +:1023D00083FB63681B6813B10621204698470623D8 +:1023E00019E0152BE9D10B2380F87030302383F3EB +:1023F000118800231A461946FFF7D6FD002383F300 +:102400001188DAE7C3689B695B68002BD5D1C36F7D +:1024100003B19847002384F87030CEE70023826828 +:10242000037503691B6899689142FBD25A6803607F +:10243000426010605860704700238268037503692A +:102440001B6899689142FBD85A680360426010602B +:102450005860704708B50846302383F311880B7D18 +:10246000032B05D0042B0DD02BB983F3118808BDA5 +:102470008B6900221A604FF0FF338361FFF7CEFFB4 +:102480000023F2E7D1E9003213605A60F3E700005D +:10249000FFF7C4BF054BD968087518680268536018 +:1024A0001A600122D8600275FDF7ACBFC828002071 +:1024B0000C4B30B5DD684B1C87B004460FD02B4663 +:1024C000094A684600F04EF92046FFF7E3FF009BFB +:1024D00013B1684600F050F9A86907B030BDFFF7A6 +:1024E000D9FFF9E7C828002055240008044B1A68D2 +:1024F000DB6890689B68984294BF00200120704779 +:10250000C8280020084B10B51C68D86822685360A2 +:102510001A600122DC602275FFF78EFF014620461B +:10252000BDE81040FDF76EBFC828002038B5074C45 +:1025300001230025064907482370656001F0E6FC89 +:102540000223237085F3118838BD00BF302B002093 +:1025500094480008C828002000F044B9034A516894 +:1025600053685B1A9842FBD8704700BF001000E028 +:102570008B600223086108468B8270478368A3F151 +:10258000840243F8142C026943F8442C426943F84E +:10259000402C094A43F8242CC268A3F1200043F8D8 +:1025A000182C022203F80C2C002203F80B2C034AEF +:1025B00043F8102C704700BF1D040008C8280020F5 +:1025C00008B5FFF7DBFFBDE80840FFF761BF00007B +:1025D000024BDB6898610F20FFF75CBFC828002022 +:1025E000302383F31188FFF7F3BF000008B50146DD +:1025F000302383F311880820FFF75AFF002383F369 +:10260000118808BD064BDB6839B1426818605A6012 +:10261000136043600420FFF74BBF4FF0FF3070475B +:10262000C82800200368984206D01A6802605060EB +:1026300018469961FFF72CBF7047000038B5044673 +:102640000D462068844200D138BD036823605C6079 +:102650008561FFF71DFFF4E7036810B59C68A2428F +:102660000CD85C688A600B604C6021605960996886 +:102670008A1A9A604FF0FF33836010BD121B1B68EB +:10268000ECE700000A2938BF0A2170B504460D4660 +:102690000A26601901F032FC01F01AFC041BA54265 +:1026A00003D8751C04462E46F3E70A2E04D90120F0 +:1026B000BDE8704001F06ABC70BD0000F8B5144B75 +:1026C0000D460A2A4FF00A07D96103F11001826012 +:1026D00038BF0A22416019691446016048601861D8 +:1026E000A81801F0FBFB01F0F3FB431B0646A342D5 +:1026F00006D37C1C28192746354601F0FFFBF2E77C +:102700000A2F04D90120BDE8F84001F03FBCF8BD14 +:10271000C8280020F8B506460D4601F0D9FB0F4A3F +:10272000134653F8107F9F4206D12A460146304691 +:10273000BDE8F840FFF7C2BFD169BB68441A2C1945 +:1027400028BF2C46A34202D92946FFF79BFF224609 +:1027500031460348BDE8F840FFF77EBFC828002097 +:10276000D8280020C0E90323002310B45DF8044BEF +:102770004361FFF7CFBF000010B5194C23699842A1 +:102780000DD08168D0E9003213605A609A680A441B +:102790009A60002303604FF0FF33A36110BD02680D +:1027A000234643F8102F53600022026022699A42A8 +:1027B00003D1BDE8104001F09BBB936881680B44D6 +:1027C000936001F085FB2269E1699268441AA24294 +:1027D000E4D91144BDE81040091AFFF753BF00BF08 +:1027E000C82800202DE9F047DFF8BC8008F1100769 +:1027F0002C4ED8F8105001F06BFBD8F81C40AA689A +:10280000031B9A423ED814444FF00009D5E9003228 +:10281000C8F81C4013605A60C5F80090D8F8103012 +:10282000B34201D101F064FB89F31188D5E903318A +:1028300028469847302383F311886B69002BD8D042 +:1028400001F046FB6A69A0EB040982464A450DD2B5 +:10285000022001F09BFB0022D8F81030B34208D1CF +:1028600051462846BDE8F047FFF728BF121A224418 +:10287000F2E712EB09092946384638BF4A46FFF706 +:10288000EBFEB5E7D8F81030B34208D01444C8F8CE +:102890001C00211AA960BDE8F047FFF7F3BEBDE8B0 +:1028A000F08700BFD8280020C828002000207047EB +:1028B000FEE70000704700004FF0FF307047000057 +:1028C00002290CD0032904D00129074818BF002091 +:1028D0007047032A05D8054800EBC200704704483A +:1028E00070470020704700BF644900084422002060 +:1028F0001849000870B59AB005460846144601A963 +:1029000000F0C2F801A8FEF7E5FA431C0022C6B2A7 +:102910005B001046C5E9003423700323023404F839 +:10292000013C01ABD1B202348E4201D81AB070BD65 +:1029300013F8011B013204F8010C04F8021CF1E742 +:1029400008B5302383F311880348FFF749FA0023C1 +:1029500083F3118808BD00BF382B002090F8803029 +:1029600003F01F02012A07D190F881200B2A03D11E +:102970000023C0E91D3315E003F06003202B08D1CC +:10298000B0F884302BB990F88120212A03D81F2A6F +:1029900004D8FFF707BA222AEBD0FAE7034A4267C6 +:1029A00007228267C3670120704700BF3B220020D7 +:1029B00007B5052917D8DFE801F019160319192002 +:1029C000302383F31188104A01210190FFF7B0FAF8 +:1029D000019802210D4AFFF7ABFA0D48FFF7CCF939 +:1029E000002383F3118803B05DF804FB302383F3E5 +:1029F00011880748FFF796F9F2E7302383F311882F +:102A00000348FFF7ADF9EBE7B8480008DC480008D9 +:102A1000382B002038B50C4D0C4C2A460C4904F1DB +:102A20000800FFF767FF05F1CA0204F11000094929 +:102A3000FFF760FF05F5CA7204F118000649BDE80A +:102A40003840FFF757BF00BF104400204422002049 +:102A5000A0480008A4480008AE48000870B5044625 +:102A600008460D46FEF736FAC6B220460134037812 +:102A70000BB9184670BD32462946FEF717FA0028F2 +:102A8000F3D10120F6E700002DE9F04705460C469A +:102A9000FEF720FA2C49C6B22846FFF7DFFF08B13F +:102AA0000836F6B229492846FFF7D8FF08B1103694 +:102AB000F6B2632E0BD8DFF89080DFF89090244FA9 +:102AC000DFF898A02E7846B92670BDE8F087294631 +:102AD0002046BDE8F04701F0FBBD252E30D107228E +:102AE00041462846FEF7E2F980B91A4B224603F127 +:102AF0000C0153F8040B8B4242F8040BF9D11988EE +:102B000007359B780F3411809370DBE70822494624 +:102B10002846FEF7CBF998B9A21C0F4B1978023260 +:102B20000909C95D02F8041C13F8011B01F00F012B +:102B30005345C95D02F8031CF0D118340835C1E7CC +:102B4000013504F8016BBDE784490008AE48000870 +:102B50009C4900088C49000800E8F11F0CE8F11FAF +:102B6000BFF34F8F044B1A695107FCD1D3F81021E2 +:102B70005207F8D1704700BF0020005208B50D4B36 +:102B80001B78ABB9FFF7ECFF0B4BDA68D10704D524 +:102B90000A4A5A6002F188325A60D3F80C21D207EF +:102BA00006D5064AC3F8042102F18832C3F804218D +:102BB00008BD00BF6E46002000200052230167457B +:102BC00008B5114B1B78F3B9104B1A69510703D59F +:102BD000DA6842F04002DA60D3F81021520705D5D6 +:102BE000D3F80C2142F04002C3F80C21FFF7B8FFE4 +:102BF000064BDA6842F00102DA60D3F80C2142F0A9 +:102C00000102C3F80C2108BD6E46002000200052CE +:102C10000F289ABF00F58060400400207047000034 +:102C20004FF4003070470000102070470F2808B59F +:102C30000BD8FFF7EDFF00F500330268013204D135 +:102C400004308342F9D1012008BD0020FCE70000D8 +:102C50000F2838B505463FD8FFF782FF1F4CFFF716 +:102C60008DFF4FF0FF3307286361C4F814311DD87E +:102C70002361FFF775FF030243F02403E360E36879 +:102C800043F08003E36023695A07FCD42846FFF72A +:102C900067FFFFF7BDFF4FF4003100F0F5F828465D +:102CA000FFF78EFFBDE83840FFF7C0BFC4F8103112 +:102CB000FFF756FFA0F108031B0243F02403C4F8FA +:102CC0000C31D4F80C3143F08003C4F80C31D4F843 +:102CD00010315B07FBD4D9E7002038BD002000523B +:102CE0002DE9F84F05460C46104645EA0203DE067C +:102CF00002D00020BDE8F88F20F01F00DFF8BCB044 +:102D0000DFF8BCA0FFF73AFF04EB0008444503D10D +:102D10000120FFF755FFEDE720222946204601F06C +:102D2000C7FC10B920352034F0E72B4605F120020E +:102D30001F68791CDDD104339A42F9D105F178433B +:102D40001B481C4EB3F5801F1B4B38BF184603F1C0 +:102D5000F80332BFD946D1461E46FFF701FF076090 +:102D6000A5EB040C336804F11C0143F0020333604B +:102D7000231FD9F8007017F00507FAD153F8042F74 +:102D80008B424CF80320F4D1BFF34F8FFFF7E8FEDE +:102D90004FF0FF332022214603602846336823F09A +:102DA0000203336001F084FC0028BBD03846B0E752 +:102DB000142100520C200052142000521020005206 +:102DC0001021005210B5084C237828B11BB9FFF729 +:102DD000D5FE0123237010BD002BFCD02070BDE870 +:102DE0001040FFF7EDBE00BF6E4600200244074BC7 +:102DF000D2B210B5904200D110BD441C00B253F8BD +:102E0000200041F8040BE0B2F4E700BF5040005846 +:102E10000E4B30B51C6F240405D41C6F1C671C6F4F +:102E200044F400441C670A4C02442368D2B243F4C1 +:102E300080732360074B904200D130BD441C51F891 +:102E4000045B00B243F82050E0B2F4E700440258BB +:102E5000004802585040005807B5012201A900203F +:102E6000FFF7C4FF019803B05DF804FB13B50446F7 +:102E7000FFF7F2FFA04205D0012201A90020019432 +:102E8000FFF7C6FF02B010BD0144BFF34F8F064BE2 +:102E9000884204D3BFF34F8FBFF36F8F7047C3F8DF +:102EA0005C022030F4E700BF00ED00E0034B1A683D +:102EB0001AB9034AD2F8D0241A607047704600202D +:102EC0000040025808B5FFF7F1FF024B1868C0F345 +:102ED000806008BD70460020EFF309830549683320 +:102EE0004A6B22F001024A6383F30988002383F3CB +:102EF0001188704700EF00E0302080F3118862B63F +:102F00000D4B0E4AD96821F4E0610904090C0A430B +:102F10000B49DA60D3F8FC2042F08072C3F8FC2041 +:102F2000084AC2F8B01F116841F001011160202267 +:102F3000DA7783F82200704700ED00E00003FA051D +:102F400055CEACC5001000E0302310B583F31188D6 +:102F50000E4B5B6813F4006314D0F1EE103AEFF3FC +:102F600009844FF08073683CE361094BDB6B236697 +:102F700084F30988FFF7BAFA10B1064BA36110BDBC +:102F8000054BFBE783F31188F9E700BF00ED00E094 +:102F900000EF00E02F0400083204000870B5BFF312 +:102FA0004F8FBFF36F8F1A4A0021C2F85012BFF340 +:102FB0004F8FBFF36F8F536943F400335361BFF3F7 +:102FC0004F8FBFF36F8FC2F88410BFF34F8FD2F8CB +:102FD000803043F6E074C3F3C900C3F34E335B01A2 +:102FE00003EA0406014646EA81750139C2F86052D7 +:102FF000F9D2203B13F1200FF2D1BFF34F8F536969 +:1030000043F480335361BFF34F8FBFF36F8F70BDB5 +:1030100000ED00E0FEE70000214B2248224A70B597 +:10302000904237D3214BC11EDA1C121A22F0030240 +:103030008B4238BF00220021FDF754FF1C4A0023B9 +:10304000C2F88430BFF34F8FD2F8803043F6E0747B +:10305000C3F3C900C3F34E335B0103EA0406014620 +:1030600046EA81750139C2F86C52F9D2203B13F15E +:10307000200FF2D1BFF34F8FBFF36F8FBFF34F8F8E +:10308000BFF36F8F0023C2F85032BFF34F8FBFF3EF +:103090006F8F70BD53F8041B40F8041BC0E700BFDE +:1030A000944B000844480020444800204448002035 +:1030B00000ED00E0074BD3F8D81021EA0001C3F877 +:1030C000D810D3F8002122EA0002C3F80021D3F877 +:1030D000003170470044025870B5D0E92443002203 +:1030E0004FF0FF359E6804EB42135101D3F80009FD +:1030F000002805DAD3F8000940F08040C3F8000941 +:10310000D3F8000B002805DAD3F8000B40F080401C +:10311000C3F8000B013263189642C3F80859C3F88C +:10312000085BE0D24FF00113C4F81C3870BD0000FA +:10313000890141F02001016103699B06FCD4122042 +:10314000FFF70CBA10B50A4C2046FEF7CFFE094B2C +:10315000C4F89030084BC4F89430084C2046FEF771 +:10316000C5FE074BC4F89030064BC4F8943010BD30 +:103170007446002000000840D44900081047002091 +:1031800000000440E049000870B503780546012BB3 +:103190005CD1434BD0F89040984258D1414B0E211E +:1031A0006520D3F8D82042F00062C3F8D820D3F8C5 +:1031B000002142F00062C3F80021D3F80021D3F8C7 +:1031C000802042F00062C3F88020D3F8802022F0F3 +:1031D0000062C3F88020D3F88030FEF7EDFA324B5E +:1031E000E360324BC4F800380023D5F89060C4F88F +:1031F000003EC02323604FF40413A3633369002B04 +:10320000FCDA01230C203361FFF7A8F93369DB07EF +:10321000FCD41220FFF7A2F93369002BFCDA002658 +:103220002846A660FFF758FF6B68C4F81068DB6893 +:10323000C4F81468C4F81C6883BB1D4BA3614FF02D +:10324000FF336361A36843F00103A36070BD194BB2 +:103250009842C9D1134B4FF08060D3F8D82042F088 +:103260000072C3F8D820D3F8002142F00072C3F8EE +:103270000021D3F80021D3F8802042F00072C3F877 +:103280008020D3F8802022F00072C3F88020D3F889 +:103290008030FFF70FFF0E214D209EE7064BCDE754 +:1032A00074460020004402584014004003002002ED +:1032B000003C30C010470020083C30C0F8B5D0F8C2 +:1032C0009040054600214FF000662046FFF730FF92 +:1032D000D5F8941000234FF001128F684FF0FF30A3 +:1032E000C4F83438C4F81C2804EB431201339F425D +:1032F000C2F80069C2F8006BC2F80809C2F8080BEE +:10330000F2D20B68D5F89020C5F89830636210238C +:103310001361166916F01006FBD11220FFF71EF993 +:10332000D4F8003823F4FE63C4F80038A36943F4EA +:10333000402343F01003A3610923C4F81038C4F8F4 +:1033400014380B4BEB604FF0C043C4F8103B094BF3 +:10335000C4F8003BC4F81069C4F80039D5F89830B7 +:1033600003F1100243F48013C5F89820A362F8BD5E +:10337000B049000840800010D0F8902090F88A10E2 +:10338000D2F8003823F4FE6343EA0113C2F8003890 +:10339000704700002DE9F84300EB8103D0F890500E +:1033A0000C468046DA680FFA81F94801166806F083 +:1033B0000306731E022B05EB41134FF0000194BF6F +:1033C000B604384EC3F8101B4FF0010104F110038E +:1033D00098BF06F1805601FA03F3916998BF06F58C +:1033E000004600293AD0578A04F158013743490171 +:1033F0006F50D5F81C180B430021C5F81C382B184A +:103400000127C3F81019A7405369611E9BB3138AA3 +:10341000928B9B08012A88BF5343D8F898209818AC +:1034200042EA034301F140022146C8F898002846C9 +:1034300005EB82025360FFF77BFE08EB8900C3684F +:103440001B8A43EA845348341E4364012E51D5F845 +:103450001C381F43C5F81C78BDE8F88305EB4917F5 +:10346000D7F8001B21F40041C7F8001BD5F81C1841 +:1034700021EA0303C0E704F13F030B4A2846214633 +:1034800005EB83035A60FFF753FE05EB4910D0F8B4 +:10349000003923F40043C0F80039D5F81C3823EA7A +:1034A0000707D7E70080001000040002D0F894203E +:1034B0001268C0F89820FFF70FBE00005831D0F80E +:1034C000903049015B5813F4004004D013F4001FFE +:1034D0000CBF0220012070474831D0F890304901DC +:1034E0005B5813F4004004D013F4001F0CBF0220FB +:1034F0000120704700EB8101CB68196A0B681360EB +:103500004B6853607047000000EB810330B5DD6805 +:10351000AA691368D36019B9402B84BF4023136094 +:103520006B8A1468D0F890201C4402EB4110013CD7 +:1035300009B2B4FBF3F46343033323F0030343EA18 +:10354000C44343F0C043C0F8103B2B6803F00303AF +:10355000012B0ED1D2F8083802EB411013F4807F12 +:10356000D0F8003B14BF43F0805343F00053C0F841 +:10357000003B02EB4112D2F8003B43F00443C2F897 +:10358000003B30BD2DE9F041D0F8906005460C4677 +:1035900006EB4113D3F8087B3A07C3F8087B08D53C +:1035A000D6F814381B0704D500EB8103DB685B6891 +:1035B0009847FA071FD5D6F81438DB071BD505EB5B +:1035C0008403D968CCB98B69488A5A68B2FBF0F693 +:1035D00000FB16228AB91868DA6890420DD2121AD6 +:1035E000C3E90024302383F3118821462846FFF7DE +:1035F0008BFF84F31188BDE8F081012303FA04F204 +:103600006B8923EA02036B81CB68002BF3D0214640 +:103610002846BDE8F041184700EB81034A0170B528 +:10362000DD68D0F890306C692668E66056BB1A44B5 +:103630004FF40020C2F810092A6802F00302012AA0 +:103640000AB20ED1D3F8080803EB421410F4807FBD +:10365000D4F8000914BF40F0805040F00050C4F886 +:10366000000903EB4212D2F8000940F00440C2F80E +:1036700000090122D3F8340802FA01F10143C3F82A +:10368000341870BD19B9402E84BF402020602068D6 +:103690001A442E8A8419013CB4FBF6F440EAC44073 +:1036A00040F00050C6E700002DE9F843D0F89060E4 +:1036B00005460C464F0106EB4113D3F8088918F074 +:1036C000010FC3F808891CD0D6F81038DB0718D5CD +:1036D00000EB8103D3F80CC0DCF81430D3F800E021 +:1036E000DA68964530D2A2EB0E024FF000091A605C +:1036F000C3F80490302383F31188FFF78DFF89F31B +:10370000118818F0800F1DD0D6F834380126A64055 +:10371000334217D005EB84030134D5F89050D3F829 +:103720000CC0E4B22F44DCF8142005EB0434D2F8CA +:1037300000E05168714514D3D5F8343823EA060601 +:10374000C5F83468BDE8F883012303FA01F2038960 +:1037500023EA02030381DCF80830002BD1D098471C +:10376000CFE7AEEB0103BCF81000834228BF03464D +:10377000D7F8180980B2B3EB800FE3D89068A0F1B6 +:10378000040959F8048FC4F80080A0EB0908984494 +:10379000B8F1040FF5D818440B4490605360C8E7A3 +:1037A0002DE9F84FD0F8905004466E69AB691E4081 +:1037B00016F480586E6103D0BDE8F84FFEF706BCE2 +:1037C000002E12DAD5F8003E9B0705D0D5F8003E52 +:1037D00023F00303C5F8003ED5F80438204623F053 +:1037E0000103C5F80438FEF71FFC370505D5204650 +:1037F000FFF772FC2046FEF705FCB0040CD5D5F8A7 +:10380000083813F0060FEB6823F470530CBF43F431 +:10381000105343F4A053EB6031071BD56368DB689A +:103820001BB9AB6923F00803AB612378052B0CD1DE +:10383000D5F8003E9A0705D0D5F8003E23F00303E3 +:10384000C5F8003E2046FEF7EFFB6368DB680BB16E +:1038500020469847F30200F1BA80B70226D5D4F883 +:10386000909000274FF0010A09EB4712D2F8003B75 +:1038700003F44023B3F5802F11D1D2F8003B002B85 +:103880000DDA62890AFA07F322EA0303638104EB83 +:103890008703DB68DB6813B1394620469847013758 +:1038A000D4F89430FFB29B689F42DDD9F00619D559 +:1038B000D4F89000026AC2F30A1702F00F0302F470 +:1038C000F012B2F5802F00F0CA80B2F5402F09D176 +:1038D00004EB8303002200F58050DB681B6A9742EB +:1038E00040F0B0803003D5F8185835D5E90303D53A +:1038F00000212046FFF746FEAA0303D501212046FA +:10390000FFF740FE6B0303D502212046FFF73AFE86 +:103910002F0303D503212046FFF734FEE80203D529 +:1039200004212046FFF72EFEA90203D505212046DB +:10393000FFF728FE6A0203D506212046FFF722FE84 +:103940002B0203D507212046FFF71CFEEF0103D50C +:1039500008212046FFF716FE700340F1A780E90713 +:1039600003D500212046FFF79FFEAA0703D50121BA +:103970002046FFF799FE6B0703D502212046FFF78B +:1039800093FE2F0703D503212046FFF78DFEEE0699 +:1039900003D504212046FFF787FEA80603D505219D +:1039A0002046FFF781FE690603D506212046FFF772 +:1039B0007BFE2A0603D507212046FFF775FEEB059F +:1039C00074D520460821BDE8F84FFFF76DBED4F846 +:1039D00090904FF0000B4FF0010AD4F894305FFA4A +:1039E0008BF79B689F423FF638AF09EB4713D3F83C +:1039F000002902F44022B2F5802F20D1D3F800290B +:103A0000002A1CDAD3F8002942F09042C3F80029BA +:103A1000D3F80029002AFBDB3946D4F89000FFF7E1 +:103A200087FB22890AFA07F322EA0303238104EBC6 +:103A30008703DB689B6813B13946204698470BF132 +:103A4000010BCAE7910701D1D0F80080072A02F1E3 +:103A500001029CBF03F8018B4FEA18283FE704EBF3 +:103A6000830300F58050DA68D2F818C0DCF808202B +:103A7000DCE9001CA1EB0C0C00218F4208D1DB68B3 +:103A80009B699A683A449A605A683A445A6029E7AE +:103A900011F0030F01D1D0F800808C4501F1010134 +:103AA00084BF02F8018B4FEA1828E6E7BDE8F88FDB +:103AB00008B50348FFF774FEBDE80840FFF744BAB5 +:103AC0007446002008B50348FFF76AFEBDE80840C9 +:103AD000FFF73ABA10470020D0F8903003EB4111BD +:103AE000D1F8003B43F40013C1F8003B70470000DD +:103AF000D0F8903003EB4111D1F8003943F40013B2 +:103B0000C1F8003970470000D0F8903003EB411144 +:103B1000D1F8003B23F40013C1F8003B70470000CC +:103B2000D0F8903003EB4111D1F8003923F40013A1 +:103B3000C1F800397047000030B50433039C0172AE +:103B4000002104FB0325C160C0E90653049B036305 +:103B5000059BC0E90000C0E90422C0E90842C0E9B1 +:103B60000A11436330BD00000022416AC260C0E90F +:103B70000411C0E90A226FF00101FEF75FBD0000E9 +:103B8000D0E90432934201D1C2680AB9181D7047C6 +:103B900000207047036919600021C2680132C260C9 +:103BA000C269134482699342036124BF436A03617B +:103BB000FEF738BD38B504460D46E3683BB162698F +:103BC0000020131D1268A3621344E36207E0237A06 +:103BD00033B929462046FEF715FD0028EDDA38BD39 +:103BE0006FF00100FBE70000C368C269013BC360DE +:103BF0004369134482699342436124BF436A43612A +:103C000000238362036B03B11847704770B53023FC +:103C1000044683F31188866A3EB9FFF7CBFF054659 +:103C200018B186F31188284670BDA36AE26A13F8BA +:103C3000015B9342A36202D32046FFF7D5FF002326 +:103C400083F31188EFE700002DE9F84F04460E4694 +:103C5000174698464FF0300989F311880025AA4687 +:103C6000D4F828B0BBF1000F09D141462046FFF738 +:103C7000A1FF20B18BF311882846BDE8F88FD4E965 +:103C80000A12A7EB050B521A934528BF9346BBF1C6 +:103C9000400F1BD9334601F1400251F8040B914209 +:103CA00043F8040BF9D1A36A403640354033A36290 +:103CB000D4E90A239A4202D32046FFF795FF8AF3FC +:103CC0001188BD42D8D289F31188C9E730465A46D7 +:103CD000FDF7E2F8A36A5E445D445B44A362E7E754 +:103CE00010B5029C0433017203FB0421C460C0E9D7 +:103CF00006130023C0E90A33039B0363049BC0E956 +:103D00000000C0E90422C0E90842436310BD00007E +:103D1000026A6FF00101C260426AC0E90422002217 +:103D2000C0E90A22FEF78ABCD0E904239A4201D1F5 +:103D3000C26822B9184650F8043B0B607047002354 +:103D40001846FAE7C3680021C2690133C3604369BA +:103D5000134482699342436124BF436A4361FEF77F +:103D600061BC000038B504460D46E3683BB12369E9 +:103D700000201A1DA262E2691344E36207E0237A7D +:103D800033B929462046FEF73DFC0028EDDA38BD60 +:103D90006FF00100FBE7000003691960C268013A97 +:103DA000C260C269134482699342036124BF436ABB +:103DB000036100238362036B03B11847704700005F +:103DC00070B530230D460446114683F31188866A88 +:103DD0002EB9FFF7C7FF10B186F3118870BDA36A33 +:103DE0001D70A36AE26A01339342A36204D3E169BE +:103DF00020460439FFF7D0FF002080F31188EDE75B +:103E00002DE9F84F04460D46904699464FF0300A8A +:103E10008AF311880026B346A76A4FB9494620465F +:103E2000FFF7A0FF20B187F311883046BDE8F88F77 +:103E3000D4E90A073A1AA8EB0607974228BF1746A3 +:103E4000402F1BD905F1400355F8042B9D4240F843 +:103E5000042BF9D1A36A40364033A362D4E90A2384 +:103E60009A4204D3E16920460439FFF795FF8BF3AA +:103E700011884645D9D28AF31188CDE729463A46BA +:103E8000FDF70AF8A36A3D443E443B44A362E5E7DC +:103E9000D0E904239A4217D1C3689BB1836A8BB1DE +:103EA000043B9B1A0ED01360C368013BC360C36917 +:103EB0001A4483699A42026124BF436A0361002362 +:103EC00083620123184670470023FBE700F024B902 +:103ED000014B586A704700BF000C0040034B0022A2 +:103EE00058631A610222DA60704700BF000C00407C +:103EF000014B0022DA607047000C0040014B586310 +:103F0000704700BF000C0040FEE7000070B51B4B7F +:103F10000025044686B058600E4685620163FEF7B0 +:103F2000EBFF04F11003A560E562C4E904334FF030 +:103F3000FF33C4E90044C4E90635FFF7C9FF2B4647 +:103F4000024604F134012046C4E9082380230C4AC8 +:103F50002565FEF70DFB01230A4AE0600092037518 +:103F6000684672680192B268CDE90223064BCDE93A +:103F70000435FEF725FB06B070BD00BF302B0020D6 +:103F8000EC490008F1490008093F0008024AD36AD9 +:103F90001843D062704700BFC82800204B684360B8 +:103FA0008B688360CB68C3600B6943614B690362B4 +:103FB0008B6943620B6803607047000008B53C4B97 +:103FC00040F2FF713B48D3F888200A43C3F88820A9 +:103FD000D3F8882022F4FF6222F00702C3F8882079 +:103FE000D3F88820D3F8E0200A43C3F8E020D3F8C0 +:103FF00008210A43C3F808212F4AD3F80831114693 +:10400000FFF7CCFF00F5806002F11C01FFF7C6FF4F +:1040100000F5806002F13801FFF7C0FF00F5806015 +:1040200002F15401FFF7BAFF00F5806002F1700160 +:10403000FFF7B4FF00F5806002F18C01FFF7AEFFDF +:1040400000F5806002F1A801FFF7A8FF00F580608D +:1040500002F1C401FFF7A2FF00F5806002F1E00168 +:10406000FFF79CFF00F5806002F1FC01FFF796FF6F +:1040700002F58C7100F58060FFF790FF00F018F9F1 +:104080000E4BD3F8902242F00102C3F89022D3F8ED +:10409000942242F00102C3F894220522C3F898202A +:1040A0004FF06052C3F89C20054AC3F8A02008BD19 +:1040B0000044025800000258F849000800ED00E0F2 +:1040C0001F00080308B500F0D3FAFEF72FFA0F4BD4 +:1040D000D3F8DC2042F04002C3F8DC20D3F80421FE +:1040E00022F04002C3F80421D3F80431084B1A68C7 +:1040F00042F008021A601A6842F004021A60FEF7E1 +:10410000D5FEBDE80840FEF785BC00BF004402585C +:104110000018024870470000114BD3F8E82042F025 +:104120000802C3F8E820D3F8102142F00802C3F8CF +:1041300010210C4AD3F81031D36B43F00803D3633A +:10414000C722094B9A624FF0FF32DA6200229A616D +:104150005A63DA605A6001225A611A60704700BFE0 +:10416000004402580010005C000C0040094A08B5E9 +:104170001169D3680B40D9B29B076FEA0101116145 +:1041800007D5302383F31188FEF7E6F9002383F384 +:10419000118808BD000C0040064BD3F8DC20024318 +:1041A000C3F8DC20D3F804211043C3F80401D3F88A +:1041B000043170470044025808B53C4B4FF0FF31C2 +:1041C000D3F8802062F00042C3F88020D3F880202A +:1041D00002F00042C3F88020D3F88020D3F8842076 +:1041E000C3F88410D3F884200022C3F88420D3F8C5 +:1041F0008400D86F40F0FF4040F4FF0040F4DF40FF +:1042000040F07F00D867D86F20F0FF4020F4FF0017 +:1042100020F4DF4020F07F00D867D86FD3F8880003 +:104220006FEA40506FEA5050C3F88800D3F8880016 +:10423000C0F30A00C3F88800D3F88800D3F89000D0 +:10424000C3F89010D3F89000C3F89020D3F89000F2 +:10425000D3F89400C3F89410D3F89400C3F89420D2 +:10426000D3F89400D3F89800C3F89810D3F89800C6 +:10427000C3F89820D3F89800D3F88C00C3F88C10BA +:10428000D3F88C00C3F88C20D3F88C00D3F89C00B2 +:10429000C3F89C10D3F89C10C3F89C20D3F89C3032 +:1042A000FDF79CF8BDE8084000F0B6B9004402589C +:1042B00008B50121534BC3F80811534BD3F8F42030 +:1042C00042F00202C3F8F420D3F81C2142F00202AB +:1042D000C3F81C21D3F81C314C4BD9605A689104A7 +:1042E000FCD54B4A1A6001229A6002F18072DA60B2 +:1042F00000221A614FF440429A61444B9A69920439 +:10430000FCD51A6842F480721A603F4B1A6F12F49F +:10431000407F04D04FF480321A6700221A671A686F +:1043200042F001021A60384B1A685007FCD500228F +:104330001A611A6912F03802FBD1012119604FF09D +:10434000804159605A67334ADA62334A1A611A68FF +:1043500042F4A0221A602C4B1A689103FCD51A680B +:1043600042F480521A601A689204FCD52B4A2C49F8 +:104370009A6200225A63196301F57C01DA6301F540 +:10438000E77199635A64274A1A64274ADA621A68FD +:1043900042F0A8521A601C4B1A6802F02852B2F17F +:1043A000285FF9D148229A614FF48862DA6140228D +:1043B0001A621E4ADA641E4A1A651E4A5A651E4A65 +:1043C0009A6532231D4A1360136803F00F03022B12 +:1043D000FAD10D4A136943F003031361136903F023 +:1043E0003803182BFAD14FF00050FFF7D5FE4FF0ED +:1043F0008040FFF7D1FE4FF00040BDE80840FFF7D6 +:10440000CBBE00BF00800051004402580048025853 +:1044100000C000F00000FF0100889008322060001A +:1044200063020901470E0508DD0BBF0120000020D3 +:10443000000001100910E0000001011000200052EE +:104440004FF0B04208B5D2F8883003F00103C2F84B +:10445000883023B1044A13680BB150689847BDE80F +:104460000840FEF771BD00BFC44700204FF0B042C6 +:1044700008B5D2F8883003F00203C2F8883023B1BF +:10448000044A93680BB1D0689847BDE80840FEF72E +:104490005BBD00BFC44700204FF0B04208B5D2F862 +:1044A000883003F00403C2F8883023B1044A13694A +:1044B0000BB150699847BDE80840FEF745BD00BF05 +:1044C000C44700204FF0B04208B5D2F8883003F05E +:1044D0000803C2F8883023B1044A93690BB1D0694C +:1044E0009847BDE80840FEF72FBD00BFC447002035 +:1044F0004FF0B04208B5D2F8883003F01003C2F88C +:10450000883023B1044A136A0BB1506A9847BDE85A +:104510000840FEF719BD00BFC44700204FF0B0436C +:1045200010B5D3F8884004F47872C3F88820A30645 +:1045300004D5124A936A0BB1D06A9847600604D535 +:104540000E4A136B0BB1506B9847210604D50B4AEA +:10455000936B0BB1D06B9847E20504D5074A136CF7 +:104560000BB1506C9847A30504D5044A936C0BB16A +:10457000D06C9847BDE81040FEF7E6BCC447002069 +:104580004FF0B04310B5D3F8884004F47C42C3F830 +:104590008820620504D5164A136D0BB1506D9847FB +:1045A000230504D5124A936D0BB1D06D9847E004F2 +:1045B00004D50F4A136E0BB1506E9847A10404D571 +:1045C0000B4A936E0BB1D06E9847620404D5084A2B +:1045D000136F0BB1506F9847230404D5044A936FAF +:1045E0000BB1D06F9847BDE81040FEF7ADBC00BFDF +:1045F000C447002008B50348FDF758F8BDE8084057 +:10460000FEF7A2BC5C24002008B5FFF7AFFDBDE8B3 +:104610000840FEF799BC0000062108B50846FDF7E2 +:10462000CBF806210720FDF7C7F806210820FDF783 +:10463000C3F806210920FDF7BFF806210A20FDF77F +:10464000BBF806211720FDF7B7F806212820FDF753 +:10465000B3F809217A20FDF7AFF807213220FDF7E2 +:10466000ABF80C212620BDE80840FDF7A5B80000F6 +:1046700008B5FFF7A1FD00F00DF8FDF75BFAFDF7B7 +:1046800033FCFDF705FBFFF745FDBDE80840FFF7EC +:104690001DBC00000023054A19460133102BC2E956 +:1046A000001102F10802F8D1704700BFC447002092 +:1046B00010B501390244904201D1002005E0037891 +:1046C00011F8014FA34201D0181B10BD0130F2E7D1 +:1046D000034611F8012B03F8012B002AF9D170478A +:1046E00053544D333248373F3F3F0053544D3332DC +:1046F000483733782F3732780053544D33324837A8 +:1047000034332F3735332F373530000001105A003E +:1047100003105900012058000320560010000240E9 +:10472000080002400008024000000B002800024080 +:10473000080002400408024006010C00400002404C +:10474000080002400808024010020D005800024014 +:10475000080002400C08024016030E0070000240E0 +:104760000C0002401008024000040F0088000240C4 +:104770000C0002401408024006051000A000024090 +:104780000C0002401808024010061100B800024058 +:104790000C0002401C08024016072F0010040240C3 +:1047A00008040240200802400008380028040240A3 +:1047B000080402402408024006093900400402406F +:1047C0000804024028080240100A3A005804024037 +:1047D000080402402C080240160B3B007004024003 +:1047E0000C04024030080240000C3C0088040240E7 +:1047F0000C04024034080240060D4400A0040240AC +:104800000C04024038080240100E4500B804024073 +:104810000C0402403C080240160F460000960000BF +:104820000000000000000000000000000000000088 +:104830000000000000000000F51A0008E11A00085E +:104840001D1B0008091B0008151B0008011B0008A0 +:10485000ED1A0008D91A0008291B00080000000002 +:104860000D1C0008F91B0008351C0008211C00085D +:104870002D1C0008191C0008051C0008F11B00086D +:10488000411C0008000000000100000000000000C2 +:10489000633000009048000820290020302B0020C1 +:1048A00033445200435A4F454D72657647002553B5 +:1048B000455249414C250000020000000000000064 +:1048C0002D1E00089D1E000840004000E04300200F +:1048D000F043002002000000000000000300000080 +:1048E00000000000E51E00080000000010000000AD +:1048F0000044002000000000010000000000000053 +:104900007446002001010200B1290008C1280008F6 +:104910005D290008412900084300000020490008E3 +:1049200009024300020100C0320904000001020232 +:1049300001000524001001052401000104240202E5 +:104940000524060001070582030800FF0904010091 +:10495000020A00000007050102400000070581026D +:1049600040000000120000006C4900081201100114 +:1049700002000040AC2624110002010203010000E5 +:104980000403090425424F41524425003344524355 +:104990006F6E74726F6C5A65726F470030313233CC +:1049A000343536373839414243444546000000002B +:1049B0000000000041200008F9220008A52300089B +:1049C00040004000AC470020AC4700200100000040 +:1049D000BC470020800000004001000008000000EB +:1049E0000001000000100000080000006D61696E09 +:1049F0000069646C650000000000802A000000006F +:104A0000AAAAAAAA00000024FFFF000000000000DC +:104A100000A00A004400400000000000AAAAAAAAC0 +:104A200000000000FFFF0000000000000000000088 +:104A30001000000000000000AAAAAAAA10000000AE +:104A4000FFFF00000000000000000000806910006F +:104A500000000000AAAA8AAA40561000FFFF00002A +:104A6000007070070000000000000040000000001F +:104A7000AAAAAAAA00000040FFFF00000000000050 +:104A8000000000000010100000000000AAAAAAAA5E +:104A900000101000FFFF00000000000000000000F8 +:104AA0000000040000000000AAAAAAAA0000040056 +:104AB000FFFF0000000000000000000000000000F8 +:104AC00000000000AAAAAAAA00000000FFFF000040 +:104AD00000000000000000000000000000000000D6 +:104AE000AAAAAAAA00000000FFFF00000000000020 +:104AF000000000000000000000000000AAAAAAAA0E +:104B000000000000FFFF00000000000000000000A7 +:104B10000000000000000000AAAAAAAA00000000ED +:104B2000FFFF000000000000000000000000000087 +:104B3000640400000000000000001E0000000000EF +:104B4000FF000000382B00205C2400200000000043 +:104B5000E046000883040000EB4600085004000013 +:104B6000F9460008009600000000080096000000CA +:104B70000008000004000000804900080000000058 +:104B80000000000000000000000000000000000025 +:044B90000000000021 +:00000001FF diff --git a/Tools/bootloaders/AET-H743-Basic_bl.bin b/Tools/bootloaders/AET-H743-Basic_bl.bin new file mode 100644 index 00000000000000..8afdc716014802 Binary files /dev/null and b/Tools/bootloaders/AET-H743-Basic_bl.bin differ diff --git a/Tools/bootloaders/AET-H743-Basic_bl.hex b/Tools/bootloaders/AET-H743-Basic_bl.hex new file mode 100644 index 00000000000000..e06821cdab430f --- /dev/null +++ b/Tools/bootloaders/AET-H743-Basic_bl.hex @@ -0,0 +1,1276 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200089D30000834 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008FD4700082948000801 +:100060005548000881480008AD48000831110008D3 +:100070005911000885110008B1110008DD110008B0 +:100080000512000831120008E3020008E30200082C +:10009000E3020008E3020008E3020008D948000870 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E0003D490008E3020008E3020008E3020008BB +:1000F000E3020008E3020008E30200085D120008C2 +:10010000E3020008E3020008C5490008E302000812 +:10011000E3020008E3020008E3020008E30200082B +:1001200089120008B1120008DD1200080913000846 +:1001300035130008E3020008E3020008E3020008A8 +:10014000E3020008E3020008E3020008E3020008FB +:100150005D13000889130008B5130008E3020008C6 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008893C0008E3020008E3020008EB +:10018000E3020008E3020008B1490008E3020008A6 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008753C0008E3020008E30200089F +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F008FF67 +:1003500004F00EF84FF055301F491B4A91423CBF44 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F020FF04F06CF8D0 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F008BF00060020002200205D +:1003D0000000000808ED00E00000002000060020FA +:1003E000384F0008002200206422002068220020EC +:1003F0000C490020E0020008E0020008E0020008CA +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002002F000F9FEE702F0FC +:100430008BF800DFFEE7000038B500F045FC00F067 +:1004400001FE02F0EBFD054602F01EFE0446C0B9B7 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0E2FD0CB100F05A +:1004700075F800F085FD284600F01EF900F06EF8D2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0E5FBA0F120035842584108BD23 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000F5FB03B05DF804FB38B5302383F31188F6 +:1004C000174803680BB102F07DF90023154A4FF479 +:1004D0007A71134802F06CF9002383F31188124CEF +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0A8FC322363602B78032B07D16368CB +:100510002BB9022000F09EFC4FF47A73636038BD63 +:1005200068220020B90400088823002080220020CF +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F07FBC022000F072BC024B0022AF +:100550005A6070478022002088230020F8B5504B55 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0C0FB0220FFF7CBFF454B0021D3F852 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F003FCB14A97 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB102F06DF80023AB4A4FF498 +:1006F0007A71A94802F05CF8002383F31188009B0B +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F08DFB24B19C4B1B683E +:10073000002B00F02682002000F092FA0390039B29 +:10074000002BF2DB012000F073FB039B213B1F2BEE +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F04FFA91E785 +:100800004FF47A7000F02CFA071EEBDB0220FFF7A2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F034FA17E004215548F9E704215A483A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F061FA0421059005A800F01EFAD2 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F078FB26B10BF01D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F030FA0220FFF73BFE1FFA86F84046B0 +:1008C00000F038FA0446B0B1039940460136A1F170 +:1008D00040025142514100F03DFA0028EDD1BA46A4 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0D4F916E725460120FFF719FE244B36 +:100900009B68AB4207D9284600F006FA013040F058 +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940008FF9B0F10008FFF64DAF18F003077FF400 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F074F90390039A002AFFF69E +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200208423002068220020B9040008DF +:1009A000882300208022002004220020082200202A +:1009B0000C22002084220020C820FFF769FD074692 +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F052FA019AFF217F4800F073FA4FEAB3 +:1009F000A803C8F387027C492846019300F072FAE5 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0B8F9F6 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F057FB8046E7E7384600F05CF9C2 +:100A60000590F2E7CDF81480042105A800F016F9EE +:100A700002E70023642104A8049300F005F900288C +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F073F90590E6E70023642104A8A8 +:100AA000049300F0F1F800287FF49CAE0220FFF7D9 +:100AB000EFFC00283FF496AE049800F061F9EAE7F5 +:100AC0000220FFF7E5FC00283FF48CAE00F070F93F +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F06BF907460421049004A800F0DC +:100AF000D5F83946B9E7322000F0B2F8071EFFF604 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0F0F80421059005A800F07F +:100B4000ADF8F1E74FF47A70FFF7A2FC00283FF40C +:100B500049AE00F01DF9002844D00A9B01330BD0A8 +:100B600008220AA9002000F0BDF900283AD020226E +:100B7000FF210AA800F0AEF9FFF792FC1C4801F033 +:100B80005BFD13B0BDE8F08F002E3FF42BAE0BF0F1 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F072F8074600287FF41CAE0220FFF721 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F039FD059800F01AFA46463C4697 +:100BD00000F0CCF9A6E506464EE64FF0000901E626 +:100BE000BA467EE637467CE68422002000220020BA +:100BF000A08601002DE9F84F4FF47A7306460D46A2 +:100C0000002402FB03F7DFF85080DFF8509098F9DA +:100C100000305FFA84FA5A1C01D0A34212D159F86D +:100C200024002A4631460368D3F820B03B46D84713 +:100C3000854207D1074B012083F800A0BDE8F88F5B +:100C40000124E4E7002CFBD04FF4FA7001F0F4FC2F +:100C50000020F3E7D42300201022002014220020DB +:100C6000002307B5024601210DF107008DF807307A +:100C7000FFF7C0FF20B19DF8070003B05DF804FB4B +:100C80004FF0FF30F9E700000A46042108B5FFF7EE +:100C9000B1FF80F00100C0B2404208BD074B0A46D8 +:100CA00030B41978064B53F821400146236820469A +:100CB000DD69044BAC4630BC604700BFD423002044 +:100CC00014220020A086010070B5104C0025104EA3 +:100CD00001F0CEFF20803068238883420CD80025A5 +:100CE0002088013801F0C0FF23880544013BB5F599 +:100CF000802F2380F4D370BD01F0B6FF3368054424 +:100D00000133B5F5003F3360E5D3E8E7D623002093 +:100D10009023002002F07AB800F1006000F5003066 +:100D20000068704700F10060920000F5003001F0AB +:100D3000FBBF0000054B1A68054B1B889B1A8342BA +:100D400002D9104401F090BF00207047902300208A +:100D5000D623002038B50446074D29B12868204421 +:100D6000BDE8384001F098BF2868204401F082FFB8 +:100D70000028F3D038BD00BF90230020002070472A +:100D800000F1FF5000F58F10D0F800087047000008 +:100D9000064991F8243033B100230822086A81F80B +:100DA0002430FFF7BFBF0120704700BF942300200D +:100DB000014B1868704700BF0010005C194B0138E8 +:100DC0000322084470B51D68174BC5F30B042D0CA6 +:100DD0001E88A6420BD15C680A46013C824213463B +:100DE0000FD214F9016F4EB102F8016BF6E7013A28 +:100DF00003F10803ECD181420B4602D22C2203F806 +:100E0000012B0424094A1688AE4204D1984284BFBB +:100E1000967803F8016B013C02F10402F3D1581AF1 +:100E200070BD00BF0010005C1C220020C84A0008F2 +:100E3000022803D1024B4FF400229A61704700BF91 +:100E400000100258022802D1014B08229A61704713 +:100E500000100258022804D1024A536983F00803A3 +:100E6000536170470010025870B504464FF47A760B +:100E70004CB1412C254628BF412506FB05F0641BDB +:100E800001F0DAFBF4E770BD002310B5934203D004 +:100E9000CC5CC4540133F9E710BD0000013810B533 +:100EA00010F9013F3BB191F900409C4203D11AB1C6 +:100EB0000131013AF4E71AB191F90020981A10BDF6 +:100EC0001046FCE703460246D01A12F9011B00291E +:100ED000FAD1704702440346934202D003F8011B43 +:100EE000FAE770472DE9F8431F4D14460746884638 +:100EF00095F8242052BBDFF870909CB395F824300D +:100F00002BB92022FF2148462F62FFF7E3FF95F817 +:100F100024004146C0F1080205EB8000A24228BF30 +:100F20002246D6B29200FFF7AFFF95F82430A41BFB +:100F300017441E449044E4B2F6B2082E85F82460AB +:100F4000DBD1FFF725FF0028D7D108E02B6A03EBA0 +:100F500082038342CFD0FFF71BFF0028CBD10020B4 +:100F6000BDE8F8830120FBE794230020024B1A78A8 +:100F7000024B1A70704700BFD423002010220020BB +:100F800038B51A4C1A4D204600F086FE29462046F8 +:100F900000F0AEFE2D684FF47A70D5F89020D2F8AC +:100FA000043843F00203C2F80438FFF75DFF11492B +:100FB000284600F0ABFFD5F890200F4DD2F804384A +:100FC000286823F002030D49A042C2F804384FF408 +:100FD000E1330B6001D000F0BDFD6868A04204D091 +:100FE0000649BDE8384000F0B5BD38BD382B0020BB +:100FF000C44C0008CC4C000814220020BC23002064 +:101000000C4B70B50C4D04461E780C4B55F8262041 +:101010009A420DD00A4B002118221846FFF75AFFBA +:101020000460014655F82600BDE8704000F092BD0E +:1010300070BD00BFD423002014220020382B0020D4 +:10104000BC230020F8B571B6002301201A461946CA +:1010500000F058FA0446802001F076FF002849D0BD +:101060000025254A80274FF4D06C3D26136913F0E4 +:10107000C06F26D1D2F8103113F0C06F21D1236890 +:1010800005F1006199602368D86023685F60236878 +:10109000C3F800C021680B6843F001030B602168AE +:1010A0000B6823F01E030B6021680B68DB07FCD480 +:1010B000237B8035616806FA03F3B5F5001F0B60EA +:1010C000D4D1204600F05EFAB5F5001F11D00024FF +:1010D0000A4E0B4D012001F099FE3388A34205D939 +:1010E00028682044013401F0D7FDF6E7002001F024 +:1010F0008DFE61B6F8BD00BF00200052D62300204F +:101100009023002030B50A44084D91420DD011F8CB +:10111000013B5840082340F30004013B2C4013F0EE +:10112000FF0384EA5000F6D1EFE730BD2083B8ED2D +:1011300008B5074B074A196801F03D0199605368EB +:101140000BB190689847BDE8084001F0DFBF00BFD1 +:1011500000000240D823002008B5084B196889090F +:1011600001F03D018A019A60054AD3680BB110690C +:101170009847BDE8084001F0C9BF00BF0000024029 +:10118000D823002008B5084B1968090C01F03D016F +:101190000A049A60054A53690BB190699847BDE803 +:1011A000084001F0B3BF00BF00000240D823002078 +:1011B00008B5084B1968890D01F03D018A059A6050 +:1011C000054AD3690BB1106A9847BDE8084001F0A1 +:1011D0009DBF00BF00000240D823002008B5074B88 +:1011E000074A596801F03D01D960536A0BB1906A12 +:1011F0009847BDE8084001F089BF00BF00000240E9 +:10120000D823002008B5084B5968890901F03D0131 +:101210008A01DA60054AD36A0BB1106B9847BDE8C2 +:10122000084001F073BF00BF00000240D823002037 +:1012300008B5084B5968090C01F03D010A04DA6051 +:10124000054A536B0BB1906B9847BDE8084001F01D +:101250005DBF00BF00000240D823002008B5084B46 +:101260005968890D01F03D018A05DA60054AD36BA2 +:101270000BB1106C9847BDE8084001F047BF00BFB4 +:1012800000000240D823002008B5074B074A196820 +:1012900001F03D019960536C0BB1906C9847BDE82B +:1012A000084001F033BF00BF00040240D8230020F3 +:1012B00008B5084B1968890901F03D018A019A6057 +:1012C000054AD36C0BB1106D9847BDE8084001F09A +:1012D0001DBF00BF00040240D823002008B5084B02 +:1012E0001968090C01F03D010A049A60054A536D22 +:1012F0000BB1906D9847BDE8084001F007BF00BFF3 +:1013000000040240D823002008B5084B1968890D55 +:1013100001F03D018A059A60054AD36D0BB1106E4C +:101320009847BDE8084001F0F1BE00BF000402404C +:10133000D823002008B5074B074A596801F03D0142 +:10134000D960536E0BB1906E9847BDE8084001F02C +:10135000DDBE00BF00040240D823002008B5084BC2 +:101360005968890901F03D018A01DA60054AD36EA6 +:101370000BB1106F9847BDE8084001F0C7BE00BF31 +:1013800000040240D823002008B5084B5968090C16 +:1013900001F03D010A04DA60054A536F0BB1906F0A +:1013A0009847BDE8084001F0B1BE00BF000402400C +:1013B000D823002008B5084B5968890D01F03D017C +:1013C0008A05DA60054AD36F13B1D2F880009847D6 +:1013D000BDE8084001F09ABE00040240D823002076 +:1013E00000230C4910B51A460B4C0B6054F823002F +:1013F000026001EB430004334260402BF6D1074A00 +:101400004FF0FF339360D360C2F80834C2F80C3455 +:1014100010BD00BFD8230020D84A000800000240B9 +:101420000F28F8B510D9102810D0112811D0122883 +:1014300008D10F240720DFF8C8E00126DEF80050AD +:10144000A04208D9002653E00446F4E70F24002008 +:10145000F1E70724FBE706FA00F73D424AD1264CA4 +:101460004FEA001C3D4304EB00160EEBC000CEF823 +:101470000050C0E90123FBB273B12048D0F8D83046 +:1014800043F00103C0F8D830D0F8003143F0010335 +:10149000C0F80031D0F8003117F47F4F0ED0174854 +:1014A000D0F8D83043F00203C0F8D830D0F800317B +:1014B00043F00203C0F80031D0F8003154F80C00BA +:1014C000036823F01F030360056815F00105FBD1D5 +:1014D00004EB0C033D2493F80CC05F6804FA0CF491 +:1014E0003C6021240560446112B1987B00F066F9EC +:1014F0003046F8BD0130A3E7D84A0008004402583E +:10150000D823002010B5302484F31188FFF788FF1A +:10151000002383F3118810BD10B50446807B00F0D2 +:1015200063F901231549627B03FA02F20B6823EA8F +:101530000203DAB20B6072B9114AD2F8D81021F066 +:101540000101C2F8D810D2F8001121F00101C2F84F +:101550000011D2F8002113F47F4F0ED1084BD3F8BD +:10156000D82022F00202C3F8D820D3F8002122F0BC +:101570000202C3F80021D3F8003110BDD8230020A7 +:101580000044025808B5302383F31188FFF7C4FFE5 +:10159000002383F3118808BD02684368114301608A +:1015A00003B1184770470000024A136843F0C003B4 +:1015B000136070470078004013B50E4C204600F0D1 +:1015C000BDFA04F1140000234FF400720A4900949C +:1015D00000F07AF9094B4FF40072094904F1380020 +:1015E000009400F0F3F9074A074BC4E9172302B04F +:1015F00010BD00BF5C240020C8240020A9150008ED +:10160000C82600200078004000E1F505037C30B5D5 +:10161000244C002918BF0C46012B11D1224B9842B3 +:101620000ED1224BD3F8E82042F08042C3F8E820E4 +:10163000D3F8102142F08042C3F81021D3F81031C2 +:101640002268036EC16D03EB52038466B3FBF2F3B1 +:101650006268150442BF23F0070503F0070343EA5D +:101660004503CB60A36843F040034B60E36843F05D +:1016700001038B6042F4967343F001030B604FF05B +:10168000FF330B62510505D512F0102205D0B2F1DF +:10169000805F04D080F8643030BD7F23FAE73F23B9 +:1016A000F8E700BFD84B00085C2400200044025833 +:1016B0002DE9F047C66D05463768F46921073462A5 +:1016C0001AD014F0080118BF4FF48071E20748BF28 +:1016D00041F02001A3074FF0300348BF41F0400123 +:1016E000600748BF41F0800183F31188281DFFF790 +:1016F00053FF002383F31188E2050AD5302383F3D7 +:1017000011884FF48061281DFFF746FF002383F303 +:1017100011884FF030094FF0000A14F0200838D13A +:101720003B0616D54FF0300905F1380A200610D5D2 +:1017300089F31188504600F07DF9002836DA082137 +:10174000281DFFF729FF27F080033360002383F370 +:101750001188790614D5620612D5302383F31188D7 +:10176000D5E913239A4208D12B6C33B127F04007F7 +:101770001021281DFFF710FF3760002383F3118825 +:10178000E30618D5AA6E1369ABB15069BDE8F047FE +:10179000184789F31188736A284695F86410194030 +:1017A00000F0E6F98AF31188F469B6E7B06288F3CD +:1017B0001188F469BAE7BDE8F0870000090100F17B +:1017C0006043012203F56143C9B283F8001300F0BE +:1017D0001F039A4043099B0003F1604303F56143F3 +:1017E000C3F880211A60704700F01F0301229A405D +:1017F000430900F160409B0000F5614003F1604344 +:1018000003F56143C3F88020C3F88021002380F8EA +:1018100000337047F8B51546826804460B46AA4265 +:1018200000D28568A1692669761AB5420BD218469E +:101830002A46FFF729FBA3692B44A3612846A36826 +:101840005B1BA360F8BD0CD9AF1B18463246FFF7EF +:101850001BFB3A46E1683044FFF716FBE3683B4464 +:10186000EBE718462A46FFF70FFBE368E5E70000C1 +:1018700083689342F7B50446154600D28568D4E9DB +:101880000460361AB5420BD22A46FFF7FDFA6369A7 +:101890002B4463612846A3685B1BA36003B0F0BDC3 +:1018A0000DD93246AF1B0191FFF7EEFA01993A4686 +:1018B000E0683144FFF7E8FAE3683B44E9E72A4689 +:1018C000FFF7E2FAE368E4E710B50A440024C361D5 +:1018D000029B8460C16002610362C0E90000C0E94C +:1018E000051110BD08B5D0E90532934201D18268D7 +:1018F00082B98268013282605A1C426119700021EB +:10190000D0E904329A4224BFC368436100F0B0FEBC +:10191000002008BD4FF0FF30FBE7000070B530231A +:1019200004460E4683F31188A568A5B1A368A26991 +:10193000013BA360531CA36115782269934224BF25 +:10194000E368A361E3690BB120469847002383F362 +:101950001188284607E03146204600F079FE00282D +:10196000E2DA85F3118870BD2DE9F74F04460E4683 +:1019700017469846D0F81C904FF0300A8AF3118829 +:101980004FF0000B154665B12A4631462046FFF759 +:1019900041FF034660B94146204600F059FE002849 +:1019A000F1D0002383F31188781B03B0BDE8F08FDA +:1019B000B9F1000F03D001902046C847019B8BF37B +:1019C0001188ED1A1E448AF31188DCE7C160C361F7 +:1019D000009B82600362C0E905111144C0E9000068 +:1019E00001617047F8B504460D461646302383F36F +:1019F0001188A768A7B1A368013BA36063695A1C5B +:101A000062611D70D4E904329A4224BFE3686361C5 +:101A1000E3690BB120469847002080F3118807E066 +:101A20003146204600F014FE0028E2DA87F31188E0 +:101A3000F8BD0000D0E9052310B59A4201D18268B3 +:101A40007AB982680021013282605A1C82611C7856 +:101A500003699A4224BFC368836100F009FE2046EF +:101A600010BD4FF0FF30FBE72DE9F74F04460E465F +:101A700017469846D0F81C904FF0300A8AF3118828 +:101A80004FF0000B154665B12A4631462046FFF758 +:101A9000EFFE034660B94146204600F0D9FD00281C +:101AA000F1D0002383F31188781B03B0BDE8F08FD9 +:101AB000B9F1000F03D001902046C847019B8BF37A +:101AC0001188ED1A1E448AF31188DCE70268436826 +:101AD0001143016003B11847704700001430FFF74D +:101AE00043BF00004FF0FF331430FFF73DBF00004D +:101AF0003830FFF7B9BF00004FF0FF333830FFF741 +:101B0000B3BF00001430FFF709BF00004FF0FF31F2 +:101B10001430FFF703BF00003830FFF763BF000049 +:101B20004FF0FF323830FFF75DBF0000012914BFCE +:101B30006FF0130000207047FFF73EBD044B0360B9 +:101B400000234360C0E9023301230374704700BFE0 +:101B5000F04B000810B53023044683F31188FFF7DB +:101B600055FD02230020237480F3118810BD00006E +:101B700038B5C36904460D461BB904210844FFF774 +:101B8000A5FF294604F11400FFF7ACFE002806DA91 +:101B9000201D4FF40061BDE83840FFF797BF38BD06 +:101BA000026843681143016003B1184770470000A1 +:101BB00013B5406B00F58054D4F8A4381A68117836 +:101BC000042914D1017C022911D119790123128928 +:101BD0008B4013420BD101A94C3002F087F9D4F8A5 +:101BE000A4480246019B2179206800F0DFF902B089 +:101BF00010BD0000143002F009B900004FF0FF33AF +:101C0000143002F003B900004C3002F0DBB90000E0 +:101C10004FF0FF334C3002F0D5B90000143002F021 +:101C2000D7B800004FF0FF31143002F0D1B80000F7 +:101C30004C3002F0A7B900004FF0FF324C3002F0F8 +:101C4000A1B900000020704710B500F58054D4F809 +:101C5000A4381A681178042917D1017C022914D1FB +:101C60005979012352898B4013420ED1143002F06E +:101C700069F8024648B1D4F8A4484FF4407361793A +:101C80002068BDE8104000F07FB910BD406BFFF741 +:101C9000DBBF0000704700007FB5124B0125042612 +:101CA000044603600023057400F184024360294662 +:101CB000C0E902330C4B0290143001934FF440738F +:101CC000009602F01BF8094B04F69442294604F1F1 +:101CD0004C000294CDE900634FF4407302F0E2F847 +:101CE00004B070BD184C00088D1C0008B11B000822 +:101CF0000A68302383F311880B790B3342F82300F1 +:101D00004B79133342F823008B7913B10B3342F82C +:101D1000230000F58053C3F8A418022303740020A5 +:101D200080F311887047000038B5037F044613B173 +:101D300090F85430ABB90125201D0221FFF730FF88 +:101D400004F114006FF00101257700F09DFC04F10F +:101D50004C0084F854506FF00101BDE8384000F0A9 +:101D600093BC38BD10B5012104460430FFF718FFBD +:101D70000023237784F8543010BD000038B50446A2 +:101D80000025143001F0D2FF04F14C00257702F059 +:101D9000A1F8201D84F854500121FFF701FF2046CF +:101DA000BDE83840FFF750BF90F8803003F0600383 +:101DB000202B06D190F881200023212A03D81F2A46 +:101DC00006D800207047222AFBD1C0E91D3303E06A +:101DD000034A426707228267C3670120704700BF3A +:101DE0003422002037B500F58055D5F8A4381A689C +:101DF000117804291AD1017C022917D119790123FC +:101E000012898B40134211D100F14C04204602F09C +:101E100021F958B101A9204602F068F8D5F8A44884 +:101E20000246019B2179206800F0C0F803B030BD64 +:101E300001F10B03F0B550F8236085B004460D4660 +:101E4000FEB1302383F3118804EB8507301D082190 +:101E5000FFF7A6FEFB6806F14C005B691B681BB12F +:101E6000019002F051F8019803A902F03FF80246F0 +:101E700048B1039B2946204600F098F8002383F3DD +:101E8000118805B0F0BDFB685A691268002AF5D0C8 +:101E90001B8A013B1340F1D104F18002EAE7000004 +:101EA000133138B550F82140ECB1302383F3118859 +:101EB00004F58053D3F8A4281368527903EB820306 +:101EC000DB689B695D6845B104216018FFF768FE17 +:101ED000294604F1140001F03FFF2046FFF7B4FE4D +:101EE000002383F3118838BD7047000001F00CBA5D +:101EF00001234022002110B5044600F8303BFEF7D4 +:101F0000E9FF0023C4E9013310BD000010B5302300 +:101F1000044683F311882422416000210C30FEF72F +:101F2000D9FF204601F012FA02230020237080F32B +:101F3000118810BD70B500EB8103054650690E464F +:101F40001446DA6018B110220021FEF7C3FFA06921 +:101F500018B110220021FEF7BDFF31462846BDE82A +:101F6000704001F0F9BA000083682022002103F0DC +:101F7000011310B5044683601030FEF7ABFF204616 +:101F8000BDE8104001F074BBF0B4012500EB810402 +:101F900047898D40E4683D43A4694581236000235F +:101FA000A2606360F0BC01F091BB0000F0B40125B9 +:101FB00000EB810407898D40E4683D436469058135 +:101FC00023600023A2606360F0BC01F007BC000046 +:101FD00070B5022300250446242203702946C0F868 +:101FE00088500C3040F8045CFEF774FF204684F8FB +:101FF000705001F045FA63681B6823B129462046FA +:10200000BDE87040184770BD0378052B10B5044635 +:102010000AD080F88C300523037043681B680BB12D +:10202000042198470023A36010BD00000178052912 +:1020300006D190F88C20436802701B6803B11847E2 +:102040007047000070B590F87030044613B100235B +:1020500080F8703004F18002204601F02DFB6368A7 +:102060009B68B3B994F8803013F0600535D0002137 +:10207000204601F01FFE0021204601F00FFE63689C +:102080001B6813B1062120469847062384F8703058 +:1020900070BD204698470028E4D0B4F88630A26F7F +:1020A0009A4288BFA36794F98030A56F002B4FF048 +:1020B000300380F20381002D00F0F280092284F8C1 +:1020C000702083F3118800212046D4E91D23FFF7F7 +:1020D0006DFF002383F31188DAE794F8812003F081 +:1020E0007F0343EA022340F20232934200F0C580AC +:1020F00021D8B3F5807F48D00DD8012B3FD0022BDB +:1021000000F09380002BB2D104F1880262670222B2 +:10211000A267E367C1E7B3F5817F00F09B80B3F569 +:10212000407FA4D194F88230012BA0D1B4F888303C +:1021300043F0020332E0B3F5006F4DD017D8B3F58A +:10214000A06F31D0A3F5C063012B90D863682046FF +:1021500094F882205E6894F88310B4F88430B04715 +:10216000002884D0436863670368A3671AE0B3F567 +:10217000106F36D040F6024293427FF478AF5C4B4A +:1021800063670223A3670023C3E794F88230012B1F +:102190007FF46DAFB4F8883023F00203A4F88830E0 +:1021A000C4E91D55E56778E7B4F88030B3F5A06F52 +:1021B0000ED194F88230204684F88A3001F0BEF9BE +:1021C00063681B6813B101212046984703232370DD +:1021D0000023C4E91D339CE704F18B0363670123EB +:1021E000C3E72378042B10D1302383F311882046D2 +:1021F000FFF7BAFE85F311880321636884F88B50DA +:1022000021701B680BB12046984794F88230002B50 +:10221000DED084F88B300423237063681B68002BA6 +:10222000D6D0022120469847D2E794F88430204641 +:102230001D0603F00F010AD501F030FA012804D081 +:1022400002287FF414AF2B4B9AE72B4B98E701F051 +:1022500017FAF3E794F88230002B7FF408AF94F874 +:10226000843013F00F01B3D01A06204602D501F0D6 +:1022700039FDADE701F02AFDAAE794F88230002B82 +:102280007FF4F5AE94F8843013F00F01A0D01B0654 +:10229000204602D501F00EFD9AE701F0FFFC97E71A +:1022A000142284F8702083F311882B462A4629468D +:1022B0002046FFF769FE85F31188E9E65DB1152236 +:1022C00084F8702083F3118800212046D4E91D236F +:1022D000FFF75AFEFDE60B2284F8702083F3118885 +:1022E0002B462A4629462046FFF760FEE3E700BF5B +:1022F000484C0008404C0008444C000838B590F8A1 +:1023000070300446002B3ED0063BDAB20F2A34D898 +:102310000F2B32D8DFE803F0373131082232313168 +:102320003131313131313737856FB0F886309D42E8 +:1023300014D2C3681B8AB5FBF3F203FB12556DB9C7 +:10234000302383F311882B462A462946FFF72EFEB9 +:1023500085F311880A2384F870300EE0142384F882 +:102360007030302383F31188002320461A46194623 +:10237000FFF70AFE002383F3118838BDC36F03B152 +:1023800098470023E7E70021204601F093FC002155 +:10239000204601F083FC63681B6813B106212046C8 +:1023A00098470623D7E7000010B590F87030044630 +:1023B000142B29D017D8062B05D001D81BB110BD7E +:1023C000093B022BFBD80021204601F073FC0021C1 +:1023D000204601F063FC63681B6813B106212046A8 +:1023E0009847062319E0152BE9D10B2380F87030AC +:1023F000302383F3118800231A461946FFF7D6FDD0 +:10240000002383F31188DAE7C3689B695B68002BBC +:10241000D5D1C36F03B19847002384F87030CEE75D +:1024200000238268037503691B6899689142FBD297 +:102430005A680360426010605860704700238268E9 +:10244000037503691B6899689142FBD85A68036059 +:10245000426010605860704708B50846302383F327 +:1024600011880A7D0023052A06D8DFE802F00B0553 +:102470000503120E826913604FF0FF338361FFF78B +:10248000CFFF002383F3118808BD8269936801336D +:102490009360D0E9003213605A60EDE7FFF7C0BFE8 +:1024A000054BD96808751868026853601A600122E4 +:1024B000D8600275FDF7A6BFC82800200C4B30B5C8 +:1024C000DD684B1C87B004460FD02B46094A68468E +:1024D00000F06EF92046FFF7E3FF009B13B168465A +:1024E00000F070F9A86907B030BDFFF7D9FFF9E730 +:1024F000C82800205924000838B50C4D04468161D5 +:10250000EB6881689A68914203D8BDE83840FFF7CC +:1025100087BF1846FFF792FF01230146EC60204673 +:102520002375BDE83840FDF76DBF00BFC828002007 +:10253000044B1A68DB6890689B68984294BF00203F +:1025400001207047C8280020084B10B51C68D868C7 +:10255000226853601A600122DC602275FFF76EFF6B +:1025600001462046BDE81040FDF74CBFC8280020BA +:1025700038B50123084C00252370656001F0A6FDE5 +:1025800001F0CCFD0549064801F05EFE02232370F0 +:1025900085F3118838BD00BF302B0020504C000857 +:1025A000C828002000F044B9034A516853685B1AF8 +:1025B0009842FBD8704700BF001000E08B600223F8 +:1025C000086108468B8270478368A3F1840243F850 +:1025D000142C026943F8442C426943F8402C094A00 +:1025E00043F8242CC268A3F1200043F8182C0222DF +:1025F00003F80C2C002203F80B2C034A43F8102C90 +:10260000704700BF1D040008C828002008B5FFF768 +:10261000DBFFBDE80840FFF741BF0000024BDB686D +:1026200098610F20FFF73CBFC8280020302383F3B8 +:102630001188FFF7F3BF000008B50146302383F38C +:1026400011880820FFF73AFF002383F3118808BDA3 +:10265000064BDB6839B1426818605A60136043600A +:102660000420FFF72BBF4FF0FF307047C828002031 +:102670000368984206D01A68026050601846996153 +:10268000FFF70CBF7047000038B504460D462068C0 +:10269000844200D138BD036823605C608561FFF728 +:1026A000FDFEF4E7036810B59C68A2420CD85C6894 +:1026B0008A600B604C602160596099688A1A9A6040 +:1026C0004FF0FF33836010BD121B1B68ECE7000066 +:1026D0000A2938BF0A2170B504460D460A2660193A +:1026E00001F0EEFC01F0D6FC041BA54203D8751CDA +:1026F00004462E46F3E70A2E04D90120BDE87040B7 +:1027000001F0E2BD70BD0000F8B5144B0D460A2A79 +:102710004FF00A07D96103F11001826038BF0A2225 +:10272000416019691446016048601861A81801F0F9 +:10273000B7FC01F0AFFC431B0646A34206D37C1C4A +:1027400028192746354601F0BBFCF2E70A2F04D9C9 +:102750000120BDE8F84001F0B7BDF8BDC828002051 +:10276000F8B506460D4601F095FC0F4A134653F89E +:10277000107F9F4206D12A4601463046BDE8F84008 +:10278000FFF7C2BFD169BB68441A2C1928BF2C4679 +:10279000A34202D92946FFF79BFF22463146034850 +:1027A000BDE8F840FFF77EBFC8280020D8280020E9 +:1027B000C0E90323002310B45DF8044B4361FFF725 +:1027C000CFBF000010B5194C236998420DD0816825 +:1027D000D0E9003213605A609A680A449A60002374 +:1027E00003604FF0FF33A36110BD0268234643F836 +:1027F000102F53600022026022699A4203D1BDE883 +:10280000104001F057BC936881680B44936001F05D +:1028100041FC2269E1699268441AA242E4D9114458 +:10282000BDE81040091AFFF753BF00BFC8280020B9 +:102830002DE9F047DFF8BC8008F110072C4ED8F8DE +:10284000105001F027FCD8F81C40AA68031B9A42DC +:102850003ED814444FF00009D5E90032C8F81C40B6 +:1028600013605A60C5F80090D8F81030B34201D117 +:1028700001F020FC89F31188D5E9033128469847F7 +:10288000302383F311886B69002BD8D001F002FC50 +:102890006A69A0EB040982464A450DD2022001F084 +:1028A00013FD0022D8F81030B34208D15146284613 +:1028B000BDE8F047FFF728BF121A2244F2E712EBF7 +:1028C00009092946384638BF4A46FFF7EBFEB5E707 +:1028D000D8F81030B34208D01444C8F81C00211AAC +:1028E000A960BDE8F047FFF7F3BEBDE8F08700BF81 +:1028F000D8280020C828002000207047FEE70000EC +:10290000704700004FF0FF307047000002290CD0E4 +:10291000032904D00129074818BF00207047032A63 +:1029200005D8054800EBC2007047044870470020F6 +:10293000704700BF284D000844220020DC4C0008EE +:1029400070B59AB005460846144601A900F0C2F8D1 +:1029500001A8FEF7B7FA431C0022C6B25B0010467E +:10296000C5E9003423700323023404F8013C01ABB1 +:10297000D1B202348E4201D81AB070BD13F8011BD7 +:10298000013204F8010C04F8021CF1E708B5302309 +:1029900083F311880348FFF725FA002383F3118896 +:1029A00008BD00BF382B002090F8803003F01F02D4 +:1029B000012A07D190F881200B2A03D10023C0E916 +:1029C0001D3315E003F06003202B08D1B0F88430EC +:1029D0002BB990F88120212A03D81F2A04D8FFF7A9 +:1029E000E3B9222AEBD0FAE7034A4267072282675B +:1029F000C3670120704700BF3B22002007B50529AF +:102A000017D8DFE801F0191603191920302383F3D2 +:102A10001188104A01210190FFF78CFA01980221D8 +:102A20000D4AFFF787FA0D48FFF7A8F9002383F353 +:102A3000118803B05DF804FB302383F31188074845 +:102A4000FFF772F9F2E7302383F311880348FFF7A9 +:102A500089F9EBE77C4C0008A04C0008382B0020DB +:102A600038B50C4D0C4C2A460C4904F10800FFF710 +:102A700067FF05F1CA0204F110000949FFF760FF82 +:102A800005F5CA7204F118000649BDE83840FFF7A1 +:102A900057BF00BF10440020442200205C4C0008B7 +:102AA000664C0008714C000870B5044608460D4697 +:102AB000FEF708FAC6B22046013403780BB918466F +:102AC00070BD32462946FEF7E9F90028F3D101200E +:102AD000F6E700002DE9F04705460C46FEF7F2F94F +:102AE0002B49C6B22846FFF7DFFF08B10736F6B21A +:102AF00028492846FFF7D8FF08B11036F6B2632EF2 +:102B00000BD8DFF88C80DFF88C90234FDFF894A08F +:102B10002E7846B92670BDE8F08729462046BDE8E4 +:102B2000F04701F0B3BF252E2ED10722414628469B +:102B3000FEF7B4F970B9194B224603F10C0153F8B2 +:102B4000040B8B4242F8040BF9D11B8807350E3475 +:102B50001380DDE7082249462846FEF79FF998B919 +:102B6000A21C0F4B197802320909C95D02F8041C36 +:102B700013F8011B01F00F015345C95D02F8031C56 +:102B8000F0D118340835C3E7013504F8016BBFE70D +:102B9000484D0008714C00085F4D0008504D00087A +:102BA00000E8F11F0CE8F11FBFF34F8F044B1A69C7 +:102BB0005107FCD1D3F810215207F8D1704700BF5C +:102BC0000020005208B50D4B1B78ABB9FFF7ECFFA6 +:102BD0000B4BDA68D10704D50A4A5A6002F18832F1 +:102BE0005A60D3F80C21D20706D5064AC3F804214F +:102BF00002F18832C3F8042108BD00BF6E460020F0 +:102C0000002000522301674508B5114B1B78F3B92A +:102C1000104B1A69510703D5DA6842F04002DA60B6 +:102C2000D3F81021520705D5D3F80C2142F0400209 +:102C3000C3F80C21FFF7B8FF064BDA6842F0010237 +:102C4000DA60D3F80C2142F00102C3F80C2108BD70 +:102C50006E460020002000520F289ABF00F58060C9 +:102C600040040020704700004FF40030704700001F +:102C7000102070470F2808B50BD8FFF7EDFF00F5BF +:102C800000330268013204D104308342F9D10120BB +:102C900008BD0020FCE700000F2838B505463FD8E6 +:102CA000FFF782FF1F4CFFF78DFF4FF0FF33072820 +:102CB0006361C4F814311DD82361FFF775FF030267 +:102CC00043F02403E360E36843F08003E360236997 +:102CD0005A07FCD42846FFF767FFFFF7BDFF4FF404 +:102CE000003100F0B3F92846FFF78EFFBDE8384009 +:102CF000FFF7C0BFC4F81031FFF756FFA0F108037B +:102D00001B0243F02403C4F80C31D4F80C3143F017 +:102D10008003C4F80C31D4F810315B07FBD4D9E739 +:102D2000002038BD002000522DE9F84F05460C4622 +:102D3000104645EA0203DE0602D00020BDE8F88F07 +:102D400020F01F00DFF8BCB0DFF8BCA0FFF73AFFAF +:102D500004EB0008444503D10120FFF755FFEDE7E0 +:102D600020222946204601F081FE10B9203520346A +:102D7000F0E72B4605F120021F68791CDDD10433F2 +:102D80009A42F9D105F178431B481C4EB3F5801FD8 +:102D90001B4B38BF184603F1F80332BFD946D14662 +:102DA0001E46FFF701FF0760A5EB040C336804F132 +:102DB0001C0143F002033360231FD9F8007017F0A1 +:102DC0000507FAD153F8042F8B424CF80320F4D1B5 +:102DD000BFF34F8FFFF7E8FE4FF0FF33202221466D +:102DE00003602846336823F00203336001F03EFE9F +:102DF0000028BBD03846B0E7142100520C20005206 +:102E000014200052102000521021005210B5084C1E +:102E1000237828B11BB9FFF7D5FE0123237010BD1D +:102E2000002BFCD02070BDE81040FFF7EDBE00BFC6 +:102E30006E4600202DE9F04F0D4685B0814658B111 +:102E400011F00D0614BF2022082211F0080301938F +:102E500004D0431E03426AD0002435E0002E37D050 +:102E600009F11F0121F01F094FF00108324F05F051 +:102E70000403DFF8D0A005EA080BBBF1000F32D045 +:102E80007869C0072FD408F101080C37B8F1060F94 +:102E9000F3D19EB9294D4946A819019201F060F974 +:102EA000044600283AD11836019A782EF3D14946C3 +:102EB00001F056F90446002830D1019A49462048CD +:102EC00001F04EF9044668BB204605B0BDE8F08F1E +:102ED0000029C9D101462846029201F041F9044671 +:102EE000E0B9029AC0E713B178694107CBD5AC07C6 +:102EF00002D578698007C6D5019911B178690107B3 +:102F0000C1D51820494600FB08A0CDE9022301F0F5 +:102F100027F90446DDE902230028B4D04A460021FF +:102F2000204601E04A460021FDF7D4FFCCE70246E7 +:102F3000002E95D198E700BF704D0008A0460020F4 +:102F400070460020884600200121FFF773BF000073 +:102F5000F8B5144D01241827134E40F2FF3200211A +:102F60000120FDF7B7FF07FB046001342A6955F81B +:102F70000C1F01F0E1F8062CF5D137254FF4C054B1 +:102F80002046FFF7E1FF014628B122460748BDE889 +:102F9000F84001F0D1B8C4EBC404013D4FEAD404B9 +:102FA000EED1F8BD704D0008884600207046002024 +:102FB0000244074BD2B210B5904200D110BD441C60 +:102FC00000B253F8200041F8040BE0B2F4E700BF70 +:102FD000504000580E4B30B51C6F240405D41C6FB4 +:102FE0001C671C6F44F400441C670A4C02442368AD +:102FF000D2B243F480732360074B904200D130BDBE +:10300000441C51F8045B00B243F82050E0B2F4E7EE +:1030100000440258004802585040005807B50122A9 +:1030200001A90020FFF7C4FF019803B05DF804FB7D +:1030300013B50446FFF7F2FFA04205D0012201A913 +:1030400000200194FFF7C6FF02B010BD0144BFF39A +:103050004F8F064B884204D3BFF34F8FBFF36F8F60 +:103060007047C3F85C022030F4E700BF00ED00E0D9 +:10307000034B1A681AB9034AD2F8D0241A60704771 +:10308000184700200040025808B5FFF7F1FF024B37 +:103090001868C0F3806008BD18470020EFF309836B +:1030A000054968334A6B22F001024A6383F30988B9 +:1030B000002383F31188704700EF00E0302080F395 +:1030C000118862B60D4B0E4AD96821F4E0610904FB +:1030D000090C0A430B49DA60D3F8FC2042F08072F5 +:1030E000C3F8FC20084AC2F8B01F116841F0010182 +:1030F00011602022DA7783F82200704700ED00E0AB +:103100000003FA0555CEACC5001000E0302310B521 +:1031100083F311880E4B5B6813F4006314D0F1EE57 +:10312000103AEFF309844FF08073683CE361094B78 +:10313000DB6B236684F30988FFF7FAF910B1064BBD +:10314000A36110BD054BFBE783F31188F9E700BFCE +:1031500000ED00E000EF00E02F040008320400085A +:1031600070B5BFF34F8FBFF36F8F1A4A0021C2F8BB +:103170005012BFF34F8FBFF36F8F536943F4003387 +:103180005361BFF34F8FBFF36F8FC2F88410BFF34B +:103190004F8FD2F8803043F6E074C3F3C900C3F315 +:1031A0004E335B0103EA0406014646EA81750139A4 +:1031B000C2F86052F9D2203B13F1200FF2D1BFF3D5 +:1031C0004F8F536943F480335361BFF34F8FBFF385 +:1031D0006F8F70BD00ED00E0FEE70000214B22483C +:1031E000224A70B5904237D3214BC11EDA1C121A05 +:1031F00022F003028B4238BF00220021FDF76AFE55 +:103200001C4A0023C2F88430BFF34F8FD2F88030BD +:1032100043F6E074C3F3C900C3F34E335B0103EA22 +:103220000406014646EA81750139C2F86C52F9D2AA +:10323000203B13F1200FF2D1BFF34F8FBFF36F8FFD +:10324000BFF34F8FBFF36F8F0023C2F85032BFF32D +:103250004F8FBFF36F8F70BD53F8041B40F8041BF2 +:10326000C0E700BF9C4F00080C4900200C4900201B +:103270000C49002000ED00E0074BD3F8D81021EAFC +:103280000001C3F8D810D3F8002122EA0002C3F8E5 +:103290000021D3F8003170470044025870B5D0E9DE +:1032A000244300224FF0FF359E6804EB4213510186 +:1032B000D3F80009002805DAD3F8000940F080406F +:1032C000C3F80009D3F8000B002805DAD3F8000B87 +:1032D00040F08040C3F8000B013263189642C3F8F7 +:1032E0000859C3F8085BE0D24FF00113C4F81C384A +:1032F00070BD0000890141F02001016103699B0656 +:10330000FCD41220FFF750B910B50A4C2046FEF746 +:10331000EFFD094BC4F89030084BC4F89430084CCA +:103320002046FEF7E5FD074BC4F89030064BC4F885 +:10333000943010BD1C47002000000840DC4D000800 +:10334000B847002000000440E84D000870B503783D +:103350000546012B5CD1434BD0F89040984258D1A0 +:10336000414B0E216520D3F8D82042F00062C3F80B +:10337000D820D3F8002142F00062C3F80021D3F82E +:103380000021D3F8802042F00062C3F88020D3F8F7 +:10339000802022F00062C3F88020D3F88030FEF74E +:1033A0000DFA324BE360324BC4F800380023D5F8F5 +:1033B0009060C4F8003EC02323604FF40413A3635D +:1033C0003369002BFCDA01230C203361FFF7ECF8A2 +:1033D0003369DB07FCD41220FFF7E6F83369002BD2 +:1033E000FCDA00262846A660FFF758FF6B68C4F891 +:1033F0001068DB68C4F81468C4F81C6883BB1D4BF4 +:10340000A3614FF0FF336361A36843F00103A3603E +:1034100070BD194B9842C9D1134B4FF08060D3F85F +:10342000D82042F00072C3F8D820D3F8002142F02F +:103430000072C3F80021D3F80021D3F8802042F0B5 +:103440000072C3F88020D3F8802022F00072C3F805 +:103450008020D3F88030FFF70FFF0E214D209EE72C +:10346000064BCDE71C4700200044025840140040A2 +:1034700003002002003C30C0B8470020083C30C0A8 +:10348000F8B5D0F89040054600214FF00066204680 +:10349000FFF730FFD5F8941000234FF001128F682A +:1034A0004FF0FF30C4F83438C4F81C2804EB431242 +:1034B00001339F42C2F80069C2F8006BC2F80809E4 +:1034C000C2F8080BF2D20B68D5F89020C5F89830F6 +:1034D000636210231361166916F01006FBD11220E7 +:1034E000FFF762F8D4F8003823F4FE63C4F800381C +:1034F000A36943F4402343F01003A3610923C4F8F4 +:103500001038C4F814380B4BEB604FF0C043C4F8CC +:10351000103B094BC4F8003BC4F81069C4F80039EB +:10352000D5F8983003F1100243F48013C5F89820C1 +:10353000A362F8BDB84D000840800010D0F890207C +:1035400090F88A10D2F8003823F4FE6343EA01139E +:10355000C2F80038704700002DE9F84300EB810302 +:10356000D0F890500C468046DA680FFA81F948018D +:10357000166806F00306731E022B05EB41134FF08D +:10358000000194BFB604384EC3F8101B4FF0010180 +:1035900004F1100398BF06F1805601FA03F3916914 +:1035A00098BF06F5004600293AD0578A04F1580121 +:1035B000374349016F50D5F81C180B430021C5F85B +:1035C0001C382B180127C3F81019A7405369611E36 +:1035D0009BB3138A928B9B08012A88BF5343D8F868 +:1035E0009820981842EA034301F140022146C8F8A6 +:1035F0009800284605EB82025360FFF77BFE08EB3C +:103600008900C3681B8A43EA845348341E4364011B +:103610002E51D5F81C381F43C5F81C78BDE8F88337 +:1036200005EB4917D7F8001B21F40041C7F8001B30 +:10363000D5F81C1821EA0303C0E704F13F030B4A45 +:103640002846214605EB83035A60FFF753FE05EB3E +:103650004910D0F8003923F40043C0F80039D5F8F8 +:103660001C3823EA0707D7E7008000100004000297 +:10367000D0F894201268C0F89820FFF70FBE000021 +:103680005831D0F8903049015B5813F4004004D011 +:1036900013F4001F0CBF0220012070474831D0F8FE +:1036A000903049015B5813F4004004D013F4001F1C +:1036B0000CBF02200120704700EB8101CB68196A22 +:1036C0000B6813604B6853607047000000EB810388 +:1036D00030B5DD68AA691368D36019B9402B84BF7F +:1036E000402313606B8A1468D0F890201C4402EBCE +:1036F0004110013C09B2B4FBF3F46343033323F0FC +:10370000030343EAC44343F0C043C0F8103B2B68B3 +:1037100003F00303012B0ED1D2F8083802EB41105D +:1037200013F4807FD0F8003B14BF43F0805343F084 +:103730000053C0F8003B02EB4112D2F8003B43F0CB +:103740000443C2F8003B30BD2DE9F041D0F8906051 +:1037500005460C4606EB4113D3F8087B3A07C3F83D +:10376000087B08D5D6F814381B0704D500EB810375 +:10377000DB685B689847FA071FD5D6F81438DB0773 +:103780001BD505EB8403D968CCB98B69488A5A6884 +:10379000B2FBF0F600FB16228AB91868DA6890428C +:1037A0000DD2121AC3E90024302383F31188214675 +:1037B0002846FFF78BFF84F31188BDE8F0810123D1 +:1037C00003FA04F26B8923EA02036B81CB68002BB6 +:1037D000F3D021462846BDE8F041184700EB8103AD +:1037E0004A0170B5DD68D0F890306C692668E660F3 +:1037F00056BB1A444FF40020C2F810092A6802F0A0 +:103800000302012A0AB20ED1D3F8080803EB4214CE +:1038100010F4807FD4F8000914BF40F0805040F0CD +:103820000050C4F8000903EB4212D2F8000940F03E +:103830000440C2F800090122D3F8340802FA01F169 +:103840000143C3F8341870BD19B9402E84BF40201D +:10385000206020681A442E8A8419013CB4FBF6F4D7 +:1038600040EAC44040F00050C6E700002DE9F843AC +:10387000D0F8906005460C464F0106EB4113D3F893 +:10388000088918F0010FC3F808891CD0D6F8103841 +:10389000DB0718D500EB8103D3F80CC0DCF814303B +:1038A000D3F800E0DA68964530D2A2EB0E024FF072 +:1038B00000091A60C3F80490302383F31188FFF7DE +:1038C0008DFF89F3118818F0800F1DD0D6F8343899 +:1038D0000126A640334217D005EB84030134D5F806 +:1038E0009050D3F80CC0E4B22F44DCF8142005EB60 +:1038F0000434D2F800E05168714514D3D5F8343857 +:1039000023EA0606C5F83468BDE8F883012303FA04 +:1039100001F2038923EA02030381DCF80830002B5B +:10392000D1D09847CFE7AEEB0103BCF8100083423B +:1039300028BF0346D7F8180980B2B3EB800FE3D84D +:103940009068A0F1040959F8048FC4F80080A0EB36 +:1039500009089844B8F1040FF5D818440B44906056 +:103960005360C8E72DE9F84FD0F8905004466E69CF +:10397000AB691E4016F480586E6103D0BDE8F84F65 +:10398000FEF726BB002E12DAD5F8003E9B0705D0C5 +:10399000D5F8003E23F00303C5F8003ED5F80438FF +:1039A000204623F00103C5F80438FEF73FFB370536 +:1039B00005D52046FFF772FC2046FEF725FBB00434 +:1039C0000CD5D5F8083813F0060FEB6823F47053C4 +:1039D0000CBF43F4105343F4A053EB6031071BD5E5 +:1039E0006368DB681BB9AB6923F00803AB6123781C +:1039F000052B0CD1D5F8003E9A0705D0D5F8003E2E +:103A000023F00303C5F8003E2046FEF70FFB636872 +:103A1000DB680BB120469847F30200F1BA80B70289 +:103A200026D5D4F8909000274FF0010A09EB4712F1 +:103A3000D2F8003B03F44023B3F5802F11D1D2F824 +:103A4000003B002B0DDA62890AFA07F322EA03032E +:103A5000638104EB8703DB68DB6813B139462046DA +:103A600098470137D4F89430FFB29B689F42DDD964 +:103A7000F00619D5D4F89000026AC2F30A1702F0D2 +:103A80000F0302F4F012B2F5802F00F0CA80B2F5F5 +:103A9000402F09D104EB8303002200F58050DB683E +:103AA0001B6A974240F0B0803003D5F8185835D5DE +:103AB000E90303D500212046FFF746FEAA0303D5FC +:103AC00001212046FFF740FE6B0303D5022120466B +:103AD000FFF73AFE2F0303D503212046FFF734FEFC +:103AE000E80203D504212046FFF72EFEA90203D5E4 +:103AF00005212046FFF728FE6A0203D5062120464D +:103B0000FFF722FE2B0203D507212046FFF71CFEFC +:103B1000EF0103D508212046FFF716FE700340F1A0 +:103B2000A780E90703D500212046FFF79FFEAA07DB +:103B300003D501212046FFF799FE6B0703D502212B +:103B40002046FFF793FE2F0703D503212046FFF7FA +:103B50008DFEEE0603D504212046FFF787FEA8065A +:103B600003D505212046FFF781FE690603D506210E +:103B70002046FFF77BFE2A0603D507212046FFF7E4 +:103B800075FEEB0574D520460821BDE8F84FFFF718 +:103B90006DBED4F890904FF0000B4FF0010AD4F8AE +:103BA00094305FFA8BF79B689F423FF638AF09EB82 +:103BB0004713D3F8002902F44022B2F5802F20D118 +:103BC000D3F80029002A1CDAD3F8002942F09042E9 +:103BD000C3F80029D3F80029002AFBDB3946D4F8C2 +:103BE0009000FFF787FB22890AFA07F322EA030312 +:103BF000238104EB8703DB689B6813B139462046B9 +:103C000098470BF1010BCAE7910701D1D0F800806A +:103C1000072A02F101029CBF03F8018B4FEA182822 +:103C20003FE704EB830300F58050DA68D2F818C050 +:103C3000DCF80820DCE9001CA1EB0C0C00218F4211 +:103C400008D1DB689B699A683A449A605A683A449A +:103C50005A6029E711F0030F01D1D0F800808C459C +:103C600001F1010184BF02F8018B4FEA1828E6E751 +:103C7000BDE8F88F08B50348FFF774FEBDE80840BB +:103C8000FFF744BA1C47002008B50348FFF76AFE57 +:103C9000BDE80840FFF73ABAB8470020D0F89030A6 +:103CA00003EB4111D1F8003B43F40013C1F8003B92 +:103CB00070470000D0F8903003EB4111D1F8003983 +:103CC00043F40013C1F8003970470000D0F8903079 +:103CD00003EB4111D1F8003B23F40013C1F8003B82 +:103CE00070470000D0F8903003EB4111D1F8003953 +:103CF00023F40013C1F800397047000030B50433D5 +:103D0000039C0172002104FB0325C160C0E9065336 +:103D1000049B0363059BC0E90000C0E90422C0E9DD +:103D20000842C0E90A11436330BD00000022416A25 +:103D3000C260C0E90411C0E90A226FF00101FEF778 +:103D4000A3BC0000D0E90432934201D1C2680AB991 +:103D5000181D704700207047036919600021C26870 +:103D60000132C260C269134482699342036124BF75 +:103D7000436A0361FEF77CBC38B504460D46E36830 +:103D80003BB162690020131D1268A3621344E36211 +:103D900007E0237A33B929462046FEF759FC00286C +:103DA000EDDA38BD6FF00100FBE70000C368C269BF +:103DB000013BC3604369134482699342436124BF5A +:103DC000436A436100238362036B03B11847704762 +:103DD00070B53023044683F31188866A3EB9FFF735 +:103DE000CBFF054618B186F31188284670BDA36A3B +:103DF000E26A13F8015B9342A36202D32046FFF705 +:103E0000D5FF002383F31188EFE700002DE9F84F79 +:103E100004460E46174698464FF0300989F311883C +:103E20000025AA46D4F828B0BBF1000F09D14146BD +:103E30002046FFF7A1FF20B18BF311882846BDE88B +:103E4000F88FD4E90A12A7EB050B521A934528BF45 +:103E50009346BBF1400F1BD9334601F1400251F8A4 +:103E6000040B914243F8040BF9D1A36A4036403564 +:103E70004033A362D4E90A239A4202D32046FFF7D3 +:103E800095FF8AF31188BD42D8D289F31188C9E71A +:103E900030465A46FCF7F8FFA36A5E445D445B4433 +:103EA000A362E7E710B5029C0433017203FB04210F +:103EB000C460C0E906130023C0E90A33039B03630F +:103EC000049BC0E90000C0E90422C0E90842436342 +:103ED00010BD0000026A6FF00101C260426AC0E9D1 +:103EE00004220022C0E90A22FEF7CEBBD0E9042357 +:103EF0009A4201D1C26822B9184650F8043B0B60BF +:103F0000704700231846FAE7C3680021C2690133ED +:103F1000C3604369134482699342436124BF436A87 +:103F20004361FEF7A5BB000038B504460D46E368C3 +:103F30003BB1236900201A1DA262E2691344E362C7 +:103F400007E0237A33B929462046FEF781FB002893 +:103F5000EDDA38BD6FF00100FBE70000036919607E +:103F6000C268013AC260C269134482699342036124 +:103F700024BF436A036100238362036B03B11847C4 +:103F80007047000070B530230D460446114683F398 +:103F90001188866A2EB9FFF7C7FF10B186F3118822 +:103FA00070BDA36A1D70A36AE26A01339342A362E3 +:103FB00004D3E16920460439FFF7D0FF002080F3E5 +:103FC0001188EDE72DE9F84F04460D4690469946D5 +:103FD0004FF0300A8AF311880026B346A76A4FB91A +:103FE00049462046FFF7A0FF20B187F311883046ED +:103FF000BDE8F88FD4E90A073A1AA8EB06079742FA +:1040000028BF1746402F1BD905F1400355F8042B54 +:104010009D4240F8042BF9D1A36A40364033A36295 +:10402000D4E90A239A4204D3E16920460439FFF710 +:1040300095FF8BF311884645D9D28AF31188CDE7D5 +:1040400029463A46FCF720FFA36A3D443E443B44E0 +:10405000A362E5E7D0E904239A4217D1C3689BB174 +:10406000836A8BB1043B9B1A0ED01360C368013B7B +:10407000C360C3691A4483699A42026124BF436AD8 +:104080000361002383620123184670470023FBE786 +:1040900000F01EBA014B586A704700BF000C004088 +:1040A000034B002258631A610222DA60704700BF96 +:1040B000000C0040014B0022DA607047000C004009 +:1040C000014B5863704700BF000C0040024B034A8D +:1040D0001A60034A5A6070476C480020104900205B +:1040E00000000220074B494210B55C68201A0840C6 +:1040F0001968821A8A4203D3A24201D85A6010BDBD +:104100000020FCE76C48002008B5302383F31188B9 +:10411000FFF7E8FF002383F3118808BD044801215D +:10412000044B03600023C0E901330C3000F0D4B825 +:104130007448002009410008CB1D083A23F007030A +:10414000591A521A012110B4D2080024C0E90043C0 +:1041500084600C301C605A605DF8044B00F0BCB801 +:104160002DE9F84F364ECD1D0F46002818BF0646E4 +:10417000082A4FEAD50538BF082206F10C08341D7D +:104180009146404600F0C4F809F10701C9F1000E5C +:10419000224624686CB9404600F0C4F83368CBB3BB +:1041A00008224946E8009847044698B340E9026768 +:1041B00030E004EB010CD4F804A00CEA0E0C0AF178 +:1041C0000100ACF1080304EBC0009842E0D9A0EB79 +:1041D0000C0CB5EBEC0F4FEAEC0BD9D89C421CD27F +:1041E00004F10802AB45A3EB02024FEAE20262606F +:1041F00009D9691CED43206803EBC1025D44556099 +:1042000043F8310022601C465F60404644F8086B6A +:1042100000F088F82046BDE8F88FAA45216802D151 +:1042200011602346EFE7013504EBC50344F8351070 +:1042300003F10801401AC01058601360F1E700BF95 +:1042400074480020FEE7000070B51B4B00250446B3 +:1042500086B058600E4685620163FEF72FFF04F1B9 +:104260001003A560E562C4E904334FF0FF33C4E9ED +:104270000044C4E90635FFF70DFF2B46024604F162 +:1042800034012046C4E9082380230C4A2565FEF743 +:1042900095F901230A4AE060009203756846726846 +:1042A0000192B268CDE90223064BCDE90435FEF751 +:1042B000ADF906B070BD00BF302B0020F44D0008F2 +:1042C000F94D000845420008024AD36A1843D062FB +:1042D000704700BFC8280020C0E900008160704717 +:1042E0008368013B002B10B583600CDA074BDC6858 +:1042F0004368A061206063601C6044600520FEF795 +:10430000CFF8A06910BD0020FCE700BFC82800203E +:1043100008B5302383F31188FFF7E2FF002383F30E +:10432000118808BD08B5302383F3118883680133F1 +:10433000002B836007DC036800211A68026050606C +:104340001846FEF7D9F8002383F3118808BD000052 +:104350004B6843608B688360CB68C3600B694361C3 +:104360004B6903628B6943620B680360704700000E +:1043700008B53C4B40F2FF713B48D3F888200A4314 +:10438000C3F88820D3F8882022F4FF6222F00702C5 +:10439000C3F88820D3F88820D3F8E0200A43C3F874 +:1043A000E020D3F808210A43C3F808212F4AD3F8A4 +:1043B00008311146FFF7CCFF00F5806002F11C01C7 +:1043C000FFF7C6FF00F5806002F13801FFF7C0FF7C +:1043D00000F5806002F15401FFF7BAFF00F580603C +:1043E00002F17001FFF7B4FF00F5806002F18C016B +:1043F000FFF7AEFF00F5806002F1A801FFF7A8FF0C +:1044000000F5806002F1C401FFF7A2FF00F58060B3 +:1044100002F1E001FFF79CFF00F5806002F1FC0172 +:10442000FFF796FF02F58C7100F58060FFF790FFB3 +:1044300000F01AF90E4BD3F8902242F00102C3F8B3 +:104440009022D3F8942242F00102C3F8942205226C +:10445000C3F898204FF06052C3F89C20054AC3F877 +:10446000A02008BD0044025800000258004E000879 +:1044700000ED00E01F00080308B500F0D7FAFEF7D2 +:1044800077F8104BD3F8DC2042F04002C3F8DC2070 +:10449000D3F8042122F04002C3F80421D3F80431F8 +:1044A000094B1A6842F008021A601A6842F00402C6 +:1044B0001A60FEF7DDFDFEF74BFDBDE80840FEF794 +:1044C000CFBA00BF004402580018024870470000ED +:1044D000114BD3F8E82042F00802C3F8E820D3F8E3 +:1044E000102142F00802C3F810210C4AD3F8103111 +:1044F000D36B43F00803D363C722094B9A624FF092 +:10450000FF32DA6200229A615A63DA605A6001224D +:104510005A611A60704700BF004402580010005CE6 +:10452000000C0040094A08B51169D3680B40D9B2A4 +:104530009B076FEA0101116107D5302383F31188CE +:10454000FEF730F8002383F3118808BD000C00400B +:10455000064BD3F8DC200243C3F8DC20D3F8042157 +:104560001043C3F80401D3F80431704700440258E3 +:1045700008B53C4B4FF0FF31D3F8802062F0004289 +:10458000C3F88020D3F8802002F00042C3F88020D6 +:10459000D3F88020D3F88420C3F88410D3F8842083 +:1045A0000022C3F88420D3F88400D86F40F0FF4085 +:1045B00040F4FF0040F4DF4040F07F00D867D86F40 +:1045C00020F0FF4020F4FF0020F4DF4020F07F00C7 +:1045D000D867D86FD3F888006FEA40506FEA505020 +:1045E000C3F88800D3F88800C0F30A00C3F8880035 +:1045F000D3F88800D3F89000C3F89010D3F8900057 +:10460000C3F89020D3F89000D3F89400C3F8941026 +:10461000D3F89400C3F89420D3F89400D3F898000A +:10462000C3F89810D3F89800C3F89820D3F89800EE +:10463000D3F88C00C3F88C10D3F88C00C3F88C200E +:10464000D3F88C00D3F89C00C3F89C10D3F89C10CE +:10465000C3F89C20D3F89C30FCF7C2FEBDE80840AC +:1046600000F0B8B90044025808B50122534BC3F812 +:104670000821534BD3F8F42042F00202C3F8F4208F +:10468000D3F81C2142F00202C3F81C210222D3F805 +:104690001C314C4BDA605A689104FCD54A4A1A60C6 +:1046A00001229A60494ADA6000221A614FF44042BE +:1046B0009A61444B9A699204FCD51A6842F480725C +:1046C0001A603F4B1A6F12F4407F04D04FF48032CF +:1046D0001A6700221A671A6842F001021A60384B02 +:1046E0001A685007FCD500221A611A6912F03802C4 +:1046F000FBD1012119604FF0804159605A67344A5B +:10470000DA62344A1A611A6842F480321A602C4B19 +:104710001A689103FCD51A6842F480521A601A682C +:104720009204FCD52C4A2D499A6200225A631963DF +:1047300001F57C01DA6301F2E71199635A64284AB2 +:104740001A64284ADA621A6842F0A8521A601C4BAE +:104750001A6802F02852B2F1285FF9D148229A6112 +:104760004FF48862DA6140221A621F4ADA641F4AF3 +:104770001A651F4A5A651F4A9A6532231E4A1360FA +:10478000136803F00F03022BFAD10D4A136943F0AB +:1047900003031361136903F03803182BFAD14FF0A8 +:1047A0000050FFF7D5FE4FF08040FFF7D1FE4FF0ED +:1047B0000040BDE80840FFF7CBBE00BF00800051BD +:1047C000004402580048025800C000F002000001F6 +:1047D0000000FF0100889008121020006302090108 +:1047E000470E0508DD0BBF0120000020000001106E +:1047F0000910E00000010110002000524FF0B0420B +:1048000008B5D2F8883003F00103C2F8883023B12C +:10481000044A13680BB150689847BDE80840FEF79A +:1048200075BC00BF8C4800204FF0B04208B5D2F8EC +:10483000883003F00203C2F8883023B1044A936839 +:104840000BB1D0689847BDE80840FEF75FBC00BFD9 +:104850008C4800204FF0B04208B5D2F8883003F001 +:104860000403C2F8883023B1044A13690BB15069BC +:104870009847BDE80840FEF749BC00BF8C480020BF +:104880004FF0B04208B5D2F8883003F00803C2F800 +:10489000883023B1044A93690BB1D0699847BDE8C9 +:1048A0000840FEF733BC00BF8C4800204FF0B042F8 +:1048B00008B5D2F8883003F01003C2F8883023B16D +:1048C000044A136A0BB1506A9847BDE80840FEF7E6 +:1048D0001DBC00BF8C4800204FF0B04310B5D3F88A +:1048E000884004F47872C3F88820A30604D5124ADD +:1048F000936A0BB1D06A9847600604D50E4A136BD1 +:104900000BB1506B9847210604D50B4A936B0BB142 +:10491000D06B9847E20504D5074A136C0BB1506C75 +:104920009847A30504D5044A936C0BB1D06C984703 +:10493000BDE81040FEF7EABB8C4800204FF0B043C2 +:1049400010B5D3F8884004F47C42C3F8882062058F +:1049500004D5164A136D0BB1506D9847230504D545 +:10496000124A936D0BB1D06D9847E00404D50F4AFD +:10497000136E0BB1506E9847A10404D50B4A936E89 +:104980000BB1D06E9847620404D5084A136F0BB17F +:10499000506F9847230404D5044A936F0BB1D06F2E +:1049A0009847BDE81040FEF7B1BB00BF8C4800201F +:1049B00008B50348FCF77CFEBDE80840FEF7A6BB3F +:1049C0005C24002008B5FFF7ADFDBDE80840FEF708 +:1049D0009DBB0000062108B50846FCF7EFFE062146 +:1049E0000720FCF7EBFE06210820FCF7E7FE062176 +:1049F0000920FCF7E3FE06210A20FCF7DFFE062172 +:104A00001720FCF7DBFE06212820FCF7D7FE092142 +:104A10007A20FCF7D3FE07213220FCF7CFFE0C21D1 +:104A20005220BDE80840FCF7C9BE000008B5FFF7FA +:104A30009FFD00F00DF8FDF77FF8FDF757FAFDF741 +:104A400029F9FFF743FDBDE80840FFF721BB00004F +:104A50000023054A19460133102BC2E9001102F167 +:104A60000802F8D1704700BF8C48002010B501390A +:104A70000244904201D1002005E0037811F8014F73 +:104A8000A34201D0181B10BD0130F2E7034611F814 +:104A9000012B03F8012B002AF9D1704753544D33F1 +:104AA0003248373F3F3F0053544D33324837337815 +:104AB0002F3732780053544D3332483734332F3741 +:104AC00035332F373530000001105A0003105900DC +:104AD0000120580003205600100002400800024048 +:104AE0000008024000000B002800024008000240BD +:104AF0000408024006010C00400002400800024089 +:104B00000808024010020D00580002400800024050 +:104B10000C08024016030E00700002400C00024018 +:104B20001008024000040F00880002400C00024000 +:104B30001408024006051000A00002400C000240CC +:104B40001808024010061100B80002400C00024094 +:104B50001C08024016072F001004024008040240FF +:104B600020080240000838002804024008040240DF +:104B700024080240060939004004024008040240AB +:104B800028080240100A3A00580402400804024073 +:104B90002C080240160B3B00700402400C0402403B +:104BA00030080240000C3C00880402400C04024023 +:104BB00034080240060D4400A00402400C040240E8 +:104BC00038080240100E4500B80402400C040240B0 +:104BD0003C080240160F460000960000000000004E +:104BE00000000000000000000000000000000000C5 +:104BF00000000000F91A0008E51A0008211B00084F +:104C00000D1B0008191B0008051B0008F11A0008FD +:104C1000DD1A00082D1B000800000000111C000810 +:104C2000FD1B0008391C0008251C0008311C000869 +:104C30001D1C0008091C0008F51B0008451C000885 +:104C400000000000010000000000000063300000D0 +:104C50004C4C000820290020302B00204172647544 +:104C600050696C6F740025424F415244252D424CCF +:104C7000002553455249414C250000000200000028 +:104C800000000000311E0008A11E00084000400086 +:104C9000E0430020F043002002000000000000007C +:104CA0000300000000000000E91E000800000000F2 +:104CB000100000000044002000000000010000007F +:104CC000000000001C47002001010200FD2900082F +:104CD0000D290008A92900088D29000843000000BB +:104CE000E44C000809024300020100C0320904003C +:104CF0000001020201000524001001052401000149 +:104D0000042402020524060001070582030800FFAF +:104D100009040100020A000000070501024000002A +:104D2000070581024000000012000000304D00081D +:104D30001201100102000040091241570002010255 +:104D4000030100000403090425424F415244250099 +:104D50004145542D483734332D4261736963003027 +:104D600031323334353637383941424344454600D1 +:104D700000000020000002000200000000000030DF +:104D800000000400080000000000002400000800EB +:104D9000040000000004000000FC0000020000000D +:104DA000000004300080000008000000000000380F +:104DB0000000010001000000000000004520000884 +:104DC000FD220008A92300084000400054480020AC +:104DD00054480020010000006448002080000000CA +:104DE0004001000008000000000100000010000069 +:104DF000080000006D61696E0069646C6500000068 +:104E00000000802A00000000AAAAAAAA000000242C +:104E1000FFFF00000000000000A00A0000000001E9 +:104E200000000000AAAAAAAA00000001FFFF0000DB +:104E3000000000000000000000000044000000002E +:104E4000AAAAAAAA00000044FFFF00000000000078 +:104E5000000000000001100000000000AAAAAAAA99 +:104E600000010000FFFB0000000000000000000047 +:104E70005080420000000000AAAAAAAA10404100E7 +:104E8000F7FF0000000000700700000000000000B5 +:104E900000000000AAAAAAAA00000000FFFF00006C +:104EA0000000000000000000000000000000000002 +:104EB000AAAAAAAA00000000FFFF0000000000004C +:104EC000000000000000000000000000AAAAAAAA3A +:104ED00000000000FFFF00000000000000000000D4 +:104EE0000000000000000000AAAAAAAA000000001A +:104EF000FFFF0000000000000000000000000000B4 +:104F000000000000AAAAAAAA00000000FFFF0000FB +:104F10000000000000000000000000000000000091 +:104F2000AAAAAAAA00000000FFFF000000000000DB +:104F30000000000000000000E80700000000000082 +:104F400000001A0000000000FF000000382B0020C5 +:104F50005C240020000000009C4A0008830400003C +:104F6000A74A000850040000B54A00080096000057 +:104F70000000080096000000000800000400000087 +:104F8000444D000800000000000000000000000088 +:0C4F900000000000000000000000000015 +:00000001FF diff --git a/Tools/bootloaders/BlitzF745AIO_bl.bin b/Tools/bootloaders/BlitzF745AIO_bl.bin old mode 100644 new mode 100755 index 84eccde48ae25a..842cdd9c1983f2 Binary files a/Tools/bootloaders/BlitzF745AIO_bl.bin and b/Tools/bootloaders/BlitzF745AIO_bl.bin differ diff --git a/Tools/bootloaders/BlitzF745AIO_bl.hex b/Tools/bootloaders/BlitzF745AIO_bl.hex index 6b6cd147a573f5..ec6fc76d5c08c5 100644 --- a/Tools/bootloaders/BlitzF745AIO_bl.hex +++ b/Tools/bootloaders/BlitzF745AIO_bl.hex @@ -898,20 +898,20 @@ :103800009916000840004000F02D0120F02D012005 :1038100001000000002E0120800000004001000097 :10382000050000006D61696E0069646C6500000050 -:103830009955A56A00000000AAAAAAAA66A91A6456 -:103840001AFC00008070000000A70A00555595552D -:1038500000000000AAAAAAAAAAAA6AAA0008000050 -:103860000000000000700000555555550000000094 -:10387000AAAAAAAAAAAAAAAA0000000000000000F8 -:10388000000000005555555500000000AAAAAAAA3C -:10389000AAAAAA2A00000000000000000000000000 -:1038A0005595555500000000AAAAAAAAAA69AAAA75 -:1038B00090000000000000800000000055555555A4 -:1038C00000000000AAAAAAAAAAAAAAAA00000000A8 -:1038D0000000000000000000555555550000000094 -:1038E000AAAAAAAAAAAAAAAA000000000000000088 -:1038F0000000000005000000000000000A000000B9 -:103900000A000000000000000000000000000000AD +:103830008801A06A00000000AAAAAAAA4401106494 +:10384000FFFF00008070000000A70A000000800059 +:1038500000000000AAAAAAAA00004000FFFF000082 +:1038600000000000007000000000000000000000E8 +:10387000AAAAAAAA00000000FFFF000000000000A2 +:10388000000000000000004000000000AAAAAAAA50 +:1038900000000000FF7F00000000000000000000AA +:1038A0000081000000000000AAAAAAAA00410000AE +:1038B000FFFF00000000008000000000000000008A +:1038C00000000000AAAAAAAA00000000FFFF000052 +:1038D00000000000000000000000000000000000E8 +:1038E000AAAAAAAA00000000FFFF00000000000032 +:1038F0000000000000000000000000000A000000BE +:1039000000000000030000000000000000000000B4 :1039100000000000000000000000000000000000A7 :103920000000000000000000000000000000000097 :103930000000000000000000000000000000000087 diff --git a/Tools/bootloaders/BlitzF745_bl.bin b/Tools/bootloaders/BlitzF745_bl.bin new file mode 100644 index 00000000000000..750ade6946435d Binary files /dev/null and b/Tools/bootloaders/BlitzF745_bl.bin differ diff --git a/Tools/bootloaders/BlitzF745_bl.hex b/Tools/bootloaders/BlitzF745_bl.hex new file mode 100644 index 00000000000000..9ab87d321e97ee --- /dev/null +++ b/Tools/bootloaders/BlitzF745_bl.hex @@ -0,0 +1,929 @@ +:020000040800F2 +:1000000000060120010200080302000803020008A4 +:1000100003020008030200080302000803020008AC +:1000200003020008030200080302000899310008D7 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:100050000302000803020008413400086934000864 +:1000600091340008B9340008E134000803020008A4 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:1000900003020008030200080302000809350008F3 +:1000A000030200080302000803020008030200081C +:1000B000DD350008030200080302000803020008FF +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E0006D3500080302000803020008030200083F +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200080D2900084A +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F01F0A8FFA9 +:1002700002F024FF4FF055301F491B4A91423CBF0A +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE701F0C0FF02F05EFF1B +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E701F0A8BF00060120002201209D +:1002F0000000000808ED00E00000012000060120D9 +:1003000090390008002201205C2201206022012097 +:10031000882E0120000200080002000800020008E8 +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F0E4FAFEE701F0FA +:100350006DFA00DFFEE7000038B500F011FC01F097 +:10036000EFFE054601F022FF0446C8B90E4B9D4240 +:1003700018D001339D4218BF044641F2883504BFAE +:1003800001240025002001F0E5FE0CB100F076F814 +:1003900000F05EFD284600F0FDF800F06FF8F9E788 +:1003A0000025EFE70546EDE7010007B008B500F0CE +:1003B000B9FBA0F120035842584108BD07B541F2EE +:1003C0001203022101A8ADF8043000F0C9FB03B00C +:1003D0005DF804FB38B572B6302383F3118862B63A +:1003E000174803680BB101F063FB164A1448002359 +:1003F0004FF47A7101F052FB002383F31188124C01 +:10040000236813B12368013B2360636813B16368F9 +:10041000013B63600D4D2B7833B963687BB90220D3 +:1004200000F080FC322363602B78032B07D16368D4 +:100430002BB9022000F076FC4FF47A73636038BD6C +:1004400060220120D50300088023012078220120AA +:10045000084B187003280CD8DFE800F008050208E4 +:10046000022000F055BC022000F048BC024B0022E4 +:100470005A6070477822012080230120F8B5404B54 +:10048000404A1C461968013179D004339342F9D1AE +:100490006268A24273D33C4B9B6803F1006303F58F +:1004A000C0339A426BD2002000F084FB0220FFF799 +:1004B000CFFF364B00211A6C19641A6E19661A6E3A +:1004C0005A6C59645A6E59665A6E5A6942F08002E3 +:1004D0005A615A6922F080025A615A691A6942F0D7 +:1004E00000521A611A6922F000521A611B6972B631 +:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 +:10050000BFF36F8F224AC2F88410BFF34F8F536935 +:1005100023F480335361BFF34F8FD2F88030C3F39D +:10052000C905C3F34E335B0143F6E07603EA060CDC +:1005300029464CEA81770139C2F87472F9D2203B1E +:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 +:100550004F8FBFF36F8F536923F400335361002330 +:10056000C2F85032BFF34F8FBFF36F8F72B6302394 +:1005700083F3118862B6854680F308882047F8BD6A +:10058000008001082080010800220120003802407C +:1005900000ED00E02DE9F04F93B0B64B0090202223 +:1005A000FF210AA89D6800F0FDFBB34A1378B3B998 +:1005B000B24801211170036072B6302383F31188B1 +:1005C00062B603680BB101F073FAAD4AAB48002381 +:1005D0004FF47A7101F062FA002383F31188009BD3 +:1005E00013B1A84B009A1A60A74A009C1378032BFA +:1005F0001EBF00231370A34A4FF0000A18BF5360B8 +:10060000D3465646D146012000F082FB24B19D4BD3 +:100610001B68002B00F02782002000F083FA039073 +:10062000039B002BF2DB012000F068FB039B213BC6 +:100630001F2BE8D801A252F823F000BFBD06000826 +:10064000E506000879070008070600080706000805 +:10065000070600080B080008DB090008F508000879 +:10066000570900087F090008A509000807060008C7 +:10067000B709000807060008290A00085D070008F6 +:10068000070600086D0A0008C90600085D07000893 +:1006900007060008570900080706000807060008B3 +:1006A00007060008070600080706000807060008F6 +:1006B0000706000807060008790700080220FFF770 +:1006C00075FE002840F0F981009B0221BAF1000F6D +:1006D00008BF1C4605A841F21233ADF8143000F0F3 +:1006E0003FFA90E74FF47A7000F01CFA071EEBDB3C +:1006F0000220FFF75BFE0028E6D0013F052F00F245 +:10070000DE81DFE807F0030A0D1013360523059399 +:10071000042105A800F024FA17E056480421F9E75F +:100720005A480421F6E75A480421F3E74FF01C0821 +:10073000404600F041FA08F104080590042105A89C +:1007400000F00EFAB8F12C0FF2D1012000FA07F7F1 +:1007500047EA0B0B5FFA8BFB4FF0000900F06EFBD2 +:1007600026B10BF00B030B2B08BF0024FFF726FE6E +:1007700049E748480421CDE7002EA5D00BF00B0334 +:100780000B2BA1D10220FFF711FE074600289BD0BA +:10079000012000F00FFA0220FFF75AFE00261FFA90 +:1007A00086F8404600F016FA0446B0B10399A1F16C +:1007B000400251425141404600F01CFA01360028E7 +:1007C000EDD1BA46044641F21213022105A8ADF854 +:1007D00014303E4600F0C4F915E70120FFF738FE5B +:1007E0002546244B9B68AB4207D9284600F0E4F924 +:1007F000013040F067810435F3E7234B00251D707D +:10080000204BBA465D603E46A8E7002E3FF45CAF41 +:100810000BF00B030B2B7FF457AF0220FFF718FEF2 +:10082000322000F07FF9B0F10008FFF64DAF18F06C +:1008300003077FF449AF0F4A926808EB0503934220 +:100840003FF642AFB8F5807F3FF73EAF124B0193C2 +:10085000B84523DD4FF47A7000F064F90390039AF1 +:10086000002AFFF631AF019B039A03F8012B0137F1 +:10087000EDE700BF002201207C230120602201203F +:10088000D5030008802301207822012004220120C2 +:10089000082201200C2201207C220120C820FFF721 +:1008A00085FD074600283FF40FAF1F2D11D8C5F175 +:1008B000200242450AAB25F0030028BF4246834987 +:1008C0000192184400F048FA019A8048FF2100F094 +:1008D00069FA4FEAA8037D490193C8F387022846C5 +:1008E00000F068FA064600283FF46DAF019B05EB67 +:1008F000830533E70220FFF759FD00283FF4E4AEFB +:1009000000F0A4F900283FF4DFAE0027B846704B92 +:100910009B68BB4218D91F2F11D80A9B01330ED0F8 +:1009200027F0030312AA134453F8203C05934046D2 +:10093000042205A900F0B6FA04378046E7E73846F6 +:1009400000F03AF90590F2E7CDF81480042105A8EB +:1009500000F006F902E70023642104A8049300F0E4 +:10096000F5F800287FF4B0AE0220FFF71FFD002845 +:100970003FF4AAAE049800F051F90590E6E7002391 +:10098000642104A8049300F0E1F800287FF49CAEF1 +:100990000220FFF70BFD00283FF496AE049800F00C +:1009A0004DF9EAE70220FFF701FD00283FF48CAE85 +:1009B00000F05CF9E1E70220FFF7F8FC00283FF4C3 +:1009C00083AE05A9142000F057F9042107460490CE +:1009D00004A800F0C5F83946B9E7322000F0A2F8C3 +:1009E000071EFFF671AEBB077FF46EAE384A926801 +:1009F00007EB090393423FF667AE0220FFF7D6FCF0 +:100A000000283FF461AE27F003074F44B9453FF497 +:100A1000A5AE484600F0D0F80421059005A800F0E6 +:100A20009FF809F10409F1E74FF47A70FFF7BEFC73 +:100A300000283FF449AE00F009F9002844D00A9B91 +:100A400001330BD008220AA9002000F0B3F90028D6 +:100A50003AD02022FF210AA800F0A4F9FFF7AEFC4B +:100A60001C4800F05FFF13B0BDE8F08F002E3FF48C +:100A70002BAE0BF00B030B2B7FF426AE002364216F +:100A800005A8059300F062F8074600287FF41CAE25 +:100A90000220FFF78BFC804600283FF415AEFFF7DD +:100AA0008DFC41F2883000F03DFF059800F0F8F928 +:100AB000464600F0C3F93C46A5E506464EE64FF033 +:100AC000000901E6BA467EE637467CE67C22012034 +:100AD00000220120A086010070B50F4B1B78013366 +:100AE000DBB2012B0C4611D80C4D29684FF47A73F8 +:100AF0000E6AA2FB0332014622462846B0478442D2 +:100B000004D1074B00221A70012070BD4FF4FA7017 +:100B100000F008FF0020F8E710220120282601201D +:100B2000B423012007B50023024601210DF107007F +:100B30008DF80730FFF7D0FF20B19DF8070003B014 +:100B40005DF804FB4FF0FF30F9E700000A4608B5F6 +:100B50000421FFF7C1FF80F00100C0B2404208BD90 +:100B600030B4054C2368DD69044B0A46AC460146A7 +:100B7000204630BC604700BF28260120A086010027 +:100B800070B501F0E3F9094E094D30800024286862 +:100B90003388834208D901F0D3F92B680444013328 +:100BA000B4F5C03F2B60F2D370BD00BFB623012067 +:100BB0008823012001F078BA00F1006000F5C03010 +:100BC0000068704700F10060920000F5C03001F04D +:100BD00003BA0000054B1A68054B1B889B1A834219 +:100BE00002D9104401F0ACB90020704788230120DD +:100BF000B623012038B5084D044629B128682044A1 +:100C0000BDE8384001F0BCB92868204401F0A0F9E3 +:100C10000028F3D038BD00BF8823012010F0030363 +:100C200009D1B0F5846F04D200F10050A0F5712015 +:100C30000368184670470023FBE7000000F10050EE +:100C4000A0F57120D0F8200470470000064991F803 +:100C5000243033B10023086A81F824300822FFF7DA +:100C6000B1BF0120704700BF8C230120014B1868E1 +:100C7000704700BF002004E0F0B51E4B1D6801382E +:100C80002E0C0A181C48C5F30B04032335460788AD +:100C9000A7420BD144680B46013C934218461BD235 +:100CA00014F9010F48B103F8010BF6E7013B00F11D +:100CB0000800ECD191420ED20B4618462C24B6F512 +:100CC000805F00F8014B0AD1824202D94122981C70 +:100CD0005A70401AF0BD0846B6F5805FF9D041F26F +:100CE00001039D42F5D18242F3D95A2300F8013B1A +:100CF000EFE700BF002004E014220120022802BF19 +:100D0000024B4FF000729A61704700BF000802402A +:100D1000022802BF024B4FF400729A61704700BF75 +:100D200000080240022801BF024A536983F400739D +:100D3000536170470008024070B504464FF47A765C +:100D40004CB1412C254628BF412506FB05F000F09B +:100D5000E9FD641BF4E770BD10B50023934203D096 +:100D6000CC5CC4540133F9E710BD000010B5013864 +:100D700010F9013F3BB191F900409C4203D11AB1F7 +:100D80000131013AF4E71AB191F90020981A10BD27 +:100D90001046FCE703460246D01A12F9011B00294F +:100DA000FAD1704702440346934202D003F8011B74 +:100DB000FAE770472DE9F8431F4D144695F82420B3 +:100DC0000746884652BBDFF870909CB395F82430F4 +:100DD0002BB92022FF2148462F62FFF7E3FF95F849 +:100DE0002400C0F10802A24228BF2246D6B24146E2 +:100DF000920005EB8000FFF7AFFF95F82430A41BAD +:100E00001E44F6B2082E17449044E4B285F82460DC +:100E1000DBD1FFF71BFF0028D7D108E02B6A03EBDB +:100E200082038342CFD0FFF711FF0028CBD10020EF +:100E3000BDE8F8830120FBE78C230120024B1A78E0 +:100E4000024B1A70704700BFB4230120102201200A +:100E500010B5104C104800F0BBF821460E4800F0C9 +:100E6000E3F82468E26ED2F8043843F00203C2F8D3 +:100E700004384FF47A70FFF75FFF0849204600F00E +:100E8000E1F9E26ED2F8043823F00203C2F8043824 +:100E900010BD00BF58370008282601206037000821 +:100EA0007047000030B5094D0A4491420DD011F849 +:100EB000013B5840082340F30004013B2C4013F051 +:100EC000FF0384EA5000F6D1EFE730BD2083B8ED90 +:100ED00072B6302383F3118862B6704702684368A4 +:100EE0001143016003B118477047000013B5446B0C +:100EF000D4F894341A681178042915D1217C022978 +:100F000012D11979128901238B4013420CD101A906 +:100F100004F14C0001F090FFD4F89444019B217936 +:100F20000246206800F0DAF902B010BD143001F07A +:100F300015BF00004FF0FF33143001F00FBF000069 +:100F40004C3001F0E5BF00004FF0FF334C3001F0B2 +:100F5000DFBF0000143001F0E5BE00004FF0FF31AC +:100F6000143001F0DFBE00004C3001F0B1BF0000D2 +:100F70004FF0FF324C3001F0ABBF00000020704753 +:100F800010B5D0F894341A6811780429044617D1A2 +:100F9000017C022914D15979528901238B401342D3 +:100FA0000ED1143001F078FE024648B1D4F89444D2 +:100FB0004FF4807361792068BDE8104000F07CB97F +:100FC00010BD0000406BFFF7DBBF00007047000062 +:100FD0007FB5124B036000234360C0E90233012553 +:100FE00002260F4B057404460290019300F184021F +:100FF000294600964FF48073143001F029FE094B06 +:101000000294CDE9006304F523724FF480732946FE +:1010100004F14C0001F0ECFE04B070BDAC360008E9 +:10102000C50F0008ED0E000808B50A68FFF750FF6D +:101030000B7902EB830318624B790D3342F82300DE +:101040008B7913B102EB830210620223C0F894146F +:101050000374002080F3118808BD000038B5037FB9 +:10106000044613B190F85430ABB9201D012502217C +:10107000FFF734FF04F1140025776FF0010100F051 +:1010800079FC84F8545004F14C006FF00101BDE884 +:10109000384000F06FBC38BD10B501210446043063 +:1010A000FFF71CFF0023237784F8543010BD0000A5 +:1010B00038B504460025143001F0E2FD04F14C007F +:1010C000257701F0ADFE201D84F854500121FFF773 +:1010D00005FF2046BDE83840FFF752BF90F85C306E +:1010E00003F06003202B07D190F85D20212A4FF0F8 +:1010F000000303D81F2A06D800207047222AFBD1FC +:10110000C0E9143303E0034A0265072242658365A0 +:10111000012070472C22012037B5D0F894341A688A +:101120001178042904461AD1017C022917D11979B2 +:10113000128901238B40134211D100F14C0528463E +:1011400001F02CFF58B101A9284601F075FED4F832 +:101150009444019B21790246206800F0BFF803B057 +:1011600030BD0000F0B500EB810385B01E6A044677 +:101170000D46F6B104EB8507301D0821FFF7A8FEE8 +:10118000FFF7ACFEFB685B691B6806F14C001BB106 +:10119000019001F05FFE019803A901F04DFE0246A7 +:1011A00048B1039B2946204600F098F8002383F3BA +:1011B000118805B0F0BDFB685A691268002AF5D0A5 +:1011C0001B8A013B1340F1D104F15C02EAE7000005 +:1011D0000D3138B550F82140D4B1FFF779FED4F87D +:1011E00094241368527903EB8203DB689B695D6882 +:1011F00045B104216018FFF771FE294604F114007F +:1012000001F054FD2046FFF7BBFE002383F3118855 +:1012100038BD00007047000072B6302383F3118898 +:1012200062B6704701F08EB810B50123044628223B +:1012300000F8243B0021FFF7B5FD0023C4E901338A +:1012400010BD000038B50025FFF7E6FF0446C0E9F1 +:101250000355C0E90555C0E90755416001F082F822 +:101260000223237085F31188284638BD70B500EB42 +:10127000810305465069DA600E46144618B1102203 +:101280000021FFF78FFDA06918B110220021FFF7A0 +:1012900089FD31462846BDE8704001F02DB90000B7 +:1012A000826802F0011282600022C0E90422C0E9D3 +:1012B0000622026201F0ACB9F0B400EB8104478968 +:1012C000E4680125A4698D403D43458123600023E6 +:1012D000A2606360F0BC01F0C7B90000F0B400EB9D +:1012E00081040789E468012564698D403D430581D7 +:1012F00023600023A2606360F0BC01F043BA0000E9 +:1013000070B50223002504460370C0E90255C0E908 +:101310000455C0E906554566056280F84C5001F059 +:1013200087F863681B6823B129462046BDE87040F2 +:10133000184770BD0378052B10B504460AD080F815 +:1013400068300523037043681B680BB1042198477C +:101350000023A36010BD00000178052906D190F894 +:101360006820436802701B6803B11847704700008B +:1013700070B590F84C30044613B1002380F84C301F +:1013800004F15C02204601F065F963689B68B3B91B +:1013900094F85C3013F0600533D00021204601F052 +:1013A0001DFC0021204601F00FFC63681B6813B18F +:1013B000062120469847062384F84C3070BD20460D +:1013C00098470028E4D0B4F86230626D9A4288BF32 +:1013D000636594F95C30656D002B80F20281002D0D +:1013E00000F0F180092384F84C30FFF715FF00214D +:1013F000D4E914232046FFF771FF002383F31188FB +:10140000DCE794F85D2003F07F0343EA022340F217 +:101410000232934200F0C48021D8B3F5807F48D0D7 +:101420000DD8012B3FD0022B00F09280002BB4D1BD +:1014300004F16402226502226265A365C3E7B3F585 +:10144000817F00F09A80B3F5407FA6D194F85E309A +:10145000012BA2D1B4F8643043F0020332E0B3F5BB +:10146000006F4DD017D8B3F5A06F31D0A3F5C0638E +:10147000012B92D8636894F85E205E6894F85F1040 +:10148000B4F860302046B047002886D04368236512 +:10149000036863651AE0B3F5106F36D040F6024278 +:1014A00093427FF47AAF5B4B23650223636500238D +:1014B000C3E794F85E30012B7FF46FAFB4F864306B +:1014C00023F00203C4E91455A4F86430A5657AE753 +:1014D000B4F85C30B3F5A06F0ED194F85E3084F8A8 +:1014E0006630204600F0FCFF63681B6813B10121E1 +:1014F00020469847032323700023C4E914339CE754 +:1015000004F1670323650123C3E72378042B0FD17C +:101510002046FFF781FEFFF7C3FE85F31188032104 +:10152000636884F8675021701B680BB120469847A8 +:1015300094F85E30002BDFD084F8673004232370EA +:1015400063681B68002BD7D0022120469847D3E759 +:1015500094F860301D0603F00F0120460AD501F013 +:101560006BF8012804D002287FF417AF2A4B9BE7C1 +:101570002A4B99E701F052F8F3E794F85E30002B1C +:101580007FF40BAF94F8603013F00F01B4D01A065B +:10159000204602D501F036FBAEE701F029FBABE7B0 +:1015A00094F85E30002B7FF4F8AE94F8603013F0BE +:1015B0000F01A1D01B06204602D501F00FFB9BE7CF +:1015C00001F002FB98E7142384F84C30FFF724FE67 +:1015D0002A462B4629462046FFF76EFE85F31188E2 +:1015E000ECE65DB1152384F84C30FFF715FE0021C1 +:1015F000D4E914232046FFF75FFEFEE60B2384F8B0 +:101600004C30FFF709FE2A462B4629462046FFF7B5 +:1016100065FEE3E7DC360008D4360008D83600085B +:1016200038B590F84C300446002B3CD0063BDAB27B +:101630000F2A32D80F2B30D8DFE803F0352F2F08D0 +:1016400021302F2F2F2F2F2F2F2F3535456DB0F80D +:1016500062309D4213D2C3681B8AB5FBF3F203FBD1 +:10166000125565B9FFF7D8FD2A462B462946FFF7E4 +:1016700035FE85F311880A2384F84C300DE01423DD +:1016800084F84C30FFF7C8FD00231A46194620465F +:10169000FFF712FE002383F3118838BD836D03B179 +:1016A00098470023E8E70021204601F097FA00213F +:1016B000204601F089FA63681B6813B106212046B1 +:1016C00098470623D8E7000010B590F84C30142B4B +:1016D000044628D017D8062B05D001D81BB110BD61 +:1016E000093B022BFBD80021204601F077FA0021AC +:1016F000204601F069FA63681B6813B10621204691 +:101700009847062318E0152BE9D10B2380F84C30BD +:10171000FFF782FD00231A461946FFF7DFFD00237D +:1017200083F31188DBE7C3689B695B68002BD6D124 +:10173000836D03B19847002384F84C30CFE7000055 +:1017400000230375826803691B6899689142FBD284 +:101750005A68036042601060586070470023037548 +:10176000826803691B6899689142FBD85A680360D4 +:10177000426010605860704708B5084672B6302362 +:1017800083F3118862B60B7D032B05D0042B0DD09B +:101790002BB983F3118808BD8B6900221A604FF0C2 +:1017A000FF338361FFF7CCFF0023F2E7D1E900327A +:1017B00013605A60F3E70000FFF7C2BF054BD9681A +:1017C0000875186802681A60536001220275D860B3 +:1017D000FEF7A8BDB823012030B50C4BDD684B1CCB +:1017E00087B004460FD02B46094A684600F056F9E8 +:1017F0002046FFF7E3FF009B13B1684600F058F95D +:10180000A86907B030BDFFF7D9FFF9E7B823012079 +:1018100079170008044B1A68DB6890689B68984247 +:1018200094BF002001207047B8230120084B10B559 +:101830001C68D86822681A60536001222275DC6037 +:10184000FFF78CFF01462046BDE81040FEF76ABD59 +:10185000B823012038B5074C074908480123002563 +:101860002370656001F0D2FB0223237085F3118899 +:1018700038BD00BF20260120E4360008B82301202F +:1018800000F04CB9034A516853685B1A9842FBD880 +:10189000704700BF001000E072B6302383F3118858 +:1018A00062B670478B60022308618B8208467047DE +:1018B0008368A3F1840243F8142C026943F8442C92 +:1018C000426943F8402C094A43F8242CC26843F883 +:1018D000182C022203F80C2C002203F80B2C044ACB +:1018E00043F8102CA3F12000704700BF3D0300080F +:1018F000B823012008B5FFF7DBFFBDE80840FFF77C +:101900005BBF0000024BDB6898610F20FFF756BFFA +:10191000B823012008B5FFF7BFFFBDE80840FFF777 +:10192000F1BF000008B501460820FFF7B5FFFFF73B +:1019300053FF002383F3118808BD0000064BDB68CA +:1019400039B1426818605A60136043600420FFF7A1 +:1019500043BF4FF0FF307047B8230120036898421F +:1019600006D01A680260506099611846FFF724BFDC +:101970007047000038B504460D462068844200D107 +:1019800038BD036823605C608561FFF715FFF4E7ED +:1019900010B503689C68A2420CD85C688A600B6032 +:1019A0004C602160596099688A1A9A604FF0FF3341 +:1019B000836010BD1B68121BECE700000A2938BFCA +:1019C0000A2170B504460D460A26601901F018FB7D +:1019D00001F004FB041BA54203D8751C2E460446E7 +:1019E000F3E70A2E04D9BDE87040012001F04EBB98 +:1019F00070BD0000F8B5144B0D46D96103F110011C +:101A000041600A2A1969826038BF0A220160486071 +:101A10001861A818144601F0E5FA0A2701F0DEFA69 +:101A2000431BA342064606D37C1C281901F0E8FAA2 +:101A300027463546F2E70A2F04D9BDE8F8400120D1 +:101A400001F024BBF8BD00BFB8230120F8B506465D +:101A50000D4601F0C3FA0F4A134653F8107F9F4218 +:101A600006D12A4601463046BDE8F840FFF7C2BF1E +:101A7000D169BB68441A2C1928BF2C46A34202D94D +:101A80002946FFF79BFF224631460348BDE8F84050 +:101A9000FFF77EBFB8230120C823012010B4C0E99E +:101AA000032300235DF8044B4361FFF7CFBF000021 +:101AB00010B5194C236998420DD0D0E900328168E5 +:101AC00013605A609A680A449A60002303604FF0DA +:101AD000FF33A36110BD2346026843F8102F536003 +:101AE0000022026022699A4203D1BDE8104001F051 +:101AF00081BA936881680B44936001F06FFA2269A0 +:101B0000E1699268441AA242E4D91144BDE8104048 +:101B1000091AFFF753BF00BFB82301202DE9F04792 +:101B2000DFF8C08008F110072D4ED8F8105001F0F2 +:101B300055FAD8F81C40AA68031B9A4240D81444AE +:101B4000D5E900324FF00009C8F81C4013605A6014 +:101B5000C5F80090D8F81030B34201D101F04AFA2C +:101B600089F31188D5E903312846984772B63023A6 +:101B700083F3118862B66B69002BD6D001F02EFA80 +:101B80006A69A0EB04094A4582460DD2022001F0A1 +:101B90007DFA0022D8F81030B34208D151462846C9 +:101BA000BDE8F047FFF726BF121A2244F2E712EB16 +:101BB000090938BF4A4629463846FFF7E9FEB3E728 +:101BC000D8F81030B34208D01444211AC8F81C00C9 +:101BD000A960BDE8F047FFF7F1BEBDE8F08700BFA0 +:101BE000C8230120B823012000207047FEE7000031 +:101BF000704700004FF0FF307047000072B630238E +:101C000083F3118862B6704702290CD0032904D0EF +:101C10000129074818BF00207047032A05D8054846 +:101C200000EBC2007047044870470020704700BFB7 +:101C3000BC3700083C2201207037000870B59AB00C +:101C40000546084601A9144600F0BEF801A8FFF7B2 +:101C5000A1F8431C5B00C5E9003400222370032374 +:101C60006370C6B201AB02341046D1B28E4204F1A9 +:101C7000020401D81AB070BD13F8011B04F8021C4D +:101C800004F8010C0132F0E708B50448FFF7B6FF8D +:101C9000FFF742FA002383F3118808BD28260120AC +:101CA00090F85C3003F01F02012A07D190F85D2004 +:101CB0000B2A03D10023C0E9143315E003F06003BD +:101CC000202B08D1B0F860302BB990F85D20212A84 +:101CD00003D81F2A04D8FFF701BA222AEBD0FAE76B +:101CE000034A02650722426583650120704700BFF1 +:101CF0003322012007B5052916D8DFE801F01815B1 +:101D00000318181E104A0121FFF778FF0190FFF712 +:101D1000ADFA01980D4A0221FFF7A8FA0C48FFF727 +:101D2000C7F9002383F3118803B05DF804FB08486A +:101D3000FFF764FFFFF792F9F3E70548FFF75EFF4F +:101D4000FFF7AAF9EDE700BF1037000834370008A5 +:101D50002826012038B50C4D0C4C0D492A4604F1BB +:101D60000800FFF76BFF05F1CA0204F110000949F2 +:101D7000FFF764FF05F5CA7204F118000649BDE8D3 +:101D80003840FFF75BBF00BFF02A01203C22012052 +:101D9000F0360008FA3600080537000870B504462A +:101DA00008460D46FEF7F6FFC6B22046013403781A +:101DB0000BB9184670BD32462946FEF7D7FF0028FA +:101DC000F3D10120F6E700002DE9F84F05460C4657 +:101DD000FEF7E0FF2B49C6B22846FFF7DFFF08B148 +:101DE0000236F6B228492846FFF7D8FF08B1103668 +:101DF000F6B2632E0DD8DFF88C80DFF88C90234F7D +:101E0000DFF890A0DFF890B02E7846B92670BDE8D4 +:101E1000F88F29462046BDE8F84F01F029BC252E51 +:101E20002BD1072241462846FEF7A0FF58B9DBF820 +:101E300000302360DBF8043063609BF808302372C5 +:101E400007350934E0E7082249462846FEF78EFFA9 +:101E500098B90F4BA21C197809090232C95D02F822 +:101E6000041C13F8011B01F00F015345C95D02F872 +:101E7000031CF0D118340835C6E704F8016B0135AE +:101E8000C2E700BFDC37000805370008EE3700085E +:101E900020F4F01F2CF4F01FE4370008BFF34F8F3D +:101EA000024AD368DB03FCD4704700BF003C024009 +:101EB00008B5074B1B7853B9FFF7F0FF054B1A69BC +:101EC000002ABFBF044A5A6002F188325A6008BD36 +:101ED0004E2D0120003C02402301674508B5054B0B +:101EE0001B7833B9FFF7DAFF034A136943F0004365 +:101EF000136108BD4E2D0120003C02400728F0B5BB +:101F000016D80C4C0C4923787BB90C4D0E4608238F +:101F10004FF0006255F8047B46F8042B013B13F0A8 +:101F2000FF033A44F6D10123237051F82000F0BD9D +:101F30000020FCE7702D0120502D01200038000802 +:101F4000014B53F820007047003800080820704704 +:101F5000072810B5044601D9002010BDFFF7CEFFB9 +:101F6000064B53F824301844C21A0BB90120F4E789 +:101F700012680132F0D1043BF6E700BF00380008D8 +:101F8000072810B5044621D8FFF788FFFFF790FF18 +:101F90000F4AF323D360C300DBB243F4007343F072 +:101FA00002031361136943F480331361FFF776FF73 +:101FB000FFF7A4FF074B53F8241000F0D9F8FFF700 +:101FC0008DFF2046BDE81040FFF7C2BF002010BDC6 +:101FD000003C024000380008F8B512F00103144636 +:101FE00042D18218B2F1016F57D82D4B1B6813F004 +:101FF000010352D02B4DFFF75BFFF323EB60FFF79C +:102000004DFF40F20127032C15D824F00104661877 +:10201000244C401A40F20117B142236900EB01053C +:1020200024D123F001032361FFF758FF0120F8BDFD +:10203000043C0430E7E78307E7D12B6923F44073BE +:102040002B612B693B432B6151F8046B0660BFF396 +:102050004F8FFFF723FF03689E42E9D02B6923F0DF +:1020600001032B61FFF73AFF0020E0E723F4407300 +:10207000236123693B4323610B882B80BFF34F8F80 +:10208000FFF70CFF2D8831F8023BADB2AB42C3D055 +:10209000236923F001032361E4E71846C7E700BF83 +:1020A00000380240003C0240084908B50B7828B1CE +:1020B0001BB9FFF7FDFE01230B7008BD002BFCD000 +:1020C000BDE808400870FFF709BF00BF4E2D012092 +:1020D00010B50244064BD2B2904200D110BD441C50 +:1020E00000B253F8200041F8040BE0B2F4E700BF5F +:1020F000502800400F4B30B51C6F240407D41C6FD0 +:1021000044F400741C671C6F44F400441C670A4CC0 +:10211000236843F4807323600244084BD2B2904298 +:1021200000D130BD441C00B251F8045B43F820508C +:10213000E0B2F4E700380240007000405028004050 +:1021400007B5012201A90020FFF7C2FF019803B0E3 +:102150005DF804FB13B50446FFF7F2FFA04205D07B +:10216000012201A900200194FFF7C4FF02B010BDB5 +:102170000144BFF34F8F064B884204D3BFF34F8F08 +:10218000BFF36F8F7047C3F85C022030F4E700BFE5 +:1021900000ED00E0034B1A681AB9034AD2F874281C +:1021A0001A607047742D01200030024008B5FFF717 +:1021B000F1FF024B1868C0F3407008BD742D012078 +:1021C00070B5BFF34F8FBFF36F8F1A4A0021C2F86B +:1021D0005012BFF34F8FBFF36F8F536943F4003337 +:1021E0005361BFF34F8FBFF36F8FC2F88410BFF3FB +:1021F0004F8FD2F88030C3F3C900C3F34E335B0175 +:1022000043F6E07403EA0406014646EA81750139A3 +:10221000C2F86052F9D2203B13F1200FF2D1BFF384 +:102220004F8F536943F480335361BFF34F8FBFF334 +:102230006F8F70BD00ED00E0FEE7000070B5214B30 +:102240002148224A904237D3214BDA1C121AC11E70 +:1022500022F003028B4238BF00220021FEF7A2FDCC +:102260001C4A0023C2F88430BFF34F8FD2F880306D +:10227000C3F3C900C3F34E335B0143F6E07403EAD2 +:102280000406014646EA81750139C2F86C52F9D25A +:10229000203B13F1200FF2D1BFF34F8FBFF36F8FAD +:1022A000BFF34F8FBFF36F8F0023C2F85032BFF3DD +:1022B0004F8FBFF36F8F70BD53F8041B40F8041BA2 +:1022C000C0E700BFEC390008882E0120882E0120CD +:1022D000882E012000ED00E070B5D0E91B439E6818 +:1022E00000224FF0FF3504EB42135101D3F80009EF +:1022F0000028BEBFD3F8000940F08040C3F80009B1 +:10230000D3F8000B0028BEBFD3F8000B40F080408C +:10231000C3F8000B013263189642C3F80859C3F89A +:10232000085BE0D24FF00113C4F81C3870BD000008 +:10233000890141F02001016103699B06FCD4122050 +:10234000FFF7A0BA10B5054C2046FEF76DFF4FF021 +:10235000A043E366024B236710BD00BF782D012028 +:102360004438000870B50378012B054650D12A4B3C +:10237000C46E98421BD1294B5A6B42F080025A63BB +:102380005A6D42F080025A655A6D5A6942F08002D5 +:102390005A615A6922F080025A610E2143205B691A +:1023A00000F03AFC1E4BE3601E4BC4F800380023DB +:1023B000C4F8003EC0232360EE6E4FF40413A36301 +:1023C0003369002BFCDA012333610C20FFF75AFA42 +:1023D0003369DB07FCD41220FFF754FA3369002B72 +:1023E000FCDA0026A6602846FFF776FF6B68C4F883 +:1023F0001068DB68C4F81468C4F81C684BB90A4B51 +:10240000A3614FF0FF336361A36843F00103A3604E +:1024100070BD064BF4E700BF782D01200038024064 +:102420004014004003002002003C30C0083C30C093 +:10243000F8B5C46E054600212046FFF779FF296FE5 +:1024400000234FF001128F68C4F834384FF0006653 +:10245000C4F81C284FF0FF3004EB431201339F42B5 +:10246000C2F80069C2F8006BC2F80809C2F8080B8C +:10247000F2D20B68EA6E6B67636210231361166910 +:1024800016F01006FBD11220FFF7FCF9D4F8003843 +:1024900023F4FE63C4F80038A36943F4402343F0F7 +:1024A0001003A3610923C4F81038C4F814380A4B88 +:1024B000EB604FF0C043C4F8103B084BC4F8003B3E +:1024C000C4F81069C4F800396B6F03F1100243F4CB +:1024D00080136A67A362F8BD2038000840800010AE +:1024E000C26E90F86610D2F8003823F4FE6343EA17 +:1024F0000113C2F8003870472DE9F84300EB81035F +:10250000C56EDA68166806F00306731E022B05EB2B +:1025100041130C4680460FFA81F94FEA41104FF003 +:102520000001C3F8101B4FF0010104F1100398BF24 +:10253000B60401FA03F391698EBF334E06F180565B +:1025400006F5004600293AD0578A04F1580149019E +:1025500037436F50D5F81C180B43C5F81C382B189F +:102560000021C3F8101953690127611EA7409BB3CE +:10257000138A928B9B08012A88BF5343D8F8742092 +:10258000981842EA034301F1400205EB8202C8F8C1 +:102590007400214653602846FFF7CAFE08EB890005 +:1025A000C3681B8A43EA8453483464011E432E5196 +:1025B000D5F81C381F43C5F81C78BDE8F88305EB37 +:1025C0004917D7F8001B21F40041C7F8001BD5F8C4 +:1025D0001C1821EA0303C0E704F13F0305EB830362 +:1025E0000A4A5A6028462146FFF7A2FE05EB491029 +:1025F000D0F8003923F40043C0F80039D5F81C386E +:1026000023EA0707D7E700BF00800010000400029C +:10261000026F12684267FFF75FBE00005831C36E59 +:1026200049015B5813F4004004D013F4001F0CBFA1 +:1026300002200120704700004831C36E49015B58F9 +:1026400013F4004004D013F4001F0CBF022001203B +:102650007047000000EB8101CB68196A0B681360BA +:102660004B6853607047000000EB810330B5DD68B4 +:10267000AA691368D36019B9402B84BF4023136043 +:102680006B8A1468C26E1C44013CB4FBF3F46343D0 +:10269000033323F0030302EB411043EAC44343F046 +:1026A000C043C0F8103B2B6803F00303012B09B2B1 +:1026B0000ED1D2F8083802EB411013F4807FD0F825 +:1026C000003B14BF43F0805343F00053C0F8003B7D +:1026D00002EB4112D2F8003B43F00443C2F8003B46 +:1026E00030BD00002DE9F041254DEE6E06EB4013A4 +:1026F0000446D3F8087BC3F8087B38070AD5D6F818 +:102700001438190706D505EB84032146DB682846F3 +:102710005B689847FA0721D5D6F81438DB071DD532 +:1027200005EB8403D968DCB98B69488A5A68B2FB27 +:10273000F0F600FB16229AB91868DA6890420FD2B8 +:10274000121AC3E9002472B6302383F3118862B6EB +:102750000B482146FFF788FF84F31188BDE8F0811C +:10276000012303FA04F26B8923EA02036B81CB682D +:10277000002BF3D021460248BDE8F041184700BFC6 +:10278000782D012000EB810370B5DD68C36E6C69A4 +:102790002668E6604A0156BB1A444FF40020C2F88E +:1027A00010092A6802F00302012A0AB20ED1D3F8F6 +:1027B000080803EB421410F4807FD4F8000914BF1A +:1027C00040F0805040F00050C4F8000903EB421282 +:1027D000D2F8000940F00440C2F80009D3F83408E8 +:1027E000012202FA01F10143C3F8341870BD19B98E +:1027F000402E84BF4020206020682E8A8419013C2E +:10280000B4FBF6F440EAC44040F000501A44C6E776 +:102810002DE9F8433C4DEE6E06EB40130446D3F829 +:102820000889C3F8088918F0010F4FEA40171CD037 +:10283000D6F81038DB0718D505EB8003D9684B694B +:102840001868DA68904232D2121A4FF000091A6002 +:10285000C3F8049072B6302383F3118862B6214620 +:102860002846FFF78FFF89F3118818F0800F1CD0DE +:10287000D6F834380126A640334216D005EB84033F +:10288000ED6ED3F80CC0DCF814200134E4B2D2F8B9 +:1028900000E005EB04342F445168714515D3D5F899 +:1028A000343823EA0606C5F83468BDE8F883012306 +:1028B00003FA04F22B8923EA02032B818B68002B95 +:1028C000D3D0214628469847CFE7BCF81000AEEB9E +:1028D0000103834228BF0346D7F8180980B2B3EB3F +:1028E000800FE2D89068A0F1040959F8048FC4F869 +:1028F0000080A0EB09089844B8F1040FF5D81844FB +:102900000B4490605360C7E7782D01202DE9F74F05 +:10291000AC4CE56E6E69AB691E4016F480586E6172 +:1029200007D02046FEF7ECFC03B0BDE8F04F00F006 +:102930006BBC002E12DAD5F8003EA2489B071EBFE2 +:10294000D5F8003E23F00303C5F8003ED5F804385F +:1029500023F00103C5F80438FEF7FEFC370505D562 +:102960009848FFF7B9FC9748FEF7E4FCB0040CD593 +:10297000D5F8083813F0060FEB6823F470530CBF3A +:1029800043F4105343F4A053EB6031071BD5636845 +:10299000DB681BB9AB6923F00803AB612378052B17 +:1029A0000CD1D5F8003E87489A071EBFD5F8003EE7 +:1029B00023F00303C5F8003EFEF7CEFC6368DB6836 +:1029C0000BB180489847F30200F18980B70227D500 +:1029D000D4F86C90DFF8ECB100274FF0010A09EB56 +:1029E0004712D2F8003B03F44023B3F5802F11D1F6 +:1029F000D2F8003B002B0DDA62890AFA07F322EACB +:102A00000303638104EB8703DB68DB6813B139469A +:102A100058469847236F01379B68FFB29F42DED923 +:102A2000F00617D5E76E3A6AC2F30A1002F00F03F8 +:102A300002F4F012B2F5802F00F09980B2F5402F29 +:102A400008D104EB83030022DB681B6A07F580577B +:102A500090427ED13303D5F818481DD5E70302D53F +:102A60000020FFF73FFEA50302D50120FFF73AFE45 +:102A7000600302D50220FFF735FE210302D50320B3 +:102A8000FFF730FEE20202D50420FFF72BFEA3027F +:102A900002D50520FFF726FE77037FF545AFE60751 +:102AA00002D50020FFF7B4FEA50702D50120FFF7ED +:102AB000AFFE600702D50220FFF7AAFE210702D56C +:102AC0000320FFF7A5FEE20602D50420FFF7A0FED3 +:102AD000A3067FF529AF0520FFF79AFE24E7E36EF2 +:102AE000DFF8E0A0019300274FF00109236F9B68F6 +:102AF0005FFA87FB9B453FF669AF019B03EB4B13E6 +:102B0000D3F8001901F44021B1F5802F1FD1D3F87B +:102B1000001900291BDAD3F8001941F09041C3F8DD +:102B20000019D3F800190029FBDB5946E06EFFF7C6 +:102B3000FFFB218909FA0BF321EA0303238104EB4C +:102B40008B03DB689B6813B15946504698470137A1 +:102B5000CCE7910708BFD7F80080072A98BF03F891 +:102B6000018B02F1010298BF4FEA182870E7023387 +:102B700004EB830207F580575268D2F818C0DCF8DE +:102B80000820DCE9001CA1EB0C0C002188420AD1D2 +:102B900004EB830463689B699A6802449A605A68EC +:102BA00002445A6056E711F0030F08BFD7F80080BF +:102BB0008C4588BF02F8018B01F1010188BF4FEA03 +:102BC0001828E3E7782D0120C36E03EB4111D1F8FB +:102BD000003B43F40013C1F8003B7047C36E03EBA6 +:102BE0004111D1F8003943F40013C1F8003970479E +:102BF000C36E03EB4111D1F8003B23F40013C1F87D +:102C0000003B7047C36E03EB4111D1F8003923F448 +:102C10000013C1F80039704700F1604303F56143C8 +:102C20000901C9B283F80013012200F01F039A4082 +:102C300043099B0003F1604303F56143C3F880211E +:102C40001A60704772B6302383F3118862B67047FA +:102C500030B5039C0172043304FB0325C0E906531D +:102C6000049B03630021059BC160C0E90000C0E92B +:102C70000422C0E90842C0E90A11436330BD0000E4 +:102C8000416A0022C0E90411C0E90A22C2606FF063 +:102C90000101FEF76FBE0000D0E90432934201D17A +:102CA000C2680AB9181D704700207047036919608F +:102CB000C2680132C260C2691344826903619342EF +:102CC00024BF436A03610021FEF748BE38B50446BD +:102CD0000D46E3683BB16269131D1268A362134499 +:102CE000E362002007E0237A33B929462046FEF745 +:102CF00025FE0028EDDA38BD6FF00100FBE700008B +:102D0000C368C269013BC36043691344826943617C +:102D1000934224BF436A436100238362036B03B180 +:102D20001847704770B5FFF78DFF866A04463EB9B5 +:102D3000FFF7CCFF054618B186F31188284670BD11 +:102D4000A36AE26A13F8015BA362934202D32046AE +:102D5000FFF7D6FF002383F31188EFE72DE9F04753 +:102D60009846FFF76FFF002504460E461746A94612 +:102D7000D4F828A0BAF1000F09D141462046FFF748 +:102D8000A5FF20B18AF311882846BDE8F087D4E971 +:102D90000A12A7EB050A521A924528BF9246BAF1C9 +:102DA000400F1BD9334601F1400251F8040B43F8A0 +:102DB000040B9142F9D1A36A40334036A3624035F7 +:102DC000D4E90A239A4202D32046FFF799FF89F3F8 +:102DD0001188BD42D8D2FFF735FFC9E730465246C9 +:102DE000FDF7BAFFA36A53445644A3625544E7E78C +:102DF00010B5029C0172043303FB0421C0E90613E1 +:102E00000023C0E90A33039B0363049BC460C0E949 +:102E10000000C0E90422C0E90842436310BD00007D +:102E2000026AC260426AC0E904220022C0E90A22A2 +:102E30006FF00101FEF79EBDD0E904239A4201D153 +:102E4000C26822B9184650F8043B0B607047002353 +:102E50001846FAE7C368C2690133C3604369134483 +:102E600082694361934224BF436A43610021FEF7B4 +:102E700075BD000038B504460D46E3683BB12369D3 +:102E80001A1DA262E2691344E362002007E0237A7C +:102E900033B929462046FEF751FD0028EDDA38BD4A +:102EA0006FF00100FBE7000003691960C268013A96 +:102EB000C260C269134482690361934224BF436ABA +:102EC000036100238362036B03B11847704700005E +:102ED00070B5FFF7B7FE866A0D46044611462EB957 +:102EE000FFF7C8FF10B186F3118870BDA36A1D708B +:102EF000A36AE26A01339342A36204D3E1692046E4 +:102F00000439FFF7D1FF002080F31188EDE70000BE +:102F10002DE9F0479946FFF795FE002604460D4639 +:102F20009046B246A76A4FB949462046FFF7A2FF2E +:102F300020B187F311883046BDE8F087D4E90A074D +:102F40003A1AA8EB0607974228BF1746402F1BD90D +:102F500005F1400355F8042B40F8042B9D42F9D1AC +:102F6000A36A4033A3624036D4E90A239A4204D3C9 +:102F7000E16920460439FFF797FF8AF31188464537 +:102F8000D9D2FFF75FFECDE729463A46FDF7E4FECA +:102F9000A36A3B443D44A3623E44E5E7D0E90423F1 +:102FA0009A4217D1C3689BB1836A8BB1043B9B1AC9 +:102FB0000ED01360C368013BC360C3691A448369C0 +:102FC00002619A4224BF436A0361002383620123A2 +:102FD000184670470023FBE700F042B94FF08043EA +:102FE000586A70474FF08043002258631A610222EA +:102FF000DA6070474FF080430022DA6070470000CB +:103000004FF0804358637047FEE7000070B51B4BDC +:1030100001630025044686B0586085620E4600F0C4 +:10302000CBF804F11003C4E904334FF0FF33C4E9D3 +:103030000635C4E90044A560E562FFF7CFFF2B46E3 +:103040000246C4E9082304F134010D4A25658023B2 +:103050002046FEF727FC0123E0600A4A0375009230 +:1030600072680192B268CDE90223074B6846CDE948 +:103070000435FEF73FFC06B070BD00BF20260120DE +:10308000503800085538000809300008024AD36A51 +:103090001843D062704700BFB82301204B684360DB +:1030A0008B688360CB68C3600B6943614B690362C3 +:1030B0008B6943620B6803607047000008B52C4BB6 +:1030C0002C481A6940F2FF710A431A611A6922F406 +:1030D000FF6222F007021A611A691A6B0A431A6327 +:1030E0001A6D0A431A65244A1B6D1146FFF7D6FF75 +:1030F00002F11C0100F58060FFF7D0FF02F13801FA +:1031000000F58060FFF7CAFF02F1540100F580600E +:10311000FFF7C4FF02F1700100F58060FFF7BEFF0A +:1031200002F18C0100F58060FFF7B8FF02F1A80101 +:1031300000F58060FFF7B2FF02F1C40100F5806086 +:10314000FFF7ACFF02F1E00100F58060FFF7A6FF9A +:1031500002F1FC0100F58060FFF7A0FF02F58C7121 +:1031600000F58060FFF79AFFBDE8084000F0EEB878 +:1031700000380240000002405C38000808B500F04A +:1031800059FAFEF767FBFFF705F8BDE80840FEF7C0 +:10319000E1BD000070470000EFF3098305494A6B69 +:1031A00022F001024A63683383F30988002383F322 +:1031B0001188704700EF00E0302080F3118862B67C +:1031C0000D4B0E4AD96821F4E0610904090C0A4349 +:1031D000DA60D3F8FC200A4942F08072C3F8FC2080 +:1031E000084AC2F8B01F116841F0010111602022A5 +:1031F000DA7783F82200704700ED00E00003FA055B +:1032000055CEACC5001000E010B572B6302383F384 +:10321000118862B60E4B5B6813F4006314D0F1EEB4 +:10322000103AEFF30984683C4FF08073E361094B77 +:10323000DB6B236684F30988FEF7ECFA10B1064BCA +:10324000A36110BD054BFBE783F31188F9E700BFCD +:1032500000ED00E000EF00E04F030008520300081B +:103260000F4B1A6C42F001021A641A6E42F001020E +:103270001A660C4A1B6E936843F0010393604FF08B +:1032800080436B229A624FF0FF32DA6200229A6129 +:103290005A63DA605A6001225A611A60704700BFAF +:1032A00000380240002004E04FF0804208B5116968 +:1032B000D3680B40D9B2C9439B07116109D572B6D7 +:1032C000302383F3118862B6FEF7DAFA002383F322 +:1032D000118808BD1B4B1A696FEA42526FEA5252BD +:1032E0001A611A69C2F30A021A614FF0FF301A69B3 +:1032F0005A69586100215A6959615A691A6A62F01B +:1033000080521A621A6A02F080521A621A6A5A6A63 +:1033100058625A6A59625A6A0B4A106840F48070BF +:103320001060186F00F44070B0F5007F1EBF4FF4BE +:10333000803018671967536823F40073536000F0F6 +:1033400055B900BF0038024000700040374B4FF0C5 +:1033500080521A64364A4FF4404111601A6842F0B4 +:1033600001021A601A689207FCD59A6822F00302DB +:103370009A602E4B9A6812F00C02FBD1196801F08A +:10338000F90119609A601A6842F480321A601A686A +:103390009003FCD55A6F42F001025A67234B5A6FD3 +:1033A0009107FCD5234A5A601A6842F080721A606D +:1033B0001F4B5A685204FCD51A6842F480321A60D6 +:1033C0005A68D003FCD51A6842F400321A60184AD1 +:1033D00053689903FCD5154B1A689201FCD5164A1F +:1033E0009A6040F20112C3F88C200022C3F89020AA +:1033F000124A40F207331360136803F00F03072BE0 +:10340000FAD10A4B9A6842F002029A609A6802F076 +:103410000C02082AFAD15A6C42F480425A645A6E5D +:1034200042F480425A665B6E704700BF003802402B +:1034300000700040086C400900948838003C02404D +:10344000074A08B5536903F00103536123B1054AE4 +:1034500013680BB150689847BDE80840FFF7D4BE29 +:10346000003C0140082E0120074A08B5536903F0CB +:103470000203536123B1054A93680BB1D0689847A2 +:10348000BDE80840FFF7C0BE003C0140082E012007 +:10349000074A08B5536903F00403536123B1054A91 +:1034A00013690BB150699847BDE80840FFF7ACBEFF +:1034B000003C0140082E0120074A08B5536903F07B +:1034C0000803536123B1054A93690BB1D06998474A +:1034D000BDE80840FFF798BE003C0140082E0120DF +:1034E000074A08B5536903F01003536123B1054A35 +:1034F000136A0BB1506A9847BDE80840FFF784BED5 +:10350000003C0140082E0120164B10B55C6904F404 +:1035100078725A61A30604D5134A936A0BB1D06A34 +:103520009847600604D5104A136B0BB1506B98474F +:10353000210604D50C4A936B0BB1D06B9847E2057A +:1035400004D5094A136C0BB1506C9847A30504D5F8 +:10355000054A936C0BB1D06C9847BDE81040FFF75B +:1035600053BE00BF003C0140082E0120194B10B58E +:103570005C6904F47C425A61620504D5164A136DF5 +:103580000BB1506D9847230504D5134A936D0BB1C9 +:10359000D06D9847E00404D50F4A136E0BB1506EFE +:1035A0009847A10404D50C4A936E0BB1D06E98478E +:1035B000620404D5084A136F0BB1506F9847230477 +:1035C00004D5054A936F0BB1D06F9847BDE8104002 +:1035D000FFF71ABE003C0140082E012008B5FFF796 +:1035E00063FEBDE80840FFF70FBE0000062108B5E6 +:1035F0000846FFF711FB06210720FFF70DFB062108 +:103600000820FFF709FB06210920FFF705FB06212B +:103610000A20FFF701FB06211720FFF7FDFA06211C +:103620002820FFF7F9FABDE8084007211C20FFF722 +:10363000F3BA000008B5FFF74DFE00F00BF8FDF7F8 +:10364000F1FDFDF7C3FCFFF7A5FDBDE80840FFF75E +:10365000C3BC00000023054A19460133102BC2E900 +:10366000001102F10802F8D1704700BF082E0120B6 +:10367000034611F8012B03F8012B002AF9D17047FA +:1036800053544D3332463F3F3F3F3F3F0053544D2D +:10369000333246375B347C355D780053544D3332DA +:1036A00046375B367C375D78000000000000000084 +:1036B000490F0008350F0008710F00085D0F000862 +:1036C000690F0008550F0008410F00082D0F000872 +:1036D0007D0F000800000000010000000000000055 +:1036E00063300000E036000810240120202601206D +:1036F0004172647550696C6F740025424F415244A9 +:10370000252D424C002553455249414C25000000CF +:10371000020000000000000065110008D11100083F +:1037200040004000C02A0120D02A012002000000F1 +:103730000000000003000000000000001512000857 +:103740000000000010000000E02A0120000000003E +:103750000100000000000000782D0120010102009E +:10376000F51C0008091C0008A11C0008891C0008A1 +:10377000430000007837000809024300020100C03E +:1037800032090400000102020100052400100105B5 +:103790002401000104240202052406000107058219 +:1037A000030800FF09040100020A000000070501E8 +:1037B00002400000070581024000000012000000E6 +:1037C000C4370008120110010200004009124157DD +:1037D00000020102030100000403090425424F41D5 +:1037E00052442500426C69747A46373435003031D2 +:1037F0003233343536373839414243444546000088 +:1038000000800000008000000080000000800000B8 +:10381000000002000000040000000400000004009A +:10382000000000007113000821160008C9160008E6 +:1038300040004000F02D0120F02D0120010000008B +:10384000002E012080000000400100000500000063 +:103850006D61696E0069646C650000000001806A3A +:1038600000000000AAAAAAAA00010064FFFF00004D +:103870000000000000A00A0000000000000000009E +:10388000AAAAAAAA00000000FFFF00000000000092 +:10389000000000000000040000000000AAAAAAAA7C +:1038A00000000000FFFD000000000000000000001C +:1038B0000000000000000000AAAAAAAA0000000060 +:1038C000FFFF0000000000000000000000010000F9 +:1038D00000000000AAAAAAAA00010000FFFF000041 +:1038E00000000000000000000000000000000000D8 +:1038F000AAAAAAAA00000000FFFF00000000000022 +:10390000000000000000000000000000AAAAAAAA0F +:1039100000000000FFFF00000000000000000000A9 +:1039200000000000000000000A000000000000008D +:103930000300000000000000000000000000000084 +:103940000000000000000000000000000000000077 +:103950000000000000000000000000000000000067 +:103960000000000000000000000000000000000057 +:103970000000000000000000000000000000000047 +:103980000000000000000000000000000000000037 +:103990008C0400000000000000800E000000000009 +:1039A000FF0000000000000080360008490400000D +:1039B0008D360008510400009B3600080096000078 +:1039C000000008009600000000080000040000004D +:1039D000D8370008000000000000000000000000D0 +:0C39E000000000000000000000000000DB +:00000001FF diff --git a/Tools/bootloaders/BlitzH743Pro_bl.bin b/Tools/bootloaders/BlitzH743Pro_bl.bin new file mode 100644 index 00000000000000..562d9aa76c5140 Binary files /dev/null and b/Tools/bootloaders/BlitzH743Pro_bl.bin differ diff --git a/Tools/bootloaders/BlitzH743Pro_bl.hex b/Tools/bootloaders/BlitzH743Pro_bl.hex new file mode 100644 index 00000000000000..5042a5393809b8 --- /dev/null +++ b/Tools/bootloaders/BlitzH743Pro_bl.hex @@ -0,0 +1,1103 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200086D2800086C +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008D93D0008053E00085D +:10006000313E00085D3E0008893E0008711000081E +:1000700099100008C5100008F11000081D110008B3 +:100080004511000871110008E3020008E3020008AE +:10009000E3020008E3020008E3020008B53E00089E +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000193F0008E3020008E3020008E3020008E9 +:1000F000E3020008E3020008E30200089D11000883 +:10010000E3020008E30200088D3F0008E302000854 +:10011000E3020008E3020008E3020008E30200082B +:10012000C9110008F11100081D1200084912000849 +:1001300075120008E3020008E3020008E302000869 +:10014000E3020008E3020008E3020008E3020008FB +:100150009D120008C9120008F5120008E302000809 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000859340008E3020008E302000823 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000845340008E3020008E3020008D7 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0F0FA84 +:1003500003F0FEFA4FF055301F491B4A91423CBF53 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F008FB03F05CFBFA +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0F0BA00060020002200207A +:1003D0000000000808ED00E00000002000060020FA +:1003E00068440008002200205C22002060220020D7 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0A4FDFEE701F056 +:1004300033FD00DFFEE7000038B500F02FFC00F0D0 +:10044000ABFD02F0D3F9054602F006FA0446C0B946 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0CAF90CB100F076 +:1004700075F800F065FD284600F01EF900F06EF8F2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F021FE0023154A4FF4D1 +:1004D0007A71134801F010FE002383F31188124C47 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F088FC322363602B78032B07D16368EB +:100510002BB9022000F07EFC4FF47A73636038BD83 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05DBC022000F050BC024B0022F3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E3FBB14AB8 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F011FD0023AB4A4FF4F0 +:1006F0007A71A94801F000FD002383F31188009B63 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F06BFB24B19C4B1B6860 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F058FB26B10BF03D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F032FA019AFF217F4800F053FA4FEAF3 +:1009F000A803C8F387027C492846019300F052FA05 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F7FA8046E7E7384600F03AF945 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09DF900283AD020228E +:100B7000FF210AA800F08EF9FFF792FC1C4801F053 +:100B8000FFF913B0BDE8F08F002E3FF42BAE0BF051 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0DDF9059800F0E4F946463C462E +:100BD00000F0ACF9A6E506464EE64FF0000901E646 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0A8F98B +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F08AFC308028683388834292 +:100CB00008D901F07FFC2B6804440133B4F5C02F40 +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F042BD00F1006000F5C02000687047DF +:100CE00000F10060920000F5C02001F0C3BC0000DC +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F058BC0020704788230020B623002043 +:100D100038B50446074D29B128682044BDE838405D +:100D200001F060BC2868204401F04AFC0028F3D0A0 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C1422002084400008022803D177 +:100DF000024B4FF080729A61704700BF00000258AA +:100E0000022803D1024B4FF480729A61704700BFF1 +:100E100000000258022804D1024A536983F4807307 +:100E2000536170470000025870B504464FF47A765B +:100E30004CB1412C254628BF412506FB05F0641B1B +:100E400001F09EF8F4E770BD002310B5934203D083 +:100E5000CC5CC4540133F9E710BD0000013810B573 +:100E600010F9013F3BB191F900409C4203D11AB106 +:100E70000131013AF4E71AB191F90020981A10BD36 +:100E80001046FCE703460246D01A12F9011B00295E +:100E9000FAD1704702440346934202D003F8011B83 +:100EA000FAE770472DE9F8431F4D14460746884678 +:100EB00095F8242052BBDFF870909CB395F824304D +:100EC0002BB92022FF2148462F62FFF7E3FF95F858 +:100ED00024004146C0F1080205EB8000A24228BF71 +:100EE0002246D6B29200FFF7AFFF95F82430A41B3C +:100EF00017441E449044E4B2F6B2082E85F82460EC +:100F0000DBD1FFF723FF0028D7D108E02B6A03EBE2 +:100F100082038342CFD0FFF719FF0028CBD10020F6 +:100F2000BDE8F8830120FBE78C230020024B1A78F0 +:100F3000024B1A70704700BFB4230020102200201B +:100F400010B5114C114800F06FFB21460F4800F01E +:100F500097FB24684FF47A70D4F89020D2F80438C4 +:100F600043F00203C2F80438FFF75EFF0849204649 +:100F700000F094FCD4F89020D2F8043823F0020357 +:100F8000C2F8043810BD00BF40420008B02600205F +:100F90004842000870470000F0B5A1B071B60023C8 +:100FA0000120002480261A46194600F04BFA4FF41F +:100FB000D067214A3D25136923BBD2F810310BBB02 +:100FC000036804F1006199600368C3F80CD00368FA +:100FD0005E6003681F6001680B6843F001030B60EB +:100FE00001680B6823F01E030B6001680B68DB07C8 +:100FF000FCD4037B8034416805FA03F3B4F5001F89 +:101000000B60D8D100F05EFAB4F5001F11D00024B7 +:101010000A4E0B4D012001F09FFB3388A34205D9F6 +:1010200028682044013401F0DDFAF6E7002001F0E1 +:1010300093FB61B621B0F0BD00200052B623002022 +:101040008823002030B50A44084D91420DD011F894 +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:1010700008B5074B074A196801F03D0199605368AC +:101080000BB190689847BDE8084001F027BC00BF4D +:1010900000000240B823002008B5084B19688909F0 +:1010A00001F03D018A019A60054AD3680BB11069CD +:1010B0009847BDE8084001F011BC00BF00000240A5 +:1010C000B823002008B5084B1968090C01F03D0150 +:1010D0000A049A60054A53690BB190699847BDE8C4 +:1010E000084001F0FBBB00BF00000240B823002015 +:1010F00008B5084B1968890D01F03D018A059A6011 +:10110000054AD3690BB1106A9847BDE8084001F061 +:10111000E5BB00BF00000240B823002008B5074B24 +:10112000074A596801F03D01D960536A0BB1906AD2 +:101130009847BDE8084001F0D1BB00BF0000024065 +:10114000B823002008B5084B5968890901F03D0112 +:101150008A01DA60054AD36A0BB1106B9847BDE883 +:10116000084001F0BBBB00BF00000240B8230020D4 +:1011700008B5084B5968090C01F03D010A04DA6012 +:10118000054A536B0BB1906B9847BDE8084001F0DE +:10119000A5BB00BF00000240B823002008B5084BE3 +:1011A0005968890D01F03D018A05DA60054AD36B63 +:1011B0000BB1106C9847BDE8084001F08FBB00BF31 +:1011C00000000240B823002008B5074B074A196801 +:1011D00001F03D019960536C0BB1906C9847BDE8EC +:1011E000084001F07BBB00BF00040240B823002090 +:1011F00008B5084B1968890901F03D018A019A6018 +:10120000054AD36C0BB1106D9847BDE8084001F05A +:1012100065BB00BF00040240B823002008B5084B9E +:101220001968090C01F03D010A049A60054A536DE2 +:101230000BB1906D9847BDE8084001F04FBB00BF6F +:1012400000040240B823002008B5084B1968890D36 +:1012500001F03D018A059A60054AD36D0BB1106E0D +:101260009847BDE8084001F039BB00BF00040240C8 +:10127000B823002008B5074B074A596801F03D0123 +:10128000D960536E0BB1906E9847BDE8084001F0ED +:1012900025BB00BF00040240B823002008B5084B5E +:1012A0005968890901F03D018A01DA60054AD36E67 +:1012B0000BB1106F9847BDE8084001F00FBB00BFAD +:1012C00000040240B823002008B5084B5968090CF7 +:1012D00001F03D010A04DA60054A536F0BB1906FCB +:1012E0009847BDE8084001F0F9BA00BF0004024089 +:1012F000B823002008B5084B5968890D01F03D015D +:101300008A05DA60054AD36F13B1D2F88000984796 +:10131000BDE8084001F0E2BA00040240B823002012 +:1013200000230C4910B51A460B4C0B6054F82300EF +:10133000026001EB430004334260402BF6D1074AC0 +:101340004FF0FF339360D360C2F80834C2F80C3416 +:1013500010BD00BFB82300209440000800000240E8 +:101360000F28F8B510D9102810D0112811D0122844 +:1013700008D10F240720DFF8C8E00126DEF800506E +:10138000A04208D9002653E00446F4E70F240020C9 +:10139000F1E70724FBE706FA00F73D424AD1264C65 +:1013A0004FEA001C3D4304EB00160EEBC000CEF8E4 +:1013B0000050C0E90123FBB273B12048D0F8D83007 +:1013C00043F00103C0F8D830D0F8003143F00103F6 +:1013D000C0F80031D0F8003117F47F4F0ED0174815 +:1013E000D0F8D83043F00203C0F8D830D0F800313C +:1013F00043F00203C0F80031D0F8003154F80C007B +:10140000036823F01F030360056815F00105FBD195 +:1014100004EB0C033D2493F80CC05F6804FA0CF451 +:101420003C6021240560446112B1987B00F054F8BF +:101430003046F8BD0130A3E794400008004402584C +:10144000B823002010B5302484F31188FFF788FFFB +:10145000002383F3118810BD10B50446807B00F093 +:1014600051F801231549627B03FA02F20B6823EA63 +:101470000203DAB20B6072B9114AD2F8D81021F027 +:101480000101C2F8D810D2F8001121F00101C2F810 +:101490000011D2F8002113F47F4F0ED1084BD3F87E +:1014A000D82022F00202C3F8D820D3F8002122F07D +:1014B0000202C3F80021D3F8003110BDB823002088 +:1014C0000044025808B5302383F31188FFF7C4FFA6 +:1014D000002383F3118808BD090100F16043012254 +:1014E00003F56143C9B283F8001300F01F039A406B +:1014F00043099B0003F1604303F56143C3F8802176 +:101500001A60704700F01F0301229A40430900F15E +:1015100060409B0000F5614003F1604303F56143C7 +:10152000C3F88020C3F88021002380F8003370477F +:10153000026843681143016003B118477047000017 +:1015400013B5406B00F58054D4F8A4381A681178AC +:10155000042914D1017C022911D11979012312899E +:101560008B4013420BD101A94C3002F0A7F8D4F8FC +:10157000A4480246019B2179206800F0DFF902B0FF +:1015800010BD0000143002F029B800004FF0FF3306 +:10159000143002F023B800004C3002F0FBB8000019 +:1015A0004FF0FF334C3002F0F5B80000143001F07A +:1015B000F7BF00004FF0FF31143001F0F1BF000021 +:1015C0004C3002F0C7B800004FF0FF324C3002F050 +:1015D000C1B800000020704710B500F58054D4F861 +:1015E000A4381A681178042917D1017C022914D172 +:1015F0005979012352898B4013420ED1143001F0E6 +:1016000089FF024648B1D4F8A4484FF44073617989 +:101610002068BDE8104000F07FB910BD406BFFF7B7 +:10162000DBBF0000704700007FB5124B0125042688 +:10163000044603600023057400F1840243602946D8 +:10164000C0E902330C4B0290143001934FF4407305 +:10165000009601F03BFF094B04F69442294604F141 +:101660004C000294CDE900634FF4407302F002F89D +:1016700004B070BD944100081D1600084115000813 +:101680000A68302383F311880B790B3342F8230067 +:101690004B79133342F823008B7913B10B3342F8A3 +:1016A000230000F58053C3F8A4180223037400201C +:1016B00080F311887047000038B5037F044613B1EA +:1016C00090F85430ABB90125201D0221FFF730FFFF +:1016D00004F114006FF00101257700F079FC04F1AA +:1016E0004C0084F854506FF00101BDE8384000F020 +:1016F0006FBC38BD10B5012104460430FFF718FF58 +:101700000023237784F8543010BD000038B5044618 +:101710000025143001F0F2FE04F14C00257701F0B1 +:10172000C1FF201D84F854500121FFF701FF20461E +:10173000BDE83840FFF750BF90F8803003F06003F9 +:10174000202B06D190F881200023212A03D81F2ABC +:1017500006D800207047222AFBD1C0E91D3303E0E0 +:10176000034A426707228267C3670120704700BFB0 +:101770002C22002037B500F58055D5F8A4381A681A +:10178000117804291AD1017C022917D11979012372 +:1017900012898B40134211D100F14C04204602F013 +:1017A00041F858B101A9204601F088FFD5F8A448B6 +:1017B0000246019B2179206800F0C0F803B030BDDB +:1017C00001F10B03F0B550F8236085B004460D46D7 +:1017D000FEB1302383F3118804EB8507301D082107 +:1017E000FFF7A6FEFB6806F14C005B691B681BB1A6 +:1017F000019001F071FF019803A901F05FFF02461B +:1018000048B1039B2946204600F098F8002383F353 +:10181000118805B0F0BDFB685A691268002AF5D03E +:101820001B8A013B1340F1D104F18002EAE700007A +:10183000133138B550F82140ECB1302383F31188CF +:1018400004F58053D3F8A4281368527903EB82037C +:10185000DB689B695D6845B104216018FFF768FE8D +:10186000294604F1140001F05FFE2046FFF7B4FEA4 +:10187000002383F3118838BD7047000001F02CB9B4 +:1018800001234022002110B5044600F8303BFFF749 +:1018900001FB0023C4E9013310BD000010B5302363 +:1018A000044683F311882422416000210C30FFF7A5 +:1018B000F1FA204601F032F902230020237080F370 +:1018C000118810BD70B500EB8103054650690E46C6 +:1018D0001446DA6018B110220021FFF7DBFAA06984 +:1018E00018B110220021FFF7D5FA31462846BDE88D +:1018F000704001F019BA000083682022002103F033 +:10190000011310B5044683601030FFF7C3FA204678 +:10191000BDE8104001F094BAF0B4012500EB810459 +:1019200047898D40E4683D43A469458123600023D5 +:10193000A2606360F0BC01F0B1BA0000F0B4012510 +:1019400000EB810407898D40E4683D4364690581AB +:1019500023600023A2606360F0BC01F027BB00009D +:1019600070B5022300250446242203702946C0F8DE +:1019700088500C3040F8045CFFF78CFA204684F85D +:10198000705001F065F963681B6823B12946204651 +:10199000BDE87040184770BD0378052B10B50446AC +:1019A0000AD080F88C300523037043681B680BB1A4 +:1019B000042198470023A36010BD00000178052989 +:1019C00006D190F88C20436802701B6803B1184759 +:1019D0007047000070B590F87030044613B10023D2 +:1019E00080F8703004F18002204601F04DFA6368FF +:1019F0009B68B3B994F8803013F0600535D00021AE +:101A0000204601F03FFD0021204601F02FFD6368D4 +:101A10001B6813B1062120469847062384F87030CE +:101A200070BD204698470028E4D0B4F88630A26FF5 +:101A30009A4288BFA36794F98030A56F002B4FF0BE +:101A4000300380F20381002D00F0F280092284F837 +:101A5000702083F3118800212046D4E91D23FFF76D +:101A60006DFF002383F31188DAE794F8812003F0F7 +:101A70007F0343EA022340F20232934200F0C58022 +:101A800021D8B3F5807F48D00DD8012B3FD0022B51 +:101A900000F09380002BB2D104F188026267022229 +:101AA000A267E367C1E7B3F5817F00F09B80B3F5E0 +:101AB000407FA4D194F88230012BA0D1B4F88830B3 +:101AC00043F0020332E0B3F5006F4DD017D8B3F501 +:101AD000A06F31D0A3F5C063012B90D86368204676 +:101AE00094F882205E6894F88310B4F88430B0478C +:101AF000002884D0436863670368A3671AE0B3F5DE +:101B0000106F36D040F6024293427FF478AF5C4BC0 +:101B100063670223A3670023C3E794F88230012B95 +:101B20007FF46DAFB4F8883023F00203A4F8883056 +:101B3000C4E91D55E56778E7B4F88030B3F5A06FC8 +:101B40000ED194F88230204684F88A3001F0DEF815 +:101B500063681B6813B10121204698470323237053 +:101B60000023C4E91D339CE704F18B036367012361 +:101B7000C3E72378042B10D1302383F31188204648 +:101B8000FFF7BAFE85F311880321636884F88B5050 +:101B900021701B680BB12046984794F88230002BC7 +:101BA000DED084F88B300423237063681B68002B1D +:101BB000D6D0022120469847D2E794F884302046B8 +:101BC0001D0603F00F010AD501F050F9012804D0D9 +:101BD00002287FF414AF2B4B9AE72B4B98E701F0C8 +:101BE00037F9F3E794F88230002B7FF408AF94F8CC +:101BF000843013F00F01B3D01A06204602D501F04D +:101C000059FCADE701F04AFCAAE794F88230002BBA +:101C10007FF4F5AE94F8843013F00F01A0D01B06CA +:101C2000204602D501F02EFC9AE701F01FFC97E751 +:101C3000142284F8702083F311882B462A46294603 +:101C40002046FFF769FE85F31188E9E65DB11522AC +:101C500084F8702083F3118800212046D4E91D23E5 +:101C6000FFF75AFEFDE60B2284F8702083F31188FB +:101C70002B462A4629462046FFF760FEE3E700BFD1 +:101C8000C4410008BC410008C041000838B590F8C4 +:101C900070300446002B3ED0063BDAB20F2A34D80F +:101CA0000F2B32D8DFE803F03731310822323131DF +:101CB0003131313131313737856FB0F886309D425F +:101CC00014D2C3681B8AB5FBF3F203FB12556DB93E +:101CD000302383F311882B462A462946FFF72EFE30 +:101CE00085F311880A2384F870300EE0142384F8F9 +:101CF0007030302383F31188002320461A4619469A +:101D0000FFF70AFE002383F3118838BDC36F03B1C8 +:101D100098470023E7E70021204601F0B3FB0021AC +:101D2000204601F0A3FB63681B6813B1062120461F +:101D300098470623D7E7000010B590F870300446A6 +:101D4000142B29D017D8062B05D001D81BB110BDF4 +:101D5000093B022BFBD80021204601F093FB002118 +:101D6000204601F083FB63681B6813B106212046FF +:101D70009847062319E0152BE9D10B2380F8703022 +:101D8000302383F3118800231A461946FFF7D6FD46 +:101D9000002383F31188DAE7C3689B695B68002B33 +:101DA000D5D1C36F03B19847002384F87030CEE7D4 +:101DB00000238268037503691B6899689142FBD20E +:101DC0005A68036042601060586070470023826860 +:101DD000037503691B6899689142FBD85A680360D0 +:101DE000426010605860704708B50846302383F39E +:101DF00011880B7D032B05D0042B0DD02BB983F359 +:101E0000118808BD8B6900221A604FF0FF3383618F +:101E1000FFF7CEFF0023F2E7D1E9003213605A60EA +:101E2000F3E70000FFF7C4BF054BD96808751868D1 +:101E3000026853601A600122D8600275FEF7E2BAA8 +:101E4000402400200C4B30B5DD684B1C87B00446A5 +:101E50000FD02B46094A684600F04EF92046FFF79E +:101E6000E3FF009B13B1684600F050F9A86907B082 +:101E700030BDFFF7D9FFF9E740240020E91D000835 +:101E8000044B1A68DB6890689B68984294BF0020F6 +:101E90000120704740240020084B10B51C68D8680A +:101EA000226853601A600122DC602275FFF78EFF02 +:101EB00001462046BDE81040FEF7A4BA40240020A9 +:101EC00038B5074C01230025064907482370656093 +:101ED00001F0E6FC0223237085F3118838BD00BFB2 +:101EE000A8260020CC4100084024002000F044B97E +:101EF000034A516853685B1A9842FBD8704700BF89 +:101F0000001000E08B600223086108468B82704756 +:101F10008368A3F1840243F8142C026943F8442C2B +:101F2000426943F8402C094A43F8242CC268A3F1C3 +:101F3000200043F8182C022203F80C2C002203F88E +:101F40000B2C034A43F8102C704700BF1D040008F7 +:101F50004024002008B5FFF7DBFFBDE80840FFF78D +:101F600061BF0000024BDB6898610F20FFF75CBF88 +:101F700040240020302383F31188FFF7F3BF0000D3 +:101F800008B50146302383F311880820FFF75AFF74 +:101F9000002383F3118808BD064BDB6839B1426822 +:101FA00018605A60136043600420FFF74BBF4FF086 +:101FB000FF307047402400200368984206D01A681A +:101FC0000260506018469961FFF72CBF704700000F +:101FD00038B504460D462068844200D138BD0368F8 +:101FE00023605C608561FFF71DFFF4E7036810B5AF +:101FF0009C68A2420CD85C688A600B604C602160CF +:10200000596099688A1A9A604FF0FF33836010BD57 +:10201000121B1B68ECE700000A2938BF0A2170B5C3 +:1020200004460D460A26601901F032FC01F01AFC44 +:10203000041BA54203D8751C04462E46F3E70A2E5E +:1020400004D90120BDE8704001F06ABC70BD0000F9 +:10205000F8B5144B0D460A2A4FF00A07D96103F16F +:102060001001826038BF0A2241601969144601607C +:1020700048601861A81801F0FBFB01F0F3FB431B5B +:102080000646A34206D37C1C28192746354601F094 +:10209000FFFBF2E70A2F04D90120BDE8F84001F068 +:1020A0003FBCF8BD40240020F8B506460D4601F0BF +:1020B000D9FB0F4A134653F8107F9F4206D12A4698 +:1020C00001463046BDE8F840FFF7C2BFD169BB68A2 +:1020D000441A2C1928BF2C46A34202D92946FFF7DF +:1020E0009BFF224631460348BDE8F840FFF77EBF1C +:1020F0004024002050240020C0E90323002310B412 +:102100005DF8044B4361FFF7CFBF000010B5194CD9 +:10211000236998420DD08168D0E9003213605A607B +:102120009A680A449A60002303604FF0FF33A3616A +:1021300010BD0268234643F8102F5360002202604E +:1021400022699A4203D1BDE8104001F09BBB93681D +:1021500081680B44936001F085FB2269E169926814 +:10216000441AA242E4D91144BDE81040091AFFF70D +:1021700053BF00BF402400202DE9F047DFF8BC80AA +:1021800008F110072C4ED8F8105001F06BFBD8F86E +:102190001C40AA68031B9A423ED814444FF0000921 +:1021A000D5E90032C8F81C4013605A60C5F80090A9 +:1021B000D8F81030B34201D101F064FB89F31188E3 +:1021C000D5E9033128469847302383F311886B699A +:1021D000002BD8D001F046FB6A69A0EB04098246C7 +:1021E0004A450DD2022001F09BFB0022D8F81030A6 +:1021F000B34208D151462846BDE8F047FFF728BF53 +:10220000121A2244F2E712EB09092946384638BF70 +:102210004A46FFF7EBFEB5E7D8F81030B34208D0D6 +:102220001444C8F81C00211AA960BDE8F047FFF764 +:10223000F3BEBDE8F08700BF5024002040240020FA +:1022400000207047FEE70000704700004FF0FF30AD +:102250007047000002290CD0032904D00129074847 +:1022600018BF00207047032A05D8054800EBC200BC +:102270007047044870470020704700BFA442000820 +:102280003C2200205842000870B59AB00546084626 +:10229000144601A900F0C2F801A8FEF7F3FD431CA3 +:1022A0000022C6B25B001046C5E900342370032348 +:1022B000023404F8013C01ABD1B202348E4201D8A1 +:1022C0001AB070BD13F8011B013204F8010C04F8B8 +:1022D000021CF1E708B5302383F311880348FFF7A8 +:1022E00049FA002383F3118808BD00BFB0260020FF +:1022F00090F8803003F01F02012A07D190F8812066 +:102300000B2A03D10023C0E91D3315E003F060035D +:10231000202B08D1B0F884302BB990F88120212AE5 +:1023200003D81F2A04D8FFF707BA222AEBD0FAE70E +:10233000034A426707228267C3670120704700BFD4 +:102340003322002007B5052917D8DFE801F0191658 +:1023500003191920302383F31188104A01210190B9 +:10236000FFF7B0FA019802210D4AFFF7ABFA0D48CA +:10237000FFF7CCF9002383F3118803B05DF804FB69 +:10238000302383F311880748FFF796F9F2E73023EB +:1023900083F311880348FFF7ADF9EBE7F841000834 +:1023A0001C420008B026002038B50C4D0C4C2A46C3 +:1023B0000C4904F10800FFF767FF05F1CA0204F1B8 +:1023C00010000949FFF760FF05F5CA7204F1180013 +:1023D0000649BDE83840FFF757BF00BF883F0020DF +:1023E0003C220020D8410008E2410008ED410008ED +:1023F00070B5044608460D46FEF744FDC6B22046B9 +:10240000013403780BB9184670BD32462946FEF7F1 +:1024100025FD0028F3D10120F6E700002DE9F84F53 +:1024200005460C46FEF72EFD2C49C6B22846FFF79E +:10243000DFFF08B10536F6B229492846FFF7D8FF75 +:1024400008B11036F6B2632E0DD8DFF89080DFF8B1 +:102450009090244FDFF894A0DFF894B02E7846B91E +:102460002670BDE8F88F29462046BDE8F84F01F0F8 +:10247000EBBD252E2ED1072241462846FEF7EEFC65 +:1024800070B9DBF8003007350C3444F80C3CDBF84D +:10249000043044F8083CDBF8083044F8043CDDE73D +:1024A000082249462846FEF7D9FC98B9A21C0E4BD3 +:1024B000197802320909C95D02F8041C13F8011BDE +:1024C00001F00F015345C95D02F8031CF0D1183427 +:1024D0000835C3E7013504F8016BBFE7C4420008C3 +:1024E000ED410008D942000800E8F11F0CE8F11F97 +:1024F000CC420008BFF34F8F044B1A695107FCD13F +:10250000D3F810215207F8D1704700BF00200052C5 +:1025100008B50D4B1B78ABB9FFF7ECFF0B4BDA6836 +:10252000D10704D50A4A5A6002F188325A60D3F8BA +:102530000C21D20706D5064AC3F8042102F18832DD +:10254000C3F8042108BD00BFE6410020002000526E +:102550002301674508B5114B1B78F3B9104B1A6975 +:10256000510703D5DA6842F04002DA60D3F810214F +:10257000520705D5D3F80C2142F04002C3F80C21D4 +:10258000FFF7B8FF064BDA6842F00102DA60D3F8D1 +:102590000C2142F00102C3F80C2108BDE6410020E5 +:1025A000002000520F289ABF00F5806040040020F0 +:1025B000704700004FF40030704700001020704753 +:1025C0000F2808B50BD8FFF7EDFF00F500330268C0 +:1025D000013204D104308342F9D1012008BD00202A +:1025E000FCE700000F2838B505463FD8FFF782FF0B +:1025F0001F4CFFF78DFF4FF0FF3307286361C4F8CE +:1026000014311DD82361FFF775FF030243F0240343 +:10261000E360E36843F08003E36023695A07FCD476 +:102620002846FFF767FFFFF7BDFF4FF4003100F0CA +:10263000F5F82846FFF78EFFBDE83840FFF7C0BF2A +:10264000C4F81031FFF756FFA0F108031B0243F056 +:102650002403C4F80C31D4F80C3143F08003C4F8DF +:102660000C31D4F810315B07FBD4D9E7002038BD1A +:10267000002000522DE9F84F05460C46104645EA69 +:102680000203DE0602D00020BDE8F88F20F01F0014 +:10269000DFF8BCB0DFF8BCA0FFF73AFF04EB00089E +:1026A000444503D10120FFF755FFEDE720222946DD +:1026B000204601F0B9FC10B920352034F0E72B4654 +:1026C00005F120021F68791CDDD104339A42F9D14B +:1026D00005F178431B481C4EB3F5801F1B4B38BFD8 +:1026E000184603F1F80332BFD946D1461E46FFF71C +:1026F00001FF0760A5EB040C336804F11C0143F0F3 +:1027000002033360231FD9F8007017F00507FAD1D0 +:1027100053F8042F8B424CF80320F4D1BFF34F8FB2 +:10272000FFF7E8FE4FF0FF332022214603602846E2 +:10273000336823F00203336001F076FC0028BBD03D +:102740003846B0E7142100520C20005214200052E9 +:10275000102000521021005210B5084C237828B1E7 +:102760001BB9FFF7D5FE0123237010BD002BFCD051 +:102770002070BDE81040FFF7EDBE00BFE64100202D +:102780000244074BD2B210B5904200D110BD441C98 +:1027900000B253F8200041F8040BE0B2F4E700BFA8 +:1027A000504000580E4B30B51C6F240405D41C6FEC +:1027B0001C671C6F44F400441C670A4C02442368E5 +:1027C000D2B243F480732360074B904200D130BDF6 +:1027D000441C51F8045B00B243F82050E0B2F4E727 +:1027E00000440258004802585040005807B50122E2 +:1027F00001A90020FFF7C4FF019803B05DF804FBB6 +:1028000013B50446FFF7F2FFA04205D0012201A94B +:1028100000200194FFF7C6FF02B010BD0144BFF3D2 +:102820004F8F064B884204D3BFF34F8FBFF36F8F98 +:102830007047C3F85C022030F4E700BF00ED00E011 +:10284000034B1A681AB9034AD2F8D0241A607047A9 +:10285000E84100200040025808B5FFF7F1FF024BA5 +:102860001868C0F3806008BDE8410020EFF30983D9 +:10287000054968334A6B22F001024A6383F30988F1 +:10288000002383F31188704700EF00E0302080F3CD +:10289000118862B60D4B0E4AD96821F4E061090433 +:1028A000090C0A430B49DA60D3F8FC2042F080722D +:1028B000C3F8FC20084AC2F8B01F116841F00101BA +:1028C00011602022DA7783F82200704700ED00E0E3 +:1028D0000003FA0555CEACC5001000E0302310B55A +:1028E00083F311880E4B5B6813F4006314D0F1EE90 +:1028F000103AEFF309844FF08073683CE361094BB1 +:10290000DB6B236684F30988FFF7BAFA10B1064B34 +:10291000A36110BD054BFBE783F31188F9E700BF06 +:1029200000ED00E000EF00E02F0400083204000892 +:1029300070B5BFF34F8FBFF36F8F1A4A0021C2F8F3 +:102940005012BFF34F8FBFF36F8F536943F40033BF +:102950005361BFF34F8FBFF36F8FC2F88410BFF383 +:102960004F8FD2F8803043F6E074C3F3C900C3F34D +:102970004E335B0103EA0406014646EA81750139DC +:10298000C2F86052F9D2203B13F1200FF2D1BFF30D +:102990004F8F536943F480335361BFF34F8FBFF3BD +:1029A0006F8F70BD00ED00E0FEE70000214B224874 +:1029B000224A70B5904237D3214BC11EDA1C121A3D +:1029C00022F003028B4238BF00220021FEF762FA98 +:1029D0001C4A0023C2F88430BFF34F8FD2F88030F6 +:1029E00043F6E074C3F3C900C3F34E335B0103EA5B +:1029F0000406014646EA81750139C2F86C52F9D2E3 +:102A0000203B13F1200FF2D1BFF34F8FBFF36F8F35 +:102A1000BFF34F8FBFF36F8F0023C2F85032BFF365 +:102A20004F8FBFF36F8F70BD53F8041B40F8041B2A +:102A3000C0E700BFC4440008BC430020BC430020E2 +:102A4000BC43002000ED00E0074BD3F8D81021EA8A +:102A50000001C3F8D810D3F8002122EA0002C3F81D +:102A60000021D3F8003170470044025870B5D0E916 +:102A7000244300224FF0FF359E6804EB42135101BE +:102A8000D3F80009002805DAD3F8000940F08040A7 +:102A9000C3F80009D3F8000B002805DAD3F8000BBF +:102AA00040F08040C3F8000B013263189642C3F82F +:102AB0000859C3F8085BE0D24FF00113C4F81C3882 +:102AC00070BD0000890141F02001016103699B068E +:102AD000FCD41220FFF70CBA10B50A4C2046FEF7C2 +:102AE000CFFE094BC4F89030084BC4F89430084C22 +:102AF0002046FEF7C5FE074BC4F89030064BC4F8DD +:102B0000943010BDEC410020000008401043000844 +:102B100088420020000004401C43000870B5037880 +:102B20000546012B5CD1434BD0F89040984258D1D8 +:102B3000414B0E216520D3F8D82042F00062C3F843 +:102B4000D820D3F8002142F00062C3F80021D3F866 +:102B50000021D3F8802042F00062C3F88020D3F82F +:102B6000802022F00062C3F88020D3F88030FEF786 +:102B7000B3FC324BE360324BC4F800380023D5F885 +:102B80009060C4F8003EC02323604FF40413A36395 +:102B90003369002BFCDA01230C203361FFF7A8F91D +:102BA0003369DB07FCD41220FFF7A2F93369002B4D +:102BB000FCDA00262846A660FFF758FF6B68C4F8C9 +:102BC0001068DB68C4F81468C4F81C6883BB1D4B2C +:102BD000A3614FF0FF336361A36843F00103A36077 +:102BE00070BD194B9842C9D1134B4FF08060D3F898 +:102BF000D82042F00072C3F8D820D3F8002142F068 +:102C00000072C3F80021D3F80021D3F8802042F0ED +:102C10000072C3F88020D3F8802022F00072C3F83D +:102C20008020D3F88030FFF70FFF0E214D209EE764 +:102C3000064BCDE7EC410020004402584014004010 +:102C400003002002003C30C088420020083C30C015 +:102C5000F8B5D0F89040054600214FF000662046B8 +:102C6000FFF730FFD5F8941000234FF001128F6862 +:102C70004FF0FF30C4F83438C4F81C2804EB43127A +:102C800001339F42C2F80069C2F8006BC2F808091C +:102C9000C2F8080BF2D20B68D5F89020C5F898302E +:102CA000636210231361166916F01006FBD112201F +:102CB000FFF71EF9D4F8003823F4FE63C4F8003897 +:102CC000A36943F4402343F01003A3610923C4F82C +:102CD0001038C4F814380B4BEB604FF0C043C4F805 +:102CE000103B094BC4F8003BC4F81069C4F8003924 +:102CF000D5F8983003F1100243F48013C5F89820FA +:102D0000A362F8BDEC42000840800010D0F890208B +:102D100090F88A10D2F8003823F4FE6343EA0113D6 +:102D2000C2F80038704700002DE9F84300EB81033A +:102D3000D0F890500C468046DA680FFA81F94801C5 +:102D4000166806F00306731E022B05EB41134FF0C5 +:102D5000000194BFB604384EC3F8101B4FF00101B8 +:102D600004F1100398BF06F1805601FA03F391694C +:102D700098BF06F5004600293AD0578A04F1580159 +:102D8000374349016F50D5F81C180B430021C5F893 +:102D90001C382B180127C3F81019A7405369611E6E +:102DA0009BB3138A928B9B08012A88BF5343D8F8A0 +:102DB0009820981842EA034301F140022146C8F8DE +:102DC0009800284605EB82025360FFF77BFE08EB74 +:102DD0008900C3681B8A43EA845348341E43640154 +:102DE0002E51D5F81C381F43C5F81C78BDE8F88370 +:102DF00005EB4917D7F8001B21F40041C7F8001B69 +:102E0000D5F81C1821EA0303C0E704F13F030B4A7D +:102E10002846214605EB83035A60FFF753FE05EB76 +:102E20004910D0F8003923F40043C0F80039D5F830 +:102E30001C3823EA0707D7E70080001000040002CF +:102E4000D0F894201268C0F89820FFF70FBE000059 +:102E50005831D0F8903049015B5813F4004004D049 +:102E600013F4001F0CBF0220012070474831D0F836 +:102E7000903049015B5813F4004004D013F4001F54 +:102E80000CBF02200120704700EB8101CB68196A5A +:102E90000B6813604B6853607047000000EB8103C0 +:102EA00030B5DD68AA691368D36019B9402B84BFB7 +:102EB000402313606B8A1468D0F890201C4402EB06 +:102EC0004110013C09B2B4FBF3F46343033323F034 +:102ED000030343EAC44343F0C043C0F8103B2B68EC +:102EE00003F00303012B0ED1D2F8083802EB411096 +:102EF00013F4807FD0F8003B14BF43F0805343F0BD +:102F00000053C0F8003B02EB4112D2F8003B43F003 +:102F10000443C2F8003B30BD2DE9F041D0F8906089 +:102F200005460C4606EB4113D3F8087B3A07C3F875 +:102F3000087B08D5D6F814381B0704D500EB8103AD +:102F4000DB685B689847FA071FD5D6F81438DB07AB +:102F50001BD505EB8403D968CCB98B69488A5A68BC +:102F6000B2FBF0F600FB16228AB91868DA689042C4 +:102F70000DD2121AC3E90024302383F311882146AD +:102F80002846FFF78BFF84F31188BDE8F081012309 +:102F900003FA04F26B8923EA02036B81CB68002BEE +:102FA000F3D021462846BDE8F041184700EB8103E5 +:102FB0004A0170B5DD68D0F890306C692668E6602B +:102FC00056BB1A444FF40020C2F810092A6802F0D8 +:102FD0000302012A0AB20ED1D3F8080803EB421407 +:102FE00010F4807FD4F8000914BF40F0805040F006 +:102FF0000050C4F8000903EB4212D2F8000940F077 +:103000000440C2F800090122D3F8340802FA01F1A1 +:103010000143C3F8341870BD19B9402E84BF402055 +:10302000206020681A442E8A8419013CB4FBF6F40F +:1030300040EAC44040F00050C6E700002DE9F843E4 +:10304000D0F8906005460C464F0106EB4113D3F8CB +:10305000088918F0010FC3F808891CD0D6F8103879 +:10306000DB0718D500EB8103D3F80CC0DCF8143073 +:10307000D3F800E0DA68964530D2A2EB0E024FF0AA +:1030800000091A60C3F80490302383F31188FFF716 +:103090008DFF89F3118818F0800F1DD0D6F83438D1 +:1030A0000126A640334217D005EB84030134D5F83E +:1030B0009050D3F80CC0E4B22F44DCF8142005EB98 +:1030C0000434D2F800E05168714514D3D5F834388F +:1030D00023EA0606C5F83468BDE8F883012303FA3D +:1030E00001F2038923EA02030381DCF80830002B94 +:1030F000D1D09847CFE7AEEB0103BCF81000834274 +:1031000028BF0346D7F8180980B2B3EB800FE3D885 +:103110009068A0F1040959F8048FC4F80080A0EB6E +:1031200009089844B8F1040FF5D818440B4490608E +:103130005360C8E72DE9F84FD0F8905004466E6907 +:10314000AB691E4016F480586E6103D0BDE8F84F9D +:10315000FEF706BC002E12DAD5F8003E9B0705D01C +:10316000D5F8003E23F00303C5F8003ED5F8043837 +:10317000204623F00103C5F80438FEF71FFC37058D +:1031800005D52046FFF772FC2046FEF705FCB0048B +:103190000CD5D5F8083813F0060FEB6823F47053FC +:1031A0000CBF43F4105343F4A053EB6031071BD51D +:1031B0006368DB681BB9AB6923F00803AB61237854 +:1031C000052B0CD1D5F8003E9A0705D0D5F8003E66 +:1031D00023F00303C5F8003E2046FEF7EFFB6368CB +:1031E000DB680BB120469847F30200F1BA80B702C2 +:1031F00026D5D4F8909000274FF0010A09EB47122A +:10320000D2F8003B03F44023B3F5802F11D1D2F85C +:10321000003B002B0DDA62890AFA07F322EA030366 +:10322000638104EB8703DB68DB6813B13946204612 +:1032300098470137D4F89430FFB29B689F42DDD99C +:10324000F00619D5D4F89000026AC2F30A1702F00A +:103250000F0302F4F012B2F5802F00F0CA80B2F52D +:10326000402F09D104EB8303002200F58050DB6876 +:103270001B6A974240F0B0803003D5F8185835D516 +:10328000E90303D500212046FFF746FEAA0303D534 +:1032900001212046FFF740FE6B0303D502212046A3 +:1032A000FFF73AFE2F0303D503212046FFF734FE34 +:1032B000E80203D504212046FFF72EFEA90203D51C +:1032C00005212046FFF728FE6A0203D50621204685 +:1032D000FFF722FE2B0203D507212046FFF71CFE35 +:1032E000EF0103D508212046FFF716FE700340F1D9 +:1032F000A780E90703D500212046FFF79FFEAA0714 +:1033000003D501212046FFF799FE6B0703D5022163 +:103310002046FFF793FE2F0703D503212046FFF732 +:103320008DFEEE0603D504212046FFF787FEA80692 +:1033300003D505212046FFF781FE690603D5062146 +:103340002046FFF77BFE2A0603D507212046FFF71C +:1033500075FEEB0574D520460821BDE8F84FFFF750 +:103360006DBED4F890904FF0000B4FF0010AD4F8E6 +:1033700094305FFA8BF79B689F423FF638AF09EBBA +:103380004713D3F8002902F44022B2F5802F20D150 +:10339000D3F80029002A1CDAD3F8002942F0904221 +:1033A000C3F80029D3F80029002AFBDB3946D4F8FA +:1033B0009000FFF787FB22890AFA07F322EA03034A +:1033C000238104EB8703DB689B6813B139462046F1 +:1033D00098470BF1010BCAE7910701D1D0F80080A3 +:1033E000072A02F101029CBF03F8018B4FEA18285B +:1033F0003FE704EB830300F58050DA68D2F818C089 +:10340000DCF80820DCE9001CA1EB0C0C00218F4249 +:1034100008D1DB689B699A683A449A605A683A44D2 +:103420005A6029E711F0030F01D1D0F800808C45D4 +:1034300001F1010184BF02F8018B4FEA1828E6E789 +:10344000BDE8F88F08B50348FFF774FEBDE80840F3 +:10345000FFF744BAEC41002008B50348FFF76AFEC5 +:10346000BDE80840FFF73ABA88420020D0F8903013 +:1034700003EB4111D1F8003B43F40013C1F8003BCA +:1034800070470000D0F8903003EB4111D1F80039BB +:1034900043F40013C1F8003970470000D0F89030B1 +:1034A00003EB4111D1F8003B23F40013C1F8003BBA +:1034B00070470000D0F8903003EB4111D1F800398B +:1034C00023F40013C1F800397047000030B504330D +:1034D000039C0172002104FB0325C160C0E906536F +:1034E000049B0363059BC0E90000C0E90422C0E916 +:1034F0000842C0E90A11436330BD00000022416A5E +:10350000C260C0E90411C0E90A226FF00101FEF7B0 +:103510005FBD0000D0E90432934201D1C2680AB90C +:10352000181D704700207047036919600021C268A8 +:103530000132C260C269134482699342036124BFAD +:10354000436A0361FEF738BD38B504460D46E368AB +:103550003BB162690020131D1268A3621344E36249 +:1035600007E0237A33B929462046FEF715FD0028E7 +:10357000EDDA38BD6FF00100FBE70000C368C269F7 +:10358000013BC3604369134482699342436124BF92 +:10359000436A436100238362036B03B1184770479A +:1035A00070B53023044683F31188866A3EB9FFF76D +:1035B000CBFF054618B186F31188284670BDA36A73 +:1035C000E26A13F8015B9342A36202D32046FFF73D +:1035D000D5FF002383F31188EFE700002DE9F84FB2 +:1035E00004460E46174698464FF0300989F3118875 +:1035F0000025AA46D4F828B0BBF1000F09D14146F6 +:103600002046FFF7A1FF20B18BF311882846BDE8C3 +:10361000F88FD4E90A12A7EB050B521A934528BF7D +:103620009346BBF1400F1BD9334601F1400251F8DC +:10363000040B914243F8040BF9D1A36A403640359C +:103640004033A362D4E90A239A4202D32046FFF70B +:1036500095FF8AF31188BD42D8D289F31188C9E752 +:1036600030465A46FDF7F0FBA36A5E445D445B4476 +:10367000A362E7E710B5029C0433017203FB042147 +:10368000C460C0E906130023C0E90A33039B036347 +:10369000049BC0E90000C0E90422C0E9084243637A +:1036A00010BD0000026A6FF00101C260426AC0E909 +:1036B00004220022C0E90A22FEF78ABCD0E90423D2 +:1036C0009A4201D1C26822B9184650F8043B0B60F7 +:1036D000704700231846FAE7C3680021C269013326 +:1036E000C3604369134482699342436124BF436AC0 +:1036F0004361FEF761BC000038B504460D46E3683F +:103700003BB1236900201A1DA262E2691344E362FF +:1037100007E0237A33B929462046FEF73DFC00280E +:10372000EDDA38BD6FF00100FBE7000003691960B6 +:10373000C268013AC260C26913448269934203615C +:1037400024BF436A036100238362036B03B11847FC +:103750007047000070B530230D460446114683F3D0 +:103760001188866A2EB9FFF7C7FF10B186F311885A +:1037700070BDA36A1D70A36AE26A01339342A3621B +:1037800004D3E16920460439FFF7D0FF002080F31D +:103790001188EDE72DE9F84F04460D46904699460D +:1037A0004FF0300A8AF311880026B346A76A4FB952 +:1037B00049462046FFF7A0FF20B187F31188304625 +:1037C000BDE8F88FD4E90A073A1AA8EB0607974232 +:1037D00028BF1746402F1BD905F1400355F8042B8D +:1037E0009D4240F8042BF9D1A36A40364033A362CE +:1037F000D4E90A239A4204D3E16920460439FFF749 +:1038000095FF8BF311884645D9D28AF31188CDE70D +:1038100029463A46FDF718FBA36A3D443E443B4423 +:10382000A362E5E7D0E904239A4217D1C3689BB1AC +:10383000836A8BB1043B9B1A0ED01360C368013BB3 +:10384000C360C3691A4483699A42026124BF436A10 +:103850000361002383620123184670470023FBE7BE +:1038600000F024B9014B586A704700BF000C0040BB +:10387000034B002258631A610222DA60704700BFCE +:10388000000C0040014B0022DA607047000C004041 +:10389000014B5863704700BF000C0040FEE700007A +:1038A00070B51B4B0025044686B058600E468562F5 +:1038B0000163FEF7EBFF04F11003A560E562C4E9C4 +:1038C00004334FF0FF33C4E90044C4E90635FFF781 +:1038D000C9FF2B46024604F134012046C4E90823FF +:1038E00080230C4A2565FEF70DFB01230A4AE060A0 +:1038F00000920375684672680192B268CDE90223AE +:10390000064BCDE90435FEF725FB06B070BD00BFC0 +:10391000A8260020284300082D4300089D380008F1 +:10392000024AD36A1843D062704700BF4024002087 +:103930004B6843608B688360CB68C3600B694361ED +:103940004B6903628B6943620B6803607047000038 +:1039500008B53C4B40F2FF713B48D3F888200A433E +:10396000C3F88820D3F8882022F4FF6222F00702EF +:10397000C3F88820D3F88820D3F8E0200A43C3F89E +:10398000E020D3F808210A43C3F808212F4AD3F8CE +:1039900008311146FFF7CCFF00F5806002F11C01F1 +:1039A000FFF7C6FF00F5806002F13801FFF7C0FFA6 +:1039B00000F5806002F15401FFF7BAFF00F5806066 +:1039C00002F17001FFF7B4FF00F5806002F18C0195 +:1039D000FFF7AEFF00F5806002F1A801FFF7A8FF36 +:1039E00000F5806002F1C401FFF7A2FF00F58060DE +:1039F00002F1E001FFF79CFF00F5806002F1FC019D +:103A0000FFF796FF02F58C7100F58060FFF790FFDD +:103A100000F018F90E4BD3F8902242F00102C3F8DF +:103A20009022D3F8942242F00102C3F89422052296 +:103A3000C3F898204FF06052C3F89C20054AC3F8A1 +:103A4000A02008BD0044025800000258344300087A +:103A500000ED00E01F00080308B500F0C7FAFEF70C +:103A60002FFA0F4BD3F8DC2042F04002C3F8DC20E1 +:103A7000D3F8042122F04002C3F80421D3F8043122 +:103A8000084B1A6842F008021A601A6842F00402F1 +:103A90001A60FEF7D5FEBDE80840FEF785BC00BF02 +:103AA000004402580018024870470000114BD3F838 +:103AB000E82042F00802C3F8E820D3F8102142F0D1 +:103AC0000802C3F810210C4AD3F81031D36B43F02D +:103AD0000803D363C722094B9A624FF0FF32DA62C0 +:103AE00000229A615A63DA605A6001225A611A60B0 +:103AF000704700BF004402580010005C000C0040FA +:103B0000094A08B51169D3680B40D9B29B076FEA1F +:103B10000101116107D5302383F31188FEF7E6F91F +:103B2000002383F3118808BD000C0040064BD3F836 +:103B3000DC200243C3F8DC20D3F804211043C3F88F +:103B40000401D3F8043170470044025808B53C4BD7 +:103B50004FF0FF31D3F8802062F00042C3F880209C +:103B6000D3F8802002F00042C3F88020D3F88020F0 +:103B7000D3F88420C3F88410D3F884200022C3F83B +:103B80008420D3F88400D86F40F0FF4040F4FF0059 +:103B900040F4DF4040F07F00D867D86F20F0FF404E +:103BA00020F4FF0020F4DF4020F07F00D867D86FBA +:103BB000D3F888006FEA40506FEA5050C3F888008D +:103BC000D3F88800C0F30A00C3F88800D3F888004F +:103BD000D3F89000C3F89010D3F89000C3F8902069 +:103BE000D3F89000D3F89400C3F89410D3F894005D +:103BF000C3F89420D3F89400D3F89800C3F8981031 +:103C0000D3F89800C3F89820D3F89800D3F88C0024 +:103C1000C3F88C10D3F88C00C3F88C20D3F88C0038 +:103C2000D3F89C00C3F89C10D3F89C10C3F89C20D8 +:103C3000D3F89C30FDF774FBBDE8084000F0AEB946 +:103C40000044025808B50122534BC3F80821534BD6 +:103C5000D3F8F42042F00202C3F8F420D3F81C2178 +:103C600042F00202C3F81C210222D3F81C314C4B53 +:103C7000DA605A689104FCD54A4A1A6001229A60B7 +:103C8000494ADA6000221A614FF440429A61444B7B +:103C90009A699204FCD51A6842F480721A603F4B0C +:103CA0001A6F12F4407F04D04FF480321A6700225A +:103CB0001A671A6842F001021A60384B1A685007F6 +:103CC000FCD500221A611A6912F03802FBD10121D9 +:103CD00019604FF0804159605A67344ADA62344AB9 +:103CE0001A611A6842F480321A602C4B1A689103E8 +:103CF000FCD51A6842F480521A601A689204FCD506 +:103D00002C4A2D499A6200225A63196301F57C01FD +:103D1000DA6301F2E71199635A64284A1A64284A5F +:103D2000DA621A6842F0A8521A601C4B1A6802F054 +:103D30002852B2F1285FF9D148229A614FF4886283 +:103D4000DA6140221A621F4ADA641F4A1A651F4A62 +:103D50005A651F4A9A6532231E4A1360136803F09E +:103D60000F03022BFAD10D4A136943F003031361C9 +:103D7000136903F03803182BFAD14FF00050FFF706 +:103D8000D5FE4FF08040FFF7D1FE4FF00040BDE878 +:103D90000840FFF7CBBE00BF00800051004402582E +:103DA0000048025800C000F0020000010000FF01BE +:103DB000008890081210200063020901470E0508D0 +:103DC000DD0BBF0120000020000001100910E00001 +:103DD00000010110002000524FF0B04208B5D2F8A7 +:103DE000883003F00103C2F8883023B1044A136815 +:103DF0000BB150689847BDE80840FEF76FBD00BFA3 +:103E00003C4300204FF0B04208B5D2F8883003F0B0 +:103E10000203C2F8883023B1044A93680BB1D0681A +:103E20009847BDE80840FEF759BD00BF3C4300205D +:103E30004FF0B04208B5D2F8883003F00403C2F85E +:103E4000883023B1044A13690BB150699847BDE823 +:103E50000840FEF743BD00BF3C4300204FF0B04296 +:103E600008B5D2F8883003F00803C2F8883023B1CF +:103E7000044A93690BB1D0699847BDE80840FEF742 +:103E80002DBD00BF3C4300204FF0B04208B5D2F832 +:103E9000883003F01003C2F8883023B1044A136A53 +:103EA0000BB1506A9847BDE80840FEF717BD00BF48 +:103EB0003C4300204FF0B04310B5D3F8884004F4E1 +:103EC0007872C3F88820A30604D5124A936A0BB10E +:103ED000D06A9847600604D50E4A136B0BB1506B3D +:103EE0009847210604D50B4A936B0BB1D06B9847CA +:103EF000E20504D5074A136C0BB1506C9847A30533 +:103F000004D5044A936C0BB1D06C9847BDE81040BF +:103F1000FEF7E4BC3C4300204FF0B04310B5D3F8AB +:103F2000884004F47C42C3F88820620504D5164A10 +:103F3000136D0BB1506D9847230504D5124A936D4C +:103F40000BB1D06D9847E00404D50F4A136E0BB146 +:103F5000506E9847A10404D50B4A936E0BB1D06EF6 +:103F60009847620404D5084A136F0BB1506F984705 +:103F7000230404D5044A936F0BB1D06F9847BDE872 +:103F80001040FEF7ABBC00BF3C43002008B5FFF774 +:103F9000B7FDBDE80840FEF7A1BC0000062108B54A +:103FA0000846FDF799FA06210720FDF795FA062144 +:103FB0000820FDF791FA06210920FDF78DFA062168 +:103FC0000A20FDF789FA06211720FDF785FA062158 +:103FD0002820FDF781FA09217A20FDF77DFA0721D3 +:103FE0003220BDE80840FDF777BA000008B5FFF7BA +:103FF000ADFD00F00BF8FDF741FCFDF713FBFFF7FB +:1040000053FDBDE80840FFF72BBC00000023054A24 +:1040100019460133102BC2E9001102F10802F8D150 +:10402000704700BF3C43002010B501390244904264 +:1040300001D1002005E0037811F8014FA34201D01F +:10404000181B10BD0130F2E7034611F8012B03F8ED +:10405000012B002AF9D1704753544D333248373F72 +:104060003F3F0053544D3332483733782F3732783F +:104070000053544D3332483734332F3735332F37CD +:104080003530000001105A0003105900012058007B +:1040900003205600100002400800024000080240C1 +:1040A00000000B0028000240080002400408024003 +:1040B00006010C00400002400800024008080240CF +:1040C00010020D0058000240080002400C08024097 +:1040D00016030E00700002400C000240100802405F +:1040E00000040F00880002400C0002401408024047 +:1040F00006051000A00002400C0002401808024013 +:1041000010061100B80002400C0002401C080240DA +:1041100016072F0010040240080402402008024045 +:104120000008380028040240080402402408024025 +:1041300006093900400402400804024028080240F1 +:10414000100A3A0058040240080402402C080240B9 +:10415000160B3B00700402400C0402403008024081 +:10416000000C3C00880402400C0402403408024069 +:10417000060D4400A00402400C040240380802402E +:10418000100E4500B80402400C0402403C080240F6 +:10419000160F460000000000A11500088D1500084C +:1041A000C9150008B5150008C1150008AD150008AF +:1041B0009915000885150008D515000800000000B5 +:1041C000010000000000000063300000C84100084A +:1041D00098240020A82600204172647550696C6FF5 +:1041E000740025424F415244252D424C0025534531 +:1041F0005249414C25000000020000000000000070 +:10420000C11700083118000840004000583F002046 +:10421000683F0020020000000000000003000000D2 +:1042200000000000791800080000000010000000E5 +:10423000783F0020000000000100000000000000A6 +:10424000EC4100200101020045230008552200082E +:10425000F1220008D5220008430000006042000857 +:1042600009024300020100C03209040000010202F9 +:1042700001000524001001052401000104240202AC +:104280000524060001070582030800FF0904010058 +:10429000020A000000070501024000000705810234 +:1042A0004000000012000000AC42000812011001A2 +:1042B0000200004009124157000201020301000000 +:1042C0000403090425424F4152442500426C69749D +:1042D0007A4837343350726F0030313233343536E8 +:1042E0003738394142434445460000000000000091 +:1042F000D51900088D1C0008391D00084000400039 +:104300002443002024430020010000003443002007 +:1043100080000000400100000800000000010000D3 +:1043200000100000080000006D61696E0069646C97 +:10433000650000000000812A00000000AAAAAAAAC5 +:1043400000000024FFFE00000000000000A00A00A2 +:104350000000000100000000AAAAAAAA00000001B3 +:10436000FFFF00000000000000000000000000400F +:1043700000000000AAAAAAAA00000040FFFF000057 +:10438000000000000000000000001000000000001D +:10439000AAAAAAAA00000000FFFF00000000000077 +:1043A000000000000000400000000000AAAAAAAA25 +:1043B00000004000FFFF00000000000000000000BF +:1043C0000000000000000000AAAAAAAA0000000045 +:1043D000FFFF0000000000000000000000000000DF +:1043E00000000000AAAAAAAA00000000FFFF000027 +:1043F00000000000000000000000000000000000BD +:10440000AAAAAAAA00000000FFFF00000000000006 +:10441000000000000000000000000000AAAAAAAAF4 +:1044200000000000FFFF000000000000000000008E +:104430000000000000000000AAAAAAAA00000000D4 +:10444000FFFF00000000000000000000000000006E +:1044500000000000AAAAAAAA00000000FFFF0000B6 +:1044600000000000000000008A04000000000000BE +:1044700000001A0000000000FF0000000000000023 +:104480005840000883040000634000085004000006 +:10449000714000080096000000000800960000002F +:1044A0000008000004000000C042000800000000F6 +:1044B00000000000000000000000000000000000FC +:0444C00000000000F8 +:00000001FF diff --git a/Tools/bootloaders/BlitzMiniF745_bl.bin b/Tools/bootloaders/BlitzMiniF745_bl.bin new file mode 100644 index 00000000000000..1580abc1668041 Binary files /dev/null and b/Tools/bootloaders/BlitzMiniF745_bl.bin differ diff --git a/Tools/bootloaders/BlitzMiniF745_bl.hex b/Tools/bootloaders/BlitzMiniF745_bl.hex new file mode 100644 index 00000000000000..10dedd366b2ea8 --- /dev/null +++ b/Tools/bootloaders/BlitzMiniF745_bl.hex @@ -0,0 +1,930 @@ +:020000040800F2 +:1000000000060120010200080302000803020008A4 +:1000100003020008030200080302000803020008AC +:1000200003020008030200080302000899310008D7 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:100050000302000803020008413400086934000864 +:1000600091340008B9340008E134000803020008A4 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:1000900003020008030200080302000809350008F3 +:1000A000030200080302000803020008030200081C +:1000B000DD350008030200080302000803020008FF +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E0006D3500080302000803020008030200083F +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200080D2900084A +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F01F0A8FFA9 +:1002700002F024FF4FF055301F491B4A91423CBF0A +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE701F0C0FF02F05EFF1B +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E701F0A8BF00060120002201209D +:1002F0000000000808ED00E00000012000060120D9 +:1003000098390008002201205C220120602201208F +:10031000882E0120000200080002000800020008E8 +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F0E4FAFEE701F0FA +:100350006DFA00DFFEE7000038B500F011FC01F097 +:10036000EFFE054601F022FF0446C8B90E4B9D4240 +:1003700018D001339D4218BF044641F2883504BFAE +:1003800001240025002001F0E5FE0CB100F076F814 +:1003900000F05EFD284600F0FDF800F06FF8F9E788 +:1003A0000025EFE70546EDE7010007B008B500F0CE +:1003B000B9FBA0F120035842584108BD07B541F2EE +:1003C0001203022101A8ADF8043000F0C9FB03B00C +:1003D0005DF804FB38B572B6302383F3118862B63A +:1003E000174803680BB101F063FB164A1448002359 +:1003F0004FF47A7101F052FB002383F31188124C01 +:10040000236813B12368013B2360636813B16368F9 +:10041000013B63600D4D2B7833B963687BB90220D3 +:1004200000F080FC322363602B78032B07D16368D4 +:100430002BB9022000F076FC4FF47A73636038BD6C +:1004400060220120D50300088023012078220120AA +:10045000084B187003280CD8DFE800F008050208E4 +:10046000022000F055BC022000F048BC024B0022E4 +:100470005A6070477822012080230120F8B5404B54 +:10048000404A1C461968013179D004339342F9D1AE +:100490006268A24273D33C4B9B6803F1006303F58F +:1004A000C0339A426BD2002000F084FB0220FFF799 +:1004B000CFFF364B00211A6C19641A6E19661A6E3A +:1004C0005A6C59645A6E59665A6E5A6942F08002E3 +:1004D0005A615A6922F080025A615A691A6942F0D7 +:1004E00000521A611A6922F000521A611B6972B631 +:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 +:10050000BFF36F8F224AC2F88410BFF34F8F536935 +:1005100023F480335361BFF34F8FD2F88030C3F39D +:10052000C905C3F34E335B0143F6E07603EA060CDC +:1005300029464CEA81770139C2F87472F9D2203B1E +:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 +:100550004F8FBFF36F8F536923F400335361002330 +:10056000C2F85032BFF34F8FBFF36F8F72B6302394 +:1005700083F3118862B6854680F308882047F8BD6A +:10058000008001082080010800220120003802407C +:1005900000ED00E02DE9F04F93B0B64B0090202223 +:1005A000FF210AA89D6800F0FDFBB34A1378B3B998 +:1005B000B24801211170036072B6302383F31188B1 +:1005C00062B603680BB101F073FAAD4AAB48002381 +:1005D0004FF47A7101F062FA002383F31188009BD3 +:1005E00013B1A84B009A1A60A74A009C1378032BFA +:1005F0001EBF00231370A34A4FF0000A18BF5360B8 +:10060000D3465646D146012000F082FB24B19D4BD3 +:100610001B68002B00F02782002000F083FA039073 +:10062000039B002BF2DB012000F068FB039B213BC6 +:100630001F2BE8D801A252F823F000BFBD06000826 +:10064000E506000879070008070600080706000805 +:10065000070600080B080008DB090008F508000879 +:10066000570900087F090008A509000807060008C7 +:10067000B709000807060008290A00085D070008F6 +:10068000070600086D0A0008C90600085D07000893 +:1006900007060008570900080706000807060008B3 +:1006A00007060008070600080706000807060008F6 +:1006B0000706000807060008790700080220FFF770 +:1006C00075FE002840F0F981009B0221BAF1000F6D +:1006D00008BF1C4605A841F21233ADF8143000F0F3 +:1006E0003FFA90E74FF47A7000F01CFA071EEBDB3C +:1006F0000220FFF75BFE0028E6D0013F052F00F245 +:10070000DE81DFE807F0030A0D1013360523059399 +:10071000042105A800F024FA17E056480421F9E75F +:100720005A480421F6E75A480421F3E74FF01C0821 +:10073000404600F041FA08F104080590042105A89C +:1007400000F00EFAB8F12C0FF2D1012000FA07F7F1 +:1007500047EA0B0B5FFA8BFB4FF0000900F06EFBD2 +:1007600026B10BF00B030B2B08BF0024FFF726FE6E +:1007700049E748480421CDE7002EA5D00BF00B0334 +:100780000B2BA1D10220FFF711FE074600289BD0BA +:10079000012000F00FFA0220FFF75AFE00261FFA90 +:1007A00086F8404600F016FA0446B0B10399A1F16C +:1007B000400251425141404600F01CFA01360028E7 +:1007C000EDD1BA46044641F21213022105A8ADF854 +:1007D00014303E4600F0C4F915E70120FFF738FE5B +:1007E0002546244B9B68AB4207D9284600F0E4F924 +:1007F000013040F067810435F3E7234B00251D707D +:10080000204BBA465D603E46A8E7002E3FF45CAF41 +:100810000BF00B030B2B7FF457AF0220FFF718FEF2 +:10082000322000F07FF9B0F10008FFF64DAF18F06C +:1008300003077FF449AF0F4A926808EB0503934220 +:100840003FF642AFB8F5807F3FF73EAF124B0193C2 +:10085000B84523DD4FF47A7000F064F90390039AF1 +:10086000002AFFF631AF019B039A03F8012B0137F1 +:10087000EDE700BF002201207C230120602201203F +:10088000D5030008802301207822012004220120C2 +:10089000082201200C2201207C220120C820FFF721 +:1008A00085FD074600283FF40FAF1F2D11D8C5F175 +:1008B000200242450AAB25F0030028BF4246834987 +:1008C0000192184400F048FA019A8048FF2100F094 +:1008D00069FA4FEAA8037D490193C8F387022846C5 +:1008E00000F068FA064600283FF46DAF019B05EB67 +:1008F000830533E70220FFF759FD00283FF4E4AEFB +:1009000000F0A4F900283FF4DFAE0027B846704B92 +:100910009B68BB4218D91F2F11D80A9B01330ED0F8 +:1009200027F0030312AA134453F8203C05934046D2 +:10093000042205A900F0B6FA04378046E7E73846F6 +:1009400000F03AF90590F2E7CDF81480042105A8EB +:1009500000F006F902E70023642104A8049300F0E4 +:10096000F5F800287FF4B0AE0220FFF71FFD002845 +:100970003FF4AAAE049800F051F90590E6E7002391 +:10098000642104A8049300F0E1F800287FF49CAEF1 +:100990000220FFF70BFD00283FF496AE049800F00C +:1009A0004DF9EAE70220FFF701FD00283FF48CAE85 +:1009B00000F05CF9E1E70220FFF7F8FC00283FF4C3 +:1009C00083AE05A9142000F057F9042107460490CE +:1009D00004A800F0C5F83946B9E7322000F0A2F8C3 +:1009E000071EFFF671AEBB077FF46EAE384A926801 +:1009F00007EB090393423FF667AE0220FFF7D6FCF0 +:100A000000283FF461AE27F003074F44B9453FF497 +:100A1000A5AE484600F0D0F80421059005A800F0E6 +:100A20009FF809F10409F1E74FF47A70FFF7BEFC73 +:100A300000283FF449AE00F009F9002844D00A9B91 +:100A400001330BD008220AA9002000F0B3F90028D6 +:100A50003AD02022FF210AA800F0A4F9FFF7AEFC4B +:100A60001C4800F05FFF13B0BDE8F08F002E3FF48C +:100A70002BAE0BF00B030B2B7FF426AE002364216F +:100A800005A8059300F062F8074600287FF41CAE25 +:100A90000220FFF78BFC804600283FF415AEFFF7DD +:100AA0008DFC41F2883000F03DFF059800F0F8F928 +:100AB000464600F0C3F93C46A5E506464EE64FF033 +:100AC000000901E6BA467EE637467CE67C22012034 +:100AD00000220120A086010070B50F4B1B78013366 +:100AE000DBB2012B0C4611D80C4D29684FF47A73F8 +:100AF0000E6AA2FB0332014622462846B0478442D2 +:100B000004D1074B00221A70012070BD4FF4FA7017 +:100B100000F008FF0020F8E710220120282601201D +:100B2000B423012007B50023024601210DF107007F +:100B30008DF80730FFF7D0FF20B19DF8070003B014 +:100B40005DF804FB4FF0FF30F9E700000A4608B5F6 +:100B50000421FFF7C1FF80F00100C0B2404208BD90 +:100B600030B4054C2368DD69044B0A46AC460146A7 +:100B7000204630BC604700BF28260120A086010027 +:100B800070B501F0E3F9094E094D30800024286862 +:100B90003388834208D901F0D3F92B680444013328 +:100BA000B4F5C03F2B60F2D370BD00BFB623012067 +:100BB0008823012001F078BA00F1006000F5C03010 +:100BC0000068704700F10060920000F5C03001F04D +:100BD00003BA0000054B1A68054B1B889B1A834219 +:100BE00002D9104401F0ACB90020704788230120DD +:100BF000B623012038B5084D044629B128682044A1 +:100C0000BDE8384001F0BCB92868204401F0A0F9E3 +:100C10000028F3D038BD00BF8823012010F0030363 +:100C200009D1B0F5846F04D200F10050A0F5712015 +:100C30000368184670470023FBE7000000F10050EE +:100C4000A0F57120D0F8200470470000064991F803 +:100C5000243033B10023086A81F824300822FFF7DA +:100C6000B1BF0120704700BF8C230120014B1868E1 +:100C7000704700BF002004E0F0B51E4B1D6801382E +:100C80002E0C0A181C48C5F30B04032335460788AD +:100C9000A7420BD144680B46013C934218461BD235 +:100CA00014F9010F48B103F8010BF6E7013B00F11D +:100CB0000800ECD191420ED20B4618462C24B6F512 +:100CC000805F00F8014B0AD1824202D94122981C70 +:100CD0005A70401AF0BD0846B6F5805FF9D041F26F +:100CE00001039D42F5D18242F3D95A2300F8013B1A +:100CF000EFE700BF002004E014220120022802BF19 +:100D0000024B4FF000729A61704700BF000802402A +:100D1000022802BF024B4FF400729A61704700BF75 +:100D200000080240022801BF024A536983F400739D +:100D3000536170470008024070B504464FF47A765C +:100D40004CB1412C254628BF412506FB05F000F09B +:100D5000E9FD641BF4E770BD10B50023934203D096 +:100D6000CC5CC4540133F9E710BD000010B5013864 +:100D700010F9013F3BB191F900409C4203D11AB1F7 +:100D80000131013AF4E71AB191F90020981A10BD27 +:100D90001046FCE703460246D01A12F9011B00294F +:100DA000FAD1704702440346934202D003F8011B74 +:100DB000FAE770472DE9F8431F4D144695F82420B3 +:100DC0000746884652BBDFF870909CB395F82430F4 +:100DD0002BB92022FF2148462F62FFF7E3FF95F849 +:100DE0002400C0F10802A24228BF2246D6B24146E2 +:100DF000920005EB8000FFF7AFFF95F82430A41BAD +:100E00001E44F6B2082E17449044E4B285F82460DC +:100E1000DBD1FFF71BFF0028D7D108E02B6A03EBDB +:100E200082038342CFD0FFF711FF0028CBD10020EF +:100E3000BDE8F8830120FBE78C230120024B1A78E0 +:100E4000024B1A70704700BFB4230120102201200A +:100E500010B5104C104800F0BBF821460E4800F0C9 +:100E6000E3F82468E26ED2F8043843F00203C2F8D3 +:100E700004384FF47A70FFF75FFF0849204600F00E +:100E8000E1F9E26ED2F8043823F00203C2F8043824 +:100E900010BD00BF58370008282601206037000821 +:100EA0007047000030B5094D0A4491420DD011F849 +:100EB000013B5840082340F30004013B2C4013F051 +:100EC000FF0384EA5000F6D1EFE730BD2083B8ED90 +:100ED00072B6302383F3118862B6704702684368A4 +:100EE0001143016003B118477047000013B5446B0C +:100EF000D4F894341A681178042915D1217C022978 +:100F000012D11979128901238B4013420CD101A906 +:100F100004F14C0001F090FFD4F89444019B217936 +:100F20000246206800F0DAF902B010BD143001F07A +:100F300015BF00004FF0FF33143001F00FBF000069 +:100F40004C3001F0E5BF00004FF0FF334C3001F0B2 +:100F5000DFBF0000143001F0E5BE00004FF0FF31AC +:100F6000143001F0DFBE00004C3001F0B1BF0000D2 +:100F70004FF0FF324C3001F0ABBF00000020704753 +:100F800010B5D0F894341A6811780429044617D1A2 +:100F9000017C022914D15979528901238B401342D3 +:100FA0000ED1143001F078FE024648B1D4F89444D2 +:100FB0004FF4807361792068BDE8104000F07CB97F +:100FC00010BD0000406BFFF7DBBF00007047000062 +:100FD0007FB5124B036000234360C0E90233012553 +:100FE00002260F4B057404460290019300F184021F +:100FF000294600964FF48073143001F029FE094B06 +:101000000294CDE9006304F523724FF480732946FE +:1010100004F14C0001F0ECFE04B070BDAC360008E9 +:10102000C50F0008ED0E000808B50A68FFF750FF6D +:101030000B7902EB830318624B790D3342F82300DE +:101040008B7913B102EB830210620223C0F894146F +:101050000374002080F3118808BD000038B5037FB9 +:10106000044613B190F85430ABB9201D012502217C +:10107000FFF734FF04F1140025776FF0010100F051 +:1010800079FC84F8545004F14C006FF00101BDE884 +:10109000384000F06FBC38BD10B501210446043063 +:1010A000FFF71CFF0023237784F8543010BD0000A5 +:1010B00038B504460025143001F0E2FD04F14C007F +:1010C000257701F0ADFE201D84F854500121FFF773 +:1010D00005FF2046BDE83840FFF752BF90F85C306E +:1010E00003F06003202B07D190F85D20212A4FF0F8 +:1010F000000303D81F2A06D800207047222AFBD1FC +:10110000C0E9143303E0034A0265072242658365A0 +:10111000012070472C22012037B5D0F894341A688A +:101120001178042904461AD1017C022917D11979B2 +:10113000128901238B40134211D100F14C0528463E +:1011400001F02CFF58B101A9284601F075FED4F832 +:101150009444019B21790246206800F0BFF803B057 +:1011600030BD0000F0B500EB810385B01E6A044677 +:101170000D46F6B104EB8507301D0821FFF7A8FEE8 +:10118000FFF7ACFEFB685B691B6806F14C001BB106 +:10119000019001F05FFE019803A901F04DFE0246A7 +:1011A00048B1039B2946204600F098F8002383F3BA +:1011B000118805B0F0BDFB685A691268002AF5D0A5 +:1011C0001B8A013B1340F1D104F15C02EAE7000005 +:1011D0000D3138B550F82140D4B1FFF779FED4F87D +:1011E00094241368527903EB8203DB689B695D6882 +:1011F00045B104216018FFF771FE294604F114007F +:1012000001F054FD2046FFF7BBFE002383F3118855 +:1012100038BD00007047000072B6302383F3118898 +:1012200062B6704701F08EB810B50123044628223B +:1012300000F8243B0021FFF7B5FD0023C4E901338A +:1012400010BD000038B50025FFF7E6FF0446C0E9F1 +:101250000355C0E90555C0E90755416001F082F822 +:101260000223237085F31188284638BD70B500EB42 +:10127000810305465069DA600E46144618B1102203 +:101280000021FFF78FFDA06918B110220021FFF7A0 +:1012900089FD31462846BDE8704001F02DB90000B7 +:1012A000826802F0011282600022C0E90422C0E9D3 +:1012B0000622026201F0ACB9F0B400EB8104478968 +:1012C000E4680125A4698D403D43458123600023E6 +:1012D000A2606360F0BC01F0C7B90000F0B400EB9D +:1012E00081040789E468012564698D403D430581D7 +:1012F00023600023A2606360F0BC01F043BA0000E9 +:1013000070B50223002504460370C0E90255C0E908 +:101310000455C0E906554566056280F84C5001F059 +:1013200087F863681B6823B129462046BDE87040F2 +:10133000184770BD0378052B10B504460AD080F815 +:1013400068300523037043681B680BB1042198477C +:101350000023A36010BD00000178052906D190F894 +:101360006820436802701B6803B11847704700008B +:1013700070B590F84C30044613B1002380F84C301F +:1013800004F15C02204601F065F963689B68B3B91B +:1013900094F85C3013F0600533D00021204601F052 +:1013A0001DFC0021204601F00FFC63681B6813B18F +:1013B000062120469847062384F84C3070BD20460D +:1013C00098470028E4D0B4F86230626D9A4288BF32 +:1013D000636594F95C30656D002B80F20281002D0D +:1013E00000F0F180092384F84C30FFF715FF00214D +:1013F000D4E914232046FFF771FF002383F31188FB +:10140000DCE794F85D2003F07F0343EA022340F217 +:101410000232934200F0C48021D8B3F5807F48D0D7 +:101420000DD8012B3FD0022B00F09280002BB4D1BD +:1014300004F16402226502226265A365C3E7B3F585 +:10144000817F00F09A80B3F5407FA6D194F85E309A +:10145000012BA2D1B4F8643043F0020332E0B3F5BB +:10146000006F4DD017D8B3F5A06F31D0A3F5C0638E +:10147000012B92D8636894F85E205E6894F85F1040 +:10148000B4F860302046B047002886D04368236512 +:10149000036863651AE0B3F5106F36D040F6024278 +:1014A00093427FF47AAF5B4B23650223636500238D +:1014B000C3E794F85E30012B7FF46FAFB4F864306B +:1014C00023F00203C4E91455A4F86430A5657AE753 +:1014D000B4F85C30B3F5A06F0ED194F85E3084F8A8 +:1014E0006630204600F0FCFF63681B6813B10121E1 +:1014F00020469847032323700023C4E914339CE754 +:1015000004F1670323650123C3E72378042B0FD17C +:101510002046FFF781FEFFF7C3FE85F31188032104 +:10152000636884F8675021701B680BB120469847A8 +:1015300094F85E30002BDFD084F8673004232370EA +:1015400063681B68002BD7D0022120469847D3E759 +:1015500094F860301D0603F00F0120460AD501F013 +:101560006BF8012804D002287FF417AF2A4B9BE7C1 +:101570002A4B99E701F052F8F3E794F85E30002B1C +:101580007FF40BAF94F8603013F00F01B4D01A065B +:10159000204602D501F036FBAEE701F029FBABE7B0 +:1015A00094F85E30002B7FF4F8AE94F8603013F0BE +:1015B0000F01A1D01B06204602D501F00FFB9BE7CF +:1015C00001F002FB98E7142384F84C30FFF724FE67 +:1015D0002A462B4629462046FFF76EFE85F31188E2 +:1015E000ECE65DB1152384F84C30FFF715FE0021C1 +:1015F000D4E914232046FFF75FFEFEE60B2384F8B0 +:101600004C30FFF709FE2A462B4629462046FFF7B5 +:1016100065FEE3E7DC360008D4360008D83600085B +:1016200038B590F84C300446002B3CD0063BDAB27B +:101630000F2A32D80F2B30D8DFE803F0352F2F08D0 +:1016400021302F2F2F2F2F2F2F2F3535456DB0F80D +:1016500062309D4213D2C3681B8AB5FBF3F203FBD1 +:10166000125565B9FFF7D8FD2A462B462946FFF7E4 +:1016700035FE85F311880A2384F84C300DE01423DD +:1016800084F84C30FFF7C8FD00231A46194620465F +:10169000FFF712FE002383F3118838BD836D03B179 +:1016A00098470023E8E70021204601F097FA00213F +:1016B000204601F089FA63681B6813B106212046B1 +:1016C00098470623D8E7000010B590F84C30142B4B +:1016D000044628D017D8062B05D001D81BB110BD61 +:1016E000093B022BFBD80021204601F077FA0021AC +:1016F000204601F069FA63681B6813B10621204691 +:101700009847062318E0152BE9D10B2380F84C30BD +:10171000FFF782FD00231A461946FFF7DFFD00237D +:1017200083F31188DBE7C3689B695B68002BD6D124 +:10173000836D03B19847002384F84C30CFE7000055 +:1017400000230375826803691B6899689142FBD284 +:101750005A68036042601060586070470023037548 +:10176000826803691B6899689142FBD85A680360D4 +:10177000426010605860704708B5084672B6302362 +:1017800083F3118862B60B7D032B05D0042B0DD09B +:101790002BB983F3118808BD8B6900221A604FF0C2 +:1017A000FF338361FFF7CCFF0023F2E7D1E900327A +:1017B00013605A60F3E70000FFF7C2BF054BD9681A +:1017C0000875186802681A60536001220275D860B3 +:1017D000FEF7A8BDB823012030B50C4BDD684B1CCB +:1017E00087B004460FD02B46094A684600F056F9E8 +:1017F0002046FFF7E3FF009B13B1684600F058F95D +:10180000A86907B030BDFFF7D9FFF9E7B823012079 +:1018100079170008044B1A68DB6890689B68984247 +:1018200094BF002001207047B8230120084B10B559 +:101830001C68D86822681A60536001222275DC6037 +:10184000FFF78CFF01462046BDE81040FEF76ABD59 +:10185000B823012038B5074C074908480123002563 +:101860002370656001F0D2FB0223237085F3118899 +:1018700038BD00BF20260120E4360008B82301202F +:1018800000F04CB9034A516853685B1A9842FBD880 +:10189000704700BF001000E072B6302383F3118858 +:1018A00062B670478B60022308618B8208467047DE +:1018B0008368A3F1840243F8142C026943F8442C92 +:1018C000426943F8402C094A43F8242CC26843F883 +:1018D000182C022203F80C2C002203F80B2C044ACB +:1018E00043F8102CA3F12000704700BF3D0300080F +:1018F000B823012008B5FFF7DBFFBDE80840FFF77C +:101900005BBF0000024BDB6898610F20FFF756BFFA +:10191000B823012008B5FFF7BFFFBDE80840FFF777 +:10192000F1BF000008B501460820FFF7B5FFFFF73B +:1019300053FF002383F3118808BD0000064BDB68CA +:1019400039B1426818605A60136043600420FFF7A1 +:1019500043BF4FF0FF307047B8230120036898421F +:1019600006D01A680260506099611846FFF724BFDC +:101970007047000038B504460D462068844200D107 +:1019800038BD036823605C608561FFF715FFF4E7ED +:1019900010B503689C68A2420CD85C688A600B6032 +:1019A0004C602160596099688A1A9A604FF0FF3341 +:1019B000836010BD1B68121BECE700000A2938BFCA +:1019C0000A2170B504460D460A26601901F018FB7D +:1019D00001F004FB041BA54203D8751C2E460446E7 +:1019E000F3E70A2E04D9BDE87040012001F04EBB98 +:1019F00070BD0000F8B5144B0D46D96103F110011C +:101A000041600A2A1969826038BF0A220160486071 +:101A10001861A818144601F0E5FA0A2701F0DEFA69 +:101A2000431BA342064606D37C1C281901F0E8FAA2 +:101A300027463546F2E70A2F04D9BDE8F8400120D1 +:101A400001F024BBF8BD00BFB8230120F8B506465D +:101A50000D4601F0C3FA0F4A134653F8107F9F4218 +:101A600006D12A4601463046BDE8F840FFF7C2BF1E +:101A7000D169BB68441A2C1928BF2C46A34202D94D +:101A80002946FFF79BFF224631460348BDE8F84050 +:101A9000FFF77EBFB8230120C823012010B4C0E99E +:101AA000032300235DF8044B4361FFF7CFBF000021 +:101AB00010B5194C236998420DD0D0E900328168E5 +:101AC00013605A609A680A449A60002303604FF0DA +:101AD000FF33A36110BD2346026843F8102F536003 +:101AE0000022026022699A4203D1BDE8104001F051 +:101AF00081BA936881680B44936001F06FFA2269A0 +:101B0000E1699268441AA242E4D91144BDE8104048 +:101B1000091AFFF753BF00BFB82301202DE9F04792 +:101B2000DFF8C08008F110072D4ED8F8105001F0F2 +:101B300055FAD8F81C40AA68031B9A4240D81444AE +:101B4000D5E900324FF00009C8F81C4013605A6014 +:101B5000C5F80090D8F81030B34201D101F04AFA2C +:101B600089F31188D5E903312846984772B63023A6 +:101B700083F3118862B66B69002BD6D001F02EFA80 +:101B80006A69A0EB04094A4582460DD2022001F0A1 +:101B90007DFA0022D8F81030B34208D151462846C9 +:101BA000BDE8F047FFF726BF121A2244F2E712EB16 +:101BB000090938BF4A4629463846FFF7E9FEB3E728 +:101BC000D8F81030B34208D01444211AC8F81C00C9 +:101BD000A960BDE8F047FFF7F1BEBDE8F08700BFA0 +:101BE000C8230120B823012000207047FEE7000031 +:101BF000704700004FF0FF307047000072B630238E +:101C000083F3118862B6704702290CD0032904D0EF +:101C10000129074818BF00207047032A05D8054846 +:101C200000EBC2007047044870470020704700BFB7 +:101C3000BC3700083C2201207037000870B59AB00C +:101C40000546084601A9144600F0BEF801A8FFF7B2 +:101C5000A1F8431C5B00C5E9003400222370032374 +:101C60006370C6B201AB02341046D1B28E4204F1A9 +:101C7000020401D81AB070BD13F8011B04F8021C4D +:101C800004F8010C0132F0E708B50448FFF7B6FF8D +:101C9000FFF742FA002383F3118808BD28260120AC +:101CA00090F85C3003F01F02012A07D190F85D2004 +:101CB0000B2A03D10023C0E9143315E003F06003BD +:101CC000202B08D1B0F860302BB990F85D20212A84 +:101CD00003D81F2A04D8FFF701BA222AEBD0FAE76B +:101CE000034A02650722426583650120704700BFF1 +:101CF0003322012007B5052916D8DFE801F01815B1 +:101D00000318181E104A0121FFF778FF0190FFF712 +:101D1000ADFA01980D4A0221FFF7A8FA0C48FFF727 +:101D2000C7F9002383F3118803B05DF804FB08486A +:101D3000FFF764FFFFF792F9F3E70548FFF75EFF4F +:101D4000FFF7AAF9EDE700BF1037000834370008A5 +:101D50002826012038B50C4D0C4C0D492A4604F1BB +:101D60000800FFF76BFF05F1CA0204F110000949F2 +:101D7000FFF764FF05F5CA7204F118000649BDE8D3 +:101D80003840FFF75BBF00BFF02A01203C22012052 +:101D9000F0360008FA3600080537000870B504462A +:101DA00008460D46FEF7F6FFC6B22046013403781A +:101DB0000BB9184670BD32462946FEF7D7FF0028FA +:101DC000F3D10120F6E700002DE9F04705460C4667 +:101DD000FEF7E0FF2B49C6B22846FFF7DFFF08B148 +:101DE0000636F6B228492846FFF7D8FF08B1103664 +:101DF000F6B2632E0BD8DFF88C80DFF88C90234F7F +:101E0000DFF894A02E7846B92670BDE8F087294601 +:101E10002046BDE8F04701F02BBC252E2ED107222D +:101E200041462846FEF7A2FF70B9194B224603F13E +:101E30000C0153F8040B42F8040B8B42F9D11B78C8 +:101E4000137007350D34DDE7082249462846FEF7B2 +:101E50008DFF98B90F4BA21C197809090232C95D90 +:101E600002F8041C13F8011B01F00F015345C95D72 +:101E700002F8031CF0D118340835C3E704F8016BED +:101E80000135BFE7DC37000805370008F2370008E6 +:101E9000E437000820F4F01F2CF4F01FBFF34F8F3D +:101EA000024AD368DB03FCD4704700BF003C024009 +:101EB00008B5074B1B7853B9FFF7F0FF054B1A69BC +:101EC000002ABFBF044A5A6002F188325A6008BD36 +:101ED0004E2D0120003C02402301674508B5054B0B +:101EE0001B7833B9FFF7DAFF034A136943F0004365 +:101EF000136108BD4E2D0120003C02400728F0B5BB +:101F000016D80C4C0C4923787BB90C4D0E4608238F +:101F10004FF0006255F8047B46F8042B013B13F0A8 +:101F2000FF033A44F6D10123237051F82000F0BD9D +:101F30000020FCE7702D0120502D012004380008FE +:101F4000014B53F820007047043800080820704700 +:101F5000072810B5044601D9002010BDFFF7CEFFB9 +:101F6000064B53F824301844C21A0BB90120F4E789 +:101F700012680132F0D1043BF6E700BF04380008D4 +:101F8000072810B5044621D8FFF788FFFFF790FF18 +:101F90000F4AF323D360C300DBB243F4007343F072 +:101FA00002031361136943F480331361FFF776FF73 +:101FB000FFF7A4FF074B53F8241000F0D9F8FFF700 +:101FC0008DFF2046BDE81040FFF7C2BF002010BDC6 +:101FD000003C024004380008F8B512F00103144632 +:101FE00042D18218B2F1016F57D82D4B1B6813F004 +:101FF000010352D02B4DFFF75BFFF323EB60FFF79C +:102000004DFF40F20127032C15D824F00104661877 +:10201000244C401A40F20117B142236900EB01053C +:1020200024D123F001032361FFF758FF0120F8BDFD +:10203000043C0430E7E78307E7D12B6923F44073BE +:102040002B612B693B432B6151F8046B0660BFF396 +:102050004F8FFFF723FF03689E42E9D02B6923F0DF +:1020600001032B61FFF73AFF0020E0E723F4407300 +:10207000236123693B4323610B882B80BFF34F8F80 +:10208000FFF70CFF2D8831F8023BADB2AB42C3D055 +:10209000236923F001032361E4E71846C7E700BF83 +:1020A00000380240003C0240084908B50B7828B1CE +:1020B0001BB9FFF7FDFE01230B7008BD002BFCD000 +:1020C000BDE808400870FFF709BF00BF4E2D012092 +:1020D00010B50244064BD2B2904200D110BD441C50 +:1020E00000B253F8200041F8040BE0B2F4E700BF5F +:1020F000502800400F4B30B51C6F240407D41C6FD0 +:1021000044F400741C671C6F44F400441C670A4CC0 +:10211000236843F4807323600244084BD2B2904298 +:1021200000D130BD441C00B251F8045B43F820508C +:10213000E0B2F4E700380240007000405028004050 +:1021400007B5012201A90020FFF7C2FF019803B0E3 +:102150005DF804FB13B50446FFF7F2FFA04205D07B +:10216000012201A900200194FFF7C4FF02B010BDB5 +:102170000144BFF34F8F064B884204D3BFF34F8F08 +:10218000BFF36F8F7047C3F85C022030F4E700BFE5 +:1021900000ED00E0034B1A681AB9034AD2F874281C +:1021A0001A607047742D01200030024008B5FFF717 +:1021B000F1FF024B1868C0F3407008BD742D012078 +:1021C00070B5BFF34F8FBFF36F8F1A4A0021C2F86B +:1021D0005012BFF34F8FBFF36F8F536943F4003337 +:1021E0005361BFF34F8FBFF36F8FC2F88410BFF3FB +:1021F0004F8FD2F88030C3F3C900C3F34E335B0175 +:1022000043F6E07403EA0406014646EA81750139A3 +:10221000C2F86052F9D2203B13F1200FF2D1BFF384 +:102220004F8F536943F480335361BFF34F8FBFF334 +:102230006F8F70BD00ED00E0FEE7000070B5214B30 +:102240002148224A904237D3214BDA1C121AC11E70 +:1022500022F003028B4238BF00220021FEF7A2FDCC +:102260001C4A0023C2F88430BFF34F8FD2F880306D +:10227000C3F3C900C3F34E335B0143F6E07403EAD2 +:102280000406014646EA81750139C2F86C52F9D25A +:10229000203B13F1200FF2D1BFF34F8FBFF36F8FAD +:1022A000BFF34F8FBFF36F8F0023C2F85032BFF3DD +:1022B0004F8FBFF36F8F70BD53F8041B40F8041BA2 +:1022C000C0E700BFF4390008882E0120882E0120C5 +:1022D000882E012000ED00E070B5D0E91B439E6818 +:1022E00000224FF0FF3504EB42135101D3F80009EF +:1022F0000028BEBFD3F8000940F08040C3F80009B1 +:10230000D3F8000B0028BEBFD3F8000B40F080408C +:10231000C3F8000B013263189642C3F80859C3F89A +:10232000085BE0D24FF00113C4F81C3870BD000008 +:10233000890141F02001016103699B06FCD4122050 +:10234000FFF7A0BA10B5054C2046FEF76DFF4FF021 +:10235000A043E366024B236710BD00BF782D012028 +:102360004838000870B50378012B054650D12A4B38 +:10237000C46E98421BD1294B5A6B42F080025A63BB +:102380005A6D42F080025A655A6D5A6942F08002D5 +:102390005A615A6922F080025A610E2143205B691A +:1023A00000F03AFC1E4BE3601E4BC4F800380023DB +:1023B000C4F8003EC0232360EE6E4FF40413A36301 +:1023C0003369002BFCDA012333610C20FFF75AFA42 +:1023D0003369DB07FCD41220FFF754FA3369002B72 +:1023E000FCDA0026A6602846FFF776FF6B68C4F883 +:1023F0001068DB68C4F81468C4F81C684BB90A4B51 +:10240000A3614FF0FF336361A36843F00103A3604E +:1024100070BD064BF4E700BF782D01200038024064 +:102420004014004003002002003C30C0083C30C093 +:10243000F8B5C46E054600212046FFF779FF296FE5 +:1024400000234FF001128F68C4F834384FF0006653 +:10245000C4F81C284FF0FF3004EB431201339F42B5 +:10246000C2F80069C2F8006BC2F80809C2F8080B8C +:10247000F2D20B68EA6E6B67636210231361166910 +:1024800016F01006FBD11220FFF7FCF9D4F8003843 +:1024900023F4FE63C4F80038A36943F4402343F0F7 +:1024A0001003A3610923C4F81038C4F814380A4B88 +:1024B000EB604FF0C043C4F8103B084BC4F8003B3E +:1024C000C4F81069C4F800396B6F03F1100243F4CB +:1024D00080136A67A362F8BD2438000840800010AA +:1024E000C26E90F86610D2F8003823F4FE6343EA17 +:1024F0000113C2F8003870472DE9F84300EB81035F +:10250000C56EDA68166806F00306731E022B05EB2B +:1025100041130C4680460FFA81F94FEA41104FF003 +:102520000001C3F8101B4FF0010104F1100398BF24 +:10253000B60401FA03F391698EBF334E06F180565B +:1025400006F5004600293AD0578A04F1580149019E +:1025500037436F50D5F81C180B43C5F81C382B189F +:102560000021C3F8101953690127611EA7409BB3CE +:10257000138A928B9B08012A88BF5343D8F8742092 +:10258000981842EA034301F1400205EB8202C8F8C1 +:102590007400214653602846FFF7CAFE08EB890005 +:1025A000C3681B8A43EA8453483464011E432E5196 +:1025B000D5F81C381F43C5F81C78BDE8F88305EB37 +:1025C0004917D7F8001B21F40041C7F8001BD5F8C4 +:1025D0001C1821EA0303C0E704F13F0305EB830362 +:1025E0000A4A5A6028462146FFF7A2FE05EB491029 +:1025F000D0F8003923F40043C0F80039D5F81C386E +:1026000023EA0707D7E700BF00800010000400029C +:10261000026F12684267FFF75FBE00005831C36E59 +:1026200049015B5813F4004004D013F4001F0CBFA1 +:1026300002200120704700004831C36E49015B58F9 +:1026400013F4004004D013F4001F0CBF022001203B +:102650007047000000EB8101CB68196A0B681360BA +:102660004B6853607047000000EB810330B5DD68B4 +:10267000AA691368D36019B9402B84BF4023136043 +:102680006B8A1468C26E1C44013CB4FBF3F46343D0 +:10269000033323F0030302EB411043EAC44343F046 +:1026A000C043C0F8103B2B6803F00303012B09B2B1 +:1026B0000ED1D2F8083802EB411013F4807FD0F825 +:1026C000003B14BF43F0805343F00053C0F8003B7D +:1026D00002EB4112D2F8003B43F00443C2F8003B46 +:1026E00030BD00002DE9F041254DEE6E06EB4013A4 +:1026F0000446D3F8087BC3F8087B38070AD5D6F818 +:102700001438190706D505EB84032146DB682846F3 +:102710005B689847FA0721D5D6F81438DB071DD532 +:1027200005EB8403D968DCB98B69488A5A68B2FB27 +:10273000F0F600FB16229AB91868DA6890420FD2B8 +:10274000121AC3E9002472B6302383F3118862B6EB +:102750000B482146FFF788FF84F31188BDE8F0811C +:10276000012303FA04F26B8923EA02036B81CB682D +:10277000002BF3D021460248BDE8F041184700BFC6 +:10278000782D012000EB810370B5DD68C36E6C69A4 +:102790002668E6604A0156BB1A444FF40020C2F88E +:1027A00010092A6802F00302012A0AB20ED1D3F8F6 +:1027B000080803EB421410F4807FD4F8000914BF1A +:1027C00040F0805040F00050C4F8000903EB421282 +:1027D000D2F8000940F00440C2F80009D3F83408E8 +:1027E000012202FA01F10143C3F8341870BD19B98E +:1027F000402E84BF4020206020682E8A8419013C2E +:10280000B4FBF6F440EAC44040F000501A44C6E776 +:102810002DE9F8433C4DEE6E06EB40130446D3F829 +:102820000889C3F8088918F0010F4FEA40171CD037 +:10283000D6F81038DB0718D505EB8003D9684B694B +:102840001868DA68904232D2121A4FF000091A6002 +:10285000C3F8049072B6302383F3118862B6214620 +:102860002846FFF78FFF89F3118818F0800F1CD0DE +:10287000D6F834380126A640334216D005EB84033F +:10288000ED6ED3F80CC0DCF814200134E4B2D2F8B9 +:1028900000E005EB04342F445168714515D3D5F899 +:1028A000343823EA0606C5F83468BDE8F883012306 +:1028B00003FA04F22B8923EA02032B818B68002B95 +:1028C000D3D0214628469847CFE7BCF81000AEEB9E +:1028D0000103834228BF0346D7F8180980B2B3EB3F +:1028E000800FE2D89068A0F1040959F8048FC4F869 +:1028F0000080A0EB09089844B8F1040FF5D81844FB +:102900000B4490605360C7E7782D01202DE9F74F05 +:10291000AC4CE56E6E69AB691E4016F480586E6172 +:1029200007D02046FEF7ECFC03B0BDE8F04F00F006 +:102930006BBC002E12DAD5F8003EA2489B071EBFE2 +:10294000D5F8003E23F00303C5F8003ED5F804385F +:1029500023F00103C5F80438FEF7FEFC370505D562 +:102960009848FFF7B9FC9748FEF7E4FCB0040CD593 +:10297000D5F8083813F0060FEB6823F470530CBF3A +:1029800043F4105343F4A053EB6031071BD5636845 +:10299000DB681BB9AB6923F00803AB612378052B17 +:1029A0000CD1D5F8003E87489A071EBFD5F8003EE7 +:1029B00023F00303C5F8003EFEF7CEFC6368DB6836 +:1029C0000BB180489847F30200F18980B70227D500 +:1029D000D4F86C90DFF8ECB100274FF0010A09EB56 +:1029E0004712D2F8003B03F44023B3F5802F11D1F6 +:1029F000D2F8003B002B0DDA62890AFA07F322EACB +:102A00000303638104EB8703DB68DB6813B139469A +:102A100058469847236F01379B68FFB29F42DED923 +:102A2000F00617D5E76E3A6AC2F30A1002F00F03F8 +:102A300002F4F012B2F5802F00F09980B2F5402F29 +:102A400008D104EB83030022DB681B6A07F580577B +:102A500090427ED13303D5F818481DD5E70302D53F +:102A60000020FFF73FFEA50302D50120FFF73AFE45 +:102A7000600302D50220FFF735FE210302D50320B3 +:102A8000FFF730FEE20202D50420FFF72BFEA3027F +:102A900002D50520FFF726FE77037FF545AFE60751 +:102AA00002D50020FFF7B4FEA50702D50120FFF7ED +:102AB000AFFE600702D50220FFF7AAFE210702D56C +:102AC0000320FFF7A5FEE20602D50420FFF7A0FED3 +:102AD000A3067FF529AF0520FFF79AFE24E7E36EF2 +:102AE000DFF8E0A0019300274FF00109236F9B68F6 +:102AF0005FFA87FB9B453FF669AF019B03EB4B13E6 +:102B0000D3F8001901F44021B1F5802F1FD1D3F87B +:102B1000001900291BDAD3F8001941F09041C3F8DD +:102B20000019D3F800190029FBDB5946E06EFFF7C6 +:102B3000FFFB218909FA0BF321EA0303238104EB4C +:102B40008B03DB689B6813B15946504698470137A1 +:102B5000CCE7910708BFD7F80080072A98BF03F891 +:102B6000018B02F1010298BF4FEA182870E7023387 +:102B700004EB830207F580575268D2F818C0DCF8DE +:102B80000820DCE9001CA1EB0C0C002188420AD1D2 +:102B900004EB830463689B699A6802449A605A68EC +:102BA00002445A6056E711F0030F08BFD7F80080BF +:102BB0008C4588BF02F8018B01F1010188BF4FEA03 +:102BC0001828E3E7782D0120C36E03EB4111D1F8FB +:102BD000003B43F40013C1F8003B7047C36E03EBA6 +:102BE0004111D1F8003943F40013C1F8003970479E +:102BF000C36E03EB4111D1F8003B23F40013C1F87D +:102C0000003B7047C36E03EB4111D1F8003923F448 +:102C10000013C1F80039704700F1604303F56143C8 +:102C20000901C9B283F80013012200F01F039A4082 +:102C300043099B0003F1604303F56143C3F880211E +:102C40001A60704772B6302383F3118862B67047FA +:102C500030B5039C0172043304FB0325C0E906531D +:102C6000049B03630021059BC160C0E90000C0E92B +:102C70000422C0E90842C0E90A11436330BD0000E4 +:102C8000416A0022C0E90411C0E90A22C2606FF063 +:102C90000101FEF76FBE0000D0E90432934201D17A +:102CA000C2680AB9181D704700207047036919608F +:102CB000C2680132C260C2691344826903619342EF +:102CC00024BF436A03610021FEF748BE38B50446BD +:102CD0000D46E3683BB16269131D1268A362134499 +:102CE000E362002007E0237A33B929462046FEF745 +:102CF00025FE0028EDDA38BD6FF00100FBE700008B +:102D0000C368C269013BC36043691344826943617C +:102D1000934224BF436A436100238362036B03B180 +:102D20001847704770B5FFF78DFF866A04463EB9B5 +:102D3000FFF7CCFF054618B186F31188284670BD11 +:102D4000A36AE26A13F8015BA362934202D32046AE +:102D5000FFF7D6FF002383F31188EFE72DE9F04753 +:102D60009846FFF76FFF002504460E461746A94612 +:102D7000D4F828A0BAF1000F09D141462046FFF748 +:102D8000A5FF20B18AF311882846BDE8F087D4E971 +:102D90000A12A7EB050A521A924528BF9246BAF1C9 +:102DA000400F1BD9334601F1400251F8040B43F8A0 +:102DB000040B9142F9D1A36A40334036A3624035F7 +:102DC000D4E90A239A4202D32046FFF799FF89F3F8 +:102DD0001188BD42D8D2FFF735FFC9E730465246C9 +:102DE000FDF7BAFFA36A53445644A3625544E7E78C +:102DF00010B5029C0172043303FB0421C0E90613E1 +:102E00000023C0E90A33039B0363049BC460C0E949 +:102E10000000C0E90422C0E90842436310BD00007D +:102E2000026AC260426AC0E904220022C0E90A22A2 +:102E30006FF00101FEF79EBDD0E904239A4201D153 +:102E4000C26822B9184650F8043B0B607047002353 +:102E50001846FAE7C368C2690133C3604369134483 +:102E600082694361934224BF436A43610021FEF7B4 +:102E700075BD000038B504460D46E3683BB12369D3 +:102E80001A1DA262E2691344E362002007E0237A7C +:102E900033B929462046FEF751FD0028EDDA38BD4A +:102EA0006FF00100FBE7000003691960C268013A96 +:102EB000C260C269134482690361934224BF436ABA +:102EC000036100238362036B03B11847704700005E +:102ED00070B5FFF7B7FE866A0D46044611462EB957 +:102EE000FFF7C8FF10B186F3118870BDA36A1D708B +:102EF000A36AE26A01339342A36204D3E1692046E4 +:102F00000439FFF7D1FF002080F31188EDE70000BE +:102F10002DE9F0479946FFF795FE002604460D4639 +:102F20009046B246A76A4FB949462046FFF7A2FF2E +:102F300020B187F311883046BDE8F087D4E90A074D +:102F40003A1AA8EB0607974228BF1746402F1BD90D +:102F500005F1400355F8042B40F8042B9D42F9D1AC +:102F6000A36A4033A3624036D4E90A239A4204D3C9 +:102F7000E16920460439FFF797FF8AF31188464537 +:102F8000D9D2FFF75FFECDE729463A46FDF7E4FECA +:102F9000A36A3B443D44A3623E44E5E7D0E90423F1 +:102FA0009A4217D1C3689BB1836A8BB1043B9B1AC9 +:102FB0000ED01360C368013BC360C3691A448369C0 +:102FC00002619A4224BF436A0361002383620123A2 +:102FD000184670470023FBE700F042B94FF08043EA +:102FE000586A70474FF08043002258631A610222EA +:102FF000DA6070474FF080430022DA6070470000CB +:103000004FF0804358637047FEE7000070B51B4BDC +:1030100001630025044686B0586085620E4600F0C4 +:10302000CBF804F11003C4E904334FF0FF33C4E9D3 +:103030000635C4E90044A560E562FFF7CFFF2B46E3 +:103040000246C4E9082304F134010D4A25658023B2 +:103050002046FEF727FC0123E0600A4A0375009230 +:1030600072680192B268CDE90223074B6846CDE948 +:103070000435FEF73FFC06B070BD00BF20260120DE +:10308000543800085938000809300008024AD36A49 +:103090001843D062704700BFB82301204B684360DB +:1030A0008B688360CB68C3600B6943614B690362C3 +:1030B0008B6943620B6803607047000008B52C4BB6 +:1030C0002C481A6940F2FF710A431A611A6922F406 +:1030D000FF6222F007021A611A691A6B0A431A6327 +:1030E0001A6D0A431A65244A1B6D1146FFF7D6FF75 +:1030F00002F11C0100F58060FFF7D0FF02F13801FA +:1031000000F58060FFF7CAFF02F1540100F580600E +:10311000FFF7C4FF02F1700100F58060FFF7BEFF0A +:1031200002F18C0100F58060FFF7B8FF02F1A80101 +:1031300000F58060FFF7B2FF02F1C40100F5806086 +:10314000FFF7ACFF02F1E00100F58060FFF7A6FF9A +:1031500002F1FC0100F58060FFF7A0FF02F58C7121 +:1031600000F58060FFF79AFFBDE8084000F0EEB878 +:1031700000380240000002406038000808B500F046 +:1031800059FAFEF767FBFFF705F8BDE80840FEF7C0 +:10319000E1BD000070470000EFF3098305494A6B69 +:1031A00022F001024A63683383F30988002383F322 +:1031B0001188704700EF00E0302080F3118862B67C +:1031C0000D4B0E4AD96821F4E0610904090C0A4349 +:1031D000DA60D3F8FC200A4942F08072C3F8FC2080 +:1031E000084AC2F8B01F116841F0010111602022A5 +:1031F000DA7783F82200704700ED00E00003FA055B +:1032000055CEACC5001000E010B572B6302383F384 +:10321000118862B60E4B5B6813F4006314D0F1EEB4 +:10322000103AEFF30984683C4FF08073E361094B77 +:10323000DB6B236684F30988FEF7ECFA10B1064BCA +:10324000A36110BD054BFBE783F31188F9E700BFCD +:1032500000ED00E000EF00E04F030008520300081B +:103260000F4B1A6C42F001021A641A6E42F001020E +:103270001A660C4A1B6E936843F0010393604FF08B +:1032800080436B229A624FF0FF32DA6200229A6129 +:103290005A63DA605A6001225A611A60704700BFAF +:1032A00000380240002004E04FF0804208B5116968 +:1032B000D3680B40D9B2C9439B07116109D572B6D7 +:1032C000302383F3118862B6FEF7DAFA002383F322 +:1032D000118808BD1B4B1A696FEA42526FEA5252BD +:1032E0001A611A69C2F30A021A614FF0FF301A69B3 +:1032F0005A69586100215A6959615A691A6A62F01B +:1033000080521A621A6A02F080521A621A6A5A6A63 +:1033100058625A6A59625A6A0B4A106840F48070BF +:103320001060186F00F44070B0F5007F1EBF4FF4BE +:10333000803018671967536823F40073536000F0F6 +:1033400055B900BF0038024000700040374B4FF0C5 +:1033500080521A64364A4FF4404111601A6842F0B4 +:1033600001021A601A689207FCD59A6822F00302DB +:103370009A602E4B9A6812F00C02FBD1196801F08A +:10338000F90119609A601A6842F480321A601A686A +:103390009003FCD55A6F42F001025A67234B5A6FD3 +:1033A0009107FCD5234A5A601A6842F080721A606D +:1033B0001F4B5A685204FCD51A6842F480321A60D6 +:1033C0005A68D003FCD51A6842F400321A60184AD1 +:1033D00053689903FCD5154B1A689201FCD5164A1F +:1033E0009A6040F20112C3F88C200022C3F89020AA +:1033F000124A40F207331360136803F00F03072BE0 +:10340000FAD10A4B9A6842F002029A609A6802F076 +:103410000C02082AFAD15A6C42F480425A645A6E5D +:1034200042F480425A665B6E704700BF003802402B +:1034300000700040086C400900948838003C02404D +:10344000074A08B5536903F00103536123B1054AE4 +:1034500013680BB150689847BDE80840FFF7D4BE29 +:10346000003C0140082E0120074A08B5536903F0CB +:103470000203536123B1054A93680BB1D0689847A2 +:10348000BDE80840FFF7C0BE003C0140082E012007 +:10349000074A08B5536903F00403536123B1054A91 +:1034A00013690BB150699847BDE80840FFF7ACBEFF +:1034B000003C0140082E0120074A08B5536903F07B +:1034C0000803536123B1054A93690BB1D06998474A +:1034D000BDE80840FFF798BE003C0140082E0120DF +:1034E000074A08B5536903F01003536123B1054A35 +:1034F000136A0BB1506A9847BDE80840FFF784BED5 +:10350000003C0140082E0120164B10B55C6904F404 +:1035100078725A61A30604D5134A936A0BB1D06A34 +:103520009847600604D5104A136B0BB1506B98474F +:10353000210604D50C4A936B0BB1D06B9847E2057A +:1035400004D5094A136C0BB1506C9847A30504D5F8 +:10355000054A936C0BB1D06C9847BDE81040FFF75B +:1035600053BE00BF003C0140082E0120194B10B58E +:103570005C6904F47C425A61620504D5164A136DF5 +:103580000BB1506D9847230504D5134A936D0BB1C9 +:10359000D06D9847E00404D50F4A136E0BB1506EFE +:1035A0009847A10404D50C4A936E0BB1D06E98478E +:1035B000620404D5084A136F0BB1506F9847230477 +:1035C00004D5054A936F0BB1D06F9847BDE8104002 +:1035D000FFF71ABE003C0140082E012008B5FFF796 +:1035E00063FEBDE80840FFF70FBE0000062108B5E6 +:1035F0000846FFF711FB06210720FFF70DFB062108 +:103600000820FFF709FB06210920FFF705FB06212B +:103610000A20FFF701FB06211720FFF7FDFA06211C +:103620002820FFF7F9FABDE8084007211C20FFF722 +:10363000F3BA000008B5FFF74DFE00F00BF8FDF7F8 +:10364000F1FDFDF7C3FCFFF7A5FDBDE80840FFF75E +:10365000C3BC00000023054A19460133102BC2E900 +:10366000001102F10802F8D1704700BF082E0120B6 +:10367000034611F8012B03F8012B002AF9D17047FA +:1036800053544D3332463F3F3F3F3F3F0053544D2D +:10369000333246375B347C355D780053544D3332DA +:1036A00046375B367C375D78000000000000000084 +:1036B000490F0008350F0008710F00085D0F000862 +:1036C000690F0008550F0008410F00082D0F000872 +:1036D0007D0F000800000000010000000000000055 +:1036E00063300000E036000810240120202601206D +:1036F0004172647550696C6F740025424F415244A9 +:10370000252D424C002553455249414C25000000CF +:10371000020000000000000065110008D11100083F +:1037200040004000C02A0120D02A012002000000F1 +:103730000000000003000000000000001512000857 +:103740000000000010000000E02A0120000000003E +:103750000100000000000000782D0120010102009E +:10376000F51C0008091C0008A11C0008891C0008A1 +:10377000430000007837000809024300020100C03E +:1037800032090400000102020100052400100105B5 +:103790002401000104240202052406000107058219 +:1037A000030800FF09040100020A000000070501E8 +:1037B00002400000070581024000000012000000E6 +:1037C000C4370008120110010200004009124157DD +:1037D00000020102030100000403090425424F41D5 +:1037E00052442500426C69747A463734354D696E0F +:1037F0006900303132333435363738394142434449 +:1038000045460000008000000080000000800000AD +:10381000008000000000020000000400000004001E +:1038200000000400000000007113000821160008C9 +:10383000C916000840004000F02D0120F02D0120A5 +:1038400001000000002E0120800000004001000067 +:10385000050000006D61696E0069646C6500000020 +:103860000001806A00000000AAAAAAAA0001006460 +:10387000FFFF00000000000000A00A0000000000A0 +:1038800000000000AAAAAAAA00000000FFFF000092 +:103890000000000000000000000004000000000024 +:1038A000AAAAAAAA00000000FFFD00000000000074 +:1038B000000000000000000000000000AAAAAAAA60 +:1038C00000000000FFFF00000000000000000000FA +:1038D0000001000000000000AAAAAAAA000100003E +:1038E000FFFF0000000000000000000000000000DA +:1038F00000000000AAAAAAAA00000000FFFF000022 +:1039000000000000000000000000000000000000B7 +:10391000AAAAAAAA00000000FFFF00000000000001 +:103920000000000000000000000000000A0000008D +:103930000000000003000000000000000000000084 +:103940000000000000000000000000000000000077 +:103950000000000000000000000000000000000067 +:103960000000000000000000000000000000000057 +:103970000000000000000000000000000000000047 +:103980000000000000000000000000000000000037 +:1039900000000000000000008B0400000000000098 +:1039A00000800E0000000000FF000000000000008A +:1039B00080360008490400008D36000851040000DC +:1039C0009B360008009600000000080096000000EA +:1039D0000008000004000000D837000800000000C4 +:1039E00000000000000000000000000000000000D7 +:0439F00000000000D3 +:00000001FF diff --git a/Tools/bootloaders/BlitzWingH743_bl.bin b/Tools/bootloaders/BlitzWingH743_bl.bin new file mode 100644 index 00000000000000..08a22a32f96584 Binary files /dev/null and b/Tools/bootloaders/BlitzWingH743_bl.bin differ diff --git a/Tools/bootloaders/BlitzWingH743_bl.hex b/Tools/bootloaders/BlitzWingH743_bl.hex new file mode 100644 index 00000000000000..275e235c6dda6b --- /dev/null +++ b/Tools/bootloaders/BlitzWingH743_bl.hex @@ -0,0 +1,1103 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200086928000870 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008D53D0008013E000865 +:100060002D3E0008593E0008853E0008711000082A +:1000700099100008C5100008F11000081D110008B3 +:100080004511000871110008E3020008E3020008AE +:10009000E3020008E3020008E3020008B13E0008A2 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000153F0008E3020008E3020008E3020008ED +:1000F000E3020008E3020008E30200089D11000883 +:10010000E3020008E3020008893F0008E302000858 +:10011000E3020008E3020008E3020008E30200082B +:10012000C9110008F11100081D1200084912000849 +:1001300075120008E3020008E3020008E302000869 +:10014000E3020008E3020008E3020008E3020008FB +:100150009D120008C9120008F5120008E302000809 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000855340008E3020008E302000827 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000841340008E3020008E3020008DB +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0EEFA86 +:1003500003F0FCFA4FF055301F491B4A91423CBF55 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F006FB03F05AFBFE +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0EEBA00060020002200207C +:1003D0000000000808ED00E00000002000060020FA +:1003E00068440008002200205C22002060220020D7 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0A4FDFEE701F056 +:1004300033FD00DFFEE7000038B500F02FFC00F0D0 +:10044000ABFD02F0D1F9054602F004FA0446C0B94A +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0C8F90CB100F078 +:1004700075F800F065FD284600F01EF900F06EF8F2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F021FE0023154A4FF4D1 +:1004D0007A71134801F010FE002383F31188124C47 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F088FC322363602B78032B07D16368EB +:100510002BB9022000F07EFC4FF47A73636038BD83 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05DBC022000F050BC024B0022F3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E3FBB14AB8 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F011FD0023AB4A4FF4F0 +:1006F0007A71A94801F000FD002383F31188009B63 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F06BFB24B19C4B1B6860 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F058FB26B10BF03D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F032FA019AFF217F4800F053FA4FEAF3 +:1009F000A803C8F387027C492846019300F052FA05 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F7FA8046E7E7384600F03AF945 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09DF900283AD020228E +:100B7000FF210AA800F08EF9FFF792FC1C4801F053 +:100B8000FFF913B0BDE8F08F002E3FF42BAE0BF051 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0DDF9059800F0E4F946463C462E +:100BD00000F0ACF9A6E506464EE64FF0000901E646 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0A8F98B +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F088FC308028683388834294 +:100CB00008D901F07DFC2B6804440133B4F5C02F42 +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F040BD00F1006000F5C02000687047E1 +:100CE00000F10060920000F5C02001F0C1BC0000DE +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F056BC0020704788230020B623002045 +:100D100038B50446074D29B128682044BDE838405D +:100D200001F05EBC2868204401F048FC0028F3D0A4 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C1422002080400008022803D17B +:100DF000024B4FF080729A61704700BF00000258AA +:100E0000022803D1024B4FF480729A61704700BFF1 +:100E100000000258022804D1024A536983F4807307 +:100E2000536170470000025870B504464FF47A765B +:100E30004CB1412C254628BF412506FB05F0641B1B +:100E400001F09EF8F4E770BD002310B5934203D083 +:100E5000CC5CC4540133F9E710BD0000013810B573 +:100E600010F9013F3BB191F900409C4203D11AB106 +:100E70000131013AF4E71AB191F90020981A10BD36 +:100E80001046FCE703460246D01A12F9011B00295E +:100E9000FAD1704702440346934202D003F8011B83 +:100EA000FAE770472DE9F8431F4D14460746884678 +:100EB00095F8242052BBDFF870909CB395F824304D +:100EC0002BB92022FF2148462F62FFF7E3FF95F858 +:100ED00024004146C0F1080205EB8000A24228BF71 +:100EE0002246D6B29200FFF7AFFF95F82430A41B3C +:100EF00017441E449044E4B2F6B2082E85F82460EC +:100F0000DBD1FFF723FF0028D7D108E02B6A03EBE2 +:100F100082038342CFD0FFF719FF0028CBD10020F6 +:100F2000BDE8F8830120FBE78C230020024B1A78F0 +:100F3000024B1A70704700BFB4230020102200201B +:100F400010B5114C114800F06FFB21460F4800F01E +:100F500097FB24684FF47A70D4F89020D2F80438C4 +:100F600043F00203C2F80438FFF75EFF0849204649 +:100F700000F094FCD4F89020D2F8043823F0020357 +:100F8000C2F8043810BD00BF3C420008B026002063 +:100F90004442000870470000F0B5A1B071B60023CC +:100FA0000120002480261A46194600F04BFA4FF41F +:100FB000D067214A3D25136923BBD2F810310BBB02 +:100FC000036804F1006199600368C3F80CD00368FA +:100FD0005E6003681F6001680B6843F001030B60EB +:100FE00001680B6823F01E030B6001680B68DB07C8 +:100FF000FCD4037B8034416805FA03F3B4F5001F89 +:101000000B60D8D100F05EFAB4F5001F11D00024B7 +:101010000A4E0B4D012001F09DFB3388A34205D9F8 +:1010200028682044013401F0DBFAF6E7002001F0E3 +:1010300091FB61B621B0F0BD00200052B623002024 +:101040008823002030B50A44084D91420DD011F894 +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:1010700008B5074B074A196801F03D0199605368AC +:101080000BB190689847BDE8084001F025BC00BF4F +:1010900000000240B823002008B5084B19688909F0 +:1010A00001F03D018A019A60054AD3680BB11069CD +:1010B0009847BDE8084001F00FBC00BF00000240A7 +:1010C000B823002008B5084B1968090C01F03D0150 +:1010D0000A049A60054A53690BB190699847BDE8C4 +:1010E000084001F0F9BB00BF00000240B823002017 +:1010F00008B5084B1968890D01F03D018A059A6011 +:10110000054AD3690BB1106A9847BDE8084001F061 +:10111000E3BB00BF00000240B823002008B5074B26 +:10112000074A596801F03D01D960536A0BB1906AD2 +:101130009847BDE8084001F0CFBB00BF0000024067 +:10114000B823002008B5084B5968890901F03D0112 +:101150008A01DA60054AD36A0BB1106B9847BDE883 +:10116000084001F0B9BB00BF00000240B8230020D6 +:1011700008B5084B5968090C01F03D010A04DA6012 +:10118000054A536B0BB1906B9847BDE8084001F0DE +:10119000A3BB00BF00000240B823002008B5084BE5 +:1011A0005968890D01F03D018A05DA60054AD36B63 +:1011B0000BB1106C9847BDE8084001F08DBB00BF33 +:1011C00000000240B823002008B5074B074A196801 +:1011D00001F03D019960536C0BB1906C9847BDE8EC +:1011E000084001F079BB00BF00040240B823002092 +:1011F00008B5084B1968890901F03D018A019A6018 +:10120000054AD36C0BB1106D9847BDE8084001F05A +:1012100063BB00BF00040240B823002008B5084BA0 +:101220001968090C01F03D010A049A60054A536DE2 +:101230000BB1906D9847BDE8084001F04DBB00BF71 +:1012400000040240B823002008B5084B1968890D36 +:1012500001F03D018A059A60054AD36D0BB1106E0D +:101260009847BDE8084001F037BB00BF00040240CA +:10127000B823002008B5074B074A596801F03D0123 +:10128000D960536E0BB1906E9847BDE8084001F0ED +:1012900023BB00BF00040240B823002008B5084B60 +:1012A0005968890901F03D018A01DA60054AD36E67 +:1012B0000BB1106F9847BDE8084001F00DBB00BFAF +:1012C00000040240B823002008B5084B5968090CF7 +:1012D00001F03D010A04DA60054A536F0BB1906FCB +:1012E0009847BDE8084001F0F7BA00BF000402408B +:1012F000B823002008B5084B5968890D01F03D015D +:101300008A05DA60054AD36F13B1D2F88000984796 +:10131000BDE8084001F0E0BA00040240B823002014 +:1013200000230C4910B51A460B4C0B6054F82300EF +:10133000026001EB430004334260402BF6D1074AC0 +:101340004FF0FF339360D360C2F80834C2F80C3416 +:1013500010BD00BFB82300209040000800000240EC +:101360000F28F8B510D9102810D0112811D0122844 +:1013700008D10F240720DFF8C8E00126DEF800506E +:10138000A04208D9002653E00446F4E70F240020C9 +:10139000F1E70724FBE706FA00F73D424AD1264C65 +:1013A0004FEA001C3D4304EB00160EEBC000CEF8E4 +:1013B0000050C0E90123FBB273B12048D0F8D83007 +:1013C00043F00103C0F8D830D0F8003143F00103F6 +:1013D000C0F80031D0F8003117F47F4F0ED0174815 +:1013E000D0F8D83043F00203C0F8D830D0F800313C +:1013F00043F00203C0F80031D0F8003154F80C007B +:10140000036823F01F030360056815F00105FBD195 +:1014100004EB0C033D2493F80CC05F6804FA0CF451 +:101420003C6021240560446112B1987B00F054F8BF +:101430003046F8BD0130A3E7904000080044025850 +:10144000B823002010B5302484F31188FFF788FFFB +:10145000002383F3118810BD10B50446807B00F093 +:1014600051F801231549627B03FA02F20B6823EA63 +:101470000203DAB20B6072B9114AD2F8D81021F027 +:101480000101C2F8D810D2F8001121F00101C2F810 +:101490000011D2F8002113F47F4F0ED1084BD3F87E +:1014A000D82022F00202C3F8D820D3F8002122F07D +:1014B0000202C3F80021D3F8003110BDB823002088 +:1014C0000044025808B5302383F31188FFF7C4FFA6 +:1014D000002383F3118808BD090100F16043012254 +:1014E00003F56143C9B283F8001300F01F039A406B +:1014F00043099B0003F1604303F56143C3F8802176 +:101500001A60704700F01F0301229A40430900F15E +:1015100060409B0000F5614003F1604303F56143C7 +:10152000C3F88020C3F88021002380F8003370477F +:10153000026843681143016003B118477047000017 +:1015400013B5406B00F58054D4F8A4381A681178AC +:10155000042914D1017C022911D11979012312899E +:101560008B4013420BD101A94C3002F0A5F8D4F8FE +:10157000A4480246019B2179206800F0DFF902B0FF +:1015800010BD0000143002F027B800004FF0FF3308 +:10159000143002F021B800004C3002F0F9B800001D +:1015A0004FF0FF334C3002F0F3B80000143001F07C +:1015B000F5BF00004FF0FF31143001F0EFBF000025 +:1015C0004C3002F0C5B800004FF0FF324C3002F052 +:1015D000BFB800000020704710B500F58054D4F863 +:1015E000A4381A681178042917D1017C022914D172 +:1015F0005979012352898B4013420ED1143001F0E6 +:1016000087FF024648B1D4F8A4484FF4407361798B +:101610002068BDE8104000F07FB910BD406BFFF7B7 +:10162000DBBF0000704700007FB5124B0125042688 +:10163000044603600023057400F1840243602946D8 +:10164000C0E902330C4B0290143001934FF4407305 +:10165000009601F039FF094B04F69442294604F143 +:101660004C000294CDE900634FF4407302F000F89F +:1016700004B070BD904100081D1600084115000817 +:101680000A68302383F311880B790B3342F8230067 +:101690004B79133342F823008B7913B10B3342F8A3 +:1016A000230000F58053C3F8A4180223037400201C +:1016B00080F311887047000038B5037F044613B1EA +:1016C00090F85430ABB90125201D0221FFF730FFFF +:1016D00004F114006FF00101257700F079FC04F1AA +:1016E0004C0084F854506FF00101BDE8384000F020 +:1016F0006FBC38BD10B5012104460430FFF718FF58 +:101700000023237784F8543010BD000038B5044618 +:101710000025143001F0F0FE04F14C00257701F0B3 +:10172000BFFF201D84F854500121FFF701FF204620 +:10173000BDE83840FFF750BF90F8803003F06003F9 +:10174000202B06D190F881200023212A03D81F2ABC +:1017500006D800207047222AFBD1C0E91D3303E0E0 +:10176000034A426707228267C3670120704700BFB0 +:101770002C22002037B500F58055D5F8A4381A681A +:10178000117804291AD1017C022917D11979012372 +:1017900012898B40134211D100F14C04204602F013 +:1017A0003FF858B101A9204601F086FFD5F8A448BA +:1017B0000246019B2179206800F0C0F803B030BDDB +:1017C00001F10B03F0B550F8236085B004460D46D7 +:1017D000FEB1302383F3118804EB8507301D082107 +:1017E000FFF7A6FEFB6806F14C005B691B681BB1A6 +:1017F000019001F06FFF019803A901F05DFF02461F +:1018000048B1039B2946204600F098F8002383F353 +:10181000118805B0F0BDFB685A691268002AF5D03E +:101820001B8A013B1340F1D104F18002EAE700007A +:10183000133138B550F82140ECB1302383F31188CF +:1018400004F58053D3F8A4281368527903EB82037C +:10185000DB689B695D6845B104216018FFF768FE8D +:10186000294604F1140001F05DFE2046FFF7B4FEA6 +:10187000002383F3118838BD7047000001F02AB9B6 +:1018800001234022002110B5044600F8303BFFF749 +:1018900001FB0023C4E9013310BD000010B5302363 +:1018A000044683F311882422416000210C30FFF7A5 +:1018B000F1FA204601F030F902230020237080F372 +:1018C000118810BD70B500EB8103054650690E46C6 +:1018D0001446DA6018B110220021FFF7DBFAA06984 +:1018E00018B110220021FFF7D5FA31462846BDE88D +:1018F000704001F017BA000083682022002103F035 +:10190000011310B5044683601030FFF7C3FA204678 +:10191000BDE8104001F092BAF0B4012500EB81045B +:1019200047898D40E4683D43A469458123600023D5 +:10193000A2606360F0BC01F0AFBA0000F0B4012512 +:1019400000EB810407898D40E4683D4364690581AB +:1019500023600023A2606360F0BC01F025BB00009F +:1019600070B5022300250446242203702946C0F8DE +:1019700088500C3040F8045CFFF78CFA204684F85D +:10198000705001F063F963681B6823B12946204653 +:10199000BDE87040184770BD0378052B10B50446AC +:1019A0000AD080F88C300523037043681B680BB1A4 +:1019B000042198470023A36010BD00000178052989 +:1019C00006D190F88C20436802701B6803B1184759 +:1019D0007047000070B590F87030044613B10023D2 +:1019E00080F8703004F18002204601F04BFA636801 +:1019F0009B68B3B994F8803013F0600535D00021AE +:101A0000204601F03DFD0021204601F02DFD6368D8 +:101A10001B6813B1062120469847062384F87030CE +:101A200070BD204698470028E4D0B4F88630A26FF5 +:101A30009A4288BFA36794F98030A56F002B4FF0BE +:101A4000300380F20381002D00F0F280092284F837 +:101A5000702083F3118800212046D4E91D23FFF76D +:101A60006DFF002383F31188DAE794F8812003F0F7 +:101A70007F0343EA022340F20232934200F0C58022 +:101A800021D8B3F5807F48D00DD8012B3FD0022B51 +:101A900000F09380002BB2D104F188026267022229 +:101AA000A267E367C1E7B3F5817F00F09B80B3F5E0 +:101AB000407FA4D194F88230012BA0D1B4F88830B3 +:101AC00043F0020332E0B3F5006F4DD017D8B3F501 +:101AD000A06F31D0A3F5C063012B90D86368204676 +:101AE00094F882205E6894F88310B4F88430B0478C +:101AF000002884D0436863670368A3671AE0B3F5DE +:101B0000106F36D040F6024293427FF478AF5C4BC0 +:101B100063670223A3670023C3E794F88230012B95 +:101B20007FF46DAFB4F8883023F00203A4F8883056 +:101B3000C4E91D55E56778E7B4F88030B3F5A06FC8 +:101B40000ED194F88230204684F88A3001F0DCF817 +:101B500063681B6813B10121204698470323237053 +:101B60000023C4E91D339CE704F18B036367012361 +:101B7000C3E72378042B10D1302383F31188204648 +:101B8000FFF7BAFE85F311880321636884F88B5050 +:101B900021701B680BB12046984794F88230002BC7 +:101BA000DED084F88B300423237063681B68002B1D +:101BB000D6D0022120469847D2E794F884302046B8 +:101BC0001D0603F00F010AD501F04EF9012804D0DB +:101BD00002287FF414AF2B4B9AE72B4B98E701F0C8 +:101BE00035F9F3E794F88230002B7FF408AF94F8CE +:101BF000843013F00F01B3D01A06204602D501F04D +:101C000057FCADE701F048FCAAE794F88230002BBE +:101C10007FF4F5AE94F8843013F00F01A0D01B06CA +:101C2000204602D501F02CFC9AE701F01DFC97E755 +:101C3000142284F8702083F311882B462A46294603 +:101C40002046FFF769FE85F31188E9E65DB11522AC +:101C500084F8702083F3118800212046D4E91D23E5 +:101C6000FFF75AFEFDE60B2284F8702083F31188FB +:101C70002B462A4629462046FFF760FEE3E700BFD1 +:101C8000C0410008B8410008BC41000838B590F8D0 +:101C900070300446002B3ED0063BDAB20F2A34D80F +:101CA0000F2B32D8DFE803F03731310822323131DF +:101CB0003131313131313737856FB0F886309D425F +:101CC00014D2C3681B8AB5FBF3F203FB12556DB93E +:101CD000302383F311882B462A462946FFF72EFE30 +:101CE00085F311880A2384F870300EE0142384F8F9 +:101CF0007030302383F31188002320461A4619469A +:101D0000FFF70AFE002383F3118838BDC36F03B1C8 +:101D100098470023E7E70021204601F0B1FB0021AE +:101D2000204601F0A1FB63681B6813B10621204621 +:101D300098470623D7E7000010B590F870300446A6 +:101D4000142B29D017D8062B05D001D81BB110BDF4 +:101D5000093B022BFBD80021204601F091FB00211A +:101D6000204601F081FB63681B6813B10621204601 +:101D70009847062319E0152BE9D10B2380F8703022 +:101D8000302383F3118800231A461946FFF7D6FD46 +:101D9000002383F31188DAE7C3689B695B68002B33 +:101DA000D5D1C36F03B19847002384F87030CEE7D4 +:101DB00000238268037503691B6899689142FBD20E +:101DC0005A68036042601060586070470023826860 +:101DD000037503691B6899689142FBD85A680360D0 +:101DE000426010605860704708B50846302383F39E +:101DF00011880B7D032B05D0042B0DD02BB983F359 +:101E0000118808BD8B6900221A604FF0FF3383618F +:101E1000FFF7CEFF0023F2E7D1E9003213605A60EA +:101E2000F3E70000FFF7C4BF054BD96808751868D1 +:101E3000026853601A600122D8600275FEF7E2BAA8 +:101E4000402400200C4B30B5DD684B1C87B00446A5 +:101E50000FD02B46094A684600F04EF92046FFF79E +:101E6000E3FF009B13B1684600F050F9A86907B082 +:101E700030BDFFF7D9FFF9E740240020E91D000835 +:101E8000044B1A68DB6890689B68984294BF0020F6 +:101E90000120704740240020084B10B51C68D8680A +:101EA000226853601A600122DC602275FFF78EFF02 +:101EB00001462046BDE81040FEF7A4BA40240020A9 +:101EC00038B5074C01230025064907482370656093 +:101ED00001F0E4FC0223237085F3118838BD00BFB4 +:101EE000A8260020C84100084024002000F044B982 +:101EF000034A516853685B1A9842FBD8704700BF89 +:101F0000001000E08B600223086108468B82704756 +:101F10008368A3F1840243F8142C026943F8442C2B +:101F2000426943F8402C094A43F8242CC268A3F1C3 +:101F3000200043F8182C022203F80C2C002203F88E +:101F40000B2C034A43F8102C704700BF1D040008F7 +:101F50004024002008B5FFF7DBFFBDE80840FFF78D +:101F600061BF0000024BDB6898610F20FFF75CBF88 +:101F700040240020302383F31188FFF7F3BF0000D3 +:101F800008B50146302383F311880820FFF75AFF74 +:101F9000002383F3118808BD064BDB6839B1426822 +:101FA00018605A60136043600420FFF74BBF4FF086 +:101FB000FF307047402400200368984206D01A681A +:101FC0000260506018469961FFF72CBF704700000F +:101FD00038B504460D462068844200D138BD0368F8 +:101FE00023605C608561FFF71DFFF4E7036810B5AF +:101FF0009C68A2420CD85C688A600B604C602160CF +:10200000596099688A1A9A604FF0FF33836010BD57 +:10201000121B1B68ECE700000A2938BF0A2170B5C3 +:1020200004460D460A26601901F030FC01F018FC48 +:10203000041BA54203D8751C04462E46F3E70A2E5E +:1020400004D90120BDE8704001F068BC70BD0000FB +:10205000F8B5144B0D460A2A4FF00A07D96103F16F +:102060001001826038BF0A2241601969144601607C +:1020700048601861A81801F0F9FB01F0F1FB431B5F +:102080000646A34206D37C1C28192746354601F094 +:10209000FDFBF2E70A2F04D90120BDE8F84001F06A +:1020A0003DBCF8BD40240020F8B506460D4601F0C1 +:1020B000D7FB0F4A134653F8107F9F4206D12A469A +:1020C00001463046BDE8F840FFF7C2BFD169BB68A2 +:1020D000441A2C1928BF2C46A34202D92946FFF7DF +:1020E0009BFF224631460348BDE8F840FFF77EBF1C +:1020F0004024002050240020C0E90323002310B412 +:102100005DF8044B4361FFF7CFBF000010B5194CD9 +:10211000236998420DD08168D0E9003213605A607B +:102120009A680A449A60002303604FF0FF33A3616A +:1021300010BD0268234643F8102F5360002202604E +:1021400022699A4203D1BDE8104001F099BB93681F +:1021500081680B44936001F083FB2269E169926816 +:10216000441AA242E4D91144BDE81040091AFFF70D +:1021700053BF00BF402400202DE9F047DFF8BC80AA +:1021800008F110072C4ED8F8105001F069FBD8F870 +:102190001C40AA68031B9A423ED814444FF0000921 +:1021A000D5E90032C8F81C4013605A60C5F80090A9 +:1021B000D8F81030B34201D101F062FB89F31188E5 +:1021C000D5E9033128469847302383F311886B699A +:1021D000002BD8D001F044FB6A69A0EB04098246C9 +:1021E0004A450DD2022001F099FB0022D8F81030A8 +:1021F000B34208D151462846BDE8F047FFF728BF53 +:10220000121A2244F2E712EB09092946384638BF70 +:102210004A46FFF7EBFEB5E7D8F81030B34208D0D6 +:102220001444C8F81C00211AA960BDE8F047FFF764 +:10223000F3BEBDE8F08700BF5024002040240020FA +:1022400000207047FEE70000704700004FF0FF30AD +:102250007047000002290CD0032904D00129074847 +:1022600018BF00207047032A05D8054800EBC200BC +:102270007047044870470020704700BFA042000824 +:102280003C2200205442000870B59AB0054608462A +:10229000144601A900F0C2F801A8FEF7F3FD431CA3 +:1022A0000022C6B25B001046C5E900342370032348 +:1022B000023404F8013C01ABD1B202348E4201D8A1 +:1022C0001AB070BD13F8011B013204F8010C04F8B8 +:1022D000021CF1E708B5302383F311880348FFF7A8 +:1022E00049FA002383F3118808BD00BFB0260020FF +:1022F00090F8803003F01F02012A07D190F8812066 +:102300000B2A03D10023C0E91D3315E003F060035D +:10231000202B08D1B0F884302BB990F88120212AE5 +:1023200003D81F2A04D8FFF707BA222AEBD0FAE70E +:10233000034A426707228267C3670120704700BFD4 +:102340003322002007B5052917D8DFE801F0191658 +:1023500003191920302383F31188104A01210190B9 +:10236000FFF7B0FA019802210D4AFFF7ABFA0D48CA +:10237000FFF7CCF9002383F3118803B05DF804FB69 +:10238000302383F311880748FFF796F9F2E73023EB +:1023900083F311880348FFF7ADF9EBE7F441000838 +:1023A00018420008B026002038B50C4D0C4C2A46C7 +:1023B0000C4904F10800FFF767FF05F1CA0204F1B8 +:1023C00010000949FFF760FF05F5CA7204F1180013 +:1023D0000649BDE83840FFF757BF00BF883F0020DF +:1023E0003C220020D4410008DE410008E9410008F9 +:1023F00070B5044608460D46FEF744FDC6B22046B9 +:10240000013403780BB9184670BD32462946FEF7F1 +:1024100025FD0028F3D10120F6E700002DE9F04763 +:1024200005460C46FEF72EFD2B49C6B22846FFF79F +:10243000DFFF08B10636F6B228492846FFF7D8FF75 +:1024400008B11036F6B2632E0BD8DFF88C80DFF8B7 +:102450008C90234FDFF894A02E7846B92670BDE803 +:10246000F08729462046BDE8F04701F0EBBD252E58 +:102470002ED1072241462846FEF7F0FC70B9194BD1 +:10248000224603F10C0153F8040B8B4242F8040B73 +:10249000F9D11B7807350D341370DDE70822494662 +:1024A0002846FEF7DBFC98B9A21C0F4B19780232C4 +:1024B0000909C95D02F8041C13F8011B01F00F01A2 +:1024C0005345C95D02F8031CF0D118340835C3E741 +:1024D000013504F8016BBFE7C0420008E94100087C +:1024E000D6420008C842000800E8F11F0CE8F11FBE +:1024F000BFF34F8F044B1A695107FCD1D3F8102159 +:102500005207F8D1704700BF0020005208B50D4BAC +:102510001B78ABB9FFF7ECFF0B4BDA68D10704D59A +:102520000A4A5A6002F188325A60D3F80C21D20765 +:1025300006D5064AC3F8042102F18832C3F8042103 +:1025400008BD00BFE641002000200052230167457E +:1025500008B5114B1B78F3B9104B1A69510703D515 +:10256000DA6842F04002DA60D3F81021520705D54C +:10257000D3F80C2142F04002C3F80C21FFF7B8FF5A +:10258000064BDA6842F00102DA60D3F80C2142F01F +:102590000102C3F80C2108BDE641002000200052D2 +:1025A0000F289ABF00F580604004002070470000AB +:1025B0004FF4003070470000102070470F2808B516 +:1025C0000BD8FFF7EDFF00F500330268013204D1AC +:1025D00004308342F9D1012008BD0020FCE700004F +:1025E0000F2838B505463FD8FFF782FF1F4CFFF78D +:1025F0008DFF4FF0FF3307286361C4F814311DD8F5 +:102600002361FFF775FF030243F02403E360E368EF +:1026100043F08003E36023695A07FCD42846FFF7A0 +:1026200067FFFFF7BDFF4FF4003100F0F5F82846D3 +:10263000FFF78EFFBDE83840FFF7C0BFC4F8103188 +:10264000FFF756FFA0F108031B0243F02403C4F870 +:102650000C31D4F80C3143F08003C4F80C31D4F8B9 +:1026600010315B07FBD4D9E7002038BD00200052B1 +:102670002DE9F84F05460C46104645EA0203DE06F2 +:1026800002D00020BDE8F88F20F01F00DFF8BCB0BA +:10269000DFF8BCA0FFF73AFF04EB0008444503D184 +:1026A0000120FFF755FFEDE720222946204601F0E3 +:1026B000B9FC10B920352034F0E72B4605F1200293 +:1026C0001F68791CDDD104339A42F9D105F17843B2 +:1026D0001B481C4EB3F5801F1B4B38BF184603F137 +:1026E000F80332BFD946D1461E46FFF701FF076007 +:1026F000A5EB040C336804F11C0143F002033360C2 +:10270000231FD9F8007017F00507FAD153F8042FEA +:102710008B424CF80320F4D1BFF34F8FFFF7E8FE54 +:102720004FF0FF332022214603602846336823F010 +:102730000203336001F076FC0028BBD03846B0E7D6 +:10274000142100520C20005214200052102000527C +:102750001021005210B5084C237828B11BB9FFF79F +:10276000D5FE0123237010BD002BFCD02070BDE8E6 +:102770001040FFF7EDBE00BFE64100200244074BCA +:10278000D2B210B5904200D110BD441C00B253F833 +:10279000200041F8040BE0B2F4E700BF50400058BD +:1027A0000E4B30B51C6F240405D41C6F1C671C6FC6 +:1027B00044F400441C670A4C02442368D2B243F438 +:1027C00080732360074B904200D130BD441C51F808 +:1027D000045B00B243F82050E0B2F4E70044025832 +:1027E000004802585040005807B5012201A90020B6 +:1027F000FFF7C4FF019803B05DF804FB13B504466E +:10280000FFF7F2FFA04205D0012201A900200194A8 +:10281000FFF7C6FF02B010BD0144BFF34F8F064B58 +:10282000884204D3BFF34F8FBFF36F8F7047C3F855 +:102830005C022030F4E700BF00ED00E0034B1A68B3 +:102840001AB9034AD2F8D0241A607047E841002030 +:102850000040025808B5FFF7F1FF024B1868C0F3BB +:10286000806008BDE8410020EFF309830549683323 +:102870004A6B22F001024A6383F30988002383F341 +:102880001188704700EF00E0302080F3118862B6B5 +:102890000D4B0E4AD96821F4E0610904090C0A4382 +:1028A0000B49DA60D3F8FC2042F08072C3F8FC20B8 +:1028B000084AC2F8B01F116841F0010111602022DE +:1028C000DA7783F82200704700ED00E00003FA0594 +:1028D00055CEACC5001000E0302310B583F311884D +:1028E0000E4B5B6813F4006314D0F1EE103AEFF373 +:1028F00009844FF08073683CE361094BDB6B23660E +:1029000084F30988FFF7BCFA10B1064BA36110BD30 +:10291000054BFBE783F31188F9E700BF00ED00E00A +:1029200000EF00E02F0400083204000870B5BFF388 +:102930004F8FBFF36F8F1A4A0021C2F85012BFF3B6 +:102940004F8FBFF36F8F536943F400335361BFF36D +:102950004F8FBFF36F8FC2F88410BFF34F8FD2F841 +:10296000803043F6E074C3F3C900C3F34E335B0118 +:1029700003EA0406014646EA81750139C2F860524D +:10298000F9D2203B13F1200FF2D1BFF34F8F5369DF +:1029900043F480335361BFF34F8FBFF36F8F70BD2C +:1029A00000ED00E0FEE70000214B2248224A70B50E +:1029B000904237D3214BC11EDA1C121A22F00302B7 +:1029C0008B4238BF00220021FEF764FA1C4A002324 +:1029D000C2F88430BFF34F8FD2F8803043F6E074F2 +:1029E000C3F3C900C3F34E335B0103EA0406014697 +:1029F00046EA81750139C2F86C52F9D2203B13F1D5 +:102A0000200FF2D1BFF34F8FBFF36F8FBFF34F8F04 +:102A1000BFF36F8F0023C2F85032BFF34F8FBFF365 +:102A20006F8F70BD53F8041B40F8041BC0E700BF54 +:102A3000C4440008BC430020BC430020BC43002029 +:102A400000ED00E0074BD3F8D81021EA0001C3F8ED +:102A5000D810D3F8002122EA0002C3F80021D3F8ED +:102A6000003170470044025870B5D0E92443002279 +:102A70004FF0FF359E6804EB42135101D3F8000973 +:102A8000002805DAD3F8000940F08040C3F80009B7 +:102A9000D3F8000B002805DAD3F8000B40F0804093 +:102AA000C3F8000B013263189642C3F80859C3F803 +:102AB000085BE0D24FF00113C4F81C3870BD000071 +:102AC000890141F02001016103699B06FCD41220B9 +:102AD000FFF70EBA10B50A4C2046FEF7D1FE094B9F +:102AE000C4F89030084BC4F89430084C2046FEF7E8 +:102AF000C7FE074BC4F89030064BC4F8943010BDA5 +:102B0000EC410020000008400C43000888420020EF +:102B1000000004401843000870B503780546012BF7 +:102B20005CD1434BD0F89040984258D1414B0E2194 +:102B30006520D3F8D82042F00062C3F8D820D3F83B +:102B4000002142F00062C3F80021D3F80021D3F83D +:102B5000802042F00062C3F88020D3F8802022F069 +:102B60000062C3F88020D3F88030FEF7B5FC324B0A +:102B7000E360324BC4F800380023D5F89060C4F805 +:102B8000003EC02323604FF40413A3633369002B7A +:102B9000FCDA01230C203361FFF7AAF93369DB0764 +:102BA000FCD41220FFF7A4F93369002BFCDA0026CD +:102BB0002846A660FFF758FF6B68C4F81068DB680A +:102BC000C4F81468C4F81C6883BB1D4BA3614FF0A4 +:102BD000FF336361A36843F00103A36070BD194B29 +:102BE0009842C9D1134B4FF08060D3F8D82042F0FF +:102BF0000072C3F8D820D3F8002142F00072C3F865 +:102C00000021D3F80021D3F8802042F00072C3F8ED +:102C10008020D3F8802022F00072C3F88020D3F8FF +:102C20008030FFF70FFF0E214D209EE7064BCDE7CA +:102C3000EC410020004402584014004003002002F0 +:102C4000003C30C088420020083C30C0F8B5D0F8C5 +:102C50009040054600214FF000662046FFF730FF08 +:102C6000D5F8941000234FF001128F684FF0FF3019 +:102C7000C4F83438C4F81C2804EB431201339F42D3 +:102C8000C2F80069C2F8006BC2F80809C2F8080B64 +:102C9000F2D20B68D5F89020C5F898306362102303 +:102CA0001361166916F01006FBD11220FFF720F908 +:102CB000D4F8003823F4FE63C4F80038A36943F461 +:102CC000402343F01003A3610923C4F81038C4F86B +:102CD00014380B4BEB604FF0C043C4F8103B094B6A +:102CE000C4F8003BC4F81069C4F80039D5F898302E +:102CF00003F1100243F48013C5F89820A362F8BDD5 +:102D0000E842000840800010D0F8902090F88A1027 +:102D1000D2F8003823F4FE6343EA0113C2F8003806 +:102D2000704700002DE9F84300EB8103D0F8905084 +:102D30000C468046DA680FFA81F94801166806F0F9 +:102D40000306731E022B05EB41134FF0000194BFE5 +:102D5000B604384EC3F8101B4FF0010104F1100304 +:102D600098BF06F1805601FA03F3916998BF06F502 +:102D7000004600293AD0578A04F1580137434901E7 +:102D80006F50D5F81C180B430021C5F81C382B18C0 +:102D90000127C3F81019A7405369611E9BB3138A1A +:102DA000928B9B08012A88BF5343D8F89820981823 +:102DB00042EA034301F140022146C8F89800284640 +:102DC00005EB82025360FFF77BFE08EB8900C368C6 +:102DD0001B8A43EA845348341E4364012E51D5F8BC +:102DE0001C381F43C5F81C78BDE8F88305EB49176C +:102DF000D7F8001B21F40041C7F8001BD5F81C18B8 +:102E000021EA0303C0E704F13F030B4A28462146A9 +:102E100005EB83035A60FFF753FE05EB4910D0F82A +:102E2000003923F40043C0F80039D5F81C3823EAF0 +:102E30000707D7E70080001000040002D0F89420B4 +:102E40001268C0F89820FFF70FBE00005831D0F884 +:102E5000903049015B5813F4004004D013F4001F74 +:102E60000CBF0220012070474831D0F89030490152 +:102E70005B5813F4004004D013F4001F0CBF022071 +:102E80000120704700EB8101CB68196A0B68136061 +:102E90004B6853607047000000EB810330B5DD687C +:102EA000AA691368D36019B9402B84BF402313600B +:102EB0006B8A1468D0F890201C4402EB4110013C4E +:102EC00009B2B4FBF3F46343033323F0030343EA8F +:102ED000C44343F0C043C0F8103B2B6803F0030326 +:102EE000012B0ED1D2F8083802EB411013F4807F89 +:102EF000D0F8003B14BF43F0805343F00053C0F8B8 +:102F0000003B02EB4112D2F8003B43F00443C2F80D +:102F1000003B30BD2DE9F041D0F8906005460C46ED +:102F200006EB4113D3F8087B3A07C3F8087B08D5B2 +:102F3000D6F814381B0704D500EB8103DB685B6807 +:102F40009847FA071FD5D6F81438DB071BD505EBD1 +:102F50008403D968CCB98B69488A5A68B2FBF0F609 +:102F600000FB16228AB91868DA6890420DD2121A4C +:102F7000C3E90024302383F3118821462846FFF754 +:102F80008BFF84F31188BDE8F081012303FA04F27A +:102F90006B8923EA02036B81CB68002BF3D02146B7 +:102FA0002846BDE8F041184700EB81034A0170B59F +:102FB000DD68D0F890306C692668E66056BB1A442C +:102FC0004FF40020C2F810092A6802F00302012A17 +:102FD0000AB20ED1D3F8080803EB421410F4807F34 +:102FE000D4F8000914BF40F0805040F00050C4F8FD +:102FF000000903EB4212D2F8000940F00440C2F885 +:1030000000090122D3F8340802FA01F10143C3F8A0 +:10301000341870BD19B9402E84BF4020206020684C +:103020001A442E8A8419013CB4FBF6F440EAC440E9 +:1030300040F00050C6E700002DE9F843D0F890605A +:1030400005460C464F0106EB4113D3F8088918F0EA +:10305000010FC3F808891CD0D6F81038DB0718D543 +:1030600000EB8103D3F80CC0DCF81430D3F800E097 +:10307000DA68964530D2A2EB0E024FF000091A60D2 +:10308000C3F80490302383F31188FFF78DFF89F391 +:10309000118818F0800F1DD0D6F834380126A640CC +:1030A000334217D005EB84030134D5F89050D3F8A0 +:1030B0000CC0E4B22F44DCF8142005EB0434D2F841 +:1030C00000E05168714514D3D5F8343823EA060678 +:1030D000C5F83468BDE8F883012303FA01F20389D7 +:1030E00023EA02030381DCF80830002BD1D0984793 +:1030F000CFE7AEEB0103BCF81000834228BF0346C4 +:10310000D7F8180980B2B3EB800FE3D89068A0F12C +:10311000040959F8048FC4F80080A0EB090898440A +:10312000B8F1040FF5D818440B4490605360C8E719 +:103130002DE9F84FD0F8905004466E69AB691E40F7 +:1031400016F480586E6103D0BDE8F84FFEF708BC56 +:10315000002E12DAD5F8003E9B0705D0D5F8003EC8 +:1031600023F00303C5F8003ED5F80438204623F0C9 +:103170000103C5F80438FEF721FC370505D52046C4 +:10318000FFF772FC2046FEF707FCB0040CD5D5F81B +:10319000083813F0060FEB6823F470530CBF43F4A8 +:1031A000105343F4A053EB6031071BD56368DB6811 +:1031B0001BB9AB6923F00803AB612378052B0CD155 +:1031C000D5F8003E9A0705D0D5F8003E23F003035A +:1031D000C5F8003E2046FEF7F1FB6368DB680BB1E3 +:1031E00020469847F30200F1BA80B70226D5D4F8FA +:1031F000909000274FF0010A09EB4712D2F8003BEC +:1032000003F44023B3F5802F11D1D2F8003B002BFB +:103210000DDA62890AFA07F322EA0303638104EBF9 +:103220008703DB68DB6813B13946204698470137CE +:10323000D4F89430FFB29B689F42DDD9F00619D5CF +:10324000D4F89000026AC2F30A1702F00F0302F4E6 +:10325000F012B2F5802F00F0CA80B2F5402F09D1EC +:1032600004EB8303002200F58050DB681B6A974261 +:1032700040F0B0803003D5F8185835D5E90303D5B0 +:1032800000212046FFF746FEAA0303D50121204670 +:10329000FFF740FE6B0303D502212046FFF73AFEFD +:1032A0002F0303D503212046FFF734FEE80203D5A0 +:1032B00004212046FFF72EFEA90203D50521204652 +:1032C000FFF728FE6A0203D506212046FFF722FEFB +:1032D0002B0203D507212046FFF71CFEEF0103D583 +:1032E00008212046FFF716FE700340F1A780E9078A +:1032F00003D500212046FFF79FFEAA0703D5012131 +:103300002046FFF799FE6B0703D502212046FFF701 +:1033100093FE2F0703D503212046FFF78DFEEE060F +:1033200003D504212046FFF787FEA80603D5052113 +:103330002046FFF781FE690603D506212046FFF7E8 +:103340007BFE2A0603D507212046FFF775FEEB0515 +:1033500074D520460821BDE8F84FFFF76DBED4F8BC +:1033600090904FF0000B4FF0010AD4F894305FFAC0 +:103370008BF79B689F423FF638AF09EB4713D3F8B2 +:10338000002902F44022B2F5802F20D1D3F8002981 +:10339000002A1CDAD3F8002942F09042C3F8002931 +:1033A000D3F80029002AFBDB3946D4F89000FFF758 +:1033B00087FB22890AFA07F322EA0303238104EB3D +:1033C0008703DB689B6813B13946204698470BF1A9 +:1033D000010BCAE7910701D1D0F80080072A02F15A +:1033E00001029CBF03F8018B4FEA18283FE704EB6A +:1033F000830300F58050DA68D2F818C0DCF80820A2 +:10340000DCE9001CA1EB0C0C00218F4208D1DB6829 +:103410009B699A683A449A605A683A445A6029E724 +:1034200011F0030F01D1D0F800808C4501F10101AA +:1034300084BF02F8018B4FEA1828E6E7BDE8F88F51 +:1034400008B50348FFF774FEBDE80840FFF744BA2B +:10345000EC41002008B50348FFF76AFEBDE80840CC +:10346000FFF73ABA88420020D0F8903003EB4111C0 +:10347000D1F8003B43F40013C1F8003B7047000053 +:10348000D0F8903003EB4111D1F8003943F4001328 +:10349000C1F8003970470000D0F8903003EB4111BB +:1034A000D1F8003B23F40013C1F8003B7047000043 +:1034B000D0F8903003EB4111D1F8003923F4001318 +:1034C000C1F800397047000030B50433039C017225 +:1034D000002104FB0325C160C0E90653049B03637C +:1034E000059BC0E90000C0E90422C0E90842C0E928 +:1034F0000A11436330BD00000022416AC260C0E986 +:103500000411C0E90A226FF00101FEF761BD00005D +:10351000D0E90432934201D1C2680AB9181D70473C +:1035200000207047036919600021C2680132C2603F +:10353000C269134482699342036124BF436A0361F1 +:10354000FEF73ABD38B504460D46E3683BB1626903 +:103550000020131D1268A3621344E36207E0237A7C +:1035600033B929462046FEF717FD0028EDDA38BDAD +:103570006FF00100FBE70000C368C269013BC36054 +:103580004369134482699342436124BF436A4361A0 +:1035900000238362036B03B11847704770B5302373 +:1035A000044683F31188866A3EB9FFF7CBFF0546D0 +:1035B00018B186F31188284670BDA36AE26A13F831 +:1035C000015B9342A36202D32046FFF7D5FF00239D +:1035D00083F31188EFE700002DE9F84F04460E460B +:1035E000174698464FF0300989F311880025AA46FE +:1035F000D4F828B0BBF1000F09D141462046FFF7AF +:10360000A1FF20B18BF311882846BDE8F88FD4E9DB +:103610000A12A7EB050B521A934528BF9346BBF13C +:10362000400F1BD9334601F1400251F8040B91427F +:1036300043F8040BF9D1A36A403640354033A36206 +:10364000D4E90A239A4202D32046FFF795FF8AF372 +:103650001188BD42D8D289F31188C9E730465A464D +:10366000FDF7F2FBA36A5E445D445B44A362E7E7B7 +:1036700010B5029C0433017203FB0421C460C0E94D +:1036800006130023C0E90A33039B0363049BC0E9CC +:103690000000C0E90422C0E90842436310BD0000F5 +:1036A000026A6FF00101C260426AC0E9042200228E +:1036B000C0E90A22FEF78CBCD0E904239A4201D16A +:1036C000C26822B9184650F8043B0B6070470023CB +:1036D0001846FAE7C3680021C2690133C360436931 +:1036E000134482699342436124BF436A4361FEF7F6 +:1036F00063BC000038B504460D46E3683BB123695E +:1037000000201A1DA262E2691344E36207E0237AF3 +:1037100033B929462046FEF73FFC0028EDDA38BDD4 +:103720006FF00100FBE7000003691960C268013A0D +:10373000C260C269134482699342036124BF436A31 +:10374000036100238362036B03B1184770470000D5 +:1037500070B530230D460446114683F31188866AFE +:103760002EB9FFF7C7FF10B186F3118870BDA36AA9 +:103770001D70A36AE26A01339342A36204D3E16934 +:1037800020460439FFF7D0FF002080F31188EDE7D1 +:103790002DE9F84F04460D46904699464FF0300A01 +:1037A0008AF311880026B346A76A4FB949462046D6 +:1037B000FFF7A0FF20B187F311883046BDE8F88FEE +:1037C000D4E90A073A1AA8EB0607974228BF17461A +:1037D000402F1BD905F1400355F8042B9D4240F8BA +:1037E000042BF9D1A36A40364033A362D4E90A23FB +:1037F0009A4204D3E16920460439FFF795FF8BF321 +:1038000011884645D9D28AF31188CDE729463A4630 +:10381000FDF71AFBA36A3D443E443B44A362E5E73F +:10382000D0E904239A4217D1C3689BB1836A8BB154 +:10383000043B9B1A0ED01360C368013BC360C3698D +:103840001A4483699A42026124BF436A03610023D8 +:1038500083620123184670470023FBE700F024B978 +:10386000014B586A704700BF000C0040034B002218 +:1038700058631A610222DA60704700BF000C0040F2 +:10388000014B0022DA607047000C0040014B586386 +:10389000704700BF000C0040FEE7000070B51B4BF6 +:1038A0000025044686B058600E4685620163FEF727 +:1038B000EBFF04F11003A560E562C4E904334FF0A7 +:1038C000FF33C4E90044C4E90635FFF7C9FF2B46BE +:1038D000024604F134012046C4E9082380230C4A3F +:1038E0002565FEF70FFB01230A4AE060009203758D +:1038F000684672680192B268CDE90223064BCDE9B1 +:103900000435FEF727FB06B070BD00BFA8260020D7 +:10391000244300082943000899380008024AD36A62 +:103920001843D062704700BF402400204B684360BA +:103930008B688360CB68C3600B6943614B6903622A +:103940008B6943620B6803607047000008B53C4B0D +:1039500040F2FF713B48D3F888200A43C3F888201F +:10396000D3F8882022F4FF6222F00702C3F88820EF +:10397000D3F88820D3F8E0200A43C3F8E020D3F836 +:1039800008210A43C3F808212F4AD3F80831114609 +:10399000FFF7CCFF00F5806002F11C01FFF7C6FFC6 +:1039A00000F5806002F13801FFF7C0FF00F580608C +:1039B00002F15401FFF7BAFF00F5806002F17001D7 +:1039C000FFF7B4FF00F5806002F18C01FFF7AEFF56 +:1039D00000F5806002F1A801FFF7A8FF00F5806004 +:1039E00002F1C401FFF7A2FF00F5806002F1E001DF +:1039F000FFF79CFF00F5806002F1FC01FFF796FFE6 +:103A000002F58C7100F58060FFF790FF00F018F967 +:103A10000E4BD3F8902242F00102C3F89022D3F863 +:103A2000942242F00102C3F894220522C3F89820A0 +:103A30004FF06052C3F89C20054AC3F8A02008BD8F +:103A400000440258000002583043000800ED00E036 +:103A50001F00080308B500F0C7FAFEF731FA0F4B54 +:103A6000D3F8DC2042F04002C3F8DC20D3F8042174 +:103A700022F04002C3F80421D3F80431084B1A683D +:103A800042F008021A601A6842F004021A60FEF757 +:103A9000D5FEBDE80840FEF787BC00BF00440258D1 +:103AA0000018024870470000114BD3F8E82042F09C +:103AB0000802C3F8E820D3F8102142F00802C3F846 +:103AC00010210C4AD3F81031D36B43F00803D363B1 +:103AD000C722094B9A624FF0FF32DA6200229A61E4 +:103AE0005A63DA605A6001225A611A60704700BF57 +:103AF000004402580010005C000C0040094A08B560 +:103B00001169D3680B40D9B29B076FEA01011161BB +:103B100007D5302383F31188FEF7E8F9002383F3F8 +:103B2000118808BD000C0040064BD3F8DC2002438E +:103B3000C3F8DC20D3F804211043C3F80401D3F800 +:103B4000043170470044025808B53C4B4FF0FF3138 +:103B5000D3F8802062F00042C3F88020D3F88020A0 +:103B600002F00042C3F88020D3F88020D3F88420EC +:103B7000C3F88410D3F884200022C3F88420D3F83B +:103B80008400D86F40F0FF4040F4FF0040F4DF4075 +:103B900040F07F00D867D86F20F0FF4020F4FF008E +:103BA00020F4DF4020F07F00D867D86FD3F888007A +:103BB0006FEA40506FEA5050C3F88800D3F888008D +:103BC000C0F30A00C3F88800D3F88800D3F8900047 +:103BD000C3F89010D3F89000C3F89020D3F8900069 +:103BE000D3F89400C3F89410D3F89400C3F8942049 +:103BF000D3F89400D3F89800C3F89810D3F898003D +:103C0000C3F89820D3F89800D3F88C00C3F88C1030 +:103C1000D3F88C00C3F88C20D3F88C00D3F89C0028 +:103C2000C3F89C10D3F89C10C3F89C20D3F89C30A8 +:103C3000FDF776FBBDE8084000F0AEB9004402583D +:103C400008B50122534BC3F80821534BD3F8F42095 +:103C500042F00202C3F8F420D3F81C2142F0020221 +:103C6000C3F81C210222D3F81C314C4BDA605A688D +:103C70009104FCD54A4A1A6001229A60494ADA60E6 +:103C800000221A614FF440429A61444B9A699204AF +:103C9000FCD51A6842F480721A603F4B1A6F12F416 +:103CA000407F04D04FF480321A6700221A671A68E6 +:103CB00042F001021A60384B1A685007FCD5002206 +:103CC0001A611A6912F03802FBD1012119604FF014 +:103CD000804159605A67344ADA62344A1A611A6874 +:103CE00042F480321A602C4B1A689103FCD51A6892 +:103CF00042F480521A601A689204FCD52C4A2D496D +:103D00009A6200225A63196301F57C01DA6301F2B9 +:103D1000E71199635A64284A1A64284ADA621A68D1 +:103D200042F0A8521A601C4B1A6802F02852B2F1F5 +:103D3000285FF9D148229A614FF48862DA61402203 +:103D40001A621F4ADA641F4A1A651F4A5A651F4AD7 +:103D50009A6532231E4A1360136803F00F03022B87 +:103D6000FAD10D4A136943F003031361136903F099 +:103D70003803182BFAD14FF00050FFF7D5FE4FF063 +:103D80008040FFF7D1FE4FF00040BDE80840FFF74C +:103D9000CBBE00BF008000510044025800480258CA +:103DA00000C000F0020000010000FF010088900840 +:103DB0001210200063020901470E0508DD0BBF0148 +:103DC00020000020000001100910E0000001011097 +:103DD000002000524FF0B04208B5D2F8883003F00E +:103DE0000103C2F8883023B1044A13680BB150684C +:103DF0009847BDE80840FEF76FBD00BF3C43002078 +:103E00004FF0B04208B5D2F8883003F00203C2F890 +:103E1000883023B1044A93680BB1D0689847BDE855 +:103E20000840FEF759BD00BF3C4300204FF0B042B0 +:103E300008B5D2F8883003F00403C2F8883023B103 +:103E4000044A13690BB150699847BDE80840FEF772 +:103E500043BD00BF3C4300204FF0B04208B5D2F84C +:103E6000883003F00803C2F8883023B1044A93690C +:103E70000BB1D0699847BDE80840FEF72DBD00BFE3 +:103E80003C4300204FF0B04208B5D2F8883003F030 +:103E90001003C2F8883023B1044A136A0BB1506A88 +:103EA0009847BDE80840FEF717BD00BF3C4300201F +:103EB0004FF0B04310B5D3F8884004F47872C3F8DB +:103EC0008820A30604D5124A936A0BB1D06A98479A +:103ED000600604D50E4A136B0BB1506B9847210650 +:103EE00004D50B4A936B0BB1D06B9847E20504D510 +:103EF000074A136C0BB1506C9847A30504D5044ACC +:103F0000936C0BB1D06C9847BDE81040FEF7E4BC51 +:103F10003C4300204FF0B04310B5D3F8884004F480 +:103F20007C42C3F88820620504D5164A136D0BB194 +:103F3000506D9847230504D5124A936D0BB1D06D8F +:103F40009847E00404D50F4A136E0BB1506E9847A2 +:103F5000A10404D50B4A936E0BB1D06E984762044E +:103F600004D5084A136F0BB1506F9847230404D54A +:103F7000044A936F0BB1D06F9847BDE81040FEF72D +:103F8000ABBC00BF3C43002008B5FFF7B7FDBDE860 +:103F90000840FEF7A1BC0000062108B50846FDF761 +:103FA0009BFA06210720FDF797FA06210820FDF766 +:103FB00093FA06210920FDF78FFA06210A20FDF762 +:103FC0008BFA06211720FDF787FA06212820FDF736 +:103FD00083FA09217A20FDF77FFA07213220BDE814 +:103FE0000840FDF779BA000008B5FFF7ADFD00F015 +:103FF0000BF8FDF743FCFDF715FBFFF753FDBDE89C +:104000000840FFF72BBC00000023054A1946013386 +:10401000102BC2E9001102F10802F8D1704700BF6D +:104020003C43002010B501390244904201D10020E8 +:1040300005E0037811F8014FA34201D0181B10BD11 +:104040000130F2E7034611F8012B03F8012B002A97 +:10405000F9D1704753544D333248373F3F3F0053F7 +:10406000544D3332483733782F3732780053544D1C +:104070003332483734332F3735332F37353000005C +:1040800001105A0003105900012058000320560067 +:1040900010000240080002400008024000000B002F +:1040A00028000240080002400408024006010C00FB +:1040B00040000240080002400808024010020D00C3 +:1040C00058000240080002400C08024016030E008F +:1040D000700002400C0002401008024000040F0073 +:1040E000880002400C00024014080240060510003F +:1040F000A00002400C000240180802401006110007 +:10410000B80002400C0002401C08024016072F00B5 +:104110001004024008040240200802400008380051 +:10412000280402400804024024080240060939001D +:10413000400402400804024028080240100A3A00E5 +:1041400058040240080402402C080240160B3B00B1 +:10415000700402400C04024030080240000C3C0095 +:10416000880402400C04024034080240060D44005A +:10417000A00402400C04024038080240100E450022 +:10418000B80402400C0402403C080240160F4600EE +:1041900000000000A11500088D150008C9150008D1 +:1041A000B5150008C1150008AD15000899150008DF +:1041B00085150008D515000800000000010000006A +:1041C0000000000063300000C44100089824002073 +:1041D000A82600204172647550696C6F74002542F6 +:1041E0004F415244252D424C002553455249414CE4 +:1041F000250000000200000000000000C1170008B8 +:104200003118000840004000583F0020683F00205F +:104210000200000000000000030000000000000099 +:10422000791800080000000010000000783F00200E +:10423000000000000100000000000000EC41002030 +:10424000010102004523000855220008F122000860 +:10425000D5220008430000005C4200080902430028 +:10426000020100C03209040000010202010005241D +:1042700000100105240100010424020205240600A7 +:1042800001070582030800FF09040100020A00007B +:104290000007050102400000070581024000000000 +:1042A00012000000A84200081201100102000040A4 +:1042B000091241570002010203010000040309042E +:1042C00025424F4152442500426C69747A57696E09 +:1042D0006748373433003031323334353637383984 +:1042E000414243444546000000000000D519000843 +:1042F0008D1C0008391D00084000400024430020A8 +:10430000244300200100000034430020800000000E +:104310004001000008000000000100000010000043 +:10432000080000006D61696E0069646C6500000042 +:104330000000812A00000000AAAAAAAA0000002406 +:10434000FFFE00000000000000A00A0000000001C5 +:1043500000000000AAAAAAAA00000001FFFF0000B6 +:10436000000000000000000000000040000000000D +:10437000AAAAAAAA00000040FFFF00000000000057 +:10438000000000000000100000000000AAAAAAAA75 +:1043900000000000FFFF000000000000000000001F +:1043A0000000400000000000AAAAAAAA00004000E5 +:1043B000FFFF0000000000000000000000000000FF +:1043C00000000000AAAAAAAA00000000FFFF000047 +:1043D00000000000000000000000000000000000DD +:1043E000AAAAAAAA00000000FFFF00000000000027 +:1043F000000000000000000000000000AAAAAAAA15 +:1044000000000000FFFF00000000000000000000AE +:104410000000000000000000AAAAAAAA00000000F4 +:10442000FFFF00000000000000000000000000008E +:1044300000000000AAAAAAAA00000000FFFF0000D6 +:10444000000000000000000000000000000000006C +:10445000AAAAAAAA00000000FFFF000000000000B6 +:1044600000000000000000009004000000000000B8 +:1044700000001A0000000000FF0000000000000023 +:1044800054400008830400005F400008500400000E +:104490006D40000800960000000008009600000033 +:1044A0000008000004000000BC42000800000000FA +:1044B00000000000000000000000000000000000FC +:0444C00000000000F8 +:00000001FF diff --git a/Tools/bootloaders/BotBloxDroneNet_bl.bin b/Tools/bootloaders/BotBloxDroneNet_bl.bin new file mode 100755 index 00000000000000..2eb9dd1a2dc42e Binary files /dev/null and b/Tools/bootloaders/BotBloxDroneNet_bl.bin differ diff --git a/Tools/bootloaders/BotBloxSwitch_bl.bin b/Tools/bootloaders/BotBloxSwitch_bl.bin deleted file mode 100755 index 77f7357d05cdb3..00000000000000 Binary files a/Tools/bootloaders/BotBloxSwitch_bl.bin and /dev/null differ diff --git a/Tools/bootloaders/CUAV-7-Nano_bl.bin b/Tools/bootloaders/CUAV-7-Nano_bl.bin new file mode 100644 index 00000000000000..60b99e1b3d7254 Binary files /dev/null and b/Tools/bootloaders/CUAV-7-Nano_bl.bin differ diff --git a/Tools/bootloaders/CUAV-7-Nano_bl.hex b/Tools/bootloaders/CUAV-7-Nano_bl.hex new file mode 100644 index 00000000000000..863c1db590b304 --- /dev/null +++ b/Tools/bootloaders/CUAV-7-Nano_bl.hex @@ -0,0 +1,2517 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200080D7700087D +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E302000819860008458600084C +:10006000718600089D860008C986000819460008A8 +:10007000414600086D46000899460008C54600083C +:10008000ED46000819470008E3020008E3020008F3 +:10009000E3020008E3020008E3020008F586000816 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E1870008E9 +:1000E00059870008E3020008E3020008E302000861 +:1000F000E3020008E3020008E302000845470008A5 +:10010000E3020008E30200081D880008E30200087B +:10011000E3020008F5870008E3020008E302000894 +:100120007147000899470008C5470008F1470008D3 +:100130001D480008E3020008E3020008E30200088B +:10014000E3020008E3020008E3020008E3020008FB +:1001500045480008714800089D480008E30200086F +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008F9820008E3020008E302000835 +:10018000E3020008E302000809880008E30200080F +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008E5820008E3020008E3020008E9 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000CD870008E3020008E3020008E30200089B +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F040FA2F +:1003500006F0ACFB4FF055301F491B4A91423CBFA1 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F058FA06F00AFCF4 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F040BA000600200022002025 +:1003D0000000000808ED00E00000002000060020FA +:1003E000B89C0008002200207422002078220020FF +:1003F00034670020E0020008E0020008E002000884 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F022F9FEE706F0D2 +:100430007BF800DFFEE7000053B94AB9002908BF86 +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000FFF901F0C1FB06F0CBFE054606F0D4FF31 +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F0C3FE0CB12B +:1007700000F078F801F048FB00F026FD08B100F029 +:1007800071F8284600F01CF9F9E70025ECE705466A +:10079000EAE700BF010007B008B501F09DF9A0F13C +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0ADF903B05DF804FB19 +:1007C00038B5302383F31188174803680BB106F05E +:1007D00033F80023154A4FF47A71134806F022F8D3 +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F060FA3223636078 +:100810002B78032B07D163682BB9022001F056FA1D +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F031BA0220BA +:1008500001F01EBA024B00225A607047902200201D +:1008600098230020F8B5504B504A1C4619680131B6 +:1008700000F0998004339342F8D162684C4B9A425D +:1008800040F291804B4B9B6803F1006303F500330A +:100890009A4280F08880002001F06CF90220FFF776 +:1008A000CBFF454B0021D3F8E820C3F8E810D3F87C +:1008B0001021C3F81011D3F81021D3F8EC20C3F89D +:1008C000EC10D3F81421C3F81411D3F81421D3F881 +:1008D000F020C3F8F010D3F81821C3F81811D3F89A +:1008E0001821D3F8802042F00062C3F88020D3F8AA +:1008F000802022F00062C3F88020D3F88020D3F853 +:10090000802042F00072C3F88020D3F8802022F0CB +:100910000072C3F88020D3F8803072B64FF0E02325 +:10092000C3F8084DD4E90004BFF34F8FBFF36F8FB6 +:10093000224AC2F88410BFF34F8F536923F48033E7 +:100940005361BFF34F8FD2F8803043F6E076C3F3A4 +:10095000C905C3F34E335B0103EA060C29464CEA92 +:1009600081770139C2F87472F9D2203B13F1200F5C +:10097000F2D1BFF34F8FBFF36F8FBFF34F8FBFF332 +:100980006F8F536923F4003353610023C2F8503250 +:10099000BFF34F8FBFF36F8F302383F311888546EA +:1009A00080F308882047F8BD0000020820000208F4 +:1009B000FFFF0108002200200044025800ED00E083 +:1009C0002DE9F04F93B0B44B2022FF2100900AA8EC +:1009D0009D6801F0C3F9B14A1378A3B90121B04869 +:1009E00011700360302383F3118803680BB105F0A5 +:1009F00023FF0023AB4A4FF47A71A94805F012FF98 +:100A0000002383F31188009B13B1A74B009A1A604F +:100A1000A64A1378032B03D000231370A24A536015 +:100A20004FF0000A009CD3465646D146012001F003 +:100A30003FF924B19C4B1B68002B00F0268200205C +:100A400001F04AF80390039B002BF2DB012001F038 +:100A50001FF9039B213B1F2BE8D801A252F823F07A +:100A6000E10A0008090B00089D0B00082D0A000888 +:100A70002D0A00082D0A00082F0C0008FF0D0008A1 +:100A8000190D00087B0D0008A30D0008C90D000812 +:100A90002D0A0008DB0D00082D0A00084D0E000885 +:100AA000810B00082D0A0008910E0008ED0A0008CD +:100AB000810B00082D0A00087B0D00082D0A000894 +:100AC0002D0A00082D0A00082D0A00082D0A00082A +:100AD0002D0A00082D0A00082D0A00089D0B0008A9 +:100AE0000220FFF759FE002840F0F981009B022107 +:100AF00005A8BAF1000F08BF1C4641F21233ADF849 +:100B0000143001F007F891E74FF47A7000F0E4FF39 +:100B1000071EEBDB0220FFF73FFE0028E6D0013F77 +:100B2000052F00F2DE81DFE807F0030A0D1013360F +:100B30000523042105A8059300F0ECFF17E004212C +:100B40005548F9E704215A48F6E704215948F3E7E4 +:100B50004FF01C08404608F1040801F00DF804218C +:100B6000059005A800F0D6FFB8F12C0FF2D10120B6 +:100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F +:100B800001F038F926B10BF00B030B2B08BF002442 +:100B9000FFF70AFE4AE704214748CDE7002EA5D01B +:100BA0000BF00B030B2BA1D10220FFF7F5FD07463D +:100BB00000289BD00120002600F0DCFF0220FFF778 +:100BC0003BFE1FFA86F8404600F0E4FF0446B0B151 +:100BD000039940460136A1F140025142514100F0D3 +:100BE000E9FF0028EDD1BA46044641F21213022172 +:100BF00005A83E46ADF8143000F08CFF16E72546F8 +:100C00000120FFF719FE244B9B68AB4207D9284609 +:100C100000F0B2FF013040F067810435F3E70025B2 +:100C2000224BBA463E461D701F4B5D60A8E7002E62 +:100C30003FF45CAF0BF00B030B2B7FF457AF02209C +:100C4000FFF7FAFD322000F047FFB0F10008FFF691 +:100C50004DAF18F003077FF449AF0F4A08EB0503C7 +:100C6000926893423FF642AFB8F5807F3FF73EAFC0 +:100C7000124BB845019323DD4FF47A7000F02CFF3E +:100C80000390039A002AFFF631AF039A0137019BC4 +:100C900003F8012BEDE700BF002200209423002081 +:100CA00078220020C107000898230020902200200D +:100CB00004220020082200200C2200209422002080 +:100CC000C820FFF769FD074600283FF40FAF1F2D2E +:100CD00011D8C5F120020AAB25F003008449424532 +:100CE000184428BF4246019201F012F8019AFF21F0 +:100CF0007F4801F033F84FEAA803C8F387027C4924 +:100D00002846019301F032F8064600283FF46DAF03 +:100D1000019B05EB830533E70220FFF73DFD00282B +:100D20003FF4E4AE00F064FF00283FF4DFAE00279C +:100D3000B846704B9B68BB4218D91F2F11D80A9B2D +:100D400001330ED027F0030312AA134453F8203CBA +:100D500005934046042205A9043701F00BF98046AB +:100D6000E7E7384600F008FF0590F2E7CDF8148079 +:100D7000042105A800F0CEFE02E70023642104A8A8 +:100D8000049300F0BDFE00287FF4B0AE0220FFF710 +:100D900003FD00283FF4AAAE049800F01FFF059061 +:100DA000E6E70023642104A8049300F0A9FE0028CC +:100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 +:100DC000049800F00DFFEAE70220FFF7E5FC002899 +:100DD0003FF48CAE00F01CFFE1E70220FFF7DCFCE3 +:100DE00000283FF483AE05A9142000F017FF074642 +:100DF0000421049004A800F08DFE3946B9E73220A2 +:100E000000F06AFE071EFFF671AEBB077FF46EAE00 +:100E1000384A07EB0903926893423FF667AE022017 +:100E2000FFF7BAFC00283FF461AE27F003074F44F8 +:100E3000B9453FF4A5AE484609F1040900F09CFE0F +:100E40000421059005A800F065FEF1E74FF47A70E3 +:100E5000FFF7A2FC00283FF449AE00F0C9FE0028CD +:100E600044D00A9B01330BD008220AA9002000F0CD +:100E70007DFF00283AD02022FF210AA800F06EFF53 +:100E8000FFF792FC1C4805F0F9FB13B0BDE8F08FAA +:100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 +:100EA0000023642105A8059300F02AFE07460028C8 +:100EB0007FF41CAE0220FFF76FFC804600283FF451 +:100EC00015AEFFF771FC41F2883005F0D7FB0598AD +:100ED00000F0D8FF46463C4600F08CFFA6E50646EB +:100EE0004EE64FF0000901E6BA467EE637467CE65C +:100EF0009422002000220020A086010070470000FC +:100F000070470000704700002DE9F04100F5803780 +:100F1000044616463B7C5BB9C0681030204400F0A4 +:100F2000F7FEE5683544B5F5004FE56002D816B127 +:100F3000BDE8F081DEB905F07F0605F11000002163 +:100F4000C6F180062044F6B232462E4400F006FF79 +:100F5000A06804F11008324600F10060414600F537 +:100F6000003006F069F830B901233B74E0E74FF434 +:100F700000463546ECE7A26805F1100140463244D0 +:100F80002144A260E268521BE26000F0C1FE022030 +:100F9000BDE8F04100F09ABE183000F0E9BC000056 +:100FA00010B5044601F002F8204610BD10B5044605 +:100FB00000F0FCFF204610BDC3B280B2A3F1410295 +:100FC000052A02D8373800B27047613B052B94BF21 +:100FD00057383038F7E70000F8B50446154608469C +:100FE00003220C4900F09EFE014688B908346F1CAC +:100FF00015F91100FFF7E0FF064617F9110001315E +:10100000FFF7DAFF102940EA061004F8010BEFD1D0 +:10101000F8BD00BF709200082DE9F04FADF53F7D9F +:101020000746416801222AA802F0A2FE002840F0EB +:1010300087800646824681461125DFF80C81DFF85D +:101040000CB101AB4FF4805241462AA802F0F0FFE8 +:10105000002875D1019AB2F5805F71D8002A65D059 +:101060000446019A9442ECD2282D0FD008DC132DAF +:101070002DD01E2D39D0112D13D00134A4B2F0E79C +:10108000322D2DD0372D2FD02D2DF6D13B68121BB0 +:1010900008EB040138461B692D259847BDF804402C +:1010A000EBE7121B022A09D9594608EB040000F0AD +:1010B00039FE18B902342825A4B2DEE718F8043046 +:1010C0003A2B3DD00A2B1CBFA1461325D5E718F8B3 +:1010D00004300A2B34D03A2B04BFA2463225CCE789 +:1010E00018F80430202BC8D0264618F804300A2BF4 +:1010F0001AD1AAEB090208EB090102A811254F2A0F +:1011000028BF4F2208F0A0F8A21B08EB060116A882 +:101110004F2A28BF4F2208F097F83B6816AA02A969 +:10112000DB6838469847A8E71E25A6E73B6838469F +:1011300004491B69984701200DF53F7DBDE8F08FFC +:101140000020F9E772930008A023002074920008A1 +:1011500000F1180110B5044686B00846019100F070 +:10116000F1FB2046FFF758FF60B1019902A800F09B +:1011700049FC102204F1080102A808F025F8B0FA91 +:1011800080F0400906B010BD70B504460025EEB2EF +:10119000304600F0FFFC58B100213046013500F028 +:1011A00009FD08B9002070BD022000F08FFDEEE7B8 +:1011B0002046FFF731FF0028F4D004F58034207C6E +:1011C00080F00100EFE70000F0B5C9B006F0A0F92B +:1011D00000F008FF18B90025284649B0F0BD69465F +:1011E0002A4802F0E7FF00284BD1294C204603F0A3 +:1011F00011F8284803F00EF8274803F00BF82146B1 +:10120000224803F083F80028E5D1702000F0C8FEE2 +:10121000064610B1214B44600360336830469B683A +:101220009847054600282ED01A4F1948394603F032 +:101230006DF805460028CED1194800F0B1FE0446ED +:1012400038B1184B4760036000F58033C0E90255A0 +:101250001D74236820469B689847054628B10E49AF +:101260000C4803F053F80028B5D1336830465B686A +:1012700098471CB1236820465B68984700F09AFEA7 +:10128000AAE70025FAE70446EFE700BF78920008D6 +:10129000889200089F920008B5920008D892000832 +:1012A00014000100F49200082DE9F04FD44A8DB0EB +:1012B0000B68D0F804A001931A440368D14E1A4475 +:1012C000D1F81C90DFF8B4C3DFF8B4B3D0E902342E +:1012D000634003EA0A03634013444A6802920AEB3C +:1012E0007363029CC84A2244C468224484688AEA20 +:1012F00004051D40654015448A68039203EB35558B +:10130000039CC24A2244846822448AEA03042C4093 +:1013100084EA0A041444CA6805EBF43404921644BF +:1013200083EA0502224056445A4032440E6905962B +:1013300004EBB222059FB64E3E441E4485EA0403E8 +:1013400013406B4033444E69069602EB7363069F6D +:10135000B04E3E442E4484EA02051D4065403544AB +:101360008E69079603EB3555079FAB4E3E442644E6 +:1013700082EA03042C4054403444A84E4E4405EB0A +:10138000F434164483EA050222405A4032440E6A7D +:10139000089604EBB222089FA14E3E441E4485EA03 +:1013A000040313406B4033444E6A099602EB7363A7 +:1013B000099F9C4ED1F830E03E44D1F83880F34488 +:1013C0002E4484EA02051D40654035448E6AA6F528 +:1013D000244703EB35550A964F3F274482EA03041E +:1013E0002C4054403C44CF6A0B9705EBF4340B9EE1 +:1013F0008D4F3744029E174483EA050222405A402B +:101400003A448A4F774404EBB2221F4485EA04032E +:1014100013406B403B444F6BBC4402EB7363654429 +:1014200084EA020C0CEA030C8CEA040C6544DFF835 +:1014300054C2C44403EB3555A44482EA03042C404F +:1014400054406444D1F83CC0794905EBF43461441C +:10145000114483EA050222405A400A44754904EBCC +:10146000B2223144079E194484EA02032B406340B0 +:101470000B44714902EBF36331440B9E0D4482EA45 +:1014800003012140514029446C4D03EBF151354497 +:10149000019E254483EA010414405C402C44684DBD +:1014A00001EBB4443544069E154481EA04021A4017 +:1014B0004A402A44634D04EB323235440A9E1D44AF +:1014C00084EA02030B4063402B445F4D02EBF3635D +:1014D0003544059E0D4482EA0301214051402944D0 +:1014E0005A4D03EBF1516544254483EA010414404D +:1014F0005C402C44564D01EBB4443544099E1544E0 +:1015000081EA04021A404A402A44524D04EB323226 +:101510003544049E1D4484EA02030B4063402B447F +:101520004D4D02EBF36345440D4482EA0301214033 +:1015300051402944494D03EBF1513544089E2C4458 +:1015400083EA010515405D402C44454D01EBB44450 +:101550003544039E2A4481EA04051D404D402A4437 +:10156000404D04EB32323D442B4484EA020593445F +:101570000D4065402B443C4D02EBF3633544069E21 +:10158000294482EA0305254055402944374D03EBA1 +:10159000F1514D442C4483EA010515405D4025443A +:1015A00001EBB54581EA050404EA03024A405A44C6 +:1015B000A6F5B82B089E05EB3232ABF2BE6B544059 +:1015C0005B4423442A4C344402EB33730B9E0C449B +:1015D00085EA020159402144264C344403EB715101 +:1015E000029E254482EA03044C402544224C444494 +:1015F00001EB3545144483EA01026A40224443E08A +:1016000078A46AD7EECEBDC156B7C7E8DB702024F8 +:10161000AF0F7CF52AC68747134630A8019546FDD3 +:10162000D8988069AFF7448BBED75C892211906B44 +:101630002108B44962251EF640B340C0515A5E26C7 +:10164000AAC7B6E95D102FD65314440281E6A1D88B +:10165000C8FBD3E7E6CDE121D60737C3870DD5F424 +:10166000ED145A4505E9E3A9F8A3EFFCD9026F6729 +:1016700081F6718722619D6D0C38E5FD937198FDAF +:101680008A4C2A8D8E4379A6934C344405EB722202 +:10169000059E1C4481EA0503534023448F4C344487 +:1016A00002EB33730A9E0C4485EA0201594021443F +:1016B0008B4C4C4403EB7151254482EA03044C40AB +:1016C0002C44884D354401EB3444019E154483EA93 +:1016D000010262402A44844D3D4404EB72221D44C1 +:1016E00081EA040353402B44804D354402EB3373AD +:1016F000049E294484EA02055D4029447C4D35441A +:1017000003EB7151079E254482EA03044C402C44AC +:10171000784D354401EB3444099E2A4483EA01059F +:1017200065401544744A324404EB7525039E134406 +:1017300081EA04026A401A44704B734405EB32722A +:101740000B4484EA0501514019446D4B634402EB9C +:1017500071511C4485EA02034B401C44694B3344DD +:1017600001EB3444019E1D4482EA010363402B4493 +:10177000654D04EB73233544069E154463EA01026C +:1017800062402A44614D03EBB2624D4462EA0409AF +:1017900029445F4D89EA0309454449442C445D4D81 +:1017A00002EBB1513544049E61EA03081D4488EA06 +:1017B0000208444401EB744464EA02034B402B44A6 +:1017C000554D04EBF323754463EA010E15448EEA8C +:1017D000040E0EEB0502514D03EBB262354462EA92 +:1017E000040E29440A9D8EEA030EA5F580164C4D81 +:1017F0007144A6F6833602EBB151264461EA030434 +:1018000054403444029E01EB7444354464EA0206B9 +:101810001D444E407319089E424D04EBF32335449A +:1018200063EA01061544664072193F4D03EBB2624C +:10183000654462EA040629443C4D5E403144079EFB +:1018400002EBB151354461EA03062C44384D564051 +:101850003D443444059E1D4401EB744464EA020394 +:101860004B402B44334D04EBF32335440B9E15447E +:1018700063EA010262402A442F4D03EBB262354411 +:10188000039E0D4462EA0401594029442B4D02EBAA +:10189000B15135442A4E254461EA030454402C4496 +:1018A000099D01EB74442E4464EA02051E4485EA56 +:1018B00001039D1903681A440AEB040303EBF523A3 +:1018C0000260436083681C44C36819448460C1603B +:1018D0000DB0BDE8F08F00BF44EABEA4A9CFDE4B37 +:1018E000604BBBF670BCBFBEC67E9B28FA27A1EA40 +:1018F0008530EFD4051D880439D0D4D9E599DBE6CD +:10190000F87CA21F6556ACC4442229F497FF2A43F1 +:10191000A72394AB39A093FCC3595B6592CC0C8F81 +:10192000D15D84854F7EA86FE0E62CFE144301A3B1 +:10193000A111084E827E53F735F23ABDBBD2D72AA9 +:1019400091D386EB094B036003F18833436003F1C5 +:101950002943A3F59613A3F68B638360A3F1883321 +:10196000C3600023C0E90433704700BF012345670B +:101970002DE9F8431446026905460E46E300C2F31A +:10198000C50800F118079B18036122BF43690133A2 +:10199000436112F4FC7F436903EB5473436114D039 +:1019A000C8F1400907EB08004C4504D22246BDE8C7 +:1019B000F84307F019BC403C4A464E4407F014FC7B +:1019C000444439462846FFF76FFCA04606EB04095D +:1019D000B8F13F0FA9EB08010AD94022384607F0B9 +:1019E00003FC39462846A8F14008FFF75DFCEFE705 +:1019F000A1096FF03F02384602FB014206EB81115C +:101A0000D5E7000070B50B6901F1180506460C46D4 +:101A1000C3F3C503EA18501C8022EA54C3F13F0205 +:101A2000072A1FD8002100F099F929462046FFF720 +:101A30003BFC38220021284600F090F92369294612 +:101A40002046236563696365FFF72EFC214610225B +:101A5000304607F0C9FB204658220021BDE87040FF +:101A600000F07CB9C3F137020021E5E72DE9F84F1A +:101A70004FF47A7306460D46002402FB03F7DFF8A5 +:101A80005080DFF8509098F900305FFA84FA5A1CC1 +:101A900001D0A34210D159F824002A4631460368E8 +:101AA000D3F820B03B46D847854205D1074B0120EB +:101AB00083F800A0BDE8F88F0134042CE3D14FF483 +:101AC000FA7004F0DBFD0020F4E700BFE4330020EF +:101AD0001022002014220020002307B50246012115 +:101AE0000DF107008DF80730FFF7C0FF20B19DF81A +:101AF000070003B05DF804FB4FF0FF30F9E700008A +:101B00000A46042108B5FFF7B1FF80F00100C0B21A +:101B1000404208BD074B0A4630B41978064B53F8CB +:101B20002140014623682046DD69044BAC4630BCA9 +:101B3000604700BFE433002014220020A08601008B +:101B400070B50A4E00240A4D05F01AFA3080286854 +:101B50003388834208D905F00FFA2B680444013317 +:101B6000B4F5003F2B60F2D370BD00BFE633002018 +:101B7000A033002005F0D2BA00F1006000F500307B +:101B80000068704700F10060920000F5003005F039 +:101B900053BA0000054B1A68054B1B889B1A8342F9 +:101BA00002D9104405F0E8B900207047A0330020A6 +:101BB000E633002038B50446074D29B12868204493 +:101BC000BDE8384005F0F0B92868204405F0DAF99E +:101BD0000028F3D038BD00BFA0330020002070479C +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7BFBF0120704700BFA43300207E +:101C1000014B1868704700BF0010005C194B013879 +:101C20000322084470B51D68174BC5F30B042D0C37 +:101C30001E88A6420BD15C680A46013C82421346CC +:101C40000FD214F9016F4EB102F8016BF6E7013AB9 +:101C500003F10803ECD181420B4602D22C2203F897 +:101C6000012B0424094A1688AE4204D1984284BF4D +:101C7000967803F8016B013C02F10402F3D1581A83 +:101C800070BD00BF0010005C2422002034930008C7 +:101C9000022804D1054B4FF400129A6170470128C5 +:101CA000FCD1024B4FF48012F7E700BF001002583E +:101CB000022803D1044B20229A6170470128FCD1ED +:101CC000014B1022F8E700BF00100258022805D18E +:101CD000064A536983F02003536170470128FCD101 +:101CE000024A536983F01003F6E700BF0010025860 +:101CF00070B504464FF47A764CB1412C254628BF86 +:101D0000412506FB05F0641B04F0B8FCF4E770BD48 +:101D1000002310B5934203D0CC5CC4540133F9E7DF +:101D200010BD0000013810B510F9013F3BB191F929 +:101D300000409C4203D11AB10131013AF4E71AB1D3 +:101D400091F90020981A10BD1046FCE703460246A0 +:101D5000D01A12F9011B0029FAD170470244034638 +:101D6000934202D003F8011BFAE770472DE9F843CC +:101D70001F4D14460746884695F8242052BBDFF8CD +:101D800070909CB395F824302BB92022FF2148464F +:101D90002F62FFF7E3FF95F824004146C0F10802E7 +:101DA00005EB8000A24228BF2246D6B29200FFF780 +:101DB000AFFF95F82430A41B17441E449044E4B2AE +:101DC000F6B2082E85F82460DBD1FFF711FF00285A +:101DD000D7D108E02B6A03EB82038342CFD0FFF711 +:101DE00007FF0028CBD10020BDE8F8830120FBE7E6 +:101DF000A4330020024B1A78024B1A70704700BFC0 +:101E0000E433002010220020F8B5194C194803F0E3 +:101E10003DFF2146174803F065FF24684FF47A70B0 +:101E2000154ED4F89020154DD2F80438114F43F0D8 +:101E30000203C2F80438FFF75BFF2046104904F0A4 +:101E40005FF8D4F890200424D2F8043823F0020379 +:101E5000C2F804384FF4E133336055F8040BB8424C +:101E600002D0314603F070FE013CF6D1F8BD00BF50 +:101E7000309B000818490020CC3300201422002099 +:101E8000389B00080C4B70B50C4D04461E780C4B6B +:101E900055F826209A420DD00A4B002118221846E8 +:101EA000FFF75CFF0460014655F82600BDE870406E +:101EB00003F04ABE70BD00BFE433002014220020AE +:101EC00018490020CC330020F0B5A1B071B6002332 +:101ED0000120002480261A46194602F087FD4FF49F +:101EE000D067214A3D25136923BBD2F810310BBBC3 +:101EF000036804F1006199600368C3F80CD00368BB +:101F00005E6003681F6001680B6843F001030B60AB +:101F100001680B6823F01E030B6001680B68DB0788 +:101F2000FCD4037B8034416805FA03F3B4F5001F49 +:101F30000B60D8D102F09AFDB4F5001F11D0002437 +:101F40000A4E0B4D012005F0E9F83388A34205D96C +:101F500028682044013405F027F8F6E7002005F052 +:101F6000DDF861B621B0F0BD00200052E63300205C +:101F7000A033002030B50A44084D91420DD011F82D +:101F8000013B5840082340F30004013B2C4013F070 +:101F9000FF0384EA5000F6D1EFE730BD2083B8EDAF +:101FA0000121884238BF084605F090B908B105F014 +:101FB00091B9704710B5084C01220849002001F082 +:101FC000B3FE23783BB1064803F036FD044803F026 +:101FD00069FD0023237010BDE833002044930008FE +:101FE000C83600201D482DE9F041036D2BB90122B0 +:101FF0004FF48051503005F0D1FA194E33780BB1BF +:10200000FFF7D8FF0324174F4FF00008134D154971 +:102010002846C7F8048003F037FD284603F070FB1C +:1020200048B1013C284603F03DFD14F0FF04EED119 +:10203000204634700FE00C4901220C4801F074FE78 +:10204000014618B1284603F0F7FCEAE7084800F01B +:1020500011F801203070BDE8F08100BFC8360020C3 +:10206000E83300203C22002044930008EC33002099 +:10207000489300080FB4002004B070470068704710 +:1020800003460068596870470B0A017043700B0CD7 +:10209000090E8370C1707047110A0270037141709C +:1020A000110C120E8170C2701A0A42711A0C1B0EAA +:1020B0008271C37170470000C36A0239023B8B42D0 +:1020C00083BF4389006C01FB0300002070470000C0 +:1020D000C2F307238A76CB760378032B01BF120C59 +:1020E0000A75120A4A75704700F10B010022D301EC +:1020F00043EA520310F8012B52FA83F38842DAB212 +:10210000F5D110467047000010B541780446002014 +:10211000013102464901022A16BFA35C032203EBE8 +:10212000C03302F101021EBF9BB203EB500398B211 +:102130009142F0D810BD000002684AB1134613F86E +:10214000011B1F290DD93A29F9D1911C8B4202D0CC +:102150004FF0FF3070471278302AF9D10360002029 +:102160007047014B187870473836002038B50D4657 +:10217000044618B9092000232B6038BD0368002BE2 +:10218000F8D01A78002AF5D08188DA889142F1D106 +:10219000587804F00FFC10F00100EBD12368EBE756 +:1021A00038B50D4640F25231144602F0B9F9FF2815 +:1021B00007D9012C0BD9030A022468702B70204622 +:1021C00038BD30B1002CFAD001242870F7E7002484 +:1021D000F5E70446F3E700002DE9F8430026D0F8C0 +:1021E000008005460C468E76836B002B4AD098F80B +:1021F0000030042B4BD133463546402720E0B7F55D +:10220000187F80F0C480F90606F1010608BF023786 +:10221000D05B02372BB900F5205292B2B2F5006FB5 +:102220000DD305F11A01C5F1FF0240EA0340214434 +:10223000FFF7B6FF002800F0AA80054400200346FF +:10224000D8F8102092F82310B142D8D8002B40F0D3 +:102250009E80002D00F09B8000232544AB766373A5 +:10226000D8F81020137903F03701DB0621730BD463 +:1022700002F13800FFF704FFC4E90001938963818C +:10228000D3892381BDE8F88300200146F4E7C36CBD +:1022900001335ED1EA6B00232E26551E184615F831 +:1022A000011F013020290CD0052908BFE52109288C +:1022B00004D10B2B9EBFE71801337E73E71801335F +:1022C00079730B28EBD1E11800204873A17E002917 +:1022D0004BD1002B40D06FF00C0604F10D00082507 +:1022E000361B331810F8011B002938D02E298BB269 +:1022F0004AD0A3F14101192903D8117B0D4200D026 +:1023000020330373EDE7B9F1000F05D100F5205339 +:102310009BB2B3F5006F0BD307F11A01C7F1FF02AF +:1023200040EA09402144FFF73BFF48B10744002041 +:1023300002368146D8F80C30985B0028E3D1384645 +:10234000B9F1000F4FF0000218BF002023189A7651 +:10235000A0E7B1463746EDE73F23A37601232344A8 +:1023600000219976137B03B96373D37A02F11C00C1 +:1023700003F03F0323730023FFF780FE20606360B8 +:10238000D38A6381138B7CE710250B46B9E73F2383 +:102390000125A37660E7000038B50546002435F82E +:1023A000020B08B9204638BD02F0EEF86308C2B24D +:1023B00003EBC43312FA83F39AB2C0F3072303EB9F +:1023C000520303EBC2339CB2E9E7000037B5C37890 +:1023D00004461BB90025284603B030BD00F14C016E +:1023E000826C01234078019104F00AFB054680B914 +:1023F000A36BE070A06C226BC31A9342EAD2A3785D +:102400000199022BE6D102440123607804F0F8FA26 +:10241000E1E70125DFE7000038B5836C05460C468F +:102420008B4210D0FFF7D2FF60B92246012305F19D +:102430004C01687804F0C0FA00281CBF4FF0FF344C +:102440000120AC6438BD0020FCE7000038B5002353 +:102450000446C3704FF0FF338364FFF7DDFF0028AD +:102460004BD1B4F84A524AF655239D4207D10B226C +:10247000254904F14C0006F0A7FE00283FD094F84F +:102480004C30EB2B03D01833DBB2012B2ED84AF69D +:1024900055239D4206D108221C4904F19E0006F0F6 +:1024A00093FE48B3B4F85730B3F5007F1ED194F8CB +:1024B0005930DBB15A1E1A4218D1B4F85A30ABB1B8 +:1024C00094F85C30013B012B10D8B4F85D306BB14F +:1024D000B4F85F307F2B06D804F16C00FFF7CEFD17 +:1024E000B0F5803F02D3B4F8623053B94AF65520B4 +:1024F00085420CBF0220032038BD0420FCE70120E8 +:10250000FAE70020F8E700BF749300088093000802 +:1025100002392DE9F04701F007044FF0010A466C3B +:1025200005460AFA04F41746984606EB1136C1F33D +:10253000C809E4B2314628460136FFF76DFF18B1ED +:102540000120BDE8F087994605EB090292F84C306E +:10255000234214BF01210021414513D06340013FB4 +:1025600082F84C3085F803A0EBD0640014F0FF042F +:10257000EAD109F1010301244FF00009B3F5007F0E +:10258000E1D1D7E70220DCE701290246F8B50C4685 +:1025900040F28C800668F36A8B4240F28780337881 +:1025A000013B032B00F28280DFE803F00229384B65 +:1025B00004EB5405B16B304601EB5521FFF72CFFBE +:1025C00010B14FF0FF30F8BD6F1CC5F30805B16BBB +:1025D0003046354401EB572195F84C50FFF71CFF6E +:1025E0000028EED1C7F30807E3073E4496F84C00F5 +:1025F00045EA00204CBF0009C0F30B00E3E7B16BD4 +:10260000304601EB1421FFF707FF0028D9D1640001 +:1026100004F4FF742644B6F84C00D4E7B16B30469E +:1026200001EBD411FFF7F8FE0028CAD1A40006F18F +:102630004C0004F4FE742044FFF720FD20F07040AD +:10264000C1E7D0E90430D57953EA000101D091689F +:1026500001B95DBB9168022DA4EB01010DD1013BD5 +:10266000728940F1FF305B0A43EAC053B3FBF2F3D7 +:1026700099421BD81CD0601CA5E7032D02D1936999 +:102680008B42F8D8D3699BB9B16B304601EBD411BA +:10269000FFF7C2FE002894D1A0004C3600F4FE7073 +:1026A0003044FFF7EBFC20F000408CE701208AE784 +:1026B0006FF0004087E70000F8B5066804460D4655 +:1026C0003378042B0CBF4FF080524FF400128A4233 +:1026D00001D80220F8BDCA06FBD182680163D2B9D5 +:1026E000022B13D83389B3EB551FF2D9F36BA363D5 +:1026F000A36B6263002BECD003EB55234C36C5F380 +:1027000008050020A3633544E563E3E7F36BC2717A +:10271000002BE7D01A4677897F02BD42114604D2CA +:102720003046FFF7C9FCA063E2E72046FFF72CFF25 +:10273000431C024606D00128CBD9F36A8342C8D98C +:10274000ED1BEAE70120C5E701292DE9F047064620 +:102750000C46174608D9C36A8B4205D90378022B69 +:1027600062D003D8012B22D0022552E0033B012B7B +:10277000FAD8816B01EBD411FFF74EFE0546002815 +:1027800047D1A40006F14C0304F4FE741C443378D2 +:10279000042B07D0204627F07047FFF76FFC00F0AE +:1027A0007040074339462046FFF76EFC2FE001EBEF +:1027B0005108816B01EB5821FFF72EFE054640BB07 +:1027C00014F0010406F14C0908F1010AC8F30808E5 +:1027D00008BFFBB230461FBF19F8083003F00F02E4 +:1027E0003B0103F0F00318BF134309F8083001233D +:1027F000B16BF37001EB5A21FFF70EFE054640B9AD +:10280000CAF3080A44B1C7F3071709F80A7001238D +:10281000F3702846BDE8F08719F80A30C7F303279C +:1028200023F00F031F43F0E7816B01EB1421FFF747 +:10283000F3FD05460028ECD1640006F14C0304F4D6 +:10284000FF741F551919C7F307274F70DFE7000002 +:10285000F8B504460E461746E3690BB91846F8BDAD +:10286000012BA6EB0305206814BFAA1C3A46691C7D +:10287000FFF76AFF0028F2D1E369013BE361EBE770 +:1028800001292DE9F84306460C461746056802D88B +:102890000220BDE8F883EB6A8B42F9D97AB9A146E8 +:1028A00021463046A046FFF76FFE0446B0B92B78AC +:1028B000042B02D1002F43D1F7710020E9E72B78D8 +:1028C000042B02D1C379022BE9D04FF0FF323946F5 +:1028D0002846FFF739FF0028E1D0DAE70128D7D0F2 +:1028E000421C01D10120D4E72B78042B19D1EA6ACC +:1028F000AB69023A93421CD308F10102A2420CD008 +:102900002B78042B08D10023A2EB09024946284664 +:10291000FFF7FEFD0028BCD1A146EB6AA342BFD859 +:10292000C5E7002241462846FFF70EFF0028DED00B +:10293000AFE70133AB612B7943F001032B71DBE788 +:10294000F3798BB9B468BC4202D10223F371B4E7C6 +:1029500021463046FFF718FE012899D9431CC1D003 +:1029600001348442EFD0A8E7032BA6D1B368BB4261 +:10297000A3D8B2691344BB429FD3E6E770B5C379CD +:102980000446032B06D181688369CD18A94203D17F +:102990000023E371002070BD4E1C20683246FFF713 +:1029A000D3FE0028F7D13146F0E700002DE9F743C8 +:1029B00005460191FFF70AFD0446002849D105F1BB +:1029C0004C09019928464FF40072FFF775FB214628 +:1029D000A86407464846FFF7C1F96C896402B4F55C +:1029E000004F28BF4FF40044B4F5007F2FD9204694 +:1029F00004F074FC804630B122460021640A0026AF +:102A0000FFF7ACF909E06408EEE72346BA1941463E +:102A1000687803F0F5FF18B926446B899E42F4D319 +:102A2000404604F06BFC6889801B18BF012003B08E +:102A3000BDE8F08301366B899E42F4D20123BA19B6 +:102A40004946687803F0DCFF0028F3D0EBE7002666 +:102A5000F1E70120EBE70000F8B50446FFF7B6FC0C +:102A60000546002842D12378032B37D12779012F3F +:102A700034D104F14C0601464FF400723046FFF7A2 +:102A80006DF955234122722184F84A32AA2304F5B4 +:102A90000D7084F84F2084F84B32522384F83012A2 +:102AA00084F84C3084F84D30612384F8311284F876 +:102AB0004E3084F83332A16984F83222FFF7E4FA09 +:102AC000616904F50E70FFF7DFFA626B3B46314631 +:102AD00001326078A26403F093FF257100226078D0 +:102AE000114603F0B1FF003818BF0120F8BD000007 +:102AF00000232DE9F0430B6085B00F461546FFF724 +:102B00001BFB061EC0F2B281804B53F82640002CFE +:102B100000F0AE813C6005F0FE0523786BB1607873 +:102B200003F048FFC70708D41DB110F0040500D01A +:102B30000A25284605B0BDE8F0830023F0B22370D3 +:102B4000607003F023FFC10700F194810DB14207CB +:102B5000EED400212046FFF779FC022840F099804E +:102B60006E4604F2122304F2522132461846103304 +:102B7000FFF784FA42F8040B8B42F7D1002556F890 +:102B8000041B00297DD02046FFF760FC012879D87E +:102B90000128A26C40F0C08004F1570304F18C01BD +:102BA00013F8015B002D7BD18B42F9D1B4F8B4301E +:102BB000B3F5807F74D194F8B830092B70D104F14B +:102BC0009400FFF75DFA4FF0FF33171841F1000151 +:102BD000BB4275EB010363D304F1A000FFF74EFA8B +:102BE00094F8BA302063012BA37059D194F8B990AE +:102BF00003FA09F91FFA89F36381002B50D0444B83 +:102C000004F1A800FFF73AFA0646984248D8831C18 +:102C1000626304F1A400E362FFF730FA00EB0208FC +:102C200004F19C00C4F84080FFF728FA10441FFA12 +:102C300089F2A06306FB02F313EB080345EB0502E0 +:102C40009F4271EB02032BD32E4604F1AC00FFF739 +:102C500015FAE06365B96389B34221D9E16B204677 +:102C6000FFF72AFA81192046FFF7D6FB98B90136FB +:102C7000631993F84C30812B14D02035C5F3080527 +:102C8000E8E703200135042D7FF479AF042807D14C +:102C900001E0042801D101254BE701287FF678AF38 +:102CA0000D2546E705F1140004F14C063044FFF70A +:102CB000E5F901280546F3D9E36A8342F0D9618931 +:102CC000821E236C02FB01336364A16B204601EB7F +:102CD000D511FFF7A1FB0028DDD105F07F0006EB41 +:102CE0008000FFF7CBF9431C03D00135A842ECD09C +:102CF000D6E70425C4E90500064A25700025138897 +:102D0000E56101339BB21380E38012E73C3600207B +:102D1000FDFFFF7F40360020B4F85730B3F5007F49 +:102D2000BED1B4F8626026B904F17000FFF7A6F9CD +:102D3000064694F85C302663591EA3700129AFD86B +:102D400094F859506581002DAAD0691E2942A7D157 +:102D5000B4F85D8018F00F0FA4F80880A0D1B4F883 +:102D60005F0018B904F16C00FFF788F9B4F85A1045 +:102D7000002995D006FB03FE01EB181CF4446045C6 +:102D80008ED3A0EB0C00A842B0FBF5F388D33E48ED +:102D9000834285D84FF6F57083426DD903259F1C79 +:102DA000114402EB0C03032DE7626263A163236409 +:102DB0004CD1B4F8763053EA08037FF471AFBB000E +:102DC00004F17800FFF75AF9E06303F2FF13B6EB62 +:102DD000532FFFF465AF4FF0FF33032DC4E90533E4 +:102DE0004FF08003237187D1B4F87C30012B83D15D +:102DF000511C2046FFF710FB00287FF47DAFB4F88C +:102E00004A224AF6552320719A427FF475AF1F4B30 +:102E100004F14C00FFF732F998427FF46DAF03F1F3 +:102E2000FF5304F50C70FFF729F903F50053203325 +:102E300098427FF461AF04F50D70FFF71FF9A061B0 +:102E400004F50E70FFF71AF9606155E7B8F1000F4D +:102E50003FF426AF7144022D4FEA4703E1631EBFE2 +:102E6000D91907F0010303EB5103AEE70B2560E628 +:102E70000C255EE603255CE640F6F575AB428CBF9B +:102E8000022501258BE700BFF5FFFF0F525261417C +:102E90002DE9F84F07460568884649B96E69C6B1FD +:102EA000EB6AB34298BF0126AB69A3B9002405E0E1 +:102EB000FFF76AFB0128044603D801242046BDE839 +:102EC000F88F421C00F0D280EB6A8342F6D8464667 +:102ED000EAE70126E8E72A78EB6A042A40F08380D3 +:102EE000A6F1020A023B4FF0010B9A4528BF4FF0B2 +:102EF000000AD146696C284601EB1931FFF78CFABC +:102F000000283BD109F00703EA6AC9F3C8010BFAAC +:102F100003F3901EDBB26A184C4609F1010992F8DE +:102F20004C20814502EA030233BF5B0000234FF4CB +:102F30000071DBB228BF9946B2B90234631E033375 +:102F4000BCD80123214628461A46FFF7E1FA022899 +:102F5000B3D0012800F08A80B8F1000F13D102230A +:102F6000FB710028A9D130E0CA450AD0002BD2D18C +:102F70000131B1F5007FBDD20123CCE74FF0FF3422 +:102F8000DCE70024DAE7FB79022B07D1731CA342AC +:102F9000E7D0BB68F31ABB610323FB7108F10102A0 +:102FA000FB69A24205D113B10133FB61D9E70223CA +:102FB000FBE70BB90123FB61224641463846FFF788 +:102FC00047FC00284FD10123FB61EA6AAB69023A52 +:102FD0006C6193429CBF03F1FF33AB612B7943F0EB +:102FE00001032B716AE7464514D1741C3846A3428D +:102FF00098BF02242146FFF7C7FA01283FF45DAFCE +:10300000431C33D0E0B16B69012B03D9EA6A9342C8 +:1030100038BF1E4634460134EB6AA34203D8012E62 +:103020007FF644AF022421463846FFF7ADFA48B197 +:1030300001283FF442AF013018D0B442EBD135E75C +:10304000002CE7D04FF0FF3221462846FFF77CFBEB +:1030500048B9B8F1000FB8D0224641462846FFF7DC +:1030600073FB0028B1D001287FF427AF4FF0FF3465 +:1030700024E700002DE9F84306680446076B8946FB +:1030800033782037042B0CBF4FF080534FF40013DC +:10309000BB429CBF00238363836B73B1C7F30808F3 +:1030A000B8F1000F3CD10133416B836339B93389E7 +:1030B000B3EB571F34D80023A36304200AE07389BD +:1030C000013B13EA57232BD1FFF75EFA012805468F +:1030D00002D80220BDE8F883421C01D10120F9E7A3 +:1030E000F36A834216D8B9F1000FE4D0616B204631 +:1030F000FFF7CEFE0546C8B10128EAD0431CEDD04B +:1031000001463046FFF752FC0028E7D1E37943F04F +:103110000403E371294630466563FEF7CDFFA063E3 +:103120004C36002027634644E663D3E70720D1E707 +:10313000F8B50E46002104460768FFF7BDFA98B9B6 +:103140000546A16B3846FFF767F968B93A78E36B33 +:10315000042A1B780CD11B060ED5054601212046FA +:10316000FFF788FF0028ECD0042808BF072006E0FE +:10317000E52B01D0002BF0D10135B542EED1F8BDE1 +:10318000C16C4B1C2DE9F04104460568066B1FD14C +:10319000E5274FF00108A16B2846FFF73DF998B9E4 +:1031A0002A78E36B042A09BF1A781F7002F07F02A5 +:1031B0001A7085F80380236BB3420DD2002120469C +:1031C000FFF758FF0028E6D0042808BF022003E0DC +:1031D000FFF772FA0028DBD0BDE8F0812DE9F0415D +:1031E00005460068A96B0669FFF716F9044620B981 +:1031F000EB6B1A78852A03D002242046BDE8F081C3 +:10320000324603F1200153F8040B8B4242F8040BC1 +:10321000F9D1777801377F01A7F16003B3F5007F1B +:10322000EAD800212846FFF725FF04280446E3D00A +:103230000028E2D1A96B2868FFF7EEF804460028C1 +:10324000DBD1EB6B1A78C02AD6D106F1200203F14C +:10325000200153F8040B8B4242F8040BF9D196F885 +:1032600023300F222C33B3FBF2F3B7EB431FC3D34E +:103270004FF0400800212846FFF7FCFE04280446D2 +:10328000BAD00028B9D1A96B2868FFF7C5F8044661 +:103290000028B2D1EB6B1A78C12AADD1B8F5187FEE +:1032A00009D206EB080203F1200153F8040B8B420C +:1032B00042F8040BF9D108F120084745DAD8B8F5EF +:1032C000187F9AD83046FEF71FFF7388834294D048 +:1032D00092E700000B68002210B5036004460B6AF9 +:1032E00083604B6AC261C37123F0FF03896AC0E93E +:1032F0000432C164FFF7E0F920B92046BDE8104070 +:10330000FFF76CBF10BD0000F8B503680546012744 +:103310001C692046FEF7F8FEA070000A6678E0708F +:103320002846E96CFFF7C8F920B1022828BF02201F +:10333000C0B2F8BDA96B2868FFF76EF80028F4D179 +:10334000EB6B04F1200254F8041B944243F8041B75 +:10335000F9D12B68DF70002EE7D000212846013E0E +:10336000FFF788FEE0E700002DE9F8434FF0FF0883 +:1033700006460768042445464FF6FF79B16B11B93C +:10338000002C73D063E03846FFF746F80446002867 +:103390005DD1F06B0378002B6ED03A78042A11D1FE +:1033A000852B4DD1336B3046F364FFF717FF04468E +:1033B00000284CD13B691B7903F03F03B3712046D1 +:1033C000BDE8F883C27AE52B02F03F02B27143D028 +:1033D0002E2B41D022F0200108293DD00F2A40D1C8 +:1033E000590637D503F0BF05336B90F80D80F364B1 +:1033F000437B434530D1428B72BB03780D21FC687F +:1034000023F04003DFF874E0013B4B4301211EF839 +:1034100001CB30F80CC009B3FF2B1DD824F813C022 +:103420006146013301320D2AF1D10278520605D5E9 +:1034300021B1FF2B10D8002224F81320013DEDB25A +:1034400000213046FFF716FE0446002896D00023E0 +:10345000B363B4E7AB42CBD0FF25F1E7CC45E1D075 +:10346000FAE72DB9FEF740FE404501D10024A6E75A +:103470004FF0FF33F364A2E70424E8E71C9400084C +:103480002DE9F04F002187B00446D0F80090FFF7F7 +:1034900013F9804670B999F80030042B33D1D9F86C +:1034A0000C00FEF779FF07462046FFF75DFF054653 +:1034B00020B18046404607B0BDE8F08FD9F8103003 +:1034C0009A8CBA42F0D193F823B040265D4506D1DC +:1034D000D9F80C3033F81530002BE5D1EAE7F106C6 +:1034E000D9F8103008BF0236985B01F04DF8D9F8D2 +:1034F0000C30824633F8150001F046F88245D3D1EE +:1035000002360135E2E74FF0FF0A4FF0FF3B554628 +:10351000C4F84CB0A16B4846FEF77EFF00285CD192 +:10352000E66B3778002F77D0F27AE52F02F03F0371 +:10353000A37103D0120704D50F2B04D0C4F84CB0EC +:103540004FE00F2B54D194F84B3058063FD47906F6 +:1035500045D5236B07F0BF0796F80DA0E364737B96 +:1035600053453ED1738B002B3BD135780121D9F8DF +:103570000C3005F03F0501930D23013D5D43284BC1 +:1035800013F8012BB25A71B3FF2D059329D81046B9 +:10359000049200F0F9FF6B1C03900293019B33F837 +:1035A000150000F0F1FF039981421AD1049A029D9F +:1035B0001146059B1B4A9342E2D133785A0604D543 +:1035C00019B1019B33F815305BB97D1EEDB20021B6 +:1035D0002046FFF74FFD00289CD080466AE7BD4299 +:1035E000BDD0FF25F3E74FF6FF708242E2D0F8E747 +:1035F0002DB93046FEF778FD50453FF45BAF94F8A7 +:103600004B30DB079AD40B2204F14001304605F021 +:10361000DBFD002892D14DE74FF004084AE700BFD8 +:103620001C940008299400082DE9F04F90F84BB045 +:1036300099B004461BF0A00540F068810668F26866 +:1036400032F81530002B4AD13378042B40F08780B4 +:103650000F230E352046B5FBF3F5A91CFFF768FDD7 +:103660008146002877D1236B0135A3EB4515E3791B +:103670005A07E56435D523F004032046E371FFF7CC +:103680007DF950BB4FF0FF32616B2046FFF7E0F849 +:1036900018BBA3682BB3214604A8FFF71BFEE0B9B3 +:1036A00070894FF40071D4E90423E0FB01233069F1 +:1036B000C4E904233830FEF7EFFC3069D4E9042371 +:1036C0002830FEF7E9FCE379326904A843F00103EE +:1036D00082F82130FFF718FE18B181463BE0013532 +:1036E000AEE7D6E90354402200212046FEF736FB20 +:1036F0008523012140222370C0234FF0C10C04EB2D +:10370000010884F8203000231E469E46571C04F80A +:1037100002C0F0B2023204F807E021B135F813100C +:1037200009B10133DBB20F0AA15408F8027002326A +:10373000D706F2D135F813700136002FE6D184F8A0 +:103740002330831C28466370FEF726FE84F824008D +:10375000000A84F82500484619B0BDE8F08F04F14E +:1037600040070DF1100A1BF0010F97E807008AE8E7 +:10377000070000F0D38040234FF0010884F84B305D +:10378000BC46F368B8F1050F9AE80700ACE80300FF +:103790002CF8022B4FEA12428CF8002059D9981EBF +:1037A000424630F8021F002942D10DF10F0C0721CB +:1037B00002F00F0E914612090EF13000392888BF31 +:1037C0000EF1370001390CF8010902D0B9F10F0FE1 +:1037D000EED818AB7E205A1802F8580C3846002252 +:1037E000914206D010F801CB02F1010EBCF1200F7E +:1037F00031D104F13F0C072902F1010297BF18AB48 +:1038000020205818013198BF10F8580C072A0CF8DE +:103810000200F0D92046FFF733FE8146002878D118 +:1038200008F10108B8F1640FAAD14FF0070992E737 +:103830004FF0100C01F0010E49080EEB4202D303C9 +:1038400044BF82F4883282F02102BCF1010CF1D134 +:10385000A7E74246A9E77246C2E7216B2046A1EBE3 +:103860004511FEF729FF814600287FF474AF4FF61B +:10387000FF783846FEF738FC0190A16B3046FEF722 +:10388000CBFD814600287FF466AFE36BE9B2019A75 +:103890004FF00D0CD6F80CE05A734FF00F02DFF822 +:1038A000E0A0DA724A1E18730CFB02F28446987686 +:1038B000D87640451AF8019B0CF1010C18BF3EF870 +:1038C000120003EB090B18BF013203F809004FEA9D +:1038D0001029002808BF4046BCF10D0F8BF801905D +:1038E000E7D1404502D03EF812200AB941F040012C +:1038F0001970012300212046F370FFF7BBFB8146BE +:1039000000287FF428AF013DB7D11BE04FF0060936 +:1039100021E704287FF41FAF84F84BB01BF0020F9F +:1039200020461BBF0C350D210125B5FBF1F518BF55 +:1039300001352946FFF7FCFB814600287FF40BAFD9 +:10394000013D8AD1A16B3046FEF766FD8146002815 +:103950007FF401AF01462022E06BFEF7FFF9E36B35 +:1039600003CF18605960BA7839889A72198194F82F +:103970004B30E26B03F0180313730123F370EAE694 +:103980001C94000810B504460A463430FEF776FB56 +:10399000886004F13800FEF773FBC2E9040194F873 +:1039A000213003F00203D3710023D36110BD000066 +:1039B00003284B8B04BF8A8A43EA024318467047A8 +:1039C0002DE9F04F0B7899B0044689462F2BD0F89B +:1039D00000B001D05C2B09D14A46137891460132E0 +:1039E0002F2BFAD05C2BF8D0002301E0DBF81C3041 +:1039F000A3600023E3619BF80030042B1ED1A36871 +:103A0000E3B1DBF82030214604A82362DBF8243040 +:103A10006362DBF82830A362FFF75CFC03460028F2 +:103A200054D1DBF8102002F13800FEF727FBC4E97F +:103A3000040392F8213003F00203E37199F8003097 +:103A40001F2B00F2358180230021204684F84B3063 +:103A500019B0BDE8F04FFEF72FBE49460B788946F6 +:103A600001312F2BFAD05C2BF8D01F2B8CBF0025F7 +:103A70000425012F2FD113882E2B31D1002322F8BA +:103A8000173004F140029F428CBF2E2120210133C8 +:103A90000B2B02F8011BF6D145F02005204684F8D7 +:103AA0004B50FFF7EDFC94F84B30002800F0E78016 +:103AB00004280BD1990603F0040240F1DC80002AAF +:103AC00000F0F6808023002084F84B3019B0BDE868 +:103AD000F08F0425CDE7022F02D153882E2BCAD0B8 +:103AE000911E87BB002322F81730002F00F01181B0 +:103AF00032F81300194601332028F9D009B92E28CD +:103B000001D145F00305901E30F817302E2B01D05F +:103B1000013FF9D14FF020334FF0000A6364D046E3 +:103B20002364C4F847300823481C32F81160009021 +:103B3000F6B1202E03D02E2E0DD1B84210D045F074 +:103B400003050099F0E731F81730202B01D02E2B18 +:103B5000C8D1013FC5E79A4505D20099B9423BD18A +:103B60000B2B30D101E00B2B27D145F003050B23A4 +:103B700094F84020E52A04BF052284F84020082B51 +:103B800004BF4FEA88085FFA88F808F00C030C2B92 +:103B900003D008F00303032B01D145F00205A80769 +:103BA0003FF57CAF18F0010F18BF45F0100518F075 +:103BB000040F18BF45F0080570E70099B94202D01C +:103BC00045F00305D4D84FEA88080B234FF0080AC4 +:103BD00000975FFA88F8B4E77F2E15D9304640F297 +:103BE0005231CDE9022345F00203019300F098FC25 +:103BF00010F0800F0646DDE9022316D000F07F06A4 +:103C000046498E5D019D46B331464548CDE90123C5 +:103C100005F004FBDDE90123F8B9A6F1410189B201 +:103C200019291ED848F0020810E0FF28EAD9591EC9 +:103C30008A4503D345F003059A4682E704EB0A015F +:103C4000000A0AF1010A019D81F8400004EB0A0113 +:103C50000AF1010A81F8406073E745F003055F2629 +:103C6000F4E7A6F1610189B219299EBF203E48F010 +:103C70000108B6B2EAE7002A08BF052026E75A077E +:103C80003FF524AFA379DB0645D59BF80000042857 +:103C900035D1A3682146E27923622369DBF810005D +:103CA00023F0FF0313436362E36CA362FFF76AFE32 +:103CB00023680027DA6819F8010B00283FF409AFE0 +:103CC00040F25231009200F04BFC054608B31F2829 +:103CD000009A7FF6FEAE2F283FF4BFAE5C283FF47B +:103CE000BCAE7F2805D801460E4805F097FA009A29 +:103CF00078B9FF2F0DD022F817500137DBE7216B81 +:103D00000BF14C03C1F308011944FFF751FEA06009 +:103D1000CEE70620DAE60520D8E600BF9C9300082F +:103D2000959300088C9300081FB5CDE9001003A8F7 +:103D300014460391FEF700FA002815DB0B4A52F8EF +:103D400020300BB100211970019B0BB100211970BB +:103D500042F820302CB1002201A96846FEF7C8FEC7 +:103D60000446204604B010BD0B24FAE73C36002080 +:103D70002DE9F04798B0904605460191002800F0E3 +:103D8000528102F03F0603A901A83246FEF7B0FEB9 +:103D9000002840F04681039B4FF48C60049303F0AD +:103DA0009DFA0746002800F04081039B00F5007251 +:103DB0000199D86004A81A61FFF702FE044620B9F1 +:103DC0009DF95B30002BB8BF062418F01C0F00F0E3 +:103DD000CD80002C4CD0042C40D104A8FFF724FC4B +:103DE000044600283AD146F00806039B1A78042AB4 +:103DF00040F08380186929462B60FFF7C3FD039BC1 +:103E00001E22002118690230FDF7A8FF039C002143 +:103E10001A2220692630FDF7A1FF236920221A719A +:103E2000246903F095FA0146012208342046FEF782 +:103E30002BF9039B04A81B6983F82120FFF764FA80 +:103E4000044658B9A96801B302462846FEF718FD92 +:103E5000AB68039A0446013B5361B4B1384603F0A2 +:103E60004DFA0CB100232B60204618B0BDE8F08756 +:103E70009DF8163013F0110F40F0848018F0040FF5 +:103E800040F0C98018F0080FAFD1039A3107139999 +:103E9000936C48BF46F04006E964AB641078042890 +:103EA00072D1069B9DF817102B62089B106923F0B6 +:103EB000FF030B4329466B62179BAB62FFF762FD62 +:103EC000DDF80CA00024002205F15008BAF80630F5 +:103ED00021464046C5F800A0AB80002385F830603D +:103EE00085F831406C64C5E90E234FF40072FDF78C +:103EF00035FFB20653D40024B0E703F029FA014697 +:103F0000009013980E30FEF7BFF813980099163002 +:103F1000FEF7BAF8039C13992078FFF749FD202398 +:103F200000228046CB7220461399FEF7D1F8139BEE +:103F3000002201211A775A779A77DA77039BD97092 +:103F4000B8F1000FA1D0414604A8D3F84890FEF77D +:103F500097FC0446002881D149460398FEF75CFA95 +:103F6000039B044608F1FF30586176E7002C7FF48C +:103F700075AF9DF81630DC064FD418F0020F84D0D0 +:103F8000D80782D5072469E7FFF712FD0023A86050 +:103F900001F11C00FEF772F86B61286190E7D5E92A +:103FA000046956EA0903A6D0BAF80AA0A9684FEA3C +:103FB0004A2AC5E90E69B24574EB09031BD30024F4 +:103FC0002964002C7FF44AAFC6F30803002B92D07B +:103FD000039C2046FEF770F808B3760A0123414699 +:103FE00046EAC95682196A64607802F0E5FC041E4C +:103FF00018BF012432E72846FEF7C6FAB6EB0A06D8 +:10400000014669F10009012803D9431CD3D10124D9 +:10401000D6E70224D4E7082420E704241EE702247C +:104020001CE704461EE709241EE711241CE70000D4 +:104030002DE9F04F994685B00023884603A9044630 +:10404000C9F800301646FEF791F8054680BB94F893 +:1040500031506DBB94F8303013F00103009300F041 +:10406000A68004F1500AD4E90432D4E90E011B1AE7 +:1040700062EB0102B34272F1000238BF1E46BEB1CC +:10408000D4E90E10C1F30803002B40F08280039B9B +:104090005A894B0A013A43EAC0531A401BD151EAEC +:1040A000000309D1A06801280DD8022584F83150F9 +:1040B000284605B0BDE8F08F216C20460192FEF73E +:1040C00063FA019AEFE7431C04D10123009D84F8B1 +:1040D0003130EDE72064DDF80CB0216C5846FDF777 +:1040E000EBFF0028E1D0B6F5007F02EB000731D3EB +:1040F000BBF80A1002EB5620730A88429BF80100B5 +:1041000088BF8B1A3A464146019302F055FC0028BD +:10411000DBD194F93020019B002A0BDA606CC01BC4 +:10412000984207D24FF40072514608EB4020FDF749 +:10413000EFFD019B5F02D9F80030F61BB8443B4409 +:10414000C9F80030D4E90E32DB1942F10002C4E9AB +:104150000E3294E7626CBA421AD094F93030002BD8 +:104160000DDA012351469BF8010002F049FC0028BA +:10417000ABD194F8303003F07F0384F830300398EB +:1041800001233A465146407802F016FC00289CD1A3 +:104190006764A16B4046C1F30801C1F50077514443 +:1041A000B74228BF37463A46FDF7B2FDC3E70725B9 +:1041B0007EE7000070B596B00E460022019002A97D +:1041C00001A8FEF795FC0446E0B94FF48C6003F0BB +:1041D00085F80546D8B1029B00F500720199D860B8 +:1041E00002A81A61FFF7ECFB044640B99DF9533071 +:1041F000002B0ADB1EB1314602A8FDF7EDFF284671 +:1042000003F07CF8204616B070BD0624F7E71124B1 +:10421000F8E7000070B5B8B00222019003A901A828 +:10422000FEF766FC044608BB039B4FF48C601093BA +:1042300003F054F80546002866D0039B00F5007291 +:104240000199D86010A81A61FFF7BAFB044650B96B +:104250009DF88B30980655D4190653D49DF84630F6 +:10426000DA0706D50724284603F048F8204638B078 +:1042700070BD039B04931878042814D104A918690D +:10428000FFF780FB069E9DF84630DB0610D410A891 +:10429000FEF776FF04460028E5D156BB0398FEF7EB +:1042A000DBFB0446DFE71F99FFF782FB0646EAE7E0 +:1042B000039BDA69B242D5D024930021269624A824 +:1042C0001B78042B01BFDDE90823CDE928239DF8E5 +:1042D00017308DF89730FEF7EFF904460028C2D169 +:1042E00024A8FFF741F804460028BBD00428BAD11F +:1042F000CDE70246314604A8FEF7C2FA044600287C +:10430000B1D1CBE70624AEE71124AFE7F0B5BDB0DD +:10431000CDE900106846FDF70FFF022203A901A8AE +:10432000FEF7E6FB0446002841D1039B4FF48C6066 +:10433000149302F0D3FF0546002800F0EE80039BA3 +:1043400000F5007214AE0199D8601A613046FFF78B +:1043500037FB044640BB9DF89B3013F0A00F40F0A4 +:10436000D880039B009F1A78042A68D11B6904AC8B +:1043700003F1400C1868083353F8041C22466345C7 +:1043800003C21446F6D15022314628A8FDF7C0FCDE +:10439000394628A8FFF714FB044600284CD12A9A76 +:1043A000169B9A4206D00824284602F0A7FF204612 +:1043B0003DB0F0BD349A209B9A42F4D128A8FFF773 +:1043C00033F904460028EFD1039B04AF1B6993F82F +:1043D00001E093F823C09C8C3A46083303CAB242EA +:1043E00043F8080C43F8041C1746F5D1039B28A892 +:1043F0001B6983F801E0039B1A6982F823C01A69DC +:1044000082F82440240A82F825401A691379D906D3 +:104410005CBF43F020031371FEF776FF04460028CB +:10442000C2D13046FEF7ACFE04460028BCD103984A +:10443000FEF712FB0446B7E70428B5D1BEE7239A7E +:1044400004AB02F1200C1068083252F8041C1C4620 +:10445000624503C42346F6D15022314628A8FDF711 +:1044600057FC394628A8FFF7ABFA044600284CD180 +:104470002A9A169B9A4296D1349A209B9A4292D1BC +:1044800028A8FFF7D1F8044600288DD137990DF1FF +:104490001D030DF12D0001F10D0253F8044B834271 +:1044A00042F8044BF9D11888012710809B7893704B +:1044B0009DF81B30039CDA0658BF43F02003CB72F3 +:1044C000E770CB7ADB06ACD5169A2A9B9A42A8D025 +:1044D0002078FFF76DFA01462046FDF7EDFD014615 +:1044E000C8B12046FDF798FF044600287FF45CAF72 +:1044F000039890F86D302E2B93D12A9A00F16C011D +:10450000FDF7E6FD039BDF708BE704287FF44CAFDB +:10451000B6E7062448E7022446E7112447E70000EF +:104520007F2810B501D880B210BDB0F5803F13D2FE +:1045300040F2523399420FD10849002231F8024B20 +:1045400093B2844203D103F18000C0B2ECE70132A0 +:10455000802AF3D11346F6E70020E5E7DC96000851 +:104560007F280DD940F25233994208D1FF2806D84E +:1045700000F10040034B803833F8100070470020F2 +:10458000704700BFDC960008B0F5803FF0B522D23E +:104590001F4A83B21F49B0F5805F28BF0A46141D29 +:1045A00034F8042C2146AAB1934213D334F8025CA8 +:1045B0002E0AEFB252FA85F5A84222DA082E09D85F +:1045C000DFE806F0050A10121416181A1C00801AEB +:1045D00034F810301846F0BD981A00F001001B1A8C +:1045E0009BB2F7E7103BFBE7203BF9E7303BF7E7EF +:1045F0001A3BF5E70833F3E7503BF1E7A3F5E35344 +:10460000EEE70434002ECBD101EB4702C7E700BF31 +:104610002C9400082096000808B5074B074A196833 +:1046200001F03D01996053680BB190689847BDE86F +:10463000084003F0A3B800BF000002404436002049 +:1046400008B5084B1968890901F03D018A019A6093 +:10465000054AD3680BB110699847BDE8084003F0DC +:104660008DB800BF000002404436002008B5084B5A +:104670001968090C01F03D010A049A60054A536962 +:104680000BB190699847BDE8084003F077B800BFC8 +:10469000000002404436002008B5084B1968890D17 +:1046A00001F03D018A059A60054AD3690BB1106A91 +:1046B0009847BDE8084003F061B800BF0000024021 +:1046C0004436002008B5074B074A596801F03D0100 +:1046D000D960536A0BB1906A9847BDE8084003F06F +:1046E0004DB800BF000002404436002008B5084B1A +:1046F0005968890901F03D018A01DA60054AD36AE7 +:104700000BB1106B9847BDE8084003F037B800BF05 +:10471000000002404436002008B5084B5968090CD7 +:1047200001F03D010A04DA60054A536B0BB1906B4E +:104730009847BDE8084003F021B800BF00000240E0 +:104740004436002008B5084B5968890D01F03D0139 +:104750008A05DA60054AD36B0BB1106C9847BDE847 +:10476000084003F00BB800BF0000024044360020B0 +:1047700008B5074B074A196801F03D019960536C71 +:104780000BB1906C9847BDE8084002F0F7BF00BF3E +:10479000000402404436002008B5084B1968890916 +:1047A00001F03D018A019A60054AD36C0BB1106D8E +:1047B0009847BDE8084002F0E1BF00BF0004024096 +:1047C0004436002008B5084B1968090C01F03D017A +:1047D0000A049A60054A536D0BB1906D9847BDE885 +:1047E000084002F0CBBF00BF000402404436002066 +:1047F00008B5084B1968890D01F03D018A059A60DA +:10480000054AD36D0BB1106E9847BDE8084002F021 +:10481000B5BF00BF000402404436002008B5074B76 +:10482000074A596801F03D01D960536E0BB1906E93 +:104830009847BDE8084002F0A1BF00BF0004024055 +:104840004436002008B5084B5968890901F03D013C +:104850008A01DA60054AD36E0BB1106F9847BDE844 +:10486000084002F08BBF00BF000402404436002025 +:1048700008B5084B5968090C01F03D010A04DA60DB +:10488000054A536F0BB1906F9847BDE8084002F09E +:1048900075BF00BF000402404436002008B5084B35 +:1048A0005968890D01F03D018A05DA60054AD36F28 +:1048B00013B1D2F880009847BDE8084002F05EBF0F +:1048C000000402404436002000230C4910B51A466B +:1048D0000B4C0B6054F82300026001EB43000433DF +:1048E0004260402BF6D1074A4FF0FF339360D3600C +:1048F000C2F80834C2F80C3410BD00BF44360020A2 +:10490000DC970008000002400F28F8B510D91028E5 +:1049100010D0112811D0122808D10F240720DFF859 +:10492000C8E00126DEF80050A04208D9002653E076 +:104930000446F4E70F240020F1E70724FBE706FA1A +:1049400000F73D424AD1264C4FEA001C3D4304EBA0 +:1049500000160EEBC000CEF80050C0E90123FBB2F8 +:1049600073B12048D0F8D83043F00103C0F8D830F4 +:10497000D0F8003143F00103C0F80031D0F8003125 +:1049800017F47F4F0ED01748D0F8D83043F0020309 +:10499000C0F8D830D0F8003143F00203C0F800313D +:1049A000D0F8003154F80C00036823F01F030360B3 +:1049B000056815F00105FBD104EB0C033D2493F8C9 +:1049C0000CC05F6804FA0CF43C602124056044616B +:1049D00012B1987B00F0CAFC3046F8BD0130A3E765 +:1049E000DC970008004402584436002010B53024FB +:1049F00084F31188FFF788FF002383F3118810BD2B +:104A000010B50446807B00F0C7FC01231549627B8A +:104A100003FA02F20B6823EA0203DAB20B6072B9FE +:104A2000114AD2F8D81021F00101C2F8D810D2F8FA +:104A3000001121F00101C2F80011D2F8002113F495 +:104A40007F4F0ED1084BD3F8D82022F00202C3F8D2 +:104A5000D820D3F8002122F00202C3F80021D3F8B5 +:104A6000003110BD443600200044025808B5302300 +:104A700083F31188FFF7C4FF002383F3118808BD77 +:104A8000836CC26A8B42506810B506D95A1E4C001E +:104A900002EB4103B3FBF4F3184410BD01F0010332 +:104AA0008A0748BF43F002034A0748BF43F00803A0 +:104AB0000A0748BF43F00403CA0648BF43F0100387 +:104AC0008A06426B48BF43F0200313434363704799 +:104AD00010B5074C204600F0CBFF064B0022C4E97E +:104AE0001023054BA364054BE363054BE36410BD42 +:104AF000C83600200024024800B4C4041C3700203B +:104B00001C390020C36A0BB9104BC3620379012B17 +:104B100011D10F4B98420ED10E4BD3F8DC2042F44A +:104B20000072C3F8DC20D3F8042142F40072C3F809 +:104B30000421D3F80431436C00221A65DA621A604A +:104B40005A605A624FF0FF329A637047DC9800084F +:104B5000C8360020004402580379012B1BD0436C57 +:104B600000221A65DA621A605A605A624FF0FF3208 +:104B70009A63094B98420ED1084BD3F8DC2022F4FB +:104B80000072C3F8DC20D3F8042122F40072C3F8C9 +:104B90000421D3F804317047C8360020004402587D +:104BA00010B5446C0649FFF76BFF6060236842F262 +:104BB000107043F003032360BDE8104001F05EBDB8 +:104BC000801A06000129F8B5466C0B4F09D17568AB +:104BD0000A493D40FFF754FF054345F48055756091 +:104BE000F8BD746806493C40FFF74AFF044344F4AB +:104BF00080547460F4E700BF00ECFFFF80F0FA021D +:104C000040787D01436C00225A601A6070470000B2 +:104C1000426C0129536823F4404304D0022905D093 +:104C200001B95360704743F48043FAE743F400430B +:104C3000F7E70000436C41F480519A60D9605A6BE9 +:104C40001206FCD580229A637047000010B541F42B +:104C50008851446CA260E160616B11F04502FBD0A9 +:104C6000A26311F0040203D0FFF718FF012010BD6A +:104C7000616910461960FAE710B541F48851446C37 +:104C8000A260E160616B11F04502FBD0A26311F0FC +:104C9000050203D0FFF702FF012010BD6169104635 +:104CA0001960FAE773B5134604460E46302282F3C4 +:104CB0001188426CD26B32B14FF0FF31403001931A +:104CC00001F0E8FC019B606C00220265C263C262D5 +:104CD000456B15F4807504D185F31188012002B06D +:104CE00070BD4FF0FF31816382F31188012E06D928 +:104CF0000C21204602B0BDE87040FFF7BDBF104652 +:104D0000EDE7000073B5446C0E4600250192616B1F +:104D1000A1632565E562FFF7C1FE012E07D9019B5E +:104D20002A460C2102B0BDE87040FFF7A5BF02B0D3 +:104D300070BD000010B541F49851446CA260E16070 +:104D4000616B11F04502FBD0A26311F03F0203D06A +:104D5000FFF7A4FE012010BD216A10461960E16929 +:104D60005960A16999606169D960F4E72DE9F74359 +:104D700004460191006D01A91746984602F026FCF1 +:104D8000064600284AD0626C2046DDF8049055683B +:104D9000C5F3090501356B00A56CB5FBF3F54FF4C0 +:104DA0007A73B5FBF3F55D43556200F027FE50BB07 +:104DB000636C4FF0FF3201254146C3F858902046FE +:104DC0001D659A634FF49572DA6342F207029F629F +:104DD000DA62E36C0A9AFFF74FFFA0B9E26C104B5E +:104DE00011680B407BB929462046FFF75BFF05465B +:104DF00048B92E463A460199206D02F01FFC304614 +:104E000003B0BDE8F0833A460199206D02F016FC2C +:104E1000E26C01212046FFF775FFF0E70126EEE77F +:104E200008E0FFFD2DE9F7431F46436C01924FF464 +:104E30007A725D6804468846C5F3090501356E003F +:104E4000856CB5FBF6F5B5FBF2F555435D6200F0F8 +:104E5000D5FD20B10125284603B0BDE8F0837E02D0 +:104E600001A9206D324602F0B1FB05460028F1D0C1 +:104E7000636C019AD4F84C909A6501221A654FF040 +:104E8000FF329A634FF49572DA639E62236BDB06FE +:104E90004B4658BF4FEA4828012F42461BD91221E2 +:104EA0002046FFF7E9FEC0B9D9F80020104B1340A7 +:104EB0009BB9636C42F2930239462046DA62E26C97 +:104EC000FFF7F0FE804640B932460199206D454615 +:104ED00002F0B4FBBFE71121E2E732460199206DF1 +:104EE00002F0ACFBE26C39462046FFF70BFFB2E75D +:104EF00008E0FFFD2DE9F3411F46436C01924FF49A +:104F00007A725D6804468846C5F3090501356E006E +:104F1000856CB5FBF6F5B5FBF2F555435D6200F027 +:104F20006DFD20B10125284602B0BDE8F0817E026A +:104F300001A9206D324602F08FFB05460028F1D012 +:104F4000636C019A9A6501221A654FF0FF329A63E9 +:104F50004FF48D72DA639E62236BE66CDB06334698 +:104F600058BF4FEA4828012F424619D91921204637 +:104F7000FFF782FEB0B932680F4B134093B9636CF0 +:104F800042F2910239462046DA62E26CFFF78AFE6D +:104F9000064638B901993546206D02F099FBC2E703 +:104FA0001821E4E70199206D02F092FBE26C39468A +:104FB0002046FFF7A7FEB6E708E0FFFD12F0030F5B +:104FC0002DE9F04107460C4615461E4617D00E4403 +:104FD000B44202D10020BDE8F0810123FA6B2146E2 +:104FE0003846FFF71FFF0028F5D128464FF400721E +:104FF000F96B05F500750134FCF78AFEE8E7BDE8BA +:10500000F041FFF70FBF000012F0030F2DE9F04150 +:1050100007460C4615461E4617D00E44B44202D130 +:105020000020BDE8F08129464FF40072F86B05F5C9 +:105030000075FCF76DFE0123FA6B21463846FFF739 +:1050400059FF0028EDD10134E8E7BDE8F041FFF752 +:1050500051BF000000207047302310B583F3118842 +:105060000024436C40302146DC6301F021FB84F3D3 +:10507000118810BD026843681143016003B11847ED +:1050800070470000024A136843F0C0031360704782 +:1050900000480040024A136843F0C00313607047A1 +:1050A00000500040024A136843F0C0031360704789 +:1050B00000780040064BD3F8E8200243C3F8E8200C +:1050C000D3F810211043C3F81001D3F81031704702 +:1050D0000044025837B5274C274D204600F028FDE4 +:1050E00004F11400009400234FF40072234900F0EF +:1050F000C3F94FF40072224904F138000094214BA7 +:1051000000F03CFA204BC4E91735204C204600F053 +:105110000FFD04F11400009400234FF400721C49A9 +:1051200000F0AAF94FF400721A4904F13800009413 +:10513000194B00F023FA194BC4E91735184C2046D7 +:1051400000F0F6FC04F1140000234FF4007215493E +:10515000009400F091F9144B4FF40072134904F1DC +:105160003800009400F00AFA114BC4E9173503B077 +:1051700030BD00BF2039002000E1F505643A002071 +:105180006440002085500008004800408C39002011 +:10519000643C00206442002095500008005000400C +:1051A000F8390020643E0020A55000086444002027 +:1051B0000078004038B5264D0446037C002918BF0E +:1051C0000D46012B06D1234B984230D14FF480205D +:1051D000FFF770FF2A68236EE16D03EB5203A566AB +:1051E000B3FBF2F36A68100442BF23F0070003F038 +:1051F000070343EA4003CB60AB6843F040034B60D6 +:10520000EB6843F001038B6042F4967343F00103B3 +:105210000B604FF0FF330B62510505D512F01022E1 +:1052200011D0B2F1805F10D084F8643038BD0A4BE1 +:10523000984205D0094B9842CCD14FF08040C7E747 +:105240004FF48010C4E77F23EEE73F23ECE700BF75 +:10525000E4980008203900208C390020F83900201B +:105260002DE9F047C66D05463768F46921073462B9 +:105270001AD014F0080118BF4FF48071E20748BF3C +:1052800041F02001A3074FF0300348BF41F0400137 +:10529000600748BF41F0800183F31188281DFFF7A4 +:1052A000E9FE002383F31188E2050AD5302383F356 +:1052B00011884FF48061281DFFF7DCFE002383F383 +:1052C00011884FF030094FF0000A14F0200838D14F +:1052D0003B0616D54FF0300905F1380A200610D5E7 +:1052E00089F31188504600F07DF9002836DA08214C +:1052F000281DFFF7BFFE27F080033360002383F3F0 +:105300001188790614D5620612D5302383F31188EB +:10531000D5E913239A4208D12B6C33B127F040070B +:105320001021281DFFF7A6FE3760002383F31188A4 +:10533000E30618D5AA6E1369ABB15069BDE8F04712 +:10534000184789F31188736A284695F86410194044 +:1053500000F008FC8AF31188F469B6E7B06288F3BC +:105360001188F469BAE7BDE8F0870000090100F18F +:105370006043012203F56143C9B283F8001300F0D2 +:105380001F039A4043099B0003F1604303F5614307 +:10539000C3F880211A60704700F01F0301229A4071 +:1053A000430900F160409B0000F5614003F1604358 +:1053B00003F56143C3F88020C3F88021002380F8FF +:1053C00000337047F8B51546826804460B46AA427A +:1053D00000D28568A1692669761AB5420BD21846B3 +:1053E0002A46FCF795FCA3692B44A3612846A368D1 +:1053F0005B1BA360F8BD0CD9AF1B18463246FCF707 +:1054000087FC3A46E1683044FCF782FCE3683B44A1 +:10541000EBE718462A46FCF77BFCE368E5E700006B +:1054200083689342F7B50446154600D28568D4E9EF +:105430000460361AB5420BD22A46FCF769FC636950 +:105440002B4463612846A3685B1BA36003B0F0BDD7 +:105450000DD93246AF1B0191FCF75AFC01993A462F +:10546000E0683144FCF754FCE3683B44E9E72A4632 +:10547000FCF74EFCE368E4E710B50A440024C3617E +:10548000029B8460C16002610362C0E90000C0E960 +:10549000051110BD08B5D0E90532934201D18268EB +:1054A00082B98268013282605A1C426119700021FF +:1054B000D0E904329A4224BFC368436101F012F973 +:1054C000002008BD4FF0FF30FBE7000070B530232F +:1054D00004460E4683F31188A568A5B1A368A269A6 +:1054E000013BA360531CA36115782269934224BF3A +:1054F000E368A361E3690BB120469847002383F377 +:105500001188284607E03146204601F0DBF80028E4 +:10551000E2DA85F3118870BD2DE9F74F04460E4697 +:1055200017469846D0F81C904FF0300A8AF311883D +:105530004FF0000B154665B12A4631462046FFF76D +:1055400041FF034660B94146204601F0BBF8002800 +:10555000F1D0002383F31188781B03B0BDE8F08FEE +:10556000B9F1000F03D001902046C847019B8BF38F +:105570001188ED1A1E448AF31188DCE7C160C3610B +:10558000009B82600362C0E905111144C0E900007C +:1055900001617047F8B504460D461646302383F383 +:1055A0001188A768A7B1A368013BA36063695A1C6F +:1055B00062611D70D4E904329A4224BFE3686361DA +:1055C000E3690BB120469847002080F3118807E07B +:1055D0003146204601F076F80028E2DA87F3118898 +:1055E000F8BD0000D0E9052310B59A4201D18268C8 +:1055F0007AB982680021013282605A1C82611C786B +:1056000003699A4224BFC368836101F06BF82046A6 +:1056100010BD4FF0FF30FBE72DE9F74F04460E4673 +:1056200017469846D0F81C904FF0300A8AF311883C +:105630004FF0000B154665B12A4631462046FFF76C +:10564000EFFE034660B94146204601F03BF80028D2 +:10565000F1D0002383F31188781B03B0BDE8F08FED +:10566000B9F1000F03D001902046C847019B8BF38E +:105670001188ED1A1E448AF31188DCE70379052BA3 +:1056800005BF836A002001204B6004BF4FF4007304 +:105690000B60704770B55D1E866A04460D44B542C6 +:1056A00005D9436B43F080034363012070BD062599 +:1056B0000571FFF783FC05232371F7E770B55D1EC5 +:1056C000866A04460D44B54205D9436B43F0800316 +:1056D0004363012070BD07250571FFF795FC052385 +:1056E0002371F7E738B505790446052D05D1082360 +:1056F0000371FFF7AFFC257138BD0120FCE7000006 +:105700000323F0B5037185B00446FFF749FA002280 +:1057100020461146FFF78EFA4FF4D57203AB0821ED +:105720002046FFF7A9FA0246B8B901232363039B79 +:10573000C3F30323012B09D103AB37212046FFF725 +:105740009BFA18B9A44B039A1340ABB1204601252C +:10575000FFF758FA0223237137E103AB0022372108 +:105760002046FFF789FA28B99B4A039B1A40002A72 +:1057700000F0A78002232363236B03F00F03022BA7 +:1057800040F0A9806425954E42F2107000F076FF3B +:1057900003AB324601212046FFF758FA0028D5D145 +:1057A000039B002B80F293805A0003D5236B43F0B8 +:1057B00010032363002204F1080302212046FFF7AF +:1057C000B9FA02460028C1D104F13803032120466A +:1057D000FFF752FA0028B9D104F11805A26B09218C +:1057E00020462B46FFF7A6FA0028AFD102ABA26BEA +:1057F00007212046FFF740FA06460028A6D1236B72 +:1058000003F00F03022B40F08F807E227F21284679 +:1058100003F022FA012840F28780E76B42F2107011 +:1058200000F02CFF08234FF4007239462046009602 +:10583000FFF79CFA002889D1384603F05BFA236B06 +:10584000A06203F00F03022B72D103AB644A06215E +:105850002046FFF711FA002871D15F49039B1940D8 +:10586000B1FA81F149092046FFF7ACF902AB4FF4D8 +:10587000007210212046FFF7FFF9054600287FF44B +:1058800065AF554E029B33427FF460AF236B13F03C +:105890000E0F03F00F0273D0022A7FF457AFE36AB2 +:1058A0001978012900F09480022900F093800029E2 +:1058B00000F089804B4F2046FFF7AAF903AB3A4628 +:1058C00076E0114620462263FFF7B4F954E7013D24 +:1058D0007FF45AAF3AE7444D6426444A3E4F012BC9 +:1058E00018BF154603AB002237212046FFF7C4F945 +:1058F00000287FF42BAF039B3B427FF427AF03AB21 +:105900002A4629212046FFF7A1F900287FF41EAF7F +:10591000039B002BFFF648AF013E3FF417AF42F266 +:10592000107000F0ABFEDDE7284603F0B7F986E71C +:105930007E227F212846E66B03F08EF908B900210C +:1059400091E7002340223146204600930623FFF7CB +:105950000DFA0028F3D1B3895BBA9B07EFD5244B2E +:1059600040223146204600930623FFF7FFF9002826 +:10597000E5D1317C01F00F010F3918BF012172E729 +:10598000E36A1978F9B101297FF4E0AE2046FFF708 +:105990003FF903ABA26B37212046FFF76DF90028D2 +:1059A0007FF4D4AE039B33427FF4D0AE03AB02222C +:1059B00006212046FFF760F900287FF4C7AE039B5D +:1059C00033427FF4C3AE05232371284605B0F0BDF2 +:1059D000084F70E7084F6EE708E0FFFD0080FFC04A +:1059E0000001B9030000B7030080FF5000001080E1 +:1059F000F1FFFF800001B7030002B70337B504468B +:105A00000C4D01ABA26B0D212046FFF735F978B99B +:105A1000019B2B420BD1C3F34323042B08D0053B3E +:105A2000022B04D84FF47A7000F028FEE9E7012039 +:105A300003B030BD08E0FFFD70B53023054683F3A9 +:105A4000118803790024022B03D184F311882046A6 +:105A500070BD0423037184F311880226FFF7CEFF83 +:105A600004462846FFF7CEF82E71F0E7FFF730B86E +:105A7000044B03600123037100234363C0E90A332D +:105A8000704700BFFC98000810B53023044683F32C +:105A90001188C162FFF736F802230020237180F3DA +:105AA000118810BD10B53023044683F31188FFF729 +:105AB00053F800230122E362227183F3118810BDA1 +:105AC000026843681143016003B118477047000042 +:105AD0001430FFF721BD00004FF0FF331430FFF703 +:105AE0001BBD00003830FFF797BD00004FF0FF33BB +:105AF0003830FFF791BD00001430FFF7E7BC00001D +:105B00004FF0FF311430FFF7E1BC00003830FFF7F1 +:105B100041BD00004FF0FF323830FFF73BBD0000C1 +:105B2000012914BF6FF0130000207047FFF7D2BAAD +:105B3000044B036000234360C0E902330123037474 +:105B4000704700BF2099000810B53023044683F346 +:105B50001188FFF72FFB02230020237480F31188A4 +:105B600010BD000038B5C36904460D461BB90421B9 +:105B70000844FFF7A5FF294604F11400FFF78AFC4B +:105B8000002806DA201D4FF40061BDE83840FFF719 +:105B900097BF38BD026843681143016003B11847DD +:105BA0007047000013B5406B00F58054D4F8A4385A +:105BB0001A681178042914D1017C022911D11979AC +:105BC000012312898B4013420BD101A94C3002F002 +:105BD00071FFD4F8A4480246019B2179206800F0A7 +:105BE000DFF902B010BD0000143002F0F3BE000077 +:105BF0004FF0FF33143002F0EDBE00004C3002F0E5 +:105C0000C5BF00004FF0FF334C3002F0BFBF0000B3 +:105C1000143002F0C1BE00004FF0FF31143002F02A +:105C2000BBBE00004C3002F091BF00004FF0FF32CD +:105C30004C3002F08BBF00000020704710B500F51B +:105C40008054D4F8A4381A681178042917D1017C3B +:105C5000022914D15979012352898B4013420ED164 +:105C6000143002F053FE024648B1D4F8A4484FF471 +:105C7000407361792068BDE8104000F07FB910BD25 +:105C8000406BFFF7DBBF0000704700007FB5124B91 +:105C900001250426044603600023057400F18402F4 +:105CA00043602946C0E902330C4B02901430019343 +:105CB0004FF44073009602F005FE094B04F694423F +:105CC000294604F14C000294CDE900634FF440737F +:105CD00002F0CCFE04B070BD48990008815C000859 +:105CE000A55B00080A68302383F311880B790B3316 +:105CF00042F823004B79133342F823008B7913B118 +:105D00000B3342F8230000F58053C3F8A418022394 +:105D10000374002080F311887047000038B5037FBA +:105D2000044613B190F85430ABB90125201D02216F +:105D3000FFF730FF04F114006FF00101257700F048 +:105D4000DDFC04F14C0084F854506FF00101BDE813 +:105D5000384000F0D3BC38BD10B5012104460430F2 +:105D6000FFF718FF0023237784F8543010BD00009C +:105D700038B504460025143002F0BCFD04F14C0097 +:105D8000257702F08BFE201D84F854500121FFF787 +:105D900001FF2046BDE83840FFF750BF90F8803043 +:105DA00003F06003202B06D190F881200023212AE4 +:105DB00003D81F2A06D800207047222AFBD1C0E949 +:105DC0001D3303E0034A426707228267C36701204D +:105DD000704700BF4422002037B500F58055D5F844 +:105DE000A4381A68117804291AD1017C022917D124 +:105DF0001979012312898B40134211D100F14C040F +:105E0000204602F00BFF58B101A9204602F052FED5 +:105E1000D5F8A4480246019B2179206800F0C0F81B +:105E200003B030BD01F10B03F0B550F8236085B02D +:105E300004460D46FEB1302383F3118804EB850739 +:105E4000301D0821FFF7A6FEFB6806F14C005B69D8 +:105E50001B681BB1019002F03BFE019803A902F000 +:105E600029FE024648B1039B2946204600F098F8D7 +:105E7000002383F3118805B0F0BDFB685A691268EE +:105E8000002AF5D01B8A013B1340F1D104F18002B6 +:105E9000EAE70000133138B550F82140ECB1302367 +:105EA00083F3118804F58053D3F8A428136852793A +:105EB00003EB8203DB689B695D6845B104216018D0 +:105EC000FFF768FE294604F1140002F029FD204680 +:105ED000FFF7B4FE002383F3118838BD704700003C +:105EE00001F04ABD01234022002110B5044600F80C +:105EF000303BFBF733FF0023C4E9013310BD000042 +:105F000010B53023044683F3118824224160002118 +:105F10000C30FBF723FF204601F050FD0223002048 +:105F2000237080F3118810BD70B500EB8103054626 +:105F300050690E461446DA6018B110220021FBF7B2 +:105F40000DFFA06918B110220021FBF707FF3146B1 +:105F50002846BDE8704001F037BE0000836820226B +:105F6000002103F0011310B5044683601030FBF7E5 +:105F7000F5FE2046BDE8104001F0B2BEF0B40125A8 +:105F800000EB810447898D40E4683D43A469458165 +:105F900023600023A2606360F0BC01F0CFBE00006C +:105FA000F0B4012500EB810407898D40E4683D438E +:105FB0006469058123600023A2606360F0BC01F086 +:105FC00045BF000070B5022300250446242203705B +:105FD0002946C0F888500C3040F8045CFBF7BEFE40 +:105FE000204684F8705001F083FD63681B6823B17C +:105FF00029462046BDE87040184770BD0378052B40 +:1060000010B504460AD080F88C300523037043682D +:106010001B680BB1042198470023A36010BD00004A +:106020000178052906D190F88C20436802701B681E +:1060300003B118477047000070B590F870300446FF +:1060400013B1002380F8703004F18002204601F083 +:106050006BFE63689B68B3B994F8803013F06005F9 +:1060600035D00021204602F05DF90021204602F0E3 +:106070004DF963681B6813B1062120469847062333 +:1060800084F8703070BD204698470028E4D0B4F8FA +:106090008630A26F9A4288BFA36794F98030A56FBB +:1060A000002B4FF0300380F20381002D00F0F280CE +:1060B000092284F8702083F3118800212046D4E956 +:1060C0001D23FFF76DFF002383F31188DAE794F8AF +:1060D000812003F07F0343EA022340F2023293421D +:1060E00000F0C58021D8B3F5807F48D00DD8012BB2 +:1060F0003FD0022B00F09380002BB2D104F1880234 +:1061000062670222A267E367C1E7B3F5817F00F00F +:106110009B80B3F5407FA4D194F88230012BA0D1AD +:10612000B4F8883043F0020332E0B3F5006F4DD08D +:1061300017D8B3F5A06F31D0A3F5C063012B90D869 +:106140006368204694F882205E6894F88310B4F85F +:106150008430B047002884D0436863670368A3672E +:106160001AE0B3F5106F36D040F6024293427FF446 +:1061700078AF5C4B63670223A3670023C3E794F8FF +:106180008230012B7FF46DAFB4F8883023F0020326 +:10619000A4F88830C4E91D55E56778E7B4F8803085 +:1061A000B3F5A06F0ED194F88230204684F88A307F +:1061B00001F0FCFC63681B6813B10121204698477D +:1061C000032323700023C4E91D339CE704F18B03F0 +:1061D00063670123C3E72378042B10D1302383F3B3 +:1061E00011882046FFF7BAFE85F311880321636802 +:1061F00084F88B5021701B680BB12046984794F8A7 +:106200008230002BDED084F88B3004232370636847 +:106210001B68002BD6D0022120469847D2E794F87D +:10622000843020461D0603F00F010AD501F06EFDF3 +:10623000012804D002287FF414AF2B4B9AE72B4B94 +:1062400098E701F055FDF3E794F88230002B7FF4D6 +:1062500008AF94F8843013F00F01B3D01A0620462B +:1062600002D502F077F8ADE702F068F8AAE794F8F3 +:106270008230002B7FF4F5AE94F8843013F00F01D8 +:10628000A0D01B06204602D502F04CF89AE702F097 +:106290003DF897E7142284F8702083F311882B4689 +:1062A0002A4629462046FFF769FE85F31188E9E66C +:1062B0005DB1152284F8702083F3118800212046F7 +:1062C000D4E91D23FFF75AFEFDE60B2284F8702067 +:1062D00083F311882B462A4629462046FFF760FEA5 +:1062E000E3E700BF789900087099000874990008E6 +:1062F00038B590F870300446002B3ED0063BDAB239 +:106300000F2A34D80F2B32D8DFE803F037313108A9 +:10631000223231313131313131313737856FB0F897 +:1063200086309D4214D2C3681B8AB5FBF3F203FB8F +:1063300012556DB9302383F311882B462A4629461E +:10634000FFF72EFE85F311880A2384F870300EE0E3 +:10635000142384F87030302383F3118800232046FF +:106360001A461946FFF70AFE002383F3118838BD49 +:10637000C36F03B198470023E7E70021204601F0EF +:10638000D1FF0021204601F0C1FF63681B6813B1F3 +:106390000621204698470623D7E7000010B590F85D +:1063A00070300446142B29D017D8062B05D001D8FD +:1063B0001BB110BD093B022BFBD80021204601F088 +:1063C000B1FF0021204601F0A1FF63681B6813B1F3 +:1063D000062120469847062319E0152BE9D10B2307 +:1063E00080F87030302383F3118800231A46194651 +:1063F000FFF7D6FD002383F31188DAE7C3689B69B2 +:106400005B68002BD5D1C36F03B19847002384F894 +:106410007030CEE70023826880F8243083691B68DF +:1064200099689142FBD25A680360426010605860DC +:10643000704700000023826880F8243083691B685D +:1064400099689142FBD85A680360426010605860B6 +:106450007047000008B50846302383F3118891F88F +:106460002430032B05D0042B0DD02BB983F31188D6 +:1064700008BD8B6A00221A604FF0FF338362FFF77A +:10648000C9FF0023F2E7D1E9003213605A60F3E755 +:10649000034610B51B68984203D09C688A689442F2 +:1064A000F8D25A680B604A601160596010BD000054 +:1064B000FFF7B0BF064BD96881F82400186802685E +:1064C00053601A600122D86080F82420F9F79ABF3F +:1064D000684600200C4B30B5DD684B1C87B0044685 +:1064E0000FD02B46094A684600F09CF92046FFF77A +:1064F000E1FF009B13B1684600F09EF9A86A07B05F +:1065000030BDFFF7D7FFF9E7684600205564000863 +:10651000044B1A68DB6890689B68984294BF00201F +:106520000120704768460020094B10B51C68D868E8 +:10653000226853601A600122DC6084F82420FFF78F +:1065400079FF01462046BDE81040F9F75BBF00BF68 +:1065500068460020044B1A68DB6892689B689A4280 +:1065600001D9FFF7E1BF70476846002038B5012325 +:10657000084C00252370656002F0EAFB02F010FC75 +:106580000549064802F0E6FC0223237085F31188D2 +:1065900038BD00BF104900208099000868460020DF +:1065A00000F080B9034A516853685B1A9842FBD8DF +:1065B000704700BF001000E08B604B630023CA618E +:1065C00000F128020B6302230A618B840123886196 +:1065D00081F8263001F11003C26A4A611360C36278 +:1065E00001F12C030846CB6270470000D0E901316D +:1065F000026841F8183CA1F19C033839CB6003696B +:1066000041F8243C436941F8203C034B41F8043CE9 +:10661000C3680248FFF7D0BF1D0400086846002089 +:1066200008B5FFF7E3FFBDE80840FFF741BF0000F2 +:1066300038B50E4BDC6804F12C05A062E06AA84274 +:106640000FD194F826303BB994F825309B0702BF50 +:10665000D4E9043213605A600F20BDE83840FFF7D8 +:1066600029BF0368E362FFF723FFE7E768460020DE +:10667000302383F31188FFF7DBBF000008B5014624 +:10668000302383F311880820FFF724FF002383F3CE +:10669000118808BD054BDB6821B1036098620320B7 +:1066A000FFF718BF4FF0FF30704700BF684600206B +:1066B00003682BB10022026018469962FFF7F8BE0A +:1066C00070470000064BDB6839B1426818605A60B9 +:1066D000136043600420FFF7FDBE4FF0FF307047AA +:1066E000684600200368984206D01A68026050602D +:1066F00018469962FFF7DCBE7047000038B50446C3 +:106700000D462068844200D138BD036823605C6078 +:106710008562FFF7CDFEF4E7036810B59C68A242DE +:106720000CD85C688A600B604C6021605960996885 +:106730008A1A9A604FF0FF33836010BD121B1B68EA +:10674000ECE700000A2938BF0A2170B504460D465F +:106750000A26601902F0F6FA02F0DEFA041BA542DE +:1067600003D8751C04462E46F3E70A2E04D90120EF +:10677000BDE8704002F0B6BC70BD0000F8B5144B27 +:106780000D460A2A4FF00A07D96103F11001826011 +:1067900038BF0A22416019691446016048601861D7 +:1067A000A81802F0BFFA02F0B7FA431B0646A3424C +:1067B00006D37C1C28192746354602F0C3FAF2E7B7 +:1067C0000A2F04D90120BDE8F84002F08BBCF8BDC7 +:1067D00068460020F8B506460D4602F09DFA0F4ABD +:1067E000134653F8107F9F4206D12A460146304691 +:1067F000BDE8F840FFF7C2BFD169BB68441A2C1945 +:1068000028BF2C46A34202D92946FFF79BFF224608 +:1068100031460348BDE8F840FFF77EBF68460020D8 +:1068200078460020C0E90323002310B45DF8044B30 +:106830004361FFF7CFBF000010B5194C23699842A0 +:106840000DD08168D0E9003213605A609A680A441A +:106850009A60002303604FF0FF33A36110BD02680C +:10686000234643F8102F53600022026022699A42A7 +:1068700003D1BDE8104002F05FBA936881680B4411 +:10688000936002F049FA2269E1699268441AA242CF +:10689000E4D91144BDE81040091AFFF753BF00BF07 +:1068A000684600202DE9F047DFF8BC8008F11007AA +:1068B0002C4ED8F8105002F02FFAD8F81C40AA68D5 +:1068C000031B9A423ED814444FF00009D5E9003228 +:1068D000C8F81C4013605A60C5F80090D8F8103012 +:1068E000B34201D102F028FA89F31188D5E90331C6 +:1068F00028469847302383F311886B69002BD8D042 +:1069000002F00AFA6A69A0EB040982464A450DD2F0 +:10691000022002F0E7FB0022D8F81030B34208D181 +:1069200051462846BDE8F047FFF728BF121A224417 +:10693000F2E712EB09092946384638BF4A46FFF705 +:10694000EBFEB5E7D8F81030B34208D01444C8F8CD +:106950001C00211AA960BDE8F047FFF7F3BEBDE8AF +:10696000F08700BF784600206846002038B502F066 +:10697000D3F9054AD2E90845031B181945F100016E +:10698000C2E9080138BD00BF6846002010B560B9F3 +:10699000074804790368053C9B6818BF01249847A1 +:1069A00008B144F00404204610BD0124FBE700BFF9 +:1069B000C8360020FFF7EABF2DE9F04788461746A2 +:1069C0009A460446B0B90D4E3579052D05D00324FD +:1069D0000DE0013D15F0FF050ED0326853463946F3 +:1069E0003046D2F814904246C8470028F1D12046DC +:1069F000BDE8F0870424FAE70124F8E7C836002050 +:106A00002DE9F047884617469A460446B0B90D4E20 +:106A10003579052D05D003240DE0013D15F0FF0566 +:106A20000ED03268534639463046D2F81890424666 +:106A3000C8470028F1D12046BDE8F0870424FAE7D2 +:106A40000124F8E7C836002037B50C46154670B962 +:106A500051B101290BD10748694603681B6A984761 +:106A600010B9019B04462B60204603B030BD0424BE +:106A7000FAE700BFC836002000207047FEE700009C +:106A8000704700004FF0FF30704700004B684360D4 +:106A90008B688360CB68C3600B6943614B69036299 +:106AA0008B6943620B6803607047000008B53C4B7C +:106AB00040F2FF713B48D3F888200A43C3F888208E +:106AC000D3F8882022F4FF6222F00702C3F888205E +:106AD000D3F88820D3F8E0200A43C3F8E020D3F8A5 +:106AE00008210A43C3F808212F4AD3F80831114678 +:106AF000FFF7CCFF00F5806002F11C01FFF7C6FF35 +:106B000000F5806002F13801FFF7C0FF00F58060FA +:106B100002F15401FFF7BAFF00F5806002F1700145 +:106B2000FFF7B4FF00F5806002F18C01FFF7AEFFC4 +:106B300000F5806002F1A801FFF7A8FF00F5806072 +:106B400002F1C401FFF7A2FF00F5806002F1E0014D +:106B5000FFF79CFF00F5806002F1FC01FFF796FF54 +:106B600002F58C7100F58060FFF790FF01F08AFC60 +:106B70000E4BD3F8902242F00102C3F89022D3F8D2 +:106B8000942242F00102C3F894220522C3F898200F +:106B90004FF06052C3F89C20054AC3F8A02008BDFE +:106BA00000440258000002589499000800ED00E0EB +:106BB0001F00080308B501F071FEFFF7D7FC104B6A +:106BC000D3F8DC2042F04002C3F8DC20D3F80421E3 +:106BD00022F04002C3F80421D3F80431094B1A68AB +:106BE00042F008021A601A6842F004021A6000F0CB +:106BF00077FD00F037FBBDE8084000F0B5B800BFF6 +:106C000000440258001802480120704700207047D5 +:106C10007047000002290CD0032904D0012907483D +:106C200018BF00207047032A05D8054800EBC200B2 +:106C30007047044870470020704700BF949B0008CD +:106C400054220020489B000870B59AB005460846BB +:106C5000144601A900F0C2F801A8FBF777F8431C1D +:106C60000022C6B25B001046C5E90034237003233E +:106C7000023404F8013C01ABD1B202348E4201D897 +:106C80001AB070BD13F8011B013204F8010C04F8AE +:106C9000021CF1E708B5302383F311880348FFF79E +:106CA0009BF8002383F3118808BD00BF184900201A +:106CB00090F8803003F01F02012A07D190F881205C +:106CC0000B2A03D10023C0E91D3315E003F0600354 +:106CD000202B08D1B0F884302BB990F88120212ADC +:106CE00003D81F2A04D8FFF759B8222AEBD0FAE7B5 +:106CF000034A426707228267C3670120704700BFCB +:106D00004B22002007B5052917D8DFE801F0191636 +:106D100003191920302383F31188104A01210190AF +:106D2000FFF702F9019802210D4AFFF7FDF80D481F +:106D3000FFF71EF8002383F3118803B05DF804FB0E +:106D4000302383F311880748FEF7E8FFF2E730238A +:106D500083F311880348FEF7FFFFEBE7E89A00088A +:106D60000C9B00081849002038B50C4D0C4C2A46E5 +:106D70000C4904F10800FFF767FF05F1CA0204F1AE +:106D800010000949FFF760FF05F5CA7204F1180009 +:106D90000649BDE83840FFF757BF00BFF06100204B +:106DA00054220020C89A0008D29A0008DD9A0008F0 +:106DB00070B5044608460D46FAF7C8FFC6B220462D +:106DC000013403780BB9184670BD32462946FAF7EC +:106DD000A9FF0028F3D10120F6E700002DE9F84FC4 +:106DE00005460C46FAF7B2FF2D49C6B22846FFF712 +:106DF000DFFF08B10436F6B22A492846FFF7D8FF6C +:106E000008B11036F6B2632E0DD8DFF89490DFF893 +:106E100094A0DFF89C80DFF89CB0234F2E7846B911 +:106E20002670BDE8F88F29462046BDE8F84F02F0ED +:106E300003BA252E30D1072249462846FAF772FFB9 +:106E400070B93B6807350B3444F80B3C7B6844F859 +:106E5000073C3B8924F8033CBB7A04F8013CDDE79E +:106E6000082251462846FAF75DFFA8B9A21C0F4B2D +:106E700019780232090911F8081002F8041C13F8F5 +:106E8000011B01F00F015B4511F8081002F8031C0B +:106E9000EED118340835C1E7013504F8016BBDE7C0 +:106EA000B49B0008DD9A0008BC9B000800E8F11FB5 +:106EB000C89B00080CE8F11FBFF34F8F044B1A6901 +:106EC0005107FCD1D3F810215207F8D1704700BF09 +:106ED0000020005208B50D4B1B78ABB9FFF7ECFF53 +:106EE0000B4BDA68D10704D50A4A5A6002F188329E +:106EF0005A60D3F80C21D20706D5064AC3F80421FC +:106F000002F18832C3F8042108BD00BF4E6400209E +:106F1000002000522301674508B5114B1B78F3B9D7 +:106F2000104B1A69510703D5DA6842F04002DA6063 +:106F3000D3F81021520705D5D3F80C2142F04002B6 +:106F4000C3F80C21FFF7B8FF064BDA6842F00102E4 +:106F5000DA60D3F80C2142F00102C3F80C2108BD1D +:106F60004E640020002000520F289ABF00F5806078 +:106F700040040020704700004FF4003070470000CC +:106F8000102070470F2808B50BD8FFF7EDFF00F56C +:106F900000330268013204D104308342F9D1012068 +:106FA00008BD0020FCE700000F2838B505463FD893 +:106FB000FFF782FF1F4CFFF78DFF4FF0FF330728CD +:106FC0006361C4F814311DD82361FFF775FF030214 +:106FD00043F02403E360E36843F08003E360236944 +:106FE0005A07FCD42846FFF767FFFFF7BDFF4FF4B1 +:106FF000003100F0AFFA2846FFF78EFFBDE83840B9 +:10700000FFF7C0BFC4F81031FFF756FFA0F1080327 +:107010001B0243F02403C4F80C31D4F80C3143F0C4 +:107020008003C4F80C31D4F810315B07FBD4D9E7E6 +:10703000002038BD002000522DE9F84F05460C46CF +:10704000104645EA0203DE0602D00020BDE8F88FB4 +:1070500020F01F00DFF8BCB0DFF8BCA0FFF73AFF5C +:1070600004EB0008444503D10120FFF755FFEDE78D +:1070700020222946204602F0A7F810B920352034F6 +:10708000F0E72B4605F120021F68791CDDD104339F +:107090009A42F9D105F178431B481C4EB3F5801F85 +:1070A0001B4B38BF184603F1F80332BFD946D1460F +:1070B0001E46FFF701FF0760A5EB040C336804F1DF +:1070C0001C0143F002033360231FD9F8007017F04E +:1070D0000507FAD153F8042F8B424CF80320F4D162 +:1070E000BFF34F8FFFF7E8FE4FF0FF33202221461A +:1070F00003602846336823F00203336002F064F82B +:107100000028BBD03846B0E7142100520C200052B2 +:1071100014200052102000521021005210B5084CCB +:10712000237828B11BB9FFF7D5FE0123237010BDCA +:10713000002BFCD02070BDE81040FFF7EDBE00BF73 +:107140004E6400202DE9F04F0D4685B0814658B1C0 +:1071500011F00D0614BF2022082211F0080301933C +:1071600004D0431E034269D0002435E0002E37D0FE +:1071700009F11F0121F01F094FF00108314F05F0FF +:107180000403DFF8CCA005EA080BBBF1000F32D0F6 +:107190007869C0072FD408F101080C37B8F1060F41 +:1071A000F3D19EB9284D4946A819019201F01AFE63 +:1071B0000446002839D12036019AA02EF3D1494641 +:1071C00001F010FE044600282FD1019A49461F48BD +:1071D00001F008FE044660BB204605B0BDE8F08F14 +:1071E0000029C9D101462846029201F0FBFD044660 +:1071F000D8B9029AC0E713B178694107CBD5AC077B +:1072000002D578698007C6D5019911B1786901075F +:10721000C1D549460AEB4810CDE9022301F0E2FD51 +:107220000446DDE902230028B5D04A460021204665 +:1072300001E04A460021FAF791FDCDE70246002E13 +:1072400096D199E7DC9B00089064002050640020F0 +:10725000706400200021FFF775BF00000121FFF7D7 +:1072600071BF000070B5144D0124144E40F2FF327E +:1072700000210120FAF772FD06EB441001342A695F +:1072800055F80C1F01F09AFD062CF5D137254FF467 +:10729000C0542046FFF7E2FF014628B122460848C5 +:1072A000BDE8704001F08ABDC4EBC404013D4FEA63 +:1072B000D404EED170BD00BFDC9B000870640020D8 +:1072C000506400200421FFF73DBF00004843FFF752 +:1072D000C1BF000008B101F0F7BD7047B0F5805F95 +:1072E00010B5044607D8FFF7EDFF28B92046BDE8E2 +:1072F0001040FFF7AFBF002010BD0000FFF7EABF4E +:1073000070B5AAB140EA010313F01F030FD1094C75 +:107310000144A5686D0706D52568A84203D36668B1 +:107320003544A94204D903330C34122BF1D1002285 +:10733000104670BDDC9B000808B501F0DBFE034A77 +:10734000D2E90032C01842EB010108BD30650020CF +:10735000434BD3E900232DE9F34113437CD0FFF7DE +:10736000EBFF404A00230027F9F766F806460D4672 +:107370003D4A0023F9F760F80023144630462946B9 +:10738000394AF9F759F84FF461613C23ADF80170BF +:10739000B4FBF1F5B4FBF3F601FB154103FB164614 +:1073A0004624B1FBF3F1314BF6B28DF80040984220 +:1073B0003CD84FF0640C4FF4C87EA30704F26C7203 +:1073C00025D1B2FBFCF30CFB132313BBB2FBFEF382 +:1073D0000EFB1322B2FA82F35B0903F26D18621CF2 +:1073E0008045D2B217D90FB18DF800400022204C51 +:1073F0004FF00C0C17460CFB0343D4B2013213F8C8 +:1074000004C084450CD8A0EB0C000127F5E700234D +:10741000E3E70123E1E7A0EB080014460127CCE7EE +:107420000FB18DF80140431C8DF802309DF801002A +:10743000431C9DF800005038400640EA43509DF838 +:10744000023040EA034040EA560040EAC52040EAE4 +:10745000411002B0BDE8F0814FF40410F9E700BF1D +:107460003065002040420F008051010090230B0046 +:10747000249C00080244074BD2B210B5904200D1C0 +:1074800010BD441C00B253F8200041F8040BE0B2D8 +:10749000F4E700BF504000580E4B30B51C6F240479 +:1074A00005D41C6F1C671C6F44F400441C670A4C15 +:1074B00002442368D2B243F480732360074B9042A6 +:1074C00000D130BD441C51F8045B00B243F8205099 +:1074D000E0B2F4E700440258004802585040005817 +:1074E00007B5012201A90020FFF7C4FF019803B0EE +:1074F0005DF804FB13B50446FFF7F2FFA04205D088 +:10750000012201A900200194FFF7C6FF02B010BDBF +:1075100010B56424013C4FF47A70FFF7AFF814F013 +:10752000FF04F7D10A4B102214249A614FF48062B1 +:107530009A61A3F580534FF400529A61013C4FF4D5 +:107540007A70FFF79BF814F0FF04F7D110BD00BF6D +:10755000001802580144BFF34F8F064B884204D3F2 +:10756000BFF34F8FBFF36F8F7047C3F85C022030BB +:10757000F4E700BF00ED00E00144BFF34F8F064B7E +:10758000884204D3BFF34F8FBFF36F8F7047C3F8A8 +:1075900070022030F4E700BF00ED00E070B5054652 +:1075A00016460C4601201021FFF790FE2860467316 +:1075B0003CB1204636B1FFF785FE2B68186000B15C +:1075C0009C6070BDFFF74AFEF7E70000F8B50F4674 +:1075D0001546044648B905F11F010126386821F017 +:1075E0001F01FFF7B7FF3046F8BD427B29463868D8 +:1075F000FFF786FE06460028EDD13B686360A3686E +:10760000AB4210D213B12068FFF764FE637B2846BB +:107610002BB1FFF757FE206020B9A060E3E7FFF72A +:107620001DFEF8E7A560206805F11F01012621F085 +:107630001F013860FFF78EFF2673D4E710B50446AC +:1076400040B10068884205D1606808B1FAF760FB74 +:107650000023237310BD0000F8B50F4614460546FD +:1076600048B904F11F010126386821F01F01FFF716 +:1076700083FF3046F8BD427B21463868FFF740FE65 +:1076800006460028EDD1AB68A34210D213B128689A +:10769000FFF720FE6B7B20462BB1FFF713FE28601F +:1076A00020B9A860E5E7FFF7D9FDF8E7AC603968D5 +:1076B00019B122462868FAF72BFB286804F11F014C +:1076C000012621F01F013860FFF756FF2E73D0E727 +:1076D00020B103688B4204BF00230373704700008E +:1076E000034B1A681AB9034AD2F8D0241A607047BB +:1076F000386500200040025808B5FFF7F1FF024B43 +:107700001868C0F3806008BD38650020EFF3098376 +:10771000054968334A6B22F001024A6383F3098802 +:10772000002383F31188704700EF00E0302080F3DE +:10773000118862B60D4B0E4AD96821F4E061090444 +:10774000090C0A430B49DA60D3F8FC2042F080723E +:10775000C3F8FC20084AC2F8B01F116841F00101CB +:1077600011602022DA7783F82200704700ED00E0F4 +:107770000003FA0555CEACC5001000E0302310B56B +:1077800083F311880E4B5B6813F4006314D0F1EEA1 +:10779000103AEFF309844FF08073683CE361094BC2 +:1077A000DB6B236684F30988FEF7B2FE10B1064B4B +:1077B000A36110BD054BFBE783F31188F9E700BF18 +:1077C00000ED00E000EF00E02F04000832040008A4 +:1077D00070B5BFF34F8FBFF36F8F1A4A0021C2F805 +:1077E0005012BFF34F8FBFF36F8F536943F40033D1 +:1077F0005361BFF34F8FBFF36F8FC2F88410BFF395 +:107800004F8FD2F8803043F6E074C3F3C900C3F35E +:107810004E335B0103EA0406014646EA81750139ED +:10782000C2F86052F9D2203B13F1200FF2D1BFF31E +:107830004F8F536943F480335361BFF34F8FBFF3CE +:107840006F8F70BD00ED00E0FEE70000214B224885 +:10785000224A70B5904237D3214BC11EDA1C121A4E +:1078600022F003028B4238BF00220021FAF776FA99 +:107870001C4A0023C2F88430BFF34F8FD2F8803007 +:1078800043F6E074C3F3C900C3F34E335B0103EA6C +:107890000406014646EA81750139C2F86C52F9D2F4 +:1078A000203B13F1200FF2D1BFF34F8FBFF36F8F47 +:1078B000BFF34F8FBFF36F8F0023C2F85032BFF377 +:1078C0004F8FBFF36F8F70BD53F8041B40F8041B3C +:1078D000C0E700BF2C9D00083467002034670020FB +:1078E0003467002000ED00E0074BD3F8D81021EA00 +:1078F0000001C3F8D810D3F8002122EA0002C3F82F +:107900000021D3F8003170470044025870B5D0E927 +:10791000244300224FF0FF359E6804EB42135101CF +:10792000D3F80009002805DAD3F8000940F08040B8 +:10793000C3F80009D3F8000B002805DAD3F8000BD0 +:1079400040F08040C3F8000B013263189642C3F840 +:107950000859C3F8085BE0D24FF00113C4F81C3893 +:1079600070BD0000890141F02001016103699B069F +:10797000FCD41220FEF716BE10B50A4C2046FEF7C6 +:10798000B1FA094BC4F89030084BC4F89430084C55 +:107990002046FEF7A7FA074BC4F89030064BC4F810 +:1079A000943010BD3C65002000000840609C000839 +:1079B000D8650020000004406C9C000870B5037876 +:1079C0000546012B5CD1434BD0F89040984258D1EA +:1079D000414B0E216520D3F8D82042F00062C3F855 +:1079E000D820D3F8002142F00062C3F80021D3F878 +:1079F0000021D3F8802042F00062C3F88020D3F841 +:107A0000802022F00062C3F88020D3F88030FDF798 +:107A1000ADFC324BE360324BC4F800380023D5F89C +:107A20009060C4F8003EC02323604FF40413A363A6 +:107A30003369002BFCDA01230C203361FEF7B2FD21 +:107A40003369DB07FCD41220FEF7ACFD3369002B51 +:107A5000FCDA00262846A660FFF758FF6B68C4F8DA +:107A60001068DB68C4F81468C4F81C6883BB1D4B3D +:107A7000A3614FF0FF336361A36843F00103A36088 +:107A800070BD194B9842C9D1134B4FF08060D3F8A9 +:107A9000D82042F00072C3F8D820D3F8002142F079 +:107AA0000072C3F80021D3F80021D3F8802042F0FF +:107AB0000072C3F88020D3F8802022F00072C3F84F +:107AC0008020D3F88030FFF70FFF0E214D209EE776 +:107AD000064BCDE73C6500200044025840140040AE +:107AE00003002002003C30C0D8650020083C30C0B4 +:107AF000F8B5D0F89040054600214FF000662046CA +:107B0000FFF730FFD5F8941000234FF001128F6873 +:107B10004FF0FF30C4F83438C4F81C2804EB43128B +:107B200001339F42C2F80069C2F8006BC2F808092D +:107B3000C2F8080BF2D20B68D5F89020C5F898303F +:107B4000636210231361166916F01006FBD1122030 +:107B5000FEF728FDD4F8003823F4FE63C4F800389B +:107B6000A36943F4402343F01003A3610923C4F83D +:107B70001038C4F814380B4BEB604FF0C043C4F816 +:107B8000103B094BC4F8003BC4F81069C4F8003935 +:107B9000D5F8983003F1100243F48013C5F898200B +:107BA000A362F8BD3C9C000840800010D0F89020F3 +:107BB00090F88A10D2F8003823F4FE6343EA0113E8 +:107BC000C2F80038704700002DE9F84300EB81034C +:107BD000D0F890500C468046DA680FFA81F94801D7 +:107BE000166806F00306731E022B05EB41134FF0D7 +:107BF000000194BFB604384EC3F8101B4FF00101CA +:107C000004F1100398BF06F1805601FA03F391695D +:107C100098BF06F5004600293AD0578A04F158016A +:107C2000374349016F50D5F81C180B430021C5F8A4 +:107C30001C382B180127C3F81019A7405369611E7F +:107C40009BB3138A928B9B08012A88BF5343D8F8B1 +:107C50009820981842EA034301F140022146C8F8EF +:107C60009800284605EB82025360FFF77BFE08EB85 +:107C70008900C3681B8A43EA845348341E43640165 +:107C80002E51D5F81C381F43C5F81C78BDE8F88381 +:107C900005EB4917D7F8001B21F40041C7F8001B7A +:107CA000D5F81C1821EA0303C0E704F13F030B4A8F +:107CB0002846214605EB83035A60FFF753FE05EB88 +:107CC0004910D0F8003923F40043C0F80039D5F842 +:107CD0001C3823EA0707D7E70080001000040002E1 +:107CE000D0F894201268C0F89820FFF70FBE00006B +:107CF0005831D0F8903049015B5813F4004004D05B +:107D000013F4001F0CBF0220012070474831D0F847 +:107D1000903049015B5813F4004004D013F4001F65 +:107D20000CBF02200120704700EB8101CB68196A6B +:107D30000B6813604B6853607047000000EB8103D1 +:107D400030B5DD68AA691368D36019B9402B84BFC8 +:107D5000402313606B8A1468D0F890201C4402EB17 +:107D60004110013C09B2B4FBF3F46343033323F045 +:107D7000030343EAC44343F0C043C0F8103B2B68FD +:107D800003F00303012B0ED1D2F8083802EB4110A7 +:107D900013F4807FD0F8003B14BF43F0805343F0CE +:107DA0000053C0F8003B02EB4112D2F8003B43F015 +:107DB0000443C2F8003B30BD2DE9F041D0F890609B +:107DC00005460C4606EB4113D3F8087B3A07C3F887 +:107DD000087B08D5D6F814381B0704D500EB8103BF +:107DE000DB685B689847FA071FD5D6F81438DB07BD +:107DF0001BD505EB8403D968CCB98B69488A5A68CE +:107E0000B2FBF0F600FB16228AB91868DA689042D5 +:107E10000DD2121AC3E90024302383F311882146BE +:107E20002846FFF78BFF84F31188BDE8F08101231A +:107E300003FA04F26B8923EA02036B81CB68002BFF +:107E4000F3D021462846BDE8F041184700EB8103F6 +:107E50004A0170B5DD68D0F890306C692668E6603C +:107E600056BB1A444FF40020C2F810092A6802F0E9 +:107E70000302012A0AB20ED1D3F8080803EB421418 +:107E800010F4807FD4F8000914BF40F0805040F017 +:107E90000050C4F8000903EB4212D2F8000940F088 +:107EA0000440C2F800090122D3F8340802FA01F1B3 +:107EB0000143C3F8341870BD19B9402E84BF402067 +:107EC000206020681A442E8A8419013CB4FBF6F421 +:107ED00040EAC44040F00050C6E700002DE9F843F6 +:107EE000D0F8906005460C464F0106EB4113D3F8DD +:107EF000088918F0010FC3F808891CD0D6F810388B +:107F0000DB0718D500EB8103D3F80CC0DCF8143084 +:107F1000D3F800E0DA68964530D2A2EB0E024FF0BB +:107F200000091A60C3F80490302383F31188FFF727 +:107F30008DFF89F3118818F0800F1DD0D6F83438E2 +:107F40000126A640334217D005EB84030134D5F84F +:107F50009050D3F80CC0E4B22F44DCF8142005EBA9 +:107F60000434D2F800E05168714514D3D5F83438A0 +:107F700023EA0606C5F83468BDE8F883012303FA4E +:107F800001F2038923EA02030381DCF80830002BA5 +:107F9000D1D09847CFE7AEEB0103BCF81000834285 +:107FA00028BF0346D7F8180980B2B3EB800FE3D897 +:107FB0009068A0F1040959F8048FC4F80080A0EB80 +:107FC00009089844B8F1040FF5D818440B449060A0 +:107FD0005360C8E72DE9F84FD0F8905004466E6919 +:107FE000AB691E4016F480586E6103D0BDE8F84FAF +:107FF000FDF7E8BF002E12DAD5F8003E9B0705D04A +:10800000D5F8003E23F00303C5F8003ED5F8043848 +:10801000204623F00103C5F80438FEF701F83705C0 +:1080200005D52046FFF772FC2046FDF7E7FFB004B8 +:108030000CD5D5F8083813F0060FEB6823F470530D +:108040000CBF43F4105343F4A053EB6031071BD52E +:108050006368DB681BB9AB6923F00803AB61237865 +:10806000052B0CD1D5F8003E9A0705D0D5F8003E77 +:1080700023F00303C5F8003E2046FDF7D1FF6368F7 +:10808000DB680BB120469847F30200F1BA80B702D3 +:1080900026D5D4F8909000274FF0010A09EB47123B +:1080A000D2F8003B03F44023B3F5802F11D1D2F86E +:1080B000003B002B0DDA62890AFA07F322EA030378 +:1080C000638104EB8703DB68DB6813B13946204624 +:1080D00098470137D4F89430FFB29B689F42DDD9AE +:1080E000F00619D5D4F89000026AC2F30A1702F01C +:1080F0000F0302F4F012B2F5802F00F0CA80B2F53F +:10810000402F09D104EB8303002200F58050DB6887 +:108110001B6A974240F0B0803003D5F8185835D527 +:10812000E90303D500212046FFF746FEAA0303D545 +:1081300001212046FFF740FE6B0303D502212046B4 +:10814000FFF73AFE2F0303D503212046FFF734FE45 +:10815000E80203D504212046FFF72EFEA90203D52D +:1081600005212046FFF728FE6A0203D50621204696 +:10817000FFF722FE2B0203D507212046FFF71CFE46 +:10818000EF0103D508212046FFF716FE700340F1EA +:10819000A780E90703D500212046FFF79FFEAA0725 +:1081A00003D501212046FFF799FE6B0703D5022175 +:1081B0002046FFF793FE2F0703D503212046FFF744 +:1081C0008DFEEE0603D504212046FFF787FEA806A4 +:1081D00003D505212046FFF781FE690603D5062158 +:1081E0002046FFF77BFE2A0603D507212046FFF72E +:1081F00075FEEB0574D520460821BDE8F84FFFF762 +:108200006DBED4F890904FF0000B4FF0010AD4F8F7 +:1082100094305FFA8BF79B689F423FF638AF09EBCB +:108220004713D3F8002902F44022B2F5802F20D161 +:10823000D3F80029002A1CDAD3F8002942F0904232 +:10824000C3F80029D3F80029002AFBDB3946D4F80B +:108250009000FFF787FB22890AFA07F322EA03035B +:10826000238104EB8703DB689B6813B13946204602 +:1082700098470BF1010BCAE7910701D1D0F80080B4 +:10828000072A02F101029CBF03F8018B4FEA18286C +:108290003FE704EB830300F58050DA68D2F818C09A +:1082A000DCF80820DCE9001CA1EB0C0C00218F425B +:1082B00008D1DB689B699A683A449A605A683A44E4 +:1082C0005A6029E711F0030F01D1D0F800808C45E6 +:1082D00001F1010184BF02F8018B4FEA1828E6E79B +:1082E000BDE8F88F08B50348FFF774FEBDE8084005 +:1082F000FFF744BA3C65002008B50348FFF76AFE63 +:10830000BDE80840FFF73ABAD8650020D0F89030B1 +:1083100003EB4111D1F8003B43F40013C1F8003BDB +:1083200070470000D0F8903003EB4111D1F80039CC +:1083300043F40013C1F8003970470000D0F89030C2 +:1083400003EB4111D1F8003B23F40013C1F8003BCB +:1083500070470000D0F8903003EB4111D1F800399C +:1083600023F40013C1F8003970470000064BD3F81E +:10837000DC200243C3F8DC20D3F804211043C3F807 +:108380000401D3F8043170470044025808B53C4B4F +:108390004FF0FF31D3F8802062F00042C3F8802014 +:1083A000D3F8802002F00042C3F88020D3F8802068 +:1083B000D3F88420C3F88410D3F884200022C3F8B3 +:1083C0008420D3F88400D86F40F0FF4040F4FF00D1 +:1083D00040F4DF4040F07F00D867D86F20F0FF40C6 +:1083E00020F4FF0020F4DF4020F07F00D867D86F32 +:1083F000D3F888006FEA40506FEA5050C3F8880005 +:10840000D3F88800C0F30A00C3F88800D3F88800C6 +:10841000D3F89000C3F89010D3F89000C3F89020E0 +:10842000D3F89000D3F89400C3F89410D3F89400D4 +:10843000C3F89420D3F89400D3F89800C3F89810A8 +:10844000D3F89800C3F89820D3F89800D3F88C009C +:10845000C3F88C10D3F88C00C3F88C20D3F88C00B0 +:10846000D3F89C00C3F89C10D3F89C10C3F89C2050 +:10847000D3F89C30FCF728FABDE8084000F0D6B9E4 +:108480000044025808B50122534BC3F80821534B4E +:10849000D3F8F42042F00202C3F8F420D3F81C21F0 +:1084A00042F00202C3F81C210222D3F81C314C4BCB +:1084B000DA605A689104FCD54A4A1A6001229A602F +:1084C000494ADA6000221A614FF440429A61444BF3 +:1084D0009A699204FCD51A6842F480721A603F4B84 +:1084E0001A6F12F4407F04D04FF480321A670022D2 +:1084F0001A671A6842F001021A60384B1A6850076E +:10850000FCD500221A611A6912F03802FBD1012150 +:1085100019604FF0804159605A67344ADA62344A30 +:108520001A611A6842F480321A602C4B1A6891035F +:10853000FCD51A6842F480521A601A689204FCD57D +:108540002C4A2D499A6200225A63196301F57C0175 +:10855000DA6301F2E71199635A64284A1A64284AD7 +:10856000DA621A6842F0A8521A601C4B1A6802F0CC +:108570002852B2F1285FF9D148229A614FF48862FB +:10858000DA6140221A621F4ADA641F4A1A651F4ADA +:108590005A651F4A9A6532231E4A1360136803F016 +:1085A0000F03022BFAD10D4A136943F00303136141 +:1085B000136903F03803182BFAD14FF00050FFF77E +:1085C000D5FE4FF08040FFF7D1FE4FF00040BDE8F0 +:1085D0000840FFF7CBBE00BF0080005100440258A6 +:1085E0000048025800C000F0020000010000FF0136 +:1085F000008890082220400063020901470E050808 +:10860000DD0BBF0120000020000001100910E00078 +:1086100000010110002000524FF0B04208B5D2F81E +:10862000883003F00103C2F8883023B1044A13688C +:108630000BB150689847BDE80840FFF79FB800BFEE +:10864000B46600204FF0B04208B5D2F8883003F08D +:108650000203C2F8883023B1044A93680BB1D06892 +:108660009847BDE80840FFF789B800BFB46600200E +:108670004FF0B04208B5D2F8883003F00403C2F8D6 +:10868000883023B1044A13690BB150699847BDE89B +:108690000840FFF773B800BFB46600204FF0B04247 +:1086A00008B5D2F8883003F00803C2F8883023B147 +:1086B000044A93690BB1D0699847BDE80840FFF7B9 +:1086C0005DB800BFB46600204FF0B04208B5D2F8E4 +:1086D000883003F01003C2F8883023B1044A136ACB +:1086E0000BB1506A9847BDE80840FFF747B800BF94 +:1086F000B46600204FF0B04310B5D3F8884004F4BE +:108700007872C3F88820A30604D5124A936A0BB185 +:10871000D06A9847600604D50E4A136B0BB1506BB4 +:108720009847210604D50B4A936B0BB1D06B984741 +:10873000E20504D5074A136C0BB1506C9847A305AA +:1087400004D5044A936C0BB1D06C9847BDE8104037 +:10875000FFF714B8B46600204FF0B04310B5D3F85B +:10876000884004F47C42C3F88820620504D5164A88 +:10877000136D0BB1506D9847230504D5124A936DC4 +:108780000BB1D06D9847E00404D50F4A136E0BB1BE +:10879000506E9847A10404D50B4A936E0BB1D06E6E +:1087A0009847620404D5084A136F0BB1506F98477D +:1087B000230404D5044A936F0BB1D06F9847BDE8EA +:1087C0001040FEF7DBBF00BFB466002008B50348C9 +:1087D000FCF742FCBDE80840FEF7D0BFC8360020D9 +:1087E00008B50348FCF73CFDBDE80840FEF7C6BFEE +:1087F0002039002008B50348FCF732FDBDE80840E9 +:10880000FEF7BCBF8C39002008B50348FCF728FDF3 +:10881000BDE80840FEF7B2BFF839002008B500F007 +:10882000BDFCBDE80840FEF7A9BF0000062108B561 +:108830000846FCF79BFD06210720FCF797FD062163 +:108840000820FCF793FD06210920FCF78FFD062187 +:108850000A20FCF78BFD06211720FCF787FD062177 +:108860002820FCF783FD09217A20FCF77FFD0921F0 +:108870007C20FCF77BFD07213220FCF777FD0C21E3 +:108880002720FCF773FD0C213520FCF76FFD0C2130 +:108890005220BDE80840FCF769BD000008B5FFF7AD +:1088A00075FD00F043FCFDF741F9FDF7DFF8FDF73A +:1088B00017FBFDF7E9F9FEF7ABF9BDE8084000F05A +:1088C00029BA000030B50433039C0172002104FB77 +:1088D0000325C160C0E90653049B0363059BC0E9FF +:1088E0000000C0E90422C0E90842C0E90A1143635C +:1088F00030BD00000022416AC260C0E90411C0E935 +:108900000A226FF00101FDF7F9BE0000D0E9043240 +:10891000934201D1C2680AB9181D70470020704700 +:10892000036919600021C2680132C260C269134440 +:1089300082699342036124BF436A0361FDF7D2BE9B +:1089400038B504460D46E3683BB162690020131D4B +:108950001268A3621344E36207E0237A33B929461D +:108960002046FDF7AFFE0028EDDA38BD6FF00100BC +:10897000FBE70000C368C269013BC360436913445D +:1089800082699342436124BF436A43610023836247 +:10899000036B03B11847704770B53023044683F367 +:1089A0001188866A3EB9FFF7CBFF054618B186F3FA +:1089B0001188284670BDA36AE26A13F8015B9342EE +:1089C000A36202D32046FFF7D5FF002383F311886B +:1089D000EFE700002DE9F84F04460E46174698468B +:1089E0004FF0300989F311880025AA46D4F828B041 +:1089F000BBF1000F09D141462046FFF7A1FF20B18E +:108A00008BF311882846BDE8F88FD4E90A12A7EB4A +:108A1000050B521A934528BF9346BBF1400F1BD953 +:108A2000334601F1400251F8040B914243F8040B24 +:108A3000F9D1A36A403640354033A362D4E90A2312 +:108A40009A4202D32046FFF795FF8AF31188BD4270 +:108A5000D8D289F31188C9E730465A46F9F758F950 +:108A6000A36A5E445D445B44A362E7E710B5029CE1 +:108A70000433017203FB0421C460C0E90613002320 +:108A8000C0E90A33039B0363049BC0E90000C0E90B +:108A90000422C0E90842436310BD0000026A6FF07F +:108AA0000101C260426AC0E904220022C0E90A2230 +:108AB000FDF724BED0E904239A4201D1C26822B94D +:108AC000184650F8043B0B60704700231846FAE73D +:108AD000C3680021C2690133C360436913448269DA +:108AE0009342436124BF436A4361FDF7FBBD00002D +:108AF00038B504460D46E3683BB1236900201A1DD2 +:108B0000A262E2691344E36207E0237A33B929469B +:108B10002046FDF7D7FD0028EDDA38BD6FF00100E3 +:108B2000FBE7000003691960C268013AC260C269CC +:108B3000134482699342036124BF436A03610023A3 +:108B40008362036B03B118477047000070B5302390 +:108B50000D460446114683F31188866A2EB9FFF745 +:108B6000C7FF10B186F3118870BDA36A1D70A36A98 +:108B7000E26A01339342A36204D3E16920460439D7 +:108B8000FFF7D0FF002080F31188EDE72DE9F84FC3 +:108B900004460D46904699464FF0300A8AF31188F4 +:108BA0000026B346A76A4FB949462046FFF7A0FF03 +:108BB00020B187F311883046BDE8F88FD4E90A0761 +:108BC0003A1AA8EB0607974228BF1746402F1BD931 +:108BD00005F1400355F8042B9D4240F8042BF9D1D0 +:108BE000A36A40364033A362D4E90A239A4204D3ED +:108BF000E16920460439FFF795FF8BF3118846455C +:108C0000D9D28AF31188CDE729463A46F9F780F898 +:108C1000A36A3D443E443B44A362E5E7D0E9042314 +:108C20009A4217D1C3689BB1836A8BB1043B9B1AEC +:108C30000ED01360C368013BC360C3691A448369E3 +:108C40009A42026124BF436A0361002383620123C5 +:108C5000184670470023FBE701F01F03F0B502F050 +:108C60001F0456095A1C0123B6EB511F50F8265019 +:108C700003FA02F34FEA511703F1FF333DBF50F8F7 +:108C80002720C4F12000134003EA05003BBF03FA8C +:108C900000F225FA04F0E0401043F0BD70B57E22EA +:108CA0007F210546FFF7D8FF18B1012819D0002011 +:108CB00070BD3E2249212846FFF7CEFF2F220446F1 +:108CC00031212846FFF7C8FF0646013450220236FC +:108CD00053212846B440FFF7BFFF093804FA00F0DB +:108CE000E6E7302245212846FFF7B6FF0130800233 +:108CF000DEE7000090F8D63090F8D7201B0403EB95 +:108D0000026390F8D42090F8D500134403EB0020C0 +:108D10007047000000F018BA014B586A704700BF56 +:108D2000000C0040034B002258631A610222DA60F3 +:108D3000704700BF000C0040014B0022DA60704712 +:108D4000000C0040014B5863704700BF000C00400E +:108D5000024B034A1A60034A5A6070478C6600202F +:108D60003867002000000220074B494210B55C68BC +:108D7000201A08401968821A8A4203D3A24201D8F5 +:108D80005A6010BD0020FCE78C66002008B5302337 +:108D900083F31188FFF7E8FF002383F3118808BDF0 +:108DA0000448054B03600023C0E901330C3000F098 +:108DB00017B900BF946600208D8D0008CB1D083ABE +:108DC00023F00703591A521A10B4D2080024C0E93C +:108DD000004384600C301C605A605DF8044B00F066 +:108DE000FFB800002DE9F74F364FCD1D884600280B +:108DF00018BF0746082A4FEAD50538BF082207F1F1 +:108E00000C003C1D9146019000F02CF9019809F1ED +:108E10000701C9F1000E2246246864B900F02CF95C +:108E20003B68CBB308224946E8009847044698B30C +:108E300040E9027830E004EB010CD4F804A00CEA1D +:108E40000E0C0AF10106ACF1080304EBC6069E42C3 +:108E5000E1D9A6EB0C0CB5EBEC0F4FEAEC0BDAD832 +:108E60009C421DD204F10802AB45A3EB02024FEA7B +:108E7000E202626009D9691CED4303EBC1025D4463 +:108E80005560256843F8315022601C46C3F80480C1 +:108E900044F8087B00F0F0F8204603B0BDE8F08FFE +:108EA000AA45216802D111602346EEE7013504EBA3 +:108EB000C50344F8351003F10801761AF6105E6018 +:108EC0001360F1E79466002073B50446A0F108052D +:108ED00050F8080C54F8043C061D0C300733019080 +:108EE000DB0844F8043C00F0BDF8334601989E428C +:108EF0001A6801D0AB4228D20AB1954225D244F873 +:108F0000082C54F8042C1D60013254F8081C05EBA1 +:108F1000C206B14206D14E68324444F8042C0A68B5 +:108F200044F8082C5E68711C03EBC1018D4207D127 +:108F300054F8042C013232445A6054F8082C1A6058 +:108F400002B0BDE8704000F097B81346CFE70000CC +:108F5000FEE7000070B51E4B0025044686B0586041 +:108F60000E4605638163FEF7E1FB04F12803A5606B +:108F70006563C4E90A3304F11003C4E904334FF014 +:108F8000FF33C4E90044C4E90635FFF7C5FE2B46AC +:108F9000024604F13C012046C4E9082380230D4A1F +:108FA0006567FDF709FB7368E0600B4A0362012304 +:108FB000009280F824306846F26801923269CDE967 +:108FC0000223064BCDE90435FDF72AFB06B070BD40 +:108FD00010490020809C0008789C0008518F0008F0 +:108FE0000023C0E9000083600361704770B51C4B2B +:108FF00005468468DE685CB3B44213D1036901336B +:10900000036170BDA36094F8243083B1062B15D1A1 +:10901000A06A2146D4E9003213605A60FDF738FA9D +:10902000A36A9C68B368A2689A42EBD306E0D4E9CD +:109030000032204613605A60FDF73AFA284631465E +:10904000FDF726FAB5620620BDE87040FDF732BA9A +:109050000369866001330361336BC3603063D0E71B +:109060006846002008B5302383F31188FFF7BEFF60 +:10907000002383F3118808BD194BD96883688B429C +:1090800010B520D1302383F311880269013A0261BF +:10909000B2B90468C368A0420B631ED04A6B9BB987 +:1090A00001238A60036103681A68026050601A6BCA +:1090B0008360C26018631846FDF7FAF9FDF74AFAB3 +:1090C000002383F3118810BD1C68A34203D0A46859 +:1090D000A24238BF2246DB68E1E78260F0E700BFCA +:1090E00068460020024A536B18435063704700BF24 +:1090F0006846002038B5EFF311859DB9EFF305847C +:10910000C4F30804302334B183F31188FDF72EFC37 +:1091100085F3118838BD83F31188FDF727FC84F3AC +:10912000118838BDBDE83840FDF720BC0023054A52 +:1091300019460133102BC2E9001102F10802F8D1DF +:10914000704700BFB4660020114BD3F8E82042F00E +:109150000802C3F8E820D3F8102142F00802C3F84F +:1091600010210C4AD3F81031D36B43F00803D363BA +:10917000C722094B9A624FF0FF32DA6200229A61ED +:109180005A63DA605A6001225A611A60704700BF60 +:10919000004402580010005C000C0040094A08B569 +:1091A0001169D3680B40D9B29B076FEA01011161C5 +:1091B00007D5302383F31188FDF7F2F9002383F3F9 +:1091C000118808BD000C004010B5013902449042DE +:1091D00001D1002005E0037811F8014FA34201D02E +:1091E000181B10BD0130F2E7884210B501EB0204F4 +:1091F00002D98442234607D8431EA14208D011F861 +:10920000012B03F8012FF8E7024401468A4200D1FE +:1092100010BD13F8014D02F8014DF7E7C9B203463E +:1092200010F8012B1AB18A42F9D11846704700296B +:1092300018BF0023F9E70000034611F8012B03F8DB +:10924000012B002AF9D1704710B50139034632B11C +:1092500011F8014F03F8014B013A002CF7D11A44E1 +:109260000021934200D110BD03F8011BF9E7000073 +:109270004D4435002D2D0A002F6172647570696CA4 +:109280006F742E6162696E002F6172647570696C13 +:109290006F742D7665726966792E6162696E002F32 +:1092A0006172647570696C6F742D666C6173682E81 +:1092B0006162696E002F6172647570696C6F742DE4 +:1092C000666C61736865642E6162696E00000000FF +:1092D0000000000000000000050F0008A10F0008BA +:1092E00051110008D90F0008990F00080000000074 +:1092F00000000000010F0008AD0F000889110008F0 +:10930000FD0E0008090F000853544D333248373F13 +:109310003F3F0053544D3332483733782F3732783C +:109320000053544D3332483734332F3735332F37CA +:109330003530000001105A00031059000120580078 +:10934000032056002F000000537563636573736636 +:10935000756C6C79206D6F756E7465642053444331 +:109360006172642028736C6F77646F776E3D25752A +:10937000290A0000EB7690455846415420202000F1 +:109380004641543332202020000000002A3A3C3E5F +:109390007C223F7F002B2C3B3D5B5D0043554541CC +:1093A0004141414345454549494941414592924FD3 +:1093B0004F4F5555594F554F9C4F9E9F41494F55C3 +:1093C000A5A5A6A7A8A9AAABACADAEAFB0B1B2B3E4 +:1093D000B4414141B8B9BABBBCBDBEBFC0C1C2C334 +:1093E000C4C54141C8C9CACBCCCDCECFD1D14545EA +:1093F0004549494949D9DADBDCDD49DF4FE14F4FC7 +:109400004F4FE6E8E85555555959EEEFF0F1F2F3B4 +:10941000F4F5F6F7F8F9FAFBFCFDFEFF010305078A +:10942000090E10121416181C1E00000061001A0309 +:10943000E0001703F8000703FF00010078010001B6 +:10944000300132010601390110014A012E01790172 +:10945000060180014D0043028101820182018401E5 +:10946000840186018701870189018A018B018B01B3 +:109470008D018E018F019001910191019301940161 +:10948000F60196019701980198013D029B019C010C +:109490009D0120029F01A001A001A201A201A4013F +:1094A000A401A601A701A701A901AA01AB01AC0172 +:1094B000AC01AE01AF01AF01B101B201B301B30123 +:1094C000B501B501B701B801B801BA01BB01BC01D2 +:1094D000BC01BE01F701C001C101C201C301C40149 +:1094E000C501C401C701C801C701CA01CB01CA0136 +:1094F000CD011001DD0101008E01DE011201F30139 +:109500000300F101F401F401F80128012202120123 +:109510003A020900652C3B023B023D02662C3F02E9 +:1095200040024102410246020A0153024000810109 +:109530008601550289018A0158028F015A02900161 +:109540005C025D025E025F029301610262029401AD +:109550006402650266026702970196016A02622C44 +:109560006C026D026E029C01700271029D01730219 +:1095700074029F0176027702780279027A027B02F6 +:109580007C02642C7E027F02A60181028202A90174 +:109590008402850286028702AE014402B101B20153 +:1095A00045028D028E028F0290029102B7017B0369 +:1095B0000300FD03FE03FF03AC03040086038803DE +:1095C00089038A03B1031103C2030200A303A303A7 +:1095D000C4030803CC0303008C038E038F03D8035A +:1095E0001801F2030A00F903F303F403F503F60389 +:1095F000F703F703F903FA03FA03300420035004D6 +:109600001007600422018A043601C1040E01CF0450 +:109610000100C004D00444016105260400000000DC +:109620007D1D0100632C001E9601A01E5A01001F23 +:109630000806101F0606201F0806301F0806401FD8 +:109640000606511F0700591F521F5B1F541F5D1F45 +:10965000561F5F1F601F0806701F0E00BA1FBB1F3A +:10966000C81FC91FCA1FCB1FDA1FDB1FF81FF91F36 +:10967000EA1FEB1FFA1FFB1F801F0806901F08063A +:10968000A01F0806B01F0400B81FB91FB21FBC1FDF +:10969000CC1F0100C31FD01F0206E01F0206E51FFA +:1096A0000100EC1FF31F0100FC1F4E2101003221BD +:1096B00070211002842101008321D0241A05302C4E +:1096C0002F04602C0201672C0601752C0201802CEE +:1096D0006401002D260841FF1A030000C700FC00AA +:1096E000E900E200E400E000E500E700EA00EB004A +:1096F000E800EF00EE00EC00C400C500C900E60081 +:10970000C600F400F600F200FB00F900FF00D600EE +:10971000DC00F800A300D800D7009201E100ED00C2 +:10972000F300FA00F100D100AA00BA00BF00AE00B9 +:10973000AC00BD00BC00A100AB00BB009125922590 +:10974000932502252425C100C200C000A90063257D +:10975000512557255D25A200A50010251425342587 +:109760002C251C2500253C25E300C3005A25542543 +:1097700069256625602550256C25A400F000D000E1 +:10978000CA00CB00C8003101CD00CE00CF001825A3 +:109790000C2588258425A600CC008025D300DF0079 +:1097A000D400D200F500D500B500FE00DE00DA00DE +:1097B000DB00D900FD00DD00AF00B400AD00B1005A +:1097C0001720BE00B600A700F700B800B000A80040 +:1097D000B700B900B300B200A025A00010000240FD +:1097E000080002400008024000000B002800024070 +:1097F000080002400408024006010C00400002403C +:10980000080002400808024010020D005800024003 +:10981000080002400C08024016030E0070000240CF +:109820000C0002401008024000040F0088000240B3 +:109830000C0002401408024006051000A00002407F +:109840000C0002401808024010061100B800024047 +:109850000C0002401C08024016072F0010040240B2 +:109860000804024020080240000838002804024092 +:10987000080402402408024006093900400402405E +:109880000804024028080240100A3A005804024026 +:10989000080402402C080240160B3B0070040240F2 +:1098A0000C04024030080240000C3C0088040240D6 +:1098B0000C04024034080240060D4400A00402409B +:1098C0000C04024038080240100E4500B804024063 +:1098D0000C0402403C080240160F46000100000044 +:1098E00000000000009600000000000000000000E2 +:1098F0000000000000000000000000000000000068 +:10990000096C00080D6C000801570008395A00085E +:1099100095560008BD560008E55600087D5600081B +:1099200000000000ED5A0008D95A0008155B000835 +:10993000015B00080D5B0008F95A0008E55A0008B1 +:10994000D15A0008215B000800000000055C0008F7 +:10995000F15B00082D5C0008195C0008255C00081C +:10996000115C0008FD5B0008E95B0008395C000839 +:109970000000000001000000000000006330000053 +:109980007C9900080000000000000000E046002074 +:10999000104900200000802A00020000AAAAAAAAFA +:1099A00000000024FFFF00000000000000A00A00EB +:1099B000000200A000000000AAAAAAAA000100500C +:1099C000FFFF0000000009000000009900000006F1 +:1099D00000000000AAAAAAAA00000001FFFF0000E0 +:1099E000000000000000080020A00A400000000065 +:1099F000AAAAAAAA10400540FFFF0000000800BB69 +:109A0000770000004045020000000000AAAAAAAAB0 +:109A100000000100C7FF0000000000000700000078 +:109A20000020000000000000AAAAAAAA001000005E +:109A3000FFFF000000000007000000001041900040 +:109A400000000000AAAAAAAA10404000FFFF0000E0 +:109A50000000000000A00000000400000000000062 +:109A6000AAAAAAAA00040000FFFF0000000000004C +:109A7000000000000000040000000000AAAAAAAA3A +:109A800000000400FFFF00000000000000000000D4 +:109A90000000000000000000AAAAAAAA000000001E +:109AA000FFFF0000000000000000000000000000B8 +:109AB00000000000AAAAAAAA00000000FFFF000000 +:109AC00000000000000000004172647550696C6F76 +:109AD000740025424F415244252D424C00255345E8 +:109AE0005249414C25000000020000000000000027 +:109AF000255E0008955E000840004000C06100201F +:109B0000D0610020020000000000000003000000FF +:109B100000000000DD5E00080000000010000000F2 +:109B2000E0610020000000000100000000000000D3 +:109B30003C65002001010200056D0008156C00085D +:109B4000B16C0008956C000843000000509B0008B1 +:109B500009024300020100C03209040000010202B0 +:109B60000100052400100105240100010424020263 +:109B70000524060001070582030800FF090401000F +:109B8000020A0000000705010240000007058102EB +:109B900040000000120000009C9B00081201100110 +:109BA00002000040091241570002010203010000B7 +:109BB0000403090425424F415244250043554156B0 +:109BC0002D372D4E616E6F003031323334353637DC +:109BD000383941424344454600000000000000205F +:109BE000000002000200000000000030000004003D +:109BF000080000000000002400000800040000002D +:109C00000004000000FC000002000000000004301E +:109C10000080000008000000000000380000010083 +:109C2000010000001F1C1F1E1F1E1F1F1E1F1E1FC6 +:109C30001F1D1F1E1F1E1F1F1E1F1E1F00000000B6 +:109C400039600008F16200089D6300084000400090 +:109C50007466002074660020010000008466002005 +:109C6000800000004001000008000000000100002A +:109C7000001000000800000069646C65000000002E +:109C80006D61696E002C0438040438080C10141C33 +:109C900020242526000000000000640401000400C8 +:109CA00000000000000C001028303400BC67FF7F6B +:109CB0000100000000000000581B00000000000030 +:109CC00000001E0000000000FF00000018490020F6 +:109CD000F83900208C3900202039002000000000D5 +:109CE0000893000883040000139300085004000048 +:109CF0002193000801000000000000000096000011 +:109D000000000800960000000008000004000000A9 +:109D1000B09B0008000000000000000000000000F0 +:0C9D200000000000000000000000000037 +:00000001FF diff --git a/Tools/bootloaders/CubeBlack+_bl.bin b/Tools/bootloaders/CubeBlack+_bl.bin index 3173b2f105d70b..a7728c8ba1cb4e 100755 Binary files a/Tools/bootloaders/CubeBlack+_bl.bin and b/Tools/bootloaders/CubeBlack+_bl.bin differ diff --git a/Tools/bootloaders/CubeBlack+_bl.hex b/Tools/bootloaders/CubeBlack+_bl.hex index 66e7d8baa7272e..ebbd8d27cbcb3e 100644 --- a/Tools/bootloaders/CubeBlack+_bl.hex +++ b/Tools/bootloaders/CubeBlack+_bl.hex @@ -1,1019 +1,1009 @@ :020000040800F2 -:1000000000040020E1010008210F0008250F00086E -:10001000790F0008250F00084D0F0008E3010008C4 -:10002000E3010008E3010008E301000811280008CB +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E301000801360008CD :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E301000879390008A539000828 -:10006000D1390008FD390008293A0008E3010008E9 +:10005000E3010008E3010008B1380008D9380008BE +:10006000013900082939000851390008E301000866 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008553A000805 +:10009000E3010008E3010008E301000879390008E2 :1000A000E3010008E3010008E3010008E3010008A0 :1000B000E3010008E3010008E3010008E301000890 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E3010008291100083D110008B0 -:1000E000BD3A0008E3010008E3010008E30100084D +:1000D000E3010008E30100084D3A0008E3010008CD +:1000E000DD390008E3010008E3010008E30100082E :1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E301000889370008E301000863 +:10010000E3010008E3010008613A0008E301000888 :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008FD2E0008B8 +:10014000E3010008E3010008E3010008A92D00080D :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E301000851110008E301000841 +:10018000E3010008E3010008E3010008E3010008BF :10019000E3010008E3010008E3010008E3010008AF :1001A000E3010008E3010008E3010008E30100089F :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F01BFB03F02DFA4FF055301F4952 -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE702F0B3 -:1002A000F9FA03F063FA144C144DAC4203DA54F833 -:1002B000041B8847F9E700F03FF8114C114DAC42A0 -:1002C00003DA54F8041B8847F9E702F0E1BA0000AA -:1002D000000400200024002000000008000000208E -:1002E00000040020683F000800240020282400208B -:1002F00028240020903D0020E0010008E0010008D3 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F0EEFE49 -:1003300001F09EFE00DFFEE770B5214C6FF0140364 -:1003400023700323002563706FF03F061F23A57001 -:10035000E57025716571A571E57125726672A372EC -:10036000E57200F0FFFC20B10F2325726672A372C4 -:10037000E57202F01FFA044602F044FA0546D8B9C5 -:10038000104B9C421AD001339C4218BF054641F2E3 -:10039000883404BF01250024002002F015FA0DB1B5 -:1003A00000F0B6F800F062FD00F01AFC204600F004 -:1003B0000DF900F0ADF8F9E70024EDE70446EBE7AE -:1003C00028240020010007B008B500F087FBA0F149 -:1003D00020035842584108BD07B5054B02211B8830 -:1003E000ADF8043001A800F0E5FB03B05DF804FBB4 -:1003F000A43B0008064991F8243033B100230822B9 -:10040000086A81F8243000F00DBC0120704700BF5D -:10041000482400202DE9F84F234C94F82430054659 -:10042000884617468BBB2E46DFF87C90002F38D0CD -:1004300094F824A0BAF1000F05D12022FF214846EC -:10044000266200F001FDCAF10805BD4228BF3D4605 -:100450005FFA85FBAD0041462A4604EB8A0000F0B6 -:10046000C9FC94F82430A7EB0B079B445FFA8BFB85 -:10047000BBF1080F2E44A844FFB284F824B0D5D1B4 -:10048000FFF7B8FF0028D1D108E0266A06EB830603 -:10049000B042C9D0FFF7AEFF0028C4D10020BDE8AC -:1004A000F88F0120BDE8F88F4824002010B52023E4 -:1004B00083F311881248C3680BB101F0ADFE00232D -:1004C000104A0F484FF47A7101F06AFE002383F35B -:1004D00011880D4C236813B12368013B23606368C6 -:1004E00013B16368013B6360084B1B7833B96368E1 -:1004F00023B9022000F074FC3223636010BD00BFFA -:1005000034240020AD040008782500207024002049 -:1005100010B5254B254953F8042F013200D110BDE9 -:100520008B42F8D1224C234B22689A423AD9224B73 -:100530009B6803F1006303F580439A4232D20020A6 -:1005400000F068FB1D4B0220187000F03FFC1C4BB4 -:100550001A6C00221A64196E1A66196E596C5A6464 -:10056000596E5A665A6E5A6942F080025A615A6947 -:1005700022F080025A615A691A6942F000521A61E7 -:100580001A6922F000521A611B6972B60D4A0E4BAD -:1005900013601B682268202181F311889D4683F334 -:1005A0000888104710BD00BFFC3F00081C40000831 -:1005B00004400008FF3F0008282400207024002089 -:1005C0000038024008ED00E0004000082DE9F04F3F -:1005D00099B0B34C01902022FF2110A8A66800F02A -:1005E00033FCB04A1378A346A3B9AF480121C360D6 -:1005F0001170202383F31188C3680BB101F00CFE46 -:100600000023AA4AA8484FF47A7101F0C9FD0023DB -:1006100083F31188019B13B1A54B019A1A60A54A77 -:10062000A349019F0292002313704B6099461C4618 -:100630001D469846012000F0C9FB002F00F01282F1 -:100640009B4B1B68002B40F00D8219B0BDE8F08F6A -:100650000220FFF7B9FE002840F0FB81019BB9F1B1 -:10066000000F08BF1F46944B1B88ADF82C300221A9 -:100670000BA800F09FFADDE74FF47A7000F02EFA35 -:10068000031E0393EADB0220FFF79EFE824600284A -:10069000E4D0039B581E042800F2DD81DFE800F05F -:1006A000030E1114170018A8052340F8343D042147 -:1006B00000F080FA54464FF0000856E004217848D4 -:1006C000F6E704217D48F3E704217D48F0E71C2488 -:1006D000204600F0A1FA04340B9004210BA800F08E -:1006E00069FA2C2CF4D1E5E7002DB7D0002CB5D059 -:1006F0000220FFF769FE0546002800F0AF810120C7 -:100700006C4C00F087FA0220207000F05FFB4FF085 -:1007100000095FFA89FA504600F08CFA074658B192 -:10072000504600F097FA09F101090028F1D12C4652 -:10073000A9460027634B97E701230220237000F0AE -:100740003BFB3E46DBF808309E4206D2304600F0C6 -:1007500063FA0130EBD10436F4E7029B00261E70E9 -:10076000534BA9465E602C46374600F075FB15B129 -:10077000002C18BF0027FFF72FFE5BE7002D3FF48A -:100780006DAF002C3FF46AAF029B0220187000F09E -:100790001DFB322000F0A2F9B0F1000AC0F25E8128 -:1007A0001AF0030540F05A81DBF8082006EB0A0333 -:1007B000934200F25381BAF5807F00F24F81554594 -:1007C0000DDA4FF47A7000F089F90490049B002B45 -:1007D000C0F244813C4A049BAB540135EFE7C8208A -:1007E000FFF7F2FD0546002800F038811F2E11D8D2 -:1007F000C6F12004544528BF544610AB26F0030030 -:1008000022463149184400F0F5FA2246FF212E48CD -:1008100000F01AFB4FEAAA0A5FFA8AF22A49304628 -:10082000FFF7F8FD0446002800F01A8106EB8A065F -:1008300005469AE70220FFF7C7FD00283FF40EAFF8 -:10084000FFF7D8FD00283FF409AF4FF0000A5346E8 -:10085000DBF8082092451CD2BAF11F0F12D8109A6B -:1008600001320FD02AF0030218A90A4452F8202CB2 -:100870000B92184604220BA900F092FB0AF1040A1D -:100880000346E5E75046039300F0C6F9039B0B903F -:10089000EFE718A8042140F84C3D00F08BF964E71D -:1008A000282400207425002034240020AD040008F2 -:1008B0007825002070240020A63B00082C2400206E -:1008C00030240020A83B00087424002018A800232E -:1008D00040F8343D642100F039F900287FF4BEAEC1 -:1008E0000220FFF771FD00283FF4B8AE0B9800F02E -:1008F000C3F918AB43F8480D04211846CDE718A8F2 -:10090000002340F8343D642100F020F900287FF4F2 -:10091000A5AE0220FFF758FD00283FF49FAE0B98CC -:1009200000F0B8F918AB43F8440DE5E70220FFF7F3 -:100930004BFD00283FF492AE00F0B2F918AB43F83B -:10094000400DD9E70220FFF73FFD00283FF486AEB7 -:100950000BA9142000F0AAF9824618A8042140F837 -:100960003CAD00F027F951460BA896E7322000F085 -:10097000B5F8B0F1000AFFF671AE1AF0030F7FF47C -:100980006DAEDBF808200AEB080393423FF666AE33 -:100990000220FFF719FD00283FF460AE2AF0030A99 -:1009A000C244D0453FF4E1AE404600F035F90421A1 -:1009B0000A900AA800F0FEF808F10408F1E74FF4E5 -:1009C0007A70FFF701FD00283FF448AEFFF712FDF3 -:1009D00000283FF4AFAE109B01330CD0082210A9C1 -:1009E0000020FFF717FD00283FF4A4AE2022FF21CE -:1009F00010A800F029FAFFF7EFFC374801F08CFB54 -:100A000023E6002D3FF42AAE002C3FF427AE18A8B1 -:100A1000002340F8343D642100F098F88246002815 -:100A20007FF41CAE0220FFF7CFFC00283FF416AE87 -:100A30000390FFF7D1FC41F2883001F06DFB0B9879 -:100A400000F04EFA00F008FA039B57461C461D467C -:100A5000F0E5054689E64FF00008FFE52546FDE58F -:100A60002C4667E6002000F039F80490049B002B28 -:100A7000FFF6E3AD012000F09FF9049B213B122B10 -:100A80003FF6D8AD01A252F823F000BF510600088E -:100A900079060008E9060008350600083506000852 -:100AA000350600087D0700086D09000835080008B4 -:100AB000CD080008FF0800082D09000835060008C9 -:100AC0004509000835060008BF0900086B07000843 -:100AD00035060008030A0008A08601002DE9F34747 -:100AE00002AE00244FF47A7506F8014D144FDFF87A -:100AF0005880454397F900305A1C5FFA84F901D0B9 -:100B0000A34212D158F8240003680122D3F820A090 -:100B100031462B46D047012807D10A4B9DF80700E4 -:100B200083F8009002B0BDE8F0870134042CE1D1D5 -:100B30004FF4FA7001F0F0FA4FF0FF30F2E700BF27 -:100B40000024002098250020FC3B00082DE9F047F8 -:100B50004FF47A75144FDFF8588006464D43002451 -:100B600097F900305A1C5FFA84F901D0A34210D1E2 -:100B700058F8240003680422D3F820A031462B46FD -:100B8000D047042805D1094B83F800900020BDE828 -:100B9000F0870134042CE3D14FF4FA7001F0BCFA71 -:100BA0004FF0FF30BDE8F08700240020982500209A -:100BB000FC3B000830B4074B1A78074B53F822402F -:100BC0002368DD69054B0A46AC460146204630BC29 -:100BD000604700BF98250020FC3B0008A08601006C -:100BE00070B501F0E3FC094C094E20700025306817 -:100BF0002378834208D901F0D3FC336805440133DC -:100C0000B5F5804F3360F2D370BD00BF9925002049 -:100C10008025002001F080BD00F1006000F58040DB -:100C20000068704700F10060920000F5804001F01C -:100C30000BBD0000054B1A68054B1B789B1A8342BD -:100C400002D9104401F0ACBC002070478025002080 -:100C50009925002038B5074D04462868204401F046 -:100C6000A7FC28B928682044BDE8384001F0B8BC8A -:100C700038BD00BF8025002010F0030308D1B0F577 -:100C8000007F05D800F10050A0F5084000687047CB -:100C900000207047014BC058704700BF107AFF1FFB -:100CA000014B1868704700BF002004E070B52A4B64 -:100CB0001C68C4F30B03240C63B140F2134293424B -:100CC00031D040F2194293422FD040F22142934258 -:100CD0002DD10323214A0C2505FB03235D6893F9DD -:100CE000082042F201039C4224D0B4F5805F23D057 -:100CF00041F201039C4221D041F203039C421FD0E8 -:100D000041F207039C4208BF3122441E0C44013DBE -:100D10000B46A3421ED215F9016F581C96B103462B -:100D200000F8016CF5E70123D4E70223D2E73F2264 -:100D30000B4DD6E73322E3E74122E1E75A22E4E70D -:100D40005922E2E72C2584421D7001D9981C5A7063 -:100D5000401A70BD1846FBE7002004E0CC3B0008B9 -:100D6000AC3B0008124B5A8842F201018A4293B20E -:100D700014D0B3F5805F13D041F20102934211D039 -:100D800041F2030293420FD041F2070293420DD188 -:100D90000423084A02EB8303D87870470023F8E75E -:100DA0000123F6E70223F4E70323F2E7002070476C -:100DB000002004E0B83B0008022802BF024B4FF4B9 -:100DC00080529A61704700BF00100240022802BFA3 -:100DD000024B4FF080529A61704700BF00100240F2 -:100DE000022801BF024A536983F48053536170475C -:100DF0000010024010B50023934203D0CC5CC454D1 -:100E00000133F9E710BD000030B5441E14F9010F9D -:100E10000B4660B193F90050854201F1010106D102 -:100E20001AB993F90020801A30BD013AEEE7002A82 -:100E3000F7D1104630BD000002460346981A13F958 -:100E4000011B0029FAD1704702440346934202D0A5 -:100E500003F8011BFAE77047024B1A78024B1A702D -:100E6000704700BF9825002000240020F8B5164CDC -:100E70001648174D174E154F00F096FC21461348A3 -:100E800000F0BEFC24681448626D936B23F40023C9 -:100E9000936301F041F92046104900F0BDFD626DF9 -:100EA000936B43F4002393634FF4E1332B600024EE -:100EB00056F82400B84202D0294600F0D3FB013492 -:100EC000042CF5D1F8BD00BFE43C000894330020A9 -:100ED00084250020FC3B000840420F00103D000824 -:100EE00038B50B4B1A780B4B53F822400A4B9C42F7 -:100EF00005460CD0094B002118461422FFF7A4FF29 -:100F0000056001462046BDE8384000F0ABBB38BD67 -:100F100098250020FC3B0008943300208425002005 -:100F2000FEE7000000B59BB0EFF309816822684638 -:100F3000FFF760FFEFF30583034B9A6B9A6A9A6A97 -:100F40009A6A9A6A9B6AFEE700ED00E000B59BB0E2 -:100F5000EFF3098168226846FFF74CFFEFF3058342 -:100F6000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A14 -:100F7000FEE700BF00ED00E000B59BB0EFF3098194 -:100F800068226846FFF736FFEFF30583034B5A6B81 -:100F90009A6A9A6A9A6A9A6A9B6AFEE700ED00E08A -:100FA00030B5084D0A4491420BD011F8013B092499 -:100FB0005840013CF7D040F300032B4083EA500037 -:100FC000F7E730BD2083B8ED002304491A465A5094 -:100FD000C8180833802B4260F9D170479C25002047 -:100FE000026843681143016003B11847704700006D -:100FF000024AD36843F0C003D36070470044004006 -:10100000024AD36843F0C003D360704700480040F1 -:10101000024AD36843F0C003D360704700780040B1 -:101020002DE9F041D0F85C64F7683368DA050546CD -:101030009CB20DD5202383F311884FF40071043046 -:10104000FFF7CEFF6FF480733360002383F31188C2 -:10105000202383F3118805F1040814F02F0333D102 -:1010600083F31188380615D5210613D5202383F381 -:10107000118805F1380000F053FA002846DA0821FB -:10108000281DFFF7ADFF4FF67F733B40F360002351 -:1010900083F311887A060ED563060CD5202383F3DB -:1010A0001188EA6C2B6D9A4202D12B6C002B2FD148 -:1010B000002383F31188D5F86424D368002B31D042 -:1010C0001069BDE8F0411847230713D014F0080F4A -:1010D0000CBF00218021E00748BF41F02001A2079A -:1010E00048BF41F04001630748BF41F4807140466A -:1010F000FFF776FFA406736805D595F860142846B7 -:10110000194000F0BDFA3468A4B2A6E77060BEE7EB -:1011100027F040073F041021281D3F0CFFF760FF18 -:10112000F760C5E7BDE8F08108B50348FFF778FF31 -:10113000BDE8084001F07CBB1C26002008B5034830 -:10114000FFF76EFFBDE8084001F072BB842A002063 -:1011500008B50348FFF764FFBDE8084001F068BB2D -:10116000EC2E002010B50E4C0E4A2046002100F057 -:1011700057FA0D4BC4F85C340C4C0D4A2046002144 -:1011800000F04EFA0B4BC4F85C340B4C0B4A0021B8 -:10119000204600F045FA0A4BC4F85C3410BD00BF8D -:1011A0001C260020F10F000800440040842A002083 -:1011B0000110000800480040EC2E0020111000082B -:1011C0000078004038B5394D037C002918BF0D4622 -:1011D000012B0446C0F8645410D1354B984242D1DB -:1011E000344B1A6C42F400321A641A6E42F4003224 -:1011F0001A661B6E0B21262000F06AF82E4BD4F8DD -:101200005C249A422B6802D02C498A424BD12C494B -:1012100001EB5301B1FBF3F3A988080442BF23F0AB -:10122000070003F0070343EA40039360EB8843F0B1 -:1012300040039BB213612B8943F001039BB25361BE -:1012400041F4045343F02C03D36001F4A051002374 -:101250001360B1F5806F136853680CBF7F23FF23C1 -:1012600084F8603438BD174B98420CD1114B1A6C7E -:1012700042F480221A641A6E42F480221A661B6EAF -:101280000B212720B8E7104B9842B7D1094B1A6CB5 -:1012900042F080421A641A6E42F080421A661B6E57 -:1012A0000B215220A8E70949B2E700BF2C3C0008F7 -:1012B0001C260020003802400010014000140140AC -:1012C00000BD0105842A0020EC2E002080DE800273 -:1012D00000F1604300F01F02400903F5614309017A -:1012E0008000C9B200F1604083F8001300F561404E -:1012F00001239340C0F8803103607047F8B515466C -:1013000082680669AA420B46816938BF8568761AE9 -:10131000B542044607D218462A46FFF76BFDA3697B -:101320002B44A3610DE011D932461846FFF762FD48 -:10133000AF1B3A46E1683044FFF75CFDE2683A448F -:10134000A261A3685B1BA3602846F8BD18462A4625 -:10135000FFF750FDE368E4E783682DE9F0410446B8 -:1013600093421546266938BF85684069361AB542EA -:101370000F4606D22A46FFF73DFD63692B446361A1 -:101380000DE012D93246A5EB0608FFF733FD4246C1 -:10139000B919E068FFF72EFDE26842446261A36874 -:1013A0005B1BA3602846BDE8F0812A46FFF722FDBB -:1013B000E368E4E710B50A440024C361029B0060BF -:1013C00040608460C160816141610261036210BD5F -:1013D00008B582694369934201D1826882B9826803 -:1013E000013282605A1C42611970426903699A4253 -:1013F00001D3C3684361002100F0AAFE002008BDAC -:101400004FF0FF3008BD000070B5202304460E46A3 -:1014100083F31188A568A5B1A368A269013BA36005 -:10142000531CA36115782269934224BFE368A3612A -:10143000E3690BB120469847002383F311882846BF -:1014400070BD3146204600F073FE0028E2DA85F3D5 -:10145000118870BD2DE9F74F05460F4690469A4614 -:10146000D0F81C90202686F311884FF0000B14460C -:1014700064B1224639462846FFF740FF034668B963 -:101480005146284600F054FE0028F1D0002383F393 -:101490001188A8EB040003B0BDE8F08FB9F1000F8C -:1014A00003D001902846C847019B8BF31188E41AAA -:1014B0001F4486F31188DBE7C16081614161C3612C -:1014C0001144009B006040608260016103627047CC -:1014D000F8B504460E461746202383F31188A56805 -:1014E000A5B1A368013BA36063695A1C62611E70C9 -:1014F000236962699A4224BFE3686361E3690BB1BF -:1015000020469847002080F31188F8BD39462046D0 -:1015100000F00EFE0028E2DA85F31188F8BD000025 -:10152000836942699A4210B501D182687AB98268AA -:10153000013282605A1C82611C7803699A4201D38D -:10154000C3688361002100F003FE204610BD4FF008 -:10155000FF3010BD2DE9F74F05460F4690469A46DD -:10156000D0F81C90202686F311884FF0000B14460B -:1015700064B1224639462846FFF7EEFE034668B9B5 -:101580005146284600F0D4FD0028F1D0002383F313 -:101590001188A8EB040003B0BDE8F08FB9F1000F8B -:1015A00003D001902846C847019B8BF31188E41AA9 -:1015B0001F4486F31188DBE702684368114301602A -:1015C00003B11847704700001430FFF743BF000015 -:1015D0004FF0FF331430FFF73DBF00003830FFF706 -:1015E000B9BF00004FF0FF333830FFF7B3BF000042 -:1015F0001430FFF709BF00004FF0FF311430FFF740 -:1016000003BF00003830FFF763BF00004FF0FF3228 -:101610003830FFF75DBF000000207047FFF7A2BD24 -:1016200037B50F4B0360002343608360C360012321 -:1016300004460374154600900B464FF4007200F107 -:101640005C011430FFF7B6FE00942B464FF4007295 -:1016500004F5177104F13800FFF72EFF03B030BD19 -:10166000403C000810B52023044683F31188FFF79F -:10167000A9FD02232374002383F3118810BD000009 -:1016800038B5C36904460D461BB904210844FFF769 -:1016900093FF294604F11400FFF79AFE002806DAAA -:1016A000201D4FF48061BDE83840FFF785BF38BD8D -:1016B000026843681143016003B118477047000096 -:1016C00013B5446BD4F894341A681178042915D1F1 -:1016D000217C022912D11979128901238B401342EE -:1016E0000CD101A904F14C0001F058FED4F8944447 -:1016F000019B21790246206800F0DAF902B010BDA2 -:10170000143001F0DBBD00004FF0FF33143001F066 -:10171000D5BD00004C3001F0ADBE00004FF0FF33EE -:101720004C3001F0A7BE0000143001F0A9BD00004C -:101730004FF0FF31143001F0A3BD00004C3001F038 -:1017400079BE00004FF0FF324C3001F073BE000054 -:10175000D0F8942438B5136819780429054601D0C7 -:10176000012038BD017C0229FAD112795C8901205F -:1017700090400440F4D105F1140001F03BFD024615 -:101780000028EDD0D5F894544FF480732868697917 -:1017900000F07CF9204638BD406BFFF7D9BF000050 -:1017A00000207047704700007FB5124B0360002394 -:1017B00043608360C360012502260F4B0574044615 -:1017C0000290019300F18402294600964FF4807341 -:1017D000143001F0EBFC094B0193029400964FF496 -:1017E000807304F52372294604F14C0001F0B2FD28 -:1017F00004B070BD683C000899170008C1160008C5 -:101800000B68202282F311880A7903EB820290612F -:101810004A79093243F822008A7912B103EB820334 -:10182000986102230374C0F89414002383F3118891 -:101830007047000038B5037F044613B190F8543068 -:10184000ABB9201D01250221FFF732FF04F114007E -:1018500025776FF0010100F087FC84F8545004F103 -:101860004C006FF00101BDE8384000F07DBC38BD90 -:1018700010B5012104460430FFF71AFF0023237737 -:1018800084F8543010BD000038B5044600251430EB -:1018900001F0A4FC04F14C00257701F073FD201D3C -:1018A00084F854500121FFF703FF2046BDE838407B -:1018B000FFF74EBF90F8443003F06003202B19D19E -:1018C00090F84520212A0AD0222A4FF000030ED09A -:1018D000202A0FD1084A82630722C26304E0064B24 -:1018E00083630723C363002303640120704783637A -:1018F000C363F9E70020704701240020D0F8943436 -:1019000037B51A681178042904461AD1017C0229D6 -:1019100017D11979128901238B40134211D100F19B -:101920004C05284601F0EEFD58B101A9284601F00A -:1019300035FDD4F89444019B21790246206800F0DB -:10194000B7F803B030BD000000EB8103F7B59C6928 -:1019500005460E46F4B1202383F3118805EB860774 -:10196000201D0821FFF7A4FEFB685B691B684C344F -:1019700013B1204601F020FD01A9204601F00EFD23 -:10198000024648B1019B3146284600F091F80023F9 -:1019900083F3118803B0F0BDFB685A691268002A0E -:1019A000F5D01B8A013B1340F1D105F14402EAE76F -:1019B000093138B550F82140DCB1202383F3118878 -:1019C000D4F894241368527903EB8203DB689B6993 -:1019D0005D6845B104216018FFF76AFE294604F1ED -:1019E000140001F011FC2046FFF7B2FE002383F340 -:1019F000118838BD7047000000F0D2BF012303708A -:101A000000234360C36183620362C3624362036372 -:101A1000038143817047000038B50446202383F3D7 -:101A2000118800254160C56005614561856100F050 -:101A3000C7FF0223237085F3118838BD70B500EB12 -:101A4000810305465069DA600E46144618B110222B -:101A50000021FFF7F9F9A06918B110220021FFF762 -:101A6000F3F931462846BDE8704001F073B8000034 -:101A7000028902F001020281428902F001024281E0 -:101A8000002202614261826101F0F8B8F0B400EB1B -:101A900081044789E4680125A4698D403D4345815F -:101AA00023600023A2606360F0BC01F013B9000062 -:101AB000F0B400EB81040789E468012564698D4076 -:101AC0003D43058123600023A2606360F0BC01F008 -:101AD0008DB9000070B50223002504460370A0F8FC -:101AE0004C5080F84E5080F84F5005814581C560BC -:101AF00005614561856180F8345000F0C7FF636877 -:101B00001B6823B129462046BDE87040184770BDC8 -:101B1000436802781B6880F85020052202700BB1E0 -:101B20000421184770470000436890F850201B6854 -:101B300002700BB1052118477047000090F834304F -:101B400070B5044613B1002380F8343004F1440228 -:101B5000204601F0B5F863689B6863BB94F8445075 -:101B600015F0600615D194F8453005F07F0545EA7B -:101B7000032540F202339D4200F00E815BD8022D16 -:101B800000F0DC803FD8002D00F08780012D00F0B0 -:101B9000CF800021204601F0EBFA0021204601F021 -:101BA000DDFA63681B6813B10621204698470623B7 -:101BB00084F8343070BD204698470028CED094F881 -:101BC0004B2094F84A3043EA0223E26B934238BF39 -:101BD000E36394F94430E56B002B4FF0200380F26F -:101BE000FD80002D00F0EC80092284F8342083F37E -:101BF00011880021E36BA26B2046FFF759FF0023F9 -:101C000083F3118870BDB5F5817F00F0B180B5F523 -:101C1000407F49D0B5F5807FBBD194F84630012B89 -:101C2000B7D1B4F84C3023F00203A4F84C30A663CB -:101C3000E6632664C3E740F201639D421ED8B5F512 -:101C4000C06F3BD2B5F5A06FA3D1B4F84430B3F563 -:101C5000A06F0ED194F8463084F84E30204600F044 -:101C60006DFF63681B6813B1012120469847032369 -:101C700023700023A363E3632364A0E7B5F5106F2B -:101C800032D040F602439D4252D0B5F5006F80D16C -:101C900004F14F03A363012324E004F14C03A36385 -:101CA0000223E36325648AE794F84630012B7FF42E -:101CB00070AFB4F84C3043F00203B6E794F8492013 -:101CC000616894F848304D6894F8471043EA02235D -:101CD000204694F84620A84700283FF45AAF4368AE -:101CE000A3630368E363A4E72378042B10D12023C4 -:101CF00083F311882046FFF7BBFE86F311886368E3 -:101D000084F84F601B68032121700BB1204698476F -:101D100094F84630002BACD084F84F300423237065 -:101D200063681B68002BA4D0022120469847A0E7D7 -:101D3000374BA3630223E36300239DE794F8481025 -:101D400011F0800F204601F00F010ED000F0AAFF25 -:101D5000012806D002287FF41CAF2E4BA363E0635A -:101D600067E72D4BA363E56363E700F08DFFEFE7C3 -:101D700094F84630002B7FF40CAF94F8483013F001 -:101D80000F013FF476AF1A06204602D501F004FA9F -:101D90006FE701F0F7F96CE794F84630002B7FF419 -:101DA000F8AE94F8483013F00F013FF462AF1B0611 -:101DB000204602D501F0DCF95BE701F0CFF958E7E6 -:101DC000142284F8342083F311882B462A462946AE -:101DD0002046FFF75BFE85F3118870BD5DB11522CB -:101DE00084F8342083F311880021E36BA26B204632 -:101DF000FFF74CFE03E70B2284F8342083F31188AD -:101E00002B462A4629462046FFF752FEE3E700BF4D -:101E1000983C0008903C0008943C000838B590F8C5 -:101E200034300446152B29D8DFE803F03E28282853 -:101E300028283E28280B2939282828282828282817 -:101E40003E3E90F84B1090F84A20C36B42EA0122C4 -:101E50009A4214D9C268128AB3FBF2F502FB153517 -:101E60006DB9202383F311882B462A462946FFF7B4 -:101E70001FFE85F311880A2384F8343038BD1423FB -:101E800084F83430202383F3118800231A4619463E -:101E90002046FFF7FBFD002383F3118838BD036C58 -:101EA00003B198470023E7E7002101F061F9002121 -:101EB000204601F053F963681B6813B106212046E0 -:101EC00098470623D8E7000090F83420152A38B543 -:101ED000044622D80123934040F6416213421DD1AB -:101EE00013F480150FD19B0217D50B2380F83430E3 -:101EF000202383F311882B462A462946FFF7D8FD75 -:101F000085F3118838BDC3689B695B682BB9036C86 -:101F100003B19847002384F8343038BD002101F024 -:101F200027F90021204601F019F963681B6813B1F5 -:101F30000621204698470623EDE70000024B0022C9 -:101F40001B605B609A607047543300200023037469 -:101F50008268054B1B6899689142FBD25A680360FE -:101F600042601060586070475433002008B5202349 -:101F700083F31188037C032B05D0042B0DD02BB9E0 -:101F800083F3118808BD436900221A604FF0FF33C4 -:101F90004361FFF7DBFF0023F2E790E80C001A60D3 -:101FA00002685360F2E70000002303748268054B67 -:101FB0001B6899689142FBD85A68036042601060C0 -:101FC0005860704754330020054B1969087418682D -:101FD00002681A605360186101230374FEF794B914 -:101FE0005433002030B54B1C87B005460A4C10D046 -:101FF00023690A4A01A800F0D3F82846FFF7E4FF56 -:10200000049B13B101A800F007F92369586907B0D0 -:1020100030BDFFF7D9FFF8E7543300206D1F0008EB -:1020200038B50C4D41612B6981689A68914204462C -:1020300003D8BDE83840FFF789BF1846FFF786FF91 -:1020400001232C61014623742046BDE83840FEF789 -:102050005BB900BF54330020044B1A681B699068B9 -:102060009B68984294BF00200120704754330020A1 -:1020700010B5084C236820691A6822605460012258 -:1020800023611A74FFF790FF01462069BDE81040F4 -:10209000FEF73AB954330020826002220274002213 -:1020A000427470478368A3F17C0243F80C2C0269E8 -:1020B00043F83C2C426943F8382C074A43F81C2C5F -:1020C000C26843F8102C022203F8082C002203F8FF -:1020D000072CA3F1180070472103000810B5202336 -:1020E00083F31188FFF7DEFF00210446FFF798FF16 -:1020F000002383F31188204610BD0000024B1B69AA -:1021000058610F20FFF760BF54330020202383F372 -:102110001188FFF7F3BF000008B50146202383F3C1 -:1021200011880820FFF75EFF002383F3118808BDA4 -:1021300049B1064B42681B6918605A6013604360DE -:102140000420FFF74FBF4FF0FF307047543300209B -:102150000368984206D01A680260506059611846B8 -:10216000FFF7F4BE7047000038B504460D462068FE -:10217000844200D138BD036823605C604561FFF78D -:10218000E5FEF4E7054B03F114025A619A614FF042 -:10219000FF32DA6100221A62704700BF5433002018 -:1021A000F8B503611A4BC2605C6A1A4B1A460229E1 -:1021B00052F8145F38BF0221954206461F460AD1E5 -:1021C000586198611C620560456081600819BDE82E -:1021D000F84001F0B9B9186AAB68241A0C1902D397 -:1021E000E41A2D6804E09C4202D2204401F0BCF9BC -:1021F000AB689C42F4D86B68736035601E606E609B -:10220000B460A9684FF0FF33091BA960FB61F8BDFA -:10221000000C00405433002010B41A4C234653F8ED -:10222000141F814210D0416802680A600268516040 -:102230009A424FF00001C16003D0936881680B445B -:1022400093605DF8044B70470A68626100209A420F -:102250005360C86003D15DF8044B01F07FB9936807 -:10226000886803449360084A206A526A121A9342AB -:10227000E7D9991A012998BF931C18445DF8044BBB -:1022800001F072B954330020000C00400020704768 -:10229000FEE70000704700004FF0FF30704700007D -:1022A000022906D0032906D00129064818BF0020BC -:1022B000704705487047032A9ABF044800EBC200E4 -:1022C000002070476C3D0008203D000808240020D5 -:1022D00070B59AB001AD064608462946144600F08E -:1022E00095F82846FEF7A8FDC0B2431C5B0086E8BF -:1022F0001800237003236370002302341946DAB2F6 -:10230000904204F1020401D81AB070BDEA5C04F8EE -:10231000022C04F8011C0133F1E7000008B520236A -:1023200083F311880348FFF7E9FA002383F3118848 -:1023300008BD00BF9433002010B50446052916D807 -:10234000DFE801F016150316161D202383F311880C -:102350000E4A0121FFF772FB20460D4A0221FFF7CA -:102360006DFB0C48FFF790FA002383F3118810BD32 -:10237000202383F311880748FFF75CFAF4E7202352 -:1023800083F311880348FFF773FAEDE79C3C0008DC -:10239000C03C00089433002038B50C4D0C4C0D495E -:1023A0002A4604F10800FFF793FF05F1CA0204F181 -:1023B00010000949FFF78CFF05F5CA7204F11800F7 -:1023C0000649BDE83840FFF783BF00BF5C380020F6 -:1023D00008240020EC3C0008F93C0008073D0008F8 -:1023E00070B5044608460D46FEF726FDC6B22046E7 -:1023F000013403780BB9184670BD32462946FEF702 -:1024000003FD0028F3D1012070BD00002DE9F84F35 -:1024100005460C46FEF710FD2B49C6B22846FFF7CD -:10242000DFFF08B10336F6B228492846FFF7D8FF88 -:1024300008B11036F6B2632E0DD8DFF88C80DFF8C5 -:102440008C90234FDFF890A0DFF890B02E7846B93B -:102450002670BDE8F88F29462046BDE8F84F01F008 -:1024600099BB252E2CD1072241462846FEF7CCFCED -:1024700058B9DBF800302360DBF804306360BBF848 -:102480000830238107350A34E0E708224946284608 -:10249000FEF7BAFCA0B90F4BA21C13F8011F0909E3 -:1024A0005345C95D02F8021C197801F00F0102F1D1 -:1024B0000202C95D02F8031CEFD118340835C5E7E4 -:1024C000267001350134C1E78C3D0008073D000846 -:1024D0009F3D00080F7AFF1F1B7AFF1F943D0008E5 -:1024E000BFF34F8F024AD368DB03FCD4704700BFB1 -:1024F000003C024008B5094B1B7873B9FFF7F0FFA9 -:10250000074B1A69002ABFBF064A5A6002F1883297 -:102510005A601A6822F480621A6008BDBA3A002034 -:10252000003C02402301674508B50B4B1B7893B96B -:10253000FFF7D6FF094B1A6942F000421A611A6888 -:1025400042F480521A601A6822F480521A601A68A3 -:1025500042F480621A6008BDBA3A0020003C024092 -:10256000172870B513D80B4A0B4C137863B90B4E70 -:102570004FF0006144F8231056F823500133182B14 -:102580002944F7D10123137054F8200070BD0020B6 -:1025900070BD00BF1C3B0020BC3A0020B03D0008CD -:1025A000014B53F820007047B03D000818207047D9 -:1025B000172810B5044601D9002010BDFFF7D0FF41 -:1025C000064B53F824301844C21A0BB9012010BD31 -:1025D00012680132F0D1043BF6E700BFB03D0008BD -:1025E000172810B5044629D8FFF77AFFFFF782FFB6 -:1025F0001349F323CB600C23B0FBF3F203FB12006F -:10260000D30143EAC003DBB243F4007343F0020397 -:102610000B610B6943F480330B61FFF761FF2046C8 -:10262000FFF79EFF074B53F8241000F0DDF8FFF78B -:102630007BFF2046BDE81040FFF7BABF002010BD69 -:10264000003C0240B03D00082DE9F84312F00103C0 -:10265000154640D18218B2F1026F3CD22C4B1B6858 -:1026600013F0010337D02B4CFFF744FFF323E36053 -:10267000FFF736FF40F20127032D01D9830713D05E -:10268000244C0F46401A40F20118EB1B0B44012B5F -:1026900000EB0706236924D823F001032361FFF729 -:1026A00043FF0120BDE8F883236923F440732361CD -:1026B00023693B43236151F8046B0660BFF34F8FDE -:1026C000FFF70EFF03689E4208D0236923F0010341 -:1026D0002361FFF729FF0020BDE8F883043D0430A3 -:1026E000CAE723F440732361236943EA08032361A3 -:1026F000B94637F8023B3380BFF34F8FFFF7F0FE48 -:102700003688B9F80030B6B2B342BED0DDE700BFBC -:1027100000380240003C0240084908B50B7828B157 -:1027200053B9FFF7E7FE01230B7008BD23B1BDE8E5 -:1027300008400870FFF7F8BE08BD00BFBA3A002095 -:1027400010B50244064B0439D2B2904200D110BDFC -:10275000441C00B253F8200041F8040FE0B2F4E743 -:1027600050280040104B30B51C6F240407D41C6F58 -:1027700044F400741C671C6F44F400441C670B4C49 -:10278000236843F4807323600244094B0439D2B2B6 -:10279000904200D130BD441C00B251F8045F43F8B0 -:1027A0002050E0B2F4E700BF003802400070004063 -:1027B0005028004007B5012201A90020FFF7C0FF03 -:1027C000019803B05DF804FB13B50446FFF7F2FF70 -:1027D000A04206D002A9012241F8044D0020FFF7D3 -:1027E000C1FF02B010BD000070470000034B1B6822 -:1027F0009B0042BF024B01221A707047743802409E -:102800001D3B0020014B1878704700BF1D3B002086 -:10281000064A536823F001035360EFF309836833DA -:1028200083F30988002383F31188704730EF00E0B9 -:1028300010B5202383F31188104B5B6813F40063F9 -:1028400018D0F1EE103AEFF309844FF0807344F89A -:102850004C3C0B4BDB6844F8083CA4F1680383F361 -:102860000988FFF7F9FB18B1064B44F8503C10BD3E -:10287000054BFAE783F3118810BD00BF00ED00E0BF -:1028800030EF00E031030008340300087047000017 -:10289000FEE70000084A094B09498B4204D3094A64 -:1028A0000021934205D3704752F8040F43F8040BFC -:1028B000F3E743F8041BF4E78C3F0008903D002049 -:1028C000903D0020903D0020836D30B500229D6832 -:1028D000446D11464FF0FF3004EB42130132954234 -:1028E000C3F80019C3F81019C3F80809C3F8001B8E -:1028F000C3F8101BC3F8080BEED24FF00113C4F855 -:102900001C3830BD890141F02001016103699B063B -:10291000FCD4122000F0B4BE204B03EB80022DE962 -:10292000F047D2F80CE05D6DDEF81420461CD2F8BA -:1029300000C005EB063605EB4018516861450BD326 -:10294000D5F83428012303FA00F022EA0000C5F884 -:1029500034081846BDE8F087BEF81040ACEB010320 -:10296000A34228BF2346D8F81849A4B2B3EB840F7A -:1029700010D894681F46A4F1040959F804AFC6F8AA -:1029800000A0042F01D9043FF7E71C440B449460D6 -:102990005360D2E70020BDE8F08700BF203B002055 -:1029A00010B5054C2046FFF729F84FF0A0436365AA -:1029B000024BA36510BD00BF203B0020343E000841 -:1029C0000378012B70B5054650D12A4B446D9842CF -:1029D0001BD1294B5A6B42F080025A635A6D42F068 -:1029E00080025A655A6D5A6942F080025A615A69EA -:1029F00022F080025A610E2143205B69FEF768FCD9 -:102A00001E4BE3601E4BC4F800380023C4F8003EA0 -:102A1000C02323606E6D4FF45023A3633369002BF2 -:102A2000FCDA012333610C2000F02AFE3369DB0756 -:102A3000FCD4122000F024FE3369002BFCDA0026BF -:102A4000A6602846FFF740FF6B68C4F81068DB6893 -:102A5000C4F81468C4F81C684BB90A4BA3614FF062 -:102A6000FF336361A36843F00103A36070BD064BAD -:102A7000F4E700BF203B0020003802404014004033 -:102A800003002002003C30C0083C30C0F8B5446D63 -:102A9000054600212046FFF735FFA96D00234FF0C2 -:102AA00001128F68C4F834384FF00066C4F81C284F -:102AB0004FF0FF3004EB431201339F42C2F800692C -:102AC000C2F8006BC2F80809C2F8080BF2D20B6812 -:102AD0006A6DEB65636210231361166916F01006C8 -:102AE000FBD1122000F0CCFDD4F8003823F4FE63B3 -:102AF000C4F80038A36943F4402343F01003A361F2 -:102B00000923C4F81038C4F814380A4BEB604FF0AE -:102B1000C043C4F8103B084BC4F8003BC4F810692C -:102B2000C4F80039EB6D03F1100243F48013EA6539 -:102B3000A362F8BD103E000840800010426D90F87E -:102B40004E10D2F8003823F4FE6343EA0113C2F8B2 -:102B5000003870472DE9F0410EB200EB86080D46B3 -:102B6000D8F80C100F6807F00303022B50D0032B8A -:102B700050D03D4A3D4F012B18BF1746446D4FEAD8 -:102B8000451E04EB0E030022C3F8102B8A6905F1E1 -:102B9000100C002A40D04A8A05F158035B013A43E1 -:102BA000E2500123D4F81C2803FA0CF31343A64483 -:102BB0004A69C4F81C380023CEF8103905F13F03E8 -:102BC000002A39D00A8A898B9208012988BF4A4392 -:102BD000C16D04EB8303561841EA0242C6652946DB -:102BE0005A602046FFF78EFED8F80C301B8A43EA65 -:102BF00085531F4305F148035B01E7500123D4F8D7 -:102C00001C2803FA05F51543C4F81C58BDE8F081EB -:102C1000174FB3E7174FB1E704EB4613D3F8002B78 -:102C200022F40042C3F8002BD4F81C28012303FA35 -:102C30000CF322EA0303BAE704EB83030E4A5A605B -:102C400004EB461629462046FFF75CFED6F800390D -:102C500023F40043C6F80039D4F81C38012202FAE4 -:102C600005F523EA0505CFE7008000100080041079 -:102C70000080081000800C1000040002826D1268B1 -:102C8000C265FFF721BE00005831436D49015B5812 -:102C900013F4004004D013F4001F14BF01200220DD -:102CA000704700004831436D49015B5813F4004000 -:102CB00004D013F4001F14BF01200220704700004D -:102CC00000EB8101CB68196A0B6813604B68536095 -:102CD0007047000000EB810330B5DD68AA69136816 -:102CE000D36019B9402B84BF402313606B8A1468EA -:102CF000426D1C44013CB4FBF3F46343033323F003 -:102D0000030302EB411043EAC44343F0C043C0F85D -:102D1000103B2B6803F00303012B09B20ED1D2F84C -:102D2000083802EB411013F4807FD0F8003B14BF49 -:102D300043F0805343F00053C0F8003B02EB4112D4 -:102D4000D2F8003B43F00443C2F8003B30BD000022 -:102D50002DE9F041244D6E6D06EB40130446D3F887 -:102D6000087BC3F8087B38070AD5D6F8143819074A -:102D700006D505EB84032146DB6828465B68984747 -:102D8000FA072FD5D6F81438DB072BD505EB8403CB -:102D9000D968CCB98B69488A5E68B6FBF0F200FB53 -:102DA00012628AB91868DA6890420DD2121A83E862 -:102DB0001400202383F311880B482146FFF78AFF74 -:102DC00084F31188BDE8F081012303FA04F26B89D2 -:102DD00023EA02036B81CB6823B121460248BDE898 -:102DE000F0411847BDE8F081203B002000EB810353 -:102DF00070B5DD68436D6C692668E6604A0156BBB4 -:102E00001A444FF40020C2F810092A6802F00302A5 -:102E1000012A0AB20ED1D3F8080803EB421410F4C9 -:102E2000807FD4F8000914BF40F0805040F000507B -:102E3000C4F8000903EB4212D2F8000940F0044044 -:102E4000C2F80009D3F83408012202FA01F1014363 -:102E5000C3F8341870BD19B9402E84BF40202060DB -:102E600020682E8A841940F00050013C1A44B4FBBB -:102E7000F6F440EAC440C6E7F8B504461E48456D7E -:102E800005EB4413D3F80869C3F80869F10717D5AF -:102E9000D5F81038DA0713D500EB8403D9684B69ED -:102EA0001F68DA68974218D2D21B00271A605F6049 -:102EB000202383F311882146FFF798FF87F31188B9 -:102EC000330617D5D5F834280123A340134211D077 -:102ED0002046BDE8F840FFF71FBD012303FA04F2C6 -:102EE000038923EA020303818B68002BE8D0214683 -:102EF0009847E5E7F8BD00BF203B002096482DE944 -:102F0000F84F456D6E69AB691E4016F4805F6E61C7 -:102F1000044605D0FEF7DEFDBDE8F84FFFF788BC9C -:102F2000002E12DAD5F8003E8B489B071EBFD5F85D -:102F3000003E23F00303C5F8003ED5F8043823F023 -:102F40000103C5F80438FEF7EFFD370502D58248C6 -:102F5000FEF7DEFDB0040CD5D5F8083813F0060FE7 -:102F6000EB6823F470530CBF43F4105343F4A053A5 -:102F7000EB60310704D56368DB680BB1764898478E -:102F8000F2025AD4B3020CD5D4F85480DFF8C8A1A9 -:102F900000274FF00109A36D9B68F9B28B4280F0C6 -:102FA0008780F70619D5616D0A6AC2F30A1702F025 -:102FB0000F0302F4F012B2F5802F00F0A180B2F5F9 -:102FC000402F0AD104EB830301F58051DB68186AB6 -:102FD00000231A469F4240F087803003D5F81848F6 -:102FE00013D5E10302D50020FFF7B2FEA20302D5FC -:102FF0000120FFF7ADFE630302D50220FFF7A8FE14 -:10300000270302D50320FFF7A3FE750384D5E0074D -:1030100002D50020FFF730FFA10702D50120FFF7FE -:103020002BFF620702D50220FFF726FF23077FF55B -:1030300073AF0320FFF720FF6EE7D4F85480DFF86A -:1030400018A100274FF00109A36D9B685FFA87FB69 -:103050005B4597D308EB4B13D3F8002902F44022C9 -:10306000B2F5802F22D1D3F80029002A1EDAD3F836 -:10307000002942F09042C3F80029D3F80029002A21 -:10308000FBDB5946606DFFF73DFC228909FA0BF323 -:1030900022EA0303238104EB8B03DB689B6813B1F3 -:1030A0005946504698475846FFF736FC0137CBE75C -:1030B00008EB4112D2F8003B03F44023B3F5802F14 -:1030C00010D1D2F8003B002B0CDA628909FA01F327 -:1030D00022EA0303638104EB8103DB68DB680BB145 -:1030E00050469847013756E79C0708BF0A68072BE8 -:1030F00098BF027003F101039CBF120A013069E717 -:10310000023304EB830201F5805152689069026832 -:10311000D0F808C04068A2EB000E0022104697428B -:103120000AD104EB830463689B699A683A449A6005 -:103130005A6817445F6050E712F0030F08BF086831 -:10314000964588BF8CF8000002F1010284BF000A96 -:103150000CF1010CE3E700BF203B0020436D03EBC3 -:103160004111D1F8003B43F40013C1F8003B704714 -:10317000436D03EB4111D1F8003943F40013C1F85A -:1031800000397047436D03EB4111D1F8003B23F444 -:103190000013C1F8003B7047436D03EB4111D1F8B8 -:1031A000003923F40013C1F80039704730B5039C8F -:1031B0000172043304FB0325C361049B03630021F4 -:1031C000059B00604060C1604261026185610462EC -:1031D00042628162C162436330BD00000022416AE5 -:1031E00041610161C2608262C2626FF00101FEF75B -:1031F000BBBF000003694269934203D1C2680AB1B0 -:1032000000207047181D704703691960C2680132B9 -:10321000C260C269134482690361934224BF436A56 -:1032200003610021FEF794BF38B504460D46E368FC -:103230003BB16269131D1268A3621344E36200206C -:1032400038BD237A33B929462046FEF771FF00289E -:10325000EDDA38BD6FF00100FBE70000C368C2691A -:10326000013BC3604369134482694361934224BFB5 -:10327000436A436100238362036B03B118477047BD -:1032800070B52023044683F31188866A3EB9FFF7A0 -:10329000CBFF054618B186F31188284670BDA36A96 -:1032A000E26A13F8015BA362934202D32046FFF760 -:1032B000D5FF002383F31188EFE700002DE9F84FD5 -:1032C00004460E4690469946202787F3118800252C -:1032D000AA46D4F828B0BBF1000F09D149462046D0 -:1032E000FFF7A2FF20B18BF311882846BDE8F88FC5 -:1032F000A16AE36AA8EB050B5B1A9B4528BF9B46B6 -:10330000BBF1400F1BD9334601F1400251F8040BC9 -:1033100043F8040B9142F9D1A36A40334036A362CB -:103320004035A26AE36A9A4202D32046FFF796FF2D -:103330008AF311884545D8D287F31188C9E730460A -:103340005A46FDF757FDA36A5B445E44A3625D44A1 -:10335000E7E7000010B5029C0172043303FB04216F -:10336000C36100238362C362039B0363049B006009 -:103370004060C460426102618161046242624363F1 -:1033800010BD0000026AC260426A4261026100220E -:103390008262C2626FF00101FEF7E6BE4369026914 -:1033A0009A4203D1C2680AB100207047184650F80B -:1033B000043B0B6070470000C368C2690133C360FF -:1033C0004369134482694361934224BF436A436162 -:1033D0000021FEF7BDBE000038B504460D46E36887 -:1033E0003BB123691A1DA262E2691344E362002023 -:1033F00038BD237A33B929462046FEF799FE0028C6 -:10340000EDDA38BD6FF00100FBE7000003691960D9 -:10341000C268013AC260C26913448269036193427F -:1034200024BF436A036100238362036B03B118471F -:103430007047000070B5202304460E4683F31188C0 -:10344000856A35B91146FFF7C7FF10B185F31188BA -:1034500070BDA36A1E70A36AE26A01339342A3623D -:1034600004D3E16920460439FFF7D0FF002080F340 -:10347000118870BD2DE9F84F04460D4691469A46D5 -:103480004FF0200888F311880026B346A76A4FB989 -:1034900051462046FFF7A0FF20B187F31188304640 -:1034A000BDE8F88FA06AE76AA9EB06033F1A9F42BE -:1034B00028BF1F46402F1BD905F1400355F8042BA8 -:1034C00040F8042B9D42F9D1A36A4033A3624036F1 -:1034D000A26AE36A9A4204D3E16920460439FFF7FD -:1034E00095FF8BF311884E45D9D288F31188CDE72B -:1034F00029463A46FDF77EFCA36A3B443D44A3625D -:103500003E44E5E7026943699A4203D1C3681BB9A7 -:10351000184670470023FBE7836A002BF8D0043B72 -:103520009B1AF5D01360C368013BC360C3691A449A -:10353000836902619A4224BF436A03610023836264 -:103540000123E5E700F034B9034B002258631A6108 -:103550000222DA60704700BF000C0040014B0022DD -:10356000DA607047000C0040014B5863704700BFA1 -:10357000000C0040FEE7000010B5174CFEF7DEFC23 -:10358000FEF700FE802215492046FEF785FD012347 -:1035900044F8180C0374124B124AD96821F4E06104 -:1035A0000904090C0A431049DA60CA6842F08072C3 -:1035B000CA600E490A6842F001020A601022DA77F6 -:1035C000202283F82220002383F3118862B6084862 -:1035D000BDE81040FEF782BD7C330020403E00086D -:1035E00000ED00E00003FA05F0ED00E0001000E05F -:1035F000483E00082DE9F84F1F4CDFF880906569C0 -:1036000004F114074FF00008D9F82430266AAA689C -:103610009E1B96421DD34FF0200AAA68236AD5F854 -:103620000CB0134423622B68BB425F60A6EB02061A -:103630006361C5F80C8001D1FFF790FF88F3118812 -:103640002869D8478AF311886569AB689E42E4D23D -:10365000DAE76269BA420CD0916823628E1B9660E9 -:10366000A86802282CBF1818981CBDE8F84FFFF76F -:103670007BBFBDE8F88F00BF54330020000C004032 -:10368000034B59685A68521A9042FBD8704700BFE2 -:10369000001000E04B6843608B688360CB68C360B8 -:1036A0000B6943614B6903628B6943620B6803607A -:1036B0007047000008B5224B22481A6940F2FF11FA -:1036C0000A431A611A6922F4FF7222F001021A6198 -:1036D0001A691A6B0A431A631A6D0A431A651A4A61 -:1036E0001B6D1146FFF7D6FF184802F11C01FFF7CA -:1036F000D1FF174802F13801FFF7CCFF154802F15E -:103700005401FFF7C7FF144802F17001FFF7C2FF31 -:10371000124802F18C01FFF7BDFF114802F1A80128 -:10372000FFF7B8FF0F4802F1C401FFF7B3FF0E48DF -:1037300002F1E001FFF7AEFFBDE8084000F0A4B8D9 -:103740000038024000000240683E000800040240C9 -:1037500000080240000C0240001002400014024029 -:1037600000180240001C02400020024008B500F092 -:10377000FFF9FFF701FFFFF739F8BDE80840FEF752 -:103780000BBE000070470000084B1A69920710B585 -:1037900008D500241C61202383F31188FFF72AFF3A -:1037A00084F31188BDE81040FFF742B8000C0040D8 -:1037B000104B1A6C42F008021A641A6E42F00802AA -:1037C0001A660D4A1B6E936843F0080393600B4B17 -:1037D00053229A624FF0FF32DA6200229A615A63F2 -:1037E000DA605A6001225A6108211A603220FDF71E -:1037F0006FBD00BF00380240002004E0000C004014 -:103800001F4B1A696FEAC2526FEAD2521A611A69E3 -:10381000C2F308021A614FF0FF301A695A69586101 -:1038200000215A6959615A691A6A62F080521A6213 -:103830001A6A02F080521A621A6A5A6A58625A6AFE -:1038400059625A6A1A6C42F080521A641A6E42F037 -:1038500080521A661A6E0B4A106840F4807010602D -:10386000186F00F44070B0F5007F1EBF4FF4803039 -:1038700018671967536823F40073536000F058B950 -:103880000038024000700040324B4FF080521A6402 -:10389000314A4FF4404111601A6842F001021A6047 -:1038A0001A689207FCD59A6822F003029A60294BA5 -:1038B00019469A6812F00C02FBD1186800F0F90062 -:1038C00018609A601A6842F480321A600B689B0391 -:1038D000FCD54B6F43F001034B671E4B5A6F9007AB -:1038E000FCD51E4A5A601A6842F080721A601A4A61 -:1038F00053685904FCD5174B1A689201FCD5184A35 -:103900009A600322C3F88C20164B1A68164B9A4211 -:10391000164B1BD1164A1168164A914216D140F235 -:1039200005121A600B4B9A6842F002029A609A687C -:1039300002F00C02082AFAD15A6C42F480425A640E -:103940005A6E42F480425A665B6E704740F20572CE -:10395000E7E700BF003802400070004018544007FD -:1039600000948838002004E011640020003C0240EC -:1039700000ED00E041C20F41084A08B553691168E3 -:103980000B4003F00103536123B1054A13680BB1E7 -:1039900050689847BDE80840FEF74ABF003C014028 -:1039A0009C250020084A08B5536911680B4003F0B4 -:1039B0000203536123B1054A93680BB1D06898475D -:1039C000BDE80840FEF734BF003C01409C250020C4 -:1039D000084A08B5536911680B4003F004035361AA -:1039E00023B1054A13690BB150699847BDE80840F7 -:1039F000FEF71EBF003C01409C250020084A08B588 -:103A0000536911680B4003F00803536123B1054A61 -:103A100093690BB1D0699847BDE80840FEF708BF2D -:103A2000003C01409C250020084A08B553691168F4 -:103A30000B4003F01003536123B1054A136A0BB125 -:103A4000506A9847BDE80840FEF7F2BE003C0140CE -:103A50009C250020174B10B55C691A68144004F4CB -:103A600078725A61A30604D5134A936A0BB1D06ADF -:103A70009847600604D5104A136B0BB1506B9847FA -:103A8000210604D50C4A936B0BB1D06B9847E20525 -:103A900004D5094A136C0BB1506C9847A30504D5A3 -:103AA000054A936C0BB1D06C9847BDE81040FEF707 -:103AB000BFBE00BF003C01409C2500201A4B10B542 -:103AC0005C691A68144004F47C425A61620504D5AA -:103AD000164A136D0BB1506D9847230504D5134A50 -:103AE000936D0BB1D06D9847E00404D50F4A136E67 -:103AF0000BB1506E9847A10404D50C4A936E0BB1DC -:103B0000D06E9847620404D5084A136F0BB1506F0A -:103B10009847230404D5054A936F0BB1D06F98479B -:103B2000BDE81040FEF784BE003C01409C2500200B -:103B3000062108B50846FDF7CBFB06210720FDF757 -:103B4000C7FB06210820FDF7C3FB06210920FDF76E -:103B5000BFFB06210A20FDF7BBFB06211720FDF75E -:103B6000B7FB06212820BDE80840FDF7B1BB0000E7 -:103B700008B5FFF745FEFDF727FAFDF74FFDFDF706 -:103B80003BFFFDF70FFEFFF7FDFDBDE80840FFF727 -:103B9000D9BC0000034611F8012B03F8012B002AC1 -:103BA000F9D17047121012131211000053544D3303 -:103BB00032463F3F3F00000001203300001041012A -:103BC00001105A01031059010710310100000000D3 -:103BD000AC3B00083F000000130400000C3C000850 -:103BE0003F00000019040000163C00083F000000E0 -:103BF00021040000203C00083F0000009433002016 -:103C00001C260020842A0020EC2E002053544D3323 -:103C100032463430780053544D33324634327800D3 -:103C200053544D3332463434365858000096000011 -:103C30000000000000000000000000000000000084 -:103C400000000000E5150008D11500080D16000859 -:103C5000F915000805160008F1150008DD15000823 -:103C6000C915000819160008000000001D170008FB -:103C70000917000845170008311700083D1700080C -:103C8000291700081517000801170008A1170008D8 -:103C90000000000001000000000000000200000021 -:103CA0000000000049190008B11900084000400058 -:103CB0002C3800203C3800200200000000000000EA -:103CC0000300000000000000F519000800000000DB -:103CD000100000004C38002000000000010000002F -:103CE00000000000203B0020010102004865782F01 -:103CF00050726F6669434E430043756265426C6162 -:103D0000636B2B2D424C002553455249414C2500F5 -:103D100039230008A1220008B51800081D23000857 -:103D200043000000283D000809024300020100C0D2 -:103D300032090400000102020100052400100105FF -:103D40002401000104240202052406000107058263 -:103D5000030800FF09040100020A00000007050132 -:103D60000240000007058102400000001200000030 -:103D7000743D00081201100102000040AE2D011137 -:103D800000020102030100000403090425424F411F -:103D90005244250043756265426C61636B2B0030B1 -:103DA00031323334353637383941424344454600A1 -:103DB0000040000000400000004000000040000003 -:103DC00000000100000002000000020000000200EC -:103DD00000000200000002000000020000000200DB -:103DE00000400000004000000040000000400000D3 -:103DF00000000100000002000000020000000200BC -:103E000000000200000002000000020000000200AA -:103E1000000000003D1B00081D1E0008C91E000810 -:103E200040004000803B0020803B0020010000005B -:103E3000903B0020800000004001000003000000D3 -:103E40006D61696E00000000603E0008983B002034 -:103E5000903D0020010000007535000800000000C2 -:103E600069646C65000000000000812A0002000007 -:103E7000AAAAAAAA00000000FFFF0000000000009C -:103E800000A00A000000000000000000AAAAAAAAE0 -:103E900000000000FFFF0000000000000000000024 -:103EA0001400005400000000AAAAAAAA140000549A -:103EB000FFFF0000000000000000000080699A0180 -:103EC00000000000AAAA8AAA40555501FFFF000081 -:103ED0000070700777700000408102010000000050 -:103EE000AAAAAAAA00410100F7FF00000000008072 -:103EF000080000000000000000000000AAAAAAAA12 -:103F000000000000FFFF00000000000000000000B3 -:103F10000000000000000000AAAAAAAA00000000F9 -:103F2000FFFF000000000000000000000000000093 -:103F3000000000000A000000000000000300000074 -:103F40000000000000000000000000000000000071 -:103F50000000000000000000000000000000000061 -:103F60000000000000000000FF00960000000008B4 -:103F700004000000883D0008000000000000000070 -:103F80000000000000000000000000000000000031 +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F074FA01 +:1002500003F074F94FF055301F491B4A91423CBFDF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F052FA03F0A2F96E +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F03ABA000600200022002031 +:1002D0000000000808ED00E00000002000060020FB +:1002E000A03E0008002200204C22002050220020C6 +:1002F00020310020E0010008E0010008E0010008D2 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F098FDFEE701F063 +:1003300027FD00DFFEE7000038B500F0DFFB02F02C +:10034000CFF940B1164B6FF03F01002259720F21D7 +:100350001A729972DA7202F0A9F9054602F0E2F90E +:100360000446C8B90F4B9D4218D001339D4218BFB7 +:10037000044641F2883504BF01240025002002F024 +:100380009FF90CB100F076F800F018FD284600F057 +:10039000C1F800F06FF8F9E70025EFE70546EDE753 +:1003A00000220020010007B008B500F073FBA0F1A7 +:1003B00020035842584108BD07B541F212030221FB +:1003C00001A8ADF8043000F083FB03B05DF804FB36 +:1003D00038B5302383F31188174803680BB101F057 +:1003E00009FE164A144800234FF47A7101F0F8FD13 +:1003F000002383F31188124C236813B12368013B57 +:100400002360636813B16368013B63600D4D2B7813 +:1004100033B963687BB9022000F03AFC3223636091 +:100420002B78032B07D163682BB9022000F030FC36 +:100430004FF47A73636038BD50220020D103000866 +:100440007023002068220020084B187003280CD865 +:10045000DFE800F008050208022000F00FBC0220CF +:1004600000F002BC024B00225A6070476822002054 +:1004700070230020234B244A10B51C461968013113 +:100480003FD004339342F9D16268A24239D31F4B63 +:100490009B6803F1006303F580439A4231D2002048 +:1004A00000F046FB0220FFF7CFFF194B1A6C002229 +:1004B0001A64196E1A66196E596C5A64596E5A6626 +:1004C0005A6E5A6942F080025A615A6922F08002DB +:1004D0005A615A691A6942F000521A611A6922F087 +:1004E00000521A611B6972B64FF0E0233021C3F845 +:1004F000084DD4E9003281F311889D4683F30888C2 +:10050000104710BD004000082040000800220020D5 +:10051000003802402DE9F04F93B0AA4B0090202202 +:10052000FF210AA89D6800F0F3FBA74A1378A3B93E +:10053000A648012103601170302383F311880368FA +:100540000BB101F057FDA24AA04800234FF47A7185 +:1005500001F046FD002383F31188009B13B19D4BEE +:10056000009A1A609C4A009C1378032B1EBF00233C +:100570001370984A4FF0000A18BF5360D34656468E +:10058000D146012000F07AFB24B1924B1B68002B6E +:1005900000F01182002000F07DFA0390039B002BF5 +:1005A000F2DB012000F060FB039B213B162BE8D817 +:1005B00001A252F823F000BF150600083D0600080E +:1005C000D10600088305000883050008830500089C +:1005D0005B0700082B09000845080008A708000869 +:1005E000CF080008F508000883050008070900087F +:1005F0008305000879090008B5060008830500088E +:10060000BD09000821060008B5060008830500089A +:10061000A70800080220FFF7C7FE002840F0F58178 +:10062000009B0221BAF1000F08BF1C4605A841F249 +:100630001233ADF8143000F04BFAA2E74FF47A70A1 +:1006400000F028FA071EEBDB0220FFF7ADFE0028C2 +:10065000E6D0013F052F00F2DA81DFE807F0030A58 +:100660000D10133605230593042105A800F030FA78 +:1006700017E054480421F9E758480421F6E75848A0 +:100680000421F3E74FF01C08404600F053FA08F14C +:1006900004080590042105A800F01AFAB8F12C0FFF +:1006A000F2D1012000FA07F747EA0B0B5FFA8BFB48 +:1006B0004FF0000900F078FB26B10BF00B030B2B79 +:1006C00008BF0024FFF778FE5BE746480421CDE72A +:1006D000002EA5D00BF00B030B2BA1D10220FFF7AE +:1006E00063FE074600289BD0012000F021FA02207B +:1006F000FFF7AAFE00261FFA86F8404600F028FA07 +:10070000044690B10021404600F032FA013600283C +:10071000F1D1BA46044641F21213022105A8ADF800 +:1007200014303E4600F0D4F92BE70120FFF78CFE91 +:100730002546244B9B68AB4207D9284600F0FAF9BE +:10074000013040F067810435F3E7234B00251D702D +:10075000204BBA465D603E46ACE7002E3FF460AFEA +:100760000BF00B030B2B7FF45BAF0220FFF76CFE4B +:10077000322000F08FF9B0F10008FFF651AF18F009 +:1007800003077FF44DAF0F4A926808EB05039342CD +:100790003FF646AFB8F5807F3FF742AF124B01936B +:1007A000B84523DD4FF47A7000F074F90390039A92 +:1007B000002AFFF635AF019B039A03F8012B01379E +:1007C000EDE700BF002200206C2300205022002013 +:1007D000D10300087023002068220020042200209A +:1007E000082200200C2200206C220020C820FFF7E5 +:1007F000DBFD074600283FF413AF1F2D11D8C5F1CC +:10080000200242450AAB25F0030028BF4246834937 +:100810000192184400F056FA019A8048FF2100F036 +:1008200077FA4FEAA8037D490193C8F38702284667 +:1008300000F076FA064600283FF46DAF019B05EB09 +:10084000830537E70220FFF7AFFD00283FF4E8AE4D +:1008500000F0BAF900283FF4E3AE0027B846704B29 +:100860009B68BB4218D91F2F11D80A9B01330ED0A9 +:1008700027F0030312AA134453F8203C0593404683 +:10088000042205A900F0F6FA04378046E7E7384667 +:1008900000F050F90590F2E7CDF81480042105A886 +:1008A00000F016F906E70023642104A8049300F081 +:1008B00005F900287FF4B4AE0220FFF775FD00288B +:1008C0003FF4AEAE049800F067F90590E6E7002328 +:1008D000642104A8049300F0F1F800287FF4A0AE8E +:1008E0000220FFF761FD00283FF49AAE049800F063 +:1008F00063F9EAE70220FFF757FD00283FF490AEC6 +:1009000000F072F9E1E70220FFF74EFD00283FF406 +:1009100087AE05A9142000F06DF904210746049064 +:1009200004A800F0D5F83946B9E7322000F0B2F853 +:10093000071EFFF675AEBB077FF472AE384A9268A9 +:1009400007EB090393423FF66BAE0220FFF72CFD45 +:1009500000283FF465AE27F003074F44B9453FF444 +:10096000A9AE484600F0E6F80421059005A800F07D +:10097000AFF809F10409F1E74FF47A70FFF714FDBD +:1009800000283FF44DAE00F01FF9002844D00A9B28 +:1009900001330BD008220AA9002000F0C1F9002879 +:1009A0003AD02022FF210AA800F0B2F9FFF704FD97 +:1009B0001C4801F059FA13B0BDE8F08F002E3FF447 +:1009C0002FAE0BF00B030B2B7FF42AAE0023642118 +:1009D00005A8059300F072F8074600287FF420AEC2 +:1009E0000220FFF7E1FC804600283FF419AEFFF734 +:1009F000E3FC41F2883001F037FA059800F018FA6C +:100A0000464600F0D1F93C46BBE5064652E64FF0BB +:100A1000000905E6BA467EE637467CE66C220020F1 +:100A200000220020A08601002DE9F84F4FF47A73D0 +:100A3000DFF85880DFF8589006460D4602FB03F7B2 +:100A4000002498F900305A1C5FFA84FA01D0A342BE +:100A500012D159F8240003682A46D3F820B0314651 +:100A60003B46D847854207D1074B012083F800A0B9 +:100A7000BDE8F88F0124E4E7002CFBD04FF4FA70B6 +:100A800001F0F2F90020F3E7B82300201022002043 +:100A90001422002007B50023024601210DF10700B2 +:100AA0008DF80730FFF7C0FF20B19DF8070003B0B5 +:100AB0005DF804FB4FF0FF30F9E700000A4608B587 +:100AC0000421FFF7B1FF80F00100C0B2404208BD31 +:100AD00030B4074B0A461978064B53F82140236877 +:100AE000DD69054B0146AC46204630BC604700BF7F +:100AF000B823002014220020A086010070B501F068 +:100B0000D3FC094E094D3080002428683388834285 +:100B100008D901F0C3FC2B6804440133B4F5804FBD +:100B20002B60F2D370BD00BFBA23002078230020D1 +:100B300001F070BD00F1006000F580400068704772 +:100B400000F10060920000F5804001F0FBBC000065 +:100B5000054B1A68054B1B889B1A834202D9104427 +:100B600001F09CBC0020704778230020BA230020AD +:100B700038B5084D044629B128682044BDE83840FE +:100B800001F0ACBC2868204401F090FC0028F3D0B0 +:100B900038BD00BF7823002010F003030AD1B0F560 +:100BA000047F05D200F10050A0F51040D0F80038C5 +:100BB000184670470023FBE700F10050A0F51040F5 +:100BC000D0F8100A70470000064991F8243033B17C +:100BD0000023086A81F824300822FFF7B1BF012002 +:100BE000704700BF7C230020014B1868704700BF8E +:100BF000002004E070B5194B1D68194B0138C5F38E +:100C00000B0408442D0C04221E88A6420BD15C68FC +:100C10000A46013C824213460FD214F9016F4EB1CD +:100C200002F8016BF6E7013A03F10803ECD18142C7 +:100C30000B4602D22C2203F8012B0A4A05241688FF +:100C4000AE4204D1984284BF967803F8016B013C10 +:100C500002F10402F3D1581A70BD00BF002004E075 +:100C6000503B00083C3B0008022802BF024B4FF4F7 +:100C700080529A61704700BF00100240022802BFF4 +:100C8000024B4FF080529A61704700BF0010024043 +:100C9000022801BF024A536983F4805353617047AD +:100CA0000010024070B504464FF47A764CB1412CE6 +:100CB000254628BF412506FB05F001F0D5F8641B49 +:100CC000F4E770BD10B50023934203D0CC5CC4544C +:100CD0000133F9E710BD000010B5013810F9013FEC +:100CE0003BB191F900409C4203D11AB10131013A64 +:100CF000F4E71AB191F90020981A10BD1046FCE7EC +:100D000003460246D01A12F9011B0029FAD1704796 +:100D100002440346934202D003F8011BFAE77047EE +:100D20002DE9F8431F4D144695F8242007468846C0 +:100D300052BBDFF870909CB395F824302BB9202279 +:100D4000FF2148462F62FFF7E3FF95F82400C0F12A +:100D50000802A24228BF2246D6B24146920005EBC5 +:100D60008000FFF7AFFF95F82430A41B1E44F6B2B5 +:100D7000082E17449044E4B285F82460DBD1FFF7D5 +:100D800023FF0028D7D108E02B6A03EB82038342BC +:100D9000CFD0FFF719FF0028CBD10020BDE8F883A2 +:100DA0000120FBE77C230020024B1A78024B1A70CB +:100DB000704700BFB82300201022002038B5174C20 +:100DC000174D204600F0B6FB2946204600F0DEFB1A +:100DD0002D686A6D936B23F4002393634FF47A704C +:100DE000FFF760FF0F49284600F0D6FC6A6D0E4DF4 +:100DF000936B28680D4943F400239363A0424FF49A +:100E0000E1330B6001D000F0F5FA6868A04204D02D +:100E1000BDE83840054900F0EDBA38BD98280020FB +:100E20005C3C0008643C000814220020A42300203D +:100E300070B50C4B0C4D1E780C4B55F826209A4281 +:100E400004460DD00A4B002114221846FFF760FF1C +:100E50000460014655F82600BDE8704000F0CABAAB +:100E600070BD00BFB8230020142200209828002065 +:100E7000A423002030B5094D0A4491420DD011F849 +:100E8000013B5840082340F30004013B2C4013F081 +:100E9000FF0384EA5000F6D1EFE730BD2083B8EDC0 +:100EA000026843681143016003B1184770470000AE +:100EB000024AD36843F0C003D36070470044004047 +:100EC00010B5054C054A0021204600F071FA044A8D +:100ED000044BC4E9972310BDBC230020B10E0008C9 +:100EE0000044004080DE8002234A037C002918BFB2 +:100EF0000A46012B30B5C0F868220CD11F4B98422E +:100F000009D11F4B196C41F400311964196E41F479 +:100F1000003119661B6EB2F904501468D0F86032C3 +:100F2000D0F85C12002D03EB5403B3FBF4F3BEBF07 +:100F300023F0070503F0070343EA450394888B6019 +:100F4000D38843F040030B61138943F001034B61E5 +:100F500044F4045343F02C03CB6004F4A054002366 +:100F60000B60B4F5806F0B684B680CBF7F23FF23C9 +:100F700080F8643230BD00BF703B0008BC23002005 +:100F8000003802402DE9F041D0F85C62F768336820 +:100F9000DA0504469DB20DD5302383F311884FF452 +:100FA00080610430FFF77CFF6FF4807333600023AF +:100FB00083F31188302383F3118804F1040815F0BA +:100FC0002F033AD183F31188380615D5290613D596 +:100FD000302383F3118804F1380000F065F900280C +:100FE0004EDA0821201DFFF75BFF4FF67F733B4071 +:100FF000F360002383F311887A0616D56B0614D5A7 +:10100000302383F31188D4E913239A420AD1236C45 +:1010100043B127F040073F041021201D3F0CFFF78C +:101020003FFFF760002383F31188D4F86822D36868 +:1010300043B3BDE8F041106918472B0714D015F0F1 +:10104000080F0CBF00214FF48071E80748BF41F042 +:101050002001AA0748BF41F040016B0748BF41F09B +:1010600080014046FFF71CFFAD06736805D594F874 +:1010700064122046194000F0CBF93568ADB29EE706 +:101080007060B6E7BDE8F081F8B51546826806697C +:10109000AA420B46816938BF8568761AB542044674 +:1010A0000BD218462A46FFF70DFEA3692B44A36115 +:1010B000A3685B1BA3602846F8BD0CD918463246CE +:1010C000FFF700FEAF1BE1683A463044FFF7FAFD38 +:1010D000E3683B44EBE718462A46FFF7F3FDE36875 +:1010E000E5E7000083689342F7B51546044638BF2C +:1010F0008568D0E90460361AB5420BD22A46FFF75C +:10110000E1FD63692B446361A36828465B1BA36010 +:1011100003B0F0BD0DD932460191FFF7D3FD01991F +:10112000E068AF1B3A463144FFF7CCFDE3683B442F +:10113000E9E72A46FFF7C6FDE368E4E710B50A448D +:101140000024C361029B8460C0E90000C0E905116E +:10115000C1600261036210BD08B5D0E90532934257 +:1011600001D1826882B98268013282605A1C426170 +:101170001970D0E904329A4224BFC3684361002148 +:1011800000F08EFE002008BD4FF0FF30FBE70000AE +:1011900070B5302304460E4683F31188A568A5B1C7 +:1011A000A368A269013BA360531CA361157822695F +:1011B000934224BFE368A361E3690BB120469847DB +:1011C000002383F31188284607E03146204600F0CB +:1011D00057FE0028E2DA85F3118870BD2DE9F74F3C +:1011E00004460E4617469846D0F81C904FF0300A39 +:1011F0008AF311884FF0000B154665B12A46314637 +:101200002046FFF741FF034660B94146204600F003 +:1012100037FE0028F1D0002383F31188781B03B038 +:10122000BDE8F08FB9F1000F03D001902046C84708 +:10123000019B8BF31188ED1A1E448AF31188DCE7B9 +:10124000C0E90511C160C3611144009B8260C0E91F +:101250000000016103627047F8B504460D4616466A +:10126000302383F31188A768A7B1A368013BA3606B +:1012700063695A1C62611D70D4E904329A4224BF2A +:10128000E3686361E3690BB120469847002080F36F +:10129000118807E03146204600F0F2FD0028E2DA2E +:1012A00087F31188F8BD0000D0E905239A4210B5F4 +:1012B00001D182687AB98268013282605A1C8261E7 +:1012C0001C7803699A4224BFC3688361002100F03F +:1012D000E7FD204610BD4FF0FF30FBE72DE9F74F4B +:1012E00004460E4617469846D0F81C904FF0300A38 +:1012F0008AF311884FF0000B154665B12A46314636 +:101300002046FFF7EFFE034660B94146204600F055 +:10131000B7FD0028F1D0002383F31188781B03B0B8 +:10132000BDE8F08FB9F1000F03D001902046C84707 +:10133000019B8BF31188ED1A1E448AF31188DCE7B8 +:10134000026843681143016003B118477047000009 +:101350001430FFF743BF00004FF0FF331430FFF7A6 +:101360003DBF00003830FFF7B9BF00004FF0FF333A +:101370003830FFF7B3BF00001430FFF709BF00009B +:101380004FF0FF311430FFF703BF00003830FFF794 +:1013900063BF00004FF0FF323830FFF75DBF000041 +:1013A000012914BF6FF0130000207047FFF788BDBC +:1013B00037B515460E4A026000224260C0E902229B +:1013C0000122044602740B46009000F15C014FF4C8 +:1013D00080721430FFF7B2FE00942B464FF48072F7 +:1013E00004F5AE7104F13800FFF72AFF03B030BDF9 +:1013F000843B000810B53023044683F31188FFF7BF +:1014000073FD02232374002080F3118810BD0000B7 +:1014100038B5C36904460D461BB904210844FFF7DB +:101420008FFF294604F11400FFF796FE002806DA24 +:10143000201D4FF40061BDE83840FFF781BF38BD83 +:10144000026843681143016003B118477047000008 +:1014500013B5446BD4F894341A681178042915D163 +:10146000217C022912D11979128901238B40134260 +:101470000CD101A904F14C0001F016FFD4F89444FA +:10148000019B21790246206800F0D0F902B010BD1E +:10149000143001F099BE00004FF0FF33143001F01A +:1014A00093BE00004C3001F06BBF00004FF0FF33E3 +:1014B0004C3001F065BF0000143001F067BE000041 +:1014C0004FF0FF31143001F061BE00004C3001F0EC +:1014D00037BF00004FF0FF324C3001F031BF000049 +:1014E0000020704710B5D0F894341A681178042998 +:1014F000044617D1017C022914D15979528901235C +:101500008B4013420ED1143001F0FAFD024648B16F +:10151000D4F894444FF4807361792068BDE810409A +:1015200000F072B910BD0000406BFFF7DBBF000098 +:10153000704700007FB5124B036000234360C0E991 +:101540000233012502260F4B0574044602900193D5 +:1015500000F18402294600964FF48073143001F0A4 +:10156000ABFD094B0294CDE9006304F523724FF4FF +:101570008073294604F14C0001F072FE04B070BD86 +:10158000AC3B000829150008511400080B683022F4 +:1015900082F311880A7903EB820290614A79093259 +:1015A00043F822008A7912B103EB82039861022387 +:1015B000C0F894140374002080F311887047000071 +:1015C00038B5037F044613B190F85430ABB9201DF1 +:1015D00001250221FFF734FF04F1140025776FF095 +:1015E000010100F069FC84F8545004F14C006FF0E4 +:1015F0000101BDE8384000F05FBC38BD10B50121E5 +:1016000004460430FFF71CFF0023237784F854308E +:1016100010BD000038B504460025143001F064FD0B +:1016200004F14C00257701F033FE201D84F854505E +:101630000121FFF705FF2046BDE83840FFF752BF04 +:1016400090F8443003F06003202B07D190F8452038 +:10165000212A4FF0000303D81F2A06D80020704724 +:10166000222AFBD1C0E90E3303E0034A826307223A +:10167000C2630364012070471C22002037B5D0F8F4 +:1016800094341A681178042904461AD1017C02297D +:1016900017D11979128901238B40134211D100F11E +:1016A0004C05284601F0B4FE58B101A9284601F0C6 +:1016B000FBFDD4F89444019B21790246206800F098 +:1016C000B5F803B030BD0000F0B500EB810385B084 +:1016D0009E6904460D46FEB1302383F3118804EB66 +:1016E0008507301D0821FFF7ABFEFB685B691B68AF +:1016F00006F14C001BB1019001F0E4FD019803A933 +:1017000001F0D2FD024648B1039B2946204600F075 +:101710008DF8002383F3118805B0F0BDFB685A698A +:101720001268002AF5D01B8A013B1340F1D104F165 +:101730004402EAE7093138B550F82140DCB13023E2 +:1017400083F31188D4F894241368527903EB82034D +:10175000DB689B695D6845B104216018FFF770FE86 +:10176000294604F1140001F0D5FC2046FFF7BAFE2B +:10177000002383F3118838BD7047000001F034B8AE +:10178000012303700023C0E90133C3618362036254 +:10179000C36243620363704738B50446302383F362 +:1017A00011880025C0E90355C0E90555416001F0E5 +:1017B0002BF80223237085F31188284638BD0000DA +:1017C00070B500EB810305465069DA600E46144699 +:1017D00018B110220021FFF79BFAA06918B110225E +:1017E0000021FFF795FA31462846BDE8704001F028 +:1017F000D5B80000826802F0011282600022C0E9C0 +:101800000422826101F056B9F0B400EB81044789EB +:10181000E4680125A4698D403D4345812360002390 +:10182000A2606360F0BC01F071B90000F0B400EB9D +:1018300081040789E468012564698D403D43058181 +:1018400023600023A2606360F0BC01F0EBB90000EC +:1018500070B50223002504460370C0E90255C0E9B3 +:101860000455C564856180F8345001F033F863682D +:101870001B6823B129462046BDE87040184770BD5B +:101880000378052B10B504460AD080F850300523A4 +:10189000037043681B680BB1042198470023A360C1 +:1018A00010BD00000178052906D190F8502043684A +:1018B00002701B6803B118477047000070B590F8BC +:1018C0003430044613B1002380F8343004F144026C +:1018D000204601F011F963689B68B3B994F844306D +:1018E00013F0600535D00021204601F0B1FB002146 +:1018F000204601F0A3FB63681B6813B10621204654 +:101900009847062384F8343070BD20469847002855 +:10191000E4D0B4F84A30E26B9A4288BFE36394F9AA +:101920004430E56B002B4FF0300380F20381002D33 +:1019300000F0F280092284F8342083F3118800211A +:10194000D4E90E232046FFF771FF002383F31188AB +:10195000DAE794F8452003F07F0343EA022340F2DC +:101960000232934200F0C58021D8B3F5807F48D081 +:101970000DD8012B3FD0022B00F09380002BB2D169 +:1019800004F14C02A2630222E2632364C1E7B3F5CF +:10199000817F00F09B80B3F5407FA4D194F846305E +:1019A000012BA0D1B4F84C3043F0020332E0B3F580 +:1019B000006F4DD017D8B3F5A06F31D0A3F5C06339 +:1019C000012B90D8636894F846205E6894F847101D +:1019D000B4F848302046B047002884D04368A36359 +:1019E0000368E3631AE0B3F5106F36D040F60242A5 +:1019F00093427FF478AF5C4BA3630223E36300233D +:101A0000C3E794F84630012B7FF46DAFB4F84C3047 +:101A100023F00203C4E90E55A4F84C30256478E79E +:101A2000B4F84430B3F5A06F0ED194F8463084F882 +:101A30004E30204600F0A6FF63681B6813B10121F9 +:101A400020469847032323700023C4E90E339CE704 +:101A500004F14F03A3630123C3E72378042B10D1C0 +:101A6000302383F311882046FFF7C4FE85F31188E5 +:101A70000321636884F84F5021701B680BB1204626 +:101A8000984794F84630002BDED084F84F3004237A +:101A9000237063681B68002BD6D00221204698472C +:101AA000D2E794F848301D0603F00F0120460AD50E +:101AB00001F014F8012804D002287FF414AF2B4B56 +:101AC0009AE72B4B98E700F0FBFFF3E794F84630DA +:101AD000002B7FF408AF94F8483013F00F01B3D017 +:101AE0001A06204602D501F0C7FAADE701F0BAFAAE +:101AF000AAE794F84630002B7FF4F5AE94F848300E +:101B000013F00F01A0D01B06204602D501F0A0FA69 +:101B10009AE701F093FA97E7142284F8342083F3CC +:101B200011882B462A4629462046FFF76DFE85F38D +:101B30001188E9E65DB1152284F8342083F3118819 +:101B40000021D4E90E232046FFF75EFEFDE60B22BE +:101B500084F8342083F311882B462A4629462046F0 +:101B6000FFF764FEE3E700BFDC3B0008D43B00085E +:101B7000D83B000838B590F834300446002B3ED0EE +:101B8000063BDAB20F2A34D80F2B32D8DFE803F045 +:101B9000373131082232313131313131313137375A +:101BA000C56BB0F84A309D4214D2C3681B8AB5FB9E +:101BB000F3F203FB12556DB9302383F311882B46E2 +:101BC0002A462946FFF732FE85F311880A2384F856 +:101BD00034300EE0142384F83430302383F311883A +:101BE00000231A4619462046FFF70EFE002383F312 +:101BF000118838BD036C03B198470023E7E7002143 +:101C0000204601F025FA0021204601F017FA63680A +:101C10001B6813B10621204698470623D7E700002A +:101C200010B590F83430142B044629D017D8062B61 +:101C300005D001D81BB110BD093B022BFBD80021F8 +:101C4000204601F005FA0021204601F0F7F963680B +:101C50001B6813B1062120469847062319E0152B6F +:101C6000E9D10B2380F83430302383F3118800232B +:101C70001A461946FFF7DAFD002383F31188DAE7E5 +:101C8000C3689B695B68002BD5D1036C03B198478F +:101C9000002384F83430CEE700230375826803699B +:101CA0001B6899689142FBD25A68036042601060D9 +:101CB0005860704700230375826803691B68996840 +:101CC0009142FBD85A6803604260106058607047C8 +:101CD00008B50846302383F311880B7D032B05D00C +:101CE000042B0DD02BB983F3118808BD8B6900221A +:101CF0001A604FF0FF338361FFF7CEFF0023F2E756 +:101D0000D1E9003213605A60F3E70000FFF7C4BF67 +:101D1000054BD9680875186802681A60536001227B +:101D20000275D860FEF7EEBA2826002030B50C4BBD +:101D3000DD684B1C87B004460FD02B46094A684625 +:101D400000F04EF92046FFF7E3FF009B13B1684611 +:101D500000F050F9A86907B030BDFFF7D9FFF9E7E7 +:101D600028260020D11C0008044B1A68DB68906804 +:101D70009B68984294BF00200120704728260020CD +:101D8000084B10B51C68D86822681A60536001229D +:101D90002275DC60FFF78EFF01462046BDE810404B +:101DA000FEF7B0BA2826002038B5074C0749084886 +:101DB000012300252370656001F068FB0223237076 +:101DC00085F3118838BD00BF90280020E43B00084F +:101DD0002826002000F044B9034A516853685B1A72 +:101DE0009842FBD8704700BF001000E08B600223D0 +:101DF00008618B82084670478368A3F1840243F828 +:101E0000142C026943F8442C426943F8402C094AD7 +:101E100043F8242CC26843F8182C022203F80C2C37 +:101E2000002203F80B2C044A43F8102CA3F12000E5 +:101E3000704700BF1D0300082826002008B5FFF7E3 +:101E4000DBFFBDE80840FFF761BF0000024BDB6825 +:101E500098610F20FFF75CBF28260020302383F312 +:101E60001188FFF7F3BF000008B50146302383F364 +:101E700011880820FFF75AFF002383F3118808BD5B +:101E8000064BDB6839B1426818605A6013604360E2 +:101E90000420FFF74BBF4FF0FF307047282600208B +:101EA0000368984206D01A6802605060996118462B +:101EB000FFF72CBF7047000038B504460D46206878 +:101EC000844200D138BD036823605C608561FFF700 +:101ED0001DFFF4E710B503689C68A2420CD85C684B +:101EE0008A600B604C602160596099688A1A9A6018 +:101EF0004FF0FF33836010BD1B68121BECE700003E +:101F00000A2938BF0A2170B504460D460A26601911 +:101F100001F0B4FA01F09CFA041BA54203D8751C29 +:101F20002E460446F3E70A2E04D9BDE8704001208E +:101F300001F0ECBA70BD0000F8B5144B0D46D96144 +:101F400003F1100141600A2A1969826038BF0A2230 +:101F5000016048601861A818144601F07FFA0A274A +:101F600001F076FA431BA342064606D37C1C2819CF +:101F700001F084FA27463546F2E70A2F04D9BDE876 +:101F8000F840012001F0C2BAF8BD00BF28260020A9 +:101F9000F8B506460D4601F05BFA0F4A134653F8B2 +:101FA000107F9F4206D12A4601463046BDE8F840E0 +:101FB000FFF7C2BFD169BB68441A2C1928BF2C4651 +:101FC000A34202D92946FFF79BFF22463146034828 +:101FD000BDE8F840FFF77EBF282600203826002005 +:101FE00010B4C0E9032300235DF8044B4361FFF7FD +:101FF000CFBF000010B5194C236998420DD0D0E92D +:102000000032816813605A609A680A449A6000231B +:1020100003604FF0FF33A36110BD2346026843F80D +:10202000102F53600022026022699A4203D1BDE85A +:10203000104001F01DBA936881680B44936001F071 +:1020400007FA2269E1699268441AA242E4D911446C +:10205000BDE81040091AFFF753BF00BF2826002033 +:102060002DE9F047DFF8BC8008F110072C4ED8F8B6 +:10207000105001F0EDF9D8F81C40AA68031B9A42F1 +:102080003ED81444D5E900324FF00009C8F81C408E +:1020900013605A60C5F80090D8F81030B34201D1EF +:1020A00001F0E6F989F31188D5E90331284698470C +:1020B000302383F311886B69002BD8D001F0C8F965 +:1020C0006A69A0EB04094A4582460DD2022001F05C +:1020D0001DFA0022D8F81030B34208D151462846E4 +:1020E000BDE8F047FFF728BF121A2244F2E712EBCF +:1020F000090938BF4A4629463846FFF7EBFEB5E7DF +:10210000D8F81030B34208D01444211AC8F81C0083 +:10211000A960BDE8F047FFF7F3BEBDE8F08700BF58 +:10212000382600202826002000207047FEE7000007 +:10213000704700004FF0FF307047000002290CD0BC +:10214000032904D00129074818BF00207047032A3B +:1021500005D8054800EBC2007047044870470020CE +:10216000704700BFC03C00082C220020743C0008CF +:1021700070B59AB00546084601A9144600F0C2F8A9 +:1021800001A8FEF7BDFD431C5B00C5E90034002239 +:10219000237003236370C6B201AB02341046D1B280 +:1021A0008E4204F1020401D81AB070BD13F8011B6D +:1021B00004F8021C04F8010C0132F0E708B53023E2 +:1021C00083F311880348FFF759FA002383F311883A +:1021D00008BD00BF9828002090F8443003F01F028B +:1021E000012A07D190F845200B2A03D10023C0E92A +:1021F0000E3315E003F06003202B08D1B0F848300F +:102200002BB990F84520212A03D81F2A04D8FFF7BC +:1022100017BA222AEBD0FAE7034A82630722C26385 +:1022200003640120704700BF2322002007B5052961 +:1022300017D8DFE801F0191603191920302383F3AA +:102240001188104A01900121FFF7BAFA01980E4A4D +:102250000221FFF7B5FA0D48FFF7DCF9002383F3FD +:10226000118803B05DF804FB302383F3118807481D +:10227000FFF7A6F9F2E7302383F311880348FFF74D +:10228000BDF9EBE7143C0008383C00089828002012 +:1022900038B50C4D0C4C0D492A4604F10800FFF7E7 +:1022A00067FF05F1CA0204F110000949FFF760FF5A +:1022B00005F5CA7204F118000649BDE83840FFF779 +:1022C00057BF00BF602D00202C220020F03B0008EB +:1022D000FD3B0008083C000870B5044608460D4662 +:1022E000FEF70EFDC6B22046013403780BB918463E +:1022F00070BD32462946FEF7EFFC0028F3D10120DD +:10230000F6E700002DE9F84F05460C46FEF7F8FC0D +:102310002B49C6B22846FFF7DFFF08B10336F6B2F5 +:1023200028492846FFF7D8FF08B11036F6B2632EC9 +:102330000DD8DFF88C80DFF88C90234FDFF890A069 +:10234000DFF890B02E7846B92670BDE8F88F2946A0 +:102350002046BDE8F84F01F0D3BB252E2BD1072234 +:1023600041462846FEF7B8FC58B9DBF80030236038 +:10237000DBF804306360BBF80830238107350A348A +:10238000E0E7082249462846FEF7A6FC98B90F4B1D +:10239000A21C197809090232C95D02F8041C13F85D +:1023A000011B01F00F015345C95D02F8031CF0D178 +:1023B00018340835C6E704F8016B0135C2E700BFE1 +:1023C000E03C0008083C0008F33C0008107AFF1FBE +:1023D0001C7AFF1FE83C0008BFF34F8F024AD36806 +:1023E000DB03FCD4704700BF003C024008B5094B3A +:1023F0001B7873B9FFF7F0FF074B1A69002ABFBFBC +:10240000064A5A6002F188325A601A6822F48062E1 +:102410001A6008BDBE2F0020003C02402301674522 +:1024200008B50B4B1B7893B9FFF7D6FF094B1A6918 +:1024300042F000421A611A6842F480521A601A6827 +:1024400022F480521A601A6842F480621A6008BD51 +:10245000BE2F0020003C02401728F0B516D80C4CC7 +:102460000C4923787BB90C4D0E4618234FF00062BF +:1024700055F8047B46F8042B013B13F0FF033A4464 +:10248000F6D10123237051F82000F0BD0020FCE7B5 +:1024900020300020C02F0020043D0008014B53F8DD +:1024A00020007047043D000818207047172810B519 +:1024B000044601D9002010BDFFF7CEFF064B53F8AC +:1024C00024301844C21A0BB90120F4E71268013213 +:1024D000F0D1043BF6E700BF043D0008172838B5EB +:1024E000044628D81549FFF777FFFFF77FFFF3234E +:1024F000CB600C23B0FBF3F203FB1205D30143EADC +:10250000C503DBB243F4007343F002030B610B69B4 +:1025100043F480330B61FFF75FFFFFF79DFF084B2C +:1025200053F8241000F0DAF8FFF77AFF2046BDE8F0 +:102530003840FFF7BBBF002038BD00BF003C024061 +:10254000043D0008F8B512F00103144642D1821888 +:10255000B2F1026F57D82D4B1B6813F0010352D014 +:102560002B4DFFF743FFF323EB60FFF735FF40F2FE +:102570000127032C15D824F001046618244C401AB6 +:1025800040F20117B142236900EB010524D123F089 +:1025900001032361FFF744FF0120F8BD043C043030 +:1025A000E7E78307E7D12B6923F440732B612B699D +:1025B0003B432B6151F8046B0660BFF34F8FFFF76D +:1025C0000BFF03689E42E9D02B6923F001032B61C6 +:1025D000FFF726FF0020E0E723F44073236123691F +:1025E0003B4323610B882B80BFF34F8FFFF7F4FE33 +:1025F0002D8831F8023BADB2AB42C3D0236923F042 +:1026000001032361E4E71846C7E700BF0038024032 +:10261000003C0240084908B50B7828B11BB9FFF708 +:10262000E5FE01230B7008BD002BFCD0BDE808407F +:102630000870FFF7F5BE00BFBE2F002010B50244A2 +:10264000064BD2B2904200D110BD441C00B253F8E8 +:10265000200041F8040BE0B2F4E700BF502800402E +:102660000F4B30B51C6F240407D41C6F44F4007466 +:102670001C671C6F44F400441C670A4C236843F435 +:10268000807323600244084BD2B2904200D130BD27 +:10269000441C00B251F8045B43F82050E0B2F4E768 +:1026A00000380240007000405028004007B5012269 +:1026B00001A90020FFF7C2FF019803B05DF804FBF9 +:1026C00013B50446FFF7F2FFA04205D0012201A98D +:1026D00000200194FFF7C4FF02B010BD7047000056 +:1026E000094B5A88B2F5805F10460BD022F00203E6 +:1026F00041F20102934205D041F20703C31A584246 +:102700005841704701207047002004E0034B1A68CD +:102710001AB9034AD2F874281A607047243000208E +:102720000030024008B5FFF7F1FF024B1868C0F314 +:10273000407008BD2430002070470000FEE7000014 +:102740000A4B0B480B4A90420BD30B4BDA1C121A64 +:10275000C11E22F003028B4238BF00220021FEF787 +:10276000D7BA53F8041B40F8041BECE7EC3E000812 +:1027700020310020203100202031002070B5D0E928 +:1027800015439E6800224FF0FF3504EB42135101C0 +:10279000D3F800090028BEBFD3F8000940F08040FC +:1027A000C3F80009D3F8000B0028BEBFD3F8000B14 +:1027B00040F08040C3F8000B013263189642C3F822 +:1027C0000859C3F8085BE0D24FF00113C4F81C3875 +:1027D00070BD0000890141F02001016103699B0681 +:1027E000FCD41220FFF7F8BA10B5054C2046FEF7CE +:1027F000C7FF4FF0A0436365024BA36510BD00BF48 +:1028000028300020883D000870B50378012B05466C +:1028100050D12A4B446D98421BD1294B5A6B42F040 +:1028200080025A635A6D42F080025A655A6D5A69A5 +:1028300042F080025A615A6922F080025A610E21E8 +:1028400043205B6900F022FC1E4BE3601E4BC4F882 +:1028500000380023C4F8003EC02323606E6D4FF49F +:102860005023A3633369002BFCDA012333610C206E +:10287000FFF7B2FA3369DB07FCD41220FFF7ACFA9A +:102880003369002BFCDA0026A6602846FFF776FFA6 +:102890006B68C4F81068DB68C4F81468C4F81C6876 +:1028A0004BB90A4BA3614FF0FF336361A36843F058 +:1028B0000103A36070BD064BF4E700BF2830002081 +:1028C000003802404014004003002002003C30C0A9 +:1028D000083C30C0F8B5446D054600212046FFF79E +:1028E00079FFA96D00234FF001128F68C4F83438C6 +:1028F0004FF00066C4F81C284FF0FF3004EB431281 +:1029000001339F42C2F80069C2F8006BC2F808099F +:10291000C2F8080BF2D20B686A6DEB656362102394 +:102920001361166916F01006FBD11220FFF754FA56 +:10293000D4F8003823F4FE63C4F80038A36943F4E4 +:10294000402343F01003A3610923C4F81038C4F8EE +:1029500014380A4BEB604FF0C043C4F8103B084BEF +:10296000C4F8003BC4F81069C4F80039EB6D03F1FA +:10297000100243F48013EA65A362F8BD643D0008C9 +:1029800040800010426D90F84E10D2F8003823F4C9 +:10299000FE6343EA0113C2F8003870472DE9F8439B +:1029A00000EB8103456DDA68166806F00306731EB6 +:1029B000022B05EB41130C4680460FFA81F94FEAD2 +:1029C00041104FF00001C3F8101B4FF0010104F15A +:1029D000100398BFB60401FA03F391698EBF334E1A +:1029E00006F1805606F5004600293AD0578A04F1D0 +:1029F0005801490137436F50D5F81C180B43C5F8EF +:102A00001C382B180021C3F8101953690127611EC7 +:102A1000A7409BB3138A928B9B08012A88BF53431C +:102A2000D8F85C20981842EA034301F1400205EB14 +:102A30008202C8F85C00214653602846FFF7CAFEB0 +:102A400008EB8900C3681B8A43EA84534834640155 +:102A50001E432E51D5F81C381F43C5F81C78BDE81D +:102A6000F88305EB4917D7F8001B21F40041C7F89C +:102A7000001BD5F81C1821EA0303C0E704F13F034B +:102A800005EB83030A4A5A6028462146FFF7A2FE57 +:102A900005EB4910D0F8003923F40043C0F80039A1 +:102AA000D5F81C3823EA0707D7E700BF00800010DD +:102AB00000040002826D1268C265FFF75FBE00006D +:102AC0005831436D49015B5813F4004004D013F4AE +:102AD000001F0CBF02200120704700004831436DE9 +:102AE00049015B5813F4004004D013F4001F0CBFDD +:102AF000022001207047000000EB8101CB68196AB9 +:102B00000B6813604B6853607047000000EB810353 +:102B100030B5DD68AA691368D36019B9402B84BF4A +:102B2000402313606B8A1468426D1C44013CB4FB63 +:102B3000F3F46343033323F0030302EB411043EA4E +:102B4000C44343F0C043C0F8103B2B6803F00303B9 +:102B5000012B09B20ED1D2F8083802EB411013F460 +:102B6000807FD0F8003B14BF43F0805343F0005304 +:102B7000C0F8003B02EB4112D2F8003B43F00443A3 +:102B8000C2F8003B30BD00002DE9F041244D6E6DD0 +:102B900006EB40130446D3F8087BC3F8087B3807DC +:102BA0000AD5D6F81438190706D505EB8403214653 +:102BB000DB6828465B689847FA071FD5D6F81438B3 +:102BC000DB071BD505EB8403D968CCB98B69488A30 +:102BD0005A68B2FBF0F600FB16228AB91868DA6868 +:102BE00090420DD2121AC3E90024302383F31188D6 +:102BF0000B482146FFF78AFF84F31188BDE8F08176 +:102C0000012303FA04F26B8923EA02036B81CB6888 +:102C1000002BF3D021460248BDE8F041184700BF21 +:102C20002830002000EB810370B5DD68436D6C69CE +:102C30002668E6604A0156BB1A444FF40020C2F8E9 +:102C400010092A6802F00302012A0AB20ED1D3F851 +:102C5000080803EB421410F4807FD4F8000914BF75 +:102C600040F0805040F00050C4F8000903EB4212DD +:102C7000D2F8000940F00440C2F80009D3F8340843 +:102C8000012202FA01F10143C3F8341870BD19B9E9 +:102C9000402E84BF4020206020682E8A8419013C89 +:102CA000B4FBF6F440EAC44040F000501A44C6E7D2 +:102CB0002DE9F8433B4D6E6D06EB40130446D3F807 +:102CC0000889C3F8088918F0010F4FEA40171AD095 +:102CD000D6F81038DB0716D505EB8003D9684B69A9 +:102CE0001868DA68904230D2121A4FF000091A6060 +:102CF000C3F80490302383F3118821462846FFF758 +:102D000091FF89F3118818F0800F1CD0D6F8343861 +:102D10000126A640334216D005EB84036D6DD3F82F +:102D20000CC0DCF814200134E4B2D2F800E005EB6A +:102D300004342F445168714515D3D5F8343823EA4B +:102D40000606C5F83468BDE8F883012303FA04F2E7 +:102D50002B8923EA02032B818B68002BD3D02146D9 +:102D600028469847CFE7BCF81000AEEB010383423A +:102D700028BF0346D7F8180980B2B3EB800FE2D81A +:102D80009068A0F1040959F8048FC4F80080A0EB02 +:102D900009089844B8F1040FF5D818440B44906022 +:102DA0005360C7E7283000202DE9F74FA24C656D2E +:102DB0006E69AB691E4016F480586E6107D02046DC +:102DC000FEF746FD03B0BDE8F04F00F04DBC002E0D +:102DD00012DAD5F8003E98489B071EBFD5F8003E92 +:102DE00023F00303C5F8003ED5F8043823F00103AF +:102DF000C5F80438FEF756FD370505D58E48FFF7B0 +:102E0000BDFC8D48FEF73CFDB0040CD5D5F8083864 +:102E100013F0060FEB6823F470530CBF43F4105308 +:102E200043F4A053EB6031071BD56368DB681BB923 +:102E3000AB6923F00803AB612378052B0CD1D5F8DF +:102E4000003E7D489A071EBFD5F8003E23F00303DD +:102E5000C5F8003EFEF726FD6368DB680BB17648D7 +:102E60009847F30274D4B70227D5D4F85490DFF80A +:102E7000C8B100274FF0010A09EB4712D2F8003B16 +:102E800003F44023B3F5802F11D1D2F8003B002B7F +:102E90000DDA62890AFA07F322EA0303638104EB7D +:102EA0008703DB68DB6813B1394658469847A36D42 +:102EB00001379B68FFB29F42DED9F00617D5676DD8 +:102EC0003A6AC2F30A1002F00F0302F4F012B2F5EC +:102ED000802F00F08580B2F5402F08D104EB8303EA +:102EE0000022DB681B6A07F5805790426AD13003E5 +:102EF000D5F8184813D5E10302D50020FFF744FEAA +:102F0000A20302D50120FFF73FFE630302D5022092 +:102F1000FFF73AFE270302D50320FFF735FE7503BE +:102F20007FF550AFE00702D50020FFF7C1FEA107F3 +:102F300002D50120FFF7BCFE620702D50220FFF791 +:102F4000B7FE23077FF53EAF0320FFF7B1FE39E759 +:102F5000636DDFF8E4A0019300274FF00109A36D32 +:102F60009B685FFA87FB9B453FF67DAF019B03EBB8 +:102F70004B13D3F8001901F44021B1F5802F1FD174 +:102F8000D3F8001900291BDAD3F8001941F0904159 +:102F9000C3F80019D3F800190029FBDB5946606D0E +:102FA000FFF718FC218909FA0BF321EA03032381B7 +:102FB00004EB8B03DB689B6813B159465046984776 +:102FC0000137CCE7910708BFD7F80080072A98BFE0 +:102FD00003F8018B02F1010298BF4FEA182884E739 +:102FE000023304EB830207F580575268D2F818C009 +:102FF000DCF80820DCE9001CA1EB0C0C0021884265 +:103000000AD104EB830463689B699A6802449A605E +:103010005A6802445A606AE711F0030F08BFD7F8F4 +:1030200000808C4588BF02F8018B01F1010188BF47 +:103030004FEA1828E3E700BF28300020436D03EB78 +:103040004111D1F8003B43F40013C1F8003B704735 +:10305000436D03EB4111D1F8003943F40013C1F87B +:1030600000397047436D03EB4111D1F8003B23F465 +:103070000013C1F8003B7047436D03EB4111D1F8D9 +:10308000003923F40013C1F80039704700F16043A0 +:1030900003F561430901C9B283F80013012200F06E +:1030A0001F039A4043099B0003F1604303F561430A +:1030B000C3F880211A60704730B5039C0172043355 +:1030C00004FB0325C0E90653049B03630021059B11 +:1030D000C160C0E90000C0E90422C0E90842C0E9BB +:1030E0000A11436330BD0000416A0022C0E90411A7 +:1030F000C0E90A22C2606FF00101FEF7DDBE0000E8 +:10310000D0E90432934201D1C2680AB9181D704750 +:103110000020704703691960C2680132C260C26949 +:10312000134482690361934224BF436A036100210F +:10313000FEF7B6BE38B504460D46E3683BB162699A +:10314000131D1268A3621344E362002007E0237A90 +:1031500033B929462046FEF793FE0028EDDA38BD44 +:103160006FF00100FBE70000C368C269013BC36068 +:103170004369134482694361934224BF436A4361B4 +:1031800000238362036B03B11847704770B5302387 +:10319000044683F31188866A3EB9FFF7CBFF0546E4 +:1031A00018B186F31188284670BDA36AE26A13F845 +:1031B000015BA362934202D32046FFF7D5FF0023B1 +:1031C00083F31188EFE700002DE9F84F04460E461F +:1031D000174698464FF0300989F311880025AA4612 +:1031E000D4F828B0BBF1000F09D141462046FFF7C3 +:1031F000A1FF20B18BF311882846BDE8F88FD4E9F0 +:103200000A12A7EB050B521A934528BF9346BBF150 +:10321000400F1BD9334601F1400251F8040B43F82B +:10322000040B9142F9D1A36A40334036A362403582 +:10323000D4E90A239A4202D32046FFF795FF8AF386 +:103240001188BD42D8D289F31188C9E730465A4661 +:10325000FDF738FDA36A5B445E44A3625D44E7E783 +:1032600010B5029C0172043303FB0421C0E906136C +:103270000023C0E90A33039B0363049BC460C0E9D5 +:103280000000C0E90422C0E90842436310BD000009 +:10329000026AC260426AC0E904220022C0E90A222E +:1032A0006FF00101FEF708BED0E904239A4201D174 +:1032B000C26822B9184650F8043B0B6070470023DF +:1032C0001846FAE7C368C2690133C360436913440F +:1032D00082694361934224BF436A43610021FEF740 +:1032E000DFBD000038B504460D46E3683BB12369F5 +:1032F0001A1DA262E2691344E362002007E0237A08 +:1033000033B929462046FEF7BBFD0028EDDA38BD6B +:103310006FF00100FBE7000003691960C268013A21 +:10332000C260C269134482690361934224BF436A45 +:10333000036100238362036B03B1184770470000E9 +:1033400070B530230D460446114683F31188866A12 +:103350002EB9FFF7C7FF10B186F3118870BDA36ABD +:103360001D70A36AE26A01339342A36204D3E16948 +:1033700020460439FFF7D0FF002080F31188EDE7E5 +:103380002DE9F84F04460D46904699464FF0300A15 +:103390008AF311880026B346A76A4FB949462046EA +:1033A000FFF7A0FF20B187F311883046BDE8F88F02 +:1033B000D4E90A073A1AA8EB0607974228BF17462E +:1033C000402F1BD905F1400355F8042B40F8042B7E +:1033D0009D42F9D1A36A4033A3624036D4E90A235F +:1033E0009A4204D3E16920460439FFF795FF8BF335 +:1033F00011884645D9D28AF31188CDE729463A4645 +:10340000FDF760FCA36A3B443D44A3623E44E5E70C +:10341000D0E904239A4217D1C3689BB1836A8BB168 +:10342000043B9B1A0ED01360C368013BC360C369A1 +:103430001A44836902619A4224BF436A03610023EC +:1034400083620123184670470023FBE700F036B97A +:10345000014B586A704700BF000C0040034B00222C +:1034600058631A610222DA60704700BF000C004006 +:10347000014B0022DA607047000C0040014B58639A +:10348000704700BF000C0040FEE7000070B51B4B0A +:1034900001630025044686B0586085620E4600F040 +:1034A000BFF804F11003C4E904334FF0FF33C4E95B +:1034B0000635C4E90044A560E562FFF7C9FF2B4665 +:1034C0000246C4E9082304F134010D4A256580232E +:1034D0002046FEF78BFC0123E0600A4A0375009248 +:1034E00072680192B268CDE90223074B6846CDE9C4 +:1034F0000435FEF7A3FC06B070BD00BF9028002085 +:10350000943D0008993D000889340008024AD36AB6 +:103510001843D062704700BF282600204B684360E4 +:103520008B688360CB68C3600B6943614B6903623E +:103530008B6943620B6803607047000008B5264B37 +:1035400026481A6940F2FF110A431A611A6922F4E7 +:10355000FF7222F001021A611A691A6B0A431A6398 +:103560001A6D0A431A651E4A1B6D1146FFF7D6FFF6 +:1035700002F11C0100F58060FFF7D0FF02F1380175 +:1035800000F58060FFF7CAFF02F1540100F580608A +:10359000FFF7C4FF02F1700100F58060FFF7BEFF86 +:1035A00002F18C0100F58060FFF7B8FF02F1A8017D +:1035B00000F58060FFF7B2FF02F1C40100F5806002 +:1035C000FFF7ACFF02F1E00100F58060FFF7A6FF16 +:1035D000BDE8084000F0F0B80038024000000240AA +:1035E000A03D000808B500F06BFAFEF7DDFBFFF721 +:1035F0008DF8BDE80840FEF74BBE000070470000A4 +:10360000EFF3098305494A6B22F001024A636833EC +:1036100083F30988002383F31188704700EF00E0EB +:10362000302080F3118862B60C4B0D4AD96821F422 +:10363000E0610904090C0A43DA60D3F8FC20094967 +:1036400042F08072C3F8FC200A6842F001020A606E +:103650002022DA7783F82200704700BF00ED00E0F7 +:103660000003FA05001000E010B5302383F3118841 +:103670000E4B5B6813F4006314D0F1EE103AEFF3D5 +:103680000984683C4FF08073E361094BDB6B236670 +:1036900084F30988FEF768FB10B1064BA36110BDE7 +:1036A000054BFBE783F31188F9E700BF00ED00E06D +:1036B00000EF00E02F030008320300080E4B1A6CE5 +:1036C00042F008021A641A6E42F008021A660B4AA7 +:1036D0001B6E936843F008039360094B53229A6270 +:1036E0004FF0FF32DA6200229A615A63DA605A6060 +:1036F00001225A611A60704700380240002004E03D +:10370000000C0040094A08B51169D3680B40D9B2D2 +:10371000C9439B07116107D5302383F31188FEF756 +:1037200059FB002383F3118808BD00BF000C004043 +:103730001F4B1A696FEAC2526FEAD2521A611A69B4 +:10374000C2F308021A614FF0FF301A695A695861D2 +:1037500000215A6959615A691A6A62F080521A62E4 +:103760001A6A02F080521A621A6A5A6A58625A6ACF +:1037700059625A6A1A6C42F080521A641A6E42F008 +:1037800080521A661A6E0B4A106840F480701060FE +:10379000186F00F44070B0F5007F1EBF4FF480300A +:1037A00018671967536823F40073536000F060B919 +:1037B0000038024000700040344B4FF080521A64D1 +:1037C000334A4FF4404111601A6842F001021A6016 +:1037D0001A689107FCD59A6822F003029A602B4B75 +:1037E0009A6812F00C02FBD1196801F0F901196016 +:1037F0009A601A6842F480321A601A689203FCD503 +:103800005A6F42F001025A67204B5A6F9007FCD55D +:10381000204A5A601A6842F080721A601C4A536843 +:103820005904FCD5194B1A689201FCD51A4A9A60C2 +:103830000322C3F88C20194B1A68194B9A42194B72 +:1038400021D1194A1168194A91421CD140F205123E +:103850001A60144A136803F00F03052BFAD10B4BBF +:103860009A6842F002029A609A6802F00C02082AF2 +:10387000FAD15A6C42F480425A645A6E42F4804241 +:103880005A665B6E704740F20572E1E7003802400D +:10389000007000401854400700948838002004E06D +:1038A00011640020003C024000ED00E041C20F41E5 +:1038B000074A08B5536903F00103536123B1054A70 +:1038C00013680BB150689847BDE80840FFF7CCBEBD +:1038D000003C0140A0300020074A08B5536903F0BE +:1038E0000203536123B1054A93680BB1D06898472E +:1038F000BDE80840FFF7B8BE003C0140A030002002 +:10390000074A08B5536903F00403536123B1054A1C +:1039100013690BB150699847BDE80840FFF7A4BE92 +:10392000003C0140A0300020074A08B5536903F06D +:103930000803536123B1054A93690BB1D0699847D5 +:10394000BDE80840FFF790BE003C0140A0300020D9 +:10395000074A08B5536903F01003536123B1054AC0 +:10396000136A0BB1506A9847BDE80840FFF77CBE68 +:10397000003C0140A0300020164B10B55C6904F4F7 +:1039800078725A61A30604D5134A936A0BB1D06AC0 +:103990009847600604D5104A136B0BB1506B9847DB +:1039A000210604D50C4A936B0BB1D06B9847E20506 +:1039B00004D5094A136C0BB1506C9847A30504D584 +:1039C000054A936C0BB1D06C9847BDE81040FFF7E7 +:1039D0004BBE00BF003C0140A0300020194B10B589 +:1039E0005C6904F47C425A61620504D5164A136D81 +:1039F0000BB1506D9847230504D5134A936D0BB155 +:103A0000D06D9847E00404D50F4A136E0BB1506E89 +:103A10009847A10404D50C4A936E0BB1D06E984719 +:103A2000620404D5084A136F0BB1506F9847230402 +:103A300004D5054A936F0BB1D06F9847BDE810408D +:103A4000FFF712BE003C0140A030002008B503483B +:103A5000FDF798FABDE80840FFF706BEBC2300203A +:103A600008B5FFF74FFEBDE80840FFF7FDBD0000B9 +:103A7000062108B50846FFF709FB06210720FFF7D6 +:103A800005FB06210820FFF701FB06210920FFF7AF +:103A9000FDFA06210A20FFF7F9FA06211720FFF7A1 +:103AA000F5FA06212820FFF7F1FA07213220FFF767 +:103AB000EDFABDE808400C212620FFF7E7BA000028 +:103AC00008B5FFF735FE00F00DF8FDF76FFCFDF7C8 +:103AD00055FEFDF72DFDFFF791FDBDE80840FFF70E +:103AE000B5BC00000023054A19460133102BC2E97A +:103AF000001102F10802F8D1704700BFA030002089 +:103B0000034611F8012B03F8012B002AF9D1704765 +:103B100053544D3332463F3F3F0053544D333246AA +:103B20003430780053544D33324634327800535495 +:103B30004D333246343436585800000001203300EB +:103B40000010410001105A00031059000710310005 +:103B500000000000103B0008130400001A3B00089E +:103B600019040000243B0008210400002E3B00083B +:103B700000960000000000000000000000000000AF +:103B800000000000000000006D1300085913000839 +:103B900095130008811300088D130008791300089D +:103BA0006513000851130008A1130008000000006D +:103BB000AD14000899140008D5140008C1140008B9 +:103BC000CD140008B9140008A514000891140008C9 +:103BD000E1140008000000000100000000000000E7 +:103BE00063300000E03B0008802600209028002081 +:103BF0004865782F50726F6669434E430025424FE7 +:103C0000415244252D424C002553455249414C25F3 +:103C1000000000000200000000000000C9160008BB +:103C20003517000840004000302D0020402D0020B6 +:103C3000020000000000000003000000000000007F +:103C4000791700080000000010000000502D00202F +:103C500000000000010000000000000028300020EB +:103C6000010102002D2200083D210008D921000891 +:103C7000BD210008430000007C3C0008090243000D +:103C8000020100C032090400000102020100052403 +:103C9000001001052401000104240202052406008D +:103CA00001070582030800FF09040100020A000061 +:103CB00000070501024000000705810240000000E6 +:103CC00012000000C83C0008120110010200004070 +:103CD000AE2D0111000201020301000004030904DA +:103CE00025424F415244250043756265426C616331 +:103CF0006B2B00303132333435363738394142435B +:103D00004445460000400000004000000040000024 +:103D1000004000000000010000000200000002005E +:103D2000000002000000020000000200000002008B +:103D300000000200004000000040000000400000C1 +:103D4000004000000000010000000200000002002E +:103D5000000002000000020000000200000002005B +:103D60000000020000000000BD180008751B0008DC +:103D7000211C0008400040008830002088300020CE +:103D80000100000098300020800000004001000089 +:103D9000030000006D61696E0069646C65000000DD +:103DA0000000812A00020000AAAAAAAA000000249A +:103DB000FFFF00000000000000A00A00000000005B +:103DC00000000000AAAAAAAA00000000FFFF00004D +:103DD000000000000000000014000054000000007B +:103DE000AAAAAAAA14000054FFFF000000000000C5 +:103DF000000000008069100000000000AAAA8AAA42 +:103E000040561000FFFF0000007070070000000027 +:103E10004001000100000000AAAAAAAA00010000B7 +:103E2000F7FF00000000000000000000000000009C +:103E300000000000AAAAAAAA00000000FFFF0000DC +:103E40000000000000000000000000000000000072 +:103E5000AAAAAAAA00000000FFFF000000000000BC +:103E60000000000000000000000000000A00000048 +:103E7000000000000300000000000000000000003F +:103E80000000000000000000000000000000000032 +:103E90000000000000000000000000000000000022 +:103EA000EB0300000000000000C01F000000000045 +:103EB000FF00000098280020BC230020009600008E +:103EC0000000080096000000000800000400000048 +:103ED000DC3C0008000000000000000000000000C2 +:0C3EE000000000000000000000000000D6 :00000001FF diff --git a/Tools/bootloaders/CubeBlack_bl.bin b/Tools/bootloaders/CubeBlack_bl.bin index c103a92ad4f402..7a800b22784906 100755 Binary files a/Tools/bootloaders/CubeBlack_bl.bin and b/Tools/bootloaders/CubeBlack_bl.bin differ diff --git a/Tools/bootloaders/CubeBlack_bl.elf b/Tools/bootloaders/CubeBlack_bl.elf index 6048f8ee907957..6eaf4225299f39 100755 Binary files a/Tools/bootloaders/CubeBlack_bl.elf and b/Tools/bootloaders/CubeBlack_bl.elf differ diff --git a/Tools/bootloaders/CubeBlack_bl.hex b/Tools/bootloaders/CubeBlack_bl.hex index 3000a28a136e56..4460c7c47d8cdf 100644 --- a/Tools/bootloaders/CubeBlack_bl.hex +++ b/Tools/bootloaders/CubeBlack_bl.hex @@ -1,1026 +1,1009 @@ :020000040800F2 -:1000000000060020E1010008F50E0008F90E0008C6 -:10001000510F0008F90E0008250F0008E301000841 -:10002000E3010008E3010008E301000805290008D6 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E301000801360008CD :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008D5390008013A00086F -:100060002D3A0008593A0008853A0008E3010008D3 +:10005000E3010008E3010008B1380008D9380008BE +:10006000013900082939000851390008E301000866 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008B13A0008A9 +:10009000E3010008E3010008E301000879390008E2 :1000A000E3010008E3010008E3010008E3010008A0 :1000B000E3010008E3010008E3010008E301000890 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E3010008011100081511000800 -:1000E000193B0008E3010008E3010008E3010008F0 +:1000D000E3010008E30100084D3A0008E3010008CD +:1000E000DD390008E3010008E3010008E30100082E :1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E301000841380008E3010008AA +:10010000E3010008E3010008613A0008E301000888 :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008493000086A +:10014000E3010008E3010008E3010008A92D00080D :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E301000829110008E301000869 +:10018000E3010008E3010008E3010008E3010008BF :10019000E3010008E3010008E3010008E3010008AF :1001A000E3010008E3010008E3010008E30100089F :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F0B5FB03F04BFA4FF055301F499A -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE702F0B3 -:1002A00093FB03F081FA144C144DAC4203DA54F87A -:1002B000041B8847F9E700F041F8114C114DAC429E -:1002C00003DA54F8041B8847F9E702F07BBB00000F -:1002D000000600200022002000000008000000208E -:1002E00000060020C03F0008002200203422002029 -:1002F0003822002014350020E0010008E001000849 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F00CFF2A -:10033000FEE701F08DFE00DFFEE7000038B500F0BB -:10034000AFFC40B1174B6FF03F01002259720F21F3 -:100350001A729972DA7202F0A7FA044602F0CCFA25 -:100360000546D8B9104B9C421AD001339C4218BFA5 -:10037000054641F2883404BF01250024002002F024 -:100380009DFA0DB100F05AF800F05AFD00F0B6FBEE -:10039000204600F0B1F800F051F8F9E70024EDE74D -:1003A0000446EBE700220020010007B008B500F08A -:1003B00071FBA0F120035842584108BD07B5054B19 -:1003C00002211B88ADF8043001A800F081FB03B0C6 -:1003D0005DF804FB003C000810B5202383F311886E -:1003E0001248C3680BB101F04BFF0023104A0F48BD -:1003F0004FF47A7101F0F2FE002383F311880D4C63 -:10040000236813B12368013B2360636813B16368F9 -:10041000013B6360084B1B7833B9636823B9022042 -:1004200000F07CFC3223636010BD00BF3822002046 -:10043000D9030008542300204C22002010B5254B7E -:10044000254953F8042F013200D110BD8B42F8D159 -:10045000224C234B22689A423AD9224B9B6803F1E3 -:10046000006303F580439A4232D2002000F060FB23 -:100470001D4B0220187000F047FC1C4B1A6C002228 -:100480001A64196E1A66196E596C5A64596E5A6656 -:100490005A6E5A6942F080025A615A6922F080020B -:1004A0005A615A691A6942F000521A611A6922F0B7 -:1004B00000521A611B6972B60D4A0E4B13601B681D -:1004C0002268202181F311889D4683F30888104714 -:1004D00010BD00BFFC3F00081C400008044000089D -:1004E000FF3F0008002200204C220020003802407C -:1004F00008ED00E0004000082DE9F04F99B0B94D3B -:1005000000902022FF2110A8AC6800F03BFCB64A06 -:1005100001951378A3B9B5480121C3601170202358 -:1005200083F31188C3680BB101F0AAFE0023B04A1F -:10053000AE484FF47A7101F051FE002383F3118825 -:10054000009BAC4A03B11360AB4B009D02930026A5 -:100550001E705660B2463746B146012000F0D4FB0B -:10056000002D00F02582A34B1B68002B40F0208259 -:1005700019B0BDE8F08F0220FFF718FF002840F007 -:100580001082009B002E08BF1D469C4B02211B8839 -:10059000ADF82C300BA800F09BFADEE74FF47A7030 -:1005A00000F078FAB0F10008EBDB0220FFF7FEFE66 -:1005B0000028E6D008F1FF38B8F1040F00F2F3810B -:1005C000DFE808F0031E2124270018A8052340F8BF -:1005D000343D042100F07CFA012303FA08F848EACC -:1005E0000A0A5FFA8AFA4FF0000900F01FFC27B1EF -:1005F0000AF00B030B2B08BF0025FFF7DFFEACE76B -:1006000004217848E6E704217D48E3E704217D489A -:10061000E0E74FF01C09484600F08CFA09F10409A4 -:100620000B9004210BA800F053FAB9F12C0FF2D172 -:10063000D2E7002FA5D00AF00B030B2BA1D102208B -:10064000FFF7B4FE804600289BD001206A4E00F0E0 -:100650006FFA0220307000F057FB00275FFA87FB2B -:10066000584600F075FA054688B1584600F080FA01 -:1006700001370028F2D146460025634B02211B8832 -:10068000ADF82C300BA800F023FA474665E70123AC -:100690000220337000F02EFB2C46019B9B689C428D -:1006A00006D2204600F046FA0130E4D10434F4E7E3 -:1006B000029B00241C704F4B46465C604746254613 -:1006C00093E7002F3FF45DAF0AF00B030B2B7FF491 -:1006D00058AF029B0220187000F016FB322000F089 -:1006E000D9F9B0F1000BFFF64CAF1BF003087FF413 -:1006F00048AF019B996804EB0B028A423FF641AF79 -:10070000BBF5807F3FF63DAF404A0392D8450FDAF4 -:100710004FF47A7000F0BEF9049004990029FFF6B6 -:1007200030AF039A049908F8021008F10108ECE7C9 -:10073000C820FFF73BFE804600283FF422AF1F2C65 -:1007400011D8C4F120075F4528BF5F4610AB24F0E5 -:1007500003003A462D49184400F0EAFA3A46FF21D0 -:100760002A4800F00FFB4FEAAB03DAB227490393A4 -:10077000204600F00FFB074600283FF47EAF039BA6 -:1007800004EB830431E70220FFF710FE00283FF45A -:10079000F8AE00F013FA00283FF4F3AE4FF0000873 -:1007A0004346019A9268904532D2B8F11F0F12D891 -:1007B000109A01320FD028F0030218A90A4452F807 -:1007C000202C0B92184604220BA900F0D5FB08F14F -:1007D00004080346E5E74046039300F0ABF9039BAA -:1007E0000B90EFE700220020502300203822002049 -:1007F000D9030008542300204C220020023C0008AA -:100800000422002008220020043C0008502200207E -:1008100018A8042140F84C3D00F05AF9E5E618A864 -:10082000002340F8343D642100F048F900287FF4AB -:10083000A8AE0220FFF7BAFD00283FF4A2AE0B9845 -:1008400000F0A8F918AB43F8480D04211846E3E777 -:1008500018A8002340F8343D642100F02FF9002847 -:100860007FF48FAE0220FFF7A1FD00283FF489AE90 -:100870000B9800F09DF918AB43F8440DE5E7022012 -:10088000FFF794FD00283FF47CAE00F0A7F918AB09 -:1008900043F8400DD9E70220FFF788FD00283FF418 -:1008A00070AE0BA9142000F09FF9804618A804210F -:1008B00040F83C8D00F00CF941460BA8ACE7322023 -:1008C00000F0E8F8B0F10008FFF65BAE18F0030F97 -:1008D0007FF457AE019A926808EB090393423FF602 -:1008E00050AE0220FFF762FD00283FF44AAE28F028 -:1008F0000308C844C1453FF478AE484600F01AF9F1 -:1009000004210A900AA800F0E3F809F10409F1E7CC -:100910004FF47A70FFF74AFD00283FF432AE00F042 -:100920004DF9002842D0109B01330BD0082210A9AA -:10093000002000F02FFA002838D02022FF2110A834 -:1009400000F020FAFFF73AFD364801F003FC0FE60D -:10095000002F3FF416AE0AF00B030B2B7FF411AE01 -:1009600018A8002340F8343D642100F0A7F8804621 -:1009700000287FF406AE0220FFF718FD00283FF4A0 -:1009800000AE0390FFF71AFD41F2883001F0E2FB60 -:100990000B9800F08FFA00F049FA039B45461F467A -:1009A000DBE5074621E64FF00009EAE5B84664E6D4 -:1009B000002000F06FF80490049B002BFFF6D0ADF0 -:1009C000012000F097F9049B213B122B3FF6C5ADA7 -:1009D00001A252F823F000BF770500089D0500082A -:1009E000330600085B0500085B0500085B0500088E -:1009F000C3060008BF080008870700081F08000892 -:100A0000510800087F0800085B05000897080008E7 -:100A10005B05000811090008EB0500085B050008EC -:100A200051090008A08601002DE9F84F4FF47A75AE -:100A3000DFF85880DFF8589007460E4655430024EB -:100A400098F900305A1C5FFA84FA01D0A34210D101 -:100A500059F8240003683246D3F820B039462B46B3 -:100A6000D847864205D1084B83F800A00120BDE895 -:100A7000F88F0134042CE3D14FF4FA7001F06AFBD3 -:100A80000020BDE8F88F00BF9C2300200C2200202E -:100A9000583C000807B502AB002203F8012D0121E4 -:100AA00002461846FFF7C0FF20B19DF8070003B0CB +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F074FA01 +:1002500003F074F94FF055301F491B4A91423CBFDF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F052FA03F0A2F96E +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F03ABA000600200022002031 +:1002D0000000000808ED00E00000002000060020FB +:1002E000A03E0008002200204C22002050220020C6 +:1002F00020310020E0010008E0010008E0010008D2 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F098FDFEE701F063 +:1003300027FD00DFFEE7000038B500F0DFFB02F02C +:10034000CFF940B1164B6FF03F01002259720F21D7 +:100350001A729972DA7202F0A9F9054602F0E2F90E +:100360000446C8B90F4B9D4218D001339D4218BFB7 +:10037000044641F2883504BF01240025002002F024 +:100380009FF90CB100F076F800F018FD284600F057 +:10039000C1F800F06FF8F9E70025EFE70546EDE753 +:1003A00000220020010007B008B500F073FBA0F1A7 +:1003B00020035842584108BD07B541F212030221FB +:1003C00001A8ADF8043000F083FB03B05DF804FB36 +:1003D00038B5302383F31188174803680BB101F057 +:1003E00009FE164A144800234FF47A7101F0F8FD13 +:1003F000002383F31188124C236813B12368013B57 +:100400002360636813B16368013B63600D4D2B7813 +:1004100033B963687BB9022000F03AFC3223636091 +:100420002B78032B07D163682BB9022000F030FC36 +:100430004FF47A73636038BD50220020D103000866 +:100440007023002068220020084B187003280CD865 +:10045000DFE800F008050208022000F00FBC0220CF +:1004600000F002BC024B00225A6070476822002054 +:1004700070230020234B244A10B51C461968013113 +:100480003FD004339342F9D16268A24239D31F4B63 +:100490009B6803F1006303F580439A4231D2002048 +:1004A00000F046FB0220FFF7CFFF194B1A6C002229 +:1004B0001A64196E1A66196E596C5A64596E5A6626 +:1004C0005A6E5A6942F080025A615A6922F08002DB +:1004D0005A615A691A6942F000521A611A6922F087 +:1004E00000521A611B6972B64FF0E0233021C3F845 +:1004F000084DD4E9003281F311889D4683F30888C2 +:10050000104710BD004000082040000800220020D5 +:10051000003802402DE9F04F93B0AA4B0090202202 +:10052000FF210AA89D6800F0F3FBA74A1378A3B93E +:10053000A648012103601170302383F311880368FA +:100540000BB101F057FDA24AA04800234FF47A7185 +:1005500001F046FD002383F31188009B13B19D4BEE +:10056000009A1A609C4A009C1378032B1EBF00233C +:100570001370984A4FF0000A18BF5360D34656468E +:10058000D146012000F07AFB24B1924B1B68002B6E +:1005900000F01182002000F07DFA0390039B002BF5 +:1005A000F2DB012000F060FB039B213B162BE8D817 +:1005B00001A252F823F000BF150600083D0600080E +:1005C000D10600088305000883050008830500089C +:1005D0005B0700082B09000845080008A708000869 +:1005E000CF080008F508000883050008070900087F +:1005F0008305000879090008B5060008830500088E +:10060000BD09000821060008B5060008830500089A +:10061000A70800080220FFF7C7FE002840F0F58178 +:10062000009B0221BAF1000F08BF1C4605A841F249 +:100630001233ADF8143000F04BFAA2E74FF47A70A1 +:1006400000F028FA071EEBDB0220FFF7ADFE0028C2 +:10065000E6D0013F052F00F2DA81DFE807F0030A58 +:100660000D10133605230593042105A800F030FA78 +:1006700017E054480421F9E758480421F6E75848A0 +:100680000421F3E74FF01C08404600F053FA08F14C +:1006900004080590042105A800F01AFAB8F12C0FFF +:1006A000F2D1012000FA07F747EA0B0B5FFA8BFB48 +:1006B0004FF0000900F078FB26B10BF00B030B2B79 +:1006C00008BF0024FFF778FE5BE746480421CDE72A +:1006D000002EA5D00BF00B030B2BA1D10220FFF7AE +:1006E00063FE074600289BD0012000F021FA02207B +:1006F000FFF7AAFE00261FFA86F8404600F028FA07 +:10070000044690B10021404600F032FA013600283C +:10071000F1D1BA46044641F21213022105A8ADF800 +:1007200014303E4600F0D4F92BE70120FFF78CFE91 +:100730002546244B9B68AB4207D9284600F0FAF9BE +:10074000013040F067810435F3E7234B00251D702D +:10075000204BBA465D603E46ACE7002E3FF460AFEA +:100760000BF00B030B2B7FF45BAF0220FFF76CFE4B +:10077000322000F08FF9B0F10008FFF651AF18F009 +:1007800003077FF44DAF0F4A926808EB05039342CD +:100790003FF646AFB8F5807F3FF742AF124B01936B +:1007A000B84523DD4FF47A7000F074F90390039A92 +:1007B000002AFFF635AF019B039A03F8012B01379E +:1007C000EDE700BF002200206C2300205022002013 +:1007D000D10300087023002068220020042200209A +:1007E000082200200C2200206C220020C820FFF7E5 +:1007F000DBFD074600283FF413AF1F2D11D8C5F1CC +:10080000200242450AAB25F0030028BF4246834937 +:100810000192184400F056FA019A8048FF2100F036 +:1008200077FA4FEAA8037D490193C8F38702284667 +:1008300000F076FA064600283FF46DAF019B05EB09 +:10084000830537E70220FFF7AFFD00283FF4E8AE4D +:1008500000F0BAF900283FF4E3AE0027B846704B29 +:100860009B68BB4218D91F2F11D80A9B01330ED0A9 +:1008700027F0030312AA134453F8203C0593404683 +:10088000042205A900F0F6FA04378046E7E7384667 +:1008900000F050F90590F2E7CDF81480042105A886 +:1008A00000F016F906E70023642104A8049300F081 +:1008B00005F900287FF4B4AE0220FFF775FD00288B +:1008C0003FF4AEAE049800F067F90590E6E7002328 +:1008D000642104A8049300F0F1F800287FF4A0AE8E +:1008E0000220FFF761FD00283FF49AAE049800F063 +:1008F00063F9EAE70220FFF757FD00283FF490AEC6 +:1009000000F072F9E1E70220FFF74EFD00283FF406 +:1009100087AE05A9142000F06DF904210746049064 +:1009200004A800F0D5F83946B9E7322000F0B2F853 +:10093000071EFFF675AEBB077FF472AE384A9268A9 +:1009400007EB090393423FF66BAE0220FFF72CFD45 +:1009500000283FF465AE27F003074F44B9453FF444 +:10096000A9AE484600F0E6F80421059005A800F07D +:10097000AFF809F10409F1E74FF47A70FFF714FDBD +:1009800000283FF44DAE00F01FF9002844D00A9B28 +:1009900001330BD008220AA9002000F0C1F9002879 +:1009A0003AD02022FF210AA800F0B2F9FFF704FD97 +:1009B0001C4801F059FA13B0BDE8F08F002E3FF447 +:1009C0002FAE0BF00B030B2B7FF42AAE0023642118 +:1009D00005A8059300F072F8074600287FF420AEC2 +:1009E0000220FFF7E1FC804600283FF419AEFFF734 +:1009F000E3FC41F2883001F037FA059800F018FA6C +:100A0000464600F0D1F93C46BBE5064652E64FF0BB +:100A1000000905E6BA467EE637467CE66C220020F1 +:100A200000220020A08601002DE9F84F4FF47A73D0 +:100A3000DFF85880DFF8589006460D4602FB03F7B2 +:100A4000002498F900305A1C5FFA84FA01D0A342BE +:100A500012D159F8240003682A46D3F820B0314651 +:100A60003B46D847854207D1074B012083F800A0B9 +:100A7000BDE8F88F0124E4E7002CFBD04FF4FA70B6 +:100A800001F0F2F90020F3E7B82300201022002043 +:100A90001422002007B50023024601210DF10700B2 +:100AA0008DF80730FFF7C0FF20B19DF8070003B0B5 :100AB0005DF804FB4FF0FF30F9E700000A4608B587 :100AC0000421FFF7B1FF80F00100C0B2404208BD31 -:100AD00030B4074B1A78074B53F822402368DD697E -:100AE000054B0A46AC460146204630BC604700BF75 -:100AF0009C230020583C0008A086010070B501F03E -:100B0000CFFD094C094E20800025306823888342A0 -:100B100008D901F0BFFD336805440133B5F5804FB6 -:100B20003360F2D370BD00BF9E2300205C23002001 -:100B300001F06CBE00F1006000F580400068704775 -:100B400000F10060920000F5804001F0F7BD000068 +:100AD00030B4074B0A461978064B53F82140236877 +:100AE000DD69054B0146AC46204630BC604700BF7F +:100AF000B823002014220020A086010070B501F068 +:100B0000D3FC094E094D3080002428683388834285 +:100B100008D901F0C3FC2B6804440133B4F5804FBD +:100B20002B60F2D370BD00BFBA23002078230020D1 +:100B300001F070BD00F1006000F580400068704772 +:100B400000F10060920000F5804001F0FBBC000065 :100B5000054B1A68054B1B889B1A834202D9104427 -:100B600001F098BD002070475C2300209E230020E8 -:100B700038B5074D04462868204401F093FD28B994 -:100B800028682044BDE8384001F0A4BD38BD00BF4E -:100B90005C23002010F0030308D1B0F5047F05D2D8 -:100BA00000F10050A0F50840006870470020704731 -:100BB000014BC058704700BF107AFF1F064991F8DB -:100BC000243033B100230822086A81F82430FFF76B -:100BD000B7BF0120704700BF60230020014B186899 -:100BE000704700BF002004E070B52A4B1C68C4F3B6 -:100BF0000B03240C63B140F21342934231D040F214 -:100C0000194293422FD040F2214293422DD1032327 -:100C1000214A0C2505FB03235D6893F9082042F265 -:100C200001039C4224D0B4F5805F23D041F201033C -:100C30009C4221D041F203039C421FD041F20703A2 -:100C40009C4208BF3122441E0C44013D0B46A34286 -:100C50001ED215F9016F581C96B1034600F8016CBD -:100C6000F5E70123D4E70223D2E73F220B4DD6E775 -:100C70003322E3E74122E1E75A22E4E75922E2E79F -:100C80002C2584421D7001D9981C5A70401A70BDE1 -:100C90001846FBE7002004E0283C0008083C000858 -:100CA000124B5A8842F201018A4293B214D0B3F532 -:100CB000805F13D041F20102934211D041F203024E -:100CC00093420FD041F2070293420DD10423084A08 -:100CD00002EB8303D87870470023F8E70123F6E797 -:100CE0000223F4E70323F2E700207047002004E02A -:100CF000143C0008022802BF024B4FF480529A6154 -:100D0000704700BF00100240022802BF024B4FF0A4 -:100D100080529A61704700BF00100240022801BF54 -:100D2000024A536983F480535361704700100240B4 -:100D300010B50023934203D0CC5CC4540133F9E7CF -:100D400010BD000030B5441E14F9010F0B4660B110 -:100D500093F90050854201F1010106D11AB993F9C6 -:100D60000020801A30BD013AEEE7002AF7D1104684 -:100D700030BD000002460346981A13F9011B0029F2 -:100D8000FAD1704702440346934202D003F8011B94 -:100D9000FAE770472DE9F047234C94F824300546D4 -:100DA0008846174683BB2E46DFF87C90C7B394F87D -:100DB00024302BB92022FF2148462662FFF7E2FFAC -:100DC00094F82400C0F10805BD4228BF3D465FFAF3 -:100DD00085FAAD0041462A4604EB8000FFF7A8FFE4 -:100DE00094F82430A7EB0A079A445FFA8AFABAF11A -:100DF000080F2E44A844FFB284F824A0D6D1FFF7F0 -:100E0000DDFE0028D2D108E0266A06EB8306B04258 -:100E1000CAD0FFF7D3FE0028C5D10020BDE8F08777 -:100E20000120BDE8F08700BF60230020024B1A7844 -:100E3000024B1A70704700BF9C2300200C22002038 -:100E4000F8B5164C1648174D174E154F00F098FC84 -:100E50002146134800F0C0FC24681448626D936B6F -:100E600023F40023936301F075F92046104900F044 -:100E7000BFFD626D936B43F4002393634FF4E13342 -:100E80002B60002456F82400B84202D0294600F016 -:100E9000D5FB0134042CF5D1F8BD00BF683D000836 -:100EA000102D002088230020583C000840420F00ED -:100EB000943D000838B50B4B1A780B4B53F8224081 -:100EC0000A4B9C4205460CD0094B002118461422BF -:100ED000FFF758FF056001462046BDE8384000F0A6 -:100EE000ADBB38BD9C230020583C0008102D0020CD -:100EF00088230020FEE7000000B59BB0EFF30981D6 -:100F000068226846FFF714FFEFF30583044B9A6BE2 -:100F1000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE78F -:100F200000ED00E000B59BB0EFF309816822684650 -:100F3000FFF7FEFEEFF30583044B9A6B9A6A9A6AF9 -:100F40009A6A9A6A9A6A9B6AFEE700BF00ED00E01F -:100F500000B59BB0EFF3098168226846FFF7E8FE11 -:100F6000EFF30583034B5A6B9A6A9A6A9A6A9A6AF4 -:100F70009B6AFEE700ED00E030B5084D0A4491425F -:100F80000BD011F8013B09245840013CF7D040F345 -:100F900000032B4083EA5000F7E730BD2083B8ED13 -:100FA000002304491A465A50C8180833802B42605F -:100FB000F9D17047A0230020026843681143016003 -:100FC00003B1184770470000024AD36843F0C003DA -:100FD000D360704700440040024AD36843F0C00326 -:100FE000D360704700480040024AD36843F0C00312 -:100FF000D3607047007800402DE9F041D0F85C6282 -:10100000F7683368DA0505469CB20DD5202383F3D3 -:1010100011884FF400710430FFF7CEFF6FF4807336 -:101020003360002383F31188202383F3118805F1B3 -:10103000040814F02F0333D183F31188380615D533 -:10104000210613D5202383F3118805F1380000F021 -:1010500053FA002846DA0821281DFFF7ADFF4FF6A6 -:101060007F733B40F360002383F311887A060ED52B -:1010700063060CD5202383F31188EA6C2B6D9A420A -:1010800002D12B6C002B2FD1002383F31188D5F8CC -:101090006422D368002B31D01069BDE8F0411847B5 -:1010A000230713D014F0080F0CBF00218021E007A4 -:1010B00048BF41F02001A20748BF41F0400163074B -:1010C00048BF41F480714046FFF776FFA40673687D -:1010D00005D595F860122846194000F0BDFA34682D -:1010E000A4B2A6E77060BEE727F040073F041021D6 -:1010F000281D3F0CFFF760FFF760C5E7BDE8F081F2 -:1011000008B50348FFF778FFBDE8084001F02EBCA2 -:101110002024002008B50348FFF76EFFBDE8084013 -:1011200001F024BC8826002008B50348FFF764FFBF -:10113000BDE8084001F01ABCF028002010B50E4CA4 -:101140000E4A2046002100F057FA0D4BC4F85C32DD -:101150000C4C0D4A2046002100F04EFA0B4BC4F80F -:101160005C320B4C0B4A0021204600F045FA0A4B3A -:10117000C4F85C3210BD00BF20240020C90F000855 -:101180000044004088260020D90F00080048004095 -:10119000F0280020E90F00080078004038B5394DEC -:1011A000037C002918BF0D46012B0446C0F8645289 -:1011B00010D1354B984242D1344B1A6C42F4003274 -:1011C0001A641A6E42F400321A661B6E0B21262036 -:1011D00000F06AF82E4BD4F85C229A422B6802D0B9 -:1011E0002C498A424BD12C4901EB5301B1FBF3F35B -:1011F000A988080442BF23F0070003F0070343EA6D -:1012000040039360EB8843F040039BB213612B894A -:1012100043F001039BB2536141F4045343F02C03A8 -:10122000D36001F4A05100231360B1F5806F1368FF -:1012300053680CBF7F23FF2384F8603238BD174BFF -:1012400098420CD1114B1A6C42F480221A641A6E27 -:1012500042F480221A661B6E0B212720B8E7104B40 -:101260009842B7D1094B1A6C42F080421A641A6E48 -:1012700042F080421A661B6E0B215220A8E70949F2 -:10128000B2E700BF883C000820240020003802405C -:10129000001001400014014000BD01058826002017 -:1012A000F028002080DE800200F1604300F01F0281 -:1012B000400903F5614309018000C9B200F16040B3 -:1012C00083F8001300F5614001239340C0F880319A -:1012D00003607047F8B5154682680669AA420B4656 -:1012E000816938BF8568761AB542044607D2184628 -:1012F0002A46FFF71DFDA3692B44A3610DE011D918 -:1013000032461846FFF714FDAF1B3A46E1683044F9 -:10131000FFF70EFDE2683A44A261A3685B1BA3607D -:101320002846F8BD18462A46FFF702FDE368E4E7C1 -:1013300083682DE9F041044693421546266938BF7B -:1013400085684069361AB5420F4606D22A46FFF72D -:10135000EFFC63692B4463610DE012D93246A5EBC3 -:101360000608FFF7E5FC4246B919E068FFF7E0FC24 -:10137000E26842446261A3685B1BA3602846BDE843 -:10138000F0812A46FFF7D4FCE368E4E710B50A448D -:101390000024C361029B006040608460C160816181 -:1013A00041610261036210BD08B5826943699342DD -:1013B00001D1826882B98268013282605A1C42611E -:1013C0001970426903699A4201D3C36843610021DD -:1013D00000F0DCFE002008BD4FF0FF3008BD00002B -:1013E00070B5202304460E4683F31188A568A5B185 -:1013F000A368A269013BA360531CA361157822690D -:10140000934224BFE368A361E3690BB12046984788 -:10141000002383F31188284670BD3146204600F032 -:10142000A5FE0028E2DA85F3118870BD2DE9F74F9B -:1014300005460F4690469A46D0F81C90202686F323 -:1014400011884FF0000B144664B1224639462846F5 -:10145000FFF740FF034668B95146284600F086FE74 -:101460000028F1D0002383F31188A8EB040003B017 -:10147000BDE8F08FB9F1000F03D001902846C847AE -:10148000019B8BF31188E41A1F4486F31188DBE774 -:10149000C16081614161C3611144009B0060406093 -:1014A0008260016103627047F8B504460E46174634 -:1014B000202383F31188A568A5B1A368013BA3602D -:1014C00063695A1C62611E70236962699A4224BF73 -:1014D000E3686361E3690BB120469847002080F31D -:1014E0001188F8BD3946204600F040FE0028E2DAB7 -:1014F00085F31188F8BD0000836942699A4210B5EE -:1015000001D182687AB98268013282605A1C826194 -:101510001C7803699A4201D3C3688361002100F0FB -:1015200035FE204610BD4FF0FF3010BD2DE9F74FBE -:1015300005460F4690469A46D0F81C90202686F322 -:1015400011884FF0000B144664B1224639462846F4 -:10155000FFF7EEFE034668B95146284600F006FE46 -:101560000028F1D0002383F31188A8EB040003B016 -:10157000BDE8F08FB9F1000F03D001902846C847AD -:10158000019B8BF31188E41A1F4486F31188DBE773 -:10159000026843681143016003B1184770470000B7 -:1015A0001430FFF743BF00004FF0FF331430FFF754 -:1015B0003DBF00003830FFF7B9BF00004FF0FF33E8 -:1015C0003830FFF7B3BF00001430FFF709BF000049 -:1015D0004FF0FF311430FFF703BF00003830FFF742 -:1015E00063BF00004FF0FF323830FFF75DBF0000EF -:1015F00000207047FFF7A2BD37B50F4B03600023F3 -:1016000043608360C3600123044603741546009061 -:101610000B464FF4807200F15C011430FFF7B6FE08 -:1016200000942B464FF4807204F5AE7104F138003B -:10163000FFF72EFF03B030BD9C3C000810B52023FF -:10164000044683F31188FFF7A9FD022323740023C6 -:1016500083F3118810BD000038B5C36904460D46F8 -:101660001BB904210844FFF793FF294604F1140035 -:10167000FFF79AFE002806DA201D4FF48061BDE8CE -:101680003840FFF785BF38BD0268436811430160E9 -:1016900003B118477047000013B5446BD4F8943475 -:1016A0001A681178042915D1217C022912D11979DF -:1016B000128901238B4013420CD101A904F14C0083 -:1016C00001F014FFD4F89444019B2179024620686C -:1016D00000F0DAF902B010BD143001F097BE00003E -:1016E0004FF0FF33143001F091BE00004C3001F098 -:1016F00069BF00004FF0FF334C3001F063BF0000C2 -:10170000143001F065BE00004FF0FF31143001F0DD -:101710005FBE00004C3001F035BF00004FF0FF32DB -:101720004C3001F02FBF0000D0F8942438B5136876 -:1017300019780429054601D0012038BD017C022911 -:10174000FAD112795C89012090400440F4D105F16E -:10175000140001F0F7FD02460028EDD0D5F89454AE -:101760004FF480732868697900F07CF9204638BD11 -:10177000406BFFF7D9BF00000020704770470000A2 -:101780007FB5124B0360002343608360C360012573 -:1017900002260F4B057404460290019300F1840267 -:1017A000294600964FF48073143001F0A7FD094BD1 -:1017B0000193029400964FF4807304F52372294636 -:1017C00004F14C0001F06EFE04B070BDC43C000892 -:1017D00071170008991600080B68202282F31188FF -:1017E0000A7903EB820290614A79093243F82200B8 -:1017F0008A7912B103EB8203986102230374C0F863 -:101800009414002383F311887047000038B5037FD8 -:10181000044613B190F85430ABB9201D01250221C4 -:10182000FFF732FF04F1140025776FF0010100F09B -:10183000B9FC84F8545004F14C006FF00101BDE88C -:10184000384000F0AFBC38BD10B50121044604306B -:10185000FFF71AFF0023237784F8543010BD0000EF -:1018600038B504460025143001F060FD04F14C0049 -:10187000257701F02FFE201D84F854500121FFF739 -:1018800003FF2046BDE83840FFF74EBF90F84430D4 -:1018900003F06003202B19D190F84520212A0AD0AB -:1018A000222A4FF000030ED0202A0FD1084A82636B -:1018B0000722C26304E0064B83630723C36300234C -:1018C0000364012070478363C363F9E70020704716 -:1018D0000D220020D0F8943437B51A681178042905 -:1018E00004461AD1017C022917D1197912890123E2 -:1018F0008B40134211D100F14C05284601F0AAFE9D -:1019000058B101A9284601F0F1FDD4F89444019B97 -:1019100021790246206800F0B7F803B030BD00001E -:1019200000EB8103F7B59C6905460E46F4B1202310 -:1019300083F3118805EB8607201D0821FFF7A4FE1D -:10194000FB685B691B684C3413B1204601F0DCFD79 -:1019500001A9204601F0CAFD024648B1019B31466B -:10196000284600F091F8002383F3118803B0F0BDFE -:10197000FB685A691268002AF5D01B8A013B1340A4 -:10198000F1D105F14402EAE7093138B550F82140B8 -:10199000DCB1202383F31188D4F89424136852799E -:1019A00003EB8203DB689B695D6845B10421601825 -:1019B000FFF76AFE294604F1140001F0CDFC204631 -:1019C000FFF7B2FE002383F3118838BD7047000093 -:1019D00001F08CB80123037000234360C36183626C -:1019E0000362C36243620363038143817047000063 -:1019F00038B50446202383F3118800254160C56073 -:101A000005614561856101F081F80223237085F34A -:101A1000118838BD70B500EB810305465069DA6066 -:101A20000E46144618B110220021FFF7ABF9A06949 -:101A300018B110220021FFF7A5F931462846BDE86C -:101A4000704001F02DB90000028902F0010202810C -:101A5000428902F0010242810022026142618261F8 -:101A600001F0B2B9F0B400EB81044789E4680125C4 -:101A7000A4698D403D43458123600023A2606360DB -:101A8000F0BC01F0CDB90000F0B400EB810407898F -:101A9000E468012564698D403D430581236000238E -:101AA000A2606360F0BC01F047BA000070B5022389 -:101AB000002504460370A0F84C5080F84E5080F882 -:101AC0004F5005814581C56005614561856180F89C -:101AD000345001F081F863681B6823B12946204621 -:101AE000BDE87040184770BD037880F8503005237A -:101AF000037043681B6810B504460BB10421984776 -:101B000000232381638110BD436890F850201B6837 -:101B100002700BB1052118477047000090F834306F -:101B200070B5044613B1002380F8343004F1440248 -:101B3000204601F06BF963689B6863BB94F84450DE -:101B400015F0600615D194F8453005F07F0545EA9B -:101B5000032540F202339D4200F00E815BD8022D36 -:101B600000F0DC803FD8002D00F08780012D00F0D0 -:101B7000CF800021204601F0A3FB0021204601F088 -:101B800095FB63681B6813B106212046984706231E -:101B900084F8343070BD204698470028CED094F8A1 -:101BA0004B2094F84A3043EA0223E26B934238BF59 -:101BB000E36394F94430E56B002B4FF0200380F28F -:101BC000FD80002D00F0EC80092284F8342083F39E -:101BD00011880021E36BA26B2046FFF755FF00231D -:101BE00083F3118870BDB5F5817F00F0B180B5F544 -:101BF000407F49D0B5F5807FBBD194F84630012BAA -:101C0000B7D1B4F84C3023F00203A4F84C30A663EB -:101C1000E6632664C3E740F201639D421ED8B5F532 -:101C2000C06F3BD2B5F5A06FA3D1B4F84430B3F583 -:101C3000A06F0ED194F8463084F84E30204601F063 -:101C400023F863681B6813B10121204698470323DA -:101C500023700023A363E3632364A0E7B5F5106F4B -:101C600032D040F602439D4252D0B5F5006F80D18C -:101C700004F14F03A363012324E004F14C03A363A5 -:101C80000223E36325648AE794F84630012B7FF44E -:101C900070AFB4F84C3043F00203B6E794F8492033 -:101CA000616894F848304D6894F8471043EA02237D -:101CB000204694F84620A84700283FF45AAF4368CE -:101CC000A3630368E363A4E72378042B10D12023E4 -:101CD00083F311882046FFF7B7FE86F31188636807 -:101CE00084F84F601B68032121700BB12046984790 -:101CF00094F84630002BACD084F84F300423237086 -:101D000063681B68002BA4D0022120469847A0E7F7 -:101D1000374BA3630223E36300239DE794F8481045 -:101D200011F0800F204601F00F010ED001F060F895 -:101D3000012806D002287FF41CAF2E4BA363E0637A -:101D400067E72D4BA363E56363E701F043F8EFE733 -:101D500094F84630002B7FF40CAF94F8483013F021 -:101D60000F013FF476AF1A06204602D501F0BCFA07 -:101D70006FE701F0AFFA6CE794F84630002B7FF480 -:101D8000F8AE94F8483013F00F013FF462AF1B0631 -:101D9000204602D501F094FA5BE701F087FA58E794 -:101DA000142284F8342083F311882B462A462946CE -:101DB0002046FFF757FE85F3118870BD5DB11522EF -:101DC00084F8342083F311880021E36BA26B204652 -:101DD000FFF748FE03E70B2284F8342083F31188D1 -:101DE0002B462A4629462046FFF74EFEE3E700BF72 -:101DF000F43C0008EC3C0008F03C000838B590F8D2 -:101E000034300446152B29D8DFE803F03E28282873 -:101E100028283E28280B2939282828282828282837 -:101E20003E3E90F84B1090F84A20C36B42EA0122E4 -:101E30009A4214D9C268128AB3FBF2F502FB153537 -:101E40006DB9202383F311882B462A462946FFF7D4 -:101E50001BFE85F311880A2384F8343038BD14231F -:101E600084F83430202383F3118800231A4619465E -:101E70002046FFF7F7FD002383F3118838BD036C7C -:101E800003B198470023E7E7002101F019FA002188 -:101E9000204601F00BFA63681B6813B10621204647 -:101EA00098470623D8E7000090F83420152A38B563 -:101EB000044622D80123934040F6416213421DD1CB -:101EC00013F480150FD19B0217D50B2380F8343003 -:101ED000202383F311882B462A462946FFF7D4FD99 -:101EE00085F3118838BDC3689B695B682BB9036CA7 -:101EF00003B19847002384F8343038BD002101F045 -:101F0000DFF90021204601F0D1F963681B6813B1A5 -:101F10000621204698470623EDE70000024B0022E9 -:101F20001B605B609A607047582B0020002303748D -:101F30008268054B1B6899689142FBD25A6803601E -:101F40004260106058607047582B002008B520236D -:101F500083F31188037C032B05D0042B0DD02BB900 -:101F600083F3118808BD436900221A604FF0FF33E4 -:101F70004361FFF7DBFF0023F2E790E80C001A60F3 -:101F800002685360F2E70000002303748268054B87 -:101F90001B6899689142FBD85A68036042601060E0 -:101FA00058607047582B0020054B19690874186851 -:101FB00002681A605360186101230374FEF7A4B924 -:101FC000582B002030B54B1C87B005460A4C10D06A -:101FD00023690A4A01A800F001F92846FFF7E4FF47 -:101FE000049B13B101A800F04BF92369586907B0AD -:101FF00030BDFFF7D9FFF8E7582B00204D1F000830 -:1020000038B50C4D41612B6981689A68914204464C -:1020100003D8BDE83840FFF789BF1846FFF7B4FF83 -:1020200001232C61014623742046BDE83840FEF7A9 -:102030006BB900BF582B0020044B1A681B699068CD -:102040009B68984294BF002001207047582B0020C5 -:1020500010B5084C236820691A6822605460012278 -:1020600023611A74FFF790FF01462069BDE8104014 -:10207000FEF74AB9582B0020FEE7000010B50C4CC3 -:10208000FFF74CFF00F09CF880220A49204600F040 -:1020900021F8012344F8180C037400F043FC0023DA -:1020A00083F3118862B60448BDE8104000F034B8EC -:1020B000802B0020F83C0008003D000800F01AB911 -:1020C000034B59685A68521A9042FBD8704700BFB8 -:1020D000001000E082600222027400224274704705 -:1020E0008368A3F17C0243F80C2C026943F83C2C72 -:1020F000426943F8382C074A43F81C2CC26843F85D -:10210000102C022203F8082C002203F8072CA3F15C -:10211000180070472103000810B5202383F31188AD -:10212000FFF7DEFF00210446FFF76AFF002383F379 -:102130001188204610BD0000024B1B6958610F201A -:10214000FFF732BF582B0020202383F31188FFF7BD -:10215000F3BF000008B50146202383F3118808204F -:10216000FFF730FF002383F3118808BD49B1064B08 -:1021700042681B6918605A60136043600420FFF7CF -:1021800021BF4FF0FF307047582B00200368984262 -:1021900006D01A680260506059611846FFF7C6BE43 -:1021A0007047000038B504460D462068844200D1CF -:1021B00038BD036823605C604561FFF7B7FEF4E754 -:1021C000054B03F114025A619A614FF0FF32DA6154 -:1021D00000221A62704700BF582B0020F8B5274F25 -:1021E0000361C2600D46044601F06CFA3B46022DC5 -:1021F00053F8142F294638BF02219A423E461D4605 -:102200000AD138627C61BC61084422606260A160CE -:10221000BDE8F84001F040BAD7F820E0A0EB0E038B -:102220005F181FD300279068834217D8376AAA42E5 -:102230001F44376201D0C01A906073699A68914256 -:1022400019D85A682360626014605C60A160986865 -:10225000411A99604FF0FF33F361F8BD97601B1A84 -:102260001268E0E793689F4203D20EEB070001F08B -:1022700023FA3946E1E7891A1B68DFE7582B00206B -:1022800038B51B4B01685A6990421D4603F1140290 -:102290000CD0446821600368002193425C60C160F7 -:1022A00025D09A6881680A449A6038BD59614A60AD -:1022B0005B6900219342C16003D1BDE8384001F061 -:1022C000F5B99A6881680A449A602C6A01F0FAF9B3 -:1022D0006A699268001B824209D9111A012998BFC4 -:1022E000821C286ABDE83840104401F0E5B938BDC9 -:1022F000582B00202DE9F84F204C0027656904F188 -:102300001406B84601F0DEF9236AA0EB030AAB68B5 -:1023100053451DD84FF02009236AAA68D5F80CB0A0 -:1023200013442362AB68AAEB030A2B68B3425E60D6 -:102330006361EF6001D101F0B9F988F31188286970 -:10234000D84789F311886569AB689A45E4D2D9E723 -:102350006369B34210D020629A68A2EB0A029A60C5 -:10236000226AAB68821A9B1A022B2CBFC01802305B -:10237000BDE8F84F01F0A0B9BDE8F88F582B002058 -:1023800000207047FEE70000704700004FF0FF306C -:1023900070470000022906D0032906D0012906480B -:1023A00018BF0020704705487047032A9ABF0448A9 -:1023B00000EBC20000207047F03D0008A43D00087B -:1023C0001422002070B59AB001AD06460846294691 -:1023D000144600F095F82846FEF7CCFCC0B2431C2A -:1023E0005B0086E818002370032363700023023427 -:1023F0001946DAB2904204F1020401D81AB070BD55 -:10240000EA5C04F8022C04F8011C0133F1E7000037 -:1024100008B5202383F311880348FFF75BFA0023F4 -:1024200083F3118808BD00BF102D002010B50446AD -:10243000052916D8DFE801F016150316161D20230E -:1024400083F311880E4A0121FFF7E4FA20460D4A72 -:102450000221FFF7DFFA0C48FFF702FA002383F3AB -:10246000118810BD202383F311880748FFF7CEF9A8 -:10247000F4E7202383F311880348FFF7E5F9EDE73C -:10248000203D0008443D0008102D002038B50C4DBB -:102490000C4C0D492A4604F10800FFF793FF05F1A3 -:1024A000CA0204F110000949FFF78CFF05F5CA7252 -:1024B00004F118000649BDE83840FFF783BF00BFAC -:1024C000D831002014220020703D00087D3D000816 -:1024D0008A3D000870B5044608460D46FEF74AFCE2 -:1024E000C6B22046013403780BB9184670BD324697 -:1024F0002946FEF727FC0028F3D1012070BD00001B -:102500002DE9F84F05460C46FEF734FC2B49C6B2C0 -:102510002846FFF7DFFF08B10236F6B22849284601 -:10252000FFF7D8FF08B11036F6B2632E0DD8DFF8EA -:102530008C80DFF88C90234FDFF890A0DFF890B00C -:102540002E7846B92670BDE8F88F29462046BDE8AA -:10255000F84F01F04DBB252E2CD1072241462846CD -:10256000FEF7F0FB58B9DBF800302360DBF80430ED -:1025700063609BF80830237207350934E0E70822CE -:1025800049462846FEF7DEFBA0B90F4BA21C13F804 -:10259000011F09095345C95D02F8021C197801F0B1 -:1025A0000F0102F10202C95D02F8031CEFD11834D9 -:1025B0000835C5E7267001350134C1E7103E000833 -:1025C0008A3D0008223E00080F7AFF1F1B7AFF1F7A -:1025D000183E0008BFF34F8F024AD368DB03FCD4D8 -:1025E000704700BF003C024008B5094B1B7873B927 -:1025F000FFF7F0FF074B1A69002ABFBF064A5A606F -:1026000002F188325A601A6822F480621A6008BDAA -:1026100036340020003C02402301674508B50B4BCF -:102620001B7893B9FFF7D6FF094B1A6942F00042B5 -:102630001A611A6842F480521A601A6822F48052B1 -:102640001A601A6842F480621A6008BD36340020AD -:10265000003C0240172870B513D80B4A0B4C137876 -:1026600063B90B4E4FF0006144F8231056F8235025 -:102670000133182B2944F7D10123137054F820009B -:1026800070BD002070BD00BF983400203834002099 -:10269000343E0008014B53F820007047343E0008D8 -:1026A00018207047172810B5044601D9002010BD26 -:1026B000FFF7D0FF064B53F824301844C21A0BB969 -:1026C000012010BD12680132F0D1043BF6E700BFD3 -:1026D000343E0008172810B5044629D8FFF77AFFC2 -:1026E000FFF782FF1349F323CB600C23B0FBF3F217 -:1026F00003FB1200D30143EAC003DBB243F40073CF -:1027000043F002030B610B6943F480330B61FFF765 -:1027100061FF2046FFF79EFF074B53F8241000F09F -:10272000DDF8FFF77BFF2046BDE81040FFF7BABF9A -:10273000002010BD003C0240343E00082DE9F84363 -:1027400012F00103154640D18218B2F1026F3CD25B -:102750002C4B1B6813F0010337D02B4CFFF744FFC1 -:10276000F323E360FFF736FF40F20127032D01D981 -:10277000830713D0244C0F46401A40F20118EB1B7C -:102780000B44012B00EB0706236924D823F0010337 -:102790002361FFF743FF0120BDE8F883236923F499 -:1027A0004073236123693B43236151F8046B066046 -:1027B000BFF34F8FFFF70EFF03689E4208D02369D7 -:1027C00023F001032361FFF729FF0020BDE8F88310 -:1027D000043D0430CAE723F440732361236943EACC -:1027E00008032361B94637F8023B3380BFF34F8FAC -:1027F000FFF7F0FE3688B9F80030B6B2B342BED06B -:10280000DDE700BF00380240003C0240084908B53F -:102810000B7828B153B9FFF7E7FE01230B7008BD11 -:1028200023B1BDE808400870FFF7F8BE08BD00BF3F -:102830003634002010B50244064B0439D2B290421F -:1028400000D110BD441C00B253F8200041F8040F21 -:10285000E0B2F4E750280040104B30B51C6F240460 -:1028600007D41C6F44F400741C671C6F44F40044CC -:102870001C670B4C236843F4807323600244094BAC -:102880000439D2B2904200D130BD441C00B251F89C -:10289000045F43F82050E0B2F4E700BF0038024084 -:1028A000007000405028004007B5012201A9002017 -:1028B000FFF7C0FF019803B05DF804FB13B50446B1 -:1028C000FFF7F2FFA04206D002A9012241F8044D11 -:1028D0000020FFF7C1FF02B010BD000070470000EC -:1028E000034B1B689B0042BF024B01221A707047CA -:1028F0007438024099340020014B1878704700BFAB -:1029000099340020EFF3098305494A6822F0010257 -:102910004A60683383F30988002383F31188704782 -:1029200030EF00E0202080F3118862B60B4B0C4A98 -:10293000D96821F4E0610904090C0A430949DA6005 -:10294000CA6842F08072CA6007490A6842F0010210 -:102950000A601022DA7783F82200704700ED00E069 -:102960000003FA05F0ED00E0001000E010B52023B0 -:1029700083F311880E4B5B6813F4006314D0F1EEFF -:10298000103AEFF30984683C4FF08073E361094B20 -:10299000DB68236684F30988FFF74EFB10B1064B12 -:1029A000A36110BD054BFBE783F3118810BD00BF89 -:1029B00000ED00E030EF00E03303000836030008CC -:1029C00070470000FEE70000084A094B09498B42A6 -:1029D00004D3094A0021934205D3704752F8040FEB -:1029E00043F8040BF3E743F8041BF4E7F03F000857 -:1029F000143500201435002014350020836D70B587 -:102A0000446D9E6800214FF0FF354A01A318013143 -:102A1000D3F800090028BEBFD3F8000940F0804079 -:102A2000C3F80009D3F8000B0028BEBFD3F8000B91 -:102A300040F08040C3F8000BA3188E42C3F8085939 -:102A4000C3F8085BE1D24FF00113C4F81C3870BD25 -:102A5000890141F02001016103699B06FCD4122029 -:102A6000FFF72EBB204B03EB80022DE9F047D2F895 -:102A70000CE05D6DDEF81420461CD2F800C005EBBA -:102A8000063605EB4018516861450BD3D5F834285C -:102A9000012303FA00F022EA0000C5F834081846C2 -:102AA000BDE8F087BEF81040ACEB0103A34228BF9D -:102AB0002346D8F81849A4B2B3EB840F10D8946811 -:102AC0001F46A4F1040959F804AFC6F800A0042F6A -:102AD00001D9043FF7E71C440B4494605360D2E7EC -:102AE0000020BDE8F08700BF9C34002010B5054CE5 -:102AF0002046FEF76FFF4FF0A0436365024BA365CE -:102B000010BD00BF9C340020B83E00080378012BA4 -:102B100070B5054650D12A4B446D98421BD1294BC4 -:102B20005A6B42F080025A635A6D42F080025A6535 -:102B30005A6D5A6942F080025A615A6922F0800245 -:102B40005A610E2143205B69FEF7AEFB1E4BE3602A -:102B50001E4BC4F800380023C4F8003EC023236095 -:102B60006E6D4FF45023A3633369002BFCDA01230D -:102B700033610C20FFF7A4FA3369DB07FCD4122081 -:102B8000FFF79EFA3369002BFCDA0026A660284680 -:102B9000FFF734FF6B68C4F81068DB68C4F814688A -:102BA000C4F81C684BB90A4BA3614FF0FF33636153 -:102BB000A36843F00103A36070BD064BF4E700BFB8 -:102BC0009C340020003802404014004003002002E2 -:102BD000003C30C0083C30C0F8B5446D05460021CB -:102BE0002046FFF735FFA96D00234FF001128F68D3 -:102BF000C4F834384FF00066C4F81C284FF0FF309A -:102C000004EB431201339F42C2F80069C2F8006B23 -:102C1000C2F80809C2F8080BF2D20B686A6DEB65BE -:102C2000636210231361166916F01006FBD112209F -:102C3000FFF746FAD4F8003823F4FE63C4F80038EE -:102C4000A36943F4402343F01003A3610923C4F8AC -:102C50001038C4F814380A4BEB604FF0C043C4F886 -:102C6000103B084BC4F8003BC4F81069C4F80039A5 -:102C7000EB6D03F1100243F48013EA65A362F8BD23 -:102C8000943E000840800010426D90F84E10D2F83B -:102C9000003823F4FE6343EA0113C2F8003870479A -:102CA0002DE9F0410EB200EB86080D46D8F80C1065 -:102CB0000F6807F00303022B50D0032B50D03D4A7E -:102CC0003D4F012B18BF1746446D4FEA451E04EBDC -:102CD0000E030022C3F8102B8A6905F1100C002A9C -:102CE00040D04A8A05F158035B013A43E250012380 -:102CF000D4F81C2803FA0CF31343A6444A69C4F819 -:102D00001C380023CEF8103905F13F03002A39D0D2 -:102D10000A8A898B9208012988BF4A43C16D04EB56 -:102D20008303561841EA0242C66529465A60204686 -:102D3000FFF78EFED8F80C301B8A43EA85531F43F9 -:102D400005F148035B01E7500123D4F81C2803FA7E -:102D500005F51543C4F81C58BDE8F081174FB3E7DB -:102D6000174FB1E704EB4613D3F8002B22F40042CF -:102D7000C3F8002BD4F81C28012303FA0CF322EA31 -:102D80000303BAE704EB83030E4A5A6004EB4616CA -:102D900029462046FFF75CFED6F8003923F40043AD -:102DA000C6F80039D4F81C38012202FA05F523EAE6 -:102DB0000505CFE700800010008004100080081097 -:102DC00000800C1000040002826D1268C265FFF7DB -:102DD00015BE00005831436D49015B5813F40040A3 -:102DE00004D013F4001F14BF01200220704700001C -:102DF0004831436D49015B5813F4004004D013F48B -:102E0000001F14BF012002207047000000EB810169 -:102E1000CB68196A0B6813604B68536070470000F9 -:102E200000EB810330B5DD68AA691368D36019B976 -:102E3000402B84BF402313606B8A1468426D1C448E -:102E4000013CB4FBF3F46343033323F0030302EBCD -:102E5000411043EAC44343F0C043C0F8103B2B6821 -:102E600003F00303012B09B20ED1D2F8083802EBAC -:102E7000411013F4807FD0F8003B14BF43F080531F -:102E800043F00053C0F8003B02EB4112D2F8003B84 -:102E900043F00443C2F8003B30BD00002DE9F0418F -:102EA000244D6E6D06EB40130446D3F8087BC3F83F -:102EB000087B38070AD5D6F81438190706D505EB6C -:102EC00084032146DB6828465B689847FA072FD5BC -:102ED000D6F81438DB072BD505EB8403D968CCB9B9 -:102EE0008B69488A5E68B6FBF0F200FB12628AB911 -:102EF0001868DA6890420DD2121A83E81400202371 -:102F000083F311880B482146FFF78AFF84F3118869 -:102F1000BDE8F081012303FA04F26B8923EA02037E -:102F20006B81CB6823B121460248BDE8F0411847C8 -:102F3000BDE8F0819C34002000EB810370B5DD68B2 -:102F4000436D6C692668E6604A0156BB1A444FF42B -:102F50000020C2F810092A6802F00302012A0AB20E -:102F60000ED1D3F8080803EB421410F4807FD4F894 -:102F7000000914BF40F0805040F00050C4F8000930 -:102F800003EB4212D2F8000940F00440C2F80009F5 -:102F9000D3F83408012202FA01F10143C3F83418CE -:102FA00070BD19B9402E84BF4020206020682E8A51 -:102FB000841940F00050013C1A44B4FBF6F440EA96 -:102FC000C440C6E7F8B504461E48456D05EB4413FA -:102FD000D3F80869C3F80869F10717D5D5F8103890 -:102FE000DA0713D500EB8403D9684B691F68DA68E8 -:102FF000974218D2D21B00271A605F60202383F308 -:1030000011882146FFF798FF87F31188330617D5FB -:10301000D5F834280123A340134211D02046BDE83F -:10302000F840FFF71FBD012303FA04F2038923EAE6 -:10303000020303818B68002BE8D021469847E5E71F -:10304000F8BD00BF9C34002097482DE9F84F456D2E -:103050006E69AB691E4016F4805F6E61044605D050 -:10306000FEF724FDBDE8F84FFFF780BC002E12DA12 -:10307000D5F8003E8C489B071EBFD5F8003E23F0D4 -:103080000303C5F8003ED5F8043823F00103C5F862 -:103090000438FEF739FD370505D58348FFF7AEFC48 -:1030A0008148FEF721FDB0040CD5D5F8083813F09F -:1030B000060FEB6823F470530CBF43F4105343F432 -:1030C000A053EB60310704D56368DB680BB1764829 -:1030D0009847F2025AD4B3020CD5D4F85480DFF8E2 -:1030E000C8A100274FF00109A36D9B68F9B28B427C -:1030F00080F08780F70619D5616D0A6AC2F30A1756 -:1031000002F00F0302F4F012B2F5802F00F0A1805C -:10311000B2F5402F0AD104EB830301F58051DB683F -:10312000186A00231A469F4240F087803003D5F882 -:10313000184813D5E10302D50020FFF7AFFEA20324 -:1031400002D50120FFF7AAFE630302D50220FFF794 -:10315000A5FE270302D50320FFF7A0FE750381D546 -:10316000E00702D50020FFF72DFFA10702D50120BF -:10317000FFF728FF620702D50220FFF723FF23078E -:103180007FF570AF0320FFF71DFF6BE7D4F8548085 -:10319000DFF814A100274FF00109A36D9B685FFAC7 -:1031A00087FB5B4597D308EB4B13D3F8002902F458 -:1031B0004022B2F5802F22D1D3F80029002A1EDA4E -:1031C000D3F8002942F09042C3F80029D3F800292F -:1031D000002AFBDB5946606DFFF73AFC228909FAA9 -:1031E0000BF322EA0303238104EB8B03DB689B6868 -:1031F00013B15946504698475846FFF733FC0137FC -:10320000CBE708EB4112D2F8003B03F44023B3F5BF -:10321000802F10D1D2F8003B002B0CDA628909FA1A -:1032200001F322EA0303638104EB8103DB68DB68BB -:103230000BB150469847013756E79C0708BF0A680C -:10324000072B98BF027003F101039CBF120A0130E3 -:1032500069E7023304EB830201F5805152689069FB -:103260000268D0F808C04068A2EB000E00221046A9 -:1032700097420AD104EB830463689B699A683A44D5 -:103280009A605A6817445F6050E712F0030F08BF56 -:103290000868964588BF8CF8000002F1010284BFDF -:1032A000000A0CF1010CE3E79C340020436D03EBB2 -:1032B0004111D1F8003B43F40013C1F8003B7047C3 -:1032C000436D03EB4111D1F8003943F40013C1F809 -:1032D00000397047436D03EB4111D1F8003B23F4F3 -:1032E0000013C1F8003B7047436D03EB4111D1F867 -:1032F000003923F40013C1F80039704730B5039C3E -:103300000172043304FB0325C361049B03630021A2 -:10331000059B00604060C16042610261856104629A -:1033200042628162C162436330BD00000022416A93 -:1033300041610161C2608262C2626FF00101FEF709 -:1033400031BF000003694269934203D1C2680AB1E8 -:1033500000207047181D704703691960C268013268 -:10336000C260C269134482690361934224BF436A05 -:1033700003610021FEF70ABF38B504460D46E36835 -:103380003BB16269131D1268A3621344E36200201B -:1033900038BD237A33B929462046FEF7E7FE0028D8 -:1033A000EDDA38BD6FF00100FBE70000C368C269C9 -:1033B000013BC3604369134482694361934224BF64 -:1033C000436A436100238362036B03B1184770476C -:1033D00070B52023044683F31188866A3EB9FFF74F -:1033E000CBFF054618B186F31188284670BDA36A45 -:1033F000E26A13F8015BA362934202D32046FFF70F -:10340000D5FF002383F31188EFE700002DE9F84F83 -:1034100004460E4690469946202787F311880025DA -:10342000AA46D4F828B0BBF1000F09D1494620467E -:10343000FFF7A2FF20B18BF311882846BDE8F88F73 -:10344000A16AE36AA8EB050B5B1A9B4528BF9B4664 -:10345000BBF1400F1BD9334601F1400251F8040B78 -:1034600043F8040B9142F9D1A36A40334036A3627A -:103470004035A26AE36A9A4202D32046FFF796FFDC -:103480008AF311884545D8D287F31188C9E73046B9 -:103490005A46FDF74DFCA36A5B445E44A3625D445B -:1034A000E7E7000010B5029C0172043303FB04211E -:1034B000C36100238362C362039B0363049B0060B8 -:1034C0004060C460426102618161046242624363A0 -:1034D00010BD0000026AC260426A426102610022BD -:1034E0008262C2626FF00101FEF75CBE436902694D -:1034F0009A4203D1C2680AB100207047184650F8BA -:10350000043B0B6070470000C368C2690133C360AD -:103510004369134482694361934224BF436A436110 -:103520000021FEF733BE000038B504460D46E368BF -:103530003BB123691A1DA262E2691344E3620020D1 -:1035400038BD237A33B929462046FEF70FFE0028FE -:10355000EDDA38BD6FF00100FBE700000369196088 -:10356000C268013AC260C26913448269036193422E -:1035700024BF436A036100238362036B03B11847CE -:103580007047000070B5202304460E4683F311886F -:10359000856A35B91146FFF7C7FF10B185F3118869 -:1035A00070BDA36A1E70A36AE26A01339342A362EC -:1035B00004D3E16920460439FFF7D0FF002080F3EF -:1035C000118870BD2DE9F84F04460D4691469A4684 -:1035D0004FF0200888F311880026B346A76A4FB938 -:1035E00051462046FFF7A0FF20B187F311883046EF -:1035F000BDE8F88FA06AE76AA9EB06033F1A9F426D -:1036000028BF1F46402F1BD905F1400355F8042B56 -:1036100040F8042B9D42F9D1A36A4033A36240369F -:10362000A26AE36A9A4204D3E16920460439FFF7AB -:1036300095FF8BF311884E45D9D288F31188CDE7D9 -:1036400029463A46FDF774FBA36A3B443D44A36216 -:103650003E44E5E7026943699A4203D1C3681BB956 -:10366000184670470023FBE7836A002BF8D0043B21 -:103670009B1AF5D01360C368013BC360C3691A4449 -:10368000836902619A4224BF436A03610023836213 -:103690000123E5E700F096B8034B002258631A6156 -:1036A0000222DA60704700BF000C0040014B00228C -:1036B000DA607047000C0040014B5863704700BF50 -:1036C000000C0040014B586A704700BF000C0040DE -:1036D0004B6843608B688360CB68C3600B69436150 -:1036E0004B6903628B6943620B680360704700009B -:1036F00008B5224B22481A6940F2FF110A431A61A9 -:103700001A6922F4FF7222F001021A611A691A6B17 -:103710000A431A631A6D0A431A651A4A1B6D114649 -:10372000FFF7D6FF184802F11C01FFF7D1FF174839 -:1037300002F13801FFF7CCFF154802F15401FFF701 -:10374000C7FF144802F17001FFF7C2FF124802F1EF -:103750008C01FFF7BDFF114802F1A801FFF7B8FF88 -:103760000F4802F1C401FFF7B3FF0E4802F1E00178 -:10377000FFF7AEFFBDE8084000F0AEB800380240E9 -:1037800000000240C43E000800040240000802405D -:10379000000C0240001002400014024000180240D9 -:1037A000001C02400020024008B500F00FFAFEF7AE -:1037B00065FCFFF795F8BDE80840FEF767BE00001E -:1037C00070470000104B1A6C42F008021A641A6E1F -:1037D00042F008021A660D4A1B6E936843F0080314 -:1037E00093600B4B53229A624FF0FF32DA62002251 -:1037F0009A615A63DA605A6001225A6108211A609C -:103800003220FDF751BD00BF00380240002004E027 -:10381000000C0040094A08B51369D1680B40D9B2C1 -:10382000C9439B07116107D5202383F31188FEF755 -:1038300045FC002383F3118808BD00BF000C004045 -:1038400008B5FFF7E7FFBDE80840FFF78FB80000B5 -:103850001F4B1A696FEAC2526FEAD2521A611A6993 -:10386000C2F308021A614FF0FF301A695A695861B1 -:1038700000215A6959615A691A6A62F080521A62C3 -:103880001A6A02F080521A621A6A5A6A58625A6AAE -:1038900059625A6A1A6C42F080521A641A6E42F0E7 -:1038A00080521A661A6E0B4A106840F480701060DD -:1038B000186F00F44070B0F5007F1EBF4FF48030E9 -:1038C00018671967536823F40073536000F05EB9FA -:1038D0000038024000700040354B4FF080521A64AF -:1038E000344A4FF4404111601A6842F001021A60F4 -:1038F0001A689207FCD59A6822F003029A602C4B52 -:1039000019469A6812F00C02FBD1186800F0F90011 -:1039100018609A601A6842F480321A600B689B0340 -:10392000FCD54B6F43F001034B67214B5A6F900757 -:10393000FCD5214A5A601A6842F080721A601D4A0A -:1039400053685904FCD51A4B1A689201FCD51B4ADE -:103950009A600322C3F88C20194B1A68194B9A42BB -:10396000194B21D1194A1168194A91421CD140F2D0 -:1039700005121A60144A136803F00F03052BFAD1DD -:103980000B4B9A6842F002029A609A6802F00C02AD -:10399000082AFAD15A6C42F480425A645A6E42F4B0 -:1039A00080425A665B6E704740F20572E1E700BFE5 -:1039B00000380240007000401854400700948838D6 -:1039C000002004E011640020003C024000ED00E013 -:1039D00041C20F41084A08B5536911680B4003F012 -:1039E0000103536123B1054A13680BB1506898472E -:1039F000BDE80840FEF7BABF003C0140A02300200C -:103A0000084A08B5536911680B4003F0020353617B -:103A100023B1054A93680BB1D0689847BDE80840C8 -:103A2000FEF7A4BF003C0140A0230020084A08B5CF -:103A3000536911680B4003F00403536123B1054A35 -:103A400013690BB150699847BDE80840FEF78EBF77 -:103A5000003C0140A0230020084A08B553691168C2 -:103A60000B4003F00803536123B1054A93690BB17E -:103A7000D0699847BDE80840FEF778BF003C014098 -:103A8000A0230020084A08B5536911680B4003F0D1 -:103A90001003536123B1054A136A0BB1506A98476A -:103AA000BDE80840FEF762BF003C0140A0230020B3 -:103AB000174B10B55C691A68144004F478725A61A7 -:103AC000A30604D5134A936A0BB1D06A98476006DF -:103AD00004D5104A136B0BB1506B9847210604D5DF -:103AE0000C4A936B0BB1D06B9847E20504D5094A99 -:103AF000136C0BB1506C9847A30504D5054A936C21 -:103B00000BB1D06C9847BDE81040FEF72FBF00BF47 -:103B1000003C0140A02300201A4B10B55C691A68D4 -:103B2000144004F47C425A61620504D5164A136DB0 -:103B30000BB1506D9847230504D5134A936D0BB113 -:103B4000D06D9847E00404D50F4A136E0BB1506E48 -:103B50009847A10404D50C4A936E0BB1D06E9847D8 -:103B6000620404D5084A136F0BB1506F98472304C1 -:103B700004D5054A936F0BB1D06F9847BDE810404C -:103B8000FEF7F4BE003C0140A0230020062108B54A -:103B90000846FDF789FB06210720FDF785FB062176 -:103BA0000820FDF781FB06210920FDF77DFB06219A -:103BB0000A20FDF779FB06211720FDF775FB06218A -:103BC0002820BDE80840FDF76FBB000008B5FFF7EF -:103BD0003FFEFDF7E5F9FDF70DFDFDF7F9FEFDF7F9 -:103BE000CDFDFFF7EDFDBDE80840FFF753BD000038 -:103BF000034611F8012B03F8012B002AF9D1704775 -:103C0000121012131211000053544D3332463F3F2D -:103C10003F000000012033000010410101105A0153 -:103C2000031059010710310100000000083C000892 -:103C30003F00000013040000683C00083F00000043 -:103C400019040000723C00083F000000210400003D -:103C50007C3C00083F000000102D002020240020A4 -:103C600088260020F028002053544D33324634304B -:103C7000780053544D3332463432780053544D3328 -:103C800032463434365858000096000000000000D8 -:103C90000000000000000000000000000000000024 -:103CA000BD150008A9150008E5150008D115000884 -:103CB000DD150008C9150008B5150008A115000894 -:103CC000F115000800000000F5160008E1160008D4 -:103CD0001D1700080917000815170008011700082C -:103CE000ED160008D916000879170008000000003A -:103CF00001000000000000006D61696E000000001E -:103D0000183D0008982B0020102D00200100000015 -:103D1000792000080000000069646C650000000064 -:103D200002000000000000002119000889190008A5 -:103D300040004000A8310020B831002002000000FF -:103D4000000000000300000000000000CD19000882 -:103D50000000000010000000C8310020000000003A -:103D600001000000000000009C340020010102005E -:103D70004865782F50726F6669434E430043756201 -:103D800065426C61636B2D424C002553455249419D -:103D90004C2500002D240008952300088D180008EC -:103DA0001124000843000000AC3D00080902430054 -:103DB000020100C0320904000001020201000524D2 -:103DC000001001052401000104240202052406005C -:103DD00001070582030800FF09040100020A000030 -:103DE00000070501024000000705810240000000B5 -:103DF00012000000F83D000812011001020000400E -:103E0000AE2D0110000201020301000004030904A9 -:103E100025424F415244250043756265426C6163FF -:103E20006B00303132333435363738394142434410 -:103E30004546000000400000004000000040000037 -:103E4000004000000000010000000200000002002D -:103E5000000002000000020000000200000002005A -:103E60000000020000400000004000000040000090 -:103E700000400000000001000000020000000200FD -:103E8000000002000000020000000200000002002A -:103E900000000200000000001D1B0008FD1D0008BE -:103EA000A91E000840004000FC340020FC34002023 -:103EB000010000000C3500208000000040010000DF -:103EC000030000000000812A00020000AAAAAAAA9A -:103ED00000000000FFFF00000000000000A00A003A -:103EE0000000000000000000AAAAAAAA000000002A -:103EF000FFFF00000000000000000000140000545C -:103F000000000000AAAAAAAA14000054FFFF0000A3 -:103F1000000000000000000080699A01000000001D -:103F2000AAAA8AAA40555501FFFF00000070700739 -:103F3000777000004081020100000000AAAAAAAA2E -:103F400000410100F7FF00000000008008000000B1 -:103F50000000000000000000AAAAAAAA00000000B9 -:103F6000FFFF000000000000000000000000000053 -:103F700000000000AAAAAAAA00000000FFFF00009B -:103F80000000000000000000000000000000000031 -:103F90000A00000000000000030000000000000014 -:103FA0000000000000000000000000000000000011 -:103FB0000000000000000000000000000000000001 -:103FC000090000000000000000C01F00FF00960074 -:103FD00000000008040000000C3E00080000000083 -:103FE00000000000000000000000000000000000D1 -:043FF00000000000CD +:100B600001F09CBC0020704778230020BA230020AD +:100B700038B5084D044629B128682044BDE83840FE +:100B800001F0ACBC2868204401F090FC0028F3D0B0 +:100B900038BD00BF7823002010F003030AD1B0F560 +:100BA000047F05D200F10050A0F51040D0F80038C5 +:100BB000184670470023FBE700F10050A0F51040F5 +:100BC000D0F8100A70470000064991F8243033B17C +:100BD0000023086A81F824300822FFF7B1BF012002 +:100BE000704700BF7C230020014B1868704700BF8E +:100BF000002004E070B5194B1D68194B0138C5F38E +:100C00000B0408442D0C04221E88A6420BD15C68FC +:100C10000A46013C824213460FD214F9016F4EB1CD +:100C200002F8016BF6E7013A03F10803ECD18142C7 +:100C30000B4602D22C2203F8012B0A4A05241688FF +:100C4000AE4204D1984284BF967803F8016B013C10 +:100C500002F10402F3D1581A70BD00BF002004E075 +:100C6000503B00083C3B0008022802BF024B4FF4F7 +:100C700080529A61704700BF00100240022802BFF4 +:100C8000024B4FF080529A61704700BF0010024043 +:100C9000022801BF024A536983F4805353617047AD +:100CA0000010024070B504464FF47A764CB1412CE6 +:100CB000254628BF412506FB05F001F0D5F8641B49 +:100CC000F4E770BD10B50023934203D0CC5CC4544C +:100CD0000133F9E710BD000010B5013810F9013FEC +:100CE0003BB191F900409C4203D11AB10131013A64 +:100CF000F4E71AB191F90020981A10BD1046FCE7EC +:100D000003460246D01A12F9011B0029FAD1704796 +:100D100002440346934202D003F8011BFAE77047EE +:100D20002DE9F8431F4D144695F8242007468846C0 +:100D300052BBDFF870909CB395F824302BB9202279 +:100D4000FF2148462F62FFF7E3FF95F82400C0F12A +:100D50000802A24228BF2246D6B24146920005EBC5 +:100D60008000FFF7AFFF95F82430A41B1E44F6B2B5 +:100D7000082E17449044E4B285F82460DBD1FFF7D5 +:100D800023FF0028D7D108E02B6A03EB82038342BC +:100D9000CFD0FFF719FF0028CBD10020BDE8F883A2 +:100DA0000120FBE77C230020024B1A78024B1A70CB +:100DB000704700BFB82300201022002038B5174C20 +:100DC000174D204600F0B6FB2946204600F0DEFB1A +:100DD0002D686A6D936B23F4002393634FF47A704C +:100DE000FFF760FF0F49284600F0D6FC6A6D0E4DF4 +:100DF000936B28680D4943F400239363A0424FF49A +:100E0000E1330B6001D000F0F5FA6868A04204D02D +:100E1000BDE83840054900F0EDBA38BD98280020FB +:100E20005C3C0008643C000814220020A42300203D +:100E300070B50C4B0C4D1E780C4B55F826209A4281 +:100E400004460DD00A4B002114221846FFF760FF1C +:100E50000460014655F82600BDE8704000F0CABAAB +:100E600070BD00BFB8230020142200209828002065 +:100E7000A423002030B5094D0A4491420DD011F849 +:100E8000013B5840082340F30004013B2C4013F081 +:100E9000FF0384EA5000F6D1EFE730BD2083B8EDC0 +:100EA000026843681143016003B1184770470000AE +:100EB000024AD36843F0C003D36070470044004047 +:100EC00010B5054C054A0021204600F071FA044A8D +:100ED000044BC4E9972310BDBC230020B10E0008C9 +:100EE0000044004080DE8002234A037C002918BFB2 +:100EF0000A46012B30B5C0F868220CD11F4B98422E +:100F000009D11F4B196C41F400311964196E41F479 +:100F1000003119661B6EB2F904501468D0F86032C3 +:100F2000D0F85C12002D03EB5403B3FBF4F3BEBF07 +:100F300023F0070503F0070343EA450394888B6019 +:100F4000D38843F040030B61138943F001034B61E5 +:100F500044F4045343F02C03CB6004F4A054002366 +:100F60000B60B4F5806F0B684B680CBF7F23FF23C9 +:100F700080F8643230BD00BF703B0008BC23002005 +:100F8000003802402DE9F041D0F85C62F768336820 +:100F9000DA0504469DB20DD5302383F311884FF452 +:100FA00080610430FFF77CFF6FF4807333600023AF +:100FB00083F31188302383F3118804F1040815F0BA +:100FC0002F033AD183F31188380615D5290613D596 +:100FD000302383F3118804F1380000F065F900280C +:100FE0004EDA0821201DFFF75BFF4FF67F733B4071 +:100FF000F360002383F311887A0616D56B0614D5A7 +:10100000302383F31188D4E913239A420AD1236C45 +:1010100043B127F040073F041021201D3F0CFFF78C +:101020003FFFF760002383F31188D4F86822D36868 +:1010300043B3BDE8F041106918472B0714D015F0F1 +:10104000080F0CBF00214FF48071E80748BF41F042 +:101050002001AA0748BF41F040016B0748BF41F09B +:1010600080014046FFF71CFFAD06736805D594F874 +:1010700064122046194000F0CBF93568ADB29EE706 +:101080007060B6E7BDE8F081F8B51546826806697C +:10109000AA420B46816938BF8568761AB542044674 +:1010A0000BD218462A46FFF70DFEA3692B44A36115 +:1010B000A3685B1BA3602846F8BD0CD918463246CE +:1010C000FFF700FEAF1BE1683A463044FFF7FAFD38 +:1010D000E3683B44EBE718462A46FFF7F3FDE36875 +:1010E000E5E7000083689342F7B51546044638BF2C +:1010F0008568D0E90460361AB5420BD22A46FFF75C +:10110000E1FD63692B446361A36828465B1BA36010 +:1011100003B0F0BD0DD932460191FFF7D3FD01991F +:10112000E068AF1B3A463144FFF7CCFDE3683B442F +:10113000E9E72A46FFF7C6FDE368E4E710B50A448D +:101140000024C361029B8460C0E90000C0E905116E +:10115000C1600261036210BD08B5D0E90532934257 +:1011600001D1826882B98268013282605A1C426170 +:101170001970D0E904329A4224BFC3684361002148 +:1011800000F08EFE002008BD4FF0FF30FBE70000AE +:1011900070B5302304460E4683F31188A568A5B1C7 +:1011A000A368A269013BA360531CA361157822695F +:1011B000934224BFE368A361E3690BB120469847DB +:1011C000002383F31188284607E03146204600F0CB +:1011D00057FE0028E2DA85F3118870BD2DE9F74F3C +:1011E00004460E4617469846D0F81C904FF0300A39 +:1011F0008AF311884FF0000B154665B12A46314637 +:101200002046FFF741FF034660B94146204600F003 +:1012100037FE0028F1D0002383F31188781B03B038 +:10122000BDE8F08FB9F1000F03D001902046C84708 +:10123000019B8BF31188ED1A1E448AF31188DCE7B9 +:10124000C0E90511C160C3611144009B8260C0E91F +:101250000000016103627047F8B504460D4616466A +:10126000302383F31188A768A7B1A368013BA3606B +:1012700063695A1C62611D70D4E904329A4224BF2A +:10128000E3686361E3690BB120469847002080F36F +:10129000118807E03146204600F0F2FD0028E2DA2E +:1012A00087F31188F8BD0000D0E905239A4210B5F4 +:1012B00001D182687AB98268013282605A1C8261E7 +:1012C0001C7803699A4224BFC3688361002100F03F +:1012D000E7FD204610BD4FF0FF30FBE72DE9F74F4B +:1012E00004460E4617469846D0F81C904FF0300A38 +:1012F0008AF311884FF0000B154665B12A46314636 +:101300002046FFF7EFFE034660B94146204600F055 +:10131000B7FD0028F1D0002383F31188781B03B0B8 +:10132000BDE8F08FB9F1000F03D001902046C84707 +:10133000019B8BF31188ED1A1E448AF31188DCE7B8 +:10134000026843681143016003B118477047000009 +:101350001430FFF743BF00004FF0FF331430FFF7A6 +:101360003DBF00003830FFF7B9BF00004FF0FF333A +:101370003830FFF7B3BF00001430FFF709BF00009B +:101380004FF0FF311430FFF703BF00003830FFF794 +:1013900063BF00004FF0FF323830FFF75DBF000041 +:1013A000012914BF6FF0130000207047FFF788BDBC +:1013B00037B515460E4A026000224260C0E902229B +:1013C0000122044602740B46009000F15C014FF4C8 +:1013D00080721430FFF7B2FE00942B464FF48072F7 +:1013E00004F5AE7104F13800FFF72AFF03B030BDF9 +:1013F000843B000810B53023044683F31188FFF7BF +:1014000073FD02232374002080F3118810BD0000B7 +:1014100038B5C36904460D461BB904210844FFF7DB +:101420008FFF294604F11400FFF796FE002806DA24 +:10143000201D4FF40061BDE83840FFF781BF38BD83 +:10144000026843681143016003B118477047000008 +:1014500013B5446BD4F894341A681178042915D163 +:10146000217C022912D11979128901238B40134260 +:101470000CD101A904F14C0001F016FFD4F89444FA +:10148000019B21790246206800F0D0F902B010BD1E +:10149000143001F099BE00004FF0FF33143001F01A +:1014A00093BE00004C3001F06BBF00004FF0FF33E3 +:1014B0004C3001F065BF0000143001F067BE000041 +:1014C0004FF0FF31143001F061BE00004C3001F0EC +:1014D00037BF00004FF0FF324C3001F031BF000049 +:1014E0000020704710B5D0F894341A681178042998 +:1014F000044617D1017C022914D15979528901235C +:101500008B4013420ED1143001F0FAFD024648B16F +:10151000D4F894444FF4807361792068BDE810409A +:1015200000F072B910BD0000406BFFF7DBBF000098 +:10153000704700007FB5124B036000234360C0E991 +:101540000233012502260F4B0574044602900193D5 +:1015500000F18402294600964FF48073143001F0A4 +:10156000ABFD094B0294CDE9006304F523724FF4FF +:101570008073294604F14C0001F072FE04B070BD86 +:10158000AC3B000829150008511400080B683022F4 +:1015900082F311880A7903EB820290614A79093259 +:1015A00043F822008A7912B103EB82039861022387 +:1015B000C0F894140374002080F311887047000071 +:1015C00038B5037F044613B190F85430ABB9201DF1 +:1015D00001250221FFF734FF04F1140025776FF095 +:1015E000010100F069FC84F8545004F14C006FF0E4 +:1015F0000101BDE8384000F05FBC38BD10B50121E5 +:1016000004460430FFF71CFF0023237784F854308E +:1016100010BD000038B504460025143001F064FD0B +:1016200004F14C00257701F033FE201D84F854505E +:101630000121FFF705FF2046BDE83840FFF752BF04 +:1016400090F8443003F06003202B07D190F8452038 +:10165000212A4FF0000303D81F2A06D80020704724 +:10166000222AFBD1C0E90E3303E0034A826307223A +:10167000C2630364012070471C22002037B5D0F8F4 +:1016800094341A681178042904461AD1017C02297D +:1016900017D11979128901238B40134211D100F11E +:1016A0004C05284601F0B4FE58B101A9284601F0C6 +:1016B000FBFDD4F89444019B21790246206800F098 +:1016C000B5F803B030BD0000F0B500EB810385B084 +:1016D0009E6904460D46FEB1302383F3118804EB66 +:1016E0008507301D0821FFF7ABFEFB685B691B68AF +:1016F00006F14C001BB1019001F0E4FD019803A933 +:1017000001F0D2FD024648B1039B2946204600F075 +:101710008DF8002383F3118805B0F0BDFB685A698A +:101720001268002AF5D01B8A013B1340F1D104F165 +:101730004402EAE7093138B550F82140DCB13023E2 +:1017400083F31188D4F894241368527903EB82034D +:10175000DB689B695D6845B104216018FFF770FE86 +:10176000294604F1140001F0D5FC2046FFF7BAFE2B +:10177000002383F3118838BD7047000001F034B8AE +:10178000012303700023C0E90133C3618362036254 +:10179000C36243620363704738B50446302383F362 +:1017A00011880025C0E90355C0E90555416001F0E5 +:1017B0002BF80223237085F31188284638BD0000DA +:1017C00070B500EB810305465069DA600E46144699 +:1017D00018B110220021FFF79BFAA06918B110225E +:1017E0000021FFF795FA31462846BDE8704001F028 +:1017F000D5B80000826802F0011282600022C0E9C0 +:101800000422826101F056B9F0B400EB81044789EB +:10181000E4680125A4698D403D4345812360002390 +:10182000A2606360F0BC01F071B90000F0B400EB9D +:1018300081040789E468012564698D403D43058181 +:1018400023600023A2606360F0BC01F0EBB90000EC +:1018500070B50223002504460370C0E90255C0E9B3 +:101860000455C564856180F8345001F033F863682D +:101870001B6823B129462046BDE87040184770BD5B +:101880000378052B10B504460AD080F850300523A4 +:10189000037043681B680BB1042198470023A360C1 +:1018A00010BD00000178052906D190F8502043684A +:1018B00002701B6803B118477047000070B590F8BC +:1018C0003430044613B1002380F8343004F144026C +:1018D000204601F011F963689B68B3B994F844306D +:1018E00013F0600535D00021204601F0B1FB002146 +:1018F000204601F0A3FB63681B6813B10621204654 +:101900009847062384F8343070BD20469847002855 +:10191000E4D0B4F84A30E26B9A4288BFE36394F9AA +:101920004430E56B002B4FF0300380F20381002D33 +:1019300000F0F280092284F8342083F3118800211A +:10194000D4E90E232046FFF771FF002383F31188AB +:10195000DAE794F8452003F07F0343EA022340F2DC +:101960000232934200F0C58021D8B3F5807F48D081 +:101970000DD8012B3FD0022B00F09380002BB2D169 +:1019800004F14C02A2630222E2632364C1E7B3F5CF +:10199000817F00F09B80B3F5407FA4D194F846305E +:1019A000012BA0D1B4F84C3043F0020332E0B3F580 +:1019B000006F4DD017D8B3F5A06F31D0A3F5C06339 +:1019C000012B90D8636894F846205E6894F847101D +:1019D000B4F848302046B047002884D04368A36359 +:1019E0000368E3631AE0B3F5106F36D040F60242A5 +:1019F00093427FF478AF5C4BA3630223E36300233D +:101A0000C3E794F84630012B7FF46DAFB4F84C3047 +:101A100023F00203C4E90E55A4F84C30256478E79E +:101A2000B4F84430B3F5A06F0ED194F8463084F882 +:101A30004E30204600F0A6FF63681B6813B10121F9 +:101A400020469847032323700023C4E90E339CE704 +:101A500004F14F03A3630123C3E72378042B10D1C0 +:101A6000302383F311882046FFF7C4FE85F31188E5 +:101A70000321636884F84F5021701B680BB1204626 +:101A8000984794F84630002BDED084F84F3004237A +:101A9000237063681B68002BD6D00221204698472C +:101AA000D2E794F848301D0603F00F0120460AD50E +:101AB00001F014F8012804D002287FF414AF2B4B56 +:101AC0009AE72B4B98E700F0FBFFF3E794F84630DA +:101AD000002B7FF408AF94F8483013F00F01B3D017 +:101AE0001A06204602D501F0C7FAADE701F0BAFAAE +:101AF000AAE794F84630002B7FF4F5AE94F848300E +:101B000013F00F01A0D01B06204602D501F0A0FA69 +:101B10009AE701F093FA97E7142284F8342083F3CC +:101B200011882B462A4629462046FFF76DFE85F38D +:101B30001188E9E65DB1152284F8342083F3118819 +:101B40000021D4E90E232046FFF75EFEFDE60B22BE +:101B500084F8342083F311882B462A4629462046F0 +:101B6000FFF764FEE3E700BFDC3B0008D43B00085E +:101B7000D83B000838B590F834300446002B3ED0EE +:101B8000063BDAB20F2A34D80F2B32D8DFE803F045 +:101B9000373131082232313131313131313137375A +:101BA000C56BB0F84A309D4214D2C3681B8AB5FB9E +:101BB000F3F203FB12556DB9302383F311882B46E2 +:101BC0002A462946FFF732FE85F311880A2384F856 +:101BD00034300EE0142384F83430302383F311883A +:101BE00000231A4619462046FFF70EFE002383F312 +:101BF000118838BD036C03B198470023E7E7002143 +:101C0000204601F025FA0021204601F017FA63680A +:101C10001B6813B10621204698470623D7E700002A +:101C200010B590F83430142B044629D017D8062B61 +:101C300005D001D81BB110BD093B022BFBD80021F8 +:101C4000204601F005FA0021204601F0F7F963680B +:101C50001B6813B1062120469847062319E0152B6F +:101C6000E9D10B2380F83430302383F3118800232B +:101C70001A461946FFF7DAFD002383F31188DAE7E5 +:101C8000C3689B695B68002BD5D1036C03B198478F +:101C9000002384F83430CEE700230375826803699B +:101CA0001B6899689142FBD25A68036042601060D9 +:101CB0005860704700230375826803691B68996840 +:101CC0009142FBD85A6803604260106058607047C8 +:101CD00008B50846302383F311880B7D032B05D00C +:101CE000042B0DD02BB983F3118808BD8B6900221A +:101CF0001A604FF0FF338361FFF7CEFF0023F2E756 +:101D0000D1E9003213605A60F3E70000FFF7C4BF67 +:101D1000054BD9680875186802681A60536001227B +:101D20000275D860FEF7EEBA2826002030B50C4BBD +:101D3000DD684B1C87B004460FD02B46094A684625 +:101D400000F04EF92046FFF7E3FF009B13B1684611 +:101D500000F050F9A86907B030BDFFF7D9FFF9E7E7 +:101D600028260020D11C0008044B1A68DB68906804 +:101D70009B68984294BF00200120704728260020CD +:101D8000084B10B51C68D86822681A60536001229D +:101D90002275DC60FFF78EFF01462046BDE810404B +:101DA000FEF7B0BA2826002038B5074C0749084886 +:101DB000012300252370656001F068FB0223237076 +:101DC00085F3118838BD00BF90280020E43B00084F +:101DD0002826002000F044B9034A516853685B1A72 +:101DE0009842FBD8704700BF001000E08B600223D0 +:101DF00008618B82084670478368A3F1840243F828 +:101E0000142C026943F8442C426943F8402C094AD7 +:101E100043F8242CC26843F8182C022203F80C2C37 +:101E2000002203F80B2C044A43F8102CA3F12000E5 +:101E3000704700BF1D0300082826002008B5FFF7E3 +:101E4000DBFFBDE80840FFF761BF0000024BDB6825 +:101E500098610F20FFF75CBF28260020302383F312 +:101E60001188FFF7F3BF000008B50146302383F364 +:101E700011880820FFF75AFF002383F3118808BD5B +:101E8000064BDB6839B1426818605A6013604360E2 +:101E90000420FFF74BBF4FF0FF307047282600208B +:101EA0000368984206D01A6802605060996118462B +:101EB000FFF72CBF7047000038B504460D46206878 +:101EC000844200D138BD036823605C608561FFF700 +:101ED0001DFFF4E710B503689C68A2420CD85C684B +:101EE0008A600B604C602160596099688A1A9A6018 +:101EF0004FF0FF33836010BD1B68121BECE700003E +:101F00000A2938BF0A2170B504460D460A26601911 +:101F100001F0B4FA01F09CFA041BA54203D8751C29 +:101F20002E460446F3E70A2E04D9BDE8704001208E +:101F300001F0ECBA70BD0000F8B5144B0D46D96144 +:101F400003F1100141600A2A1969826038BF0A2230 +:101F5000016048601861A818144601F07FFA0A274A +:101F600001F076FA431BA342064606D37C1C2819CF +:101F700001F084FA27463546F2E70A2F04D9BDE876 +:101F8000F840012001F0C2BAF8BD00BF28260020A9 +:101F9000F8B506460D4601F05BFA0F4A134653F8B2 +:101FA000107F9F4206D12A4601463046BDE8F840E0 +:101FB000FFF7C2BFD169BB68441A2C1928BF2C4651 +:101FC000A34202D92946FFF79BFF22463146034828 +:101FD000BDE8F840FFF77EBF282600203826002005 +:101FE00010B4C0E9032300235DF8044B4361FFF7FD +:101FF000CFBF000010B5194C236998420DD0D0E92D +:102000000032816813605A609A680A449A6000231B +:1020100003604FF0FF33A36110BD2346026843F80D +:10202000102F53600022026022699A4203D1BDE85A +:10203000104001F01DBA936881680B44936001F071 +:1020400007FA2269E1699268441AA242E4D911446C +:10205000BDE81040091AFFF753BF00BF2826002033 +:102060002DE9F047DFF8BC8008F110072C4ED8F8B6 +:10207000105001F0EDF9D8F81C40AA68031B9A42F1 +:102080003ED81444D5E900324FF00009C8F81C408E +:1020900013605A60C5F80090D8F81030B34201D1EF +:1020A00001F0E6F989F31188D5E90331284698470C +:1020B000302383F311886B69002BD8D001F0C8F965 +:1020C0006A69A0EB04094A4582460DD2022001F05C +:1020D0001DFA0022D8F81030B34208D151462846E4 +:1020E000BDE8F047FFF728BF121A2244F2E712EBCF +:1020F000090938BF4A4629463846FFF7EBFEB5E7DF +:10210000D8F81030B34208D01444211AC8F81C0083 +:10211000A960BDE8F047FFF7F3BEBDE8F08700BF58 +:10212000382600202826002000207047FEE7000007 +:10213000704700004FF0FF307047000002290CD0BC +:10214000032904D00129074818BF00207047032A3B +:1021500005D8054800EBC2007047044870470020CE +:10216000704700BFC03C00082C220020743C0008CF +:1021700070B59AB00546084601A9144600F0C2F8A9 +:1021800001A8FEF7BDFD431C5B00C5E90034002239 +:10219000237003236370C6B201AB02341046D1B280 +:1021A0008E4204F1020401D81AB070BD13F8011B6D +:1021B00004F8021C04F8010C0132F0E708B53023E2 +:1021C00083F311880348FFF759FA002383F311883A +:1021D00008BD00BF9828002090F8443003F01F028B +:1021E000012A07D190F845200B2A03D10023C0E92A +:1021F0000E3315E003F06003202B08D1B0F848300F +:102200002BB990F84520212A03D81F2A04D8FFF7BC +:1022100017BA222AEBD0FAE7034A82630722C26385 +:1022200003640120704700BF2322002007B5052961 +:1022300017D8DFE801F0191603191920302383F3AA +:102240001188104A01900121FFF7BAFA01980E4A4D +:102250000221FFF7B5FA0D48FFF7DCF9002383F3FD +:10226000118803B05DF804FB302383F3118807481D +:10227000FFF7A6F9F2E7302383F311880348FFF74D +:10228000BDF9EBE7143C0008383C00089828002012 +:1022900038B50C4D0C4C0D492A4604F10800FFF7E7 +:1022A00067FF05F1CA0204F110000949FFF760FF5A +:1022B00005F5CA7204F118000649BDE83840FFF779 +:1022C00057BF00BF602D00202C220020F03B0008EB +:1022D000FD3B0008083C000870B5044608460D4662 +:1022E000FEF70EFDC6B22046013403780BB918463E +:1022F00070BD32462946FEF7EFFC0028F3D10120DD +:10230000F6E700002DE9F84F05460C46FEF7F8FC0D +:102310002B49C6B22846FFF7DFFF08B10236F6B2F6 +:1023200028492846FFF7D8FF08B11036F6B2632EC9 +:102330000DD8DFF88C80DFF88C90234FDFF890A069 +:10234000DFF890B02E7846B92670BDE8F88F2946A0 +:102350002046BDE8F84F01F0D3BB252E2BD1072234 +:1023600041462846FEF7B8FC58B9DBF80030236038 +:10237000DBF8043063609BF80830237207350934BA +:10238000E0E7082249462846FEF7A6FC98B90F4B1D +:10239000A21C197809090232C95D02F8041C13F85D +:1023A000011B01F00F015345C95D02F8031CF0D178 +:1023B00018340835C6E704F8016B0135C2E700BFE1 +:1023C000E03C0008083C0008F23C0008107AFF1FBF +:1023D0001C7AFF1FE83C0008BFF34F8F024AD36806 +:1023E000DB03FCD4704700BF003C024008B5094B3A +:1023F0001B7873B9FFF7F0FF074B1A69002ABFBFBC +:10240000064A5A6002F188325A601A6822F48062E1 +:102410001A6008BDBE2F0020003C02402301674522 +:1024200008B50B4B1B7893B9FFF7D6FF094B1A6918 +:1024300042F000421A611A6842F480521A601A6827 +:1024400022F480521A601A6842F480621A6008BD51 +:10245000BE2F0020003C02401728F0B516D80C4CC7 +:102460000C4923787BB90C4D0E4618234FF00062BF +:1024700055F8047B46F8042B013B13F0FF033A4464 +:10248000F6D10123237051F82000F0BD0020FCE7B5 +:1024900020300020C02F0020043D0008014B53F8DD +:1024A00020007047043D000818207047172810B519 +:1024B000044601D9002010BDFFF7CEFF064B53F8AC +:1024C00024301844C21A0BB90120F4E71268013213 +:1024D000F0D1043BF6E700BF043D0008172838B5EB +:1024E000044628D81549FFF777FFFFF77FFFF3234E +:1024F000CB600C23B0FBF3F203FB1205D30143EADC +:10250000C503DBB243F4007343F002030B610B69B4 +:1025100043F480330B61FFF75FFFFFF79DFF084B2C +:1025200053F8241000F0DAF8FFF77AFF2046BDE8F0 +:102530003840FFF7BBBF002038BD00BF003C024061 +:10254000043D0008F8B512F00103144642D1821888 +:10255000B2F1026F57D82D4B1B6813F0010352D014 +:102560002B4DFFF743FFF323EB60FFF735FF40F2FE +:102570000127032C15D824F001046618244C401AB6 +:1025800040F20117B142236900EB010524D123F089 +:1025900001032361FFF744FF0120F8BD043C043030 +:1025A000E7E78307E7D12B6923F440732B612B699D +:1025B0003B432B6151F8046B0660BFF34F8FFFF76D +:1025C0000BFF03689E42E9D02B6923F001032B61C6 +:1025D000FFF726FF0020E0E723F44073236123691F +:1025E0003B4323610B882B80BFF34F8FFFF7F4FE33 +:1025F0002D8831F8023BADB2AB42C3D0236923F042 +:1026000001032361E4E71846C7E700BF0038024032 +:10261000003C0240084908B50B7828B11BB9FFF708 +:10262000E5FE01230B7008BD002BFCD0BDE808407F +:102630000870FFF7F5BE00BFBE2F002010B50244A2 +:10264000064BD2B2904200D110BD441C00B253F8E8 +:10265000200041F8040BE0B2F4E700BF502800402E +:102660000F4B30B51C6F240407D41C6F44F4007466 +:102670001C671C6F44F400441C670A4C236843F435 +:10268000807323600244084BD2B2904200D130BD27 +:10269000441C00B251F8045B43F82050E0B2F4E768 +:1026A00000380240007000405028004007B5012269 +:1026B00001A90020FFF7C2FF019803B05DF804FBF9 +:1026C00013B50446FFF7F2FFA04205D0012201A98D +:1026D00000200194FFF7C4FF02B010BD7047000056 +:1026E000094B5A88B2F5805F10460BD022F00203E6 +:1026F00041F20102934205D041F20703C31A584246 +:102700005841704701207047002004E0034B1A68CD +:102710001AB9034AD2F874281A607047243000208E +:102720000030024008B5FFF7F1FF024B1868C0F314 +:10273000407008BD2430002070470000FEE7000014 +:102740000A4B0B480B4A90420BD30B4BDA1C121A64 +:10275000C11E22F003028B4238BF00220021FEF787 +:10276000D7BA53F8041B40F8041BECE7EC3E000812 +:1027700020310020203100202031002070B5D0E928 +:1027800015439E6800224FF0FF3504EB42135101C0 +:10279000D3F800090028BEBFD3F8000940F08040FC +:1027A000C3F80009D3F8000B0028BEBFD3F8000B14 +:1027B00040F08040C3F8000B013263189642C3F822 +:1027C0000859C3F8085BE0D24FF00113C4F81C3875 +:1027D00070BD0000890141F02001016103699B0681 +:1027E000FCD41220FFF7F8BA10B5054C2046FEF7CE +:1027F000C7FF4FF0A0436365024BA36510BD00BF48 +:1028000028300020883D000870B50378012B05466C +:1028100050D12A4B446D98421BD1294B5A6B42F040 +:1028200080025A635A6D42F080025A655A6D5A69A5 +:1028300042F080025A615A6922F080025A610E21E8 +:1028400043205B6900F022FC1E4BE3601E4BC4F882 +:1028500000380023C4F8003EC02323606E6D4FF49F +:102860005023A3633369002BFCDA012333610C206E +:10287000FFF7B2FA3369DB07FCD41220FFF7ACFA9A +:102880003369002BFCDA0026A6602846FFF776FFA6 +:102890006B68C4F81068DB68C4F81468C4F81C6876 +:1028A0004BB90A4BA3614FF0FF336361A36843F058 +:1028B0000103A36070BD064BF4E700BF2830002081 +:1028C000003802404014004003002002003C30C0A9 +:1028D000083C30C0F8B5446D054600212046FFF79E +:1028E00079FFA96D00234FF001128F68C4F83438C6 +:1028F0004FF00066C4F81C284FF0FF3004EB431281 +:1029000001339F42C2F80069C2F8006BC2F808099F +:10291000C2F8080BF2D20B686A6DEB656362102394 +:102920001361166916F01006FBD11220FFF754FA56 +:10293000D4F8003823F4FE63C4F80038A36943F4E4 +:10294000402343F01003A3610923C4F81038C4F8EE +:1029500014380A4BEB604FF0C043C4F8103B084BEF +:10296000C4F8003BC4F81069C4F80039EB6D03F1FA +:10297000100243F48013EA65A362F8BD643D0008C9 +:1029800040800010426D90F84E10D2F8003823F4C9 +:10299000FE6343EA0113C2F8003870472DE9F8439B +:1029A00000EB8103456DDA68166806F00306731EB6 +:1029B000022B05EB41130C4680460FFA81F94FEAD2 +:1029C00041104FF00001C3F8101B4FF0010104F15A +:1029D000100398BFB60401FA03F391698EBF334E1A +:1029E00006F1805606F5004600293AD0578A04F1D0 +:1029F0005801490137436F50D5F81C180B43C5F8EF +:102A00001C382B180021C3F8101953690127611EC7 +:102A1000A7409BB3138A928B9B08012A88BF53431C +:102A2000D8F85C20981842EA034301F1400205EB14 +:102A30008202C8F85C00214653602846FFF7CAFEB0 +:102A400008EB8900C3681B8A43EA84534834640155 +:102A50001E432E51D5F81C381F43C5F81C78BDE81D +:102A6000F88305EB4917D7F8001B21F40041C7F89C +:102A7000001BD5F81C1821EA0303C0E704F13F034B +:102A800005EB83030A4A5A6028462146FFF7A2FE57 +:102A900005EB4910D0F8003923F40043C0F80039A1 +:102AA000D5F81C3823EA0707D7E700BF00800010DD +:102AB00000040002826D1268C265FFF75FBE00006D +:102AC0005831436D49015B5813F4004004D013F4AE +:102AD000001F0CBF02200120704700004831436DE9 +:102AE00049015B5813F4004004D013F4001F0CBFDD +:102AF000022001207047000000EB8101CB68196AB9 +:102B00000B6813604B6853607047000000EB810353 +:102B100030B5DD68AA691368D36019B9402B84BF4A +:102B2000402313606B8A1468426D1C44013CB4FB63 +:102B3000F3F46343033323F0030302EB411043EA4E +:102B4000C44343F0C043C0F8103B2B6803F00303B9 +:102B5000012B09B20ED1D2F8083802EB411013F460 +:102B6000807FD0F8003B14BF43F0805343F0005304 +:102B7000C0F8003B02EB4112D2F8003B43F00443A3 +:102B8000C2F8003B30BD00002DE9F041244D6E6DD0 +:102B900006EB40130446D3F8087BC3F8087B3807DC +:102BA0000AD5D6F81438190706D505EB8403214653 +:102BB000DB6828465B689847FA071FD5D6F81438B3 +:102BC000DB071BD505EB8403D968CCB98B69488A30 +:102BD0005A68B2FBF0F600FB16228AB91868DA6868 +:102BE00090420DD2121AC3E90024302383F31188D6 +:102BF0000B482146FFF78AFF84F31188BDE8F08176 +:102C0000012303FA04F26B8923EA02036B81CB6888 +:102C1000002BF3D021460248BDE8F041184700BF21 +:102C20002830002000EB810370B5DD68436D6C69CE +:102C30002668E6604A0156BB1A444FF40020C2F8E9 +:102C400010092A6802F00302012A0AB20ED1D3F851 +:102C5000080803EB421410F4807FD4F8000914BF75 +:102C600040F0805040F00050C4F8000903EB4212DD +:102C7000D2F8000940F00440C2F80009D3F8340843 +:102C8000012202FA01F10143C3F8341870BD19B9E9 +:102C9000402E84BF4020206020682E8A8419013C89 +:102CA000B4FBF6F440EAC44040F000501A44C6E7D2 +:102CB0002DE9F8433B4D6E6D06EB40130446D3F807 +:102CC0000889C3F8088918F0010F4FEA40171AD095 +:102CD000D6F81038DB0716D505EB8003D9684B69A9 +:102CE0001868DA68904230D2121A4FF000091A6060 +:102CF000C3F80490302383F3118821462846FFF758 +:102D000091FF89F3118818F0800F1CD0D6F8343861 +:102D10000126A640334216D005EB84036D6DD3F82F +:102D20000CC0DCF814200134E4B2D2F800E005EB6A +:102D300004342F445168714515D3D5F8343823EA4B +:102D40000606C5F83468BDE8F883012303FA04F2E7 +:102D50002B8923EA02032B818B68002BD3D02146D9 +:102D600028469847CFE7BCF81000AEEB010383423A +:102D700028BF0346D7F8180980B2B3EB800FE2D81A +:102D80009068A0F1040959F8048FC4F80080A0EB02 +:102D900009089844B8F1040FF5D818440B44906022 +:102DA0005360C7E7283000202DE9F74FA24C656D2E +:102DB0006E69AB691E4016F480586E6107D02046DC +:102DC000FEF746FD03B0BDE8F04F00F04DBC002E0D +:102DD00012DAD5F8003E98489B071EBFD5F8003E92 +:102DE00023F00303C5F8003ED5F8043823F00103AF +:102DF000C5F80438FEF756FD370505D58E48FFF7B0 +:102E0000BDFC8D48FEF73CFDB0040CD5D5F8083864 +:102E100013F0060FEB6823F470530CBF43F4105308 +:102E200043F4A053EB6031071BD56368DB681BB923 +:102E3000AB6923F00803AB612378052B0CD1D5F8DF +:102E4000003E7D489A071EBFD5F8003E23F00303DD +:102E5000C5F8003EFEF726FD6368DB680BB17648D7 +:102E60009847F30274D4B70227D5D4F85490DFF80A +:102E7000C8B100274FF0010A09EB4712D2F8003B16 +:102E800003F44023B3F5802F11D1D2F8003B002B7F +:102E90000DDA62890AFA07F322EA0303638104EB7D +:102EA0008703DB68DB6813B1394658469847A36D42 +:102EB00001379B68FFB29F42DED9F00617D5676DD8 +:102EC0003A6AC2F30A1002F00F0302F4F012B2F5EC +:102ED000802F00F08580B2F5402F08D104EB8303EA +:102EE0000022DB681B6A07F5805790426AD13003E5 +:102EF000D5F8184813D5E10302D50020FFF744FEAA +:102F0000A20302D50120FFF73FFE630302D5022092 +:102F1000FFF73AFE270302D50320FFF735FE7503BE +:102F20007FF550AFE00702D50020FFF7C1FEA107F3 +:102F300002D50120FFF7BCFE620702D50220FFF791 +:102F4000B7FE23077FF53EAF0320FFF7B1FE39E759 +:102F5000636DDFF8E4A0019300274FF00109A36D32 +:102F60009B685FFA87FB9B453FF67DAF019B03EBB8 +:102F70004B13D3F8001901F44021B1F5802F1FD174 +:102F8000D3F8001900291BDAD3F8001941F0904159 +:102F9000C3F80019D3F800190029FBDB5946606D0E +:102FA000FFF718FC218909FA0BF321EA03032381B7 +:102FB00004EB8B03DB689B6813B159465046984776 +:102FC0000137CCE7910708BFD7F80080072A98BFE0 +:102FD00003F8018B02F1010298BF4FEA182884E739 +:102FE000023304EB830207F580575268D2F818C009 +:102FF000DCF80820DCE9001CA1EB0C0C0021884265 +:103000000AD104EB830463689B699A6802449A605E +:103010005A6802445A606AE711F0030F08BFD7F8F4 +:1030200000808C4588BF02F8018B01F1010188BF47 +:103030004FEA1828E3E700BF28300020436D03EB78 +:103040004111D1F8003B43F40013C1F8003B704735 +:10305000436D03EB4111D1F8003943F40013C1F87B +:1030600000397047436D03EB4111D1F8003B23F465 +:103070000013C1F8003B7047436D03EB4111D1F8D9 +:10308000003923F40013C1F80039704700F16043A0 +:1030900003F561430901C9B283F80013012200F06E +:1030A0001F039A4043099B0003F1604303F561430A +:1030B000C3F880211A60704730B5039C0172043355 +:1030C00004FB0325C0E90653049B03630021059B11 +:1030D000C160C0E90000C0E90422C0E90842C0E9BB +:1030E0000A11436330BD0000416A0022C0E90411A7 +:1030F000C0E90A22C2606FF00101FEF7DDBE0000E8 +:10310000D0E90432934201D1C2680AB9181D704750 +:103110000020704703691960C2680132C260C26949 +:10312000134482690361934224BF436A036100210F +:10313000FEF7B6BE38B504460D46E3683BB162699A +:10314000131D1268A3621344E362002007E0237A90 +:1031500033B929462046FEF793FE0028EDDA38BD44 +:103160006FF00100FBE70000C368C269013BC36068 +:103170004369134482694361934224BF436A4361B4 +:1031800000238362036B03B11847704770B5302387 +:10319000044683F31188866A3EB9FFF7CBFF0546E4 +:1031A00018B186F31188284670BDA36AE26A13F845 +:1031B000015BA362934202D32046FFF7D5FF0023B1 +:1031C00083F31188EFE700002DE9F84F04460E461F +:1031D000174698464FF0300989F311880025AA4612 +:1031E000D4F828B0BBF1000F09D141462046FFF7C3 +:1031F000A1FF20B18BF311882846BDE8F88FD4E9F0 +:103200000A12A7EB050B521A934528BF9346BBF150 +:10321000400F1BD9334601F1400251F8040B43F82B +:10322000040B9142F9D1A36A40334036A362403582 +:10323000D4E90A239A4202D32046FFF795FF8AF386 +:103240001188BD42D8D289F31188C9E730465A4661 +:10325000FDF738FDA36A5B445E44A3625D44E7E783 +:1032600010B5029C0172043303FB0421C0E906136C +:103270000023C0E90A33039B0363049BC460C0E9D5 +:103280000000C0E90422C0E90842436310BD000009 +:10329000026AC260426AC0E904220022C0E90A222E +:1032A0006FF00101FEF708BED0E904239A4201D174 +:1032B000C26822B9184650F8043B0B6070470023DF +:1032C0001846FAE7C368C2690133C360436913440F +:1032D00082694361934224BF436A43610021FEF740 +:1032E000DFBD000038B504460D46E3683BB12369F5 +:1032F0001A1DA262E2691344E362002007E0237A08 +:1033000033B929462046FEF7BBFD0028EDDA38BD6B +:103310006FF00100FBE7000003691960C268013A21 +:10332000C260C269134482690361934224BF436A45 +:10333000036100238362036B03B1184770470000E9 +:1033400070B530230D460446114683F31188866A12 +:103350002EB9FFF7C7FF10B186F3118870BDA36ABD +:103360001D70A36AE26A01339342A36204D3E16948 +:1033700020460439FFF7D0FF002080F31188EDE7E5 +:103380002DE9F84F04460D46904699464FF0300A15 +:103390008AF311880026B346A76A4FB949462046EA +:1033A000FFF7A0FF20B187F311883046BDE8F88F02 +:1033B000D4E90A073A1AA8EB0607974228BF17462E +:1033C000402F1BD905F1400355F8042B40F8042B7E +:1033D0009D42F9D1A36A4033A3624036D4E90A235F +:1033E0009A4204D3E16920460439FFF795FF8BF335 +:1033F00011884645D9D28AF31188CDE729463A4645 +:10340000FDF760FCA36A3B443D44A3623E44E5E70C +:10341000D0E904239A4217D1C3689BB1836A8BB168 +:10342000043B9B1A0ED01360C368013BC360C369A1 +:103430001A44836902619A4224BF436A03610023EC +:1034400083620123184670470023FBE700F036B97A +:10345000014B586A704700BF000C0040034B00222C +:1034600058631A610222DA60704700BF000C004006 +:10347000014B0022DA607047000C0040014B58639A +:10348000704700BF000C0040FEE7000070B51B4B0A +:1034900001630025044686B0586085620E4600F040 +:1034A000BFF804F11003C4E904334FF0FF33C4E95B +:1034B0000635C4E90044A560E562FFF7C9FF2B4665 +:1034C0000246C4E9082304F134010D4A256580232E +:1034D0002046FEF78BFC0123E0600A4A0375009248 +:1034E00072680192B268CDE90223074B6846CDE9C4 +:1034F0000435FEF7A3FC06B070BD00BF9028002085 +:10350000943D0008993D000889340008024AD36AB6 +:103510001843D062704700BF282600204B684360E4 +:103520008B688360CB68C3600B6943614B6903623E +:103530008B6943620B6803607047000008B5264B37 +:1035400026481A6940F2FF110A431A611A6922F4E7 +:10355000FF7222F001021A611A691A6B0A431A6398 +:103560001A6D0A431A651E4A1B6D1146FFF7D6FFF6 +:1035700002F11C0100F58060FFF7D0FF02F1380175 +:1035800000F58060FFF7CAFF02F1540100F580608A +:10359000FFF7C4FF02F1700100F58060FFF7BEFF86 +:1035A00002F18C0100F58060FFF7B8FF02F1A8017D +:1035B00000F58060FFF7B2FF02F1C40100F5806002 +:1035C000FFF7ACFF02F1E00100F58060FFF7A6FF16 +:1035D000BDE8084000F0F0B80038024000000240AA +:1035E000A03D000808B500F06BFAFEF7DDFBFFF721 +:1035F0008DF8BDE80840FEF74BBE000070470000A4 +:10360000EFF3098305494A6B22F001024A636833EC +:1036100083F30988002383F31188704700EF00E0EB +:10362000302080F3118862B60C4B0D4AD96821F422 +:10363000E0610904090C0A43DA60D3F8FC20094967 +:1036400042F08072C3F8FC200A6842F001020A606E +:103650002022DA7783F82200704700BF00ED00E0F7 +:103660000003FA05001000E010B5302383F3118841 +:103670000E4B5B6813F4006314D0F1EE103AEFF3D5 +:103680000984683C4FF08073E361094BDB6B236670 +:1036900084F30988FEF768FB10B1064BA36110BDE7 +:1036A000054BFBE783F31188F9E700BF00ED00E06D +:1036B00000EF00E02F030008320300080E4B1A6CE5 +:1036C00042F008021A641A6E42F008021A660B4AA7 +:1036D0001B6E936843F008039360094B53229A6270 +:1036E0004FF0FF32DA6200229A615A63DA605A6060 +:1036F00001225A611A60704700380240002004E03D +:10370000000C0040094A08B51169D3680B40D9B2D2 +:10371000C9439B07116107D5302383F31188FEF756 +:1037200059FB002383F3118808BD00BF000C004043 +:103730001F4B1A696FEAC2526FEAD2521A611A69B4 +:10374000C2F308021A614FF0FF301A695A695861D2 +:1037500000215A6959615A691A6A62F080521A62E4 +:103760001A6A02F080521A621A6A5A6A58625A6ACF +:1037700059625A6A1A6C42F080521A641A6E42F008 +:1037800080521A661A6E0B4A106840F480701060FE +:10379000186F00F44070B0F5007F1EBF4FF480300A +:1037A00018671967536823F40073536000F060B919 +:1037B0000038024000700040344B4FF080521A64D1 +:1037C000334A4FF4404111601A6842F001021A6016 +:1037D0001A689107FCD59A6822F003029A602B4B75 +:1037E0009A6812F00C02FBD1196801F0F901196016 +:1037F0009A601A6842F480321A601A689203FCD503 +:103800005A6F42F001025A67204B5A6F9007FCD55D +:10381000204A5A601A6842F080721A601C4A536843 +:103820005904FCD5194B1A689201FCD51A4A9A60C2 +:103830000322C3F88C20194B1A68194B9A42194B72 +:1038400021D1194A1168194A91421CD140F205123E +:103850001A60144A136803F00F03052BFAD10B4BBF +:103860009A6842F002029A609A6802F00C02082AF2 +:10387000FAD15A6C42F480425A645A6E42F4804241 +:103880005A665B6E704740F20572E1E7003802400D +:10389000007000401854400700948838002004E06D +:1038A00011640020003C024000ED00E041C20F41E5 +:1038B000074A08B5536903F00103536123B1054A70 +:1038C00013680BB150689847BDE80840FFF7CCBEBD +:1038D000003C0140A0300020074A08B5536903F0BE +:1038E0000203536123B1054A93680BB1D06898472E +:1038F000BDE80840FFF7B8BE003C0140A030002002 +:10390000074A08B5536903F00403536123B1054A1C +:1039100013690BB150699847BDE80840FFF7A4BE92 +:10392000003C0140A0300020074A08B5536903F06D +:103930000803536123B1054A93690BB1D0699847D5 +:10394000BDE80840FFF790BE003C0140A0300020D9 +:10395000074A08B5536903F01003536123B1054AC0 +:10396000136A0BB1506A9847BDE80840FFF77CBE68 +:10397000003C0140A0300020164B10B55C6904F4F7 +:1039800078725A61A30604D5134A936A0BB1D06AC0 +:103990009847600604D5104A136B0BB1506B9847DB +:1039A000210604D50C4A936B0BB1D06B9847E20506 +:1039B00004D5094A136C0BB1506C9847A30504D584 +:1039C000054A936C0BB1D06C9847BDE81040FFF7E7 +:1039D0004BBE00BF003C0140A0300020194B10B589 +:1039E0005C6904F47C425A61620504D5164A136D81 +:1039F0000BB1506D9847230504D5134A936D0BB155 +:103A0000D06D9847E00404D50F4A136E0BB1506E89 +:103A10009847A10404D50C4A936E0BB1D06E984719 +:103A2000620404D5084A136F0BB1506F9847230402 +:103A300004D5054A936F0BB1D06F9847BDE810408D +:103A4000FFF712BE003C0140A030002008B503483B +:103A5000FDF798FABDE80840FFF706BEBC2300203A +:103A600008B5FFF74FFEBDE80840FFF7FDBD0000B9 +:103A7000062108B50846FFF709FB06210720FFF7D6 +:103A800005FB06210820FFF701FB06210920FFF7AF +:103A9000FDFA06210A20FFF7F9FA06211720FFF7A1 +:103AA000F5FA06212820FFF7F1FA07213220FFF767 +:103AB000EDFABDE808400C212620FFF7E7BA000028 +:103AC00008B5FFF735FE00F00DF8FDF76FFCFDF7C8 +:103AD00055FEFDF72DFDFFF791FDBDE80840FFF70E +:103AE000B5BC00000023054A19460133102BC2E97A +:103AF000001102F10802F8D1704700BFA030002089 +:103B0000034611F8012B03F8012B002AF9D1704765 +:103B100053544D3332463F3F3F0053544D333246AA +:103B20003430780053544D33324634327800535495 +:103B30004D333246343436585800000001203300EB +:103B40000010410001105A00031059000710310005 +:103B500000000000103B0008130400001A3B00089E +:103B600019040000243B0008210400002E3B00083B +:103B700000960000000000000000000000000000AF +:103B800000000000000000006D1300085913000839 +:103B900095130008811300088D130008791300089D +:103BA0006513000851130008A1130008000000006D +:103BB000AD14000899140008D5140008C1140008B9 +:103BC000CD140008B9140008A514000891140008C9 +:103BD000E1140008000000000100000000000000E7 +:103BE00063300000E03B0008802600209028002081 +:103BF0004865782F50726F6669434E430025424FE7 +:103C0000415244252D424C002553455249414C25F3 +:103C1000000000000200000000000000C9160008BB +:103C20003517000840004000302D0020402D0020B6 +:103C3000020000000000000003000000000000007F +:103C4000791700080000000010000000502D00202F +:103C500000000000010000000000000028300020EB +:103C6000010102002D2200083D210008D921000891 +:103C7000BD210008430000007C3C0008090243000D +:103C8000020100C032090400000102020100052403 +:103C9000001001052401000104240202052406008D +:103CA00001070582030800FF09040100020A000061 +:103CB00000070501024000000705810240000000E6 +:103CC00012000000C83C0008120110010200004070 +:103CD000AE2D0110000201020301000004030904DB +:103CE00025424F415244250043756265426C616331 +:103CF0006B00303132333435363738394142434442 +:103D00004546000000400000004000000040000068 +:103D1000004000000000010000000200000002005E +:103D2000000002000000020000000200000002008B +:103D300000000200004000000040000000400000C1 +:103D4000004000000000010000000200000002002E +:103D5000000002000000020000000200000002005B +:103D60000000020000000000BD180008751B0008DC +:103D7000211C0008400040008830002088300020CE +:103D80000100000098300020800000004001000089 +:103D9000030000006D61696E0069646C65000000DD +:103DA0000000812A00020000AAAAAAAA000000249A +:103DB000FFFF00000000000000A00A00000000005B +:103DC00000000000AAAAAAAA00000000FFFF00004D +:103DD000000000000000000014000054000000007B +:103DE000AAAAAAAA14000054FFFF000000000000C5 +:103DF000000000008069100000000000AAAA8AAA42 +:103E000040561000FFFF0000007070070000000027 +:103E10004001000100000000AAAAAAAA00010000B7 +:103E2000F7FF00000000000000000000000000009C +:103E300000000000AAAAAAAA00000000FFFF0000DC +:103E40000000000000000000000000000000000072 +:103E5000AAAAAAAA00000000FFFF000000000000BC +:103E60000000000000000000000000000A00000048 +:103E7000000000000300000000000000000000003F +:103E80000000000000000000000000000000000032 +:103E90000000000000000000000000000000000022 +:103EA000090000000000000000C01F00000000002A +:103EB000FF00000098280020BC230020009600008E +:103EC0000000080096000000000800000400000048 +:103ED000DC3C0008000000000000000000000000C2 +:0C3EE000000000000000000000000000D6 :00000001FF diff --git a/Tools/bootloaders/CubeGreen-solo_bl.bin b/Tools/bootloaders/CubeGreen-solo_bl.bin index 29a012f8da076f..238691cfdc72eb 100755 Binary files a/Tools/bootloaders/CubeGreen-solo_bl.bin and b/Tools/bootloaders/CubeGreen-solo_bl.bin differ diff --git a/Tools/bootloaders/CubeGreen-solo_bl.hex b/Tools/bootloaders/CubeGreen-solo_bl.hex index 62a0215be7206f..a841e24a368059 100644 --- a/Tools/bootloaders/CubeGreen-solo_bl.hex +++ b/Tools/bootloaders/CubeGreen-solo_bl.hex @@ -1,1019 +1,1009 @@ :020000040800F2 -:1000000000040020E10100081D0F0008210F000876 -:10001000750F0008210F0008490F0008E3010008D0 -:10002000E3010008E3010008E301000811280008CB +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E301000801360008CD :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E301000879390008A539000828 -:10006000D1390008FD390008293A0008E3010008E9 +:10005000E3010008E3010008B1380008D9380008BE +:10006000013900082939000851390008E301000866 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008553A000805 +:10009000E3010008E3010008E301000879390008E2 :1000A000E3010008E3010008E3010008E3010008A0 :1000B000E3010008E3010008E3010008E301000890 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E30100082511000839110008B8 -:1000E000BD3A0008E3010008E3010008E30100084D +:1000D000E3010008E30100084D3A0008E3010008CD +:1000E000DD390008E3010008E3010008E30100082E :1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E301000889370008E301000863 +:10010000E3010008E3010008613A0008E301000888 :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008FD2E0008B8 +:10014000E3010008E3010008E3010008A92D00080D :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E30100084D110008E301000845 +:10018000E3010008E3010008E3010008E3010008BF :10019000E3010008E3010008E3010008E3010008AF :1001A000E3010008E3010008E3010008E30100089F :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F01BFB03F02DFA4FF055301F4952 -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE702F0B3 -:1002A000F9FA03F063FA144C144DAC4203DA54F833 -:1002B000041B8847F9E700F03FF8114C114DAC42A0 -:1002C00003DA54F8041B8847F9E702F0E1BA0000AA -:1002D000000400200024002000000008000000208E -:1002E00000040020683F000800240020282400208B -:1002F00028240020903D0020E0010008E0010008D3 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F0ECFE4B -:1003300001F09CFE00DFFEE770B5204C092300258C -:1003400023706FF03F061F236570A570E57025715F -:100350006571A571E57125726672A372E57200F090 -:10036000FFFC20B10F2325726672A372E57202F0C2 -:1003700021FA044602F046FA0546D8B9104B9C42D1 -:100380001AD001339C4218BF054641F2883404BF9D -:1003900001250024002002F017FA0DB100F0B6F894 -:1003A00000F062FD00F01AFC204600F00DF900F0AC -:1003B000ADF8F9E70024EDE70446EBE72824002038 -:1003C000010007B008B500F087FBA0F120035842F8 -:1003D000584108BD07B5054B02211B88ADF8043014 -:1003E00001A800F0E5FB03B05DF804FBA43B0008A6 -:1003F000064991F8243033B100230822086A81F8B5 -:10040000243000F00DBC0120704700BF48240020BC -:100410002DE9F84F234C94F82430054688461746BA -:100420008BBB2E46DFF87C90002F38D094F824A0A8 -:10043000BAF1000F05D12022FF214846266200F0C4 -:1004400001FDCAF10805BD4228BF3D465FFA85FBA4 -:10045000AD0041462A4604EB8A0000F0C9FC94F83E -:100460002430A7EB0B079B445FFA8BFBBBF1080F13 -:100470002E44A844FFB284F824B0D5D1FFF7B8FFCA -:100480000028D1D108E0266A06EB8306B042C9D025 -:10049000FFF7AEFF0028C4D10020BDE8F88F01208F -:1004A000BDE8F88F4824002010B5202383F311887D -:1004B0001248C3680BB101F0ADFE0023104A0F488B -:1004C0004FF47A7101F06AFE002383F311880D4C1A -:1004D000236813B12368013B2360636813B1636829 -:1004E000013B6360084B1B7833B9636823B9022072 -:1004F00000F074FC3223636010BD00BF3424002080 -:10050000A9040008782500207024002010B5254B90 -:10051000254953F8042F013200D110BD8B42F8D188 -:10052000224C234B22689A423AD9224B9B6803F112 -:10053000006303F580439A4232D2002000F068FB4A -:100540001D4B0220187000F03FFC1C4B1A6C00225F -:100550001A64196E1A66196E596C5A64596E5A6685 -:100560005A6E5A6942F080025A615A6922F080023A -:100570005A615A691A6942F000521A611A6922F0E6 -:1005800000521A611B6972B60D4A0E4B13601B684C -:100590002268202181F311889D4683F30888104743 -:1005A00010BD00BFFC3F00081C40000804400008CC -:1005B000FF3F00082824002070240020003802405B -:1005C00008ED00E0004000082DE9F04F99B0B34C71 -:1005D00001902022FF2110A8A66800F033FCB04A49 -:1005E0001378A346A3B9AF480121C360117020233B -:1005F00083F31188C3680BB101F00CFE0023AA4AF3 -:10060000A8484FF47A7101F0C9FD002383F31188E3 -:10061000019B13B1A54B019A1A60A54AA349019FFA -:100620000292002313704B6099461C461D46984663 -:10063000012000F0C9FB002F00F012829B4B1B68C9 -:10064000002B40F00D8219B0BDE8F08F0220FFF7BB -:10065000B9FE002840F0FB81019BB9F1000F08BFF3 -:100660001F46944B1B88ADF82C3002210BA800F0DC -:100670009FFADDE74FF47A7000F02EFA031E039321 -:10068000EADB0220FFF79EFE82460028E4D0039BAF -:10069000581E042800F2DD81DFE800F0030E11147B -:1006A000170018A8052340F8343D042100F080FA13 -:1006B00054464FF0000856E004217848F6E704213C -:1006C0007D48F3E704217D48F0E71C24204600F034 -:1006D000A1FA04340B9004210BA800F069FA2C2C29 -:1006E000F4D1E5E7002DB7D0002CB5D00220FFF7FC -:1006F00069FE0546002800F0AF8101206C4C00F037 -:1007000087FA0220207000F05FFB4FF000095FFACB -:1007100089FA504600F08CFA074658B1504600F06E -:1007200097FA09F101090028F1D12C46A9460027C2 -:10073000634B97E701230220237000F03BFB3E460A -:10074000DBF808309E4206D2304600F063FA0130F2 -:10075000EBD10436F4E7029B00261E70534BA946EA -:100760005E602C46374600F075FB15B1002C18BFB3 -:100770000027FFF72FFE5BE7002D3FF46DAF002C45 -:100780003FF46AAF029B0220187000F01DFB32207C -:1007900000F0A2F9B0F1000AC0F25E811AF0030580 -:1007A00040F05A81DBF8082006EB0A03934200F27E -:1007B0005381BAF5807F00F24F8155450DDA4FF431 -:1007C0007A7000F089F90490049B002BC0F24481F8 -:1007D0003C4A049BAB540135EFE7C820FFF7F2FD1C -:1007E0000546002800F038811F2E11D8C6F12004DC -:1007F000544528BF544610AB26F003002246314929 -:10080000184400F0F5FA2246FF212E4800F01AFBAA -:100810004FEAAA0A5FFA8AF22A493046FFF7F8FD42 -:100820000446002800F01A8106EB8A0605469AE77E -:100830000220FFF7C7FD00283FF40EAFFFF7D8FDF9 -:1008400000283FF409AF4FF0000A5346DBF80820B8 -:1008500092451CD2BAF11F0F12D8109A01320FD054 -:100860002AF0030218A90A4452F8202C0B921846C9 -:1008700004220BA900F092FB0AF1040A0346E5E703 -:100880005046039300F0C6F9039B0B90EFE718A8BE -:10089000042140F84C3D00F08BF964E72824002047 -:1008A0007425002034240020A904000878250020A5 -:1008B00070240020A63B00082C24002030240020B7 -:1008C000A83B00087424002018A8002340F8343DF9 -:1008D000642100F039F900287FF4BEAE0220FFF752 -:1008E00071FD00283FF4B8AE0B9800F0C3F918ABC7 -:1008F00043F8480D04211846CDE718A8002340F816 -:10090000343D642100F020F900287FF4A5AE0220D8 -:10091000FFF758FD00283FF49FAE0B9800F0B8F9A0 -:1009200018AB43F8440DE5E70220FFF74BFD002824 -:100930003FF492AE00F0B2F918AB43F8400DD9E79E -:100940000220FFF73FFD00283FF486AE0BA91420DC -:1009500000F0AAF9824618A8042140F83CAD00F046 -:1009600027F951460BA896E7322000F0B5F8B0F110 -:10097000000AFFF671AE1AF0030F7FF46DAEDBF8DC -:1009800008200AEB080393423FF666AE0220FFF709 -:1009900019FD00283FF460AE2AF0030AC244D04596 -:1009A0003FF4E1AE404600F035F904210A900AA870 -:1009B00000F0FEF808F10408F1E74FF47A70FFF751 -:1009C00001FD00283FF448AEFFF712FD00283FF478 -:1009D000AFAE109B01330CD0082210A90020FFF706 -:1009E00017FD00283FF4A4AE2022FF2110A800F03C -:1009F00029FAFFF7EFFC374801F08CFB23E6002DC6 -:100A00003FF42AAE002C3FF427AE18A8002340F88C -:100A1000343D642100F098F8824600287FF41CAE33 -:100A20000220FFF7CFFC00283FF416AE0390FFF73B -:100A3000D1FC41F2883001F06DFB0B9800F04EFACA -:100A400000F008FA039B57461C461D46F0E5054694 -:100A500089E64FF00008FFE52546FDE52C4667E6F0 -:100A6000002000F039F80490049B002BFFF6E3AD62 -:100A7000012000F09FF9049B213B122B3FF6D8ADDB -:100A800001A252F823F000BF4D06000875060008C9 -:100A9000E5060008310600083106000831060008A6 -:100AA000790700086909000831080008C90800082A -:100AB000FB08000829090008310600084109000860 -:100AC00031060008BB090008670700083106000866 -:100AD000FF090008A08601002DE9F34702AE0024BB -:100AE0004FF47A7506F8014D144FDFF858804543EE -:100AF00097F900305A1C5FFA84F901D0A34212D151 -:100B000058F8240003680122D3F820A031462B4670 -:100B1000D047012807D10A4B9DF8070083F80090C1 -:100B200002B0BDE8F0870134042CE1D14FF4FA7033 -:100B300001F0F0FA4FF0FF30F2E700BF0024002090 -:100B400098250020FC3B00082DE9F0474FF47A750A -:100B5000144FDFF8588006464D43002497F90030C3 -:100B60005A1C5FFA84F901D0A34210D158F824002E -:100B700003680422D3F820A031462B46D04704282E -:100B800005D1094B83F800900020BDE8F0870134BF -:100B9000042CE3D14FF4FA7001F0BCFA4FF0FF30AF -:100BA000BDE8F0870024002098250020FC3B0008C9 -:100BB00030B4074B1A78074B53F822402368DD699D -:100BC000054B0A46AC460146204630BC604700BF94 -:100BD00098250020FC3B0008A086010070B501F0BC -:100BE000E5FC094C094E20700025306823788342CB -:100BF00008D901F0D5FC336805440133B5F5804FC1 -:100C00003360F2D370BD00BF9925002080250020FD -:100C100001F082BD00F1006000F58040006870477F -:100C200000F10060920000F5804001F00DBD000071 -:100C3000054B1A68054B1B789B1A834202D9104456 -:100C400001F0AEBC002070478025002099250020CF -:100C500038B5074D04462868204401F0A9FC28B99E -:100C600028682044BDE8384001F0BABC38BD00BF58 -:100C70008025002010F0030308D1B0F5007F05D8CF -:100C800000F10050A0F50840006870470020704750 -:100C9000014BC058704700BF107AFF1F014B186806 -:100CA000704700BF002004E070B52A4B1C68C4F3F5 -:100CB0000B03240C63B140F21342934231D040F253 -:100CC000194293422FD040F2214293422DD1032367 -:100CD000214A0C2505FB03235D6893F9082042F2A5 -:100CE00001039C4224D0B4F5805F23D041F201037C -:100CF0009C4221D041F203039C421FD041F20703E2 -:100D00009C4208BF3122441E0C44013D0B46A342C5 -:100D10001ED215F9016F581C96B1034600F8016CFC -:100D2000F5E70123D4E70223D2E73F220B4DD6E7B4 -:100D30003322E3E74122E1E75A22E4E75922E2E7DE -:100D40002C2584421D7001D9981C5A70401A70BD20 -:100D50001846FBE7002004E0CC3B0008AC3B000851 -:100D6000124B5A8842F201018A4293B214D0B3F571 -:100D7000805F13D041F20102934211D041F203028D -:100D800093420FD041F2070293420DD10423084A47 -:100D900002EB8303D87870470023F8E70123F6E7D6 -:100DA0000223F4E70323F2E700207047002004E069 -:100DB000B83B0008022802BF024B4FF480529A61F0 -:100DC000704700BF00100240022802BF024B4FF0E4 -:100DD00080529A61704700BF00100240022801BF94 -:100DE000024A536983F480535361704700100240F4 -:100DF00010B50023934203D0CC5CC4540133F9E70F -:100E000010BD000030B5441E14F9010F0B4660B14F -:100E100093F90050854201F1010106D11AB993F905 -:100E20000020801A30BD013AEEE7002AF7D11046C3 -:100E300030BD000002460346981A13F9011B002931 -:100E4000FAD1704702440346934202D003F8011BD3 -:100E5000FAE77047024B1A78024B1A70704700BFCE -:100E60009825002000240020F8B5164C1648174D90 -:100E7000174E154F00F096FC2146134800F0BEFCBB -:100E800024681448626D936B23F40023936301F08C -:100E900041F92046104900F0BDFD626D936B43F4AB -:100EA000002393634FF4E1332B60002456F82400B1 -:100EB000B84202D0294600F0D3FB0134042CF5D10E -:100EC000F8BD00BFE43C00089433002084250020D6 -:100ED000FC3B000840420F00103D000838B50B4BAA -:100EE0001A780B4B53F822400A4B9C4205460CD013 -:100EF000094B002118461422FFF7A4FF05600146A4 -:100F00002046BDE8384000F0ABBB38BD9825002036 -:100F1000FC3B00089433002084250020FEE70000FD -:100F200000B59BB0EFF3098168226846FFF760FFC8 -:100F3000EFF30583034B9A6B9A6A9A6A9A6A9A6AE4 -:100F40009B6AFEE700ED00E000B59BB0EFF309817E -:100F500068226846FFF74CFFEFF30583044B9A6B5A -:100F60009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFC4 -:100F700000ED00E000B59BB0EFF309816822684600 -:100F8000FFF736FFEFF30583034B5A6B9A6A9A6AB1 -:100F90009A6A9A6A9B6AFEE700ED00E030B5084D58 -:100FA0000A4491420BD011F8013B09245840013CFE -:100FB000F7D040F300032B4083EA5000F7E730BD41 -:100FC0002083B8ED002304491A465A50C818083344 -:100FD000802B4260F9D170479C250020026843684D -:100FE0001143016003B1184770470000024AD368FB -:100FF00043F0C003D360704700440040024AD36806 -:1010000043F0C003D360704700480040024AD368F1 -:1010100043F0C003D3607047007800402DE9F041F1 -:10102000D0F85C64F7683368DA0505469CB20DD5E4 -:10103000202383F311884FF400710430FFF7CEFFB3 -:101040006FF480733360002383F31188202383F3CC -:10105000118805F1040814F02F0333D183F31188AC -:10106000380615D5210613D5202383F3118805F101 -:10107000380000F053FA002846DA0821281DFFF74F -:10108000ADFF4FF67F733B40F360002383F311887D -:101090007A060ED563060CD5202383F31188EA6CFB -:1010A0002B6D9A4202D12B6C002B2FD1002383F39E -:1010B0001188D5F86424D368002B31D01069BDE8BD -:1010C000F0411847230713D014F0080F0CBF00217C -:1010D0008021E00748BF41F02001A20748BF41F04E -:1010E0004001630748BF41F480714046FFF776FF37 -:1010F000A406736805D595F860142846194000F0D9 -:10110000BDFA3468A4B2A6E77060BEE727F04007D6 -:101110003F041021281D3F0CFFF760FFF760C5E773 -:10112000BDE8F08108B50348FFF778FFBDE8084047 -:1011300001F07EBB1C26002008B50348FFF76EFFB8 -:10114000BDE8084001F074BB842A002008B50348BC -:10115000FFF764FFBDE8084001F06ABBEC2E0020F9 -:1011600010B50E4C0E4A2046002100F057FA0D4BE8 -:10117000C4F85C340C4C0D4A2046002100F04EFAB5 -:101180000B4BC4F85C340B4C0B4A0021204600F09A -:1011900045FA0A4BC4F85C3410BD00BF1C26002081 -:1011A000ED0F000800440040842A0020FD0F0008D5 -:1011B00000480040EC2E00200D1000080078004090 -:1011C00038B5394D037C002918BF0D46012B044664 -:1011D000C0F8645410D1354B984242D1344B1A6C4C -:1011E00042F400321A641A6E42F400321A661B6E20 -:1011F0000B21262000F06AF82E4BD4F85C249A428A -:101200002B6802D02C498A424BD12C4901EB530167 -:10121000B1FBF3F3A988080442BF23F0070003F0F1 -:10122000070343EA40039360EB8843F040039BB21B -:1012300013612B8943F001039BB2536141F40453C2 -:1012400043F02C03D36001F4A05100231360B1F5E7 -:10125000806F136853680CBF7F23FF2384F86034CA -:1012600038BD174B98420CD1114B1A6C42F48022B6 -:101270001A641A6E42F480221A661B6E0B21272014 -:10128000B8E7104B9842B7D1094B1A6C42F0804234 -:101290001A641A6E42F080421A661B6E0B215220AD -:1012A000A8E70949B2E700BF2C3C00081C26002033 -:1012B00000380240001001400014014000BD01054B -:1012C000842A0020EC2E002080DE800200F16043A2 -:1012D00000F01F02400903F5614309018000C9B213 -:1012E00000F1604083F8001300F561400123934052 -:1012F000C0F8803103607047F8B51546826806690A -:10130000AA420B46816938BF8568761AB542044601 -:1013100007D218462A46FFF76BFDA3692B44A36149 -:101320000DE011D932461846FFF762FDAF1B3A4671 -:10133000E1683044FFF75CFDE2683A44A261A368CB -:101340005B1BA3602846F8BD18462A46FFF750FDF0 -:10135000E368E4E783682DE9F041044693421546CB -:10136000266938BF85684069361AB5420F4606D2ED -:101370002A46FFF73DFD63692B4463610DE012D9F6 -:101380003246A5EB0608FFF733FD4246B919E0687F -:10139000FFF72EFDE26842446261A3685B1BA36015 -:1013A0002846BDE8F0812A46FFF722FDE368E4E71E -:1013B00010B50A440024C361029B00604060846051 -:1013C000C160816141610261036210BD08B582693B -:1013D0004369934201D1826882B982680132826096 -:1013E0005A1C42611970426903699A4201D3C36869 -:1013F0004361002100F0AAFE002008BD4FF0FF303D -:1014000008BD000070B5202304460E4683F3118802 -:10141000A568A5B1A368A269013BA360531CA361A1 -:1014200015782269934224BFE368A361E3690BB195 -:1014300020469847002383F31188284670BD314623 -:10144000204600F073FE0028E2DA85F3118870BDB3 -:101450002DE9F74F05460F4690469A46D0F81C9066 -:10146000202686F311884FF0000B144664B1224603 -:1014700039462846FFF740FF034668B951462846DB -:1014800000F054FE0028F1D0002383F31188A8EB6C -:10149000040003B0BDE8F08FB9F1000F03D0019054 -:1014A0002846C847019B8BF31188E41A1F4486F332 -:1014B0001188DBE7C16081614161C3611144009B18 -:1014C000006040608260016103627047F8B50446C5 -:1014D0000E461746202383F31188A568A5B1A3689B -:1014E000013BA36063695A1C62611E7023696269D3 -:1014F0009A4224BFE3686361E3690BB120469847D1 -:10150000002080F31188F8BD3946204600F00EFE19 -:101510000028E2DA85F31188F8BD0000836942698A -:101520009A4210B501D182687AB98268013282602C -:101530005A1C82611C7803699A4201D3C368836193 -:10154000002100F003FE204610BD4FF0FF3010BD1B -:101550002DE9F74F05460F4690469A46D0F81C9065 -:10156000202686F311884FF0000B144664B1224602 -:1015700039462846FFF7EEFE034668B9514628462D -:1015800000F0D4FD0028F1D0002383F31188A8EBEC -:10159000040003B0BDE8F08FB9F1000F03D0019053 -:1015A0002846C847019B8BF31188E41A1F4486F331 -:1015B0001188DBE7026843681143016003B11847F3 -:1015C000704700001430FFF743BF00004FF0FF33B7 -:1015D0001430FFF73DBF00003830FFF7B9BF0000FF -:1015E0004FF0FF333830FFF7B3BF00001430FFF780 -:1015F00009BF00004FF0FF311430FFF703BF0000B8 -:101600003830FFF763BF00004FF0FF323830FFF78C -:101610005DBF000000207047FFF7A2BD37B50F4B3C -:101620000360002343608360C360012304460374A6 -:10163000154600900B464FF4007200F15C01143027 -:10164000FFF7B6FE00942B464FF4007204F51771B5 -:1016500004F13800FFF72EFF03B030BD403C000816 -:1016600010B52023044683F31188FFF7A9FD022358 -:101670002374002383F3118810BD000038B5C369BB -:1016800004460D461BB904210844FFF793FF294681 -:1016900004F11400FFF79AFE002806DA201D4FF42B -:1016A0008061BDE83840FFF785BF38BD02684368F8 -:1016B0001143016003B118477047000013B5446B34 -:1016C000D4F894341A681178042915D1217C0229A0 -:1016D00012D11979128901238B4013420CD101A92F -:1016E00004F14C0001F05AFED4F89444019B217996 -:1016F0000246206800F0DAF902B010BD143001F0A3 -:10170000DDBD00004FF0FF33143001F0D7BD000005 -:101710004C3001F0AFBE00004FF0FF334C3001F011 -:10172000A9BE0000143001F0ABBD00004FF0FF3146 -:10173000143001F0A5BD00004C3001F07BBE00006C -:101740004FF0FF324C3001F075BE0000D0F8942409 -:1017500038B5136819780429054601D0012038BD31 -:10176000017C0229FAD112795C8901209040044061 -:10177000F4D105F1140001F03DFD02460028EDD042 -:10178000D5F894544FF480732868697900F07CF997 -:10179000204638BD406BFFF7D9BF000000207047DE -:1017A000704700007FB5124B0360002343608360E5 -:1017B000C360012502260F4B057404460290019375 -:1017C00000F18402294600964FF48073143001F032 -:1017D000EDFC094B0193029400964FF4807304F5DD -:1017E0002372294604F14C0001F0B4FD04B070BD31 -:1017F000683C000895170008BD1600080B682022F9 -:1018000082F311880A7903EB820290614A790932E6 -:1018100043F822008A7912B103EB82039861022314 -:101820000374C0F89414002383F3118870470000F8 -:1018300038B5037F044613B190F85430ABB9201D7E -:1018400001250221FFF732FF04F1140025776FF024 -:10185000010100F087FC84F8545004F14C006FF053 -:101860000101BDE8384000F07DBC38BD10B5012154 -:1018700004460430FFF71AFF0023237784F854301E -:1018800010BD000038B504460025143001F0A6FC58 -:1018900004F14C00257701F075FD201D84F85450AB -:1018A0000121FFF703FF2046BDE83840FFF74EBF98 -:1018B00090F8443003F06003202B19D190F84520B4 -:1018C000212A0AD0222A4FF000030ED0202A0FD15D -:1018D000084A82630722C26304E0064B836307233E -:1018E000C36300230364012070478363C363F9E784 -:1018F0000020704701240020D0F8943437B51A68CE -:101900001178042904461AD1017C022917D11979CA -:10191000128901238B40134211D100F14C05284656 -:1019200001F0F0FD58B101A9284601F037FDD4F8C7 -:101930009444019B21790246206800F0B7F803B077 -:1019400030BD000000EB8103F7B59C6905460E46EB -:10195000F4B1202383F3118805EB8607201D0821AD -:10196000FFF7A4FEFB685B691B684C3413B120468B -:1019700001F022FD01A9204601F010FD024648B108 -:10198000019B3146284600F091F8002383F311882B -:1019900003B0F0BDFB685A691268002AF5D01B8AB3 -:1019A000013B1340F1D105F14402EAE7093138B5B2 -:1019B00050F82140DCB1202383F31188D4F894241B -:1019C0001368527903EB8203DB689B695D6845B15C -:1019D00004216018FFF76AFE294604F1140001F0A3 -:1019E00013FC2046FFF7B2FE002383F3118838BDB5 -:1019F0007047000000F0D4BF012303700023436050 -:101A0000C36183620362C3624362036303814381F0 -:101A10007047000038B50446202383F31188002561 -:101A20004160C56005614561856100F0C9FF022321 -:101A3000237085F3118838BD70B500EB810305462E -:101A40005069DA600E46144618B110220021FFF7E3 -:101A5000F9F9A06918B110220021FFF7F3F9314616 -:101A60002846BDE8704001F075B80000028902F018 -:101A700001020281428902F00102428100220261D8 -:101A80004261826101F0FAB8F0B400EB8104478949 -:101A9000E4680125A4698D403D434581236000230E -:101AA000A2606360F0BC01F015B90000F0B400EB77 -:101AB00081040789E468012564698D403D430581FF -:101AC00023600023A2606360F0BC01F08FB90000C6 -:101AD00070B50223002504460370A0F84C5080F82E -:101AE0004E5080F84F5005814581C56005614561C4 -:101AF000856180F8345000F0C9FF63681B6823B12A -:101B000029462046BDE87040184770BD43680278FA -:101B10001B6880F85020052202700BB10421184781 -:101B200070470000436890F850201B6802700BB1AA -:101B3000052118477047000090F8343070B504460E -:101B400013B1002380F8343004F14402204601F040 -:101B5000B7F863689B6863BB94F8445015F060065F -:101B600015D194F8453005F07F0545EA032540F28C -:101B700002339D4200F00E815BD8022D00F0DC8024 -:101B80003FD8002D00F08780012D00F0CF8000218C -:101B9000204601F0EDFA0021204601F0DFFA6368EB -:101BA0001B6813B1062120469847062384F8343079 -:101BB00070BD204698470028CED094F84B2094F86A -:101BC0004A3043EA0223E26B934238BFE36394F95D -:101BD0004430E56B002B4FF0200380F2FD80002D98 -:101BE00000F0EC80092284F8342083F3118800216E -:101BF000E36BA26B2046FFF759FF002383F31188A4 -:101C000070BDB5F5817F00F0B180B5F5407F49D05A -:101C1000B5F5807FBBD194F84630012BB7D1B4F82D -:101C20004C3023F00203A4F84C30A663E66326642C -:101C3000C3E740F201639D421ED8B5F5C06F3BD2A9 -:101C4000B5F5A06FA3D1B4F84430B3F5A06F0ED1B1 -:101C500094F8463084F84E30204600F06FFF6368F9 -:101C60001B6813B1012120469847032323700023EA -:101C7000A363E3632364A0E7B5F5106F32D040F6A9 -:101C800002439D4252D0B5F5006F80D104F14F035D -:101C9000A363012324E004F14C03A3630223E36361 -:101CA00025648AE794F84630012B7FF470AFB4F8CE -:101CB0004C3043F00203B6E794F84920616894F889 -:101CC00048304D6894F8471043EA0223204694F8C0 -:101CD0004620A84700283FF45AAF4368A36303682F -:101CE000E363A4E72378042B10D1202383F3118826 -:101CF0002046FFF7BBFE86F31188636884F84F60C7 -:101D00001B68032121700BB12046984794F8463098 -:101D1000002BACD084F84F300423237063681B6819 -:101D2000002BA4D0022120469847A0E7374BA3639D -:101D30000223E36300239DE794F8481011F0800F1D -:101D4000204601F00F010ED000F0ACFF012806D0B4 -:101D500002287FF41CAF2E4BA363E06367E72D4B93 -:101D6000A363E56363E700F08FFFEFE794F8463085 -:101D7000002B7FF40CAF94F8483013F00F013FF4C0 -:101D800076AF1A06204602D501F006FA6FE701F099 -:101D9000F9F96CE794F84630002B7FF4F8AE94F82C -:101DA000483013F00F013FF462AF1B06204602D506 -:101DB00001F0DEF95BE701F0D1F958E7142284F86D -:101DC000342083F311882B462A4629462046FFF704 -:101DD0005BFE85F3118870BD5DB1152284F8342057 -:101DE00083F311880021E36BA26B2046FFF74CFEC2 -:101DF00003E70B2284F8342083F311882B462A460C -:101E000029462046FFF752FEE3E700BF983C000852 -:101E1000903C0008943C000838B590F834300446F3 -:101E2000152B29D8DFE803F03E28282828283E284B -:101E3000280B293928282828282828283E3E90F8C9 -:101E40004B1090F84A20C36B42EA01229A4214D9FF -:101E5000C268128AB3FBF2F502FB15356DB9202377 -:101E600083F311882B462A462946FFF71FFE85F388 -:101E700011880A2384F8343038BD142384F83430B0 -:101E8000202383F3118800231A4619462046FFF7C2 -:101E9000FBFD002383F3118838BD036C03B1984721 -:101EA0000023E7E7002101F063F90021204601F05B -:101EB00055F963681B6813B106212046984706232D -:101EC000D8E7000090F83420152A38B5044622D807 -:101ED0000123934040F6416213421DD113F4801553 -:101EE0000FD19B0217D50B2380F83430202383F3C6 -:101EF00011882B462A462946FFF7D8FD85F311881D -:101F000038BDC3689B695B682BB9036C03B1984704 -:101F1000002384F8343038BD002101F029F9002174 -:101F2000204601F01BF963681B6813B106212046A7 -:101F300098470623EDE70000024B00221B605B6020 -:101F40009A60704754330020002303748268054B65 -:101F50001B6899689142FBD25A6803604260106026 -:101F6000586070475433002008B5202383F311884C -:101F7000037C032B05D0042B0DD02BB983F31188E0 -:101F800008BD436900221A604FF0FF334361FFF739 -:101F9000DBFF0023F2E790E80C001A600268536050 -:101FA000F2E70000002303748268054B1B68996800 -:101FB0009142FBD85A6803604260106058607047D5 -:101FC00054330020054B19690874186802681A60B8 -:101FD0005360186101230374FEF796B9543300204F -:101FE00030B54B1C87B005460A4C10D023690A4A0D -:101FF00001A800F0D3F82846FFF7E4FF049B13B1D3 -:1020000001A800F007F92369586907B030BDFFF750 -:10201000D9FFF8E754330020691F000838B50C4D8C -:1020200041612B6981689A689142044603D8BDE8F2 -:102030003840FFF789BF1846FFF786FF01232C6160 -:10204000014623742046BDE83840FEF75DB900BF65 -:1020500054330020044B1A681B6990689B689842AF -:1020600094BF0020012070475433002010B5084C65 -:10207000236820691A6822605460012223611A745F -:10208000FFF790FF01462069BDE81040FEF73CB91C -:10209000543300208260022202740022427470478E -:1020A0008368A3F17C0243F80C2C026943F83C2CB2 -:1020B000426943F8382C074A43F81C2CC26843F89D -:1020C000102C022203F8082C002203F8072CA3F19D -:1020D000180070472103000810B5202383F31188EE -:1020E000FFF7DEFF00210446FFF798FF002383F38C -:1020F0001188204610BD0000024B1B6958610F205B -:10210000FFF760BF54330020202383F31188FFF7CB -:10211000F3BF000008B50146202383F3118808208F -:10212000FFF75EFF002383F3118808BD49B1064B1A -:1021300042681B6918605A60136043600420FFF70F -:102140004FBF4FF0FF307047543300200368984270 -:1021500006D01A680260506059611846FFF7F4BE55 -:102160007047000038B504460D462068844200D10F -:1021700038BD036823605C604561FFF7E5FEF4E766 -:10218000054B03F114025A619A614FF0FF32DA6194 -:1021900000221A62704700BF54330020F8B5036173 -:1021A0001A4BC2605C6A1A4B1A46022952F8145F35 -:1021B00038BF0221954206461F460AD158619861F0 -:1021C0001C620560456081600819BDE8F84001F0B7 -:1021D000BBB9186AAB68241A0C1902D3E41A2D682B -:1021E00004E09C4202D2204401F0BEF9AB689C425C -:1021F000F4D86B68736035601E606E60B460A96867 -:102200004FF0FF33091BA960FB61F8BD000C0040D3 -:102210005433002010B41A4C234653F8141F814243 -:1022200010D0416802680A60026851609A424FF01B -:102230000001C16003D0936881680B4493605DF82E -:10224000044B70470A68626100209A425360C8607C -:1022500003D15DF8044B01F081B9936888680344A9 -:102260009360084A206A526A121A9342E7D9991A6F -:10227000012998BF931C18445DF8044B01F074B910 -:1022800054330020000C004000207047FEE700009F -:10229000704700004FF0FF3070470000022906D061 -:1022A000032906D00129064818BF002070470548B9 -:1022B0007047032A9ABF044800EBC2000020704711 -:1022C0006C3D0008203D00080824002070B59AB03D -:1022D00001AD064608462946144600F095F8284602 -:1022E000FEF7A8FDC0B2431C5B0086E8180023700F -:1022F00003236370002302341946DAB2904204F1DA -:10230000020401D81AB070BDEA5C04F8022C04F88B -:10231000011C0133F1E7000008B5202383F3118885 -:102320000348FFF7E9FA002383F3118808BD00BFD3 -:102330009433002010B50446052916D8DFE801F0D3 -:1023400016150316161D202383F311880E4A01214A -:10235000FFF772FB20460D4A0221FFF76DFB0C4888 -:10236000FFF790FA002383F3118810BD202383F335 -:1023700011880748FFF75CFAF4E7202383F31188FC -:102380000348FFF773FAEDE79C3C0008C03C0008E7 -:102390009433002038B50C4D0C4C0D492A4604F1FD -:1023A0000800FFF793FF05F1CA0204F11000094984 -:1023B000FFF78CFF05F5CA7204F118000649BDE865 -:1023C0003840FFF783BF00BF5C380020082400209E -:1023D000EC3C0008F93C0008063D000870B50446D6 -:1023E00008460D46FEF726FDC6B2204601340378A6 -:1023F0000BB9184670BD32462946FEF703FD00288A -:10240000F3D1012070BD00002DE9F04704460D46D0 -:10241000FEF710FD2C49C6B22046FFF7DFFF08B1DA -:102420000736F6B229492046FFF7D8FF08B1103623 -:10243000F6B2632E0BD8DFF89080DFF89090244F2F -:10244000DFF898A0267846B92E70BDE8F0872146BF -:102450002846BDE8F04701F09DBB252E2FD107226D -:1024600041462046FEF7CEFC70B91A4B2A4603F1CE -:102470000C0153F8040B42F8040B8B42F9D11B8872 -:10248000138007340E35DDE7082249462046FEF763 -:10249000B9FCA0B9104BAA1C13F8011F0909534538 -:1024A000C95D02F8021C197801F00F0102F1020265 -:1024B000C95D02F8031CEFD118350834C2E72E704D -:1024C00001340135BEE700BF8C3D0008063D000821 -:1024D000A33D0008943D00080F7AFF1F1B7AFF1FE1 -:1024E000BFF34F8F024AD368DB03FCD4704700BFB1 -:1024F000003C024008B5094B1B7873B9FFF7F0FFA9 -:10250000074B1A69002ABFBF064A5A6002F1883297 -:102510005A601A6822F480621A6008BDBA3A002034 -:10252000003C02402301674508B50B4B1B7893B96B -:10253000FFF7D6FF094B1A6942F000421A611A6888 -:1025400042F480521A601A6822F480521A601A68A3 -:1025500042F480621A6008BDBA3A0020003C024092 -:10256000172870B513D80B4A0B4C137863B90B4E70 -:102570004FF0006144F8231056F823500133182B14 -:102580002944F7D10123137054F8200070BD0020B6 -:1025900070BD00BF1C3B0020BC3A0020B43D0008C9 -:1025A000014B53F820007047B43D000818207047D5 -:1025B000172810B5044601D9002010BDFFF7D0FF41 -:1025C000064B53F824301844C21A0BB9012010BD31 -:1025D00012680132F0D1043BF6E700BFB43D0008B9 -:1025E000172810B5044629D8FFF77AFFFFF782FFB6 -:1025F0001349F323CB600C23B0FBF3F203FB12006F -:10260000D30143EAC003DBB243F4007343F0020397 -:102610000B610B6943F480330B61FFF761FF2046C8 -:10262000FFF79EFF074B53F8241000F0DDF8FFF78B -:102630007BFF2046BDE81040FFF7BABF002010BD69 -:10264000003C0240B43D00082DE9F84312F00103BC -:10265000154640D18218B2F1026F3CD22C4B1B6858 -:1026600013F0010337D02B4CFFF744FFF323E36053 -:10267000FFF736FF40F20127032D01D9830713D05E -:10268000244C0F46401A40F20118EB1B0B44012B5F -:1026900000EB0706236924D823F001032361FFF729 -:1026A00043FF0120BDE8F883236923F440732361CD -:1026B00023693B43236151F8046B0660BFF34F8FDE -:1026C000FFF70EFF03689E4208D0236923F0010341 -:1026D0002361FFF729FF0020BDE8F883043D0430A3 -:1026E000CAE723F440732361236943EA08032361A3 -:1026F000B94637F8023B3380BFF34F8FFFF7F0FE48 -:102700003688B9F80030B6B2B342BED0DDE700BFBC -:1027100000380240003C0240084908B50B7828B157 -:1027200053B9FFF7E7FE01230B7008BD23B1BDE8E5 -:1027300008400870FFF7F8BE08BD00BFBA3A002095 -:1027400010B50244064B0439D2B2904200D110BDFC -:10275000441C00B253F8200041F8040FE0B2F4E743 -:1027600050280040104B30B51C6F240407D41C6F58 -:1027700044F400741C671C6F44F400441C670B4C49 -:10278000236843F4807323600244094B0439D2B2B6 -:10279000904200D130BD441C00B251F8045F43F8B0 -:1027A0002050E0B2F4E700BF003802400070004063 -:1027B0005028004007B5012201A90020FFF7C0FF03 -:1027C000019803B05DF804FB13B50446FFF7F2FF70 -:1027D000A04206D002A9012241F8044D0020FFF7D3 -:1027E000C1FF02B010BD000070470000034B1B6822 -:1027F0009B0042BF024B01221A707047743802409E -:102800001D3B0020014B1878704700BF1D3B002086 -:10281000064A536823F001035360EFF309836833DA -:1028200083F30988002383F31188704730EF00E0B9 -:1028300010B5202383F31188104B5B6813F40063F9 -:1028400018D0F1EE103AEFF309844FF0807344F89A -:102850004C3C0B4BDB6844F8083CA4F1680383F361 -:102860000988FFF7F7FB18B1064B44F8503C10BD40 -:10287000054BFAE783F3118810BD00BF00ED00E0BF -:1028800030EF00E031030008340300087047000017 -:10289000FEE70000084A094B09498B4204D3094A64 -:1028A0000021934205D3704752F8040F43F8040BFC -:1028B000F3E743F8041BF4E78C3F0008903D002049 -:1028C000903D0020903D0020836D30B500229D6832 -:1028D000446D11464FF0FF3004EB42130132954234 -:1028E000C3F80019C3F81019C3F80809C3F8001B8E -:1028F000C3F8101BC3F8080BEED24FF00113C4F855 -:102900001C3830BD890141F02001016103699B063B -:10291000FCD4122000F0B4BE204B03EB80022DE962 -:10292000F047D2F80CE05D6DDEF81420461CD2F8BA -:1029300000C005EB063605EB4018516861450BD326 -:10294000D5F83428012303FA00F022EA0000C5F884 -:1029500034081846BDE8F087BEF81040ACEB010320 -:10296000A34228BF2346D8F81849A4B2B3EB840F7A -:1029700010D894681F46A4F1040959F804AFC6F8AA -:1029800000A0042F01D9043FF7E71C440B449460D6 -:102990005360D2E70020BDE8F08700BF203B002055 -:1029A00010B5054C2046FFF727F84FF0A0436365AC -:1029B000024BA36510BD00BF203B0020383E00083D -:1029C0000378012B70B5054650D12A4B446D9842CF -:1029D0001BD1294B5A6B42F080025A635A6D42F068 -:1029E00080025A655A6D5A6942F080025A615A69EA -:1029F00022F080025A610E2143205B69FEF766FCDB -:102A00001E4BE3601E4BC4F800380023C4F8003EA0 -:102A1000C02323606E6D4FF45023A3633369002BF2 -:102A2000FCDA012333610C2000F02AFE3369DB0756 -:102A3000FCD4122000F024FE3369002BFCDA0026BF -:102A4000A6602846FFF740FF6B68C4F81068DB6893 -:102A5000C4F81468C4F81C684BB90A4BA3614FF062 -:102A6000FF336361A36843F00103A36070BD064BAD -:102A7000F4E700BF203B0020003802404014004033 -:102A800003002002003C30C0083C30C0F8B5446D63 -:102A9000054600212046FFF735FFA96D00234FF0C2 -:102AA00001128F68C4F834384FF00066C4F81C284F -:102AB0004FF0FF3004EB431201339F42C2F800692C -:102AC000C2F8006BC2F80809C2F8080BF2D20B6812 -:102AD0006A6DEB65636210231361166916F01006C8 -:102AE000FBD1122000F0CCFDD4F8003823F4FE63B3 -:102AF000C4F80038A36943F4402343F01003A361F2 -:102B00000923C4F81038C4F814380A4BEB604FF0AE -:102B1000C043C4F8103B084BC4F8003BC4F810692C -:102B2000C4F80039EB6D03F1100243F48013EA6539 -:102B3000A362F8BD143E000840800010426D90F87A -:102B40004E10D2F8003823F4FE6343EA0113C2F8B2 -:102B5000003870472DE9F0410EB200EB86080D46B3 -:102B6000D8F80C100F6807F00303022B50D0032B8A -:102B700050D03D4A3D4F012B18BF1746446D4FEAD8 -:102B8000451E04EB0E030022C3F8102B8A6905F1E1 -:102B9000100C002A40D04A8A05F158035B013A43E1 -:102BA000E2500123D4F81C2803FA0CF31343A64483 -:102BB0004A69C4F81C380023CEF8103905F13F03E8 -:102BC000002A39D00A8A898B9208012988BF4A4392 -:102BD000C16D04EB8303561841EA0242C6652946DB -:102BE0005A602046FFF78EFED8F80C301B8A43EA65 -:102BF00085531F4305F148035B01E7500123D4F8D7 -:102C00001C2803FA05F51543C4F81C58BDE8F081EB -:102C1000174FB3E7174FB1E704EB4613D3F8002B78 -:102C200022F40042C3F8002BD4F81C28012303FA35 -:102C30000CF322EA0303BAE704EB83030E4A5A605B -:102C400004EB461629462046FFF75CFED6F800390D -:102C500023F40043C6F80039D4F81C38012202FAE4 -:102C600005F523EA0505CFE7008000100080041079 -:102C70000080081000800C1000040002826D1268B1 -:102C8000C265FFF721BE00005831436D49015B5812 -:102C900013F4004004D013F4001F14BF01200220DD -:102CA000704700004831436D49015B5813F4004000 -:102CB00004D013F4001F14BF01200220704700004D -:102CC00000EB8101CB68196A0B6813604B68536095 -:102CD0007047000000EB810330B5DD68AA69136816 -:102CE000D36019B9402B84BF402313606B8A1468EA -:102CF000426D1C44013CB4FBF3F46343033323F003 -:102D0000030302EB411043EAC44343F0C043C0F85D -:102D1000103B2B6803F00303012B09B20ED1D2F84C -:102D2000083802EB411013F4807FD0F8003B14BF49 -:102D300043F0805343F00053C0F8003B02EB4112D4 -:102D4000D2F8003B43F00443C2F8003B30BD000022 -:102D50002DE9F041244D6E6D06EB40130446D3F887 -:102D6000087BC3F8087B38070AD5D6F8143819074A -:102D700006D505EB84032146DB6828465B68984747 -:102D8000FA072FD5D6F81438DB072BD505EB8403CB -:102D9000D968CCB98B69488A5E68B6FBF0F200FB53 -:102DA00012628AB91868DA6890420DD2121A83E862 -:102DB0001400202383F311880B482146FFF78AFF74 -:102DC00084F31188BDE8F081012303FA04F26B89D2 -:102DD00023EA02036B81CB6823B121460248BDE898 -:102DE000F0411847BDE8F081203B002000EB810353 -:102DF00070B5DD68436D6C692668E6604A0156BBB4 -:102E00001A444FF40020C2F810092A6802F00302A5 -:102E1000012A0AB20ED1D3F8080803EB421410F4C9 -:102E2000807FD4F8000914BF40F0805040F000507B -:102E3000C4F8000903EB4212D2F8000940F0044044 -:102E4000C2F80009D3F83408012202FA01F1014363 -:102E5000C3F8341870BD19B9402E84BF40202060DB -:102E600020682E8A841940F00050013C1A44B4FBBB -:102E7000F6F440EAC440C6E7F8B504461E48456D7E -:102E800005EB4413D3F80869C3F80869F10717D5AF -:102E9000D5F81038DA0713D500EB8403D9684B69ED -:102EA0001F68DA68974218D2D21B00271A605F6049 -:102EB000202383F311882146FFF798FF87F31188B9 -:102EC000330617D5D5F834280123A340134211D077 -:102ED0002046BDE8F840FFF71FBD012303FA04F2C6 -:102EE000038923EA020303818B68002BE8D0214683 -:102EF0009847E5E7F8BD00BF203B002096482DE944 -:102F0000F84F456D6E69AB691E4016F4805F6E61C7 -:102F1000044605D0FEF7DCFDBDE8F84FFFF788BC9E -:102F2000002E12DAD5F8003E8B489B071EBFD5F85D -:102F3000003E23F00303C5F8003ED5F8043823F023 -:102F40000103C5F80438FEF7EDFD370502D58248C8 -:102F5000FEF7DCFDB0040CD5D5F8083813F0060FE9 -:102F6000EB6823F470530CBF43F4105343F4A053A5 -:102F7000EB60310704D56368DB680BB1764898478E -:102F8000F2025AD4B3020CD5D4F85480DFF8C8A1A9 -:102F900000274FF00109A36D9B68F9B28B4280F0C6 -:102FA0008780F70619D5616D0A6AC2F30A1702F025 -:102FB0000F0302F4F012B2F5802F00F0A180B2F5F9 -:102FC000402F0AD104EB830301F58051DB68186AB6 -:102FD00000231A469F4240F087803003D5F81848F6 -:102FE00013D5E10302D50020FFF7B2FEA20302D5FC -:102FF0000120FFF7ADFE630302D50220FFF7A8FE14 -:10300000270302D50320FFF7A3FE750384D5E0074D -:1030100002D50020FFF730FFA10702D50120FFF7FE -:103020002BFF620702D50220FFF726FF23077FF55B -:1030300073AF0320FFF720FF6EE7D4F85480DFF86A -:1030400018A100274FF00109A36D9B685FFA87FB69 -:103050005B4597D308EB4B13D3F8002902F44022C9 -:10306000B2F5802F22D1D3F80029002A1EDAD3F836 -:10307000002942F09042C3F80029D3F80029002A21 -:10308000FBDB5946606DFFF73DFC228909FA0BF323 -:1030900022EA0303238104EB8B03DB689B6813B1F3 -:1030A0005946504698475846FFF736FC0137CBE75C -:1030B00008EB4112D2F8003B03F44023B3F5802F14 -:1030C00010D1D2F8003B002B0CDA628909FA01F327 -:1030D00022EA0303638104EB8103DB68DB680BB145 -:1030E00050469847013756E79C0708BF0A68072BE8 -:1030F00098BF027003F101039CBF120A013069E717 -:10310000023304EB830201F5805152689069026832 -:10311000D0F808C04068A2EB000E0022104697428B -:103120000AD104EB830463689B699A683A449A6005 -:103130005A6817445F6050E712F0030F08BF086831 -:10314000964588BF8CF8000002F1010284BF000A96 -:103150000CF1010CE3E700BF203B0020436D03EBC3 -:103160004111D1F8003B43F40013C1F8003B704714 -:10317000436D03EB4111D1F8003943F40013C1F85A -:1031800000397047436D03EB4111D1F8003B23F444 -:103190000013C1F8003B7047436D03EB4111D1F8B8 -:1031A000003923F40013C1F80039704730B5039C8F -:1031B0000172043304FB0325C361049B03630021F4 -:1031C000059B00604060C1604261026185610462EC -:1031D00042628162C162436330BD00000022416AE5 -:1031E00041610161C2608262C2626FF00101FEF75B -:1031F000B9BF000003694269934203D1C2680AB1B2 -:1032000000207047181D704703691960C2680132B9 -:10321000C260C269134482690361934224BF436A56 -:1032200003610021FEF792BF38B504460D46E368FE -:103230003BB16269131D1268A3621344E36200206C -:1032400038BD237A33B929462046FEF76FFF0028A0 -:10325000EDDA38BD6FF00100FBE70000C368C2691A -:10326000013BC3604369134482694361934224BFB5 -:10327000436A436100238362036B03B118477047BD -:1032800070B52023044683F31188866A3EB9FFF7A0 -:10329000CBFF054618B186F31188284670BDA36A96 -:1032A000E26A13F8015BA362934202D32046FFF760 -:1032B000D5FF002383F31188EFE700002DE9F84FD5 -:1032C00004460E4690469946202787F3118800252C -:1032D000AA46D4F828B0BBF1000F09D149462046D0 -:1032E000FFF7A2FF20B18BF311882846BDE8F88FC5 -:1032F000A16AE36AA8EB050B5B1A9B4528BF9B46B6 -:10330000BBF1400F1BD9334601F1400251F8040BC9 -:1033100043F8040B9142F9D1A36A40334036A362CB -:103320004035A26AE36A9A4202D32046FFF796FF2D -:103330008AF311884545D8D287F31188C9E730460A -:103340005A46FDF755FDA36A5B445E44A3625D44A3 -:10335000E7E7000010B5029C0172043303FB04216F -:10336000C36100238362C362039B0363049B006009 -:103370004060C460426102618161046242624363F1 -:1033800010BD0000026AC260426A4261026100220E -:103390008262C2626FF00101FEF7E4BE4369026916 -:1033A0009A4203D1C2680AB100207047184650F80B -:1033B000043B0B6070470000C368C2690133C360FF -:1033C0004369134482694361934224BF436A436162 -:1033D0000021FEF7BBBE000038B504460D46E36889 -:1033E0003BB123691A1DA262E2691344E362002023 -:1033F00038BD237A33B929462046FEF797FE0028C8 -:10340000EDDA38BD6FF00100FBE7000003691960D9 -:10341000C268013AC260C26913448269036193427F -:1034200024BF436A036100238362036B03B118471F -:103430007047000070B5202304460E4683F31188C0 -:10344000856A35B91146FFF7C7FF10B185F31188BA -:1034500070BDA36A1E70A36AE26A01339342A3623D -:1034600004D3E16920460439FFF7D0FF002080F340 -:10347000118870BD2DE9F84F04460D4691469A46D5 -:103480004FF0200888F311880026B346A76A4FB989 -:1034900051462046FFF7A0FF20B187F31188304640 -:1034A000BDE8F88FA06AE76AA9EB06033F1A9F42BE -:1034B00028BF1F46402F1BD905F1400355F8042BA8 -:1034C00040F8042B9D42F9D1A36A4033A3624036F1 -:1034D000A26AE36A9A4204D3E16920460439FFF7FD -:1034E00095FF8BF311884E45D9D288F31188CDE72B -:1034F00029463A46FDF77CFCA36A3B443D44A3625F -:103500003E44E5E7026943699A4203D1C3681BB9A7 -:10351000184670470023FBE7836A002BF8D0043B72 -:103520009B1AF5D01360C368013BC360C3691A449A -:10353000836902619A4224BF436A03610023836264 -:103540000123E5E700F034B9034B002258631A6108 -:103550000222DA60704700BF000C0040014B0022DD -:10356000DA607047000C0040014B5863704700BFA1 -:10357000000C0040FEE7000010B5174CFEF7DCFC25 -:10358000FEF7FEFD802215492046FEF783FD01234C -:1035900044F8180C0374124B124AD96821F4E06104 -:1035A0000904090C0A431049DA60CA6842F08072C3 -:1035B000CA600E490A6842F001020A601022DA77F6 -:1035C000202283F82220002383F3118862B6084862 -:1035D000BDE81040FEF780BD7C330020443E00086B -:1035E00000ED00E00003FA05F0ED00E0001000E05F -:1035F0004C3E00082DE9F84F1F4CDFF880906569BC -:1036000004F114074FF00008D9F82430266AAA689C -:103610009E1B96421DD34FF0200AAA68236AD5F854 -:103620000CB0134423622B68BB425F60A6EB02061A -:103630006361C5F80C8001D1FFF790FF88F3118812 -:103640002869D8478AF311886569AB689E42E4D23D -:10365000DAE76269BA420CD0916823628E1B9660E9 -:10366000A86802282CBF1818981CBDE8F84FFFF76F -:103670007BBFBDE8F88F00BF54330020000C004032 -:10368000034B59685A68521A9042FBD8704700BFE2 -:10369000001000E04B6843608B688360CB68C360B8 -:1036A0000B6943614B6903628B6943620B6803607A -:1036B0007047000008B5224B22481A6940F2FF11FA -:1036C0000A431A611A6922F4FF7222F001021A6198 -:1036D0001A691A6B0A431A631A6D0A431A651A4A61 -:1036E0001B6D1146FFF7D6FF184802F11C01FFF7CA -:1036F000D1FF174802F13801FFF7CCFF154802F15E -:103700005401FFF7C7FF144802F17001FFF7C2FF31 -:10371000124802F18C01FFF7BDFF114802F1A80128 -:10372000FFF7B8FF0F4802F1C401FFF7B3FF0E48DF -:1037300002F1E001FFF7AEFFBDE8084000F0A4B8D9 -:1037400000380240000002406C3E000800040240C5 -:1037500000080240000C0240001002400014024029 -:1037600000180240001C02400020024008B500F092 -:10377000FFF9FFF701FFFFF739F8BDE80840FEF752 -:1037800009BE000070470000084B1A69920710B587 -:1037900008D500241C61202383F31188FFF72AFF3A -:1037A00084F31188BDE81040FFF742B8000C0040D8 -:1037B000104B1A6C42F008021A641A6E42F00802AA -:1037C0001A660D4A1B6E936843F0080393600B4B17 -:1037D00053229A624FF0FF32DA6200229A615A63F2 -:1037E000DA605A6001225A6108211A603220FDF71E -:1037F0006DBD00BF00380240002004E0000C004016 -:103800001F4B1A696FEAC2526FEAD2521A611A69E3 -:10381000C2F308021A614FF0FF301A695A69586101 -:1038200000215A6959615A691A6A62F080521A6213 -:103830001A6A02F080521A621A6A5A6A58625A6AFE -:1038400059625A6A1A6C42F080521A641A6E42F037 -:1038500080521A661A6E0B4A106840F4807010602D -:10386000186F00F44070B0F5007F1EBF4FF4803039 -:1038700018671967536823F40073536000F058B950 -:103880000038024000700040324B4FF080521A6402 -:10389000314A4FF4404111601A6842F001021A6047 -:1038A0001A689207FCD59A6822F003029A60294BA5 -:1038B00019469A6812F00C02FBD1186800F0F90062 -:1038C00018609A601A6842F480321A600B689B0391 -:1038D000FCD54B6F43F001034B671E4B5A6F9007AB -:1038E000FCD51E4A5A601A6842F080721A601A4A61 -:1038F00053685904FCD5174B1A689201FCD5184A35 -:103900009A600322C3F88C20164B1A68164B9A4211 -:10391000164B1BD1164A1168164A914216D140F235 -:1039200005121A600B4B9A6842F002029A609A687C -:1039300002F00C02082AFAD15A6C42F480425A640E -:103940005A6E42F480425A665B6E704740F20572CE -:10395000E7E700BF003802400070004018544007FD -:1039600000948838002004E011640020003C0240EC -:1039700000ED00E041C20F41084A08B553691168E3 -:103980000B4003F00103536123B1054A13680BB1E7 -:1039900050689847BDE80840FEF74ABF003C014028 -:1039A0009C250020084A08B5536911680B4003F0B4 -:1039B0000203536123B1054A93680BB1D06898475D -:1039C000BDE80840FEF734BF003C01409C250020C4 -:1039D000084A08B5536911680B4003F004035361AA -:1039E00023B1054A13690BB150699847BDE80840F7 -:1039F000FEF71EBF003C01409C250020084A08B588 -:103A0000536911680B4003F00803536123B1054A61 -:103A100093690BB1D0699847BDE80840FEF708BF2D -:103A2000003C01409C250020084A08B553691168F4 -:103A30000B4003F01003536123B1054A136A0BB125 -:103A4000506A9847BDE80840FEF7F2BE003C0140CE -:103A50009C250020174B10B55C691A68144004F4CB -:103A600078725A61A30604D5134A936A0BB1D06ADF -:103A70009847600604D5104A136B0BB1506B9847FA -:103A8000210604D50C4A936B0BB1D06B9847E20525 -:103A900004D5094A136C0BB1506C9847A30504D5A3 -:103AA000054A936C0BB1D06C9847BDE81040FEF707 -:103AB000BFBE00BF003C01409C2500201A4B10B542 -:103AC0005C691A68144004F47C425A61620504D5AA -:103AD000164A136D0BB1506D9847230504D5134A50 -:103AE000936D0BB1D06D9847E00404D50F4A136E67 -:103AF0000BB1506E9847A10404D50C4A936E0BB1DC -:103B0000D06E9847620404D5084A136F0BB1506F0A -:103B10009847230404D5054A936F0BB1D06F98479B -:103B2000BDE81040FEF784BE003C01409C2500200B -:103B3000062108B50846FDF7C9FB06210720FDF759 -:103B4000C5FB06210820FDF7C1FB06210920FDF772 -:103B5000BDFB06210A20FDF7B9FB06211720FDF762 -:103B6000B5FB06212820BDE80840FDF7AFBB0000EB -:103B700008B5FFF745FEFDF725FAFDF74DFDFDF70A -:103B800039FFFDF70DFEFFF7FDFDBDE80840FFF72B -:103B9000D9BC0000034611F8012B03F8012B002AC1 -:103BA000F9D17047121012131211000053544D3303 -:103BB00032463F3F3F00000001203300001041012A -:103BC00001105A01031059010710310100000000D3 -:103BD000AC3B00083F000000130400000C3C000850 -:103BE0003F00000019040000163C00083F000000E0 -:103BF00021040000203C00083F0000009433002016 -:103C00001C260020842A0020EC2E002053544D3323 -:103C100032463430780053544D33324634327800D3 -:103C200053544D3332463434365858000096000011 -:103C30000000000000000000000000000000000084 -:103C400000000000E1150008CD1500080916000865 -:103C5000F515000801160008ED150008D915000833 -:103C6000C515000815160008000000001917000807 -:103C700005170008411700082D170008391700081C -:103C80002517000811170008FD1600089D170008E9 -:103C90000000000001000000000000000200000021 -:103CA0000000000045190008AD1900084000400060 -:103CB0002C3800203C3800200200000000000000EA -:103CC0000300000000000000F119000800000000DF -:103CD000100000004C38002000000000010000002F -:103CE00000000000203B0020010102004865782F01 -:103CF00050726F6669434E430043756265426C6162 -:103D0000636B2D424C002553455249414C25000020 -:103D1000352300089D220008B11800081923000867 -:103D200043000000283D000809024300020100C0D2 -:103D300032090400000102020100052400100105FF -:103D40002401000104240202052406000107058263 -:103D5000030800FF09040100020A00000007050132 -:103D60000240000007058102400000001200000030 -:103D7000743D00081201100102000040AE2D011038 -:103D800000020102030100000403090425424F411F -:103D90005244250043756265477265656E2D736FE9 -:103DA0006C6F003031323334353637383941424365 -:103DB0004445460000400000004000000040000074 -:103DC00000400000000001000000020000000200AE -:103DD00000000200000002000000020000000200DB -:103DE0000000020000400000004000000040000011 -:103DF000004000000000010000000200000002007E -:103E000000000200000002000000020000000200AA -:103E10000000020000000000391B0008191E000805 -:103E2000C51E000840004000803B0020803B002071 -:103E300001000000903B00208000000040010000D5 -:103E4000030000006D61696E00000000643E000820 -:103E5000983B0020903D00200100000075350008CF -:103E60000000000069646C65000000000000812A09 -:103E700000020000AAAAAAAA00000000FFFF00009A -:103E80000000000000A00A00000000000000000088 -:103E9000AAAAAAAA00000000FFFF0000000000007C -:103EA000000000001400005400000000AAAAAAAA02 -:103EB00014000054FFFF000000000000000000009C -:103EC00080699A0100000000AAAA8AAA40555501FB -:103ED000FFFF000000707007777000004081020152 -:103EE00000000000AAAAAAAA00410100F7FF0000F2 -:103EF000000000800800000000000000000000003A -:103F0000AAAAAAAA00000000FFFF0000000000000B -:103F1000000000000000000000000000AAAAAAAAF9 -:103F200000000000FFFF0000000000000000000093 -:103F300000000000000000000A0000000000000077 -:103F4000030000000000000000000000000000006E -:103F50000000000000000000000000000000000061 -:103F60000000000000000000FF00960000000008B4 -:103F700004000000883D0008000000000000000070 -:103F80000000000000000000000000000000000031 +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F074FA01 +:1002500003F074F94FF055301F491B4A91423CBFDF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F052FA03F0A2F96E +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F03ABA000600200022002031 +:1002D0000000000808ED00E00000002000060020FB +:1002E000A03E0008002200204C22002050220020C6 +:1002F00020310020E0010008E0010008E0010008D2 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F098FDFEE701F063 +:1003300027FD00DFFEE7000038B500F0DFFB02F02C +:10034000CFF940B1164B6FF03F01002259720F21D7 +:100350001A729972DA7202F0A9F9054602F0E2F90E +:100360000446C8B90F4B9D4218D001339D4218BFB7 +:10037000044641F2883504BF01240025002002F024 +:100380009FF90CB100F076F800F018FD284600F057 +:10039000C1F800F06FF8F9E70025EFE70546EDE753 +:1003A00000220020010007B008B500F073FBA0F1A7 +:1003B00020035842584108BD07B541F212030221FB +:1003C00001A8ADF8043000F083FB03B05DF804FB36 +:1003D00038B5302383F31188174803680BB101F057 +:1003E00009FE164A144800234FF47A7101F0F8FD13 +:1003F000002383F31188124C236813B12368013B57 +:100400002360636813B16368013B63600D4D2B7813 +:1004100033B963687BB9022000F03AFC3223636091 +:100420002B78032B07D163682BB9022000F030FC36 +:100430004FF47A73636038BD50220020D103000866 +:100440007023002068220020084B187003280CD865 +:10045000DFE800F008050208022000F00FBC0220CF +:1004600000F002BC024B00225A6070476822002054 +:1004700070230020234B244A10B51C461968013113 +:100480003FD004339342F9D16268A24239D31F4B63 +:100490009B6803F1006303F580439A4231D2002048 +:1004A00000F046FB0220FFF7CFFF194B1A6C002229 +:1004B0001A64196E1A66196E596C5A64596E5A6626 +:1004C0005A6E5A6942F080025A615A6922F08002DB +:1004D0005A615A691A6942F000521A611A6922F087 +:1004E00000521A611B6972B64FF0E0233021C3F845 +:1004F000084DD4E9003281F311889D4683F30888C2 +:10050000104710BD004000082040000800220020D5 +:10051000003802402DE9F04F93B0AA4B0090202202 +:10052000FF210AA89D6800F0F3FBA74A1378A3B93E +:10053000A648012103601170302383F311880368FA +:100540000BB101F057FDA24AA04800234FF47A7185 +:1005500001F046FD002383F31188009B13B19D4BEE +:10056000009A1A609C4A009C1378032B1EBF00233C +:100570001370984A4FF0000A18BF5360D34656468E +:10058000D146012000F07AFB24B1924B1B68002B6E +:1005900000F01182002000F07DFA0390039B002BF5 +:1005A000F2DB012000F060FB039B213B162BE8D817 +:1005B00001A252F823F000BF150600083D0600080E +:1005C000D10600088305000883050008830500089C +:1005D0005B0700082B09000845080008A708000869 +:1005E000CF080008F508000883050008070900087F +:1005F0008305000879090008B5060008830500088E +:10060000BD09000821060008B5060008830500089A +:10061000A70800080220FFF7C7FE002840F0F58178 +:10062000009B0221BAF1000F08BF1C4605A841F249 +:100630001233ADF8143000F04BFAA2E74FF47A70A1 +:1006400000F028FA071EEBDB0220FFF7ADFE0028C2 +:10065000E6D0013F052F00F2DA81DFE807F0030A58 +:100660000D10133605230593042105A800F030FA78 +:1006700017E054480421F9E758480421F6E75848A0 +:100680000421F3E74FF01C08404600F053FA08F14C +:1006900004080590042105A800F01AFAB8F12C0FFF +:1006A000F2D1012000FA07F747EA0B0B5FFA8BFB48 +:1006B0004FF0000900F078FB26B10BF00B030B2B79 +:1006C00008BF0024FFF778FE5BE746480421CDE72A +:1006D000002EA5D00BF00B030B2BA1D10220FFF7AE +:1006E00063FE074600289BD0012000F021FA02207B +:1006F000FFF7AAFE00261FFA86F8404600F028FA07 +:10070000044690B10021404600F032FA013600283C +:10071000F1D1BA46044641F21213022105A8ADF800 +:1007200014303E4600F0D4F92BE70120FFF78CFE91 +:100730002546244B9B68AB4207D9284600F0FAF9BE +:10074000013040F067810435F3E7234B00251D702D +:10075000204BBA465D603E46ACE7002E3FF460AFEA +:100760000BF00B030B2B7FF45BAF0220FFF76CFE4B +:10077000322000F08FF9B0F10008FFF651AF18F009 +:1007800003077FF44DAF0F4A926808EB05039342CD +:100790003FF646AFB8F5807F3FF742AF124B01936B +:1007A000B84523DD4FF47A7000F074F90390039A92 +:1007B000002AFFF635AF019B039A03F8012B01379E +:1007C000EDE700BF002200206C2300205022002013 +:1007D000D10300087023002068220020042200209A +:1007E000082200200C2200206C220020C820FFF7E5 +:1007F000DBFD074600283FF413AF1F2D11D8C5F1CC +:10080000200242450AAB25F0030028BF4246834937 +:100810000192184400F056FA019A8048FF2100F036 +:1008200077FA4FEAA8037D490193C8F38702284667 +:1008300000F076FA064600283FF46DAF019B05EB09 +:10084000830537E70220FFF7AFFD00283FF4E8AE4D +:1008500000F0BAF900283FF4E3AE0027B846704B29 +:100860009B68BB4218D91F2F11D80A9B01330ED0A9 +:1008700027F0030312AA134453F8203C0593404683 +:10088000042205A900F0F6FA04378046E7E7384667 +:1008900000F050F90590F2E7CDF81480042105A886 +:1008A00000F016F906E70023642104A8049300F081 +:1008B00005F900287FF4B4AE0220FFF775FD00288B +:1008C0003FF4AEAE049800F067F90590E6E7002328 +:1008D000642104A8049300F0F1F800287FF4A0AE8E +:1008E0000220FFF761FD00283FF49AAE049800F063 +:1008F00063F9EAE70220FFF757FD00283FF490AEC6 +:1009000000F072F9E1E70220FFF74EFD00283FF406 +:1009100087AE05A9142000F06DF904210746049064 +:1009200004A800F0D5F83946B9E7322000F0B2F853 +:10093000071EFFF675AEBB077FF472AE384A9268A9 +:1009400007EB090393423FF66BAE0220FFF72CFD45 +:1009500000283FF465AE27F003074F44B9453FF444 +:10096000A9AE484600F0E6F80421059005A800F07D +:10097000AFF809F10409F1E74FF47A70FFF714FDBD +:1009800000283FF44DAE00F01FF9002844D00A9B28 +:1009900001330BD008220AA9002000F0C1F9002879 +:1009A0003AD02022FF210AA800F0B2F9FFF704FD97 +:1009B0001C4801F059FA13B0BDE8F08F002E3FF447 +:1009C0002FAE0BF00B030B2B7FF42AAE0023642118 +:1009D00005A8059300F072F8074600287FF420AEC2 +:1009E0000220FFF7E1FC804600283FF419AEFFF734 +:1009F000E3FC41F2883001F037FA059800F018FA6C +:100A0000464600F0D1F93C46BBE5064652E64FF0BB +:100A1000000905E6BA467EE637467CE66C220020F1 +:100A200000220020A08601002DE9F84F4FF47A73D0 +:100A3000DFF85880DFF8589006460D4602FB03F7B2 +:100A4000002498F900305A1C5FFA84FA01D0A342BE +:100A500012D159F8240003682A46D3F820B0314651 +:100A60003B46D847854207D1074B012083F800A0B9 +:100A7000BDE8F88F0124E4E7002CFBD04FF4FA70B6 +:100A800001F0F2F90020F3E7B82300201022002043 +:100A90001422002007B50023024601210DF10700B2 +:100AA0008DF80730FFF7C0FF20B19DF8070003B0B5 +:100AB0005DF804FB4FF0FF30F9E700000A4608B587 +:100AC0000421FFF7B1FF80F00100C0B2404208BD31 +:100AD00030B4074B0A461978064B53F82140236877 +:100AE000DD69054B0146AC46204630BC604700BF7F +:100AF000B823002014220020A086010070B501F068 +:100B0000D3FC094E094D3080002428683388834285 +:100B100008D901F0C3FC2B6804440133B4F5804FBD +:100B20002B60F2D370BD00BFBA23002078230020D1 +:100B300001F070BD00F1006000F580400068704772 +:100B400000F10060920000F5804001F0FBBC000065 +:100B5000054B1A68054B1B889B1A834202D9104427 +:100B600001F09CBC0020704778230020BA230020AD +:100B700038B5084D044629B128682044BDE83840FE +:100B800001F0ACBC2868204401F090FC0028F3D0B0 +:100B900038BD00BF7823002010F003030AD1B0F560 +:100BA000047F05D200F10050A0F51040D0F80038C5 +:100BB000184670470023FBE700F10050A0F51040F5 +:100BC000D0F8100A70470000064991F8243033B17C +:100BD0000023086A81F824300822FFF7B1BF012002 +:100BE000704700BF7C230020014B1868704700BF8E +:100BF000002004E070B5194B1D68194B0138C5F38E +:100C00000B0408442D0C04221E88A6420BD15C68FC +:100C10000A46013C824213460FD214F9016F4EB1CD +:100C200002F8016BF6E7013A03F10803ECD18142C7 +:100C30000B4602D22C2203F8012B0A4A05241688FF +:100C4000AE4204D1984284BF967803F8016B013C10 +:100C500002F10402F3D1581A70BD00BF002004E075 +:100C6000503B00083C3B0008022802BF024B4FF4F7 +:100C700080529A61704700BF00100240022802BFF4 +:100C8000024B4FF080529A61704700BF0010024043 +:100C9000022801BF024A536983F4805353617047AD +:100CA0000010024070B504464FF47A764CB1412CE6 +:100CB000254628BF412506FB05F001F0D5F8641B49 +:100CC000F4E770BD10B50023934203D0CC5CC4544C +:100CD0000133F9E710BD000010B5013810F9013FEC +:100CE0003BB191F900409C4203D11AB10131013A64 +:100CF000F4E71AB191F90020981A10BD1046FCE7EC +:100D000003460246D01A12F9011B0029FAD1704796 +:100D100002440346934202D003F8011BFAE77047EE +:100D20002DE9F8431F4D144695F8242007468846C0 +:100D300052BBDFF870909CB395F824302BB9202279 +:100D4000FF2148462F62FFF7E3FF95F82400C0F12A +:100D50000802A24228BF2246D6B24146920005EBC5 +:100D60008000FFF7AFFF95F82430A41B1E44F6B2B5 +:100D7000082E17449044E4B285F82460DBD1FFF7D5 +:100D800023FF0028D7D108E02B6A03EB82038342BC +:100D9000CFD0FFF719FF0028CBD10020BDE8F883A2 +:100DA0000120FBE77C230020024B1A78024B1A70CB +:100DB000704700BFB82300201022002038B5174C20 +:100DC000174D204600F0B6FB2946204600F0DEFB1A +:100DD0002D686A6D936B23F4002393634FF47A704C +:100DE000FFF760FF0F49284600F0D6FC6A6D0E4DF4 +:100DF000936B28680D4943F400239363A0424FF49A +:100E0000E1330B6001D000F0F5FA6868A04204D02D +:100E1000BDE83840054900F0EDBA38BD98280020FB +:100E20005C3C0008643C000814220020A42300203D +:100E300070B50C4B0C4D1E780C4B55F826209A4281 +:100E400004460DD00A4B002114221846FFF760FF1C +:100E50000460014655F82600BDE8704000F0CABAAB +:100E600070BD00BFB8230020142200209828002065 +:100E7000A423002030B5094D0A4491420DD011F849 +:100E8000013B5840082340F30004013B2C4013F081 +:100E9000FF0384EA5000F6D1EFE730BD2083B8EDC0 +:100EA000026843681143016003B1184770470000AE +:100EB000024AD36843F0C003D36070470044004047 +:100EC00010B5054C054A0021204600F071FA044A8D +:100ED000044BC4E9972310BDBC230020B10E0008C9 +:100EE0000044004080DE8002234A037C002918BFB2 +:100EF0000A46012B30B5C0F868220CD11F4B98422E +:100F000009D11F4B196C41F400311964196E41F479 +:100F1000003119661B6EB2F904501468D0F86032C3 +:100F2000D0F85C12002D03EB5403B3FBF4F3BEBF07 +:100F300023F0070503F0070343EA450394888B6019 +:100F4000D38843F040030B61138943F001034B61E5 +:100F500044F4045343F02C03CB6004F4A054002366 +:100F60000B60B4F5806F0B684B680CBF7F23FF23C9 +:100F700080F8643230BD00BF703B0008BC23002005 +:100F8000003802402DE9F041D0F85C62F768336820 +:100F9000DA0504469DB20DD5302383F311884FF452 +:100FA00080610430FFF77CFF6FF4807333600023AF +:100FB00083F31188302383F3118804F1040815F0BA +:100FC0002F033AD183F31188380615D5290613D596 +:100FD000302383F3118804F1380000F065F900280C +:100FE0004EDA0821201DFFF75BFF4FF67F733B4071 +:100FF000F360002383F311887A0616D56B0614D5A7 +:10100000302383F31188D4E913239A420AD1236C45 +:1010100043B127F040073F041021201D3F0CFFF78C +:101020003FFFF760002383F31188D4F86822D36868 +:1010300043B3BDE8F041106918472B0714D015F0F1 +:10104000080F0CBF00214FF48071E80748BF41F042 +:101050002001AA0748BF41F040016B0748BF41F09B +:1010600080014046FFF71CFFAD06736805D594F874 +:1010700064122046194000F0CBF93568ADB29EE706 +:101080007060B6E7BDE8F081F8B51546826806697C +:10109000AA420B46816938BF8568761AB542044674 +:1010A0000BD218462A46FFF70DFEA3692B44A36115 +:1010B000A3685B1BA3602846F8BD0CD918463246CE +:1010C000FFF700FEAF1BE1683A463044FFF7FAFD38 +:1010D000E3683B44EBE718462A46FFF7F3FDE36875 +:1010E000E5E7000083689342F7B51546044638BF2C +:1010F0008568D0E90460361AB5420BD22A46FFF75C +:10110000E1FD63692B446361A36828465B1BA36010 +:1011100003B0F0BD0DD932460191FFF7D3FD01991F +:10112000E068AF1B3A463144FFF7CCFDE3683B442F +:10113000E9E72A46FFF7C6FDE368E4E710B50A448D +:101140000024C361029B8460C0E90000C0E905116E +:10115000C1600261036210BD08B5D0E90532934257 +:1011600001D1826882B98268013282605A1C426170 +:101170001970D0E904329A4224BFC3684361002148 +:1011800000F08EFE002008BD4FF0FF30FBE70000AE +:1011900070B5302304460E4683F31188A568A5B1C7 +:1011A000A368A269013BA360531CA361157822695F +:1011B000934224BFE368A361E3690BB120469847DB +:1011C000002383F31188284607E03146204600F0CB +:1011D00057FE0028E2DA85F3118870BD2DE9F74F3C +:1011E00004460E4617469846D0F81C904FF0300A39 +:1011F0008AF311884FF0000B154665B12A46314637 +:101200002046FFF741FF034660B94146204600F003 +:1012100037FE0028F1D0002383F31188781B03B038 +:10122000BDE8F08FB9F1000F03D001902046C84708 +:10123000019B8BF31188ED1A1E448AF31188DCE7B9 +:10124000C0E90511C160C3611144009B8260C0E91F +:101250000000016103627047F8B504460D4616466A +:10126000302383F31188A768A7B1A368013BA3606B +:1012700063695A1C62611D70D4E904329A4224BF2A +:10128000E3686361E3690BB120469847002080F36F +:10129000118807E03146204600F0F2FD0028E2DA2E +:1012A00087F31188F8BD0000D0E905239A4210B5F4 +:1012B00001D182687AB98268013282605A1C8261E7 +:1012C0001C7803699A4224BFC3688361002100F03F +:1012D000E7FD204610BD4FF0FF30FBE72DE9F74F4B +:1012E00004460E4617469846D0F81C904FF0300A38 +:1012F0008AF311884FF0000B154665B12A46314636 +:101300002046FFF7EFFE034660B94146204600F055 +:10131000B7FD0028F1D0002383F31188781B03B0B8 +:10132000BDE8F08FB9F1000F03D001902046C84707 +:10133000019B8BF31188ED1A1E448AF31188DCE7B8 +:10134000026843681143016003B118477047000009 +:101350001430FFF743BF00004FF0FF331430FFF7A6 +:101360003DBF00003830FFF7B9BF00004FF0FF333A +:101370003830FFF7B3BF00001430FFF709BF00009B +:101380004FF0FF311430FFF703BF00003830FFF794 +:1013900063BF00004FF0FF323830FFF75DBF000041 +:1013A000012914BF6FF0130000207047FFF788BDBC +:1013B00037B515460E4A026000224260C0E902229B +:1013C0000122044602740B46009000F15C014FF4C8 +:1013D00080721430FFF7B2FE00942B464FF48072F7 +:1013E00004F5AE7104F13800FFF72AFF03B030BDF9 +:1013F000843B000810B53023044683F31188FFF7BF +:1014000073FD02232374002080F3118810BD0000B7 +:1014100038B5C36904460D461BB904210844FFF7DB +:101420008FFF294604F11400FFF796FE002806DA24 +:10143000201D4FF40061BDE83840FFF781BF38BD83 +:10144000026843681143016003B118477047000008 +:1014500013B5446BD4F894341A681178042915D163 +:10146000217C022912D11979128901238B40134260 +:101470000CD101A904F14C0001F016FFD4F89444FA +:10148000019B21790246206800F0D0F902B010BD1E +:10149000143001F099BE00004FF0FF33143001F01A +:1014A00093BE00004C3001F06BBF00004FF0FF33E3 +:1014B0004C3001F065BF0000143001F067BE000041 +:1014C0004FF0FF31143001F061BE00004C3001F0EC +:1014D00037BF00004FF0FF324C3001F031BF000049 +:1014E0000020704710B5D0F894341A681178042998 +:1014F000044617D1017C022914D15979528901235C +:101500008B4013420ED1143001F0FAFD024648B16F +:10151000D4F894444FF4807361792068BDE810409A +:1015200000F072B910BD0000406BFFF7DBBF000098 +:10153000704700007FB5124B036000234360C0E991 +:101540000233012502260F4B0574044602900193D5 +:1015500000F18402294600964FF48073143001F0A4 +:10156000ABFD094B0294CDE9006304F523724FF4FF +:101570008073294604F14C0001F072FE04B070BD86 +:10158000AC3B000829150008511400080B683022F4 +:1015900082F311880A7903EB820290614A79093259 +:1015A00043F822008A7912B103EB82039861022387 +:1015B000C0F894140374002080F311887047000071 +:1015C00038B5037F044613B190F85430ABB9201DF1 +:1015D00001250221FFF734FF04F1140025776FF095 +:1015E000010100F069FC84F8545004F14C006FF0E4 +:1015F0000101BDE8384000F05FBC38BD10B50121E5 +:1016000004460430FFF71CFF0023237784F854308E +:1016100010BD000038B504460025143001F064FD0B +:1016200004F14C00257701F033FE201D84F854505E +:101630000121FFF705FF2046BDE83840FFF752BF04 +:1016400090F8443003F06003202B07D190F8452038 +:10165000212A4FF0000303D81F2A06D80020704724 +:10166000222AFBD1C0E90E3303E0034A826307223A +:10167000C2630364012070471C22002037B5D0F8F4 +:1016800094341A681178042904461AD1017C02297D +:1016900017D11979128901238B40134211D100F11E +:1016A0004C05284601F0B4FE58B101A9284601F0C6 +:1016B000FBFDD4F89444019B21790246206800F098 +:1016C000B5F803B030BD0000F0B500EB810385B084 +:1016D0009E6904460D46FEB1302383F3118804EB66 +:1016E0008507301D0821FFF7ABFEFB685B691B68AF +:1016F00006F14C001BB1019001F0E4FD019803A933 +:1017000001F0D2FD024648B1039B2946204600F075 +:101710008DF8002383F3118805B0F0BDFB685A698A +:101720001268002AF5D01B8A013B1340F1D104F165 +:101730004402EAE7093138B550F82140DCB13023E2 +:1017400083F31188D4F894241368527903EB82034D +:10175000DB689B695D6845B104216018FFF770FE86 +:10176000294604F1140001F0D5FC2046FFF7BAFE2B +:10177000002383F3118838BD7047000001F034B8AE +:10178000012303700023C0E90133C3618362036254 +:10179000C36243620363704738B50446302383F362 +:1017A00011880025C0E90355C0E90555416001F0E5 +:1017B0002BF80223237085F31188284638BD0000DA +:1017C00070B500EB810305465069DA600E46144699 +:1017D00018B110220021FFF79BFAA06918B110225E +:1017E0000021FFF795FA31462846BDE8704001F028 +:1017F000D5B80000826802F0011282600022C0E9C0 +:101800000422826101F056B9F0B400EB81044789EB +:10181000E4680125A4698D403D4345812360002390 +:10182000A2606360F0BC01F071B90000F0B400EB9D +:1018300081040789E468012564698D403D43058181 +:1018400023600023A2606360F0BC01F0EBB90000EC +:1018500070B50223002504460370C0E90255C0E9B3 +:101860000455C564856180F8345001F033F863682D +:101870001B6823B129462046BDE87040184770BD5B +:101880000378052B10B504460AD080F850300523A4 +:10189000037043681B680BB1042198470023A360C1 +:1018A00010BD00000178052906D190F8502043684A +:1018B00002701B6803B118477047000070B590F8BC +:1018C0003430044613B1002380F8343004F144026C +:1018D000204601F011F963689B68B3B994F844306D +:1018E00013F0600535D00021204601F0B1FB002146 +:1018F000204601F0A3FB63681B6813B10621204654 +:101900009847062384F8343070BD20469847002855 +:10191000E4D0B4F84A30E26B9A4288BFE36394F9AA +:101920004430E56B002B4FF0300380F20381002D33 +:1019300000F0F280092284F8342083F3118800211A +:10194000D4E90E232046FFF771FF002383F31188AB +:10195000DAE794F8452003F07F0343EA022340F2DC +:101960000232934200F0C58021D8B3F5807F48D081 +:101970000DD8012B3FD0022B00F09380002BB2D169 +:1019800004F14C02A2630222E2632364C1E7B3F5CF +:10199000817F00F09B80B3F5407FA4D194F846305E +:1019A000012BA0D1B4F84C3043F0020332E0B3F580 +:1019B000006F4DD017D8B3F5A06F31D0A3F5C06339 +:1019C000012B90D8636894F846205E6894F847101D +:1019D000B4F848302046B047002884D04368A36359 +:1019E0000368E3631AE0B3F5106F36D040F60242A5 +:1019F00093427FF478AF5C4BA3630223E36300233D +:101A0000C3E794F84630012B7FF46DAFB4F84C3047 +:101A100023F00203C4E90E55A4F84C30256478E79E +:101A2000B4F84430B3F5A06F0ED194F8463084F882 +:101A30004E30204600F0A6FF63681B6813B10121F9 +:101A400020469847032323700023C4E90E339CE704 +:101A500004F14F03A3630123C3E72378042B10D1C0 +:101A6000302383F311882046FFF7C4FE85F31188E5 +:101A70000321636884F84F5021701B680BB1204626 +:101A8000984794F84630002BDED084F84F3004237A +:101A9000237063681B68002BD6D00221204698472C +:101AA000D2E794F848301D0603F00F0120460AD50E +:101AB00001F014F8012804D002287FF414AF2B4B56 +:101AC0009AE72B4B98E700F0FBFFF3E794F84630DA +:101AD000002B7FF408AF94F8483013F00F01B3D017 +:101AE0001A06204602D501F0C7FAADE701F0BAFAAE +:101AF000AAE794F84630002B7FF4F5AE94F848300E +:101B000013F00F01A0D01B06204602D501F0A0FA69 +:101B10009AE701F093FA97E7142284F8342083F3CC +:101B200011882B462A4629462046FFF76DFE85F38D +:101B30001188E9E65DB1152284F8342083F3118819 +:101B40000021D4E90E232046FFF75EFEFDE60B22BE +:101B500084F8342083F311882B462A4629462046F0 +:101B6000FFF764FEE3E700BFDC3B0008D43B00085E +:101B7000D83B000838B590F834300446002B3ED0EE +:101B8000063BDAB20F2A34D80F2B32D8DFE803F045 +:101B9000373131082232313131313131313137375A +:101BA000C56BB0F84A309D4214D2C3681B8AB5FB9E +:101BB000F3F203FB12556DB9302383F311882B46E2 +:101BC0002A462946FFF732FE85F311880A2384F856 +:101BD00034300EE0142384F83430302383F311883A +:101BE00000231A4619462046FFF70EFE002383F312 +:101BF000118838BD036C03B198470023E7E7002143 +:101C0000204601F025FA0021204601F017FA63680A +:101C10001B6813B10621204698470623D7E700002A +:101C200010B590F83430142B044629D017D8062B61 +:101C300005D001D81BB110BD093B022BFBD80021F8 +:101C4000204601F005FA0021204601F0F7F963680B +:101C50001B6813B1062120469847062319E0152B6F +:101C6000E9D10B2380F83430302383F3118800232B +:101C70001A461946FFF7DAFD002383F31188DAE7E5 +:101C8000C3689B695B68002BD5D1036C03B198478F +:101C9000002384F83430CEE700230375826803699B +:101CA0001B6899689142FBD25A68036042601060D9 +:101CB0005860704700230375826803691B68996840 +:101CC0009142FBD85A6803604260106058607047C8 +:101CD00008B50846302383F311880B7D032B05D00C +:101CE000042B0DD02BB983F3118808BD8B6900221A +:101CF0001A604FF0FF338361FFF7CEFF0023F2E756 +:101D0000D1E9003213605A60F3E70000FFF7C4BF67 +:101D1000054BD9680875186802681A60536001227B +:101D20000275D860FEF7EEBA2826002030B50C4BBD +:101D3000DD684B1C87B004460FD02B46094A684625 +:101D400000F04EF92046FFF7E3FF009B13B1684611 +:101D500000F050F9A86907B030BDFFF7D9FFF9E7E7 +:101D600028260020D11C0008044B1A68DB68906804 +:101D70009B68984294BF00200120704728260020CD +:101D8000084B10B51C68D86822681A60536001229D +:101D90002275DC60FFF78EFF01462046BDE810404B +:101DA000FEF7B0BA2826002038B5074C0749084886 +:101DB000012300252370656001F068FB0223237076 +:101DC00085F3118838BD00BF90280020E43B00084F +:101DD0002826002000F044B9034A516853685B1A72 +:101DE0009842FBD8704700BF001000E08B600223D0 +:101DF00008618B82084670478368A3F1840243F828 +:101E0000142C026943F8442C426943F8402C094AD7 +:101E100043F8242CC26843F8182C022203F80C2C37 +:101E2000002203F80B2C044A43F8102CA3F12000E5 +:101E3000704700BF1D0300082826002008B5FFF7E3 +:101E4000DBFFBDE80840FFF761BF0000024BDB6825 +:101E500098610F20FFF75CBF28260020302383F312 +:101E60001188FFF7F3BF000008B50146302383F364 +:101E700011880820FFF75AFF002383F3118808BD5B +:101E8000064BDB6839B1426818605A6013604360E2 +:101E90000420FFF74BBF4FF0FF307047282600208B +:101EA0000368984206D01A6802605060996118462B +:101EB000FFF72CBF7047000038B504460D46206878 +:101EC000844200D138BD036823605C608561FFF700 +:101ED0001DFFF4E710B503689C68A2420CD85C684B +:101EE0008A600B604C602160596099688A1A9A6018 +:101EF0004FF0FF33836010BD1B68121BECE700003E +:101F00000A2938BF0A2170B504460D460A26601911 +:101F100001F0B4FA01F09CFA041BA54203D8751C29 +:101F20002E460446F3E70A2E04D9BDE8704001208E +:101F300001F0ECBA70BD0000F8B5144B0D46D96144 +:101F400003F1100141600A2A1969826038BF0A2230 +:101F5000016048601861A818144601F07FFA0A274A +:101F600001F076FA431BA342064606D37C1C2819CF +:101F700001F084FA27463546F2E70A2F04D9BDE876 +:101F8000F840012001F0C2BAF8BD00BF28260020A9 +:101F9000F8B506460D4601F05BFA0F4A134653F8B2 +:101FA000107F9F4206D12A4601463046BDE8F840E0 +:101FB000FFF7C2BFD169BB68441A2C1928BF2C4651 +:101FC000A34202D92946FFF79BFF22463146034828 +:101FD000BDE8F840FFF77EBF282600203826002005 +:101FE00010B4C0E9032300235DF8044B4361FFF7FD +:101FF000CFBF000010B5194C236998420DD0D0E92D +:102000000032816813605A609A680A449A6000231B +:1020100003604FF0FF33A36110BD2346026843F80D +:10202000102F53600022026022699A4203D1BDE85A +:10203000104001F01DBA936881680B44936001F071 +:1020400007FA2269E1699268441AA242E4D911446C +:10205000BDE81040091AFFF753BF00BF2826002033 +:102060002DE9F047DFF8BC8008F110072C4ED8F8B6 +:10207000105001F0EDF9D8F81C40AA68031B9A42F1 +:102080003ED81444D5E900324FF00009C8F81C408E +:1020900013605A60C5F80090D8F81030B34201D1EF +:1020A00001F0E6F989F31188D5E90331284698470C +:1020B000302383F311886B69002BD8D001F0C8F965 +:1020C0006A69A0EB04094A4582460DD2022001F05C +:1020D0001DFA0022D8F81030B34208D151462846E4 +:1020E000BDE8F047FFF728BF121A2244F2E712EBCF +:1020F000090938BF4A4629463846FFF7EBFEB5E7DF +:10210000D8F81030B34208D01444211AC8F81C0083 +:10211000A960BDE8F047FFF7F3BEBDE8F08700BF58 +:10212000382600202826002000207047FEE7000007 +:10213000704700004FF0FF307047000002290CD0BC +:10214000032904D00129074818BF00207047032A3B +:1021500005D8054800EBC2007047044870470020CE +:10216000704700BFC03C00082C220020743C0008CF +:1021700070B59AB00546084601A9144600F0C2F8A9 +:1021800001A8FEF7BDFD431C5B00C5E90034002239 +:10219000237003236370C6B201AB02341046D1B280 +:1021A0008E4204F1020401D81AB070BD13F8011B6D +:1021B00004F8021C04F8010C0132F0E708B53023E2 +:1021C00083F311880348FFF759FA002383F311883A +:1021D00008BD00BF9828002090F8443003F01F028B +:1021E000012A07D190F845200B2A03D10023C0E92A +:1021F0000E3315E003F06003202B08D1B0F848300F +:102200002BB990F84520212A03D81F2A04D8FFF7BC +:1022100017BA222AEBD0FAE7034A82630722C26385 +:1022200003640120704700BF2322002007B5052961 +:1022300017D8DFE801F0191603191920302383F3AA +:102240001188104A01900121FFF7BAFA01980E4A4D +:102250000221FFF7B5FA0D48FFF7DCF9002383F3FD +:10226000118803B05DF804FB302383F3118807481D +:10227000FFF7A6F9F2E7302383F311880348FFF74D +:10228000BDF9EBE7143C0008383C00089828002012 +:1022900038B50C4D0C4C0D492A4604F10800FFF7E7 +:1022A00067FF05F1CA0204F110000949FFF760FF5A +:1022B00005F5CA7204F118000649BDE83840FFF779 +:1022C00057BF00BF602D00202C220020F03B0008EB +:1022D000FD3B0008083C000870B5044608460D4662 +:1022E000FEF70EFDC6B22046013403780BB918463E +:1022F00070BD32462946FEF7EFFC0028F3D10120DD +:10230000F6E700002DE9F04705460C46FEF7F8FC1D +:102310002B49C6B22846FFF7DFFF08B10736F6B2F1 +:1023200028492846FFF7D8FF08B11036F6B2632EC9 +:102330000BD8DFF88C80DFF88C90234FDFF894A067 +:102340002E7846B92670BDE8F08729462046BDE8BC +:10235000F04701F0D5BB252E2ED107224146284655 +:10236000FEF7BAFC70B9194B224603F10C0153F881 +:10237000040B42F8040B8B42F9D11B8813800735FC +:102380000E34DDE7082249462846FEF7A5FC98B939 +:102390000F4BA21C197809090232C95D02F8041C0E +:1023A00013F8011B01F00F015345C95D02F8031C2E +:1023B000F0D118340835C3E704F8016B0135BFE7E5 +:1023C000E03C0008083C0008F73C0008E83C000836 +:1023D000107AFF1F1C7AFF1FBFF34F8F024AD3688A +:1023E000DB03FCD4704700BF003C024008B5094B3A +:1023F0001B7873B9FFF7F0FF074B1A69002ABFBFBC +:10240000064A5A6002F188325A601A6822F48062E1 +:102410001A6008BDBE2F0020003C02402301674522 +:1024200008B50B4B1B7893B9FFF7D6FF094B1A6918 +:1024300042F000421A611A6842F480521A601A6827 +:1024400022F480521A601A6842F480621A6008BD51 +:10245000BE2F0020003C02401728F0B516D80C4CC7 +:102460000C4923787BB90C4D0E4618234FF00062BF +:1024700055F8047B46F8042B013B13F0FF033A4464 +:10248000F6D10123237051F82000F0BD0020FCE7B5 +:1024900020300020C02F0020083D0008014B53F8D9 +:1024A00020007047083D000818207047172810B515 +:1024B000044601D9002010BDFFF7CEFF064B53F8AC +:1024C00024301844C21A0BB90120F4E71268013213 +:1024D000F0D1043BF6E700BF083D0008172838B5E7 +:1024E000044628D81549FFF777FFFFF77FFFF3234E +:1024F000CB600C23B0FBF3F203FB1205D30143EADC +:10250000C503DBB243F4007343F002030B610B69B4 +:1025100043F480330B61FFF75FFFFFF79DFF084B2C +:1025200053F8241000F0DAF8FFF77AFF2046BDE8F0 +:102530003840FFF7BBBF002038BD00BF003C024061 +:10254000083D0008F8B512F00103144642D1821884 +:10255000B2F1026F57D82D4B1B6813F0010352D014 +:102560002B4DFFF743FFF323EB60FFF735FF40F2FE +:102570000127032C15D824F001046618244C401AB6 +:1025800040F20117B142236900EB010524D123F089 +:1025900001032361FFF744FF0120F8BD043C043030 +:1025A000E7E78307E7D12B6923F440732B612B699D +:1025B0003B432B6151F8046B0660BFF34F8FFFF76D +:1025C0000BFF03689E42E9D02B6923F001032B61C6 +:1025D000FFF726FF0020E0E723F44073236123691F +:1025E0003B4323610B882B80BFF34F8FFFF7F4FE33 +:1025F0002D8831F8023BADB2AB42C3D0236923F042 +:1026000001032361E4E71846C7E700BF0038024032 +:10261000003C0240084908B50B7828B11BB9FFF708 +:10262000E5FE01230B7008BD002BFCD0BDE808407F +:102630000870FFF7F5BE00BFBE2F002010B50244A2 +:10264000064BD2B2904200D110BD441C00B253F8E8 +:10265000200041F8040BE0B2F4E700BF502800402E +:102660000F4B30B51C6F240407D41C6F44F4007466 +:102670001C671C6F44F400441C670A4C236843F435 +:10268000807323600244084BD2B2904200D130BD27 +:10269000441C00B251F8045B43F82050E0B2F4E768 +:1026A00000380240007000405028004007B5012269 +:1026B00001A90020FFF7C2FF019803B05DF804FBF9 +:1026C00013B50446FFF7F2FFA04205D0012201A98D +:1026D00000200194FFF7C4FF02B010BD7047000056 +:1026E000094B5A88B2F5805F10460BD022F00203E6 +:1026F00041F20102934205D041F20703C31A584246 +:102700005841704701207047002004E0034B1A68CD +:102710001AB9034AD2F874281A607047243000208E +:102720000030024008B5FFF7F1FF024B1868C0F314 +:10273000407008BD2430002070470000FEE7000014 +:102740000A4B0B480B4A90420BD30B4BDA1C121A64 +:10275000C11E22F003028B4238BF00220021FEF787 +:10276000D7BA53F8041B40F8041BECE7EC3E000812 +:1027700020310020203100202031002070B5D0E928 +:1027800015439E6800224FF0FF3504EB42135101C0 +:10279000D3F800090028BEBFD3F8000940F08040FC +:1027A000C3F80009D3F8000B0028BEBFD3F8000B14 +:1027B00040F08040C3F8000B013263189642C3F822 +:1027C0000859C3F8085BE0D24FF00113C4F81C3875 +:1027D00070BD0000890141F02001016103699B0681 +:1027E000FCD41220FFF7F8BA10B5054C2046FEF7CE +:1027F000C7FF4FF0A0436365024BA36510BD00BF48 +:10280000283000208C3D000870B50378012B054668 +:1028100050D12A4B446D98421BD1294B5A6B42F040 +:1028200080025A635A6D42F080025A655A6D5A69A5 +:1028300042F080025A615A6922F080025A610E21E8 +:1028400043205B6900F022FC1E4BE3601E4BC4F882 +:1028500000380023C4F8003EC02323606E6D4FF49F +:102860005023A3633369002BFCDA012333610C206E +:10287000FFF7B2FA3369DB07FCD41220FFF7ACFA9A +:102880003369002BFCDA0026A6602846FFF776FFA6 +:102890006B68C4F81068DB68C4F81468C4F81C6876 +:1028A0004BB90A4BA3614FF0FF336361A36843F058 +:1028B0000103A36070BD064BF4E700BF2830002081 +:1028C000003802404014004003002002003C30C0A9 +:1028D000083C30C0F8B5446D054600212046FFF79E +:1028E00079FFA96D00234FF001128F68C4F83438C6 +:1028F0004FF00066C4F81C284FF0FF3004EB431281 +:1029000001339F42C2F80069C2F8006BC2F808099F +:10291000C2F8080BF2D20B686A6DEB656362102394 +:102920001361166916F01006FBD11220FFF754FA56 +:10293000D4F8003823F4FE63C4F80038A36943F4E4 +:10294000402343F01003A3610923C4F81038C4F8EE +:1029500014380A4BEB604FF0C043C4F8103B084BEF +:10296000C4F8003BC4F81069C4F80039EB6D03F1FA +:10297000100243F48013EA65A362F8BD683D0008C5 +:1029800040800010426D90F84E10D2F8003823F4C9 +:10299000FE6343EA0113C2F8003870472DE9F8439B +:1029A00000EB8103456DDA68166806F00306731EB6 +:1029B000022B05EB41130C4680460FFA81F94FEAD2 +:1029C00041104FF00001C3F8101B4FF0010104F15A +:1029D000100398BFB60401FA03F391698EBF334E1A +:1029E00006F1805606F5004600293AD0578A04F1D0 +:1029F0005801490137436F50D5F81C180B43C5F8EF +:102A00001C382B180021C3F8101953690127611EC7 +:102A1000A7409BB3138A928B9B08012A88BF53431C +:102A2000D8F85C20981842EA034301F1400205EB14 +:102A30008202C8F85C00214653602846FFF7CAFEB0 +:102A400008EB8900C3681B8A43EA84534834640155 +:102A50001E432E51D5F81C381F43C5F81C78BDE81D +:102A6000F88305EB4917D7F8001B21F40041C7F89C +:102A7000001BD5F81C1821EA0303C0E704F13F034B +:102A800005EB83030A4A5A6028462146FFF7A2FE57 +:102A900005EB4910D0F8003923F40043C0F80039A1 +:102AA000D5F81C3823EA0707D7E700BF00800010DD +:102AB00000040002826D1268C265FFF75FBE00006D +:102AC0005831436D49015B5813F4004004D013F4AE +:102AD000001F0CBF02200120704700004831436DE9 +:102AE00049015B5813F4004004D013F4001F0CBFDD +:102AF000022001207047000000EB8101CB68196AB9 +:102B00000B6813604B6853607047000000EB810353 +:102B100030B5DD68AA691368D36019B9402B84BF4A +:102B2000402313606B8A1468426D1C44013CB4FB63 +:102B3000F3F46343033323F0030302EB411043EA4E +:102B4000C44343F0C043C0F8103B2B6803F00303B9 +:102B5000012B09B20ED1D2F8083802EB411013F460 +:102B6000807FD0F8003B14BF43F0805343F0005304 +:102B7000C0F8003B02EB4112D2F8003B43F00443A3 +:102B8000C2F8003B30BD00002DE9F041244D6E6DD0 +:102B900006EB40130446D3F8087BC3F8087B3807DC +:102BA0000AD5D6F81438190706D505EB8403214653 +:102BB000DB6828465B689847FA071FD5D6F81438B3 +:102BC000DB071BD505EB8403D968CCB98B69488A30 +:102BD0005A68B2FBF0F600FB16228AB91868DA6868 +:102BE00090420DD2121AC3E90024302383F31188D6 +:102BF0000B482146FFF78AFF84F31188BDE8F08176 +:102C0000012303FA04F26B8923EA02036B81CB6888 +:102C1000002BF3D021460248BDE8F041184700BF21 +:102C20002830002000EB810370B5DD68436D6C69CE +:102C30002668E6604A0156BB1A444FF40020C2F8E9 +:102C400010092A6802F00302012A0AB20ED1D3F851 +:102C5000080803EB421410F4807FD4F8000914BF75 +:102C600040F0805040F00050C4F8000903EB4212DD +:102C7000D2F8000940F00440C2F80009D3F8340843 +:102C8000012202FA01F10143C3F8341870BD19B9E9 +:102C9000402E84BF4020206020682E8A8419013C89 +:102CA000B4FBF6F440EAC44040F000501A44C6E7D2 +:102CB0002DE9F8433B4D6E6D06EB40130446D3F807 +:102CC0000889C3F8088918F0010F4FEA40171AD095 +:102CD000D6F81038DB0716D505EB8003D9684B69A9 +:102CE0001868DA68904230D2121A4FF000091A6060 +:102CF000C3F80490302383F3118821462846FFF758 +:102D000091FF89F3118818F0800F1CD0D6F8343861 +:102D10000126A640334216D005EB84036D6DD3F82F +:102D20000CC0DCF814200134E4B2D2F800E005EB6A +:102D300004342F445168714515D3D5F8343823EA4B +:102D40000606C5F83468BDE8F883012303FA04F2E7 +:102D50002B8923EA02032B818B68002BD3D02146D9 +:102D600028469847CFE7BCF81000AEEB010383423A +:102D700028BF0346D7F8180980B2B3EB800FE2D81A +:102D80009068A0F1040959F8048FC4F80080A0EB02 +:102D900009089844B8F1040FF5D818440B44906022 +:102DA0005360C7E7283000202DE9F74FA24C656D2E +:102DB0006E69AB691E4016F480586E6107D02046DC +:102DC000FEF746FD03B0BDE8F04F00F04DBC002E0D +:102DD00012DAD5F8003E98489B071EBFD5F8003E92 +:102DE00023F00303C5F8003ED5F8043823F00103AF +:102DF000C5F80438FEF756FD370505D58E48FFF7B0 +:102E0000BDFC8D48FEF73CFDB0040CD5D5F8083864 +:102E100013F0060FEB6823F470530CBF43F4105308 +:102E200043F4A053EB6031071BD56368DB681BB923 +:102E3000AB6923F00803AB612378052B0CD1D5F8DF +:102E4000003E7D489A071EBFD5F8003E23F00303DD +:102E5000C5F8003EFEF726FD6368DB680BB17648D7 +:102E60009847F30274D4B70227D5D4F85490DFF80A +:102E7000C8B100274FF0010A09EB4712D2F8003B16 +:102E800003F44023B3F5802F11D1D2F8003B002B7F +:102E90000DDA62890AFA07F322EA0303638104EB7D +:102EA0008703DB68DB6813B1394658469847A36D42 +:102EB00001379B68FFB29F42DED9F00617D5676DD8 +:102EC0003A6AC2F30A1002F00F0302F4F012B2F5EC +:102ED000802F00F08580B2F5402F08D104EB8303EA +:102EE0000022DB681B6A07F5805790426AD13003E5 +:102EF000D5F8184813D5E10302D50020FFF744FEAA +:102F0000A20302D50120FFF73FFE630302D5022092 +:102F1000FFF73AFE270302D50320FFF735FE7503BE +:102F20007FF550AFE00702D50020FFF7C1FEA107F3 +:102F300002D50120FFF7BCFE620702D50220FFF791 +:102F4000B7FE23077FF53EAF0320FFF7B1FE39E759 +:102F5000636DDFF8E4A0019300274FF00109A36D32 +:102F60009B685FFA87FB9B453FF67DAF019B03EBB8 +:102F70004B13D3F8001901F44021B1F5802F1FD174 +:102F8000D3F8001900291BDAD3F8001941F0904159 +:102F9000C3F80019D3F800190029FBDB5946606D0E +:102FA000FFF718FC218909FA0BF321EA03032381B7 +:102FB00004EB8B03DB689B6813B159465046984776 +:102FC0000137CCE7910708BFD7F80080072A98BFE0 +:102FD00003F8018B02F1010298BF4FEA182884E739 +:102FE000023304EB830207F580575268D2F818C009 +:102FF000DCF80820DCE9001CA1EB0C0C0021884265 +:103000000AD104EB830463689B699A6802449A605E +:103010005A6802445A606AE711F0030F08BFD7F8F4 +:1030200000808C4588BF02F8018B01F1010188BF47 +:103030004FEA1828E3E700BF28300020436D03EB78 +:103040004111D1F8003B43F40013C1F8003B704735 +:10305000436D03EB4111D1F8003943F40013C1F87B +:1030600000397047436D03EB4111D1F8003B23F465 +:103070000013C1F8003B7047436D03EB4111D1F8D9 +:10308000003923F40013C1F80039704700F16043A0 +:1030900003F561430901C9B283F80013012200F06E +:1030A0001F039A4043099B0003F1604303F561430A +:1030B000C3F880211A60704730B5039C0172043355 +:1030C00004FB0325C0E90653049B03630021059B11 +:1030D000C160C0E90000C0E90422C0E90842C0E9BB +:1030E0000A11436330BD0000416A0022C0E90411A7 +:1030F000C0E90A22C2606FF00101FEF7DDBE0000E8 +:10310000D0E90432934201D1C2680AB9181D704750 +:103110000020704703691960C2680132C260C26949 +:10312000134482690361934224BF436A036100210F +:10313000FEF7B6BE38B504460D46E3683BB162699A +:10314000131D1268A3621344E362002007E0237A90 +:1031500033B929462046FEF793FE0028EDDA38BD44 +:103160006FF00100FBE70000C368C269013BC36068 +:103170004369134482694361934224BF436A4361B4 +:1031800000238362036B03B11847704770B5302387 +:10319000044683F31188866A3EB9FFF7CBFF0546E4 +:1031A00018B186F31188284670BDA36AE26A13F845 +:1031B000015BA362934202D32046FFF7D5FF0023B1 +:1031C00083F31188EFE700002DE9F84F04460E461F +:1031D000174698464FF0300989F311880025AA4612 +:1031E000D4F828B0BBF1000F09D141462046FFF7C3 +:1031F000A1FF20B18BF311882846BDE8F88FD4E9F0 +:103200000A12A7EB050B521A934528BF9346BBF150 +:10321000400F1BD9334601F1400251F8040B43F82B +:10322000040B9142F9D1A36A40334036A362403582 +:10323000D4E90A239A4202D32046FFF795FF8AF386 +:103240001188BD42D8D289F31188C9E730465A4661 +:10325000FDF738FDA36A5B445E44A3625D44E7E783 +:1032600010B5029C0172043303FB0421C0E906136C +:103270000023C0E90A33039B0363049BC460C0E9D5 +:103280000000C0E90422C0E90842436310BD000009 +:10329000026AC260426AC0E904220022C0E90A222E +:1032A0006FF00101FEF708BED0E904239A4201D174 +:1032B000C26822B9184650F8043B0B6070470023DF +:1032C0001846FAE7C368C2690133C360436913440F +:1032D00082694361934224BF436A43610021FEF740 +:1032E000DFBD000038B504460D46E3683BB12369F5 +:1032F0001A1DA262E2691344E362002007E0237A08 +:1033000033B929462046FEF7BBFD0028EDDA38BD6B +:103310006FF00100FBE7000003691960C268013A21 +:10332000C260C269134482690361934224BF436A45 +:10333000036100238362036B03B1184770470000E9 +:1033400070B530230D460446114683F31188866A12 +:103350002EB9FFF7C7FF10B186F3118870BDA36ABD +:103360001D70A36AE26A01339342A36204D3E16948 +:1033700020460439FFF7D0FF002080F31188EDE7E5 +:103380002DE9F84F04460D46904699464FF0300A15 +:103390008AF311880026B346A76A4FB949462046EA +:1033A000FFF7A0FF20B187F311883046BDE8F88F02 +:1033B000D4E90A073A1AA8EB0607974228BF17462E +:1033C000402F1BD905F1400355F8042B40F8042B7E +:1033D0009D42F9D1A36A4033A3624036D4E90A235F +:1033E0009A4204D3E16920460439FFF795FF8BF335 +:1033F00011884645D9D28AF31188CDE729463A4645 +:10340000FDF760FCA36A3B443D44A3623E44E5E70C +:10341000D0E904239A4217D1C3689BB1836A8BB168 +:10342000043B9B1A0ED01360C368013BC360C369A1 +:103430001A44836902619A4224BF436A03610023EC +:1034400083620123184670470023FBE700F036B97A +:10345000014B586A704700BF000C0040034B00222C +:1034600058631A610222DA60704700BF000C004006 +:10347000014B0022DA607047000C0040014B58639A +:10348000704700BF000C0040FEE7000070B51B4B0A +:1034900001630025044686B0586085620E4600F040 +:1034A000BFF804F11003C4E904334FF0FF33C4E95B +:1034B0000635C4E90044A560E562FFF7C9FF2B4665 +:1034C0000246C4E9082304F134010D4A256580232E +:1034D0002046FEF78BFC0123E0600A4A0375009248 +:1034E00072680192B268CDE90223074B6846CDE9C4 +:1034F0000435FEF7A3FC06B070BD00BF9028002085 +:10350000983D00089D3D000889340008024AD36AAE +:103510001843D062704700BF282600204B684360E4 +:103520008B688360CB68C3600B6943614B6903623E +:103530008B6943620B6803607047000008B5264B37 +:1035400026481A6940F2FF110A431A611A6922F4E7 +:10355000FF7222F001021A611A691A6B0A431A6398 +:103560001A6D0A431A651E4A1B6D1146FFF7D6FFF6 +:1035700002F11C0100F58060FFF7D0FF02F1380175 +:1035800000F58060FFF7CAFF02F1540100F580608A +:10359000FFF7C4FF02F1700100F58060FFF7BEFF86 +:1035A00002F18C0100F58060FFF7B8FF02F1A8017D +:1035B00000F58060FFF7B2FF02F1C40100F5806002 +:1035C000FFF7ACFF02F1E00100F58060FFF7A6FF16 +:1035D000BDE8084000F0F0B80038024000000240AA +:1035E000A43D000808B500F06BFAFEF7DDFBFFF71D +:1035F0008DF8BDE80840FEF74BBE000070470000A4 +:10360000EFF3098305494A6B22F001024A636833EC +:1036100083F30988002383F31188704700EF00E0EB +:10362000302080F3118862B60C4B0D4AD96821F422 +:10363000E0610904090C0A43DA60D3F8FC20094967 +:1036400042F08072C3F8FC200A6842F001020A606E +:103650002022DA7783F82200704700BF00ED00E0F7 +:103660000003FA05001000E010B5302383F3118841 +:103670000E4B5B6813F4006314D0F1EE103AEFF3D5 +:103680000984683C4FF08073E361094BDB6B236670 +:1036900084F30988FEF768FB10B1064BA36110BDE7 +:1036A000054BFBE783F31188F9E700BF00ED00E06D +:1036B00000EF00E02F030008320300080E4B1A6CE5 +:1036C00042F008021A641A6E42F008021A660B4AA7 +:1036D0001B6E936843F008039360094B53229A6270 +:1036E0004FF0FF32DA6200229A615A63DA605A6060 +:1036F00001225A611A60704700380240002004E03D +:10370000000C0040094A08B51169D3680B40D9B2D2 +:10371000C9439B07116107D5302383F31188FEF756 +:1037200059FB002383F3118808BD00BF000C004043 +:103730001F4B1A696FEAC2526FEAD2521A611A69B4 +:10374000C2F308021A614FF0FF301A695A695861D2 +:1037500000215A6959615A691A6A62F080521A62E4 +:103760001A6A02F080521A621A6A5A6A58625A6ACF +:1037700059625A6A1A6C42F080521A641A6E42F008 +:1037800080521A661A6E0B4A106840F480701060FE +:10379000186F00F44070B0F5007F1EBF4FF480300A +:1037A00018671967536823F40073536000F060B919 +:1037B0000038024000700040344B4FF080521A64D1 +:1037C000334A4FF4404111601A6842F001021A6016 +:1037D0001A689107FCD59A6822F003029A602B4B75 +:1037E0009A6812F00C02FBD1196801F0F901196016 +:1037F0009A601A6842F480321A601A689203FCD503 +:103800005A6F42F001025A67204B5A6F9007FCD55D +:10381000204A5A601A6842F080721A601C4A536843 +:103820005904FCD5194B1A689201FCD51A4A9A60C2 +:103830000322C3F88C20194B1A68194B9A42194B72 +:1038400021D1194A1168194A91421CD140F205123E +:103850001A60144A136803F00F03052BFAD10B4BBF +:103860009A6842F002029A609A6802F00C02082AF2 +:10387000FAD15A6C42F480425A645A6E42F4804241 +:103880005A665B6E704740F20572E1E7003802400D +:10389000007000401854400700948838002004E06D +:1038A00011640020003C024000ED00E041C20F41E5 +:1038B000074A08B5536903F00103536123B1054A70 +:1038C00013680BB150689847BDE80840FFF7CCBEBD +:1038D000003C0140A0300020074A08B5536903F0BE +:1038E0000203536123B1054A93680BB1D06898472E +:1038F000BDE80840FFF7B8BE003C0140A030002002 +:10390000074A08B5536903F00403536123B1054A1C +:1039100013690BB150699847BDE80840FFF7A4BE92 +:10392000003C0140A0300020074A08B5536903F06D +:103930000803536123B1054A93690BB1D0699847D5 +:10394000BDE80840FFF790BE003C0140A0300020D9 +:10395000074A08B5536903F01003536123B1054AC0 +:10396000136A0BB1506A9847BDE80840FFF77CBE68 +:10397000003C0140A0300020164B10B55C6904F4F7 +:1039800078725A61A30604D5134A936A0BB1D06AC0 +:103990009847600604D5104A136B0BB1506B9847DB +:1039A000210604D50C4A936B0BB1D06B9847E20506 +:1039B00004D5094A136C0BB1506C9847A30504D584 +:1039C000054A936C0BB1D06C9847BDE81040FFF7E7 +:1039D0004BBE00BF003C0140A0300020194B10B589 +:1039E0005C6904F47C425A61620504D5164A136D81 +:1039F0000BB1506D9847230504D5134A936D0BB155 +:103A0000D06D9847E00404D50F4A136E0BB1506E89 +:103A10009847A10404D50C4A936E0BB1D06E984719 +:103A2000620404D5084A136F0BB1506F9847230402 +:103A300004D5054A936F0BB1D06F9847BDE810408D +:103A4000FFF712BE003C0140A030002008B503483B +:103A5000FDF798FABDE80840FFF706BEBC2300203A +:103A600008B5FFF74FFEBDE80840FFF7FDBD0000B9 +:103A7000062108B50846FFF709FB06210720FFF7D6 +:103A800005FB06210820FFF701FB06210920FFF7AF +:103A9000FDFA06210A20FFF7F9FA06211720FFF7A1 +:103AA000F5FA06212820FFF7F1FA07213220FFF767 +:103AB000EDFABDE808400C212620FFF7E7BA000028 +:103AC00008B5FFF735FE00F00DF8FDF76FFCFDF7C8 +:103AD00055FEFDF72DFDFFF791FDBDE80840FFF70E +:103AE000B5BC00000023054A19460133102BC2E97A +:103AF000001102F10802F8D1704700BFA030002089 +:103B0000034611F8012B03F8012B002AF9D1704765 +:103B100053544D3332463F3F3F0053544D333246AA +:103B20003430780053544D33324634327800535495 +:103B30004D333246343436585800000001203300EB +:103B40000010410001105A00031059000710310005 +:103B500000000000103B0008130400001A3B00089E +:103B600019040000243B0008210400002E3B00083B +:103B700000960000000000000000000000000000AF +:103B800000000000000000006D1300085913000839 +:103B900095130008811300088D130008791300089D +:103BA0006513000851130008A1130008000000006D +:103BB000AD14000899140008D5140008C1140008B9 +:103BC000CD140008B9140008A514000891140008C9 +:103BD000E1140008000000000100000000000000E7 +:103BE00063300000E03B0008802600209028002081 +:103BF0004865782F50726F6669434E430025424FE7 +:103C0000415244252D424C002553455249414C25F3 +:103C1000000000000200000000000000C9160008BB +:103C20003517000840004000302D0020402D0020B6 +:103C3000020000000000000003000000000000007F +:103C4000791700080000000010000000502D00202F +:103C500000000000010000000000000028300020EB +:103C6000010102002D2200083D210008D921000891 +:103C7000BD210008430000007C3C0008090243000D +:103C8000020100C032090400000102020100052403 +:103C9000001001052401000104240202052406008D +:103CA00001070582030800FF09040100020A000061 +:103CB00000070501024000000705810240000000E6 +:103CC00012000000C83C0008120110010200004070 +:103CD000AE2D0110000201020301000004030904DB +:103CE00025424F4152442500437562654772656520 +:103CF0006E2D736F6C6F0030313233343536373898 +:103D00003941424344454600004000000040000065 +:103D10000040000000400000000001000000020020 +:103D2000000002000000020000000200000002008B +:103D300000000200000002000040000000400000FF +:103D400000400000004000000000010000000200F0 +:103D5000000002000000020000000200000002005B +:103D6000000002000000020000000000BD18000872 +:103D7000751B0008211C000840004000883000200E +:103D800088300020010000009830002080000000F2 +:103D900040010000030000006D61696E0069646C01 +:103DA000650000000000812A00020000AAAAAAAA59 +:103DB00000000024FFFF00000000000000A00A0037 +:103DC0000000000000000000AAAAAAAA000000004B +:103DD000FFFF00000000000000000000140000547D +:103DE00000000000AAAAAAAA14000054FFFF0000C5 +:103DF00000000000000000008069100000000000CA +:103E0000AAAA8AAA40561000FFFF0000007070079F +:103E1000000000004001000100000000AAAAAAAAB8 +:103E200000010000F7FF000000000000000000009B +:103E30000000000000000000AAAAAAAA00000000DA +:103E4000FFFF000000000000000000000000000074 +:103E500000000000AAAAAAAA00000000FFFF0000BC +:103E60000000000000000000000000000000000052 +:103E70000A00000000000000030000000000000035 +:103E80000000000000000000000000000000000032 +:103E90000000000000000000000000000000000022 +:103EA000090000000000000000C01F00000000002A +:103EB000FF00000098280020BC230020009600008E +:103EC0000000080096000000000800000400000048 +:103ED000DC3C0008000000000000000000000000C2 +:0C3EE000000000000000000000000000D6 :00000001FF diff --git a/Tools/bootloaders/CubeNode-ETH_bl.bin b/Tools/bootloaders/CubeNode-ETH_bl.bin new file mode 100755 index 00000000000000..b27eaea5fd6d51 Binary files /dev/null and b/Tools/bootloaders/CubeNode-ETH_bl.bin differ diff --git a/Tools/bootloaders/CubeNode-ETH_bl.hex b/Tools/bootloaders/CubeNode-ETH_bl.hex new file mode 100644 index 00000000000000..99d6c28ea6cb27 --- /dev/null +++ b/Tools/bootloaders/CubeNode-ETH_bl.hex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diff --git a/Tools/bootloaders/CubeNode_bl.bin b/Tools/bootloaders/CubeNode_bl.bin new file mode 100755 index 00000000000000..20a33af6a70ba9 Binary files /dev/null and b/Tools/bootloaders/CubeNode_bl.bin differ diff --git a/Tools/bootloaders/CubeNode_bl.hex b/Tools/bootloaders/CubeNode_bl.hex new file mode 100644 index 00000000000000..1ac9ba815851e1 --- /dev/null +++ b/Tools/bootloaders/CubeNode_bl.hex @@ -0,0 +1,2140 @@ +:020000040800F2 +:1000000000070020F1020008B1330008693300083E +:10001000913300086933000889330008F3020008AF +:10002000F3020008F3020008F30200083544000858 +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F3020008C97C0008F57C0008E0 +:10006000217D00084D7D0008797D0008F9440008D5 +:10007000214500084D45000879450008A5450008C0 +:10008000CD450008F9450008F3020008493300088F +:10009000F302000859330008F3020008A57D0008A8 +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F3020008F3020008F3020008F30200082C +:1000E000097E0008F3020008F3020008F30200088A +:1000F000F3020008F3020008F30200082546000896 +:10010000F3020008F3020008917E0008F3020008E1 +:10011000F3020008F3020008F3020008F3020008EB +:100120005146000879460008A5460008D146000857 +:10013000FD460008F3020008F3020008F30200087D +:10014000F3020008F3020008F3020008F3020008BB +:1001500025470008514700087D470008F3020008C2 +:10016000F3020008F3020008F3020008F30200089B +:10017000F3020008F5700008F3020008F30200081B +:10018000F3020008F30200087D7E0008F302000875 +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000F3020008F3020008F3020008F30200084B +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F3020008E1700008F3020008F3020008CF +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008F3020008F3020008DA +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E000BD16000800000000000000000000000033 +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F06F040F921 +:1003600007F07EFA4FF055301F491B4A91423CBFBF +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE706F058F907F0DEFA13 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F042F8114C124DAC4203DA54F8041B11 +:1003D0008847F9E706F040B9000700200023002015 +:1003E0000000000808ED00E00001002000070020E8 +:1003F00030850008002300206C230020702300209B +:1004000070740020E0020008E4020008E402000822 +:10041000E40200082DE9F04F2DED108AC1F80CD050 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002005F0D2FAFEE705F013 +:100440004DFA00DFFEE70000F8B501F0B3F901F066 +:1004500055FB06F021F8074606F0B8F80546A8BB9C +:100460001F4B9F4232D001339F4232D027F0FF0210 +:100470001C4B9A4230D12E4642F21074F8B200F072 +:100480006DFF00F071FF08B10024264601F0C6FDA3 +:1004900020B10024032000F079F8264635B1124B34 +:1004A0009F4203D0002406F089F82646002005F07C +:1004B000FDFF0EB100F080F801F0BEFA00F088FFF9 +:1004C000204600F02BF900F077F8F9E72E460024DB +:1004D000D7E704460126D4E7064641F28834D0E740 +:1004E000010007B0000008B0263A09B008B501F0D5 +:1004F0002DF9A0F120035842584108BD07B541F23B +:100500001203022101A8ADF8043001F03DF903B057 +:100510005DF804FB38B5302383F31188174803686E +:100520000BB105F029FB0023154A4FF47A711348EB +:1005300005F018FB002383F31188124C236813B1D4 +:100540002368013B2360636813B16368013B636008 +:100550000D4D2B7833B963687BB9022001F0DEF9C9 +:10056000322363602B78032B07D163682BB90220F9 +:1005700001F0D4F94FF47A73636038BD7023002022 +:10058000150500089024002088230020084B1870CF +:1005900003280CD8DFE800F008050208022001F06B +:1005A000BBB9022001F0B6B9024B00225A60704775 +:1005B0008823002090240020F8B501F02FFD30B1F1 +:1005C0004D4B03221A7000224C4B5A60F8BD4C4B25 +:1005D0004C4A1C4619680131F8D004339342F9D1D2 +:1005E0006268494B9A42F1D9484B9B6803F100631A +:1005F00003F580239A42E9D205F0B4FF05F0C6FF67 +:10060000002001F0FDF80220FFF7C0FF404B002161 +:100610009A6C99641A6F19671A6FDA6CD9645A6FF9 +:1006200059675A6F1A6D19659A6F99679B6F394BA5 +:10063000D3F8802042F00062C3F88020D3F88020F5 +:1006400022F00062C3F88020D3F88020D3F8802005 +:1006500042F00072C3F88020D3F8802022F00072AC +:10066000C3F88020D3F8803072B64FF0E023C3F88F +:10067000084DD4E90004BFF34F8FBFF36F8F264AB4 +:10068000C2F88410BFF34F8F536923F48033536152 +:10069000BFF34F8FD2F8803043F6E076C3F3C9053D +:1006A000C3F34E335B0103EA060C29464CEA81771B +:1006B0000139C2F87472F9D2203B13F1200FF2D144 +:1006C000BFF34F8FBFF36F8FBFF34F8FBFF36F8FAA +:1006D000536923F4003353610023C2F85032BFF34F +:1006E0004F8FBFF36F8F302383F31188854680F3DC +:1006F000088820476AE700BF882300209024002054 +:100700000000040820000408FFFF03080023002065 +:10071000004502580044025800ED00E02DE9F04F7A +:1007200093B0B74B2022FF2100900AA89D6801F0EA +:100730002DF9B44A1378A3B90121B34811700360AD +:10074000302383F3118803680BB105F015FA0023F9 +:10075000AE4A4FF47A71AC4805F004FA002383F3F3 +:100760001188009B13B1AA4B009A1A60A94A13780A +:10077000032B03D000231370A54A53604FF0000AE7 +:10078000009CD3465646D146012001F0C5F824B15D +:100790009F4B1B68002B00F02C82002000F0D6FF3E +:1007A0000390039B002B01DA00F05AFE039B002B01 +:1007B000EDDB012001F0AEF8039B213B1F2BE3D8BA +:1007C00001A252F823F000BF490800087108000890 +:1007D000050900088907000889070008890700083B +:1007E00097090008670B0008810A0008E30A00085F +:1007F0000B0B0008310B000889070008430B0008A9 +:1008000089070008B50B0008E908000889070008F7 +:10081000F90B000855080008E908000889070008D6 +:10082000E30A00088907000889070008890700080B +:100830008907000889070008890700088907000858 +:1008400089070008050900080220FFF74FFE00286D +:1008500040F0F981009B022105A8BAF1000F08BF02 +:100860001C4641F21233ADF8143000F08DFF8BE7D7 +:100870004FF47A7000F06AFF071EEBDB0220FFF7EF +:1008800035FE0028E6D0013F052F00F2DE81DFE8CB +:1008900007F0030A0D1013360523042105A805935C +:1008A00000F072FF17E004215548F9E704215A4887 +:1008B000F6E704215948F3E74FF01C08404608F1D9 +:1008C000040800F09FFF0421059005A800F05CFFDC +:1008D000B8F12C0FF2D101204FF0000900FA07F710 +:1008E00047EA0B0B5FFA8BFB01F09CF826B10BF08B +:1008F0000B030B2B08BF0024FFF700FE44E7042185 +:100900004748CDE7002EA5D00BF00B030B2BA1D150 +:100910000220FFF7EBFD074600289BD001200026B0 +:1009200000F06EFF0220FFF731FE1FFA86F8404606 +:1009300000F076FF0446B0B1039940460136A1F1BC +:1009400040025142514100F083FF0028EDD1BA46E8 +:10095000044641F21213022105A83E46ADF81430B8 +:1009600000F012FF10E725460120FFF70FFE244B91 +:100970009B68AB4207D9284600F044FF013040F0A5 +:1009800067810435F3E70025224BBA463E461D70C9 +:100990001F4B5D60A8E7002E3FF45CAF0BF00B032C +:1009A0000B2B7FF457AF0220FFF7F0FD322000F051 +:1009B000CDFEB0F10008FFF64DAF18F003077FF44D +:1009C00049AF0F4A08EB0503926893423FF642AFE6 +:1009D000B8F5807F3FF73EAF124BB845019323DD5A +:1009E0004FF47A7000F0B2FE0390039A002AFFF6EB +:1009F00031AF039A0137019B03F8012BEDE700BFEC +:100A0000002300208C2400207023002015050008FE +:100A100090240020882300200423002008230020A5 +:100A20000C2300208C230020C820FFF75FFD074621 +:100A300000283FF40FAF1F2D11D8C5F120020AABDB +:100A400025F0030084494245184428BF42460192DC +:100A500000F076FF019AFF217F4800F097FF4FEAF0 +:100A6000A803C8F387027C492846019300F096FF4B +:100A7000064600283FF46DAF019B05EB830533E785 +:100A80000220FFF733FD00283FF4E4AE00F0F2FE51 +:100A900000283FF4DFAE0027B846704B9B68BB428E +:100AA00018D91F2F11D80A9B01330ED027F003034A +:100AB00012AA134453F8203C05934046042205A98A +:100AC000043701F095FA8046E7E7384600F09AFED1 +:100AD0000590F2E7CDF81480042105A800F054FE3B +:100AE00002E70023642104A8049300F043FE0028D9 +:100AF0007FF4B0AE0220FFF7F9FC00283FF4AAAE65 +:100B0000049800F0ADFE0590E6E70023642104A8F8 +:100B1000049300F02FFE00287FF49CAE0220FFF724 +:100B2000E5FC00283FF496AE049800F09BFEEAE74F +:100B30000220FFF7DBFC00283FF48CAE00F0AAFE99 +:100B4000E1E70220FFF7D2FC00283FF483AE05A9BD +:100B5000142000F0A5FE07460421049004A800F02C +:100B600013FE3946B9E7322000F0F0FD071EFFF60C +:100B700071AEBB077FF46EAE384A07EB090392688B +:100B800093423FF667AE0220FFF7B0FC00283FF427 +:100B900061AE27F003074F44B9453FF4A5AE484680 +:100BA00009F1040900F02EFE0421059005A800F0CB +:100BB000EBFDF1E74FF47A70FFF798FC00283FF463 +:100BC00049AE00F057FE002844D00A9B01330BD0F9 +:100BD00008220AA9002000F0E1FE00283AD02022D5 +:100BE000FF210AA800F0D2FEFFF788FC1C4804F0A1 +:100BF000FDFE13B0BDE8F08F002E3FF42BAE0BF0DE +:100C00000B030B2B7FF426AE0023642105A805936C +:100C100000F0B0FD074600287FF41CAE0220FFF76D +:100C200065FC804600283FF415AEFFF767FC41F2F3 +:100C3000883004F0DBFE059800F03EFF46463C4657 +:100C400000F0F0FEA0E506464EE64FF0000901E692 +:100C5000BA467EE637467CE68C230020002300203F +:100C6000A0860100094A49F26900136899B21B0C79 +:100C700000FB013344F250611360054B186882B2E7 +:100C8000000C01FB0200186080B2704714230020A2 +:100C9000102300200021102210B5044600F076FE3B +:100CA000034B03CB206061601868A06010BD00BFDB +:100CB00000E8F11FF0B5ADF54F7D4FF4C472074663 +:100CC0000D466CAC0021204600F060FE02F078FB7F +:100CD0004FF47A72254BB0FBF2F0186093E80700EE +:100CE000022384E807000DF5E9702382FFF7D2FFA5 +:100CF00043F204731E4907A8238407F063F91623FF +:100D00000DF2E3220DF12C0C84F8323107AB1E46B4 +:100D1000083203CE664542F8080C42F8041C3346FC +:100D2000F5D1306810602046B3880DAE938031460F +:100D3000012200F043FF002380B2E97E0393AB7EE3 +:100D4000029305F1190301930123009305A3D3E94D +:100D50000023CDE90460384602F03CFF0DF54F7DDD +:100D6000F0BD00BF9E6AC421818A46EE982400200F +:100D7000D47F00082DE9F0412C4CDAB080460D46B6 +:100D8000237A5BBB27A9284601F03CF807460028D8 +:100D900042D19DF89D60C82E3ED801464FF4A66210 +:100DA000204600F0F3FD4FF4807332460DF19E01B2 +:100DB000C4F8F8314FF4007304F109002644C4F874 +:100DC0000C334FF44073C4F8203400F0B9FD9DF8A3 +:100DD0009C30777223720BB9EB7E237206AC8122B2 +:100DE000002127A800F0D2FD0122214627A801F00A +:100DF0004FF8002380B2E97E0393AB7E029305F1A6 +:100E0000190301932823CDE904400093404605A32C +:100E1000D3E9002302F0DEFE5AB0BDE8F08100BF46 +:100E2000AFF3008026417272DF25D7B7E03400208F +:100E3000F0B5254E4FF48A75F1B0002405FB00652E +:100E400096F8D830D822214685F8DC303AA885F8C3 +:100E5000E84006AF00F09AFD06F1090000F08EFDB3 +:100E6000D5F8E430C2B206F109018DF8F0000DF1B9 +:100E7000F100CDE93A3400F063FD394601223AA889 +:100E800001F03CF8082380B2317ACDE904700127E3 +:100E90000E48CDE9023706F1D803019330230093C1 +:100EA00007A3D3E9002302F095FEA04206DD02F07D +:100EB00087FAC5F8E000384671B0F0BD2046FBE780 +:100EC00078F6339F93CACD8DE0340020B0340020F3 +:100ED0002DE9F0411D4D86B01D4E1E4F284602F0F3 +:100EE000A5FE034658B30024DFF86C80ADF814402B +:100EF0000294CDE90344027B8DF8142003AA99687B +:100F0000406803C21B6843F00043029302F05AFAA0 +:100F100082190094384641F1000302A901F07CFADD +:100F2000A04205DD284602F085FE88F80040D5E79E +:100F300098F80030072B05D8013388F8003006B048 +:100F4000BDE8F081014802F075FEF8E7B0340020FA +:100F500040420F00183A0020153A002070B50D46A7 +:100F600014461E4602F092FD50B9022E10D1012CFB +:100F70000ED112A3D3E900230120C5E9002307E025 +:100F8000282C10D005D8012C09D0052C0FD000201A +:100F900070BD302CFBD10BA3D3E90023ECE70BA3EE +:100FA000D3E90023E8E70BA3D3E90023E4E70BA38D +:100FB000D3E90023E0E700BFAFF30080401DA1208C +:100FC00026812A0B78F6339F93CACD8D9E6AC42161 +:100FD000818A46EE26417272DF25D7B7F017304A74 +:100FE00039059E5638B505460E4C0021013500F0F6 +:100FF0002FFCA4F82C55B4F82C0500F011FC78B1A6 +:10100000B4F82C0500F01CFC014648B9B4F82C05D6 +:1010100000F01EFCB4F82C350133A4F82C35EAE7B7 +:1010200038BD00BFE03400200A4B0B4A10B51A60EF +:1010300003F5805393F850203AB9DC6C2CB120466C +:1010400001F06AF8204601F0A3F90448BDE8104019 +:1010500001F062B8183A00207C800008504A002055 +:101060002DE9F04F8FB005460C4600AF02F00EFDA3 +:1010700000284BD1237E022B1BD1E38A012B18D1F0 +:1010800002F09EF90646FFF7EDFD03464FF4C870E7 +:1010900006F51676DFF8C082B3FBF0F202FB1033E0 +:1010A00016FA83F3C8F80030E37E33B9A34B00226D +:1010B0001A703C37BD46BDE8F08F07F12401204689 +:1010C00000F054FE0028F4D107F11400FFF7E2FD10 +:1010D00097F8264007F1140107F12700224606F091 +:1010E0003FFF0028E2D10F2C08D8944B1C70D8F891 +:1010F0000030A3F51673C8F80030DAE797F824102B +:101100000029D6D0284602F0B9FCD2E7E38A282B82 +:101110002BD010D8012B23D0052BCAD1BFF34F8F72 +:101120008749884BCA6802F4E0621343CB60BFF37F +:101130004F8F00BFFDE7302BBBD1834EE17E327A6B +:101140009142B6D1607E3146002291F8DC50854252 +:1011500000F0A580013201F58A71042AF5D1A8E7D3 +:1011600021462846FFF7A6FDA3E721462846FFF7BC +:1011700001FE9EE7B2F8EC507B6005F103094FEAEF +:1011800099094FEA8902D11DC908A8EBC1030021C2 +:101190009D46EB46584600F0F9FB04F1EE012A4665 +:1011A0005846314400F0CCFB7B6813B9012000F0B5 +:1011B00027FB96F8D20000F033FB044630B93072BA +:1011C00000F058FB204600F01BFBB0E0D6F8D4201E +:1011D0003AB996F8D200B6F82C25824201D8FFF72A +:1011E00001FFD6F8D4202A44944208D296F8D200BF +:1011F000B6F82C250130824201D8FFF7F3FE5FFAE2 +:1012000089F25946706800F0C9FB08B9C54679E013 +:10121000726896F8D2002A447260D6F8D42005EBA2 +:101220000209C6F8D49000F0FBFA814509D396F87C +:10123000D220D6F8D4000132001B86F8D220C6F89E +:10124000D400FF2D0FD80024347200F013FB204689 +:1012500000F0D6FA00F0E2FE3C4B188108B9FFF727 +:10126000ABF9C54625E7BB6896F8D9000AFB0362CF +:10127000FB68D2F8E41082F8E83001F58061C2F82A +:10128000E030C2F8E410FFF7D3FDFFF721FE96F837 +:10129000D920013202F0030286F8D920B6E74FF4D4 +:1012A0008A7A20460AFB02F505F1EA01314400F092 +:1012B00059FEF86000287FF4FCAE0122354485F821 +:1012C000E82002F07DF8D5F8E020D6ED007A801A0B +:1012D00040F6B832B8EE677ADFED1D6A192838BFDC +:1012E0001920904228BF104607EE900AF8EEE77AE0 +:1012F00067EEA67ADFED176AE7EE267AFCEEE77A6C +:10130000C6ED007A96F8D93071680AFB03F4BB6029 +:10131000321992F8E8505DB1D2F8E430E8468B42D9 +:101320003FF428AF002182F8E810C2F8E010C5466B +:101330007368064A9B0A01331381BAE6A934002078 +:1013400000ED00E00400FA05E034002098240020BD +:10135000CDCCCC3D6666663FAC340020014B1870A6 +:10136000704700BFA424002038B54FF00054144B40 +:1013700022689A4222D1607DF8B1124B0025C92221 +:10138000114918701148237D0930C0F8DB5000F86E +:10139000013C4FF48073C0F8EF314FF40073C0F894 +:1013A00003334FF44073C0F8173400F0C9FAE02259 +:1013B0002946204600F0EAFA012038BD0020FCE76B +:1013C0009AAD44C5A424002016000020E03400207B +:1013D00037B500F023FE194D022300221849288159 +:1013E0006B710123174801F0A7FB002316494FF446 +:1013F00080520193154B16480093164B02F016FBD2 +:10140000154B197811B1124802F038FB01F0D8FFE2 +:101410000446FFF727FC4FF4C873B0FBF3F202FB5E +:10142000130304F5167010FA83F00C4B186005F0E6 +:10143000CDF808B10F232B8103B030BD98240020D4 +:1014400040420F00183A0020A82400205D0F000839 +:10145000B034002061100008A4240020AC34002027 +:101460002DE9F04F8C4C2DED028B85A7D7E9006755 +:1014700095B00FF21429D9E900899FED858BFFF70C +:1014800027FD0DAD0023DFF824B20C93ADF83C30FE +:101490000D936B6000234FF0010A0DF1250209A99D +:1014A00058468DF825308DF824A08DED008B01F085 +:1014B000EFFE9DF824200023002A40F0AE80204655 +:1014C00002F0E4FA0546002847D1DFF8E4B101F064 +:1014D00077FFDBF8003098423FD301F071FF0790AF +:1014E000FFF7C0FB4FF4C873079AB0FBF3F101FBA1 +:1014F000130302F5167010FA83F0CBF8000010A861 +:10150000DFF8B0B19BF80010002914BF2B465346FA +:1015100007918DF83030FFF7BDFB079910AB0DF147 +:101520003100C1F110021944D2B2062A28BF0622A6 +:10153000079200F005FA079A0CAB2046039301329C +:101540001823D2B20293554B04923246CDE900A340 +:101550003B4602F0E1FA8BF8005001F031FF504AAF +:10156000504D1368C31AB3F57A7F32D3106001F07F +:1015700029FF02460B46204602F066FB204602F099 +:1015800085FA30B32B7A0DF1400BDFF82CA1002B3C +:1015900014BF032302238AF8053001F011FF4FF432 +:1015A0007A7301225946B0FBF3F0CAF800005046A6 +:1015B00000F0B4FB182380B2424602933A4B0193E9 +:1015C00040F25513CDE903B0009320464B4602F09C +:1015D000A3FA2B7AABB101F0F3FE4FF0000A834679 +:1015E0004FF48A7295F8D900504400F0030002FBD2 +:1015F000005393F8E81071B30AF1010ABAF1040F2D +:10160000F0D1C82004F0F2F92B7A002B7FF435AF2B +:1016100015B0BDEC028BBDE8F08F1946102210A862 +:1016200000F0B4F90DF126030AAA0CA9584601F0FE +:1016300011F911AB95E8030083E803009DF83C30F5 +:1016400010A920468DF84C300C9B1093DDE90A233D +:1016500002F0CEFC1EE7D3F8E01049B12B68ABEBEB +:101660000101FA2B38BFFA230533B1EB430FC3D383 +:10167000FFF7DEFB4FF48A720028BDD1C1E700BF3F +:10168000401DA12026812A0BF1C6A7C1D068080FF2 +:101690000000000000000000B0340020A83400204A +:1016A000103A0020E0340020143A0020183A0020BC +:1016B000AC340020A93400209824002008B5054847 +:1016C00001F072F9044A05490020BDE8084006F01F +:1016D00033BC00BF183A0020344F00202910000806 +:1016E0002DE9F84F4FF47A7306460D46002402FBAD +:1016F00003F7DFF85080DFF8509098F900305FFA78 +:1017000084FA5A1C01D0A34212D159F824002A4667 +:1017100031460368D3F820B03B46D847854207D10D +:10172000074B012083F800A0BDE8F88F0124E4E70F +:10173000002CFBD04FF4FA7004F058F90020F3E7C6 +:10174000244F0020182300201C230020002307B56D +:10175000024601210DF107008DF80730FFF7C0FFA9 +:1017600020B19DF8070003B05DF804FB4FF0FF3097 +:10177000F9E700000A46042108B5FFF7B1FF80F041 +:101780000100C0B2404208BD074B0A4630B4197888 +:10179000064B53F82140014623682046DD69044B7F +:1017A000AC4630BC604700BF244F00201C23002003 +:1017B000A086010070B5104C0025104E04F040FCCE +:1017C00020803068238883420CD800252088013887 +:1017D00004F032FC23880544013BB5F5802F2380BB +:1017E000F4D370BD04F028FC336805440133B5F52B +:1017F000802F3360E5D3E8E7264F0020E04E00203D +:1018000004F0ECBC00F1006000F580200068704737 +:1018100000F10060920000F5802004F06DBC000033 +:10182000054B1A68054B1B889B1A834202D910444A +:1018300004F002BC00207047E04E0020264F00203C +:10184000024B1B68184404F0FDBB00BFE04E0020B3 +:10185000024B1B68184404F007BC00BFE04E002098 +:101860000020704700F1FF5000F58F10D0F80008FD +:1018700070470000064991F8243033B10023082254 +:10188000086A81F82430FFF7C3BF0120704700BF0A +:10189000E44E0020014B1868704700BF0010005C48 +:1018A000194B01380322084470B51D68174BC5F366 +:1018B0000B042D0C1E88A6420BD15C680A46013C25 +:1018C000824213460FD214F9016F4EB102F8016B38 +:1018D000F6E7013A03F10803ECD181420B4602D24C +:1018E0002C2203F8012B0424094A1688AE4204D1A5 +:1018F000984284BF967803F8016B013C02F1040220 +:10190000F3D1581A70BD00BF0010005C24230020E2 +:101910001880000870470000704700007047000002 +:1019200070B504464FF47A764CB1412C254628BF59 +:10193000412506FB05F0641B04F058F8F4E770BD80 +:10194000002310B5934203D0CC5CC4540133F9E7B3 +:1019500010BD0000013810B510F9013F3BB191F9FD +:1019600000409C4203D11AB10131013AF4E71AB1A7 +:1019700091F90020981A10BD1046FCE70346024674 +:10198000D01A12F9011B0029FAD17047024403460C +:10199000934202D003F8011BFAE770472DE9F843A0 +:1019A0001F4D14460746884695F8242052BBDFF8A1 +:1019B00070909CB395F824302BB92022FF21484623 +:1019C0002F62FFF7E3FF95F824004146C0F10802BB +:1019D00005EB8000A24228BF2246D6B29200FFF754 +:1019E000AFFF95F82430A41B17441E449044E4B282 +:1019F000F6B2082E85F82460DBD1FFF73BFF002804 +:101A0000D7D108E02B6A03EB82038342CFD0FFF7E4 +:101A100031FF0028CBD10020BDE8F8830120FBE78F +:101A2000E44E0020024B1A78024B1A70704700BF38 +:101A3000244F00201823002038B51A4C1A4D204698 +:101A400003F0F4FA2946204603F01CFB2D684FF4FE +:101A50007A70D5F89020D2F8043843F00203C2F827 +:101A60000438FFF75DFF1149284603F019FCD5F84B +:101A700090200F4DD2F80438286823F002030D4956 +:101A8000A042C2F804384FF4E1330B6001D003F0F8 +:101A90002BFA6868A04204D00649BDE8384003F03C +:101AA00023BA38BD98560020CC820008D4820008A2 +:101AB0001C2300200C4F00200C4B70B50C4D04462D +:101AC0001E780C4B55F826209A420DD00A4B002167 +:101AD00018221846FFF75AFF0460014655F8260001 +:101AE000BDE8704003F000BA70BD00BF244F002075 +:101AF0001C230020985600200C4F0020F8B571B62A +:101B0000002301201A46194602F0D6FE0446802022 +:101B100004F002FC002849D00025254A80274FF414 +:101B2000D06C3D26136913F0C06F26D1D2F8103166 +:101B300013F0C06F21D1236805F10061996023681B +:101B4000D86023685F602368C3F800C021680B6811 +:101B500043F001030B6021680B6823F01E030B6048 +:101B600021680B68DB07FCD4237B8035616806FAAB +:101B700003F3B5F5001F0B60D4D1204602F0D2FE6E +:101B8000B5F5001F11D000240A4E0B4D012004F0C2 +:101B900025FB3388A34205D928682044013404F08A +:101BA00063FAF6E7002004F019FB61B6F8BD00BF48 +:101BB00000200052264F0020E04E00202DE9F34780 +:101BC0000D46044600219046284640F27912FFF760 +:101BD000DDFE234620220021284604F1220702F0E0 +:101BE000A9F9231D022220212846C02602F0A2F9CD +:101BF000631D03222221284602F09CF9A31D032223 +:101C00002521284602F096F904F108031022282124 +:101C1000284602F08FF904F11003082238212846E3 +:101C200002F088F904F1110308224021284602F04D +:101C300081F904F1120308224821284602F07AF9BA +:101C400004F1140320225021284602F073F904F114 +:101C5000180340227021284602F06CF904F1200399 +:101C60000822B021284602F065F904F12103082278 +:101C7000B821284602F05EF9314608363B46082274 +:101C80002846013702F056F9B6F5A07FF4D194F852 +:101C90003230314604F1330A00268DF8073008222D +:101CA0000DF10703284602F045F99DF807304FEA89 +:101CB000C6099E4209F5A47720D394F83231502BFF +:101CC00028BF50238DF80730B8F1000F08D13946EE +:101CD00009F24F170DF107030722284602F02AF9EF +:101CE000002604F233149DF8073007EBC6019E422C +:101CF0000DD30731C80802B0BDE8F0870AEB060330 +:101D0000082239462846013602F014F9CDE7A31916 +:101D100008222846013602F00DF9E4E713B504461F +:101D2000084600212022234601900160C0F80310DC +:101D300002F000F9231D01980222202102F0FAF896 +:101D4000631D01980322222102F0F4F8A31D0198DB +:101D50000322252102F0EEF8019804F10803102275 +:101D6000282102F0E7F8072002B010BDF7B5047F84 +:101D700005460E462CB1838A122B02D9012003B0EE +:101D8000F0BD0023072228460096194601F096FF71 +:101D9000731C0122072100932846002301F08EFFC7 +:101DA000D4B9B31C052208212846009323460D24EC +:101DB00001F084FFB378102BE0D83746BB1BB27814 +:101DC000934210D307342B7FA88AE408B3B9844226 +:101DD00094BF00200120D2E7AB8A0824DB00083B37 +:101DE000DB08B370E6E7FB1C214608222846009377 +:101DF00000230834013701F061FFDFE7201A18BF24 +:101E00000120BCE7F7B5047F05460E462CB1838A56 +:101E1000CA2B02D9012003B0F0BD002308222846B6 +:101E20000096194601F04AFF731CD4B908220093AA +:101E3000234610241146284601F040FF7378C82B32 +:101E4000E8D801235F1C7278013B934210D307341A +:101E50002B7FA88AE408B3B9844294BF00200120F4 +:101E6000D9E7AB8A0824DB00083BDB087370E5E7A1 +:101E7000F3192146082228460093002301F01EFF93 +:101E800008343B46DEE7201A18BF0120C3E70000F4 +:101E9000F7B50D4604460021164628468122FFF775 +:101EA00075FD234608220021284602F043F894F9E4 +:101EB00001206378002AB8BF7F238DF807309EB9D0 +:101EC0000F270DF1070307220821284602F032F8F8 +:101ED000002602349DF8073007EBC6019E4205D369 +:101EE0000731C80803B0F0BD0827F1E7A31908229D +:101EF0002846013602F01EF8ECE70000F7B50E4662 +:101F00000546002114463046CE22FFF73FFD2B4602 +:101F100028220021304602F00DF82B7AC82B28BF6A +:101F2000C8238DF807308CB930240DF1070308223F +:101F30002821304601F0FEFF2F467B1B9DF807202D +:101F4000934205D3E01DC00803B0F0BD2824F3E799 +:101F500007F109032146082230460834013701F011 +:101F6000E9FFEAE7F7B5047F05460E4634B1838AF8 +:101F7000B3F5827F02D9012003B0F0BD0123102206 +:101F800000212846009601F099FEDCB9B31C092215 +:101F90001021284600932346192401F08FFE7388F0 +:101FA000B3F5807FE7D83746BB1B7288934210D3C6 +:101FB00007342B7FA88AE408B3B9844294BF002079 +:101FC0000120D9E7AB8A1024DB00103BDB087380CB +:101FD000E5E73B1D214608222846009300230834EC +:101FE000013701F06BFEDFE7201A18BF0120C3E7BD +:101FF00030B50A44084D91420DD011F8013B5840CC +:10200000082340F30004013B2C4013F0FF0384EA53 +:102010005000F6D1EFE730BD2083B8EDF7B5384A70 +:102020006B46106851686A4603C308233549364831 +:1020300005F0A6FF0446002833D10A25334A6B4633 +:10204000106851686A4603C3082331492E4805F0D9 +:1020500097FF0446002849D00369B3F5E01F45D82F +:10206000B0F8661040F2374291423FD1294A02440B +:1020700002F15C018B4239D35C3B234900209E1A5C +:10208000FFF7B6FF04F16401074632460020FFF770 +:10209000AFFFA3689F4229D1E368984208BF00259B +:1020A00024E00369B3F5E01F27D8418B40F23742A3 +:1020B000914220D1174A024402F110018B4218D3F9 +:1020C000103B114900209D1AFFF792FF04F11801FF +:1020D00006462A460020FFF78BFFA3689E4202D1E6 +:1020E000E368984201D00D25A8E70025284603B0F3 +:1020F000F0BD1025A2E70C25A0E70B259EE700BF49 +:1021000028800008DCFF1B00000004083180000864 +:1021100090FF1B000800FCF710B5037C044613B9C0 +:10212000006804F02DF9204610BD00000023BFF325 +:102130005B8FC360BFF35B8FBFF35B8F8360BFF3C5 +:102140005B8F7047BFF35B8F0068BFF35B8F704797 +:1021500070B505460C30FFF7F5FF044605F108069B +:102160003046FFF7EFFFA04206D96D683046FFF713 +:10217000E9FF2544281A70BD3046FFF7E3FF201A17 +:10218000F9E7000070B505464068A0B105F10C06FE +:1021900005F10800FFF7D6FF04463046FFF7D2FFEF +:1021A000844204F1FF34304694BF6D680025FFF788 +:1021B000C9FF2C44201A70BD38B50C460546FFF700 +:1021C000C7FFA04210D305F10800FFF7BBFF04448E +:1021D0006868BFF35B8FB4FBF0F100FB1144012092 +:1021E000AC60BFF35B8F38BD0020FCE72DE9F04108 +:1021F000144607460D46FFF7C5FF844228BF044634 +:10220000D4B1B84658F80C6B4046FFF79BFF3044FA +:10221000286040467E68FFF795FF331A9C4203D83A +:1022200001206C60BDE8F081A41B6B603B6820441A +:10223000AB60E8600220F5E72046F3E738B50C46CE +:102240000546FFF79FFFA04210D305F10C00FFF7F2 +:1022500079FF04446868BFF35B8FB4FBF0F100FBC7 +:1022600011440120EC60BFF35B8F38BD0020FCE718 +:102270002DE9FF418846694607466C46FFF7B6FFE1 +:10228000002506B204EBC606B4420AD0626808EB29 +:10229000050120680834FFF753FB54F8043C1D4443 +:1022A000F2E729463846FFF7C9FF284604B0BDE8E3 +:1022B000F0810000F8B505460C300F46FFF742FFED +:1022C00005F1080604463046FFF73CFFA0423046C1 +:1022D00088BF6C68FFF736FF201A386020B12C6881 +:1022E0003046FFF72FFF2044F8BD000073B51446B9 +:1022F00006460D46FFF72CFF8442019028BF044696 +:10230000DCB101A93046FFF7D5FF019B33B9326834 +:10231000C5E90233C5E9002401200CE09C42286095 +:1023200038BF0194019884426860F5D93368241A53 +:102330000220AB60EC6002B070BD2046FBE70000FD +:102340002DE9FF410F4669466C46FFF7CFFF00B20B +:10235000002604EBC005AC4209D0D4F80480B819BB +:1023600054F8081B42464644FFF7EAFAF3E73046C2 +:1023700004B0BDE8F081000038B50546FFF7E0FF86 +:10238000044601462846FFF717FF204638BD0000E7 +:1023900008B103F0F5BF70477047000010B4134652 +:1023A000026814680022A4465DF8044B60470000F0 +:1023B00000F5805090F861047047000000F58050EF +:1023C00090F85A047047000000F5805090F96004BE +:1023D000704700004E207047302383F3118800F5CA +:1023E0008052D2F8A434D2F8A0041844D2F89C3415 +:1023F0001844D2F884341844D2F894341844D2F8EB +:1024000090341844002383F31188704700F58050FE +:10241000C0F85C14012070472DE9FF47054600F520 +:1024200080500C46BDF830A090F85A1499B1D0F8FD +:1024300080140131C0F8801421688E0006D4217BFD +:1024400008290BD9667B0EB10F2907D9D0F884343F +:102450000133C0F884344FF0FF30A5E0302181F320 +:102460001188696BD1F8C46016F4001813D0D0F845 +:1024700088140131C0F88814D0F88C14002940F079 +:10248000968021462846CDF800A000F0E1FF002309 +:1024900083F3118888E026684FF04809D1F8C470AA +:1024A000002EE96AC7F30447B4BF46F08046B6047D +:1024B00019FB0719C9F80060216849004FEA076154 +:1024C00044BF46F00056C9F80060267B41EA064149 +:1024D0007E01C9F8041094F80DC0BCF1000F27D09C +:1024E00041F44011C9F80410D0F8B8140131C0F813 +:1024F000B814A91901F58351087D40F02000087532 +:10250000207BCDE9022300F0F5FF0330DDE9022353 +:1025100080105FFA88F108F1010881420FDA04EBBC +:10252000810C09EB8101DCF804C0C1F808C0F0E7B8 +:10253000A91901F58351087D6CF34510DFE70120EF +:10254000696B04F10C0CB840C1F8D000A919204601 +:1025500001F58251C1E90623A7F17D01C9B205EB5E +:10256000411150F804EB604541F804EBF9D10088C3 +:102570002E44088041F27001775006F580560AF02B +:10258000030196F8740041F0100120F01F00014390 +:1025900086F87410002181F3118821462846CDF871 +:1025A00000A000F055FF012004B0BDE8F087002036 +:1025B0006DE700002DE9F04700F58056044696F8D7 +:1025C0005A54002D40F00381037E032B40F0948089 +:1025D00028462B462F465FFA80FC944510DA01EB23 +:1025E000CC0E51F83CC0BCF1000F04DBDEF804C097 +:1025F000BCF1000F02DB01370130ECE70133FBE7F0 +:10260000302080F31188606BF3B9D0F8803043F04C +:102610000203C0F880304E23606B002F6FD1D0F8DA +:10262000803043F00103C0F880306A4B6A4A1B686F +:1026300003F1805303F52C539B009342236340F234 +:10264000B080664800F0B6FE4D2B42D8DFF884819A +:102650004FEA034EDFF88891D8F800C04EEA8C0E9E +:10266000C0F884E00CF1805000F52C508000E0614F +:1026700003EB0C00D4F834C0C3F14E03C8F80000DB +:10268000DCF8800040F03000CCF880004FF0000C07 +:10269000D4F81C80E6465FFA8CF08242BCDD01EB88 +:1026A000C00A51F83000002810DBDAF804A0BAF1B3 +:1026B000000F0BDA09EA00400AF07F0A40EA0A003C +:1026C00040F0084048F82E000EF1010E0CF1010C0C +:1026D000E1E7836923F00103836100F071FE0646A0 +:1026E000636B9B69D90704D500F06AFE831BFA2B44 +:1026F000F6D9002383F311882846BDE8F087B7EBAD +:10270000530F3DD2DFF8CCE04FEA074CDEF8003043 +:102710004CEA830CC0F888C003F1805003EB4703F8 +:10272000002700F52C50CEF80030BC468000206217 +:10273000606BD0F8803043F00C03C0F88030D4F8E0 +:1027400020E0FBB29A427FF770AF51F8330001EB03 +:10275000C3080028D8F8043001DB002B0EDB20F082 +:10276000604023F0604340F0005043F000434EF8D7 +:102770003C000EEBCC000CF1010C43600137E0E7AC +:10278000836923F00103836100F01AFE0646636B40 +:102790009B69DA07ADD500F013FE831BFA2BF6D93F +:1027A000A7E7626B936923F00103936100F008FED1 +:1027B0000746636B9B69DB0705D500F001FEC31B71 +:1027C000FA2BF6D995E7012586F85A5491E70025AA +:1027D00092E700BF304F0020FCB500403C8000086D +:1027E0000000FF0713B500F580540191E06CFFF77E +:1027F000C9FC1F280AD920220199E06CFFF738FD97 +:10280000A0F120035842584102B010BD0020FBE760 +:1028100008B5302383F3118800F58050C06CFFF7B2 +:1028200085FC002383F3118808BD000000220260AC +:1028300082814260826070470022002310B5C0E9A7 +:102840000023002304460C3020F8043CFFF7EEFF81 +:10285000204610BD2DE9F0479A4688B007468846C5 +:102860009146302383F3118807F580546846FFF7BB +:10287000E3FFE06CFFF76CFC1F282ED9202269468D +:10288000E06CFFF779FD202827D194F85A3423B360 +:1028900003AD444605AB2E46083403CE9E4244F8B1 +:1028A000080C44F8041C3546F5D130682060B38824 +:1028B000A380DDE90023C9E90023BDF80830AAF8A8 +:1028C0000030002383F3118853464A464146384678 +:1028D00008B0BDE8F04700F081BD002080F311880A +:1028E00008B0BDE8F08700002DE9F84F064688469D +:1028F0001022002104303546FFF748F806F58157CD +:10290000264B183745F8383B2C4620462034FFF735 +:1029100093FFA742F9D106F580544FF4805306F592 +:10292000A3594FF0000AA5630025E76406F5835715 +:1029300009F118094FF0000B18376564C4E90F3529 +:10294000012384F8483084F85030A7F1180020376C +:1029500047E910ABFFF76AFF47F8285C4F45F4D111 +:1029600084F86084A4F86254A4F86454A4F866540B +:1029700084F86854A4F86A54A4F86C54A4F86E540B +:1029800084F87054B8F1000F02D0054800F012FD31 +:10299000044B30467363BDE8F88F00BF7C800008AD +:1029A0006080000800A00040044B10B51978044670 +:1029B0004A1C1A70FFF798FF204610BD2D4F0020CB +:1029C0002DE9F04300295AD02E4E2F48B6FBF1F4E2 +:1029D00081428CBF0A201120431EB4FBF0F700FB9C +:1029E0001740DDB220B1022B1846F5D8002032E0A6 +:1029F0007B1EB3F5806F2ED2C5EBC5084FF47A73FA +:102A000008F103044FEAE40EC4F3C7040EF1010910 +:102A1000281B0EFB033E5FFA80FC59FA80F0BEFBD8 +:102A2000F0F0B0F5617F18DC83B2601C5CFA80F0D6 +:102A30007843B6FBF0F08142D8D1611E0F29D5D87A +:102A40000CF1FF310729D1D8012013805780107174 +:102A5000547182F806C0BDE8F08308F1FF34E0103D +:102A6000C4F3C70400F1010E2D1B00FB03335FFA12 +:102A700085FC5EFA85F5B3FBF5F39BB2D5E7084616 +:102A8000E9E700BF00B4C4043F420F0030B50D4B6E +:102A900005200D4D1C786C438C420ED159780120D5 +:102AA000518099785171D9789171197911715B7947 +:102AB00003EB83035B00138030BD013803F1060391 +:102AC000E8D1F9E7C080000840420F0038B540F275 +:102AD0007772436B154CC3F8BC200722436BC3F8D5 +:102AE000C8202268416B930043F4C023C1F8A03092 +:102AF00002F1805302F16C01456B03F52C53EA326D +:102B000089009B00226041F0E061094A4362C5F8F8 +:102B1000C01003F5D87103F56A73C1629342036371 +:102B200002D9044800F046FC38BD00BF304F0020F9 +:102B3000FCB500403C8000082DE9F04F00F58055C1 +:102B40001F4689B0044695F8603489469046012BAB +:102B500004D90026304609B0BDE8F08FA04A52F8EB +:102B6000231009B942F823009E48C4F81490017854 +:102B70002776C9B9302383F311889B4BD3F8EC2017 +:102B800042F48072C3F8EC20D3F8942042F48072AF +:102B9000C3F89420D3F8942022F48072C3F89420D0 +:102BA0000123037081F3118895F859647EB93023AD +:102BB00083F311880321132001F0CAFF032115209C +:102BC00001F0C6FF012385F8593486F311883023BC +:102BD00083F31188626B936923F01003936100F013 +:102BE000EFFB8246636B9E6916F0080609D000F081 +:102BF000E7FBA0EB0A03FA2BF4D9002686F3118831 +:102C0000A8E79A6942F001029A6100F0D9FB824676 +:102C1000636B9A69D00706D400F0D2FBA0EB0A03DD +:102C2000FA2BF5D9E9E79A694FF0000A42F002025F +:102C30009A61636BC3F854A08AF3118804F5825B30 +:102C4000E86CFFF773FA0BF1180B2022002168469D +:102C5000FEF79CFE02A8FFF7E9FD6A460BEB0603B0 +:102C60000DF1180ECDF818A094460833BCE8030007 +:102C7000F44543F8080C43F8041C6246F4D1DCF830 +:102C8000000020361860B6F5806F9CF804201A7199 +:102C9000DBD1002304F5A35249462046023285F8D1 +:102CA000583485F85B34FFF78BFE064690B9626BAB +:102CB000936923F00103936100F082FB0546636B87 +:102CC0009B69D9077FF545AF00F07AFB431BFA2BD0 +:102CD000F5D93EE795F86634C5F87494591E95F811 +:102CE0006734626B013B1B0243EA416395F8681449 +:102CF00001390B43B5F86414013943EA0143D36148 +:102D0000B8F1000F36D004F5A352414620460A32EE +:102D1000FFF7BCFE90B9626B936923F001039361E6 +:102D200000F04EFB0546636B9B69DA077FF511AF38 +:102D300000F046FB431BFA2BF5D90AE795F86F2400 +:102D4000C5F87884511E95F87024636B013A12011E +:102D500042EA012295F86E1401390A43B5F86C1461 +:102D6000013942EA014242F40002DA604FF4206283 +:102D7000636B9A64636B4FF000082046C3F8BC8015 +:102D8000FFF7A4FE85F861846FF04042636B1A651B +:102D9000164A636B5A654FF00222636B9A654FF0D7 +:102DA000FF32636BC3F8E0200322636B9742DA655E +:102DB0003FF4D0AE626B936923F00103936100F09E +:102DC000FFFA0746636B9B69DB0705D500F0F8FA4D +:102DD000C31BFA2BF6D9BCE6012385F85A34B9E6B1 +:102DE000284F00202C4F00200044025855020002BA +:102DF0002DE9F04F00F5A5578BB004469046994653 +:102E00004FF0000B41F2700A1037636BD3F8D830E3 +:102E100023FA0BF3DD0752D504EB4B114FEA4B12AB +:102E200051440B7918074AD404F58056D6F88C34EF +:102E30000133C6F88C3447E902890B79990604EB13 +:102E4000020148BFD6F8BC34514444BF0133C6F830 +:102E5000BC340B7943F008030B71DB0724D596F8DB +:102E60005B340BB302A8019204F58355FFF7E4FC31 +:102E7000019A05AB154405F1080C2868083555F88A +:102E8000041C1A46654503C21346F6D1286802A9F8 +:102E900010602046AA889A800123ADF8103023687C +:102EA000CDE902891B6C9847D6F8B034D6F85C049B +:102EB0000133C6F8B03410B103681B6998470BF1B1 +:102EC000010BBBF1200FA0D10BB0BDE8F08F0000CB +:102ED0002DE9F04F0F468DB0044600F073FA82469C +:102EE0008946002F5BD1636BD3F8A02012F4FE0F4C +:102EF00003D100200DB0BDE8F08FD3F8A4209201DB +:102F000041BF04F58051D1F8A0240132C1F8A024BA +:102F1000D3F8A4205606ECD0D3F8A450666AC5F3C3 +:102F200005254823E8464FF0000B03FB05664046A5 +:102F3000FFF77CFC326851004ABF22F06043C2F3C5 +:102F40008A4343F00043920048BF43F0804300931C +:102F5000736813F400131BBF012304F580528DF82E +:102F60000D308DF80D301EBFD2F8C0340133C2F8D9 +:102F7000C034F38803F00F038DF80C309DF80C007B +:102F800000F0B8FA5FFA8BF3984225D9F2180CA931 +:102F90000BF1010B127A0B4403F82C2CEEE7012FF6 +:102FA000A7D1636BD3F8B02012F4FE0FA1D0D3F8F1 +:102FB000B420950141BF04F58051D1F8A02401321D +:102FC000C1F8A024D3F8B420500692D0D3F8B4505E +:102FD000A66AC5F30525A4E7EFB9636BC3F8A8504B +:102FE00004A807ADFFF728FC98E80F0007C52B8061 +:102FF0000023204604A9ADF81830236804F5805456 +:103000001B6CCDE904A9984758B1D4F89834013322 +:10301000C4F898346EE7012FE2D1636BC3F8B8505F +:10302000DEE7D4F89C3401200133C4F89C3461E716 +:103030002DE9F04105460F4600F58054012639463A +:103040002846FFF745FF10B184F85B64F7E7D4F832 +:10305000B034D4F85C040133C4F8B03420B1036850 +:10306000BDE8F0411B691847BDE8F081436BF0B53E +:103070001A6C12F47F0F2BD01B6C00F5805441F2B8 +:1030800070054FF0010CC4F8B4340023471900EB6D +:1030900043125E012A44117911F0020F15D049073D +:1030A00013D4B959466B0CFA01F1D6F8CCE011EA09 +:1030B0000E0F0AD0C6F8D410117941F00401117135 +:1030C000D4F894240132C4F894240133202BDED1A7 +:1030D000F0BD000010B5264C264B22680AB340B361 +:1030E0001A6D92050FD54FF400721A6500F06AF957 +:1030F00050EA01020B4602D0013861F1000302469A +:103100002068FFF775FE1B4A136D9B012AD52368C3 +:103110004FF0007103F580531165012283F861249B +:1031200020E001221A6510221A654FF480521A65B8 +:1031300010BD196DC80702D4196D490705D50521C1 +:10314000104619650021FFF773FF0A4B1A6DD00670 +:1031500002D41A6D510605D5502201211A65206846 +:10316000FFF766FF2068BDE81040FFF77FBF00BF94 +:10317000284F002000A0004008B5302383F31188B9 +:10318000FFF774FF002383F3118808BD436BD3F866 +:10319000C00010F07C5005D0D3F8C40080F40010BB +:1031A000C0F340507047000008B5302383F3118806 +:1031B00000F58050C06CFEF7CBFF002383F311882D +:1031C00043090CBF0120002008BD000000F580531A +:1031D00093F8612462B1416B8A6922F001028A612D +:1031E000D3F8A4240132C3F8A424002283F8612474 +:1031F000704700002DE9F743302181F3118800F575 +:103200008251002541F2700E4FF00108183100F58F +:10321000805C00EB45147444267977071CD4F606CD +:103220001AD58E69D0F8349008FA06F6D9F8CC7021 +:103230003E4211D04F6801970F689742019F9F410E +:103240000AD2C9F8D460267946F004062671DCF863 +:1032500090440134CCF8904401352031202DD8D150 +:10326000002383F3118803B0BDE8F083F8B51E4650 +:1032700000230F46054613701446FFF795FF80F0B4 +:10328000010038701EB12846FFF780FF2070F8BD9E +:103290002DE9F04F85B099460D468046164691F8C7 +:1032A00000B0DDE90EA302931378019300F08AF8D1 +:1032B0002B7804460F4613B93378002B41D02246B1 +:1032C0003B464046FFF796FFFFF756FFFFF77EFFAE +:1032D0004B4632462946FFF7C9FF2B7833B1BBF185 +:1032E000000F03D0012005B0BDE8F08F337813B193 +:1032F000019B002BF6D108F5805303935445029BA4 +:1033000077EB03031DD2039BD3F85C04C8B10368B9 +:10331000AAEB04011B6898474B46324629464046B3 +:10332000FFF7A4FF2B7813B1BBF1000FDAD133788C +:1033300013B1019B002BD5D100F044F804460F4691 +:10334000DCE70020CFE7000008B50020FFF7C2FE51 +:10335000BDE8084001F0A6B808B50120FFF7BAFEA5 +:10336000BDE8084001F09EB800B59BB0EFF30981BD +:1033700068226846FEF7E4FAEFF30583014B9B6B86 +:10338000FEE700BF00ED00E008B5FFF7EDFF00002D +:1033900000B59BB0EFF3098168226846FEF7D0FACA +:1033A000EFF30583014B5B6BFEE700BF00ED00E030 +:1033B000FEE700000FB408B5029802F0BDFAFEE780 +:1033C00003F00CB802F0EEBF0139C9B201299EBF6B +:1033D00000EBC1000023C0E901337047F8B51B883A +:1033E00005460E465B0715D4044600F11007BC42A3 +:1033F00010D0636853B12B682846DB6B9847A368ED +:10340000C1B23246606898470834F0E7A368002BE1 +:10341000F1D1F9E70120F8BD37B56D4685E8060022 +:1034200042680AB9846824B1C26872B9026962B993 +:10343000012400EBC4000134021D95E8030082E87A +:10344000030001201C7003B030BD0020FBE700002A +:103450002DE9F04F89B004460E460546BDF8487088 +:1034600000F110084FF000094FF0000A07F00407C0 +:103470004FF0000BA84539D06B680BB9AB684BB166 +:1034800057B923682046DB6B9847AB68C1B2324618 +:10349000686898470835EDE7B9F1000FFAD133466F +:1034A00003AA06F1080EADF80890CDE900AB186844 +:1034B000083353F8041C94467345ACE80300624695 +:1034C000F5D118684FF00109CCF800009B88ACF8E2 +:1034D0000430FFF777FF0423ADF808302368CDE907 +:1034E00000011B6C694620469847D3E7012009B0CC +:1034F000BDE8F08F082817D909280CD00A280CD06D +:103500000B280CD00C280CD00D280CD00E2814BF82 +:103510004020302070470C20704710207047142046 +:103520007047182070472020704700002DE9F041B7 +:10353000456A15B94162BDE8F0814B68AC4623F09D +:103540006047C3F38A464FEAD37EC3F3807816EA16 +:10355000230638BF3E462B465A68BEEBD27F22F088 +:1035600060440AD0002A18DAA40CB44217D19D4254 +:103570000FD10D60DEE71346EEE7A74207D102F058 +:103580008044C2F3807242450BD054B1EFE708D2B9 +:10359000EDE7CCF800100B60CDE7B44201D0B442A7 +:1035A000E5D81A689C46002AE5D11960C3E70000F7 +:1035B0002DE9F047089D01F0070400EBD1004FF41E +:1035C0007F494FEAD508224405F00705944201D10E +:1035D000BDE8F08704F0070705F0070A111B08EBA8 +:1035E000D50E57453E4613F80EC038BF5646C6F1B5 +:1035F00008068E4228BF0E46E108415C344435443B +:10360000B94029FA06F721FA0AF1FFB28CEA010162 +:1036100047FA0AF739408CEA010C03F80EC0D5E7E7 +:1036200080EA0120082341F2210201B2013B40005F +:10363000002980B2B8BF504013F0FF03F5D17047A6 +:1036400038B50C468D18A54200D138BD14F8011BC1 +:10365000FFF7E6FFF7E7000042684AB11368818987 +:103660004360438901339BB29942438138BF8381D0 +:103670001046704770B588B0044620220D46684653 +:103680000021FEF783F920460495FFF7E5FF024687 +:1036900060B16B46054608AE1C46083503CCB44203 +:1036A00045F8080C45F8041C2346F5D1104608B02F +:1036B00070BD0000082817D909280CD00A280CD0A2 +:1036C0000B280CD00C280CD00D280CD00E2814BFC1 +:1036D0004020302070470C20704710207047142085 +:1036E000704718207047202070470000082817D91D +:1036F0000C280CD910280CD914280CD918280CD94E +:1037000020280CD930288CBF0F200E2070470920AC +:1037100070470A2070470B2070470C2070470D201F +:10372000704700002DE9F843078C0446072F1ED987 +:1037300000254FF6FF73D0E90298C5F12006A5F1E8 +:10374000200029FA05F1083508FA06F628FA00F0F3 +:10375000314301431846C9B2FFF762FF402D0346CB +:10376000EBD13A46E169BDE8F843FFF769BF4FF690 +:10377000FF70BDE8F883000010B54B6823B9CA8A12 +:1037800063F30902CA8210BD04691A681C600361F0 +:10379000C38A013BC3824A60EFE700002DE9F84F7E +:1037A0001D46CB8A0F468146C3F30901924605297F +:1037B0000B4630D00020AAB207F11A049EB21FFABD +:1037C00080F8042E0FD8904503F1010306D30A4474 +:1037D000FB8A62F309030120FB821AE01AF80060F9 +:1037E0000130E654EAE79045F1D2A1F1050B1C2324 +:1037F0007C68BBFBF3F203FB12BB1FFA8BF6002CB9 +:1038000045D14846FFF728FF044638B978606FF085 +:103810000200BDE8F88F4FF00008E6E700260660DA +:103820007860ADB24FF0000B454510D90AEB0803A4 +:10383000221D13F8011B08F101089155B1B21FFABE +:1038400088F81B292BD0454506F10106F1D8FB8AE3 +:10385000C3F30902154465F30903BCE701321C46B2 +:1038600092B22368002BF9D16B1F0B441C21B3FBD0 +:10387000F1F301339BB29A42D3D2BBF1000FD0D106 +:103880004846FFF7E9FE20B9C4F800B0BFE70122BF +:10389000E7E7C0F800B05E4620600446C1E7454552 +:1038A000D5D94846FFF7D8FE08B92060AFE7C0F881 +:1038B00000B0002620600446B6E700002DE9F04F76 +:1038C0001C46074688462DED028B83B05B6901924A +:1038D000002B00F0A780238C2BB1E269002A00F0B6 +:1038E000A180072B35D807F10C00FFF7B5FE054680 +:1038F00038B96FF00205284603B0BDEC028BBDE875 +:10390000F08F14220021FEF741F8228CE16905F1C5 +:103910000800FEF715F8208C48F00041013080B215 +:10392000FFF7E4FEFFF7C6FE013880B220840130C5 +:10393000287438466369228C1B782A4403F01F03DD +:1039400063F03F03137269602946FFF7EFFD01251D +:10395000D1E702330722C18A9BB20633B3FBF2F3ED +:10396000828A9BB2521A92B29342C2D84FF0000997 +:1039700000F10C034FF0800A4E464D4608EE103A17 +:1039800018EE100AFFF768FE83460028B1D0142213 +:103990000021FDF7FBFF002E3AD1019B0222ABF87C +:1039A00008300BF1080E1FFA82FC218C0CF101008B +:1039B000BCF1060F80B201D88E422BD3FFF796FEE2 +:1039C0008E4208BF4FF0400AFFF774FE626901386B +:1039D000013512781BFA80F1013002F01F022DB27E +:1039E00042EA491289F001094AEA020A48F0004213 +:1039F00081F808A059468BF810003846CBF804200F +:103A00004FF0000AFFF792FD238CB342B8D172E762 +:103A10000022C6E7E169895D01360EF80210B6B2F0 +:103A20000132C0E76FF0010565E70000F8B5154603 +:103A30000E463022002104461F46FDF7A7FF069BD5 +:103A4000B5F5001FA760636004F11000079B34BF49 +:103A50006A094FF6FF72E661A362002397B29A42A9 +:103A600006D800230360A782E3822383E360F8BDC6 +:103A70000660013330462036F1E7000003781BB9B9 +:103A80004BB2002BC8BF0170704700000078704730 +:103A9000F8B50C46C969074611B9238C002B37D1FC +:103AA000257E1F2D34D8387828BB228C072A2CD8A5 +:103AB000268A36F003032BD14FF6FF70FFF7C0FDC7 +:103AC00020F0010031024FF6FF72400441EA056127 +:103AD000400C41EA4025234629463846FFF7EEFED2 +:103AE000002807DD626913780133DBB21F2B88BF22 +:103AF00000231370F8BD218A2D0645EA01250543F0 +:103B00002046FFF70FFE0246E5E76FF00300F1E7FE +:103B10006FF00100EEE7000070B58AB0044616466B +:103B20000021282268461D46FDF730FFBDF83830D9 +:103B300069462046ADF810300F9B05939DF8403044 +:103B40008DF81830119B0793BDF84830CDE9026518 +:103B5000ADF82030FFF79CFF0AB070BD2DE9F041B1 +:103B6000D36905460C4616460BB9138C5BBB377EF2 +:103B70001F2F28D895F80080B8F1000F26D03046C6 +:103B8000FFF7D0FD337821020246284641EAC331CF +:103B9000338A41EA080141EA076141EA03413346B9 +:103BA00041F08001FFF78AFE00280ADD3378012BFF +:103BB00007D1726913780133DBB21F2B88BF002352 +:103BC0001370BDE8F0816FF00100FAE76FF00300B9 +:103BD000F7E70000F0B58BB004460D46174600210C +:103BE000282268461E46FDF7D1FE9DF84C30294636 +:103BF00020465A1E534253416A468DF800309DF8C4 +:103C00004030ADF81030119B05939DF848308DF889 +:103C10001830149B0793BDF85430CDE90276ADF807 +:103C20002030FFF79BFF0BB0F0BD0000406A00B1F1 +:103C300004307047436A1A68426202691A6003617D +:103C4000C38A013BC38270472DE9F041D0F8208040 +:103C500014461D46184E4146002709B9BDE8F081BB +:103C6000D1E90223A21A65EB0303964277EB030323 +:103C70001ED2036A8B420DD1FFF77EFD036A1B68DB +:103C8000036203690B60C38A0161013B016AC3825D +:103C90008846E2E7FFF770FD0B68C8F8003003695B +:103CA0000B60C38A0161013BC382D8F80010D4E7DE +:103CB00088460968D1E700BF80841E002DE9F04FD7 +:103CC0008BB00D4614469B46DDF850908046002888 +:103CD00000F01881B9F1000F00F01481531E3F2B42 +:103CE00000F21081012A03D1BBF1000F40F00A81DC +:103CF0000023CDE90833B8F81430B5EBC30F4FEA11 +:103D0000C30703D300200BB0BDE8F08F2B199F42EF +:103D1000D8F80C3036BF7F1B2746FFB21BB9D8F846 +:103D20001030002B7AD0272D4DD8C5F1280600235E +:103D30002946B742009308ABD8F808002CBFF6B26A +:103D40003E46A7EB060A354432465FFA8AFAFFF789 +:103D50002FFCB8F81430282103F10053053BDB0099 +:103D60000493D8F80C300393039B13B1BAF1000FFE +:103D70002CD1D8F8100040B1BAF1000F05D008AB33 +:103D80005246691A0096FFF713FC38B2002FB9D0DB +:103D900066070AD00AAB624203EBD40102F00702C5 +:103DA00011F8083C134101F8083C082C3DD9102CAF +:103DB00040F2B580202C40F2B780BBF1000F00F03C +:103DC0009C80082335E0BA460026C2E7049BE02B1E +:103DD00028BFE02306930B44AB42059315D95A1B29 +:103DE0000398691A0096924508AB00F1040034BFAD +:103DF0005246D2B20792FFF7DBFB079A1644AAEBB2 +:103E0000020A1544F6B25FFA8AFA049B069A0599EB +:103E10009B1A0493039B1B680393A5E700933A4600 +:103E200008AB2946D8F80800ADE7BBF1000F13D066 +:103E30000123B4EBC30F6BD0082C12D89DF82030AF +:103E4000621E23FA02F2D50706D54FF0FF3202FABE +:103E500004F423438DF820309DF8203089F8003099 +:103E600051E7102C12D8BDF82030621E23FA02F25E +:103E7000D10706D54FF0FF3202FA04F42343ADF820 +:103E80002030BDF82030A9F800303CE7202C0FD8B6 +:103E90000899631E21FA03F3DA0705D54FF0FF32C4 +:103EA00002FA04F40C430894089BC9F800302AE78E +:103EB000402C2AD0611EC4F12102A4F12103DDE9C6 +:103EC000086526FA01F105FA02F225FA03F3114317 +:103ED0001943CB0711D50122A4F12003C4F120011D +:103EE00002FA03F322FA01F1A2400B43524263EBC0 +:103EF000430332432B43CDE90823DDE90823C9E915 +:103F0000002300E76FF00100FDE66FF00800FAE61D +:103F1000082CA1D9102CB4D9202CEED8C4E7BBF1C1 +:103F2000000FAED0022384E7BBF1000FBCD0042306 +:103F30007FE70000012A30B5144638BF012485B060 +:103F40000025402C28BF4024012ACDE9025518D86D +:103F50001B788DF8083063070AD004AB624203EB8C +:103F6000D40502F0070215F8083C934005F8083C18 +:103F7000034600912246002102A8FFF719FB05B075 +:103F800030BD082AE4D9102A03D81B88ADF80830C0 +:103F9000E1E7202A95BF1B68D3E900230293CDE90E +:103FA0000223D8E710B5CB681BB98B600B618B82FD +:103FB00010BD04691A681C600361C38A013BC38297 +:103FC000CA60F0E703064CBFC0F3C0300220704760 +:103FD00008B50246FFF7F6FF022806D15306C2F3E2 +:103FE0000F2001D100F0030008BDC2F30740FBE73A +:103FF0002DE9F04F93B004460D46CDE903230A683E +:104000001046FFF7DFFF0228824614BFC2F30626E0 +:104010000026002A80F2F88112F0C04940F0F481B5 +:10402000097B002900F0F081022803D02378B342F5 +:1040300040F0ED81C2F3046310462944069302F078 +:104040007F030593FFF7C4FF059B002283464FEAD9 +:104050008348002348EA0A4848EA4668CE78CDE912 +:104060000823F30948EA0008029368D0059B02463A +:1040700008A92046009353466768B847002800F017 +:10408000C981276A4FB9414604F10C00FFF7F2FAE3 +:10409000074690B96FF0020055E03B6998450DD096 +:1040A0003F68002FF9D1414604F10C00FFF7E2FA16 +:1040B00007460028EED0236A3B60276297F817C0B6 +:1040C00006F01F08CCF3840CACEB0800A8EB0C0343 +:1040D0001FFA80FE0028B8BF0EF120001FFA83FEF1 +:1040E000B8BF00B2002B0793B8BF0EF12003D7E989 +:1040F0000221BCBF1BB2079352EA010338D0039BD5 +:104100004FF0000CDFF81CE39A1A049B63EB0101EB +:1041100096457CEB01032BD36B7B97F81AE0734534 +:1041200019D1029B002B78D0012821DC7868F8B9DE +:10413000DFF8ECC2944570EB010316D337E0276A31 +:1041400027B96FF00C0013B0BDE8F08F3B699845BC +:10415000B4D03F68F4E7B24890427CEB010301D34E +:104160000020F0E7029B002BFAD0079B0F2B17DCF7 +:10417000FA7DB3003946204602F0030203F07C03C7 +:104180001343FB75FFF7F8FA6B7BBB76029B3BB9D9 +:10419000FB7DC3F38402013262F38603FB75D0E733 +:1041A0006A7BBB7E9A42DBD1029B002B35D0B309E0 +:1041B000022B32D0039B142200210DA8BB60049B6C +:1041C000FB60FDF7E3FB039B0AA920460A93049BCF +:1041D000ADF83EB00B932B1D8DF840A00C932B7BBC +:1041E0008DF84180013BDBB2ADF83C30069B8DF889 +:1041F0004230059B8DF8433094F82C3083F0010356 +:104200008DF84430A3689847FB7DC3F384030133E2 +:1042100003F01F039B02FB82A2E7FB7DC6F3401263 +:10422000B2EBD31F40F0F980C3F38403434540F061 +:10423000FB80029AB6092B7B002A52D016F00106A9 +:1042400061D1032B40F2F380039B394604F10C004B +:10425000BB60049BFB60FB8A66F30903AE1DFB8217 +:1042600032462B7B033BDBB2FFF798FA00280CDACF +:1042700039462046FFF780FAFB7DC3F38403013300 +:1042800003F01F039B02FB8204E7AB88DDE908848F +:104290003B834FF6FF73C9F12000A9F1200228FAF1 +:1042A00009F109F1080904FA00F024FA02F20143C5 +:1042B00018461143C9B2FFF7B3F9B9F1400F0346ED +:1042C000E9D1B88231462A7B033AD2B2FFF7B8F976 +:1042D000FB7DB882DA43C2F3C01262F3C713FB75E9 +:1042E0003EE786B92E1D013B394604F10C00DBB2D6 +:1042F0003246FFF753FA0028BADB2A7B3146B88AE8 +:10430000013AD2B2E2E7F98A013BC1F30901DAB21C +:1043100004295BD8281D002307F11B069A4208D9FF +:1043200010F801CB013306F801C00131DBB20529D9 +:10433000F4D1039993420A9138BF043304992CBFF6 +:10434000002355FA83F30B9107F11B010C91796857 +:104350000E930D91291DFB8AADF83EB0C3F30903FE +:104360008DF840A08DF841801A44069B8DF84230AC +:10437000059BADF83C208DF8433094F82C3083F049 +:1043800001038DF844300023B88A7B602A7B013A10 +:10439000FFF756F93B8BB882834203D1A3680AA981 +:1043A0002046984720460AA9FFF7FCFDFB7DBA8A04 +:1043B000C3F38403013303F01F039B02FB823B8B97 +:1043C0009A420CBF00206FF01000BCE67B68002B07 +:1043D000AFD0052001E01C3033461E68002EFAD114 +:1043E000091A2E1D081D184401EB090C5FFA89F308 +:1043F000BCF11B0F9DD89A429BD916F8013B09F1DD +:10440000010900F8013BEFE76FF009009BE66FF050 +:104410000A0098E66FF00B0095E66FF00D0092E64B +:1044200040420F0080841E006FF00E008BE66FF09C +:104430000F0088E6EFF30983054968334A6B22F0E1 +:1044400001024A6383F30988002383F311887047CC +:1044500000EF00E0302080F3118862B60D4B0E4A69 +:10446000D96821F4E0610904090C0A430B49DA60B8 +:10447000D3F8FC2042F08072C3F8FC20084AC2F84E +:10448000B01F116841F0010111602022DA7783F832 +:104490002200704700ED00E00003FA0555CEACC5E0 +:1044A000001000E0302310B583F311880E4B5B68D9 +:1044B00013F4006314D0F1EE103AEFF309844FF0D7 +:1044C0008073683CE361094BDB6B236684F30988E6 +:1044D00001F0F8F910B1064BA36110BD054BFBE7E5 +:1044E00083F31188F9E700BF00ED00E000EF00E082 +:1044F0003F0400084204000808B5074B074A196842 +:1045000001F03D01996053680BB190689847BDE890 +:104510000840FFF7C7BF00BF00000240384F00202F +:1045200008B5084B1968890901F03D018A019A60B4 +:10453000054AD3680BB110699847BDE80840FFF7FA +:10454000B1BF00BF00000240384F002008B5084B43 +:104550001968090C01F03D010A049A60054A536983 +:104560000BB190699847BDE80840FFF79BBF00BFBB +:1045700000000240384F002008B5084B1968890D2B +:1045800001F03D018A059A60054AD3690BB1106AB2 +:104590009847BDE80840FFF785BF00BF0000024014 +:1045A000384F002008B5074B074A596801F03D0114 +:1045B000D960536A0BB1906A9847BDE80840FFF78D +:1045C00071BF00BF00000240384F002008B5084B03 +:1045D0005968890901F03D018A01DA60054AD36A08 +:1045E0000BB1106B9847BDE80840FFF75BBF00BFF9 +:1045F00000000240384F002008B5084B5968090CEC +:1046000001F03D010A04DA60054A536B0BB1906B6F +:104610009847BDE80840FFF745BF00BF00000240D3 +:10462000384F002008B5084B5968890D01F03D014D +:104630008A05DA60054AD36B0BB1106C9847BDE868 +:104640000840FFF72FBF00BF00000240384F002096 +:1046500008B5074B074A196801F03D019960536C92 +:104660000BB1906C9847BDE80840FFF71BBF00BF37 +:1046700000040240384F002008B5084B196889092A +:1046800001F03D018A019A60054AD36C0BB1106DAF +:104690009847BDE80840FFF705BF00BF000402408F +:1046A000384F002008B5084B1968090C01F03D018E +:1046B0000A049A60054A536D0BB1906D9847BDE8A6 +:1046C0000840FFF7EFBE00BF00040240384F002053 +:1046D00008B5084B1968890D01F03D018A059A60FB +:1046E000054AD36D0BB1106E9847BDE80840FFF73F +:1046F000D9BE00BF00040240384F002008B5074B68 +:10470000074A596801F03D01D960536E0BB1906EB4 +:104710009847BDE80840FFF7C5BE00BF000402404F +:10472000384F002008B5084B5968890901F03D0150 +:104730008A01DA60054AD36E0BB1106F9847BDE865 +:104740000840FFF7AFBE00BF00040240384F002012 +:1047500008B5084B5968090C01F03D010A04DA60FC +:10476000054A536F0BB1906F9847BDE80840FFF7BB +:1047700099BE00BF00040240384F002008B5084B26 +:104780005968890D01F03D018A05DA60054AD36F49 +:1047900013B1D2F880009847BDE80840FFF782BE09 +:1047A00000040240384F002000230C4910B51A467F +:1047B0000B4C0B6054F82300026001EB4300043300 +:1047C0004260402BF6D1074A4FF0FF339360D3602D +:1047D000C2F80834C2F80C3410BD00BF384F0020B6 +:1047E000E0800008000002400F28F8B510D910281A +:1047F00010D0112811D0122808D10F240720DFF87B +:10480000B4E00126DEF80050A04208D9002649E0B5 +:104810000446F4E70F240020F1E70724FBE706FA3B +:1048200000F73D4240D1214C4FEA001C3D4304EBD0 +:1048300000160EEBC000CEF80050C0E90123FBB219 +:104840004BB11B48836B43F001038363036E43F05A +:1048500001030366036E17F47F4F09D01448836B7E +:1048600043F002038363036E43F002030366036EA7 +:1048700054F80C00036823F01F030360056815F06B +:104880000105FBD104EB0C033D2493F80CC05F68D9 +:1048900004FA0CF43C6021240560446112B1987B59 +:1048A00000F056F93046F8BD0130ADE7E080000871 +:1048B00000450258384F002010B5302484F3118889 +:1048C000FFF792FF002383F3118810BD10B5044653 +:1048D000807B00F053F901231049627B03FA02F256 +:1048E0000B6823EA0203DAB20B604AB90C4A916BF7 +:1048F00021F001019163116E21F001011166126E28 +:1049000013F47F4F09D1064B9A6B22F002029A638F +:104910001A6E22F002021A661B6E10BD384F00207C +:104920000045025808B5302383F31188FFF7CEFF06 +:10493000002383F3118808BD0268436811430160B6 +:1049400003B1184770470000024A136843F0C003E0 +:10495000136070470078004013B50E4C204600F0FD +:10496000B7FA04F1140000234FF400720A490094CE +:1049700000F074F9094B4FF40072094904F1380052 +:10498000009400F0EDF9074A074BC4E9172302B081 +:1049900010BD00BFBC4F002028500020494900082E +:1049A000285200200078004000E1F505037C30B576 +:1049B000214C002918BF0C46012B0CD11F4B9842EB +:1049C00009D11F4B9A6C42F080429A641A6F42F0F0 +:1049D00080421A671B6F2268036EC16D03EB52039E +:1049E0008466B3FBF2F36268150442BF23F0070547 +:1049F00003F0070343EA4503CB60A36843F0400399 +:104A00004B60E36843F001038B6042F4967343F01C +:104A100001030B604FF0FF330B62510505D512F017 +:104A2000102205D0B2F1805F04D080F8643030BD30 +:104A30007F23FAE73F23F8E7E0810008BC4F00201E +:104A4000004502582DE9F047C66D05463768F46900 +:104A5000210734621AD014F0080118BF4FF4807196 +:104A6000E20748BF41F02001A3074FF0300348BFE1 +:104A700041F04001600748BF41F0800183F3118895 +:104A8000281DFFF759FF002383F31188E2050AD59B +:104A9000302383F311884FF48061281DFFF74CFF0A +:104AA000002383F311884FF030094FF0000A14F00F +:104AB000200838D13B0616D54FF0300905F1380AE9 +:104AC000200610D589F31188504600F07DF90028A2 +:104AD00036DA0821281DFFF72FFF27F08003336007 +:104AE000002383F31188790614D5620612D530238A +:104AF00083F31188D5E913239A4208D12B6C33B183 +:104B000027F040071021281DFFF716FF376000230C +:104B100083F31188E30618D5AA6E1369ABB1506907 +:104B2000BDE8F047184789F31188736A284695F85D +:104B30006410194000F0E6F98AF31188F469B6E7C9 +:104B4000B06288F31188F469BAE7BDE8F087000025 +:104B5000090100F16043012203F56143C9B283F802 +:104B6000001300F01F039A4043099B0003F16043C8 +:104B700003F56143C3F880211A60704700F01F03FA +:104B800001229A40430900F160409B0000F561401A +:104B900003F1604303F56143C3F88020C3F880212B +:104BA000002380F800337047F8B515468268044644 +:104BB0000B46AA4200D28568A1692669761AB542D9 +:104BC0000BD218462A46FCF7BBFEA3692B44A3610F +:104BD0002846A3685B1BA360F8BD0CD9AF1B184621 +:104BE0003246FCF7ADFE3A46E1683044FCF7A8FED9 +:104BF000E3683B44EBE718462A46FCF7A1FEE3686E +:104C0000E5E7000083689342F7B50446154600D2F5 +:104C10008568D4E90460361AB5420BD22A46FCF7FF +:104C20008FFE63692B4463612846A3685B1BA36006 +:104C300003B0F0BD0DD93246AF1B0191FCF780FEE9 +:104C400001993A46E0683144FCF77AFEE3683B4458 +:104C5000E9E72A46FCF774FEE368E4E710B50A4486 +:104C60000024C361029B8460C16002610362C0E9E9 +:104C70000000C0E9051110BD08B5D0E90532934226 +:104C800001D1826882B98268013282605A1C426115 +:104C900019700021D0E904329A4224BFC3684361ED +:104CA00000F0C0FE002008BD4FF0FF30FBE7000021 +:104CB00070B5302304460E4683F31188A568A5B16C +:104CC000A368A269013BA360531CA3611578226904 +:104CD000934224BFE368A361E3690BB12046984780 +:104CE000002383F31188284607E03146204600F070 +:104CF00089FE0028E2DA85F3118870BD2DE9F74FAF +:104D000004460E4617469846D0F81C904FF0300ADD +:104D10008AF311884FF0000B154665B12A463146DB +:104D20002046FFF741FF034660B94146204600F0A8 +:104D300069FE0028F1D0002383F31188781B03B0AB +:104D4000BDE8F08FB9F1000F03D001902046C847AD +:104D5000019B8BF31188ED1A1E448AF31188DCE75E +:104D6000C160C361009B82600362C0E90511114408 +:104D7000C0E9000001617047F8B504460D461646CB +:104D8000302383F31188A768A7B1A368013BA36010 +:104D900063695A1C62611D70D4E904329A4224BFCF +:104DA000E3686361E3690BB120469847002080F314 +:104DB000118807E03146204600F024FE0028E2DAA0 +:104DC00087F31188F8BD0000D0E9052310B59A4299 +:104DD00001D182687AB982680021013282605A1C4E +:104DE00082611C7803699A4224BFC368836100F022 +:104DF00019FE204610BD4FF0FF30FBE72DE9F74FBD +:104E000004460E4617469846D0F81C904FF0300ADC +:104E10008AF311884FF0000B154665B12A463146DA +:104E20002046FFF7EFFE034660B94146204600F0FA +:104E3000E9FD0028F1D0002383F31188781B03B02B +:104E4000BDE8F08FB9F1000F03D001902046C847AC +:104E5000019B8BF31188ED1A1E448AF31188DCE75D +:104E6000026843681143016003B1184770470000AE +:104E70001430FFF743BF00004FF0FF331430FFF74B +:104E80003DBF00003830FFF7B9BF00004FF0FF33DF +:104E90003830FFF7B3BF00001430FFF709BF000040 +:104EA0004FF0FF311430FFF703BF00003830FFF739 +:104EB00063BF00004FF0FF323830FFF75DBF0000E6 +:104EC000012914BF6FF0130000207047FFF744BDA5 +:104ED000044B036000234360C0E9023301230374E1 +:104EE000704700BFF881000810B53023044683F3F3 +:104EF0001188FFF75BFD02230020237480F31188E3 +:104F000010BD000038B5C36904460D461BB9042125 +:104F10000844FFF7A5FF294604F11400FFF7ACFE93 +:104F2000002806DA201D4FF40061BDE83840FFF785 +:104F300097BF38BD026843681143016003B1184749 +:104F40007047000013B5406B00F58054D4F8A438C6 +:104F50001A681178042914D1017C022911D1197918 +:104F6000012312898B4013420BD101A94C3002F06E +:104F7000F3F9D4F8A4480246019B2179206800F097 +:104F8000DFF902B010BD0000143002F075B9000066 +:104F90004FF0FF33143002F06FB900004C3002F0D4 +:104FA00047BA00004FF0FF334C3002F041BA000026 +:104FB000143002F043B900004FF0FF31143002F01A +:104FC0003DB900004C3002F013BA00004FF0FF3240 +:104FD0004C3002F00DBA00000020704710B500F50B +:104FE0008054D4F8A4381A681178042917D1017CA8 +:104FF000022914D15979012352898B4013420ED1D1 +:10500000143002F0D5F8024648B1D4F8A4484FF461 +:10501000407361792068BDE8104000F07FB910BD91 +:10502000406BFFF7DBBF0000704700007FB5124BFD +:1050300001250426044603600023057400F1840260 +:1050400043602946C0E902330C4B029014300193AF +:105050004FF44073009602F087F8094B04F694422F +:10506000294604F14C000294CDE900634FF44073EB +:1050700002F04EF904B070BD2082000821500008F3 +:10508000454F00080A68302383F311880B790B33EE +:1050900042F823004B79133342F823008B7913B184 +:1050A0000B3342F8230000F58053C3F8A418022301 +:1050B0000374002080F311887047000038B5037F27 +:1050C000044613B190F85430ABB90125201D0221DC +:1050D000FFF730FF04F114006FF00101257700F0B5 +:1050E000ADFC04F14C0084F854506FF00101BDE8B0 +:1050F000384000F0A3BC38BD10B50121044604308F +:10510000FFF718FF0023237784F8543010BD000008 +:1051100038B504460025143002F03EF804F14C0086 +:10512000257702F00DF9201D84F854500121FFF776 +:1051300001FF2046BDE83840FFF750BF90F88030AF +:1051400003F06003202B06D190F881200023212A50 +:1051500003D81F2A06D800207047222AFBD1C0E9B5 +:105160001D3303E0034A426707228267C3670120B9 +:10517000704700BF3C23002037B500F58055D5F8B7 +:10518000A4381A68117804291AD1017C022917D190 +:105190001979012312898B40134211D100F14C047B +:1051A000204602F08DF958B101A9204602F0D4F84A +:1051B000D5F8A4480246019B2179206800F0C0F888 +:1051C00003B030BD01F10B03F0B550F8236085B09A +:1051D00004460D46FEB1302383F3118804EB8507A6 +:1051E000301D0821FFF7A6FEFB6806F14C005B6945 +:1051F0001B681BB1019002F0BDF8019803A902F0F1 +:10520000ABF8024648B1039B2946204600F098F8C7 +:10521000002383F3118805B0F0BDFB685A6912685A +:10522000002AF5D01B8A013B1340F1D104F1800222 +:10523000EAE70000133138B550F82140ECB13023D3 +:1052400083F3118804F58053D3F8A42813685279A6 +:1052500003EB8203DB689B695D6845B1042160183C +:10526000FFF768FE294604F1140001F0ABFF204669 +:10527000FFF7B4FE002383F3118838BD70470000A8 +:1052800001F07EBA01234022002110B5044600F847 +:10529000303BFCF77BFB0023C4E9013310BD000069 +:1052A00010B53023044683F3118824224160002185 +:1052B0000C30FCF76BFB204601F084FA022300203F +:1052C000237080F3118810BD70B500EB8103054693 +:1052D00050690E461446DA6018B110220021FCF71E +:1052E00055FBA06918B110220021FCF74FFB314695 +:1052F0002846BDE8704001F065BB000083682022AD +:10530000002103F0011310B5044683601030FCF750 +:105310003DFB2046BDE8104001F0E0BBF0B40125A4 +:1053200000EB810447898D40E4683D43A4694581D1 +:1053300023600023A2606360F0BC01F0FDBB0000AD +:10534000F0B4012500EB810407898D40E4683D43FA +:105350006469058123600023A2606360F0BC01F0F2 +:1053600073BC000070B5022300250446242203709C +:105370002946C0F888500C3040F8045CFCF706FB66 +:10538000204684F8705001F0B1FA63681B6823B1BD +:1053900029462046BDE87040184770BD0378052BAC +:1053A00010B504460AD080F88C300523037043689A +:1053B0001B680BB1042198470023A36010BD0000B7 +:1053C0000178052906D190F88C20436802701B688B +:1053D00003B118477047000070B590F8703004466C +:1053E00013B1002380F8703004F18002204601F0F0 +:1053F00099FB63689B68B3B994F8803013F060053B +:1054000035D00021204601F08BFE0021204601F01E +:105410007BFE63681B6813B106212046984706236C +:1054200084F8703070BD204698470028E4D0B4F866 +:105430008630A26F9A4288BFA36794F98030A56F27 +:10544000002B4FF0300380F20381002D00F0F2803A +:10545000092284F8702083F3118800212046D4E9C2 +:105460001D23FFF76DFF002383F31188DAE794F81B +:10547000812003F07F0343EA022340F20232934289 +:1054800000F0C58021D8B3F5807F48D00DD8012B1E +:105490003FD0022B00F09380002BB2D104F18802A0 +:1054A00062670222A267E367C1E7B3F5817F00F07C +:1054B0009B80B3F5407FA4D194F88230012BA0D11A +:1054C000B4F8883043F0020332E0B3F5006F4DD0FA +:1054D00017D8B3F5A06F31D0A3F5C063012B90D8D6 +:1054E0006368204694F882205E6894F88310B4F8CC +:1054F0008430B047002884D0436863670368A3679B +:105500001AE0B3F5106F36D040F6024293427FF4B2 +:1055100078AF5C4B63670223A3670023C3E794F86B +:105520008230012B7FF46DAFB4F8883023F0020392 +:10553000A4F88830C4E91D55E56778E7B4F88030F1 +:10554000B3F5A06F0ED194F88230204684F88A30EB +:1055500001F02AFA63681B6813B1012120469847BD +:10556000032323700023C4E91D339CE704F18B035C +:1055700063670123C3E72378042B10D1302383F31F +:1055800011882046FFF7BAFE85F31188032163686E +:1055900084F88B5021701B680BB12046984794F813 +:1055A0008230002BDED084F88B30042323706368B4 +:1055B0001B68002BD6D0022120469847D2E794F8EA +:1055C000843020461D0603F00F010AD501F09CFA35 +:1055D000012804D002287FF414AF2B4B9AE72B4B01 +:1055E00098E701F083FAF3E794F88230002B7FF418 +:1055F00008AF94F8843013F00F01B3D01A06204698 +:1056000002D501F0A5FDADE701F096FDAAE794F8FB +:105610008230002B7FF4F5AE94F8843013F00F0144 +:10562000A0D01B06204602D501F07AFD9AE701F0D2 +:105630006BFD97E7142284F8702083F311882B46C2 +:105640002A4629462046FFF769FE85F31188E9E6D8 +:105650005DB1152284F8702083F311880021204663 +:10566000D4E91D23FFF75AFEFDE60B2284F87020D3 +:1056700083F311882B462A4629462046FFF760FE11 +:10568000E3E700BF50820008488200084C8200080F +:1056900038B590F870300446002B3ED0063BDAB2A5 +:1056A0000F2A34D80F2B32D8DFE803F03731310816 +:1056B000223231313131313131313737856FB0F804 +:1056C00086309D4214D2C3681B8AB5FBF3F203FBFC +:1056D00012556DB9302383F311882B462A4629468B +:1056E000FFF72EFE85F311880A2384F870300EE050 +:1056F000142384F87030302383F31188002320466C +:105700001A461946FFF70AFE002383F3118838BDB5 +:10571000C36F03B198470023E7E70021204601F05B +:10572000FFFC0021204601F0EFFC63681B6813B109 +:105730000621204698470623D7E7000010B590F8C9 +:1057400070300446142B29D017D8062B05D001D869 +:105750001BB110BD093B022BFBD80021204601F0F4 +:10576000DFFC0021204601F0CFFC63681B6813B109 +:10577000062120469847062319E0152BE9D10B2373 +:1057800080F87030302383F3118800231A461946BD +:10579000FFF7D6FD002383F31188DAE7C3689B691E +:1057A0005B68002BD5D1C36F03B19847002384F801 +:1057B0007030CEE700238268037503691B6899681F +:1057C0009142FBD25A680360426010605860704793 +:1057D00000238268037503691B6899689142FBD8AE +:1057E0005A680360426010605860704708B5084608 +:1057F000302383F311880A7D0023052A06D8DFE8C9 +:1058000002F00B050503120E826913604FF0FF339F +:105810008361FFF7CFFF002383F3118808BD8269FE +:10582000936801339360D0E9003213605A60EDE76A +:10583000FFF7C0BF054BD968087518680268536048 +:105840001A600122D8600275FAF7E4BD28540020DE +:105850000C4B30B5DD684B1C87B004460FD02B468F +:10586000094A684600F07EF92046FFF7E3FF009BF7 +:1058700013B1684600F080F9A86907B030BDFFF7A2 +:10588000D9FFF9E728540020ED57000838B50C4D32 +:1058900004468161EB6881689A68914203D8BDE84B +:1058A0003840FFF787BF1846FFF792FF01230146F4 +:1058B000EC6020462375BDE83840FAF7ABBD00BF69 +:1058C00028540020044B1A68DB6890689B68984253 +:1058D00094BF00200120704728540020084B10B5C9 +:1058E0001C68D868226853601A600122DC60227547 +:1058F000FFF76EFF01462046BDE81040FAF78ABD6B +:105900002854002038B50123084C00252370656019 +:1059100001F012FE01F038FE0549064801F00CFFC7 +:105920000223237085F3118838BD00BF90560020F4 +:10593000588200082854002008B572B6044B186538 +:1059400000F022FD00F0E4FD024B03221A70FEE796 +:10595000285400209056002000F044B9034A5168B2 +:1059600053685B1A9842FBD8704700BF001000E0F4 +:105970008B600223086108468B8270478368A3F11D +:10598000840243F8142C026943F8442C426943F81A +:10599000402C094A43F8242CC268A3F1200043F8A4 +:1059A000182C022203F80C2C002203F80B2C034ABB +:1059B00043F8102C704700BF2D0400082854002025 +:1059C00008B5FFF7DBFFBDE80840FFF731BF000077 +:1059D000024BDB6898610F20FFF72CBF2854002092 +:1059E000302383F31188FFF7F3BF000008B50146A9 +:1059F000302383F311880820FFF72AFF002383F365 +:105A0000118808BD064BDB6839B1426818605A60DE +:105A1000136043600420FFF71BBF4FF0FF30704757 +:105A2000285400200368984206D01A68026050602B +:105A300018469961FFF7FCBE7047000038B5044670 +:105A40000D462068844200D138BD036823605C6045 +:105A50008561FFF7EDFEF4E7036810B59C68A2428C +:105A60000CD85C688A600B604C6021605960996852 +:105A70008A1A9A604FF0FF33836010BD121B1B68B7 +:105A8000ECE700000A2938BF0A2170B504460D462C +:105A90000A26601901F04AFD01F032FD041BA542FF +:105AA00003D8751C04462E46F3E70A2E04D90120BC +:105AB000BDE8704001F080BE70BD0000F8B5144B29 +:105AC0000D460A2A4FF00A07D96103F110018260DE +:105AD00038BF0A22416019691446016048601861A4 +:105AE000A81801F013FD01F00BFD431B0646A3426D +:105AF00006D37C1C28192746354601F017FDF2E72E +:105B00000A2F04D90120BDE8F84001F055BEF8BDC8 +:105B100028540020F8B506460D4601F0F1FC0F4A66 +:105B2000134653F8107F9F4206D12A46014630465D +:105B3000BDE8F840FFF7C2BFD169BB68441A2C1911 +:105B400028BF2C46A34202D92946FFF79BFF2246D5 +:105B500031460348BDE8F840FFF77EBF28540020D7 +:105B600038540020C0E90323002310B45DF8044B2F +:105B70004361FFF7CFBF000010B5194C236998426D +:105B80000DD08168D0E9003213605A609A680A44E7 +:105B90009A60002303604FF0FF33A36110BD0268D9 +:105BA000234643F8102F53600022026022699A4274 +:105BB00003D1BDE8104001F0B3BC936881680B4489 +:105BC000936001F09DFC2269E1699268441AA24247 +:105BD000E4D91144BDE81040091AFFF753BF00BFD4 +:105BE000285400202DE9F047DFF8BC8008F11007A9 +:105BF0002C4ED8F8105001F083FCD8F81C40AA684D +:105C0000031B9A423ED814444FF00009D5E90032F4 +:105C1000C8F81C4013605A60C5F80090D8F81030DE +:105C2000B34201D101F07CFC89F31188D5E903313D +:105C300028469847302383F311886B69002BD8D00E +:105C400001F05EFC6A69A0EB040982464A450DD268 +:105C5000022001F0B1FD0022D8F81030B34208D183 +:105C600051462846BDE8F047FFF728BF121A2244E4 +:105C7000F2E712EB09092946384638BF4A46FFF7D2 +:105C8000EBFEB5E7D8F81030B34208D01444C8F89A +:105C90001C00211AA960BDE8F047FFF7F3BEBDE87C +:105CA000F08700BF385400202854002038B501F098 +:105CB00027FC054AD2E90845031B181945F10001E4 +:105CC000C2E9080138BD00BF2854002000207047F9 +:105CD000FEE70000704700004FF0FF307047000003 +:105CE00002290CD0032904D00129074818BF00203D +:105CF0007047032A05D8054800EBC20070470448E6 +:105D000070470020704700BF308300084C230020FC +:105D1000E482000870B59AB005460846144601A909 +:105D200000F0C2F801A8FBF729FE431C0022C6B20E +:105D30005B001046C5E9003423700323023404F8E5 +:105D4000013C01ABD1B202348E4201D81AB070BD11 +:105D500013F8011B013204F8010C04F8021CF1E7EE +:105D600008B5302383F311880348FFF705FA0023B1 +:105D700083F3118808BD00BF9856002090F880304A +:105D800003F01F02012A07D190F881200B2A03D1CA +:105D90000023C0E91D3315E003F06003202B08D178 +:105DA000B0F884302BB990F88120212A03D81F2A1B +:105DB00004D8FFF7C3B9222AEBD0FAE7034A4267B7 +:105DC00007228267C3670120704700BF432300207A +:105DD00007B5052917D8DFE801F0191603191920AE +:105DE000302383F31188104A01210190FFF76CFAE8 +:105DF000019802210D4AFFF767FA0D48FFF788F96D +:105E0000002383F3118803B05DF804FB302383F390 +:105E100011880748FFF752F9F2E7302383F311881E +:105E20000348FFF769F9EBE784820008A8820008BD +:105E30009856002038B50C4D0C4C2A460C4904F1FC +:105E40000800FFF767FF05F1CA0204F110000949D5 +:105E5000FFF760FF05F5CA7204F118000649BDE8B6 +:105E60003840FFF757BF00BF706F00204C23002061 +:105E7000648200086E8200087982000870B50446CA +:105E800008460D46FBF77AFDC6B22046013403787A +:105E90000BB9184670BD32462946FBF75BFD00285A +:105EA000F3D10120F6E700002DE9F84F05460C4636 +:105EB000FBF764FD2A49C6B22846FFF7DFFF08B1A9 +:105EC0000136F6B227492846FFF7D8FF08B1103649 +:105ED000F6B2632E0DD8DFF88890DFF888A0224F45 +:105EE000DFF88CB0DFF88C802E7846B92670BDE8DC +:105EF000F88F29462046BDE8F84F02F063B8252EFA +:105F00002AD1072249462846FBF724FD50B9D8F884 +:105F100000300735083444F8083CD8F8043044F819 +:105F2000043CE1E7082251462846FBF713FD98B9E7 +:105F3000A21C0E4B197802320909C95D02F8041C33 +:105F400013F8011B01F00F015B45C95D02F8031C4A +:105F5000F0D118340835C7E7013504F8016BC3E701 +:105F600050830008798200085883000800E8F11F78 +:105F70000CE8F11FE27F0008BFF34F8F044B1A6952 +:105F80005107FCD1D3F810215207F8D1704700BF58 +:105F90000020005208B50D4B1B78ABB9FFF7ECFFA2 +:105FA0000B4BDA68D10704D50A4A5A6002F18832ED +:105FB0005A60D3F80C21D20706D5064AC3F804214B +:105FC00002F18832C3F8042108BD00BFCE71002061 +:105FD000002000522301674508B5114B1B78F3B927 +:105FE000104B1A69510703D5DA6842F04002DA60B3 +:105FF000D3F81021520705D5D3F80C2142F0400206 +:10600000C3F80C21FFF7B8FF064BDA6842F0010233 +:10601000DA60D3F80C2142F00102C3F80C2108BD6C +:10602000CE710020002000520F289ABF00F580603A +:1060300040040020704700004FF40030704700001B +:10604000102070470F2808B50BD8FFF7EDFF00F5BB +:1060500000330268013204D104308342F9D10120B7 +:1060600008BD0020FCE700000F2838B505463FD8E2 +:10607000FFF782FF1F4CFFF78DFF4FF0FF3307281C +:106080006361C4F814311DD82361FFF775FF030263 +:1060900043F02403E360E36843F08003E360236993 +:1060A0005A07FCD42846FFF767FFFFF7BDFF4FF400 +:1060B000003100F009FA2846FFF78EFFBDE83840AE +:1060C000FFF7C0BFC4F81031FFF756FFA0F1080377 +:1060D0001B0243F02403C4F80C31D4F80C3143F014 +:1060E0008003C4F80C31D4F810315B07FBD4D9E736 +:1060F000002038BD002000522DE9F84F05460C461F +:10610000104645EA0203DE0602D00020BDE8F88F03 +:1061100020F01F00DFF8BCB0DFF8BCA0FFF73AFFAB +:1061200004EB0008444503D10120FFF755FFEDE7DC +:1061300020222946204601F013FF10B920352034D3 +:10614000F0E72B4605F120021F68791CDDD10433EE +:106150009A42F9D105F178431B481C4EB3F5801FD4 +:106160001B4B38BF184603F1F80332BFD946D1465E +:106170001E46FFF701FF0760A5EB040C336804F12E +:106180001C0143F002033360231FD9F8007017F09D +:106190000507FAD153F8042F8B424CF80320F4D1B1 +:1061A000BFF34F8FFFF7E8FE4FF0FF332022214669 +:1061B00003602846336823F00203336001F0D0FE09 +:1061C0000028BBD03846B0E7142100520C20005202 +:1061D00014200052102000521021005210B5084C1B +:1061E000237828B11BB9FFF7D5FE0123237010BD1A +:1061F000002BFCD02070BDE81040FFF7EDBE00BFC3 +:10620000CE7100202DE9F04F0D4685B0814658B182 +:1062100011F00D0614BF2022082211F0080301938B +:1062200004D0431E03426AD0002435E0002E37D04C +:1062300009F11F0121F01F094FF00108324F05F04D +:106240000403DFF8D0A005EA080BBBF1000F32D041 +:106250007869C0072FD408F101080C37B8F1060F90 +:10626000F3D19EB9294D4946A819019201F0AEF922 +:10627000044600283AD11836019A782EF3D14946BF +:1062800001F0A4F90446002830D1019A494620487B +:1062900001F09CF9044668BB204605B0BDE8F08FCC +:1062A0000029C9D101462846029201F08FF904461F +:1062B000E0B9029AC0E713B178694107CBD5AC07C2 +:1062C00002D578698007C6D5019911B178690107AF +:1062D000C1D51820494600FB08A0CDE9022301F0F2 +:1062E00075F90446DDE902230028B4D04A460021AE +:1062F000204601E04A460021FBF748FBCCE7024676 +:10630000002E95D198E700BF6C8300080072002032 +:10631000D0710020E87100200121FFF773BF000059 +:10632000F8B5144D01241827134E40F2FF32002116 +:106330000120FBF72BFB07FB046001342A6955F8A9 +:106340000C1F01F02FF9062CF5D137254FF4C0545E +:106350002046FFF7E1FF014628B122460748BDE885 +:10636000F84001F01FB9C4EBC404013D4FEAD40466 +:10637000EED1F8BD6C830008E8710020D0710020D8 +:1063800008B101F095B9704738B5054D00240334C4 +:10639000696855F80C0B00F0A9F8122CF7D138BD3C +:1063A0006C83000838B5EFF311859DB9EFF30584D0 +:1063B000C4F30804302334B183F31188FFF776FC6B +:1063C00085F3118838BD83F31188FFF76FFC84F3E0 +:1063D000118838BDBDE83840FFF768BC10B5FFF73D +:1063E000E1FF104CC008104A002340EA4170C90880 +:1063F000A0FB04ECA0FB020E1CEB0000A1FB044C74 +:10640000A1FB02125B41001943EB0C0011EB0E01E2 +:1064100042F10002411842F10000090941EA00700E +:1064200010BD00BFCFF753E3A59BC4200244074B28 +:10643000D2B210B5904200D110BD441C00B253F846 +:10644000200041F8040BE0B2F4E700BF50400058D0 +:106450000E4B30B51C6F240405D41C6F1C671C6FD9 +:1064600044F400441C670A4C02442368D2B243F44B +:1064700080732360074B904200D130BD441C51F81B +:10648000045B00B243F82050E0B2F4E70044025845 +:10649000004802585040005807B5012201A90020C9 +:1064A000FFF7C4FF019803B05DF804FB13B5044681 +:1064B000FFF7F2FFA04205D0012201A900200194BC +:1064C000FFF7C6FF02B010BD0144BFF34F8F064B6C +:1064D000884204D3BFF34F8FBFF36F8F7047C3F869 +:1064E0005C022030F4E700BF00ED00E00144BFF3A0 +:1064F0004F8F064B884204D3BFF34F8FBFF36F8F8C +:106500007047C3F870022030F4E700BF00ED00E0F0 +:1065100070470000114BDA6952021ED59A69D00704 +:1065200004D50F4A9A6002F144329A600B4BDA6943 +:10653000D107FCD41A6A22F480021A629A6942F0E6 +:1065400002029A61DA69D207FCD49A6942F0010228 +:106550009A61024AD369DB07FCD4704700200052DD +:106560003B2A1908074B45F255521A6003225A601C +:1065700040F2FF729A604CF6CC421A600122024B44 +:106580001A707047004800587C720020034B1B783B +:106590001BB1034B4AF6AA221A6070477C72002096 +:1065A00000480058034B1A681AB9034AD2F8D0249D +:1065B0001A6070477872002000400258024B4FF476 +:1065C0008032C3F8D02470470040025808B5FFF766 +:1065D000E9FF024B1868C0F3806008BD78720020A4 +:1065E00070B5BFF34F8FBFF36F8F1A4A0021C2F807 +:1065F0005012BFF34F8FBFF36F8F536943F40033D3 +:106600005361BFF34F8FBFF36F8FC2F88410BFF396 +:106610004F8FD2F8803043F6E074C3F3C900C3F360 +:106620004E335B0103EA0406014646EA81750139EF +:10663000C2F86052F9D2203B13F1200FF2D1BFF320 +:106640004F8F536943F480335361BFF34F8FBFF3D0 +:106650006F8F70BD00ED00E0FEE70000214B224887 +:10666000224A70B5904237D3214BC11EDA1C121A50 +:1066700022F003028B4238BF00220021FBF786F98B +:106680001C4A0023C2F88430BFF34F8FD2F8803009 +:1066900043F6E074C3F3C900C3F34E335B0103EA6E +:1066A0000406014646EA81750139C2F86C52F9D2F6 +:1066B000203B13F1200FF2D1BFF34F8FBFF36F8F49 +:1066C000BFF34F8FBFF36F8F0023C2F85032BFF379 +:1066D0004F8FBFF36F8F70BD53F8041B40F8041B3E +:1066E000C0E700BF9C850008707400207074002013 +:1066F0007074002000ED00E0054B996B21EA000169 +:1067000099631A6E22EA00021A661B6E704700BF78 +:106710000045025870B5D0E9244300224FF0FF3500 +:106720009E6804EB42135101D3F80009002805DAF2 +:10673000D3F8000940F08040C3F80009D3F8000BFB +:10674000002805DAD3F8000B40F08040C3F8000BB6 +:10675000013263189642C3F80859C3F8085BE0D2C7 +:106760004FF00113C4F81C3870BD0000890141F0DE +:106770002001016103699B06FCD41220FFF7EEB8EB +:1067800010B50A4C2046FEF77DFD094BC4F8903049 +:10679000084BC4F89430084C2046FEF773FD074BB5 +:1067A000C4F89030064BC4F8943010BD80720020BD +:1067B00000000840D88300081C730020000004403B +:1067C000E483000870B503780546012B58D13F4B90 +:1067D000D0F89040984254D13D4B0E2165209A6BE1 +:1067E00042F000629A631A6E42F000621A661B6EF3 +:1067F000384BD3F8802042F00062C3F88020D3F8F1 +:10680000802022F00062C3F88020D3F88030FEF7A9 +:106810009FF9314BE360314BC4F800380023D5F8C1 +:106820009060C4F8003EC02323604FF40413A363B8 +:106830003369002BFCDA01230C203361FFF78EF85B +:106840003369DB07FCD41220FFF788F83369002B8B +:10685000FCDA00262846A660FFF75CFF6B68C4F8E8 +:106860001068DB68C4F81468C4F81C6863BB1C4B70 +:10687000A3614FF0FF336361A36843F00103A3609A +:1068800070BD184B9842C9D1114B4FF080609A6B84 +:1068900042F000729A631A6E42F000721A661B6E22 +:1068A0000C4BD3F8802042F00072C3F88020D3F85C +:1068B000802022F00072C3F88020D3F88030FFF7E8 +:1068C0001BFF0E214D20A2E7074BD1E7807200206D +:1068D00000450258004402584014004003002002C2 +:1068E000003C30C01C730020083C30C0F8B5D0F824 +:1068F0009040054600214FF000662046FFF736FF26 +:10690000D5F8941000234FF001128F684FF0FF303C +:10691000C4F83438C4F81C2804EB431201339F42F6 +:10692000C2F80069C2F8006BC2F80809C2F8080B87 +:10693000F2D20B68D5F89020C5F898306362102326 +:106940001361166916F01006FBD11220FFF706F846 +:10695000D4F8003823F4FE63C4F80038A36943F484 +:10696000402343F01003A3610923C4F81038C4F88E +:1069700014380B4BEB604FF0C043C4F8103B094B8D +:10698000C4F8003BC4F81069C4F80039D5F8983051 +:1069900003F1100243F48013C5F89820A362F8BDF8 +:1069A000B483000840800010D0F8902090F88A103E +:1069B000D2F8003823F4FE6343EA0113C2F800382A +:1069C000704700002DE9F84300EB8103D0F89050A8 +:1069D0000C468046DA680FFA81F94801166806F01D +:1069E0000306731E022B05EB41134FF0000194BF09 +:1069F000B604384EC3F8101B4FF0010104F1100328 +:106A000098BF06F1805601FA03F3916998BF06F525 +:106A1000004600293AD0578A04F15801374349010A +:106A20006F50D5F81C180B430021C5F81C382B18E3 +:106A30000127C3F81019A7405369611E9BB3138A3D +:106A4000928B9B08012A88BF5343D8F89820981846 +:106A500042EA034301F140022146C8F89800284663 +:106A600005EB82025360FFF781FE08EB8900C368E3 +:106A70001B8A43EA845348341E4364012E51D5F8DF +:106A80001C381F43C5F81C78BDE8F88305EB49178F +:106A9000D7F8001B21F40041C7F8001BD5F81C18DB +:106AA00021EA0303C0E704F13F030B4A28462146CD +:106AB00005EB83035A60FFF759FE05EB4910D0F848 +:106AC000003923F40043C0F80039D5F81C3823EA14 +:106AD0000707D7E70080001000040002D0F89420D8 +:106AE0001268C0F89820FFF715BE00005831D0F8A2 +:106AF000903049015B5813F4004004D013F4001F98 +:106B00000CBF0220012070474831D0F89030490175 +:106B10005B5813F4004004D013F4001F0CBF022094 +:106B20000120704700EB8101CB68196A0B68136084 +:106B30004B6853607047000000EB810330B5DD689F +:106B4000AA691368D36019B9402B84BF402313602E +:106B50006B8A1468D0F890201C4402EB4110013C71 +:106B600009B2B4FBF3F46343033323F0030343EAB2 +:106B7000C44343F0C043C0F8103B2B6803F0030349 +:106B8000012B0ED1D2F8083802EB411013F4807FAC +:106B9000D0F8003B14BF43F0805343F00053C0F8DB +:106BA000003B02EB4112D2F8003B43F00443C2F831 +:106BB000003B30BD2DE9F041D0F8906005460C4611 +:106BC00006EB4113D3F8087B3A07C3F8087B08D5D6 +:106BD000D6F814381B0704D500EB8103DB685B682B +:106BE0009847FA071FD5D6F81438DB071BD505EBF5 +:106BF0008403D968CCB98B69488A5A68B2FBF0F62D +:106C000000FB16228AB91868DA6890420DD2121A6F +:106C1000C3E90024302383F3118821462846FFF777 +:106C20008BFF84F31188BDE8F081012303FA04F29D +:106C30006B8923EA02036B81CB68002BF3D02146DA +:106C40002846BDE8F041184700EB81034A0170B5C2 +:106C5000DD68D0F890306C692668E66056BB1A444F +:106C60004FF40020C2F810092A6802F00302012A3A +:106C70000AB20ED1D3F8080803EB421410F4807F57 +:106C8000D4F8000914BF40F0805040F00050C4F820 +:106C9000000903EB4212D2F8000940F00440C2F8A8 +:106CA00000090122D3F8340802FA01F10143C3F8C4 +:106CB000341870BD19B9402E84BF40202060206870 +:106CC0001A442E8A8419013CB4FBF6F440EAC4400D +:106CD00040F00050C6E700002DE9F843D0F890607E +:106CE00005460C464F0106EB4113D3F8088918F00E +:106CF000010FC3F808891CD0D6F81038DB0718D567 +:106D000000EB8103D3F80CC0DCF81430D3F800E0BA +:106D1000DA68964530D2A2EB0E024FF000091A60F5 +:106D2000C3F80490302383F31188FFF78DFF89F3B4 +:106D3000118818F0800F1DD0D6F834380126A640EF +:106D4000334217D005EB84030134D5F89050D3F8C3 +:106D50000CC0E4B22F44DCF8142005EB0434D2F864 +:106D600000E05168714514D3D5F8343823EA06069B +:106D7000C5F83468BDE8F883012303FA01F20389FA +:106D800023EA02030381DCF80830002BD1D09847B6 +:106D9000CFE7AEEB0103BCF81000834228BF0346E7 +:106DA000D7F8180980B2B3EB800FE3D89068A0F150 +:106DB000040959F8048FC4F80080A0EB090898442E +:106DC000B8F1040FF5D818440B4490605360C8E73D +:106DD0002DE9F84FD0F8905004466E69AB691E401B +:106DE00016F480586E6103D0BDE8F84FFEF7BABACA +:106DF000002E12DAD5F8003E9B0705D0D5F8003EEC +:106E000023F00303C5F8003ED5F80438204623F0EC +:106E10000103C5F80438FEF7D3FA370505D5204637 +:106E2000FFF778FC2046FEF7B9FAB0040CD5D5F888 +:106E3000083813F0060FEB6823F470530CBF43F4CB +:106E4000105343F4A053EB6031071BD56368DB6834 +:106E50001BB9AB6923F00803AB612378052B0CD178 +:106E6000D5F8003E9A0705D0D5F8003E23F003037D +:106E7000C5F8003E2046FEF7A3FA6368DB680BB155 +:106E800020469847F30200F1BA80B70226D5D4F81D +:106E9000909000274FF0010A09EB4712D2F8003B0F +:106EA00003F44023B3F5802F11D1D2F8003B002B1F +:106EB0000DDA62890AFA07F322EA0303638104EB1D +:106EC0008703DB68DB6813B13946204698470137F2 +:106ED000D4F89430FFB29B689F42DDD9F00619D5F3 +:106EE000D4F89000026AC2F30A1702F00F0302F40A +:106EF000F012B2F5802F00F0CA80B2F5402F09D110 +:106F000004EB8303002200F58050DB681B6A974284 +:106F100040F0B0803003D5F8185835D5E90303D5D3 +:106F200000212046FFF746FEAA0303D50121204693 +:106F3000FFF740FE6B0303D502212046FFF73AFE20 +:106F40002F0303D503212046FFF734FEE80203D5C3 +:106F500004212046FFF72EFEA90203D50521204675 +:106F6000FFF728FE6A0203D506212046FFF722FE1E +:106F70002B0203D507212046FFF71CFEEF0103D5A6 +:106F800008212046FFF716FE700340F1A780E907AD +:106F900003D500212046FFF79FFEAA0703D5012154 +:106FA0002046FFF799FE6B0703D502212046FFF725 +:106FB00093FE2F0703D503212046FFF78DFEEE0633 +:106FC00003D504212046FFF787FEA80603D5052137 +:106FD0002046FFF781FE690603D506212046FFF70C +:106FE0007BFE2A0603D507212046FFF775FEEB0539 +:106FF00074D520460821BDE8F84FFFF76DBED4F8E0 +:1070000090904FF0000B4FF0010AD4F894305FFAE3 +:107010008BF79B689F423FF638AF09EB4713D3F8D5 +:10702000002902F44022B2F5802F20D1D3F80029A4 +:10703000002A1CDAD3F8002942F09042C3F8002954 +:10704000D3F80029002AFBDB3946D4F89000FFF77B +:107050008DFB22890AFA07F322EA0303238104EB5A +:107060008703DB689B6813B13946204698470BF1CC +:10707000010BCAE7910701D1D0F80080072A02F17D +:1070800001029CBF03F8018B4FEA18283FE704EB8D +:10709000830300F58050DA68D2F818C0DCF80820C5 +:1070A000DCE9001CA1EB0C0C00218F4208D1DB684D +:1070B0009B699A683A449A605A683A445A6029E748 +:1070C00011F0030F01D1D0F800808C4501F10101CE +:1070D00084BF02F8018B4FEA1828E6E7BDE8F88F75 +:1070E00008B50348FFF774FEBDE80840FDF7DAB9BC +:1070F0008072002008B50348FFF76AFEBDE808402B +:10710000FDF7D0B91C730020D0F8903003EB41118B +:10711000D1F8003B43F40013C1F8003B7047000076 +:10712000D0F8903003EB4111D1F8003943F400134B +:10713000C1F8003970470000D0F8903003EB4111DE +:10714000D1F8003B23F40013C1F8003B7047000066 +:10715000D0F8903003EB4111D1F8003923F400133B +:10716000C1F800397047000030B50433039C017248 +:10717000002104FB0325C160C0E90653049B03639F +:10718000059BC0E90000C0E90422C0E90842C0E94B +:107190000A11436330BD00000022416AC260C0E9A9 +:1071A0000411C0E90A226FF00101FEF747BC00009C +:1071B000D0E90432934201D1C2680AB9181D704760 +:1071C00000207047036919600021C2680132C26063 +:1071D000C269134482699342036124BF436A036115 +:1071E000FEF720BC38B504460D46E3683BB1626942 +:1071F0000020131D1268A3621344E36207E0237AA0 +:1072000033B929462046FEF7FDFB0028EDDA38BDEC +:107210006FF00100FBE70000C368C269013BC36077 +:107220004369134482699342436124BF436A4361C3 +:1072300000238362036B03B11847704770B5302396 +:10724000044683F31188866A3EB9FFF7CBFF0546F3 +:1072500018B186F31188284670BDA36AE26A13F854 +:10726000015B9342A36202D32046FFF7D5FF0023C0 +:1072700083F31188EFE700002DE9F84F04460E462E +:10728000174698464FF0300989F311880025AA4621 +:10729000D4F828B0BBF1000F09D141462046FFF7D2 +:1072A000A1FF20B18BF311882846BDE8F88FD4E9FF +:1072B0000A12A7EB050B521A934528BF9346BBF160 +:1072C000400F1BD9334601F1400251F8040B9142A3 +:1072D00043F8040BF9D1A36A403640354033A3622A +:1072E000D4E90A239A4202D32046FFF795FF8AF396 +:1072F0001188BD42D8D289F31188C9E730465A4671 +:10730000FAF71EFBA36A5E445D445B44A362E7E7B1 +:1073100010B5029C0433017203FB0421C460C0E970 +:1073200006130023C0E90A33039B0363049BC0E9EF +:107330000000C0E90422C0E90842436310BD000018 +:10734000026A6FF00101C260426AC0E904220022B1 +:10735000C0E90A22FEF772BBD0E904239A4201D1A8 +:10736000C26822B9184650F8043B0B6070470023EE +:107370001846FAE7C3680021C2690133C360436954 +:10738000134482699342436124BF436A4361FEF719 +:1073900049BB000038B504460D46E3683BB123699C +:1073A00000201A1DA262E2691344E36207E0237A17 +:1073B00033B929462046FEF725FB0028EDDA38BD13 +:1073C0006FF00100FBE7000003691960C268013A31 +:1073D000C260C269134482699342036124BF436A55 +:1073E000036100238362036B03B1184770470000F9 +:1073F00070B530230D460446114683F31188866A22 +:107400002EB9FFF7C7FF10B186F3118870BDA36ACC +:107410001D70A36AE26A01339342A36204D3E16957 +:1074200020460439FFF7D0FF002080F31188EDE7F4 +:107430002DE9F84F04460D46904699464FF0300A24 +:107440008AF311880026B346A76A4FB949462046F9 +:10745000FFF7A0FF20B187F311883046BDE8F88F11 +:10746000D4E90A073A1AA8EB0607974228BF17463D +:10747000402F1BD905F1400355F8042B9D4240F8DD +:10748000042BF9D1A36A40364033A362D4E90A231E +:107490009A4204D3E16920460439FFF795FF8BF344 +:1074A00011884645D9D28AF31188CDE729463A4654 +:1074B000FAF746FAA36A3D443E443B44A362E5E73B +:1074C000D0E904239A4217D1C3689BB1836A8BB178 +:1074D000043B9B1A0ED01360C368013BC360C369B1 +:1074E0001A4483699A42026124BF436A03610023FC +:1074F00083620123184670470023FBE700F05CBA63 +:10750000014B586A704700BF000C0040034B00223B +:1075100058631A610222DA60704700BF000C004015 +:10752000014B0022DA607047000C0040014B5863A9 +:10753000704700BF000C0040024B034A1A60034A28 +:107540005A607047D0730020707400200000022041 +:10755000074B494210B55C68201A08401968821A26 +:107560008A4203D3A24201D85A6010BD0020FCE732 +:10757000D073002008B5302383F31188FFF7E8FFAC +:10758000002383F3118808BD04480121044B0360E4 +:107590000023C0E901330C3000F016B9D873002085 +:1075A00075750008CB1D083A23F00703591A521AC3 +:1075B000012110B4D2080024C0E9004384600C30DB +:1075C0001C605A605DF8044B00F0FEB82DE9F84FDE +:1075D000364ECD1D0F46002818BF0646082A4FEA32 +:1075E000D50538BF082206F10C08341D91464046E7 +:1075F00000F006F909F10701C9F1000E22462468DE +:107600006CB9404600F006F93368CBB3082249460E +:10761000E8009847044698B340E9026730E004EB7D +:10762000010CD4F804A00CEA0E0C0AF10100ACF134 +:10763000080304EBC0009842E0D9A0EB0C0CB5EBBA +:10764000EC0F4FEAEC0BD9D89C421CD204F1080293 +:10765000AB45A3EB02024FEAE202626009D9691C62 +:10766000ED43206803EBC1025D44556043F83100EF +:1076700022601C465F60404644F8086B00F0CAF880 +:107680002046BDE8F88FAA45216802D11160234643 +:10769000EFE7013504EBC50344F8351003F10801A9 +:1076A000401AC01058601360F1E700BFD873002083 +:1076B000F8B550F8043C044650F8085CA0F1080600 +:1076C00007332F1D0C35DB0840F8043C284600F03A +:1076D00097F83B469F421A6801D0B34228D20AB1BC +:1076E000964225D244F8082C54F8042C1E6001322E +:1076F00054F8081C06EBC200814206D148680244D7 +:1077000044F8042C0A6844F8082C5868411C03EB20 +:10771000C1018E4207D154F8042C013202445A6050 +:1077200054F8082C1A602846BDE8F84000F072B8FA +:107730001346CFE7FEE7000070B51B4B002504465B +:1077400086B058600E4685620163FCF783FE04F143 +:107750001003A560E562C4E904334FF0FF33C4E9C8 +:107760000044C4E90635FFF7CBFE2B46024604F180 +:1077700034012046C4E9082380230C4A2565FEF71E +:10778000F7F801230A4AE0600092037568467268C0 +:107790000192B268CDE90223064BCDE90435FEF72C +:1077A0000FF906B070BD00BF90560020F0830008AE +:1077B000F583000835770008024AD36A1843D0627F +:1077C000704700BF28540020C0E900008160704766 +:1077D0008368013B002B10B583600CDA074BDC6833 +:1077E0004368A061206063601C6044600520FEF770 +:1077F00021F8A06910BD0020FCE700BF285400203C +:1078000008B5302383F31188FFF7E2FF002383F3E9 +:10781000118808BD08B5302383F3118883680133CC +:10782000002B836007DC036800211A680260506047 +:107830001846FEF72BF8002383F3118808BD0000DB +:107840004B6843608B688360CB68C3600B6943619E +:107850004B6903628B6943620B68036070470000E9 +:1078600008B53C4B40F2FF713B48D3F888200A43EF +:10787000C3F88820D3F8882022F4FF6222F00702A0 +:10788000C3F88820D3F88830344B1A6C0A431A6442 +:107890009A6E0A439A66324A9B6E1146FFF7D0FFF2 +:1078A00000F5806002F11C01FFF7CAFF00F580605F +:1078B00002F13801FFF7C4FF00F5806002F15401C6 +:1078C000FFF7BEFF00F5806002F17001FFF7B8FF1F +:1078D00000F5806002F18C01FFF7B2FF00F58060D7 +:1078E00002F1A801FFF7ACFF00F5806002F1C401CE +:1078F000FFF7A6FF00F5806002F1E001FFF7A0FFAF +:1079000000F5806002F1FC01FFF79AFF02F58C712F +:1079100000F58060FFF794FF00F010F9114BD3F8E9 +:10792000902242F00102C3F89022D3F8942242F050 +:107930000102C3F894220522C3F898204FF0605248 +:10794000C3F89C20084AC3F8A020BDE80840FEF711 +:10795000E1BD00BF00440258000002580045025833 +:10796000FC83000800ED00E01F00080308B500F0EC +:10797000C3FAFDF7C7FF0D4BDA6B42F04002DA6342 +:107980005A6E22F040025A665B6E094B1A6842F04A +:1079900008021A601A6842F004021A60FEF702FE3A +:1079A000FEF7BEFCBDE80840FEF744BA00450258A9 +:1079B00000180248704700000E4B9A6C42F0080213 +:1079C0009A641A6F42F008021A670B4A1B6FD36B56 +:1079D00043F00803D363C722084B9A624FF0FF328B +:1079E000DA6200229A615A63DA605A6001225A61AF +:1079F0001A607047004502580010005C000C0040FF +:107A0000094A08B51169D3680B40D9B29B076FEAE0 +:107A10000101116107D5302383F31188FDF79CFF25 +:107A2000002383F3118808BD000C0040044BDA6B7F +:107A30000243DA635A6E104358665B6E704700BFAC +:107A40000045025808B53C4B4FF0FF31D3F8802079 +:107A500062F00042C3F88020D3F8802002F0004298 +:107A6000C3F88020D3F88020D3F88420C3F8841092 +:107A7000D3F884200022C3F88420D3F88400D86F80 +:107A800040F0FF4040F4FF0040F4DF4040F07F0052 +:107A9000D867D86F20F0FF4020F4FF0020F4DF40CB +:107AA00020F07F00D867D86FD3F888006FEA405085 +:107AB0006FEA5050C3F88800D3F88800C0F30A007A +:107AC000C3F88800D3F88800D3F89000C3F890106A +:107AD000D3F89000C3F89020D3F89000D3F8940026 +:107AE000C3F89410D3F89400C3F89420D3F894000A +:107AF000D3F89800C3F89810D3F89800C3F89820EA +:107B0000D3F89800D3F88C00C3F88C10D3F88C000D +:107B1000C3F88C20D3F88C00D3F89C00C3F89C10D9 +:107B2000D3F89C10C3F89C20D3F89C30FCF73CFEA3 +:107B3000BDE8084000F0B4B90044025808B501227D +:107B4000504BC3F80821504B5A6D42F002025A655F +:107B5000DA6F42F00202DA670422DB6F4B4BDA6025 +:107B60005A689104FCD54A4A1A6001229A60494A2F +:107B7000DA6000221A614FF440429A61434B9A69DD +:107B80009204FCD51A6842F480721A60424B1A6F54 +:107B900012F4407F04D04FF480321A6700221A6733 +:107BA0001A6842F001021A603B4B1A685007FCD574 +:107BB00000221A611A6912F03802FBD10121196002 +:107BC0004FF0804159605A67344ADA62344A1A6188 +:107BD0001A6842F480321A602F4B1A689103FCD560 +:107BE0001A6842F480521A601A689204FCD52D4A31 +:107BF0002D499A6200225A63196301F57C01DA6308 +:107C000001F5E77199635A64284A1A64284ADA62CE +:107C10001A6842F0A8521A601F4B1A6802F02852E4 +:107C2000B2F1285FF9D148229A614FF48862DA6193 +:107C300040221A621F4ADA641F4A1A651F4A5A65AF +:107C40001F4A9A6532231F4A1360136803F00F031B +:107C5000022BFAD1104A136943F00303136113692D +:107C600003F03803182BFAD14FF00050FFF7DEFE77 +:107C70004FF08040FFF7DAFE4FF00040BDE80840CB +:107C8000FFF7D4BE0080005100450258004802585A +:107C900000C000F004000001004402580000FF0191 +:107CA000008890083220600063020901470E050831 +:107CB000DD0BBF0120000020000001100910E000D2 +:107CC00000010110002000524FF0B04208B5D2F878 +:107CD000883003F00103C2F8883023B1044A1368E6 +:107CE0000BB150689847BDE80840FCF7DBBB00BF0C +:107CF000F07300204FF0B04208B5D2F8883003F09E +:107D00000203C2F8883023B1044A93680BB1D068EB +:107D10009847BDE80840FCF7C5BB00BFF0730020E2 +:107D20004FF0B04208B5D2F8883003F00403C2F82F +:107D3000883023B1044A13690BB150699847BDE8F4 +:107D40000840FCF7AFBB00BFF07300204FF0B0421B +:107D500008B5D2F8883003F00803C2F8883023B1A0 +:107D6000044A93690BB1D0699847BDE80840FCF715 +:107D700099BB00BFF07300204FF0B04208B5D2F8B5 +:107D8000883003F01003C2F8883023B1044A136A24 +:107D90000BB1506A9847BDE80840FCF783BB00BFB1 +:107DA000F07300204FF0B04310B5D3F8884004F4CE +:107DB0007872C3F88820A30604D5124A936A0BB1DF +:107DC000D06A9847600604D50E4A136B0BB1506B0E +:107DD0009847210604D50B4A936B0BB1D06B98479B +:107DE000E20504D5074A136C0BB1506C9847A30504 +:107DF00004D5044A936C0BB1D06C9847BDE8104091 +:107E0000FCF750BBF07300204FF0B04310B5D3F82F +:107E1000884004F47C42C3F88820620504D5164AE1 +:107E2000136D0BB1506D9847230504D5124A936D1D +:107E30000BB1D06D9847E00404D50F4A136E0BB117 +:107E4000506E9847A10404D50B4A936E0BB1D06EC7 +:107E50009847620404D5084A136F0BB1506F9847D6 +:107E6000230404D5044A936F0BB1D06F9847BDE843 +:107E70001040FCF717BB00BFF073002008B50348A3 +:107E8000FCF7E0FDBDE80840FCF70CBBBC4F002050 +:107E900008B5FFF7B5FDBDE80840FCF703BB0000DF +:107EA000062108B50846FCF753FE06210720FCF71B +:107EB0004FFE06210820FCF74BFE06210920FCF7A7 +:107EC00047FE06210A20FCF743FE06211720FCF797 +:107ED0003FFE06212820FCF73BFE09217A20FCF713 +:107EE00037FE07213220FCF733FE0C215220BDE87B +:107EF0000840FCF72DBE000008B5FFF7A3FD00F019 +:107F00000DF8FCF7E3FFFDF7BBF9FDF78DF8FFF780 +:107F100051FDBDE80840FFF7F1BA00000023054A13 +:107F200019460133102BC2E9001102F10802F8D101 +:107F3000704700BFF07300200B460146184600F062 +:107F400001B8000010B5054C13462CB10A46014695 +:107F50000220AFF3008010BD2046FCE700000000C7 +:107F600010B501390244904201D1002005E00378A8 +:107F700011F8014FA34201D0181B10BD0130F2E7E8 +:107F80002DE9F041A3B1C91A17780144044603F161 +:107F9000FF3C8C42204601D9002009E00578BD4213 +:107FA00004F10104F5D10CEB0405D618A54201D16A +:107FB000BDE8F08115F8018D16F801EDF045F5D01A +:107FC000E7E70000034611F8012B03F8012B002A14 +:107FD000F9D170476F72672E6172647570696C6F4A +:107FE000742E437562654E6F6465000053544D33C3 +:107FF0003248373F3F3F0053544D33324837337890 +:108000002F3732780053544D3332483734332F37BB +:1080100035332F373530000001105A000310590056 +:10802000012058000320560040A2E4F16468910644 +:108030000041A3E5F26569920700000043414E4606 +:108040004449666163653A204D65737361676520D5 +:1080500052414D204F766572666C6F7721000000AB +:108060004261642043414E496661636520696E64E4 +:1080700065782E000000000000000000392B000889 +:108080009D230008913200080D24000819240008DF +:1080900055280008B5250008D5230008D923000875 +:1080A000B12300089923000811280008BD23000807 +:1080B00019340008C9330008C9230008E52700085F +:1080C00001040E05054B02020E05054B04010E05C9 +:1080D000054B05010B04044B080106030346000091 +:1080E00010000240080002400008024000000B009F +:1080F00028000240080002400408024006010C006B +:1081000040000240080002400808024010020D0032 +:1081100058000240080002400C08024016030E00FE +:10812000700002400C0002401008024000040F00E2 +:10813000880002400C0002401408024006051000AE +:10814000A00002400C000240180802401006110076 +:10815000B80002400C0002401C08024016072F0025 +:1081600010040240080402402008024000083800C1 +:10817000280402400804024024080240060939008D +:10818000400402400804024028080240100A3A0055 +:1081900058040240080402402C080240160B3B0021 +:1081A000700402400C04024030080240000C3C0005 +:1081B000880402400C04024034080240060D4400CA +:1081C000A00402400C04024038080240100E450092 +:1081D000B80402400C0402403C080240160F46005E +:1081E00000960000000000000000000000000000F9 +:1081F0000000000000000000000000008D4E00089C +:10820000794E0008B54E0008A14E0008AD4E00089A +:10821000994E0008854E0008714E0008C14E0008B6 +:1082200000000000A54F0008914F0008CD4F000846 +:10823000B94F0008C54F0008B14F00089D4F000816 +:10824000894F0008D94F000800000000010000001D +:1082500000000000633000005482000880540020B9 +:10826000905600204172647550696C6F740025420D +:108270004F415244252D424C002553455249414C13 +:10828000250000000200000000000000C5510008A9 +:108290003552000840004000406F0020506F002021 +:1082A00002000000000000000300000000000000C9 +:1082B0007D5200080000000010000000606F0020E8 +:1082C000000000000100000000000000807200209B +:1082D00001010200D15D0008E15C00087D5D00083D +:1082E000615D000843000000EC82000809024300C1 +:1082F000020100C03209040000010202010005244D +:1083000000100105240100010424020205240600D6 +:1083100001070582030800FF09040100020A0000AA +:10832000000705010240000007058102400000002F +:108330001200000038830008120110010200004002 +:10834000091241570002010203010000040309045D +:1083500025424F41524425003031323334353637CF +:1083600038394142434445460000000000010020E6 +:1083700000FF0100020000000000003000000400C7 +:1083800008000000000000240000080004000000B5 +:108390000004000000FC00000200000000000430A7 +:1083A000008000000800000000000038000001000C +:1083B0000100000000000000D95300089156000899 +:1083C0003D57000840004000B8730020B8730020FB +:1083D00001000000C8730020800000004001000080 +:1083E000080000000001000000100000080000006C +:1083F0006D61696E0069646C650000000000802A90 +:1084000000000000AAAAAAAA00000024FFFF0000A2 +:108410000000000000A00A000000000000000000B2 +:10842000AAAAAAAA00000000FFFF000000000000A6 +:10843000000000000000000000000000AAAAAAAA94 +:1084400000000000FFFF000000000000000000002E +:108450000A00000000000000AAAAAAAA000000006A +:10846000FFFF0000990000000000000000800200F3 +:1084700000000000AAAAAAAA00400100FFFF000015 +:108480000000007007000000000000000000000075 +:10849000AAAAAAAA00000000FFFF00000000000036 +:1084A000000000000500000000000000A5AAAAAA24 +:1084B00000000000FCFF00000000000000000000C1 +:1084C0000000000000000000AAAAAAAA0000000004 +:1084D000FFFF00000000000000000000000000009E +:1084E00000000000AAAAAAAA00000000FFFF0000E6 +:1084F000000000000000000000000000000000007C +:10850000AAAAAAAA00000000FFFF000000000000C5 +:10851000000000000000000000000000AAAAAAAAB3 +:1085200000000000FFFF000000000000000000004D +:1085300037040000000000000000180000000000E8 +:10854000FE2A0100D2040000FF000000985600201F +:10855000BC4F002000000000EC7F000883040000F6 +:10856000F77F000850040000058000080096000016 +:108570000000080096000000000800000400000051 +:108580004C83000800000000000000000000000014 +:0C859000000000000000000000000000DF +:00000001FF diff --git a/Tools/bootloaders/CubeOrange-ODID_bl.bin b/Tools/bootloaders/CubeOrange-ODID_bl.bin index a63483ca2decfd..045fd1e445e7cc 100755 Binary files a/Tools/bootloaders/CubeOrange-ODID_bl.bin 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 index 5e40768ac46987..57942b84e4d0a5 100755 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 index ac844a7f4858e4..260a13e82cd169 100644 --- a/Tools/bootloaders/CubeOrange-bdshot_bl.hex +++ b/Tools/bootloaders/CubeOrange-bdshot_bl.hex @@ -1,1105 +1,2516 @@ :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 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008ED7600089E +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008F9850008258600088D +:10006000518600087D860008A98600080946000818 +:10007000314600085D46000889460008B54600087C +:10008000DD46000809470008E3020008E302000813 +:10009000E3020008E3020008E3020008D586000836 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008C1870008D587000892 +:1000E00039870008E3020008E3020008E302000881 +:1000F000E3020008E3020008E302000835470008B5 +:10010000E3020008AD870008FD870008E30200084D +:10011000E3020008E3020008E3020008E30200082B +:100120006147000889470008B5470008E147000813 +:100130000D480008E3020008E3020008E30200089B +:10014000E3020008E3020008E3020008E3020008FB +:1001500035480008614800088D480008E30200089F +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008D9820008E3020008E302000855 +:10018000E3020008E3020008E9870008E302000830 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008C5820008E3020008E302000809 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F030FA3F +:1003500006F0A4FB4FF055301F491B4A91423CBFA9 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F048FA06F002FC0C +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F030BA000600200022002035 +:1003D0000000000808ED00E00000002000060020FA +:1003E000A09C000800220020742200207822002017 +:1003F00034670020E0020008E0020008E002000884 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F01AF9FEE706F0DA +:1004300073F800DFFEE7000053B94AB9002908BF8E +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000FFF901F0AFFB06F0BFFE054606F0C4FF5F +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F0B7FE0CB137 +:1007700000F078F801F036FB00F026FD08B100F03B +:1007800071F8284600F01CF9F9E70025ECE705466A +:10079000EAE700BF010007B008B501F09DF9A0F13C +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0ADF903B05DF804FB19 +:1007C00038B5302383F31188174803680BB106F05E +:1007D0002BF80023154A4FF47A71134806F01AF8E3 +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F056FA3223636082 +:100810002B78032B07D163682BB9022001F04CFA27 +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F02BBA0220C0 +:1008500001F01EBA024B00225A607047902200201D +:1008600098230020F8B5504B504A1C4619680131B6 +:1008700000F0998004339342F8D162684C4B9A425D +:1008800040F291804B4B9B6803F1006303F500330A +:100890009A4280F08880002001F06CF90220FFF776 +:1008A000CBFF454B0021D3F8E820C3F8E810D3F87C +:1008B0001021C3F81011D3F81021D3F8EC20C3F89D +:1008C000EC10D3F81421C3F81411D3F81421D3F881 +:1008D000F020C3F8F010D3F81821C3F81811D3F89A +:1008E0001821D3F8802042F00062C3F88020D3F8AA +:1008F000802022F00062C3F88020D3F88020D3F853 +:10090000802042F00072C3F88020D3F8802022F0CB +:100910000072C3F88020D3F8803072B64FF0E02325 +:10092000C3F8084DD4E90004BFF34F8FBFF36F8FB6 +:10093000224AC2F88410BFF34F8F536923F48033E7 +:100940005361BFF34F8FD2F8803043F6E076C3F3A4 +:10095000C905C3F34E335B0103EA060C29464CEA92 +:1009600081770139C2F87472F9D2203B13F1200F5C +:10097000F2D1BFF34F8FBFF36F8FBFF34F8FBFF332 +:100980006F8F536923F4003353610023C2F8503250 +:10099000BFF34F8FBFF36F8F302383F311888546EA +:1009A00080F308882047F8BD0000020820000208F4 +:1009B000FFFF0108002200200044025800ED00E083 +:1009C0002DE9F04F93B0B44B2022FF2100900AA8EC +:1009D0009D6801F0B1F9B14A1378A3B90121B0487B +:1009E00011700360302383F3118803680BB105F0A5 +:1009F0001BFF0023AB4A4FF47A71A94805F00AFFA8 +:100A0000002383F31188009B13B1A74B009A1A604F +:100A1000A64A1378032B03D000231370A24A536015 +:100A20004FF0000A009CD3465646D146012001F003 +:100A300039F924B19C4B1B68002B00F02682002062 +:100A400001F04AF80390039B002BF2DB012001F038 +:100A50001FF9039B213B1F2BE8D801A252F823F07A +:100A6000E10A0008090B00089D0B00082D0A000888 +:100A70002D0A00082D0A00082F0C0008FF0D0008A1 +:100A8000190D00087B0D0008A30D0008C90D000812 +:100A90002D0A0008DB0D00082D0A00084D0E000885 +:100AA000810B00082D0A0008910E0008ED0A0008CD +:100AB000810B00082D0A00087B0D00082D0A000894 +:100AC0002D0A00082D0A00082D0A00082D0A00082A +:100AD0002D0A00082D0A00082D0A00089D0B0008A9 +:100AE0000220FFF759FE002840F0F981009B022107 +:100AF00005A8BAF1000F08BF1C4641F21233ADF849 +:100B0000143001F007F891E74FF47A7000F0E4FF39 +:100B1000071EEBDB0220FFF73FFE0028E6D0013F77 +:100B2000052F00F2DE81DFE807F0030A0D1013360F +:100B30000523042105A8059300F0ECFF17E004212C +:100B40005548F9E704215A48F6E704215948F3E7E4 +:100B50004FF01C08404608F1040801F00DF804218C +:100B6000059005A800F0D6FFB8F12C0FF2D10120B6 +:100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F +:100B800001F026F926B10BF00B030B2B08BF002454 +:100B9000FFF70AFE4AE704214748CDE7002EA5D01B +:100BA0000BF00B030B2BA1D10220FFF7F5FD07463D +:100BB00000289BD00120002600F0DCFF0220FFF778 +:100BC0003BFE1FFA86F8404600F0E4FF0446B0B151 +:100BD000039940460136A1F140025142514100F0D3 +:100BE000E9FF0028EDD1BA46044641F21213022172 +:100BF00005A83E46ADF8143000F08CFF16E72546F8 +:100C00000120FFF719FE244B9B68AB4207D9284609 +:100C100000F0B2FF013040F067810435F3E70025B2 +:100C2000224BBA463E461D701F4B5D60A8E7002E62 +:100C30003FF45CAF0BF00B030B2B7FF457AF02209C +:100C4000FFF7FAFD322000F047FFB0F10008FFF691 +:100C50004DAF18F003077FF449AF0F4A08EB0503C7 +:100C6000926893423FF642AFB8F5807F3FF73EAFC0 +:100C7000124BB845019323DD4FF47A7000F02CFF3E +:100C80000390039A002AFFF631AF039A0137019BC4 +:100C900003F8012BEDE700BF002200209423002081 +:100CA00078220020C107000898230020902200200D +:100CB00004220020082200200C2200209422002080 +:100CC000C820FFF769FD074600283FF40FAF1F2D2E +:100CD00011D8C5F120020AAB25F003008449424532 +:100CE000184428BF4246019201F000F8019AFF2102 +:100CF0007F4801F021F84FEAA803C8F387027C4936 +:100D00002846019301F020F8064600283FF46DAF15 +:100D1000019B05EB830533E70220FFF73DFD00282B +:100D20003FF4E4AE00F064FF00283FF4DFAE00279C +:100D3000B846704B9B68BB4218D91F2F11D80A9B2D +:100D400001330ED027F0030312AA134453F8203CBA +:100D500005934046042205A9043701F003F98046B3 +:100D6000E7E7384600F008FF0590F2E7CDF8148079 +:100D7000042105A800F0CEFE02E70023642104A8A8 +:100D8000049300F0BDFE00287FF4B0AE0220FFF710 +:100D900003FD00283FF4AAAE049800F01FFF059061 +:100DA000E6E70023642104A8049300F0A9FE0028CC +:100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 +:100DC000049800F00DFFEAE70220FFF7E5FC002899 +:100DD0003FF48CAE00F01CFFE1E70220FFF7DCFCE3 +:100DE00000283FF483AE05A9142000F017FF074642 +:100DF0000421049004A800F08DFE3946B9E73220A2 +:100E000000F06AFE071EFFF671AEBB077FF46EAE00 +:100E1000384A07EB0903926893423FF667AE022017 +:100E2000FFF7BAFC00283FF461AE27F003074F44F8 +:100E3000B9453FF4A5AE484609F1040900F09CFE0F +:100E40000421059005A800F065FEF1E74FF47A70E3 +:100E5000FFF7A2FC00283FF449AE00F0C9FE0028CD +:100E600044D00A9B01330BD008220AA9002000F0CD +:100E70006BFF00283AD02022FF210AA800F05CFF77 +:100E8000FFF792FC1C4805F0F1FB13B0BDE8F08FB2 +:100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 +:100EA0000023642105A8059300F02AFE07460028C8 +:100EB0007FF41CAE0220FFF76FFC804600283FF451 +:100EC00015AEFFF771FC41F2883005F0CFFB0598B5 +:100ED00000F0C6FF46463C4600F07AFFA6E506460F +:100EE0004EE64FF0000901E6BA467EE637467CE65C +:100EF0009422002000220020A086010070470000FC +:100F000070470000704700002DE9F04100F5803780 +:100F1000044616463B7C5BB9C0681030204400F0A4 +:100F2000E5FEE5683544B5F5004FE56002D816B139 +:100F3000BDE8F081DEB905F07F0605F11000002163 +:100F4000C6F180062044F6B232462E4400F0F4FE8C +:100F5000A06804F11008324600F10060414600F537 +:100F6000003006F05DF830B901233B74E0E74FF440 +:100F700000463546ECE7A26805F1100140463244D0 +:100F80002144A260E268521BE26000F0AFFE022042 +:100F9000BDE8F04100F090BE183000F0E9BC000060 +:100FA00010B5044600F0FAFF204610BD10B5044607 +:100FB00000F0F4FF204610BDC3B280B2A3F141029D +:100FC000052A02D8373800B27047613B052B94BF21 +:100FD00057383038F7E70000F8B50446154608469C +:100FE00003220C4900F08CFE014688B908346F1CBE +:100FF00015F91100FFF7E0FF064617F9110001315E +:10100000FFF7DAFF102940EA061004F8010BEFD1D0 +:10101000F8BD00BF509200082DE9F04FADF53F7DBF +:101020000746416801222AA802F09AFE002840F0F3 +:1010300087800646824681461125DFF80C81DFF85D +:101040000CB101AB4FF4805241462AA802F0E8FFF0 +:10105000002875D1019AB2F5805F71D8002A65D059 +:101060000446019A9442ECD2282D0FD008DC132DAF +:101070002DD01E2D39D0112D13D00134A4B2F0E79C +:10108000322D2DD0372D2FD02D2DF6D13B68121BB0 +:1010900008EB040138461B692D259847BDF804402C +:1010A000EBE7121B022A09D9594608EB040000F0AD +:1010B00027FE18B902342825A4B2DEE718F8043058 +:1010C0003A2B3DD00A2B1CBFA1461325D5E718F8B3 +:1010D00004300A2B34D03A2B04BFA2463225CCE789 +:1010E00018F80430202BC8D0264618F804300A2BF4 +:1010F0001AD1AAEB090208EB090102A811254F2A0F +:1011000028BF4F2208F090F8A21B08EB060116A892 +:101110004F2A28BF4F2208F087F83B6816AA02A979 +:10112000DB6838469847A8E71E25A6E73B6838469F +:1011300004491B69984701200DF53F7DBDE8F08FFC +:101140000020F9E752930008A023002054920008E1 +:1011500000F1180110B5044686B00846019100F070 +:10116000F1FB2046FFF758FF60B1019902A800F09B +:1011700049FC102204F1080102A808F015F8B0FAA1 +:1011800080F0400906B010BD70B504460025EEB2EF +:10119000304600F0FFFC58B100213046013500F028 +:1011A00009FD08B9002070BD022000F085FDEEE7C2 +:1011B0002046FFF731FF0028F4D004F58034207C6E +:1011C00080F00100EFE70000F0B5C9B006F094F937 +:1011D00000F000FF18B90025284649B0F0BD694667 +:1011E0002A4802F0DFFF00284BD1294C204603F0AB +:1011F00009F8284803F006F8274803F003F82146C9 +:10120000224803F07BF80028E5D1702000F0C0FEF2 +:10121000064610B1214B44600360336830469B683A +:101220009847054600282ED01A4F1948394603F032 +:1012300065F805460028CED1194800F0A9FE0446FD +:1012400038B1184B4760036000F58033C0E90255A0 +:101250001D74236820469B689847054628B10E49AF +:101260000C4803F04BF80028B5D1336830465B6872 +:1012700098471CB1236820465B68984700F092FEAF +:10128000AAE70025FAE70446EFE700BF58920008F6 +:10129000689200087F92000895920008B8920008B2 +:1012A00014000100D49200082DE9F04FD44A8DB00B +:1012B0000B68D0F804A001931A440368D14E1A4475 +:1012C000D1F81C90DFF8B4C3DFF8B4B3D0E902342E +:1012D000634003EA0A03634013444A6802920AEB3C +:1012E0007363029CC84A2244C468224484688AEA20 +:1012F00004051D40654015448A68039203EB35558B +:10130000039CC24A2244846822448AEA03042C4093 +:1013100084EA0A041444CA6805EBF43404921644BF +:1013200083EA0502224056445A4032440E6905962B +:1013300004EBB222059FB64E3E441E4485EA0403E8 +:1013400013406B4033444E69069602EB7363069F6D +:10135000B04E3E442E4484EA02051D4065403544AB +:101360008E69079603EB3555079FAB4E3E442644E6 +:1013700082EA03042C4054403444A84E4E4405EB0A +:10138000F434164483EA050222405A4032440E6A7D +:10139000089604EBB222089FA14E3E441E4485EA03 +:1013A000040313406B4033444E6A099602EB7363A7 +:1013B000099F9C4ED1F830E03E44D1F83880F34488 +:1013C0002E4484EA02051D40654035448E6AA6F528 +:1013D000244703EB35550A964F3F274482EA03041E +:1013E0002C4054403C44CF6A0B9705EBF4340B9EE1 +:1013F0008D4F3744029E174483EA050222405A402B +:101400003A448A4F774404EBB2221F4485EA04032E +:1014100013406B403B444F6BBC4402EB7363654429 +:1014200084EA020C0CEA030C8CEA040C6544DFF835 +:1014300054C2C44403EB3555A44482EA03042C404F +:1014400054406444D1F83CC0794905EBF43461441C +:10145000114483EA050222405A400A44754904EBCC +:10146000B2223144079E194484EA02032B406340B0 +:101470000B44714902EBF36331440B9E0D4482EA45 +:1014800003012140514029446C4D03EBF151354497 +:10149000019E254483EA010414405C402C44684DBD +:1014A00001EBB4443544069E154481EA04021A4017 +:1014B0004A402A44634D04EB323235440A9E1D44AF +:1014C00084EA02030B4063402B445F4D02EBF3635D +:1014D0003544059E0D4482EA0301214051402944D0 +:1014E0005A4D03EBF1516544254483EA010414404D +:1014F0005C402C44564D01EBB4443544099E1544E0 +:1015000081EA04021A404A402A44524D04EB323226 +:101510003544049E1D4484EA02030B4063402B447F +:101520004D4D02EBF36345440D4482EA0301214033 +:1015300051402944494D03EBF1513544089E2C4458 +:1015400083EA010515405D402C44454D01EBB44450 +:101550003544039E2A4481EA04051D404D402A4437 +:10156000404D04EB32323D442B4484EA020593445F +:101570000D4065402B443C4D02EBF3633544069E21 +:10158000294482EA0305254055402944374D03EBA1 +:10159000F1514D442C4483EA010515405D4025443A +:1015A00001EBB54581EA050404EA03024A405A44C6 +:1015B000A6F5B82B089E05EB3232ABF2BE6B544059 +:1015C0005B4423442A4C344402EB33730B9E0C449B +:1015D00085EA020159402144264C344403EB715101 +:1015E000029E254482EA03044C402544224C444494 +:1015F00001EB3545144483EA01026A40224443E08A +:1016000078A46AD7EECEBDC156B7C7E8DB702024F8 +:10161000AF0F7CF52AC68747134630A8019546FDD3 +:10162000D8988069AFF7448BBED75C892211906B44 +:101630002108B44962251EF640B340C0515A5E26C7 +:10164000AAC7B6E95D102FD65314440281E6A1D88B +:10165000C8FBD3E7E6CDE121D60737C3870DD5F424 +:10166000ED145A4505E9E3A9F8A3EFFCD9026F6729 +:1016700081F6718722619D6D0C38E5FD937198FDAF +:101680008A4C2A8D8E4379A6934C344405EB722202 +:10169000059E1C4481EA0503534023448F4C344487 +:1016A00002EB33730A9E0C4485EA0201594021443F +:1016B0008B4C4C4403EB7151254482EA03044C40AB +:1016C0002C44884D354401EB3444019E154483EA93 +:1016D000010262402A44844D3D4404EB72221D44C1 +:1016E00081EA040353402B44804D354402EB3373AD +:1016F000049E294484EA02055D4029447C4D35441A +:1017000003EB7151079E254482EA03044C402C44AC +:10171000784D354401EB3444099E2A4483EA01059F +:1017200065401544744A324404EB7525039E134406 +:1017300081EA04026A401A44704B734405EB32722A +:101740000B4484EA0501514019446D4B634402EB9C +:1017500071511C4485EA02034B401C44694B3344DD +:1017600001EB3444019E1D4482EA010363402B4493 +:10177000654D04EB73233544069E154463EA01026C +:1017800062402A44614D03EBB2624D4462EA0409AF +:1017900029445F4D89EA0309454449442C445D4D81 +:1017A00002EBB1513544049E61EA03081D4488EA06 +:1017B0000208444401EB744464EA02034B402B44A6 +:1017C000554D04EBF323754463EA010E15448EEA8C +:1017D000040E0EEB0502514D03EBB262354462EA92 +:1017E000040E29440A9D8EEA030EA5F580164C4D81 +:1017F0007144A6F6833602EBB151264461EA030434 +:1018000054403444029E01EB7444354464EA0206B9 +:101810001D444E407319089E424D04EBF32335449A +:1018200063EA01061544664072193F4D03EBB2624C +:10183000654462EA040629443C4D5E403144079EFB +:1018400002EBB151354461EA03062C44384D564051 +:101850003D443444059E1D4401EB744464EA020394 +:101860004B402B44334D04EBF32335440B9E15447E +:1018700063EA010262402A442F4D03EBB262354411 +:10188000039E0D4462EA0401594029442B4D02EBAA +:10189000B15135442A4E254461EA030454402C4496 +:1018A000099D01EB74442E4464EA02051E4485EA56 +:1018B00001039D1903681A440AEB040303EBF523A3 +:1018C0000260436083681C44C36819448460C1603B +:1018D0000DB0BDE8F08F00BF44EABEA4A9CFDE4B37 +:1018E000604BBBF670BCBFBEC67E9B28FA27A1EA40 +:1018F0008530EFD4051D880439D0D4D9E599DBE6CD +:10190000F87CA21F6556ACC4442229F497FF2A43F1 +:10191000A72394AB39A093FCC3595B6592CC0C8F81 +:10192000D15D84854F7EA86FE0E62CFE144301A3B1 +:10193000A111084E827E53F735F23ABDBBD2D72AA9 +:1019400091D386EB094B036003F18833436003F1C5 +:101950002943A3F59613A3F68B638360A3F1883321 +:10196000C3600023C0E90433704700BF012345670B +:101970002DE9F8431446026905460E46E300C2F31A +:10198000C50800F118079B18036122BF43690133A2 +:10199000436112F4FC7F436903EB5473436114D039 +:1019A000C8F1400907EB08004C4504D22246BDE8C7 +:1019B000F84307F009BC403C4A464E4407F004FC9B +:1019C000444439462846FFF76FFCA04606EB04095D +:1019D000B8F13F0FA9EB08010AD94022384607F0B9 +:1019E000F3FB39462846A8F14008FFF75DFCEFE716 +:1019F000A1096FF03F02384602FB014206EB81115C +:101A0000D5E7000070B50B6901F1180506460C46D4 +:101A1000C3F3C503EA18501C8022EA54C3F13F0205 +:101A2000072A1FD8002100F087F929462046FFF732 +:101A30003BFC38220021284600F07EF92369294624 +:101A40002046236563696365FFF72EFC214610225B +:101A5000304607F0B9FB204658220021BDE870400F +:101A600000F06AB9C3F137020021E5E72DE9F84F2C +:101A70004FF47A7306460D46002402FB03F7DFF8A5 +:101A80005080DFF8509098F900305FFA84FA5A1CC1 +:101A900001D0A34210D159F824002A4631460368E8 +:101AA000D3F820B03B46D847854205D1074B0120EB +:101AB00083F800A0BDE8F88F0134042CE3D14FF483 +:101AC000FA7004F0D3FD0020F4E700BFE4330020F7 +:101AD0001022002014220020002307B50246012115 +:101AE0000DF107008DF80730FFF7C0FF20B19DF81A +:101AF000070003B05DF804FB4FF0FF30F9E700008A +:101B00000A46042108B5FFF7B1FF80F00100C0B21A +:101B1000404208BD074B0A4630B41978064B53F8CB +:101B20002140014623682046DD69044BAC4630BCA9 +:101B3000604700BFE433002014220020A08601008B +:101B400070B50A4E00240A4D05F00EFA3080286860 +:101B50003388834208D905F003FA2B680444013323 +:101B6000B4F5003F2B60F2D370BD00BFE633002018 +:101B7000A033002005F0C6BA00F1006000F5003087 +:101B80000068704700F10060920000F5003005F039 +:101B900047BA0000054B1A68054B1B889B1A834205 +:101BA00002D9104405F0DCB900207047A0330020B2 +:101BB000E633002038B50446074D29B12868204493 +:101BC000BDE8384005F0E4B92868204405F0CEF9B6 +:101BD0000028F3D038BD00BFA0330020002070479C +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7BFBF0120704700BFA43300207E +:101C1000014B1868704700BF0010005C194B013879 +:101C20000322084470B51D68174BC5F30B042D0C37 +:101C30001E88A6420BD15C680A46013C82421346CC +:101C40000FD214F9016F4EB102F8016BF6E7013AB9 +:101C500003F10803ECD181420B4602D22C2203F897 +:101C6000012B0424094A1688AE4204D1984284BF4D +:101C7000967803F8016B013C02F10402F3D1581A83 +:101C800070BD00BF0010005C2422002014930008E7 +:101C9000022803D1024B4FF080529A61704700BF77 +:101CA00000100258022803D1024B4FF480529A616F +:101CB000704700BF00100258022804D1024A53693D +:101CC00083F48053536170470010025870B5044686 +:101CD0004FF47A764CB1412C254628BF412506FBAE +:101CE00005F0641B04F0C2FCF4E770BD002310B5DE +:101CF000934203D0CC5CC4540133F9E710BD00001B +:101D0000013810B510F9013F3BB191F900409C42F8 +:101D100003D11AB10131013AF4E71AB191F9002067 +:101D2000981A10BD1046FCE703460246D01A12F975 +:101D3000011B0029FAD1704702440346934202D0A6 +:101D400003F8011BFAE770472DE9F8431F4D1446CD +:101D50000746884695F8242052BBDFF870909CB364 +:101D600095F824302BB92022FF2148462F62FFF737 +:101D7000E3FF95F824004146C0F1080205EB80001E +:101D8000A24228BF2246D6B29200FFF7AFFF95F8D5 +:101D90002430A41B17441E449044E4B2F6B2082E2B +:101DA00085F82460DBD1FFF723FF0028D7D108E0B6 +:101DB0002B6A03EB82038342CFD0FFF719FF002881 +:101DC000CBD10020BDE8F8830120FBE7A43300203D +:101DD000024B1A78024B1A70704700BFE4330020A0 +:101DE00010220020F8B5194C194803F047FF21468E +:101DF000174803F06FFF24684FF47A70154ED4F83B +:101E00009020154DD2F80438114F43F00203C2F868 +:101E10000438FFF75BFF2046104904F069F8D4F856 +:101E200090200424D2F8043823F00203C2F80438C6 +:101E30004FF4E133336055F8040BB84202D0314619 +:101E400003F07AFE013CF6D1F8BD00BF149B0008F8 +:101E500018490020CC330020142200201C9B0008CD +:101E60000C4B70B50C4D04461E780C4B55F82620D3 +:101E70009A420DD00A4B002118221846FFF75CFF4A +:101E80000460014655F82600BDE8704003F054BEDA +:101E900070BD00BFE4330020142200201849002048 +:101EA000CC330020F8B571B6002301201A4619463C +:101EB00002F094FD0446802005F0C4F9002849D0C2 +:101EC0000025254A80274FF4D06C3D26136913F076 +:101ED000C06F26D1D2F8103113F0C06F21D1236822 +:101EE00005F1006199602368D86023685F6023680A +:101EF000C3F800C021680B6843F001030B60216840 +:101F00000B6823F01E030B6021680B68DB07FCD411 +:101F1000237B8035616806FA03F3B5F5001F0B607B +:101F2000D4D1204602F09AFDB5F5001F11D000244F +:101F30000A4E0B4D012005F0E5F83388A34205D980 +:101F400028682044013405F023F8F6E7002005F066 +:101F5000D9F861B6F8BD00BF00200052E63300207A +:101F6000A033002030B50A44084D91420DD011F83D +:101F7000013B5840082340F30004013B2C4013F080 +:101F8000FF0384EA5000F6D1EFE730BD2083B8EDBF +:101F90000121884238BF084605F08CB908B105F028 +:101FA0008DB9704710B5084C01220849002001F096 +:101FB000B3FE23783BB1064803F036FD044803F036 +:101FC00069FD0023237010BDE8330020249300082E +:101FD000C83600201D482DE9F041036D2BB90122C0 +:101FE0004FF48051503005F0C9FA194E33780BB1D7 +:101FF000FFF7D8FF0324174F4FF00008134D154982 +:102000002846C7F8048003F037FD284603F070FB2C +:1020100048B1013C284603F03DFD14F0FF04EED129 +:10202000204634700FE00C4901220C4801F074FE88 +:10203000014618B1284603F0F7FCEAE7084800F02B +:1020400011F801203070BDE8F08100BFC8360020D3 +:10205000E83300203C22002024930008EC330020C9 +:10206000289300080FB4002004B070470068704740 +:1020700003460068596870470B0A017043700B0CE7 +:10208000090E8370C1707047110A027003714170AC +:10209000110C120E8170C2701A0A42711A0C1B0EBA +:1020A0008271C37170470000C36A0239023B8B42E0 +:1020B00083BF4389006C01FB0300002070470000D0 +:1020C000C2F307238A76CB760378032B01BF120C69 +:1020D0000A75120A4A75704700F10B010022D301FC +:1020E00043EA520310F8012B52FA83F38842DAB222 +:1020F000F5D110467047000010B541780446002025 +:10210000013102464901022A16BFA35C032203EBF8 +:10211000C03302F101021EBF9BB203EB500398B221 +:102120009142F0D810BD000002684AB1134613F87E +:10213000011B1F290DD93A29F9D1911C8B4202D0DC +:102140004FF0FF3070471278302AF9D10360002039 +:102150007047014B187870473836002038B50D4667 +:10216000044618B9092000232B6038BD0368002BF2 +:10217000F8D01A78002AF5D08188DA889142F1D116 +:10218000587804F00FFC10F00100EBD12368EBE766 +:1021900038B50D4640F25231144602F0B9F9FF2825 +:1021A00007D9012C0BD9030A022468702B70204632 +:1021B00038BD30B1002CFAD001242870F7E7002494 +:1021C000F5E70446F3E700002DE9F8430026D0F8D0 +:1021D000008005460C468E76836B002B4AD098F81B +:1021E0000030042B4BD133463546402720E0B7F56D +:1021F000187F80F0C480F90606F1010608BF023797 +:10220000D05B02372BB900F5205292B2B2F5006FC5 +:102210000DD305F11A01C5F1FF0240EA0340214444 +:10222000FFF7B6FF002800F0AA800544002003460F +:10223000D8F8102092F82310B142D8D8002B40F0E3 +:102240009E80002D00F09B8000232544AB766373B5 +:10225000D8F81020137903F03701DB0621730BD473 +:1022600002F13800FFF704FFC4E90001938963819C +:10227000D3892381BDE8F88300200146F4E7C36CCD +:1022800001335ED1EA6B00232E26551E184615F841 +:10229000011F013020290CD0052908BFE52109289C +:1022A00004D10B2B9EBFE71801337E73E71801336F +:1022B00079730B28EBD1E11800204873A17E002927 +:1022C0004BD1002B40D06FF00C0604F10D00082517 +:1022D000361B331810F8011B002938D02E298BB279 +:1022E0004AD0A3F14101192903D8117B0D4200D036 +:1022F00020330373EDE7B9F1000F05D100F520534A +:102300009BB2B3F5006F0BD307F11A01C7F1FF02BF +:1023100040EA09402144FFF73BFF48B10744002051 +:1023200002368146D8F80C30985B0028E3D1384655 +:10233000B9F1000F4FF0000218BF002023189A7661 +:10234000A0E7B1463746EDE73F23A37601232344B8 +:1023500000219976137B03B96373D37A02F11C00D1 +:1023600003F03F0323730023FFF780FE20606360C8 +:10237000D38A6381138B7CE710250B46B9E73F2393 +:102380000125A37660E7000038B50546002435F83E +:10239000020B08B9204638BD02F0EEF86308C2B25D +:1023A00003EBC43312FA83F39AB2C0F3072303EBAF +:1023B000520303EBC2339CB2E9E7000037B5C378A0 +:1023C00004461BB90025284603B030BD00F14C017E +:1023D000826C01234078019104F00AFB054680B924 +:1023E000A36BE070A06C226BC31A9342EAD2A3786D +:1023F0000199022BE6D102440123607804F0F8FA37 +:10240000E1E70125DFE7000038B5836C05460C469F +:102410008B4210D0FFF7D2FF60B92246012305F1AD +:102420004C01687804F0C0FA00281CBF4FF0FF345C +:102430000120AC6438BD0020FCE7000038B5002363 +:102440000446C3704FF0FF338364FFF7DDFF0028BD +:102450004BD1B4F84A524AF655239D4207D10B227C +:10246000254904F14C0006F09FFE00283FD094F867 +:102470004C30EB2B03D01833DBB2012B2ED84AF6AD +:1024800055239D4206D108221C4904F19E0006F006 +:102490008BFE48B3B4F85730B3F5007F1ED194F8E3 +:1024A0005930DBB15A1E1A4218D1B4F85A30ABB1C8 +:1024B00094F85C30013B012B10D8B4F85D306BB15F +:1024C000B4F85F307F2B06D804F16C00FFF7CEFD27 +:1024D000B0F5803F02D3B4F8623053B94AF65520C4 +:1024E00085420CBF0220032038BD0420FCE70120F8 +:1024F000FAE70020F8E700BF549300086093000853 +:1025000002392DE9F04701F007044FF0010A466C4B +:1025100005460AFA04F41746984606EB1136C1F34D +:10252000C809E4B2314628460136FFF76DFF18B1FD +:102530000120BDE8F087994605EB090292F84C307E +:10254000234214BF01210021414513D06340013FC4 +:1025500082F84C3085F803A0EBD0640014F0FF043F +:10256000EAD109F1010301244FF00009B3F5007F1E +:10257000E1D1D7E70220DCE701290246F8B50C4695 +:1025800040F28C800668F36A8B4240F28780337891 +:10259000013B032B00F28280DFE803F00229384B75 +:1025A00004EB5405B16B304601EB5521FFF72CFFCE +:1025B00010B14FF0FF30F8BD6F1CC5F30805B16BCB +:1025C0003046354401EB572195F84C50FFF71CFF7E +:1025D0000028EED1C7F30807E3073E4496F84C0005 +:1025E00045EA00204CBF0009C0F30B00E3E7B16BE4 +:1025F000304601EB1421FFF707FF0028D9D1640012 +:1026000004F4FF742644B6F84C00D4E7B16B3046AE +:1026100001EBD411FFF7F8FE0028CAD1A40006F19F +:102620004C0004F4FE742044FFF720FD20F07040BD +:10263000C1E7D0E90430D57953EA000101D09168AF +:1026400001B95DBB9168022DA4EB01010DD1013BE5 +:10265000728940F1FF305B0A43EAC053B3FBF2F3E7 +:1026600099421BD81CD0601CA5E7032D02D19369A9 +:102670008B42F8D8D3699BB9B16B304601EBD411CA +:10268000FFF7C2FE002894D1A0004C3600F4FE7083 +:102690003044FFF7EBFC20F000408CE701208AE794 +:1026A0006FF0004087E70000F8B5066804460D4665 +:1026B0003378042B0CBF4FF080524FF400128A4243 +:1026C00001D80220F8BDCA06FBD182680163D2B9E5 +:1026D000022B13D83389B3EB551FF2D9F36BA363E5 +:1026E000A36B6263002BECD003EB55234C36C5F390 +:1026F00008050020A3633544E563E3E7F36BC2718B +:10270000002BE7D01A4677897F02BD42114604D2DA +:102710003046FFF7C9FCA063E2E72046FFF72CFF35 +:10272000431C024606D00128CBD9F36A8342C8D99C +:10273000ED1BEAE70120C5E701292DE9F047064630 +:102740000C46174608D9C36A8B4205D90378022B79 +:1027500062D003D8012B22D0022552E0033B012B8B +:10276000FAD8816B01EBD411FFF74EFE0546002825 +:1027700047D1A40006F14C0304F4FE741C443378E2 +:10278000042B07D0204627F07047FFF76FFC00F0BE +:102790007040074339462046FFF76EFC2FE001EBFF +:1027A0005108816B01EB5821FFF72EFE054640BB17 +:1027B00014F0010406F14C0908F1010AC8F30808F5 +:1027C00008BFFBB230461FBF19F8083003F00F02F4 +:1027D0003B0103F0F00318BF134309F8083001234D +:1027E000B16BF37001EB5A21FFF70EFE054640B9BD +:1027F000CAF3080A44B1C7F3071709F80A7001239E +:10280000F3702846BDE8F08719F80A30C7F30327AC +:1028100023F00F031F43F0E7816B01EB1421FFF757 +:10282000F3FD05460028ECD1640006F14C0304F4E6 +:10283000FF741F551919C7F307274F70DFE7000012 +:10284000F8B504460E461746E3690BB91846F8BDBD +:10285000012BA6EB0305206814BFAA1C3A46691C8D +:10286000FFF76AFF0028F2D1E369013BE361EBE780 +:1028700001292DE9F84306460C461746056802D89B +:102880000220BDE8F883EB6A8B42F9D97AB9A146F8 +:1028900021463046A046FFF76FFE0446B0B92B78BC +:1028A000042B02D1002F43D1F7710020E9E72B78E8 +:1028B000042B02D1C379022BE9D04FF0FF32394605 +:1028C0002846FFF739FF0028E1D0DAE70128D7D002 +:1028D000421C01D10120D4E72B78042B19D1EA6ADC +:1028E000AB69023A93421CD308F10102A2420CD018 +:1028F0002B78042B08D10023A2EB09024946284675 +:10290000FFF7FEFD0028BCD1A146EB6AA342BFD869 +:10291000C5E7002241462846FFF70EFF0028DED01B +:10292000AFE70133AB612B7943F001032B71DBE798 +:10293000F3798BB9B468BC4202D10223F371B4E7D6 +:1029400021463046FFF718FE012899D9431CC1D013 +:1029500001348442EFD0A8E7032BA6D1B368BB4271 +:10296000A3D8B2691344BB429FD3E6E770B5C379DD +:102970000446032B06D181688369CD18A94203D18F +:102980000023E371002070BD4E1C20683246FFF723 +:10299000D3FE0028F7D13146F0E700002DE9F743D8 +:1029A00005460191FFF70AFD0446002849D105F1CB +:1029B0004C09019928464FF40072FFF775FB214638 +:1029C000A86407464846FFF7B7F96C896402B4F576 +:1029D000004F28BF4FF40044B4F5007F2FD92046A4 +:1029E00004F070FC804630B122460021640A0026C3 +:1029F000FFF7A2F909E06408EEE72346BA19414659 +:102A0000687803F0F5FF18B926446B899E42F4D329 +:102A1000404604F067FC6889801B18BF012003B0A2 +:102A2000BDE8F08301366B899E42F4D20123BA19C6 +:102A30004946687803F0DCFF0028F3D0EBE7002676 +:102A4000F1E70120EBE70000F8B50446FFF7B6FC1C +:102A50000546002842D12378032B37D12779012F4F +:102A600034D104F14C0601464FF400723046FFF7B2 +:102A700063F955234122722184F84A32AA2304F5CE +:102A80000D7084F84F2084F84B32522384F83012B2 +:102A900084F84C3084F84D30612384F8311284F886 +:102AA0004E3084F83332A16984F83222FFF7E4FA19 +:102AB000616904F50E70FFF7DFFA626B3B46314641 +:102AC00001326078A26403F093FF257100226078E0 +:102AD000114603F0B1FF003818BF0120F8BD000017 +:102AE00000232DE9F0430B6085B00F461546FFF734 +:102AF0001BFB061EC0F2B281804B53F82640002C0F +:102B000000F0AE813C6005F0FE0523786BB1607883 +:102B100003F048FFC70708D41DB110F0040500D02A +:102B20000A25284605B0BDE8F0830023F0B22370E3 +:102B3000607003F023FFC10700F194810DB14207DB +:102B4000EED400212046FFF779FC022840F099805E +:102B50006E4604F2122304F2522132461846103314 +:102B6000FFF784FA42F8040B8B42F7D1002556F8A0 +:102B7000041B00297DD02046FFF760FC012879D88E +:102B80000128A26C40F0C08004F1570304F18C01CD +:102B900013F8015B002D7BD18B42F9D1B4F8B4302E +:102BA000B3F5807F74D194F8B830092B70D104F15B +:102BB0009400FFF75DFA4FF0FF33171841F1000161 +:102BC000BB4275EB010363D304F1A000FFF74EFA9B +:102BD00094F8BA302063012BA37059D194F8B990BE +:102BE00003FA09F91FFA89F36381002B50D0444B93 +:102BF00004F1A800FFF73AFA0646984248D8831C29 +:102C0000626304F1A400E362FFF730FA00EB02080C +:102C100004F19C00C4F84080FFF728FA10441FFA22 +:102C200089F2A06306FB02F313EB080345EB0502F0 +:102C30009F4271EB02032BD32E4604F1AC00FFF749 +:102C400015FAE06365B96389B34221D9E16B204687 +:102C5000FFF72AFA81192046FFF7D6FB98B901360B +:102C6000631993F84C30812B14D02035C5F3080537 +:102C7000E8E703200135042D7FF479AF042807D15C +:102C800001E0042801D101254BE701287FF678AF48 +:102C90000D2546E705F1140004F14C063044FFF71A +:102CA000E5F901280546F3D9E36A8342F0D9618941 +:102CB000821E236C02FB01336364A16B204601EB8F +:102CC000D511FFF7A1FB0028DDD105F07F0006EB51 +:102CD0008000FFF7CBF9431C03D00135A842ECD0AC +:102CE000D6E70425C4E90500064A257000251388A7 +:102CF000E56101339BB21380E38012E73C3600208C +:102D0000FDFFFF7F40360020B4F85730B3F5007F59 +:102D1000BED1B4F8626026B904F17000FFF7A6F9DD +:102D2000064694F85C302663591EA3700129AFD87B +:102D300094F859506581002DAAD0691E2942A7D167 +:102D4000B4F85D8018F00F0FA4F80880A0D1B4F893 +:102D50005F0018B904F16C00FFF788F9B4F85A1055 +:102D6000002995D006FB03FE01EB181CF4446045D6 +:102D70008ED3A0EB0C00A842B0FBF5F388D33E48FD +:102D8000834285D84FF6F57083426DD903259F1C89 +:102D9000114402EB0C03032DE7626263A163236419 +:102DA0004CD1B4F8763053EA08037FF471AFBB001E +:102DB00004F17800FFF75AF9E06303F2FF13B6EB72 +:102DC000532FFFF465AF4FF0FF33032DC4E90533F4 +:102DD0004FF08003237187D1B4F87C30012B83D16D +:102DE000511C2046FFF710FB00287FF47DAFB4F89C +:102DF0004A224AF6552320719A427FF475AF1F4B41 +:102E000004F14C00FFF732F998427FF46DAF03F103 +:102E1000FF5304F50C70FFF729F903F50053203335 +:102E200098427FF461AF04F50D70FFF71FF9A061C0 +:102E300004F50E70FFF71AF9606155E7B8F1000F5D +:102E40003FF426AF7144022D4FEA4703E1631EBFF2 +:102E5000D91907F0010303EB5103AEE70B2560E638 +:102E60000C255EE603255CE640F6F575AB428CBFAB +:102E7000022501258BE700BFF5FFFF0F525261418C +:102E80002DE9F84F07460568884649B96E69C6B10D +:102E9000EB6AB34298BF0126AB69A3B9002405E0F1 +:102EA000FFF76AFB0128044603D801242046BDE849 +:102EB000F88F421C00F0D280EB6A8342F6D8464677 +:102EC000EAE70126E8E72A78EB6A042A40F08380E3 +:102ED000A6F1020A023B4FF0010B9A4528BF4FF0C2 +:102EE000000AD146696C284601EB1931FFF78CFACC +:102EF00000283BD109F00703EA6AC9F3C8010BFABD +:102F000003F3901EDBB26A184C4609F1010992F8EE +:102F10004C20814502EA030233BF5B0000234FF4DB +:102F20000071DBB228BF9946B2B90234631E033385 +:102F3000BCD80123214628461A46FFF7E1FA0228A9 +:102F4000B3D0012800F08A80B8F1000F13D102231A +:102F5000FB710028A9D130E0CA450AD0002BD2D19C +:102F60000131B1F5007FBDD20123CCE74FF0FF3432 +:102F7000DCE70024DAE7FB79022B07D1731CA342BC +:102F8000E7D0BB68F31ABB610323FB7108F10102B0 +:102F9000FB69A24205D113B10133FB61D9E70223DA +:102FA000FBE70BB90123FB61224641463846FFF798 +:102FB00047FC00284FD10123FB61EA6AAB69023A62 +:102FC0006C6193429CBF03F1FF33AB612B7943F0FB +:102FD00001032B716AE7464514D1741C3846A3429D +:102FE00098BF02242146FFF7C7FA01283FF45DAFDE +:102FF000431C33D0E0B16B69012B03D9EA6A9342D9 +:1030000038BF1E4634460134EB6AA34203D8012E72 +:103010007FF644AF022421463846FFF7ADFA48B1A7 +:1030200001283FF442AF013018D0B442EBD135E76C +:10303000002CE7D04FF0FF3221462846FFF77CFBFB +:1030400048B9B8F1000FB8D0224641462846FFF7EC +:1030500073FB0028B1D001287FF427AF4FF0FF3475 +:1030600024E700002DE9F84306680446076B89460B +:1030700033782037042B0CBF4FF080534FF40013EC +:10308000BB429CBF00238363836B73B1C7F3080803 +:10309000B8F1000F3CD10133416B836339B93389F7 +:1030A000B3EB571F34D80023A36304200AE07389CD +:1030B000013B13EA57232BD1FFF75EFA012805469F +:1030C00002D80220BDE8F883421C01D10120F9E7B3 +:1030D000F36A834216D8B9F1000FE4D0616B204641 +:1030E000FFF7CEFE0546C8B10128EAD0431CEDD05B +:1030F00001463046FFF752FC0028E7D1E37943F060 +:103100000403E371294630466563FEF7CDFFA063F3 +:103110004C36002027634644E663D3E70720D1E717 +:10312000F8B50E46002104460768FFF7BDFA98B9C6 +:103130000546A16B3846FFF767F968B93A78E36B43 +:10314000042A1B780CD11B060ED50546012120460A +:10315000FFF788FF0028ECD0042808BF072006E00E +:10316000E52B01D0002BF0D10135B542EED1F8BDF1 +:10317000C16C4B1C2DE9F04104460568066B1FD15C +:10318000E5274FF00108A16B2846FFF73DF998B9F4 +:103190002A78E36B042A09BF1A781F7002F07F02B5 +:1031A0001A7085F80380236BB3420DD200212046AC +:1031B000FFF758FF0028E6D0042808BF022003E0EC +:1031C000FFF772FA0028DBD0BDE8F0812DE9F0416D +:1031D00005460068A96B0669FFF716F9044620B991 +:1031E000EB6B1A78852A03D002242046BDE8F081D3 +:1031F000324603F1200153F8040B8B4242F8040BD2 +:10320000F9D1777801377F01A7F16003B3F5007F2B +:10321000EAD800212846FFF725FF04280446E3D01A +:103220000028E2D1A96B2868FFF7EEF804460028D1 +:10323000DBD1EB6B1A78C02AD6D106F1200203F15C +:10324000200153F8040B8B4242F8040BF9D196F895 +:1032500023300F222C33B3FBF2F3B7EB431FC3D35E +:103260004FF0400800212846FFF7FCFE04280446E2 +:10327000BAD00028B9D1A96B2868FFF7C5F8044671 +:103280000028B2D1EB6B1A78C12AADD1B8F5187FFE +:1032900009D206EB080203F1200153F8040B8B421C +:1032A00042F8040BF9D108F120084745DAD8B8F5FF +:1032B000187F9AD83046FEF71FFF7388834294D058 +:1032C00092E700000B68002210B5036004460B6A09 +:1032D00083604B6AC261C37123F0FF03896AC0E94E +:1032E0000432C164FFF7E0F920B92046BDE8104080 +:1032F000FFF76CBF10BD0000F8B503680546012755 +:103300001C692046FEF7F8FEA070000A6678E0709F +:103310002846E96CFFF7C8F920B1022828BF02202F +:10332000C0B2F8BDA96B2868FFF76EF80028F4D189 +:10333000EB6B04F1200254F8041B944243F8041B85 +:10334000F9D12B68DF70002EE7D000212846013E1E +:10335000FFF788FEE0E700002DE9F8434FF0FF0893 +:1033600006460768042445464FF6FF79B16B11B94C +:10337000002C73D063E03846FFF746F80446002877 +:103380005DD1F06B0378002B6ED03A78042A11D10E +:10339000852B4DD1336B3046F364FFF717FF04469E +:1033A00000284CD13B691B7903F03F03B3712046E1 +:1033B000BDE8F883C27AE52B02F03F02B27143D038 +:1033C0002E2B41D022F0200108293DD00F2A40D1D8 +:1033D000590637D503F0BF05336B90F80D80F364C1 +:1033E000437B434530D1428B72BB03780D21FC688F +:1033F00023F04003DFF874E0013B4B4301211EF84A +:1034000001CB30F80CC009B3FF2B1DD824F813C032 +:103410006146013301320D2AF1D10278520605D5F9 +:1034200021B1FF2B10D8002224F81320013DEDB26A +:1034300000213046FFF716FE0446002896D00023F0 +:10344000B363B4E7AB42CBD0FF25F1E7CC45E1D085 +:10345000FAE72DB9FEF740FE404501D10024A6E76A +:103460004FF0FF33F364A2E70424E8E7FC9300087D +:103470002DE9F04F002187B00446D0F80090FFF707 +:1034800013F9804670B999F80030042B33D1D9F87C +:103490000C00FEF779FF07462046FFF75DFF054663 +:1034A00020B18046404607B0BDE8F08FD9F8103013 +:1034B0009A8CBA42F0D193F823B040265D4506D1EC +:1034C000D9F80C3033F81530002BE5D1EAE7F106D6 +:1034D000D9F8103008BF0236985B01F04DF8D9F8E2 +:1034E0000C30824633F8150001F046F88245D3D1FE +:1034F00002360135E2E74FF0FF0A4FF0FF3B554639 +:10350000C4F84CB0A16B4846FEF77EFF00285CD1A2 +:10351000E66B3778002F77D0F27AE52F02F03F0381 +:10352000A37103D0120704D50F2B04D0C4F84CB0FC +:103530004FE00F2B54D194F84B3058063FD4790606 +:1035400045D5236B07F0BF0796F80DA0E364737BA6 +:1035500053453ED1738B002B3BD135780121D9F8EF +:103560000C3005F03F0501930D23013D5D43284BD1 +:1035700013F8012BB25A71B3FF2D059329D81046C9 +:10358000049200F0F9FF6B1C03900293019B33F847 +:10359000150000F0F1FF039981421AD1049A029DAF +:1035A0001146059B1B4A9342E2D133785A0604D553 +:1035B00019B1019B33F815305BB97D1EEDB20021C6 +:1035C0002046FFF74FFD00289CD080466AE7BD42A9 +:1035D000BDD0FF25F3E74FF6FF708242E2D0F8E757 +:1035E0002DB93046FEF778FD50453FF45BAF94F8B7 +:1035F0004B30DB079AD40B2204F14001304605F032 +:10360000D3FD002892D14DE74FF004084AE700BFF0 +:10361000FC930008099400082DE9F04F90F84BB096 +:1036200099B004461BF0A00540F068810668F26876 +:1036300032F81530002B4AD13378042B40F08780C4 +:103640000F230E352046B5FBF3F5A91CFFF768FDE7 +:103650008146002877D1236B0135A3EB4515E3792B +:103660005A07E56435D523F004032046E371FFF7DC +:103670007DF950BB4FF0FF32616B2046FFF7E0F859 +:1036800018BBA3682BB3214604A8FFF71BFEE0B9C3 +:1036900070894FF40071D4E90423E0FB0123306901 +:1036A000C4E904233830FEF7EFFC3069D4E9042381 +:1036B0002830FEF7E9FCE379326904A843F00103FE +:1036C00082F82130FFF718FE18B181463BE0013542 +:1036D000AEE7D6E90354402200212046FEF72CFB3A +:1036E0008523012140222370C0234FF0C10C04EB3D +:1036F000010884F8203000231E469E46571C04F81B +:1037000002C0F0B2023204F807E021B135F813101C +:1037100009B10133DBB20F0AA15408F8027002327A +:10372000D706F2D135F813700136002FE6D184F8B0 +:103730002330831C28466370FEF726FE84F824009D +:10374000000A84F82500484619B0BDE8F08F04F15E +:1037500040070DF1100A1BF0010F97E807008AE8F7 +:10376000070000F0D38040234FF0010884F84B306D +:10377000BC46F368B8F1050F9AE80700ACE803000F +:103780002CF8022B4FEA12428CF8002059D9981ECF +:10379000424630F8021F002942D10DF10F0C0721DB +:1037A00002F00F0E914612090EF13000392888BF41 +:1037B0000EF1370001390CF8010902D0B9F10F0FF1 +:1037C000EED818AB7E205A1802F8580C3846002262 +:1037D000914206D010F801CB02F1010EBCF1200F8E +:1037E00031D104F13F0C072902F1010297BF18AB58 +:1037F00020205818013198BF10F8580C072A0CF8EF +:103800000200F0D92046FFF733FE8146002878D128 +:1038100008F10108B8F1640FAAD14FF0070992E747 +:103820004FF0100C01F0010E49080EEB4202D303D9 +:1038300044BF82F4883282F02102BCF1010CF1D144 +:10384000A7E74246A9E77246C2E7216B2046A1EBF3 +:103850004511FEF729FF814600287FF474AF4FF62B +:10386000FF783846FEF738FC0190A16B3046FEF732 +:10387000CBFD814600287FF466AFE36BE9B2019A85 +:103880004FF00D0CD6F80CE05A734FF00F02DFF832 +:10389000E0A0DA724A1E18730CFB02F28446987696 +:1038A000D87640451AF8019B0CF1010C18BF3EF880 +:1038B000120003EB090B18BF013203F809004FEAAD +:1038C0001029002808BF4046BCF10D0F8BF801906D +:1038D000E7D1404502D03EF812200AB941F040013C +:1038E0001970012300212046F370FFF7BBFB8146CE +:1038F00000287FF428AF013DB7D11BE04FF0060947 +:1039000021E704287FF41FAF84F84BB01BF0020FAF +:1039100020461BBF0C350D210125B5FBF1F518BF65 +:1039200001352946FFF7FCFB814600287FF40BAFE9 +:10393000013D8AD1A16B3046FEF766FD8146002825 +:103940007FF401AF01462022E06BFEF7F5F9E36B4F +:1039500003CF18605960BA7839889A72198194F83F +:103960004B30E26B03F0180313730123F370EAE6A4 +:10397000FC93000810B504460A463430FEF776FB87 +:10398000886004F13800FEF773FBC2E9040194F883 +:10399000213003F00203D3710023D36110BD000076 +:1039A00003284B8B04BF8A8A43EA024318467047B8 +:1039B0002DE9F04F0B7899B0044689462F2BD0F8AB +:1039C00000B001D05C2B09D14A46137891460132F0 +:1039D0002F2BFAD05C2BF8D0002301E0DBF81C3051 +:1039E000A3600023E3619BF80030042B1ED1A36881 +:1039F000E3B1DBF82030214604A82362DBF8243051 +:103A00006362DBF82830A362FFF75CFC0346002802 +:103A100054D1DBF8102002F13800FEF727FBC4E98F +:103A2000040392F8213003F00203E37199F80030A7 +:103A30001F2B00F2358180230021204684F84B3073 +:103A400019B0BDE8F04FFEF72FBE49460B78894606 +:103A500001312F2BFAD05C2BF8D01F2B8CBF002507 +:103A60000425012F2FD113882E2B31D1002322F8CA +:103A7000173004F140029F428CBF2E2120210133D8 +:103A80000B2B02F8011BF6D145F02005204684F8E7 +:103A90004B50FFF7EDFC94F84B30002800F0E78026 +:103AA00004280BD1990603F0040240F1DC80002ABF +:103AB00000F0F6808023002084F84B3019B0BDE878 +:103AC000F08F0425CDE7022F02D153882E2BCAD0C8 +:103AD000911E87BB002322F81730002F00F01181C0 +:103AE00032F81300194601332028F9D009B92E28DD +:103AF00001D145F00305901E30F817302E2B01D070 +:103B0000013FF9D14FF020334FF0000A6364D046F3 +:103B10002364C4F847300823481C32F81160009031 +:103B2000F6B1202E03D02E2E0DD1B84210D045F084 +:103B300003050099F0E731F81730202B01D02E2B28 +:103B4000C8D1013FC5E79A4505D20099B9423BD19A +:103B50000B2B30D101E00B2B27D145F003050B23B4 +:103B600094F84020E52A04BF052284F84020082B61 +:103B700004BF4FEA88085FFA88F808F00C030C2BA2 +:103B800003D008F00303032B01D145F00205A80779 +:103B90003FF57CAF18F0010F18BF45F0100518F085 +:103BA000040F18BF45F0080570E70099B94202D02C +:103BB00045F00305D4D84FEA88080B234FF0080AD4 +:103BC00000975FFA88F8B4E77F2E15D9304640F2A7 +:103BD0005231CDE9022345F00203019300F098FC35 +:103BE00010F0800F0646DDE9022316D000F07F06B4 +:103BF00046498E5D019D46B331464548CDE90123D6 +:103C000005F0FCFADDE90123F8B9A6F1410189B21A +:103C100019291ED848F0020810E0FF28EAD9591ED9 +:103C20008A4503D345F003059A4682E704EB0A016F +:103C3000000A0AF1010A019D81F8400004EB0A0123 +:103C40000AF1010A81F8406073E745F003055F2639 +:103C5000F4E7A6F1610189B219299EBF203E48F020 +:103C60000108B6B2EAE7002A08BF052026E75A078E +:103C70003FF524AFA379DB0645D59BF80000042867 +:103C800035D1A3682146E27923622369DBF810006D +:103C900023F0FF0313436362E36CA362FFF76AFE42 +:103CA00023680027DA6819F8010B00283FF409AFF0 +:103CB00040F25231009200F04BFC054608B31F2839 +:103CC000009A7FF6FEAE2F283FF4BFAE5C283FF48B +:103CD000BCAE7F2805D801460E4805F08FFA009A41 +:103CE00078B9FF2F0DD022F817500137DBE7216B91 +:103CF0000BF14C03C1F308011944FFF751FEA0601A +:103D0000CEE70620DAE60520D8E600BF7C9300085F +:103D1000759300086C9300081FB5CDE9001003A847 +:103D200014460391FEF700FA002815DB0B4A52F8FF +:103D300020300BB100211970019B0BB100211970CB +:103D400042F820302CB1002201A96846FEF7C8FED7 +:103D50000446204604B010BD0B24FAE73C36002090 +:103D60002DE9F04798B0904605460191002800F0F3 +:103D7000528102F03F0603A901A83246FEF7B0FEC9 +:103D8000002840F04681039B4FF48C60049303F0BD +:103D900099FA0746002800F04081039B00F5007265 +:103DA0000199D86004A81A61FFF702FE044620B901 +:103DB0009DF95B30002BB8BF062418F01C0F00F0F3 +:103DC000CD80002C4CD0042C40D104A8FFF724FC5B +:103DD000044600283AD146F00806039B1A78042AC4 +:103DE00040F08380186929462B60FFF7C3FD039BD1 +:103DF0001E22002118690230FDF79EFF039C00215E +:103E00001A2220692630FDF797FF236920221A71B4 +:103E1000246903F091FA0146012208342046FEF796 +:103E20002BF9039B04A81B6983F82120FFF764FA90 +:103E3000044658B9A96801B302462846FEF718FDA2 +:103E4000AB68039A0446013B5361B4B1384603F0B2 +:103E500049FA0CB100232B60204618B0BDE8F0876A +:103E60009DF8163013F0110F40F0848018F0040F05 +:103E700040F0C98018F0080FAFD1039A31071399A9 +:103E8000936C48BF46F04006E964AB6410780428A0 +:103E900072D1069B9DF817102B62089B106923F0C6 +:103EA000FF030B4329466B62179BAB62FFF762FD72 +:103EB000DDF80CA00024002205F15008BAF8063005 +:103EC00021464046C5F800A0AB80002385F830604D +:103ED00085F831406C64C5E90E234FF40072FDF79C +:103EE0002BFFB20653D40024B0E703F025FA0146B5 +:103EF000009013980E30FEF7BFF813980099163013 +:103F0000FEF7BAF8039C13992078FFF749FD2023A8 +:103F100000228046CB7220461399FEF7D1F8139BFE +:103F2000002201211A775A779A77DA77039BD970A2 +:103F3000B8F1000FA1D0414604A8D3F84890FEF78D +:103F400097FC0446002881D149460398FEF75CFAA5 +:103F5000039B044608F1FF30586176E7002C7FF49C +:103F600075AF9DF81630DC064FD418F0020F84D0E0 +:103F7000D80782D5072469E7FFF712FD0023A86060 +:103F800001F11C00FEF772F86B61286190E7D5E93A +:103F9000046956EA0903A6D0BAF80AA0A9684FEA4C +:103FA0004A2AC5E90E69B24574EB09031BD3002404 +:103FB0002964002C7FF44AAFC6F30803002B92D08B +:103FC000039C2046FEF770F808B3760A01234146A9 +:103FD00046EAC95682196A64607802F0E5FC041E5C +:103FE00018BF012432E72846FEF7C6FAB6EB0A06E8 +:103FF000014669F10009012803D9431CD3D10124EA +:10400000D6E70224D4E7082420E704241EE702248C +:104010001CE704461EE709241EE711241CE70000E4 +:104020002DE9F04F994685B00023884603A9044640 +:10403000C9F800301646FEF791F8054680BB94F8A3 +:1040400031506DBB94F8303013F00103009300F051 +:10405000A68004F1500AD4E90432D4E90E011B1AF7 +:1040600062EB0102B34272F1000238BF1E46BEB1DC +:10407000D4E90E10C1F30803002B40F08280039BAB +:104080005A894B0A013A43EAC0531A401BD151EAFC +:10409000000309D1A06801280DD8022584F8315009 +:1040A000284605B0BDE8F08F216C20460192FEF74E +:1040B00063FA019AEFE7431C04D10123009D84F8C1 +:1040C0003130EDE72064DDF80CB0216C5846FDF787 +:1040D000EBFF0028E1D0B6F5007F02EB000731D3FB +:1040E000BBF80A1002EB5620730A88429BF80100C5 +:1040F00088BF8B1A3A464146019302F055FC0028CE +:10410000DBD194F93020019B002A0BDA606CC01BD4 +:10411000984207D24FF40072514608EB4020FDF759 +:10412000E5FD019B5F02D9F80030F61BB8443B4423 +:10413000C9F80030D4E90E32DB1942F10002C4E9BB +:104140000E3294E7626CBA421AD094F93030002BE8 +:104150000DDA012351469BF8010002F049FC0028CA +:10416000ABD194F8303003F07F0384F830300398FB +:1041700001233A465146407802F016FC00289CD1B3 +:104180006764A16B4046C1F30801C1F50077514453 +:10419000B74228BF37463A46FDF7A8FDC3E70725D3 +:1041A0007EE7000070B596B00E460022019002A98D +:1041B00001A8FEF795FC0446E0B94FF48C6003F0CB +:1041C00081F80546D8B1029B00F500720199D860CC +:1041D00002A81A61FFF7ECFB044640B99DF9533081 +:1041E000002B0ADB1EB1314602A8FDF7EDFF284681 +:1041F00003F078F8204616B070BD0624F7E71124C6 +:10420000F8E7000070B5B8B00222019003A901A838 +:10421000FEF766FC044608BB039B4FF48C601093CA +:1042200003F050F80546002866D0039B00F50072A5 +:104230000199D86010A81A61FFF7BAFB044650B97B +:104240009DF88B30980655D4190653D49DF8463006 +:10425000DA0706D50724284603F044F8204638B08C +:1042600070BD039B04931878042814D104A918691D +:10427000FFF780FB069E9DF84630DB0610D410A8A1 +:10428000FEF776FF04460028E5D156BB0398FEF7FB +:10429000DBFB0446DFE71F99FFF782FB0646EAE7F0 +:1042A000039BDA69B242D5D024930021269624A834 +:1042B0001B78042B01BFDDE90823CDE928239DF8F5 +:1042C00017308DF89730FEF7EFF904460028C2D179 +:1042D00024A8FFF741F804460028BBD00428BAD12F +:1042E000CDE70246314604A8FEF7C2FA044600288C +:1042F000B1D1CBE70624AEE71124AFE7F0B5BDB0EE +:10430000CDE900106846FDF70FFF022203A901A8BE +:10431000FEF7E6FB0446002841D1039B4FF48C6076 +:10432000149302F0CFFF0546002800F0EE80039BB7 +:1043300000F5007214AE0199D8601A613046FFF79B +:1043400037FB044640BB9DF89B3013F0A00F40F0B4 +:10435000D880039B009F1A78042A68D11B6904AC9B +:1043600003F1400C1868083353F8041C22466345D7 +:1043700003C21446F6D15022314628A8FDF7B6FCF8 +:10438000394628A8FFF714FB044600284CD12A9A86 +:10439000169B9A4206D00824284602F0A3FF204626 +:1043A0003DB0F0BD349A209B9A42F4D128A8FFF783 +:1043B00033F904460028EFD1039B04AF1B6993F83F +:1043C00001E093F823C09C8C3A46083303CAB242FA +:1043D00043F8080C43F8041C1746F5D1039B28A8A2 +:1043E0001B6983F801E0039B1A6982F823C01A69EC +:1043F00082F82440240A82F825401A691379D906E4 +:104400005CBF43F020031371FEF776FF04460028DB +:10441000C2D13046FEF7ACFE04460028BCD103985A +:10442000FEF712FB0446B7E70428B5D1BEE7239A8E +:1044300004AB02F1200C1068083252F8041C1C4630 +:10444000624503C42346F6D15022314628A8FDF721 +:104450004DFC394628A8FFF7ABFA044600284CD19A +:104460002A9A169B9A4296D1349A209B9A4292D1CC +:1044700028A8FFF7D1F8044600288DD137990DF10F +:104480001D030DF12D0001F10D0253F8044B834281 +:1044900042F8044BF9D11888012710809B7893705B +:1044A0009DF81B30039CDA0658BF43F02003CB7203 +:1044B000E770CB7ADB06ACD5169A2A9B9A42A8D035 +:1044C0002078FFF76DFA01462046FDF7EDFD014625 +:1044D000C8B12046FDF798FF044600287FF45CAF82 +:1044E000039890F86D302E2B93D12A9A00F16C012D +:1044F000FDF7E6FD039BDF708BE704287FF44CAFEC +:10450000B6E7062448E7022446E7112447E70000FF +:104510007F2810B501D880B210BDB0F5803F13D20E +:1045200040F2523399420FD10849002231F8024B30 +:1045300093B2844203D103F18000C0B2ECE70132B0 +:10454000802AF3D11346F6E70020E5E7BC96000881 +:104550007F280DD940F25233994208D1FF2806D85E +:1045600000F10040034B803833F810007047002002 +:10457000704700BFBC960008B0F5803FF0B522D26E +:104580001F4A83B21F49B0F5805F28BF0A46141D39 +:1045900034F8042C2146AAB1934213D334F8025CB8 +:1045A0002E0AEFB252FA85F5A84222DA082E09D86F +:1045B000DFE806F0050A10121416181A1C00801AFB +:1045C00034F810301846F0BD981A00F001001B1A9C +:1045D0009BB2F7E7103BFBE7203BF9E7303BF7E7FF +:1045E0001A3BF5E70833F3E7503BF1E7A3F5E35354 +:1045F000EEE70434002ECBD101EB4702C7E700BF42 +:104600000C9400080096000808B5074B074A196883 +:1046100001F03D01996053680BB190689847BDE87F +:10462000084003F09BB800BF000002404436002061 +:1046300008B5084B1968890901F03D018A019A60A3 +:10464000054AD3680BB110699847BDE8084003F0EC +:1046500085B800BF000002404436002008B5084B72 +:104660001968090C01F03D010A049A60054A536972 +:104670000BB190699847BDE8084003F06FB800BFE0 +:10468000000002404436002008B5084B1968890D27 +:1046900001F03D018A059A60054AD3690BB1106AA1 +:1046A0009847BDE8084003F059B800BF0000024039 +:1046B0004436002008B5074B074A596801F03D0110 +:1046C000D960536A0BB1906A9847BDE8084003F07F +:1046D00045B800BF000002404436002008B5084B32 +:1046E0005968890901F03D018A01DA60054AD36AF7 +:1046F0000BB1106B9847BDE8084003F02FB800BF1E +:10470000000002404436002008B5084B5968090CE7 +:1047100001F03D010A04DA60054A536B0BB1906B5E +:104720009847BDE8084003F019B800BF00000240F8 +:104730004436002008B5084B5968890D01F03D0149 +:104740008A05DA60054AD36B0BB1106C9847BDE857 +:10475000084003F003B800BF0000024044360020C8 +:1047600008B5074B074A196801F03D019960536C81 +:104770000BB1906C9847BDE8084002F0EFBF00BF56 +:10478000000402404436002008B5084B1968890926 +:1047900001F03D018A019A60054AD36C0BB1106D9E +:1047A0009847BDE8084002F0D9BF00BF00040240AE +:1047B0004436002008B5084B1968090C01F03D018A +:1047C0000A049A60054A536D0BB1906D9847BDE895 +:1047D000084002F0C3BF00BF00040240443600207E +:1047E00008B5084B1968890D01F03D018A059A60EA +:1047F000054AD36D0BB1106E9847BDE8084002F032 +:10480000ADBF00BF000402404436002008B5074B8E +:10481000074A596801F03D01D960536E0BB1906EA3 +:104820009847BDE8084002F099BF00BF000402406D +:104830004436002008B5084B5968890901F03D014C +:104840008A01DA60054AD36E0BB1106F9847BDE854 +:10485000084002F083BF00BF00040240443600203D +:1048600008B5084B5968090C01F03D010A04DA60EB +:10487000054A536F0BB1906F9847BDE8084002F0AE +:104880006DBF00BF000402404436002008B5084B4D +:104890005968890D01F03D018A05DA60054AD36F38 +:1048A00013B1D2F880009847BDE8084002F056BF27 +:1048B000000402404436002000230C4910B51A467B +:1048C0000B4C0B6054F82300026001EB43000433EF +:1048D0004260402BF6D1074A4FF0FF339360D3601C +:1048E000C2F80834C2F80C3410BD00BF44360020B2 +:1048F000BC970008000002400F28F8B510D9102816 +:1049000010D0112811D0122808D10F240720DFF869 +:10491000C8E00126DEF80050A04208D9002653E086 +:104920000446F4E70F240020F1E70724FBE706FA2A +:1049300000F73D424AD1264C4FEA001C3D4304EBB0 +:1049400000160EEBC000CEF80050C0E90123FBB208 +:1049500073B12048D0F8D83043F00103C0F8D83004 +:10496000D0F8003143F00103C0F80031D0F8003135 +:1049700017F47F4F0ED01748D0F8D83043F0020319 +:10498000C0F8D830D0F8003143F00203C0F800314D +:10499000D0F8003154F80C00036823F01F030360C3 +:1049A000056815F00105FBD104EB0C033D2493F8D9 +:1049B0000CC05F6804FA0CF43C602124056044617B +:1049C00012B1987B00F0CAFC3046F8BD0130A3E775 +:1049D000BC970008004402584436002010B530242B +:1049E00084F31188FFF788FF002383F3118810BD3B +:1049F00010B50446807B00F0C7FC01231549627B9B +:104A000003FA02F20B6823EA0203DAB20B6072B90E +:104A1000114AD2F8D81021F00101C2F8D810D2F80A +:104A2000001121F00101C2F80011D2F8002113F4A5 +:104A30007F4F0ED1084BD3F8D82022F00202C3F8E2 +:104A4000D820D3F8002122F00202C3F80021D3F8C5 +:104A5000003110BD443600200044025808B5302310 +:104A600083F31188FFF7C4FF002383F3118808BD87 +:104A7000836CC26A8B42506810B506D95A1E4C002E +:104A800002EB4103B3FBF4F3184410BD01F0010342 +:104A90008A0748BF43F002034A0748BF43F00803B0 +:104AA0000A0748BF43F00403CA0648BF43F0100397 +:104AB0008A06426B48BF43F02003134343637047A9 +:104AC00010B5074C204600F0CBFF064B0022C4E98E +:104AD0001023054BA364054BE363054BE36410BD52 +:104AE000C83600200070005200B4C4041C370020F7 +:104AF0001C390020C36A0BB9104BC3620379012B28 +:104B000011D10F4B98420ED10E4BD3F8D42042F462 +:104B10008032C3F8D420D3F8FC2042F48032C3F8AA +:104B2000FC20D3F8FC30436C00221A65DA621A606C +:104B30005A605A624FF0FF329A637047BC9800087F +:104B4000C8360020004402580379012B1BD0436C67 +:104B500000221A65DA621A605A605A624FF0FF3218 +:104B60009A63094B98420ED1084BD3F8D42022F413 +:104B70008032C3F8D420D3F8FC2022F48032C3F86A +:104B8000FC20D3F8FC307047C8360020004402589F +:104B900010B5446C0649FFF76BFF6060236842F272 +:104BA000107043F003032360BDE8104001F05EBDC8 +:104BB000801A06000129F8B5466C0B4F09D17568BB +:104BC0000A493D40FFF754FF054345F480557560A1 +:104BD000F8BD746806493C40FFF74AFF044344F4BB +:104BE00080547460F4E700BF00ECFFFF80F0FA022D +:104BF00040787D01436C00225A601A6070470000C3 +:104C0000426C0129536823F4404304D0022905D0A3 +:104C100001B95360704743F48043FAE743F400431B +:104C2000F7E70000436C41F480519A60D9605A6BF9 +:104C30001206FCD580229A637047000010B541F43B +:104C40008851446CA260E160616B11F04502FBD0B9 +:104C5000A26311F0040203D0FFF718FF012010BD7A +:104C6000616910461960FAE710B541F48851446C47 +:104C7000A260E160616B11F04502FBD0A26311F00C +:104C8000050203D0FFF702FF012010BD6169104645 +:104C90001960FAE773B5134604460E46302282F3D4 +:104CA0001188426CD26B32B14FF0FF31403001932A +:104CB00001F0E8FC019B606C00220265C263C262E5 +:104CC000456B15F4807504D185F31188012002B07D +:104CD00070BD4FF0FF31816382F31188012E06D938 +:104CE0000C21204602B0BDE87040FFF7BDBF104662 +:104CF000EDE7000073B5446C0E4600250192616B30 +:104D0000A1632565E562FFF7C1FE012E07D9019B6E +:104D10002A460C2102B0BDE87040FFF7A5BF02B0E3 +:104D200070BD000010B541F49851446CA260E16080 +:104D3000616B11F04502FBD0A26311F03F0203D07A +:104D4000FFF7A4FE012010BD216A10461960E16939 +:104D50005960A16999606169D960F4E72DE9F74369 +:104D600004460191006D01A91746984602F01EFC09 +:104D7000064600284AD0626C2046DDF8049055684B +:104D8000C5F3090501356B00A56CB5FBF3F54FF4D0 +:104D90007A73B5FBF3F55D43556200F027FE50BB17 +:104DA000636C4FF0FF3201254146C3F8589020460E +:104DB0001D659A634FF49572DA6342F207029F62AF +:104DC000DA62E36C0A9AFFF74FFFA0B9E26C104B6E +:104DD00011680B407BB929462046FFF75BFF05466B +:104DE00048B92E463A460199206D02F017FC30462C +:104DF00003B0BDE8F0833A460199206D02F00EFC45 +:104E0000E26C01212046FFF775FFF0E70126EEE78F +:104E100008E0FFFD2DE9F7431F46436C01924FF474 +:104E20007A725D6804468846C5F3090501356E004F +:104E3000856CB5FBF6F5B5FBF2F555435D6200F008 +:104E4000D5FD20B10125284603B0BDE8F0837E02E0 +:104E500001A9206D324602F0A9FB05460028F1D0D9 +:104E6000636C019AD4F84C909A6501221A654FF050 +:104E7000FF329A634FF49572DA639E62236BDB060E +:104E80004B4658BF4FEA4828012F42461BD91221F2 +:104E90002046FFF7E9FEC0B9D9F80020104B1340B7 +:104EA0009BB9636C42F2930239462046DA62E26CA7 +:104EB000FFF7F0FE804640B932460199206D454625 +:104EC00002F0ACFBBFE71121E2E732460199206D09 +:104ED00002F0A4FBE26C39462046FFF70BFFB2E775 +:104EE00008E0FFFD2DE9F3411F46436C01924FF4AA +:104EF0007A725D6804468846C5F3090501356E007F +:104F0000856CB5FBF6F5B5FBF2F555435D6200F037 +:104F10006DFD20B10125284602B0BDE8F0817E027A +:104F200001A9206D324602F087FB05460028F1D02A +:104F3000636C019A9A6501221A654FF0FF329A63F9 +:104F40004FF48D72DA639E62236BE66CDB063346A8 +:104F500058BF4FEA4828012F424619D91921204647 +:104F6000FFF782FEB0B932680F4B134093B9636C00 +:104F700042F2910239462046DA62E26CFFF78AFE7D +:104F8000064638B901993546206D02F091FBC2E71B +:104F90001821E4E70199206D02F08AFBE26C3946A2 +:104FA0002046FFF7A7FEB6E708E0FFFD12F0030F6B +:104FB0002DE9F04107460C4615461E4617D00E4413 +:104FC000B44202D10020BDE8F0810123FA6B2146F2 +:104FD0003846FFF71FFF0028F5D128464FF400722E +:104FE000F96B05F500750134FCF780FEE8E7BDE8D4 +:104FF000F041FFF70FBF000012F0030F2DE9F04161 +:1050000007460C4615461E4617D00E44B44202D140 +:105010000020BDE8F08129464FF40072F86B05F5D9 +:105020000075FCF763FE0123FA6B21463846FFF753 +:1050300059FF0028EDD10134E8E7BDE8F041FFF762 +:1050400051BF000000207047302310B583F3118852 +:105050000024436C40302146DC6301F021FB84F3E3 +:10506000118810BD026843681143016003B11847FD +:1050700070470000024A136843F0C0031360704792 +:1050800000440040024A136843F0C00313607047B5 +:1050900000480040024A136843F0C00313607047A1 +:1050A00000780040064BD3F8E8200243C3F8E8201C +:1050B000D3F810211043C3F81001D3F81031704712 +:1050C0000044025837B5274C274D204600F028FDF4 +:1050D00004F11400009400234FF40072234900F0FF +:1050E000C3F94FF40072224904F138000094214BB7 +:1050F00000F03CFA204BC4E91735204C204600F064 +:105100000FFD04F11400009400234FF400721C49B9 +:1051100000F0AAF94FF400721A4904F13800009423 +:10512000194B00F023FA194BC4E91735184C2046E7 +:1051300000F0F6FC04F1140000234FF4007215494E +:10514000009400F091F9144B4FF40072134904F1EC +:105150003800009400F00AFA114BC4E9173503B087 +:1051600030BD00BF2039002000E1F505643A002081 +:105170006440002075500008004400408C39002035 +:10518000643C002064420020855000080048004034 +:10519000F8390020643E0020955000086444002047 +:1051A0000078004038B5264D0446037C002918BF1E +:1051B0000D46012B06D1234B984230D14FF40030DD +:1051C000FFF770FF2A68236EE16D03EB5203A566BB +:1051D000B3FBF2F36A68100442BF23F0070003F048 +:1051E000070343EA4003CB60AB6843F040034B60E6 +:1051F000EB6843F001038B6042F4967343F00103C4 +:105200000B604FF0FF330B62510505D512F01022F1 +:1052100011D0B2F1805F10D084F8643038BD0A4BF1 +:10522000984205D0094B9842CCD14FF08040C7E757 +:105230004FF48020C4E77F23EEE73F23ECE700BF75 +:10524000C4980008203900208C390020F83900204B +:105250002DE9F047C66D05463768F46921073462C9 +:105260001AD014F0080118BF4FF48071E20748BF4C +:1052700041F02001A3074FF0300348BF41F0400147 +:10528000600748BF41F0800183F31188281DFFF7B4 +:10529000E9FE002383F31188E2050AD5302383F366 +:1052A00011884FF48061281DFFF7DCFE002383F393 +:1052B00011884FF030094FF0000A14F0200838D15F +:1052C0003B0616D54FF0300905F1380A200610D5F7 +:1052D00089F31188504600F07DF9002836DA08215C +:1052E000281DFFF7BFFE27F080033360002383F300 +:1052F0001188790614D5620612D5302383F31188FC +:10530000D5E913239A4208D12B6C33B127F040071B +:105310001021281DFFF7A6FE3760002383F31188B4 +:10532000E30618D5AA6E1369ABB15069BDE8F04722 +:10533000184789F31188736A284695F86410194054 +:1053400000F008FC8AF31188F469B6E7B06288F3CC +:105350001188F469BAE7BDE8F0870000090100F19F +:105360006043012203F56143C9B283F8001300F0E2 +:105370001F039A4043099B0003F1604303F5614317 +:10538000C3F880211A60704700F01F0301229A4081 +:10539000430900F160409B0000F5614003F1604368 +:1053A00003F56143C3F88020C3F88021002380F80F +:1053B00000337047F8B51546826804460B46AA428A +:1053C00000D28568A1692669761AB5420BD21846C3 +:1053D0002A46FCF78BFCA3692B44A3612846A368EB +:1053E0005B1BA360F8BD0CD9AF1B18463246FCF717 +:1053F0007DFC3A46E1683044FCF778FCE3683B44C6 +:10540000EBE718462A46FCF771FCE368E5E7000085 +:1054100083689342F7B50446154600D28568D4E9FF +:105420000460361AB5420BD22A46FCF75FFC63696A +:105430002B4463612846A3685B1BA36003B0F0BDE7 +:105440000DD93246AF1B0191FCF750FC01993A4649 +:10545000E0683144FCF74AFCE3683B44E9E72A464C +:10546000FCF744FCE368E4E710B50A440024C36198 +:10547000029B8460C16002610362C0E90000C0E970 +:10548000051110BD08B5D0E90532934201D18268FB +:1054900082B98268013282605A1C4261197000210F +:1054A000D0E904329A4224BFC368436101F012F983 +:1054B000002008BD4FF0FF30FBE7000070B530233F +:1054C00004460E4683F31188A568A5B1A368A269B6 +:1054D000013BA360531CA36115782269934224BF4A +:1054E000E368A361E3690BB120469847002383F387 +:1054F0001188284607E03146204601F0DBF80028F5 +:10550000E2DA85F3118870BD2DE9F74F04460E46A7 +:1055100017469846D0F81C904FF0300A8AF311884D +:105520004FF0000B154665B12A4631462046FFF77D +:1055300041FF034660B94146204601F0BBF8002810 +:10554000F1D0002383F31188781B03B0BDE8F08FFE +:10555000B9F1000F03D001902046C847019B8BF39F +:105560001188ED1A1E448AF31188DCE7C160C3611B +:10557000009B82600362C0E905111144C0E900008C +:1055800001617047F8B504460D461646302383F393 +:105590001188A768A7B1A368013BA36063695A1C7F +:1055A00062611D70D4E904329A4224BFE3686361EA +:1055B000E3690BB120469847002080F3118807E08B +:1055C0003146204601F076F80028E2DA87F31188A8 +:1055D000F8BD0000D0E9052310B59A4201D18268D8 +:1055E0007AB982680021013282605A1C82611C787B +:1055F00003699A4224BFC368836101F06BF82046B7 +:1056000010BD4FF0FF30FBE72DE9F74F04460E4683 +:1056100017469846D0F81C904FF0300A8AF311884C +:105620004FF0000B154665B12A4631462046FFF77C +:10563000EFFE034660B94146204601F03BF80028E2 +:10564000F1D0002383F31188781B03B0BDE8F08FFD +:10565000B9F1000F03D001902046C847019B8BF39E +:105660001188ED1A1E448AF31188DCE70379052BB3 +:1056700005BF836A002001204B6004BF4FF4007314 +:105680000B60704770B55D1E866A04460D44B542D6 +:1056900005D9436B43F080034363012070BD0625A9 +:1056A0000571FFF783FC05232371F7E770B55D1ED5 +:1056B000866A04460D44B54205D9436B43F0800326 +:1056C0004363012070BD07250571FFF795FC052395 +:1056D0002371F7E738B505790446052D05D1082370 +:1056E0000371FFF7AFFC257138BD0120FCE7000016 +:1056F0000323F0B5037185B00446FFF749FA002291 +:1057000020461146FFF78EFA4FF4D57203AB0821FD +:105710002046FFF7A9FA0246B8B901232363039B89 +:10572000C3F30323012B09D103AB37212046FFF735 +:105730009BFA18B9A44B039A1340ABB1204601253C +:10574000FFF758FA0223237137E103AB0022372118 +:105750002046FFF789FA28B99B4A039B1A40002A82 +:1057600000F0A78002232363236B03F00F03022BB7 +:1057700040F0A9806425954E42F2107000F076FF4B +:1057800003AB324601212046FFF758FA0028D5D155 +:10579000039B002B80F293805A0003D5236B43F0C8 +:1057A00010032363002204F1080302212046FFF7BF +:1057B000B9FA02460028C1D104F13803032120467A +:1057C000FFF752FA0028B9D104F11805A26B09219C +:1057D00020462B46FFF7A6FA0028AFD102ABA26BFA +:1057E00007212046FFF740FA06460028A6D1236B82 +:1057F00003F00F03022B40F08F807E227F2128468A +:1058000003F01AFA012840F28780E76B42F2107029 +:1058100000F02CFF08234FF4007239462046009612 +:10582000FFF79CFA002889D1384603F053FA236B1E +:10583000A06203F00F03022B72D103AB644A06216E +:105840002046FFF711FA002871D15F49039B1940E8 +:10585000B1FA81F149092046FFF7ACF902AB4FF4E8 +:10586000007210212046FFF7FFF9054600287FF45B +:1058700065AF554E029B33427FF460AF236B13F04C +:105880000E0F03F00F0273D0022A7FF457AFE36AC2 +:105890001978012900F09480022900F093800029F2 +:1058A00000F089804B4F2046FFF7AAF903AB3A4638 +:1058B00076E0114620462263FFF7B4F954E7013D34 +:1058C0007FF45AAF3AE7444D6426444A3E4F012BD9 +:1058D00018BF154603AB002237212046FFF7C4F955 +:1058E00000287FF42BAF039B3B427FF427AF03AB31 +:1058F0002A4629212046FFF7A1F900287FF41EAF90 +:10590000039B002BFFF648AF013E3FF417AF42F276 +:10591000107000F0ABFEDDE7284603F0AFF986E734 +:105920007E227F212846E66B03F086F908B9002124 +:1059300091E7002340223146204600930623FFF7DB +:105940000DFA0028F3D1B3895BBA9B07EFD5244B3E +:1059500040223146204600930623FFF7FFF9002836 +:10596000E5D1317C01F00F010F3918BF012172E739 +:10597000E36A1978F9B101297FF4E0AE2046FFF718 +:105980003FF903ABA26B37212046FFF76DF90028E2 +:105990007FF4D4AE039B33427FF4D0AE03AB02223C +:1059A00006212046FFF760F900287FF4C7AE039B6D +:1059B00033427FF4C3AE05232371284605B0F0BD02 +:1059C000084F70E7084F6EE708E0FFFD0080FFC05A +:1059D0000001B9030000B7030080FF5000001080F1 +:1059E000F1FFFF800001B7030002B70337B504469B +:1059F0000C4D01ABA26B0D212046FFF735F978B9AC +:105A0000019B2B420BD1C3F34323042B08D0053B4E +:105A1000022B04D84FF47A7000F028FEE9E7012049 +:105A200003B030BD08E0FFFD70B53023054683F3B9 +:105A3000118803790024022B03D184F311882046B6 +:105A400070BD0423037184F311880226FFF7CEFF93 +:105A500004462846FFF7CEF82E71F0E7FFF730B87E +:105A6000044B03600123037100234363C0E90A333D +:105A7000704700BFDC98000810B53023044683F35C +:105A80001188C162FFF736F802230020237180F3EA +:105A9000118810BD10B53023044683F31188FFF739 +:105AA00053F800230122E362227183F3118810BDB1 +:105AB000026843681143016003B118477047000052 +:105AC0001430FFF721BD00004FF0FF331430FFF713 +:105AD0001BBD00003830FFF797BD00004FF0FF33CB +:105AE0003830FFF791BD00001430FFF7E7BC00002D +:105AF0004FF0FF311430FFF7E1BC00003830FFF702 +:105B000041BD00004FF0FF323830FFF73BBD0000D1 +:105B1000012914BF6FF0130000207047FFF7D2BABD +:105B2000044B036000234360C0E902330123037484 +:105B3000704700BF0099000810B53023044683F376 +:105B40001188FFF72FFB02230020237480F31188B4 +:105B500010BD000038B5C36904460D461BB90421C9 +:105B60000844FFF7A5FF294604F11400FFF78AFC5B +:105B7000002806DA201D4FF40061BDE83840FFF729 +:105B800097BF38BD026843681143016003B11847ED +:105B90007047000013B5406B00F58054D4F8A4386A +:105BA0001A681178042914D1017C022911D11979BC +:105BB000012312898B4013420BD101A94C3002F012 +:105BC00069FFD4F8A4480246019B2179206800F0BF +:105BD000DFF902B010BD0000143002F0EBBE00008F +:105BE0004FF0FF33143002F0E5BE00004C3002F0FD +:105BF000BDBF00004FF0FF334C3002F0B7BF0000D4 +:105C0000143002F0B9BE00004FF0FF31143002F042 +:105C1000B3BE00004C3002F089BF00004FF0FF32ED +:105C20004C3002F083BF00000020704710B500F533 +:105C30008054D4F8A4381A681178042917D1017C4B +:105C4000022914D15979012352898B4013420ED174 +:105C5000143002F04BFE024648B1D4F8A4484FF489 +:105C6000407361792068BDE8104000F07FB910BD35 +:105C7000406BFFF7DBBF0000704700007FB5124BA1 +:105C800001250426044603600023057400F1840204 +:105C900043602946C0E902330C4B02901430019353 +:105CA0004FF44073009602F0FDFD094B04F6944258 +:105CB000294604F14C000294CDE900634FF440738F +:105CC00002F0C4FE04B070BD28990008715C0008A1 +:105CD000955B00080A68302383F311880B790B3336 +:105CE00042F823004B79133342F823008B7913B128 +:105CF0000B3342F8230000F58053C3F8A4180223A5 +:105D00000374002080F311887047000038B5037FCA +:105D1000044613B190F85430ABB90125201D02217F +:105D2000FFF730FF04F114006FF00101257700F058 +:105D3000DDFC04F14C0084F854506FF00101BDE823 +:105D4000384000F0D3BC38BD10B501210446043002 +:105D5000FFF718FF0023237784F8543010BD0000AC +:105D600038B504460025143002F0B4FD04F14C00AF +:105D7000257702F083FE201D84F854500121FFF79F +:105D800001FF2046BDE83840FFF750BF90F8803053 +:105D900003F06003202B06D190F881200023212AF4 +:105DA00003D81F2A06D800207047222AFBD1C0E959 +:105DB0001D3303E0034A426707228267C36701205D +:105DC000704700BF4422002037B500F58055D5F854 +:105DD000A4381A68117804291AD1017C022917D134 +:105DE0001979012312898B40134211D100F14C041F +:105DF000204602F003FF58B101A9204602F04AFEF6 +:105E0000D5F8A4480246019B2179206800F0C0F82B +:105E100003B030BD01F10B03F0B550F8236085B03D +:105E200004460D46FEB1302383F3118804EB850749 +:105E3000301D0821FFF7A6FEFB6806F14C005B69E8 +:105E40001B681BB1019002F033FE019803A902F018 +:105E500021FE024648B1039B2946204600F098F8EF +:105E6000002383F3118805B0F0BDFB685A691268FE +:105E7000002AF5D01B8A013B1340F1D104F18002C6 +:105E8000EAE70000133138B550F82140ECB1302377 +:105E900083F3118804F58053D3F8A428136852794A +:105EA00003EB8203DB689B695D6845B104216018E0 +:105EB000FFF768FE294604F1140002F021FD204698 +:105EC000FFF7B4FE002383F3118838BD704700004C +:105ED00001F042BD01234022002110B5044600F824 +:105EE000303BFBF729FF0023C4E9013310BD00005C +:105EF00010B53023044683F3118824224160002129 +:105F00000C30FBF719FF204601F048FD022300206A +:105F1000237080F3118810BD70B500EB8103054636 +:105F200050690E461446DA6018B110220021FBF7C2 +:105F300003FFA06918B110220021FBF7FDFE3146D6 +:105F40002846BDE8704001F02FBE00008368202283 +:105F5000002103F0011310B5044683601030FBF7F5 +:105F6000EBFE2046BDE8104001F0AABEF0B40125CA +:105F700000EB810447898D40E4683D43A469458175 +:105F800023600023A2606360F0BC01F0C7BE000084 +:105F9000F0B4012500EB810407898D40E4683D439E +:105FA0006469058123600023A2606360F0BC01F096 +:105FB0003DBF000070B50223002504462422037073 +:105FC0002946C0F888500C3040F8045CFBF7B4FE5A +:105FD000204684F8705001F07BFD63681B6823B194 +:105FE00029462046BDE87040184770BD0378052B50 +:105FF00010B504460AD080F88C300523037043683E +:106000001B680BB1042198470023A36010BD00005A +:106010000178052906D190F88C20436802701B682E +:1060200003B118477047000070B590F8703004460F +:1060300013B1002380F8703004F18002204601F093 +:1060400063FE63689B68B3B994F8803013F0600511 +:1060500035D00021204602F055F90021204602F0FB +:1060600045F963681B6813B106212046984706234B +:1060700084F8703070BD204698470028E4D0B4F80A +:106080008630A26F9A4288BFA36794F98030A56FCB +:10609000002B4FF0300380F20381002D00F0F280DE +:1060A000092284F8702083F3118800212046D4E966 +:1060B0001D23FFF76DFF002383F31188DAE794F8BF +:1060C000812003F07F0343EA022340F2023293422D +:1060D00000F0C58021D8B3F5807F48D00DD8012BC2 +:1060E0003FD0022B00F09380002BB2D104F1880244 +:1060F00062670222A267E367C1E7B3F5817F00F020 +:106100009B80B3F5407FA4D194F88230012BA0D1BD +:10611000B4F8883043F0020332E0B3F5006F4DD09D +:1061200017D8B3F5A06F31D0A3F5C063012B90D879 +:106130006368204694F882205E6894F88310B4F86F +:106140008430B047002884D0436863670368A3673E +:106150001AE0B3F5106F36D040F6024293427FF456 +:1061600078AF5C4B63670223A3670023C3E794F80F +:106170008230012B7FF46DAFB4F8883023F0020336 +:10618000A4F88830C4E91D55E56778E7B4F8803095 +:10619000B3F5A06F0ED194F88230204684F88A308F +:1061A00001F0F4FC63681B6813B101212046984795 +:1061B000032323700023C4E91D339CE704F18B0300 +:1061C00063670123C3E72378042B10D1302383F3C3 +:1061D00011882046FFF7BAFE85F311880321636812 +:1061E00084F88B5021701B680BB12046984794F8B7 +:1061F0008230002BDED084F88B3004232370636858 +:106200001B68002BD6D0022120469847D2E794F88D +:10621000843020461D0603F00F010AD501F066FD0B +:10622000012804D002287FF414AF2B4B9AE72B4BA4 +:1062300098E701F04DFDF3E794F88230002B7FF4EE +:1062400008AF94F8843013F00F01B3D01A0620463B +:1062500002D502F06FF8ADE702F060F8AAE794F813 +:106260008230002B7FF4F5AE94F8843013F00F01E8 +:10627000A0D01B06204602D502F044F89AE702F0AF +:1062800035F897E7142284F8702083F311882B46A1 +:106290002A4629462046FFF769FE85F31188E9E67C +:1062A0005DB1152284F8702083F311880021204607 +:1062B000D4E91D23FFF75AFEFDE60B2284F8702077 +:1062C00083F311882B462A4629462046FFF760FEB5 +:1062D000E3E700BF58990008509900085499000856 +:1062E00038B590F870300446002B3ED0063BDAB249 +:1062F0000F2A34D80F2B32D8DFE803F037313108BA +:10630000223231313131313131313737856FB0F8A7 +:1063100086309D4214D2C3681B8AB5FBF3F203FB9F +:1063200012556DB9302383F311882B462A4629462E +:10633000FFF72EFE85F311880A2384F870300EE0F3 +:10634000142384F87030302383F31188002320460F +:106350001A461946FFF70AFE002383F3118838BD59 +:10636000C36F03B198470023E7E70021204601F0FF +:10637000C9FF0021204601F0B9FF63681B6813B113 +:106380000621204698470623D7E7000010B590F86D +:1063900070300446142B29D017D8062B05D001D80D +:1063A0001BB110BD093B022BFBD80021204601F098 +:1063B000A9FF0021204601F099FF63681B6813B113 +:1063C000062120469847062319E0152BE9D10B2317 +:1063D00080F87030302383F3118800231A46194661 +:1063E000FFF7D6FD002383F31188DAE7C3689B69C2 +:1063F0005B68002BD5D1C36F03B19847002384F8A5 +:106400007030CEE70023826880F8243083691B68EF +:1064100099689142FBD25A680360426010605860EC +:10642000704700000023826880F8243083691B686D +:1064300099689142FBD85A680360426010605860C6 +:106440007047000008B50846302383F3118891F89F +:106450002430032B05D0042B0DD02BB983F31188E6 +:1064600008BD8B6A00221A604FF0FF338362FFF78A +:10647000C9FF0023F2E7D1E9003213605A60F3E765 +:10648000034610B51B68984203D09C688A68944202 +:10649000F8D25A680B604A601160596010BD000064 +:1064A000FFF7B0BF064BD96881F82400186802686E +:1064B00053601A600122D86080F82420F9F7A2BF47 +:1064C000684600200C4B30B5DD684B1C87B0044695 +:1064D0000FD02B46094A684600F09CF92046FFF78A +:1064E000E1FF009B13B1684600F09EF9A86A07B06F +:1064F00030BDFFF7D7FFF9E7684600204564000884 +:10650000044B1A68DB6890689B68984294BF00202F +:106510000120704768460020094B10B51C68D868F8 +:10652000226853601A600122DC6084F82420FFF79F +:1065300079FF01462046BDE81040F9F763BF00BF70 +:1065400068460020044B1A68DB6892689B689A4290 +:1065500001D9FFF7E1BF70476846002038B5012335 +:10656000084C00252370656002F0E2FB02F008FC95 +:106570000549064802F0DEFC0223237085F31188EA +:1065800038BD00BF1049002060990008684600200F +:1065900000F080B9034A516853685B1A9842FBD8EF +:1065A000704700BF001000E08B604B630023CA619E +:1065B00000F128020B6302230A618B8401238861A6 +:1065C00081F8263001F11003C26A4A611360C36288 +:1065D00001F12C030846CB6270470000D0E901317D +:1065E000026841F8183CA1F19C033839CB6003697B +:1065F00041F8243C436941F8203C034B41F8043CFA +:10660000C3680248FFF7D0BF1D0400086846002099 +:1066100008B5FFF7E3FFBDE80840FFF741BF000002 +:1066200038B50E4BDC6804F12C05A062E06AA84284 +:106630000FD194F826303BB994F825309B0702BF60 +:10664000D4E9043213605A600F20BDE83840FFF7E8 +:1066500029BF0368E362FFF723FFE7E768460020EE +:10666000302383F31188FFF7DBBF000008B5014634 +:10667000302383F311880820FFF724FF002383F3DE +:10668000118808BD054BDB6821B1036098620320C7 +:10669000FFF718BF4FF0FF30704700BF684600207B +:1066A00003682BB10022026018469962FFF7F8BE1A +:1066B00070470000064BDB6839B1426818605A60C9 +:1066C000136043600420FFF7FDBE4FF0FF307047BA +:1066D000684600200368984206D01A68026050603D +:1066E00018469962FFF7DCBE7047000038B50446D3 +:1066F0000D462068844200D138BD036823605C6089 +:106700008562FFF7CDFEF4E7036810B59C68A242EE +:106710000CD85C688A600B604C6021605960996895 +:106720008A1A9A604FF0FF33836010BD121B1B68FA +:10673000ECE700000A2938BF0A2170B504460D466F +:106740000A26601902F0EEFA02F0D6FA041BA542FE +:1067500003D8751C04462E46F3E70A2E04D90120FF +:10676000BDE8704002F0AEBC70BD0000F8B5144B3F +:106770000D460A2A4FF00A07D96103F11001826021 +:1067800038BF0A22416019691446016048601861E7 +:10679000A81802F0B7FA02F0AFFA431B0646A3426C +:1067A00006D37C1C28192746354602F0BBFAF2E7CF +:1067B0000A2F04D90120BDE8F84002F083BCF8BDDF +:1067C00068460020F8B506460D4602F095FA0F4AD5 +:1067D000134653F8107F9F4206D12A4601463046A1 +:1067E000BDE8F840FFF7C2BFD169BB68441A2C1955 +:1067F00028BF2C46A34202D92946FFF79BFF224619 +:1068000031460348BDE8F840FFF77EBF68460020E8 +:1068100078460020C0E90323002310B45DF8044B40 +:106820004361FFF7CFBF000010B5194C23699842B0 +:106830000DD08168D0E9003213605A609A680A442A +:106840009A60002303604FF0FF33A36110BD02681C +:10685000234643F8102F53600022026022699A42B7 +:1068600003D1BDE8104002F057BA936881680B4429 +:10687000936002F041FA2269E1699268441AA242E7 +:10688000E4D91144BDE81040091AFFF753BF00BF17 +:10689000684600202DE9F047DFF8BC8008F11007BA +:1068A0002C4ED8F8105002F027FAD8F81C40AA68ED +:1068B000031B9A423ED814444FF00009D5E9003238 +:1068C000C8F81C4013605A60C5F80090D8F8103022 +:1068D000B34201D102F020FA89F31188D5E90331DE +:1068E00028469847302383F311886B69002BD8D052 +:1068F00002F002FA6A69A0EB040982464A450DD209 +:10690000022002F0DFFB0022D8F81030B34208D199 +:1069100051462846BDE8F047FFF728BF121A224427 +:10692000F2E712EB09092946384638BF4A46FFF715 +:10693000EBFEB5E7D8F81030B34208D01444C8F8DD +:106940001C00211AA960BDE8F047FFF7F3BEBDE8BF +:10695000F08700BF784600206846002038B502F076 +:10696000CBF9054AD2E90845031B181945F1000186 +:10697000C2E9080138BD00BF6846002010B560B903 +:10698000074804790368053C9B6818BF01249847B1 +:1069900008B144F00404204610BD0124FBE700BF09 +:1069A000C8360020FFF7EABF2DE9F04788461746B2 +:1069B0009A460446B0B90D4E3579052D05D003240D +:1069C0000DE0013D15F0FF050ED032685346394603 +:1069D0003046D2F814904246C8470028F1D12046EC +:1069E000BDE8F0870424FAE70124F8E7C836002060 +:1069F0002DE9F047884617469A460446B0B90D4E31 +:106A00003579052D05D003240DE0013D15F0FF0576 +:106A10000ED03268534639463046D2F81890424676 +:106A2000C8470028F1D12046BDE8F0870424FAE7E2 +:106A30000124F8E7C836002037B50C46154670B972 +:106A400051B101290BD10748694603681B6A984771 +:106A500010B9019B04462B60204603B030BD0424CE +:106A6000FAE700BFC836002000207047FEE70000AC +:106A7000704700004FF0FF30704700004B684360E4 +:106A80008B688360CB68C3600B6943614B690362A9 +:106A90008B6943620B6803607047000008B53C4B8C +:106AA00040F2FF713B48D3F888200A43C3F888209E +:106AB000D3F8882022F4FF6222F00702C3F888206E +:106AC000D3F88820D3F8E0200A43C3F8E020D3F8B5 +:106AD00008210A43C3F808212F4AD3F80831114688 +:106AE000FFF7CCFF00F5806002F11C01FFF7C6FF45 +:106AF00000F5806002F13801FFF7C0FF00F580600B +:106B000002F15401FFF7BAFF00F5806002F1700155 +:106B1000FFF7B4FF00F5806002F18C01FFF7AEFFD4 +:106B200000F5806002F1A801FFF7A8FF00F5806082 +:106B300002F1C401FFF7A2FF00F5806002F1E0015D +:106B4000FFF79CFF00F5806002F1FC01FFF796FF64 +:106B500002F58C7100F58060FFF790FF01F082FC78 +:106B60000E4BD3F8902242F00102C3F89022D3F8E2 +:106B7000942242F00102C3F894220522C3F898201F +:106B80004FF06052C3F89C20054AC3F8A02008BD0E +:106B900000440258000002587499000800ED00E01B +:106BA0001F00080308B501F069FEFFF7D7FC104B82 +:106BB000D3F8DC2042F04002C3F8DC20D3F80421F3 +:106BC00022F04002C3F80421D3F80431094B1A68BB +:106BD00042F008021A601A6842F004021A6000F0DB +:106BE0006FFD00F033FBBDE8084000F0B5B800BF12 +:106BF00000440258001802480120704700207047E6 +:106C00007047000002290CD0032904D0012907484D +:106C100018BF00207047032A05D8054800EBC200C2 +:106C20007047044870470020704700BF789B0008F9 +:106C3000542200202C9B000870B59AB005460846E7 +:106C4000144601A900F0C2F801A8FBF76DF8431C37 +:106C50000022C6B25B001046C5E90034237003234E +:106C6000023404F8013C01ABD1B202348E4201D8A7 +:106C70001AB070BD13F8011B013204F8010C04F8BE +:106C8000021CF1E708B5302383F311880348FFF7AE +:106C90009BF8002383F3118808BD00BF184900202A +:106CA00090F8803003F01F02012A07D190F881206C +:106CB0000B2A03D10023C0E91D3315E003F0600364 +:106CC000202B08D1B0F884302BB990F88120212AEC +:106CD00003D81F2A04D8FFF759B8222AEBD0FAE7C5 +:106CE000034A426707228267C3670120704700BFDB +:106CF0004B22002007B5052917D8DFE801F0191647 +:106D000003191920302383F31188104A01210190BF +:106D1000FFF702F9019802210D4AFFF7FDF80D482F +:106D2000FFF71EF8002383F3118803B05DF804FB1E +:106D3000302383F311880748FEF7E8FFF2E730239A +:106D400083F311880348FEF7FFFFEBE7CC9A0008B6 +:106D5000F09A00081849002038B50C4D0C4C2A4612 +:106D60000C4904F10800FFF767FF05F1CA0204F1BE +:106D700010000949FFF760FF05F5CA7204F1180019 +:106D80000649BDE83840FFF757BF00BFF06100205B +:106D900054220020A89A0008B59A0008C09A00085A +:106DA00070B5044608460D46FAF7BEFFC6B2204647 +:106DB000013403780BB9184670BD32462946FAF7FC +:106DC0009FFF0028F3D10120F6E700002DE9F047EE +:106DD00005460C46FAF7A8FF2B49C6B22846FFF72E +:106DE000DFFF08B10A36F6B228492846FFF7D8FF78 +:106DF00008B11036F6B2632E0BD8DFF88C80DFF8BE +:106E00008C90234FDFF894A02E7846B92670BDE809 +:106E1000F08729462046BDE8F04702F0FDB9252E4F +:106E20002ED1072241462846FAF76AFF70B9194B5E +:106E3000224603F1100153F8040B8B4242F8040B75 +:106E4000F9D11B78073511341370DDE70822494664 +:106E50002846FAF755FF98B9A21C0F4B1978023251 +:106E60000909C95D02F8041C13F8011B01F00F01A8 +:106E70005345C95D02F8031CF0D118340835C3E747 +:106E8000013504F8016BBFE7989B0008C09A000821 +:106E9000B29B0008A09B000800E8F11F0CE8F11F5E +:106EA000BFF34F8F044B1A695107FCD1D3F810215F +:106EB0005207F8D1704700BF0020005208B50D4BB3 +:106EC0001B78ABB9FFF7ECFF0B4BDA68D10704D5A1 +:106ED0000A4A5A6002F188325A60D3F80C21D2076C +:106EE00006D5064AC3F8042102F18832C3F804210A +:106EF00008BD00BF4E6400200020005223016745FA +:106F000008B5114B1B78F3B9104B1A69510703D51B +:106F1000DA6842F04002DA60D3F81021520705D552 +:106F2000D3F80C2142F04002C3F80C21FFF7B8FF60 +:106F3000064BDA6842F00102DA60D3F80C2142F025 +:106F40000102C3F80C2108BD4E640020002000524D +:106F50000F289ABF00F580604004002070470000B1 +:106F60004FF4003070470000102070470F2808B51C +:106F70000BD8FFF7EDFF00F500330268013204D1B2 +:106F800004308342F9D1012008BD0020FCE7000055 +:106F90000F2838B505463FD8FFF782FF1F4CFFF793 +:106FA0008DFF4FF0FF3307286361C4F814311DD8FB +:106FB0002361FFF775FF030243F02403E360E368F6 +:106FC00043F08003E36023695A07FCD42846FFF7A7 +:106FD00067FFFFF7BDFF4FF4003100F0ABFA284622 +:106FE000FFF78EFFBDE83840FFF7C0BFC4F810318F +:106FF000FFF756FFA0F108031B0243F02403C4F877 +:107000000C31D4F80C3143F08003C4F80C31D4F8BF +:1070100010315B07FBD4D9E7002038BD00200052B7 +:107020002DE9F84F05460C46104645EA0203DE06F8 +:1070300002D00020BDE8F88F20F01F00DFF8BCB0C0 +:10704000DFF8BCA0FFF73AFF04EB0008444503D18A +:107050000120FFF755FFEDE720222946204602F0E8 +:10706000A3F810B920352034F0E72B4605F12002B3 +:107070001F68791CDDD104339A42F9D105F17843B8 +:107080001B481C4EB3F5801F1B4B38BF184603F13D +:10709000F80332BFD946D1461E46FFF701FF07600D +:1070A000A5EB040C336804F11C0143F002033360C8 +:1070B000231FD9F8007017F00507FAD153F8042FF1 +:1070C0008B424CF80320F4D1BFF34F8FFFF7E8FE5B +:1070D0004FF0FF332022214603602846336823F017 +:1070E0000203336002F060F80028BBD03846B0E7F6 +:1070F000142100520C200052142000521020005283 +:107100001021005210B5084C237828B11BB9FFF7A5 +:10711000D5FE0123237010BD002BFCD02070BDE8EC +:107120001040FFF7EDBE00BF4E6400202DE9F04F88 +:107130000D4685B0814658B111F00D0614BF2022CE +:10714000082211F00803019304D0431E034269D0C2 +:10715000002435E0002E37D009F11F0121F01F096E +:107160004FF00108314F05F00403DFF8CCA005EA29 +:10717000080BBBF1000F32D07869C0072FD408F19B +:1071800001080C37B8F1060FF3D19EB9284D4946D6 +:10719000A819019201F016FE0446002839D12036C4 +:1071A000019AA02EF3D1494601F00CFE04460028B6 +:1071B0002FD1019A49461F4801F004FE044660BBE6 +:1071C000204605B0BDE8F08F0029C9D10146284608 +:1071D000029201F0F7FD0446D8B9029AC0E713B154 +:1071E00078694107CBD5AC0702D578698007C6D549 +:1071F000019911B178690107C1D549460AEB4810D8 +:10720000CDE9022301F0DEFD0446DDE9022300287A +:10721000B5D04A460021204601E04A460021FAF74F +:107220008BFDCDE70246002E96D199E7C49B00085E +:107230009064002050640020706400200021FFF75B +:1072400075BF00000121FFF771BF000070B5144D3C +:107250000124144E40F2FF3200210120FAF76CFDA8 +:1072600006EB441001342A6955F80C1F01F096FD15 +:10727000062CF5D137254FF4C0542046FFF7E2FF26 +:10728000014628B122460848BDE8704001F086BD9D +:10729000C4EBC404013D4FEAD404EED170BD00BF7D +:1072A000C49B000870640020506400200421FFF794 +:1072B0003DBF00004843FFF7C1BF000008B101F027 +:1072C000F3BD7047B0F5805F10B5044607D8FFF7EF +:1072D000EDFF28B92046BDE81040FFF7AFBF002002 +:1072E00010BD0000FFF7EABF70B5AAB140EA010384 +:1072F00013F01F030FD1094C0144A5686D0706D593 +:107300002568A84203D366683544A94204D90333EB +:107310000C34122BF1D10022104670BDC49B000822 +:1073200008B501F0D7FE034AD2E90032C01842EB9B +:10733000010108BD30650020434BD3E900232DE94E +:10734000F34113437CD0FFF7EBFF404A00230027B3 +:10735000F9F772F806460D463D4A0023F9F76CF836 +:107360000023144630462946394AF9F765F84FF4A8 +:1073700061613C23ADF80170B4FBF1F5B4FBF3F6A9 +:1073800001FB154103FB16464624B1FBF3F1314BDB +:10739000F6B28DF8004098423CD84FF0640C4FF4A0 +:1073A000C87EA30704F26C7225D1B2FBFCF30CFB80 +:1073B000132313BBB2FBFEF30EFB1322B2FA82F3CC +:1073C0005B0903F26D18621C8045D2B217D90FB168 +:1073D0008DF800400022204C4FF00C0C17460CFB9F +:1073E0000343D4B2013213F804C084450CD8A0EB97 +:1073F0000C000127F5E70023E3E70123E1E7A0EB19 +:10740000080014460127CCE70FB18DF80140431C5A +:107410008DF802309DF80100431C9DF800005038A3 +:10742000400640EA43509DF8023040EA034040EAFB +:10743000560040EAC52040EA411002B0BDE8F081A4 +:107440004FF40410F9E700BF3065002040420F0000 +:107450008051010090230B000C9C00080244074B54 +:10746000D2B210B5904200D110BD441C00B253F806 +:10747000200041F8040BE0B2F4E700BF5040005890 +:107480000E4B30B51C6F240405D41C6F1C671C6F99 +:1074900044F400441C670A4C02442368D2B243F40B +:1074A00080732360074B904200D130BD441C51F8DB +:1074B000045B00B243F82050E0B2F4E70044025805 +:1074C000004802585040005807B5012201A9002089 +:1074D000FFF7C4FF019803B05DF804FB13B5044641 +:1074E000FFF7F2FFA04205D0012201A9002001947C +:1074F000FFF7C6FF02B010BD10B56424013C4FF485 +:107500007A70FFF7B3F814F0FF04F7D1084B4FF08F +:10751000807214249A6103F5805308229A61013C19 +:107520004FF47A70FFF7A2F814F0FF04F7D110BD02 +:10753000000002580144BFF34F8F064B884204D32A +:10754000BFF34F8FBFF36F8F7047C3F85C022030DB +:10755000F4E700BF00ED00E00144BFF34F8F064B9E +:10756000884204D3BFF34F8FBFF36F8F7047C3F8C8 +:1075700070022030F4E700BF00ED00E070B5054672 +:1075800016460C4601201021FFF794FE2860467332 +:107590003CB1204636B1FFF789FE2B68186000B178 +:1075A0009C6070BDFFF74EFEF7E70000F8B50F4690 +:1075B0001546044648B905F11F010126386821F037 +:1075C0001F01FFF7B7FF3046F8BD427B29463868F8 +:1075D000FFF78AFE06460028EDD13B686360A3688A +:1075E000AB4210D213B12068FFF768FE637B2846D8 +:1075F0002BB1FFF75BFE206020B9A060E3E7FFF747 +:1076000021FEF8E7A560206805F11F01012621F0A1 +:107610001F013860FFF78EFF2673D4E710B50446CC +:1076200040B10068884205D1606808B1FAF75EFB96 +:107630000023237310BD0000F8B50F46144605461D +:1076400048B904F11F010126386821F01F01FFF736 +:1076500083FF3046F8BD427B21463868FFF744FE81 +:1076600006460028EDD1AB68A34210D213B12868BA +:10767000FFF724FE6B7B20462BB1FFF717FE286037 +:1076800020B9A860E5E7FFF7DDFDF8E7AC603968F1 +:1076900019B122462868FAF729FB286804F11F016E +:1076A000012621F01F013860FFF756FF2E73D0E747 +:1076B00020B103688B4204BF0023037370470000AE +:1076C000034B1A681AB9034AD2F8D0241A607047DB +:1076D000386500200040025808B5FFF7F1FF024B63 +:1076E0001868C0F3806008BD38650020EFF3098397 +:1076F000054968334A6B22F001024A6383F3098823 +:10770000002383F31188704700EF00E0302080F3FE +:10771000118862B60D4B0E4AD96821F4E061090464 +:10772000090C0A430B49DA60D3F8FC2042F080725E +:10773000C3F8FC20084AC2F8B01F116841F00101EB +:1077400011602022DA7783F82200704700ED00E014 +:107750000003FA0555CEACC5001000E0302310B58B +:1077600083F311880E4B5B6813F4006314D0F1EEC1 +:10777000103AEFF309844FF08073683CE361094BE2 +:10778000DB6B236684F30988FEF7BAFE10B1064B63 +:10779000A36110BD054BFBE783F31188F9E700BF38 +:1077A00000ED00E000EF00E02F04000832040008C4 +:1077B00070B5BFF34F8FBFF36F8F1A4A0021C2F825 +:1077C0005012BFF34F8FBFF36F8F536943F40033F1 +:1077D0005361BFF34F8FBFF36F8FC2F88410BFF3B5 +:1077E0004F8FD2F8803043F6E074C3F3C900C3F37F +:1077F0004E335B0103EA0406014646EA817501390E +:10780000C2F86052F9D2203B13F1200FF2D1BFF33E +:107810004F8F536943F480335361BFF34F8FBFF3EE +:107820006F8F70BD00ED00E0FEE70000214B2248A5 +:10783000224A70B5904237D3214BC11EDA1C121A6E +:1078400022F003028B4238BF00220021FAF774FABB +:107850001C4A0023C2F88430BFF34F8FD2F8803027 +:1078600043F6E074C3F3C900C3F34E335B0103EA8C +:107870000406014646EA81750139C2F86C52F9D214 +:10788000203B13F1200FF2D1BFF34F8FBFF36F8F67 +:10789000BFF34F8FBFF36F8F0023C2F85032BFF397 +:1078A0004F8FBFF36F8F70BD53F8041B40F8041B5C +:1078B000C0E700BF149D0008346700203467002033 +:1078C0003467002000ED00E0074BD3F8D81021EA20 +:1078D0000001C3F8D810D3F8002122EA0002C3F84F +:1078E0000021D3F8003170470044025870B5D0E948 +:1078F000244300224FF0FF359E6804EB42135101F0 +:10790000D3F80009002805DAD3F8000940F08040D8 +:10791000C3F80009D3F8000B002805DAD3F8000BF0 +:1079200040F08040C3F8000B013263189642C3F860 +:107930000859C3F8085BE0D24FF00113C4F81C38B3 +:1079400070BD0000890141F02001016103699B06BF +:10795000FCD41220FEF71EBE10B50A4C2046FEF7DE +:10796000B9FA094BC4F89030084BC4F89430084C6D +:107970002046FEF7AFFA074BC4F89030064BC4F828 +:10798000943010BD3C65002000000840489C000871 +:10799000D865002000000440549C000870B50378AE +:1079A0000546012B5CD1434BD0F89040984258D10A +:1079B000414B0E216520D3F8D82042F00062C3F875 +:1079C000D820D3F8002142F00062C3F80021D3F898 +:1079D0000021D3F8802042F00062C3F88020D3F861 +:1079E000802022F00062C3F88020D3F88030FDF7B9 +:1079F000B5FC324BE360324BC4F800380023D5F8B5 +:107A00009060C4F8003EC02323604FF40413A363C6 +:107A10003369002BFCDA01230C203361FEF7BAFD39 +:107A20003369DB07FCD41220FEF7B4FD3369002B69 +:107A3000FCDA00262846A660FFF758FF6B68C4F8FA +:107A40001068DB68C4F81468C4F81C6883BB1D4B5D +:107A5000A3614FF0FF336361A36843F00103A360A8 +:107A600070BD194B9842C9D1134B4FF08060D3F8C9 +:107A7000D82042F00072C3F8D820D3F8002142F099 +:107A80000072C3F80021D3F80021D3F8802042F01F +:107A90000072C3F88020D3F8802022F00072C3F86F +:107AA0008020D3F88030FFF70FFF0E214D209EE796 +:107AB000064BCDE73C6500200044025840140040CE +:107AC00003002002003C30C0D8650020083C30C0D4 +:107AD000F8B5D0F89040054600214FF000662046EA +:107AE000FFF730FFD5F8941000234FF001128F6894 +:107AF0004FF0FF30C4F83438C4F81C2804EB4312AC +:107B000001339F42C2F80069C2F8006BC2F808094D +:107B1000C2F8080BF2D20B68D5F89020C5F898305F +:107B2000636210231361166916F01006FBD1122050 +:107B3000FEF730FDD4F8003823F4FE63C4F80038B3 +:107B4000A36943F4402343F01003A3610923C4F85D +:107B50001038C4F814380B4BEB604FF0C043C4F836 +:107B6000103B094BC4F8003BC4F81069C4F8003955 +:107B7000D5F8983003F1100243F48013C5F898202B +:107B8000A362F8BD249C000840800010D0F890202B +:107B900090F88A10D2F8003823F4FE6343EA011308 +:107BA000C2F80038704700002DE9F84300EB81036C +:107BB000D0F890500C468046DA680FFA81F94801F7 +:107BC000166806F00306731E022B05EB41134FF0F7 +:107BD000000194BFB604384EC3F8101B4FF00101EA +:107BE00004F1100398BF06F1805601FA03F391697E +:107BF00098BF06F5004600293AD0578A04F158018B +:107C0000374349016F50D5F81C180B430021C5F8C4 +:107C10001C382B180127C3F81019A7405369611E9F +:107C20009BB3138A928B9B08012A88BF5343D8F8D1 +:107C30009820981842EA034301F140022146C8F80F +:107C40009800284605EB82025360FFF77BFE08EBA5 +:107C50008900C3681B8A43EA845348341E43640185 +:107C60002E51D5F81C381F43C5F81C78BDE8F883A1 +:107C700005EB4917D7F8001B21F40041C7F8001B9A +:107C8000D5F81C1821EA0303C0E704F13F030B4AAF +:107C90002846214605EB83035A60FFF753FE05EBA8 +:107CA0004910D0F8003923F40043C0F80039D5F862 +:107CB0001C3823EA0707D7E7008000100004000201 +:107CC000D0F894201268C0F89820FFF70FBE00008B +:107CD0005831D0F8903049015B5813F4004004D07B +:107CE00013F4001F0CBF0220012070474831D0F868 +:107CF000903049015B5813F4004004D013F4001F86 +:107D00000CBF02200120704700EB8101CB68196A8B +:107D10000B6813604B6853607047000000EB8103F1 +:107D200030B5DD68AA691368D36019B9402B84BFE8 +:107D3000402313606B8A1468D0F890201C4402EB37 +:107D40004110013C09B2B4FBF3F46343033323F065 +:107D5000030343EAC44343F0C043C0F8103B2B681D +:107D600003F00303012B0ED1D2F8083802EB4110C7 +:107D700013F4807FD0F8003B14BF43F0805343F0EE +:107D80000053C0F8003B02EB4112D2F8003B43F035 +:107D90000443C2F8003B30BD2DE9F041D0F89060BB +:107DA00005460C4606EB4113D3F8087B3A07C3F8A7 +:107DB000087B08D5D6F814381B0704D500EB8103DF +:107DC000DB685B689847FA071FD5D6F81438DB07DD +:107DD0001BD505EB8403D968CCB98B69488A5A68EE +:107DE000B2FBF0F600FB16228AB91868DA689042F6 +:107DF0000DD2121AC3E90024302383F311882146DF +:107E00002846FFF78BFF84F31188BDE8F08101233A +:107E100003FA04F26B8923EA02036B81CB68002B1F +:107E2000F3D021462846BDE8F041184700EB810316 +:107E30004A0170B5DD68D0F890306C692668E6605C +:107E400056BB1A444FF40020C2F810092A6802F009 +:107E50000302012A0AB20ED1D3F8080803EB421438 +:107E600010F4807FD4F8000914BF40F0805040F037 +:107E70000050C4F8000903EB4212D2F8000940F0A8 +:107E80000440C2F800090122D3F8340802FA01F1D3 +:107E90000143C3F8341870BD19B9402E84BF402087 +:107EA000206020681A442E8A8419013CB4FBF6F441 +:107EB00040EAC44040F00050C6E700002DE9F84316 +:107EC000D0F8906005460C464F0106EB4113D3F8FD +:107ED000088918F0010FC3F808891CD0D6F81038AB +:107EE000DB0718D500EB8103D3F80CC0DCF81430A5 +:107EF000D3F800E0DA68964530D2A2EB0E024FF0DC +:107F000000091A60C3F80490302383F31188FFF747 +:107F10008DFF89F3118818F0800F1DD0D6F8343802 +:107F20000126A640334217D005EB84030134D5F86F +:107F30009050D3F80CC0E4B22F44DCF8142005EBC9 +:107F40000434D2F800E05168714514D3D5F83438C0 +:107F500023EA0606C5F83468BDE8F883012303FA6E +:107F600001F2038923EA02030381DCF80830002BC5 +:107F7000D1D09847CFE7AEEB0103BCF810008342A5 +:107F800028BF0346D7F8180980B2B3EB800FE3D8B7 +:107F90009068A0F1040959F8048FC4F80080A0EBA0 +:107FA00009089844B8F1040FF5D818440B449060C0 +:107FB0005360C8E72DE9F84FD0F8905004466E6939 +:107FC000AB691E4016F480586E6103D0BDE8F84FCF +:107FD000FDF7F0BF002E12DAD5F8003E9B0705D062 +:107FE000D5F8003E23F00303C5F8003ED5F8043869 +:107FF000204623F00103C5F80438FEF709F83705D9 +:1080000005D52046FFF772FC2046FDF7EFFFB004D0 +:108010000CD5D5F8083813F0060FEB6823F470532D +:108020000CBF43F4105343F4A053EB6031071BD54E +:108030006368DB681BB9AB6923F00803AB61237885 +:10804000052B0CD1D5F8003E9A0705D0D5F8003E97 +:1080500023F00303C5F8003E2046FDF7D9FF63680F +:10806000DB680BB120469847F30200F1BA80B702F3 +:1080700026D5D4F8909000274FF0010A09EB47125B +:10808000D2F8003B03F44023B3F5802F11D1D2F88E +:10809000003B002B0DDA62890AFA07F322EA030398 +:1080A000638104EB8703DB68DB6813B13946204644 +:1080B00098470137D4F89430FFB29B689F42DDD9CE +:1080C000F00619D5D4F89000026AC2F30A1702F03C +:1080D0000F0302F4F012B2F5802F00F0CA80B2F55F +:1080E000402F09D104EB8303002200F58050DB68A8 +:1080F0001B6A974240F0B0803003D5F8185835D548 +:10810000E90303D500212046FFF746FEAA0303D565 +:1081100001212046FFF740FE6B0303D502212046D4 +:10812000FFF73AFE2F0303D503212046FFF734FE65 +:10813000E80203D504212046FFF72EFEA90203D54D +:1081400005212046FFF728FE6A0203D506212046B6 +:10815000FFF722FE2B0203D507212046FFF71CFE66 +:10816000EF0103D508212046FFF716FE700340F10A +:10817000A780E90703D500212046FFF79FFEAA0745 +:1081800003D501212046FFF799FE6B0703D5022195 +:108190002046FFF793FE2F0703D503212046FFF764 +:1081A0008DFEEE0603D504212046FFF787FEA806C4 +:1081B00003D505212046FFF781FE690603D5062178 +:1081C0002046FFF77BFE2A0603D507212046FFF74E +:1081D00075FEEB0574D520460821BDE8F84FFFF782 +:1081E0006DBED4F890904FF0000B4FF0010AD4F818 +:1081F00094305FFA8BF79B689F423FF638AF09EBEC +:108200004713D3F8002902F44022B2F5802F20D181 +:10821000D3F80029002A1CDAD3F8002942F0904252 +:10822000C3F80029D3F80029002AFBDB3946D4F82B +:108230009000FFF787FB22890AFA07F322EA03037B +:10824000238104EB8703DB689B6813B13946204622 +:1082500098470BF1010BCAE7910701D1D0F80080D4 +:10826000072A02F101029CBF03F8018B4FEA18288C +:108270003FE704EB830300F58050DA68D2F818C0BA +:10828000DCF80820DCE9001CA1EB0C0C00218F427B +:1082900008D1DB689B699A683A449A605A683A4404 +:1082A0005A6029E711F0030F01D1D0F800808C4506 +:1082B00001F1010184BF02F8018B4FEA1828E6E7BB +:1082C000BDE8F88F08B50348FFF774FEBDE8084025 +:1082D000FFF744BA3C65002008B50348FFF76AFE83 +:1082E000BDE80840FFF73ABAD8650020D0F89030D2 +:1082F00003EB4111D1F8003B43F40013C1F8003BFC +:1083000070470000D0F8903003EB4111D1F80039EC +:1083100043F40013C1F8003970470000D0F89030E2 +:1083200003EB4111D1F8003B23F40013C1F8003BEB +:1083300070470000D0F8903003EB4111D1F80039BC +:1083400023F40013C1F8003970470000064BD3F83E +:10835000DC200243C3F8DC20D3F804211043C3F827 +:108360000401D3F8043170470044025808B53C4B6F +:108370004FF0FF31D3F8802062F00042C3F8802034 +:10838000D3F8802002F00042C3F88020D3F8802088 +:10839000D3F88420C3F88410D3F884200022C3F8D3 +:1083A0008420D3F88400D86F40F0FF4040F4FF00F1 +:1083B00040F4DF4040F07F00D867D86F20F0FF40E6 +:1083C00020F4FF0020F4DF4020F07F00D867D86F52 +:1083D000D3F888006FEA40506FEA5050C3F8880025 +:1083E000D3F88800C0F30A00C3F88800D3F88800E7 +:1083F000D3F89000C3F89010D3F89000C3F8902001 +:10840000D3F89000D3F89400C3F89410D3F89400F4 +:10841000C3F89420D3F89400D3F89800C3F89810C8 +:10842000D3F89800C3F89820D3F89800D3F88C00BC +:10843000C3F88C10D3F88C00C3F88C20D3F88C00D0 +:10844000D3F89C00C3F89C10D3F89C10C3F89C2070 +:10845000D3F89C30FCF730FABDE8084000F0D6B9FC +:108460000044025808B50122534BC3F80821534B6E +:10847000D3F8F42042F00202C3F8F420D3F81C2110 +:1084800042F00202C3F81C210222D3F81C314C4BEB +:10849000DA605A689104FCD54A4A1A6001229A604F +:1084A000494ADA6000221A614FF440429A61444B13 +:1084B0009A699204FCD51A6842F480721A603F4BA4 +:1084C0001A6F12F4407F04D04FF480321A670022F2 +:1084D0001A671A6842F001021A60384B1A6850078E +:1084E000FCD500221A611A6912F03802FBD1012171 +:1084F00019604FF0804159605A67344ADA62344A51 +:108500001A611A6842F480321A602C4B1A6891037F +:10851000FCD51A6842F480521A601A689204FCD59D +:108520002C4A2D499A6200225A63196301F57C0195 +:10853000DA6301F5E77199635A64284A1A64284A94 +:10854000DA621A6842F0A8521A601C4B1A6802F0EC +:108550002852B2F1285FF9D148229A614FF488621B +:10856000DA6140221A621F4ADA641F4A1A651F4AFA +:108570005A651F4A9A6532231E4A1360136803F036 +:108580000F03022BFAD10D4A136943F00303136161 +:10859000136903F03803182BFAD14FF00050FFF79E +:1085A000D5FE4FF08040FFF7D1FE4FF00040BDE810 +:1085B0000840FFF7CBBE00BF0080005100440258C6 +:1085C0000048025800C000F0020000010000FF0156 +:1085D000008890083220600063020901470E0508F8 +:1085E000DD0BBF0120000020000001100910E00099 +:1085F00000010110002000524FF0B04208B5D2F83F +:10860000883003F00103C2F8883023B1044A1368AC +:108610000BB150689847BDE80840FFF79FB800BF0E +:10862000B46600204FF0B04208B5D2F8883003F0AD +:108630000203C2F8883023B1044A93680BB1D068B2 +:108640009847BDE80840FFF789B800BFB46600202E +:108650004FF0B04208B5D2F8883003F00403C2F8F6 +:10866000883023B1044A13690BB150699847BDE8BB +:108670000840FFF773B800BFB46600204FF0B04267 +:1086800008B5D2F8883003F00803C2F8883023B167 +:10869000044A93690BB1D0699847BDE80840FFF7D9 +:1086A0005DB800BFB46600204FF0B04208B5D2F804 +:1086B000883003F01003C2F8883023B1044A136AEB +:1086C0000BB1506A9847BDE80840FFF747B800BFB4 +:1086D000B46600204FF0B04310B5D3F8884004F4DE +:1086E0007872C3F88820A30604D5124A936A0BB1A6 +:1086F000D06A9847600604D50E4A136B0BB1506BD5 +:108700009847210604D50B4A936B0BB1D06B984761 +:10871000E20504D5074A136C0BB1506C9847A305CA +:1087200004D5044A936C0BB1D06C9847BDE8104057 +:10873000FFF714B8B46600204FF0B04310B5D3F87B +:10874000884004F47C42C3F88820620504D5164AA8 +:10875000136D0BB1506D9847230504D5124A936DE4 +:108760000BB1D06D9847E00404D50F4A136E0BB1DE +:10877000506E9847A10404D50B4A936E0BB1D06E8E +:108780009847620404D5084A136F0BB1506F98479D +:10879000230404D5044A936F0BB1D06F9847BDE80A +:1087A0001040FEF7DBBF00BFB466002008B50348E9 +:1087B000FCF74AFCBDE80840FEF7D0BFC8360020F1 +:1087C00008B50348FCF744FDBDE80840FEF7C6BF06 +:1087D0002039002008B50348FCF73AFDBDE8084001 +:1087E000FEF7BCBF8C39002008B50348FCF730FD0C +:1087F000BDE80840FEF7B2BFF839002008B500F028 +:10880000BDFCBDE80840FEF7A9BF0000062108B581 +:108810000846FCF7A3FD06210720FCF79FFD062173 +:108820000820FCF79BFD06210920FCF797FD062197 +:108830000A20FCF793FD06211720FCF78FFD062187 +:108840002820FCF78BFD09217A20FCF787FD092100 +:108850003120FCF783FD07213220FCF77FFD0C213E +:108860002620FCF77BFD0C212720FCF777FD0C214F +:108870005220BDE80840FCF771BD000008B5FFF7C5 +:1088800075FD00F043FCFDF749F9FDF7E7F8FDF74A +:108890001FFBFDF7F1F9FEF7B3F9BDE8084000F062 +:1088A00029BA000030B50433039C0172002104FB97 +:1088B0000325C160C0E90653049B0363059BC0E91F +:1088C0000000C0E90422C0E90842C0E90A1143637C +:1088D00030BD00000022416AC260C0E90411C0E955 +:1088E0000A226FF00101FDF701BF0000D0E9043258 +:1088F000934201D1C2680AB9181D70470020704721 +:10890000036919600021C2680132C260C269134460 +:1089100082699342036124BF436A0361FDF7DABEB3 +:1089200038B504460D46E3683BB162690020131D6B +:108930001268A3621344E36207E0237A33B929463D +:108940002046FDF7B7FE0028EDDA38BD6FF00100D4 +:10895000FBE70000C368C269013BC360436913447D +:1089600082699342436124BF436A43610023836267 +:10897000036B03B11847704770B53023044683F387 +:108980001188866A3EB9FFF7CBFF054618B186F31A +:108990001188284670BDA36AE26A13F8015B93420E +:1089A000A36202D32046FFF7D5FF002383F311888B +:1089B000EFE700002DE9F84F04460E4617469846AB +:1089C0004FF0300989F311880025AA46D4F828B061 +:1089D000BBF1000F09D141462046FFF7A1FF20B1AE +:1089E0008BF311882846BDE8F88FD4E90A12A7EB6B +:1089F000050B521A934528BF9346BBF1400F1BD974 +:108A0000334601F1400251F8040B914243F8040B44 +:108A1000F9D1A36A403640354033A362D4E90A2332 +:108A20009A4202D32046FFF795FF8AF31188BD4290 +:108A3000D8D289F31188C9E730465A46F9F756F972 +:108A4000A36A5E445D445B44A362E7E710B5029C01 +:108A50000433017203FB0421C460C0E90613002340 +:108A6000C0E90A33039B0363049BC0E90000C0E92B +:108A70000422C0E90842436310BD0000026A6FF09F +:108A80000101C260426AC0E904220022C0E90A2250 +:108A9000FDF72CBED0E904239A4201D1C26822B965 +:108AA000184650F8043B0B60704700231846FAE75D +:108AB000C3680021C2690133C360436913448269FA +:108AC0009342436124BF436A4361FDF703BE000044 +:108AD00038B504460D46E3683BB1236900201A1DF2 +:108AE000A262E2691344E36207E0237A33B92946BC +:108AF0002046FDF7DFFD0028EDDA38BD6FF00100FC +:108B0000FBE7000003691960C268013AC260C269EC +:108B1000134482699342036124BF436A03610023C3 +:108B20008362036B03B118477047000070B53023B0 +:108B30000D460446114683F31188866A2EB9FFF765 +:108B4000C7FF10B186F3118870BDA36A1D70A36AB8 +:108B5000E26A01339342A36204D3E16920460439F7 +:108B6000FFF7D0FF002080F31188EDE72DE9F84FE3 +:108B700004460D46904699464FF0300A8AF3118814 +:108B80000026B346A76A4FB949462046FFF7A0FF23 +:108B900020B187F311883046BDE8F88FD4E90A0781 +:108BA0003A1AA8EB0607974228BF1746402F1BD951 +:108BB00005F1400355F8042B9D4240F8042BF9D1F0 +:108BC000A36A40364033A362D4E90A239A4204D30D +:108BD000E16920460439FFF795FF8BF3118846457C +:108BE000D9D28AF31188CDE729463A46F9F77EF8BB +:108BF000A36A3D443E443B44A362E5E7D0E9042335 +:108C00009A4217D1C3689BB1836A8BB1043B9B1A0C +:108C10000ED01360C368013BC360C3691A44836903 +:108C20009A42026124BF436A0361002383620123E5 +:108C3000184670470023FBE701F01F03F0B502F070 +:108C40001F0456095A1C0123B6EB511F50F8265039 +:108C500003FA02F34FEA511703F1FF333DBF50F817 +:108C60002720C4F12000134003EA05003BBF03FAAC +:108C700000F225FA04F0E0401043F0BD70B57E220A +:108C80007F210546FFF7D8FF18B1012819D0002031 +:108C900070BD3E2249212846FFF7CEFF2F22044611 +:108CA00031212846FFF7C8FF06460134502202361C +:108CB00053212846B440FFF7BFFF093804FA00F0FB +:108CC000E6E7302245212846FFF7B6FF0130800253 +:108CD000DEE7000090F8D63090F8D7201B0403EBB5 +:108CE000026390F8D42090F8D500134403EB0020E1 +:108CF0007047000000F018BA014B586A704700BF77 +:108D0000000C0040034B002258631A610222DA6013 +:108D1000704700BF000C0040014B0022DA60704732 +:108D2000000C0040014B5863704700BF000C00402E +:108D3000024B034A1A60034A5A6070478C6600204F +:108D40003867002000000220074B494210B55C68DC +:108D5000201A08401968821A8A4203D3A24201D815 +:108D60005A6010BD0020FCE78C66002008B5302357 +:108D700083F31188FFF7E8FF002383F3118808BD10 +:108D80000448054B03600023C0E901330C3000F0B8 +:108D900017B900BF946600206D8D0008CB1D083AFE +:108DA00023F00703591A521A10B4D2080024C0E95C +:108DB000004384600C301C605A605DF8044B00F086 +:108DC000FFB800002DE9F74F364FCD1D884600282B +:108DD00018BF0746082A4FEAD50538BF082207F111 +:108DE0000C003C1D9146019000F02CF9019809F10E +:108DF0000701C9F1000E2246246864B900F02CF97D +:108E00003B68CBB308224946E8009847044698B32C +:108E100040E9027830E004EB010CD4F804A00CEA3D +:108E20000E0C0AF10106ACF1080304EBC6069E42E3 +:108E3000E1D9A6EB0C0CB5EBEC0F4FEAEC0BDAD852 +:108E40009C421DD204F10802AB45A3EB02024FEA9B +:108E5000E202626009D9691CED4303EBC1025D4483 +:108E60005560256843F8315022601C46C3F80480E1 +:108E700044F8087B00F0F0F8204603B0BDE8F08F1E +:108E8000AA45216802D111602346EEE7013504EBC3 +:108E9000C50344F8351003F10801761AF6105E6038 +:108EA0001360F1E79466002073B50446A0F108054D +:108EB00050F8080C54F8043C061D0C3007330190A0 +:108EC000DB0844F8043C00F0BDF8334601989E42AC +:108ED0001A6801D0AB4228D20AB1954225D244F893 +:108EE000082C54F8042C1D60013254F8081C05EBC2 +:108EF000C206B14206D14E68324444F8042C0A68D6 +:108F000044F8082C5E68711C03EBC1018D4207D147 +:108F100054F8042C013232445A6054F8082C1A6078 +:108F200002B0BDE8704000F097B81346CFE70000EC +:108F3000FEE7000070B51E4B0025044686B0586061 +:108F40000E4605638163FEF7E1FB04F12803A5608B +:108F50006563C4E90A3304F11003C4E904334FF034 +:108F6000FF33C4E90044C4E90635FFF7C5FE2B46CC +:108F7000024604F13C012046C4E9082380230D4A3F +:108F80006567FDF711FB7368E0600B4A036201231C +:108F9000009280F824306846F26801923269CDE987 +:108FA0000223064BCDE90435FDF732FB06B070BD58 +:108FB00010490020689C0008609C0008318F000860 +:108FC0000023C0E9000083600361704770B51C4B4B +:108FD00005468468DE685CB3B44213D1036901338B +:108FE000036170BDA36094F8243083B1062B15D1C2 +:108FF000A06A2146D4E9003213605A60FDF740FAB6 +:10900000A36A9C68B368A2689A42EBD306E0D4E9ED +:109010000032204613605A60FDF742FA2846314676 +:10902000FDF72EFAB5620620BDE87040FDF73ABAAA +:109030000369866001330361336BC3603063D0E73B +:109040006846002008B5302383F31188FFF7BEFF80 +:10905000002383F3118808BD194BD96883688B42BC +:1090600010B520D1302383F311880269013A0261DF +:10907000B2B90468C368A0420B631ED04A6B9BB9A7 +:1090800001238A60036103681A68026050601A6BEA +:109090008360C26018631846FDF702FAFDF752FAC2 +:1090A000002383F3118810BD1C68A34203D0A46879 +:1090B000A24238BF2246DB68E1E78260F0E700BFEA +:1090C00068460020024A536B18435063704700BF44 +:1090D0006846002038B5EFF311859DB9EFF305849C +:1090E000C4F30804302334B183F31188FDF736FC50 +:1090F00085F3118838BD83F31188FDF72FFC84F3C5 +:10910000118838BDBDE83840FDF728BC0023054A6A +:1091100019460133102BC2E9001102F10802F8D1FF +:10912000704700BFB4660020114BD3F8E82042F02E +:109130000802C3F8E820D3F8102142F00802C3F86F +:1091400010210C4AD3F81031D36B43F00803D363DA +:10915000C722094B9A624FF0FF32DA6200229A610D +:109160005A63DA605A6001225A611A60704700BF80 +:10917000004402580010005C000C0040094A08B589 +:109180001169D3680B40D9B29B076FEA01011161E5 +:1091900007D5302383F31188FDF7FAF9002383F311 +:1091A000118808BD000C004010B5013902449042FE +:1091B00001D1002005E0037811F8014FA34201D04E +:1091C000181B10BD0130F2E7884210B501EB020414 +:1091D00002D98442234607D8431EA14208D011F881 +:1091E000012B03F8012FF8E7024401468A4200D11F +:1091F00010BD13F8014D02F8014DF7E7C9B203465F +:1092000010F8012B1AB18A42F9D11846704700298B +:1092100018BF0023F9E70000034611F8012B03F8FB +:10922000012B002AF9D1704710B50139034632B13C +:1092300011F8014F03F8014B013A002CF7D11A4401 +:109240000021934200D110BD03F8011BF9E7000093 +:109250004D4435002D2D0A002F6172647570696CC4 +:109260006F742E6162696E002F6172647570696C33 +:109270006F742D7665726966792E6162696E002F52 +:109280006172647570696C6F742D666C6173682EA1 +:109290006162696E002F6172647570696C6F742D04 +:1092A000666C61736865642E6162696E000000001F +:1092B0000000000000000000050F0008A10F0008DA +:1092C00051110008D90F0008990F00080000000094 +:1092D00000000000010F0008AD0F00088911000810 +:1092E000FD0E0008090F000853544D333248373F34 +:1092F0003F3F0053544D3332483733782F3732785D +:109300000053544D3332483734332F3735332F37EA +:109310003530000001105A00031059000120580098 +:10932000032056002F000000537563636573736656 +:10933000756C6C79206D6F756E7465642053444351 +:109340006172642028736C6F77646F776E3D25754A +:10935000290A0000EB769045584641542020200011 +:109360004641543332202020000000002A3A3C3E7F +:109370007C223F7F002B2C3B3D5B5D0043554541EC +:109380004141414345454549494941414592924FF3 +:109390004F4F5555594F554F9C4F9E9F41494F55E3 +:1093A000A5A5A6A7A8A9AAABACADAEAFB0B1B2B304 +:1093B000B4414141B8B9BABBBCBDBEBFC0C1C2C354 +:1093C000C4C54141C8C9CACBCCCDCECFD1D145450A +:1093D0004549494949D9DADBDCDD49DF4FE14F4FE7 +:1093E0004F4FE6E8E85555555959EEEFF0F1F2F3D5 +:1093F000F4F5F6F7F8F9FAFBFCFDFEFF01030507AB +:10940000090E10121416181C1E00000061001A0329 +:10941000E0001703F8000703FF00010078010001D6 +:10942000300132010601390110014A012E01790192 +:10943000060180014D004302810182018201840105 +:10944000840186018701870189018A018B018B01D3 +:109450008D018E018F019001910191019301940181 +:10946000F60196019701980198013D029B019C012C +:109470009D0120029F01A001A001A201A201A4015F +:10948000A401A601A701A701A901AA01AB01AC0192 +:10949000AC01AE01AF01AF01B101B201B301B30143 +:1094A000B501B501B701B801B801BA01BB01BC01F2 +:1094B000BC01BE01F701C001C101C201C301C40169 +:1094C000C501C401C701C801C701CA01CB01CA0156 +:1094D000CD011001DD0101008E01DE011201F30159 +:1094E0000300F101F401F401F80128012202120144 +:1094F0003A020900652C3B023B023D02662C3F020A +:1095000040024102410246020A0153024000810129 +:109510008601550289018A0158028F015A02900181 +:109520005C025D025E025F029301610262029401CD +:109530006402650266026702970196016A02622C64 +:109540006C026D026E029C01700271029D01730239 +:1095500074029F0176027702780279027A027B0216 +:109560007C02642C7E027F02A60181028202A90194 +:109570008402850286028702AE014402B101B20173 +:1095800045028D028E028F0290029102B7017B0389 +:109590000300FD03FE03FF03AC03040086038803FE +:1095A00089038A03B1031103C2030200A303A303C7 +:1095B000C4030803CC0303008C038E038F03D8037A +:1095C0001801F2030A00F903F303F403F503F603A9 +:1095D000F703F703F903FA03FA03300420035004F6 +:1095E0001007600422018A043601C1040E01CF0471 +:1095F0000100C004D00444016105260400000000FD +:109600007D1D0100632C001E9601A01E5A01001F43 +:109610000806101F0606201F0806301F0806401FF8 +:109620000606511F0700591F521F5B1F541F5D1F65 +:10963000561F5F1F601F0806701F0E00BA1FBB1F5A +:10964000C81FC91FCA1FCB1FDA1FDB1FF81FF91F56 +:10965000EA1FEB1FFA1FFB1F801F0806901F08065A +:10966000A01F0806B01F0400B81FB91FB21FBC1FFF +:10967000CC1F0100C31FD01F0206E01F0206E51F1A +:109680000100EC1FF31F0100FC1F4E2101003221DD +:1096900070211002842101008321D0241A05302C6E +:1096A0002F04602C0201672C0601752C0201802C0E +:1096B0006401002D260841FF1A030000C700FC00CA +:1096C000E900E200E400E000E500E700EA00EB006A +:1096D000E800EF00EE00EC00C400C500C900E600A1 +:1096E000C600F400F600F200FB00F900FF00D6000F +:1096F000DC00F800A300D800D7009201E100ED00E3 +:10970000F300FA00F100D100AA00BA00BF00AE00D9 +:10971000AC00BD00BC00A100AB00BB0091259225B0 +:10972000932502252425C100C200C000A90063259D +:10973000512557255D25A200A500102514253425A7 +:109740002C251C2500253C25E300C3005A25542563 +:1097500069256625602550256C25A400F000D00001 +:10976000CA00CB00C8003101CD00CE00CF001825C3 +:109770000C2588258425A600CC008025D300DF0099 +:10978000D400D200F500D500B500FE00DE00DA00FE +:10979000DB00D900FD00DD00AF00B400AD00B1007A +:1097A0001720BE00B600A700F700B800B000A80060 +:1097B000B700B900B300B200A025A000100002401D +:1097C000080002400008024000000B002800024090 +:1097D000080002400408024006010C00400002405C +:1097E000080002400808024010020D005800024024 +:1097F000080002400C08024016030E0070000240F0 +:109800000C0002401008024000040F0088000240D3 +:109810000C0002401408024006051000A00002409F +:109820000C0002401808024010061100B800024067 +:109830000C0002401C08024016072F0010040240D2 +:1098400008040240200802400008380028040240B2 +:10985000080402402408024006093900400402407E +:109860000804024028080240100A3A005804024046 +:10987000080402402C080240160B3B007004024012 +:109880000C04024030080240000C3C0088040240F6 +:109890000C04024034080240060D4400A0040240BB +:1098A0000C04024038080240100E4500B804024083 +:1098B0000C0402403C080240160F46000100000064 +:1098C0000000000000960000000000000000000002 +:1098D0000000000000000000000000000000000088 +:1098E000F96B0008FD6B0008F1560008295A0008C2 +:1098F00085560008AD560008D55600086D5600087C +:1099000000000000DD5A0008C95A0008055B000885 +:10991000F15A0008FD5A0008E95A0008D55A000813 +:10992000C15A0008115B000800000000F55B000848 +:10993000E15B00081D5C0008095C0008155C00087C +:10994000015C0008ED5B0008D95B0008295C000899 +:109950000000000001000000000000006330000073 +:109960005C9900080000000000000000E0460020B4 +:10997000104900200000812A00000000AAAAAAAA1B +:1099800000000024FFFE00000000000000A00A000C +:109990000001000000000000AAAAAAAA000000001E +:1099A000FFFF000000000000000000001400AA56A5 +:1099B00000000000AAAAAAAA14005554FFFF000044 +:1099C00000000000CCCC0C0020681A000000000051 +:1099D000AAAA8AAA10541500FFFF0000000C700705 +:1099E000770000004081020100100000AAAAAAAA84 +:1099F00000410100F7FF00000000007007000000B8 +:109A00000000000000000000AAAAAAAA00000000AE +:109A1000FFFF000000000000000000000000000048 +:109A200000000000AAAAAAAA00000000FFFF000090 +:109A30000000000000000000000000000000000026 +:109A4000AAAAAAAA00000000FFFF00000000000070 +:109A5000000000000000000000000000AAAAAAAA5E +:109A600000000000FFFF00000000000000000000F8 +:109A70000000000000000000AAAAAAAA000000003E +:109A8000FFFF0000000000000000000000000000D8 +:109A900000000000AAAAAAAA00000000FFFF000020 +:109AA00000000000000000004865782F50726F66CB +:109AB00069434E430025424F415244252D424C00FC +:109AC0002553455249414C2500000000020000008A +:109AD00000000000155E0008855E000840004000A0 +:109AE000C0610020D06100200200000000000000E2 +:109AF0000300000000000000CD5E00080000000030 +:109B000010000000E06100200000000001000000E3 +:109B1000000000003C65002001010200F56C000817 +:109B2000056C0008A16C0008856C0008430000006B +:109B3000349B000809024300020100C032090400FE +:109B400000010202010005240010010524010001AA +:109B5000042402020524060001070582030800FF11 +:109B600009040100020A000000070501024000008C +:109B7000070581024000000012000000809B0008E1 +:109B80001201100102000040AE2D16100002010269 +:109B9000030100000403090425424F4152442500FB +:109BA000437562654F72616E67652D626473686F9D +:109BB000740030313233343536373839414243441A +:109BC00045460000000000200000020002000000E6 +:109BD0000000003000000400080000000000002425 +:109BE00000000800040000000004000000FC000069 +:109BF00002000000000004300080000008000000A7 +:109C00000000003800000100010000001F1C1F1EA2 +:109C10001F1E1F1F1E1F1E1F1F1D1F1E1F1E1F1F5B +:109C20001E1F1E1F0000000029600008E1620008DE +:109C30008D630008400040007466002074660020B8 +:109C40000100000084660020800000004001000048 +:109C500008000000000100000010000008000000E3 +:109C600069646C65000000006D61696E002C043849 +:109C7000040438080C10141C2024252600000000C1 +:109C8000000064040100040000000000000C00104B +:109C900028303400D467FF7F01000000000000007E +:109CA0008C0000000000000000001E00000000000A +:109CB000FF00000018490020203900208C390020C6 +:109CC000F839002000000000E8920008830400003A +:109CD000F392000850040000019300080100000006 +:109CE0000000000000960000000008009600000040 +:109CF0000008000004000000949B00080000000021 +:109D00000000000000000000000000000000000053 +:049D1000000000004F :00000001FF diff --git a/Tools/bootloaders/CubeOrange-joey_bl.bin b/Tools/bootloaders/CubeOrange-joey_bl.bin index 3270f22c878bf9..9209ca80b049d6 100755 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 index 6ad3df3385e275..1393b512a6f597 100644 --- a/Tools/bootloaders/CubeOrange-joey_bl.hex +++ b/Tools/bootloaders/CubeOrange-joey_bl.hex @@ -1,1105 +1,2515 @@ :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 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008F17600089A +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008FD8500082986000885 +:100060005586000881860008AD860008094600080C +:10007000314600085D46000889460008B54600087C +:10008000DD46000809470008E3020008E302000813 +:10009000E3020008E3020008E3020008D986000832 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008C5870008D98700088A +:1000E0003D870008E3020008E3020008E30200087D +:1000F000E3020008E3020008E302000835470008B5 +:10010000E3020008B187000801880008E302000844 +:10011000E3020008E3020008E3020008E30200082B +:100120006147000889470008B5470008E147000813 +:100130000D480008E3020008E3020008E30200089B +:10014000E3020008E3020008E3020008E3020008FB +:1001500035480008614800088D480008E30200089F +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008DD820008E3020008E302000851 +:10018000E3020008E3020008ED870008E30200082C +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008C9820008E3020008E302000805 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F032FA3D +:1003500006F0A4FB4FF055301F491B4A91423CBFA9 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F04AFA06F002FC0A +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F032BA000600200022002033 +:1003D0000000000808ED00E00000002000060020FA +:1003E000989C00080022002074220020782200201F +:1003F00034670020E0020008E0020008E002000884 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F01AF9FEE706F0DA +:1004300073F800DFFEE7000053B94AB9002908BF8E +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000FFF901F0AFFB06F0C1FE054606F0C6FF5B +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F0B9FE0CB135 +:1007700000F078F801F036FB00F026FD08B100F03B +:1007800071F8284600F01CF9F9E70025ECE705466A +:10079000EAE700BF010007B008B501F09DF9A0F13C +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0ADF903B05DF804FB19 +:1007C00038B5302383F31188174803680BB106F05E +:1007D0002BF80023154A4FF47A71134806F01AF8E3 +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F056FA3223636082 +:100810002B78032B07D163682BB9022001F04CFA27 +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F02BBA0220C0 +:1008500001F01EBA024B00225A607047902200201D +:1008600098230020F8B5504B504A1C4619680131B6 +:1008700000F0998004339342F8D162684C4B9A425D +:1008800040F291804B4B9B6803F1006303F500330A +:100890009A4280F08880002001F06CF90220FFF776 +:1008A000CBFF454B0021D3F8E820C3F8E810D3F87C +:1008B0001021C3F81011D3F81021D3F8EC20C3F89D +:1008C000EC10D3F81421C3F81411D3F81421D3F881 +:1008D000F020C3F8F010D3F81821C3F81811D3F89A +:1008E0001821D3F8802042F00062C3F88020D3F8AA +:1008F000802022F00062C3F88020D3F88020D3F853 +:10090000802042F00072C3F88020D3F8802022F0CB +:100910000072C3F88020D3F8803072B64FF0E02325 +:10092000C3F8084DD4E90004BFF34F8FBFF36F8FB6 +:10093000224AC2F88410BFF34F8F536923F48033E7 +:100940005361BFF34F8FD2F8803043F6E076C3F3A4 +:10095000C905C3F34E335B0103EA060C29464CEA92 +:1009600081770139C2F87472F9D2203B13F1200F5C +:10097000F2D1BFF34F8FBFF36F8FBFF34F8FBFF332 +:100980006F8F536923F4003353610023C2F8503250 +:10099000BFF34F8FBFF36F8F302383F311888546EA +:1009A00080F308882047F8BD0000020820000208F4 +:1009B000FFFF0108002200200044025800ED00E083 +:1009C0002DE9F04F93B0B44B2022FF2100900AA8EC +:1009D0009D6801F0B1F9B14A1378A3B90121B0487B +:1009E00011700360302383F3118803680BB105F0A5 +:1009F0001BFF0023AB4A4FF47A71A94805F00AFFA8 +:100A0000002383F31188009B13B1A74B009A1A604F +:100A1000A64A1378032B03D000231370A24A536015 +:100A20004FF0000A009CD3465646D146012001F003 +:100A300039F924B19C4B1B68002B00F02682002062 +:100A400001F04AF80390039B002BF2DB012001F038 +:100A50001FF9039B213B1F2BE8D801A252F823F07A +:100A6000E10A0008090B00089D0B00082D0A000888 +:100A70002D0A00082D0A00082F0C0008FF0D0008A1 +:100A8000190D00087B0D0008A30D0008C90D000812 +:100A90002D0A0008DB0D00082D0A00084D0E000885 +:100AA000810B00082D0A0008910E0008ED0A0008CD +:100AB000810B00082D0A00087B0D00082D0A000894 +:100AC0002D0A00082D0A00082D0A00082D0A00082A +:100AD0002D0A00082D0A00082D0A00089D0B0008A9 +:100AE0000220FFF759FE002840F0F981009B022107 +:100AF00005A8BAF1000F08BF1C4641F21233ADF849 +:100B0000143001F007F891E74FF47A7000F0E4FF39 +:100B1000071EEBDB0220FFF73FFE0028E6D0013F77 +:100B2000052F00F2DE81DFE807F0030A0D1013360F +:100B30000523042105A8059300F0ECFF17E004212C +:100B40005548F9E704215A48F6E704215948F3E7E4 +:100B50004FF01C08404608F1040801F00DF804218C +:100B6000059005A800F0D6FFB8F12C0FF2D10120B6 +:100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F +:100B800001F026F926B10BF00B030B2B08BF002454 +:100B9000FFF70AFE4AE704214748CDE7002EA5D01B +:100BA0000BF00B030B2BA1D10220FFF7F5FD07463D +:100BB00000289BD00120002600F0DCFF0220FFF778 +:100BC0003BFE1FFA86F8404600F0E4FF0446B0B151 +:100BD000039940460136A1F140025142514100F0D3 +:100BE000E9FF0028EDD1BA46044641F21213022172 +:100BF00005A83E46ADF8143000F08CFF16E72546F8 +:100C00000120FFF719FE244B9B68AB4207D9284609 +:100C100000F0B2FF013040F067810435F3E70025B2 +:100C2000224BBA463E461D701F4B5D60A8E7002E62 +:100C30003FF45CAF0BF00B030B2B7FF457AF02209C +:100C4000FFF7FAFD322000F047FFB0F10008FFF691 +:100C50004DAF18F003077FF449AF0F4A08EB0503C7 +:100C6000926893423FF642AFB8F5807F3FF73EAFC0 +:100C7000124BB845019323DD4FF47A7000F02CFF3E +:100C80000390039A002AFFF631AF039A0137019BC4 +:100C900003F8012BEDE700BF002200209423002081 +:100CA00078220020C107000898230020902200200D +:100CB00004220020082200200C2200209422002080 +:100CC000C820FFF769FD074600283FF40FAF1F2D2E +:100CD00011D8C5F120020AAB25F003008449424532 +:100CE000184428BF4246019201F000F8019AFF2102 +:100CF0007F4801F021F84FEAA803C8F387027C4936 +:100D00002846019301F020F8064600283FF46DAF15 +:100D1000019B05EB830533E70220FFF73DFD00282B +:100D20003FF4E4AE00F064FF00283FF4DFAE00279C +:100D3000B846704B9B68BB4218D91F2F11D80A9B2D +:100D400001330ED027F0030312AA134453F8203CBA +:100D500005934046042205A9043701F003F98046B3 +:100D6000E7E7384600F008FF0590F2E7CDF8148079 +:100D7000042105A800F0CEFE02E70023642104A8A8 +:100D8000049300F0BDFE00287FF4B0AE0220FFF710 +:100D900003FD00283FF4AAAE049800F01FFF059061 +:100DA000E6E70023642104A8049300F0A9FE0028CC +:100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 +:100DC000049800F00DFFEAE70220FFF7E5FC002899 +:100DD0003FF48CAE00F01CFFE1E70220FFF7DCFCE3 +:100DE00000283FF483AE05A9142000F017FF074642 +:100DF0000421049004A800F08DFE3946B9E73220A2 +:100E000000F06AFE071EFFF671AEBB077FF46EAE00 +:100E1000384A07EB0903926893423FF667AE022017 +:100E2000FFF7BAFC00283FF461AE27F003074F44F8 +:100E3000B9453FF4A5AE484609F1040900F09CFE0F +:100E40000421059005A800F065FEF1E74FF47A70E3 +:100E5000FFF7A2FC00283FF449AE00F0C9FE0028CD +:100E600044D00A9B01330BD008220AA9002000F0CD +:100E70006BFF00283AD02022FF210AA800F05CFF77 +:100E8000FFF792FC1C4805F0F1FB13B0BDE8F08FB2 +:100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 +:100EA0000023642105A8059300F02AFE07460028C8 +:100EB0007FF41CAE0220FFF76FFC804600283FF451 +:100EC00015AEFFF771FC41F2883005F0CFFB0598B5 +:100ED00000F0C6FF46463C4600F07AFFA6E506460F +:100EE0004EE64FF0000901E6BA467EE637467CE65C +:100EF0009422002000220020A086010070470000FC +:100F000070470000704700002DE9F04100F5803780 +:100F1000044616463B7C5BB9C0681030204400F0A4 +:100F2000E5FEE5683544B5F5004FE56002D816B139 +:100F3000BDE8F081DEB905F07F0605F11000002163 +:100F4000C6F180062044F6B232462E4400F0F4FE8C +:100F5000A06804F11008324600F10060414600F537 +:100F6000003006F05FF830B901233B74E0E74FF43E +:100F700000463546ECE7A26805F1100140463244D0 +:100F80002144A260E268521BE26000F0AFFE022042 +:100F9000BDE8F04100F090BE183000F0E9BC000060 +:100FA00010B5044600F0FAFF204610BD10B5044607 +:100FB00000F0F4FF204610BDC3B280B2A3F141029D +:100FC000052A02D8373800B27047613B052B94BF21 +:100FD00057383038F7E70000F8B50446154608469C +:100FE00003220C4900F08CFE014688B908346F1CBE +:100FF00015F91100FFF7E0FF064617F9110001315E +:10100000FFF7DAFF102940EA061004F8010BEFD1D0 +:10101000F8BD00BF549200082DE9F04FADF53F7DBB +:101020000746416801222AA802F09AFE002840F0F3 +:1010300087800646824681461125DFF80C81DFF85D +:101040000CB101AB4FF4805241462AA802F0E8FFF0 +:10105000002875D1019AB2F5805F71D8002A65D059 +:101060000446019A9442ECD2282D0FD008DC132DAF +:101070002DD01E2D39D0112D13D00134A4B2F0E79C +:10108000322D2DD0372D2FD02D2DF6D13B68121BB0 +:1010900008EB040138461B692D259847BDF804402C +:1010A000EBE7121B022A09D9594608EB040000F0AD +:1010B00027FE18B902342825A4B2DEE718F8043058 +:1010C0003A2B3DD00A2B1CBFA1461325D5E718F8B3 +:1010D00004300A2B34D03A2B04BFA2463225CCE789 +:1010E00018F80430202BC8D0264618F804300A2BF4 +:1010F0001AD1AAEB090208EB090102A811254F2A0F +:1011000028BF4F2208F092F8A21B08EB060116A890 +:101110004F2A28BF4F2208F089F83B6816AA02A977 +:10112000DB6838469847A8E71E25A6E73B6838469F +:1011300004491B69984701200DF53F7DBDE8F08FFC +:101140000020F9E756930008A023002058920008D9 +:1011500000F1180110B5044686B00846019100F070 +:10116000F1FB2046FFF758FF60B1019902A800F09B +:1011700049FC102204F1080102A808F017F8B0FA9F +:1011800080F0400906B010BD70B504460025EEB2EF +:10119000304600F0FFFC58B100213046013500F028 +:1011A00009FD08B9002070BD022000F085FDEEE7C2 +:1011B0002046FFF731FF0028F4D004F58034207C6E +:1011C00080F00100EFE70000F0B5C9B006F096F935 +:1011D00000F000FF18B90025284649B0F0BD694667 +:1011E0002A4802F0DFFF00284BD1294C204603F0AB +:1011F00009F8284803F006F8274803F003F82146C9 +:10120000224803F07BF80028E5D1702000F0C0FEF2 +:10121000064610B1214B44600360336830469B683A +:101220009847054600282ED01A4F1948394603F032 +:1012300065F805460028CED1194800F0A9FE0446FD +:1012400038B1184B4760036000F58033C0E90255A0 +:101250001D74236820469B689847054628B10E49AF +:101260000C4803F04BF80028B5D1336830465B6872 +:1012700098471CB1236820465B68984700F092FEAF +:10128000AAE70025FAE70446EFE700BF5C920008F2 +:101290006C9200088392000899920008BC920008A2 +:1012A00014000100D89200082DE9F04FD44A8DB007 +:1012B0000B68D0F804A001931A440368D14E1A4475 +:1012C000D1F81C90DFF8B4C3DFF8B4B3D0E902342E +:1012D000634003EA0A03634013444A6802920AEB3C +:1012E0007363029CC84A2244C468224484688AEA20 +:1012F00004051D40654015448A68039203EB35558B +:10130000039CC24A2244846822448AEA03042C4093 +:1013100084EA0A041444CA6805EBF43404921644BF +:1013200083EA0502224056445A4032440E6905962B +:1013300004EBB222059FB64E3E441E4485EA0403E8 +:1013400013406B4033444E69069602EB7363069F6D +:10135000B04E3E442E4484EA02051D4065403544AB +:101360008E69079603EB3555079FAB4E3E442644E6 +:1013700082EA03042C4054403444A84E4E4405EB0A +:10138000F434164483EA050222405A4032440E6A7D +:10139000089604EBB222089FA14E3E441E4485EA03 +:1013A000040313406B4033444E6A099602EB7363A7 +:1013B000099F9C4ED1F830E03E44D1F83880F34488 +:1013C0002E4484EA02051D40654035448E6AA6F528 +:1013D000244703EB35550A964F3F274482EA03041E +:1013E0002C4054403C44CF6A0B9705EBF4340B9EE1 +:1013F0008D4F3744029E174483EA050222405A402B +:101400003A448A4F774404EBB2221F4485EA04032E +:1014100013406B403B444F6BBC4402EB7363654429 +:1014200084EA020C0CEA030C8CEA040C6544DFF835 +:1014300054C2C44403EB3555A44482EA03042C404F +:1014400054406444D1F83CC0794905EBF43461441C +:10145000114483EA050222405A400A44754904EBCC +:10146000B2223144079E194484EA02032B406340B0 +:101470000B44714902EBF36331440B9E0D4482EA45 +:1014800003012140514029446C4D03EBF151354497 +:10149000019E254483EA010414405C402C44684DBD +:1014A00001EBB4443544069E154481EA04021A4017 +:1014B0004A402A44634D04EB323235440A9E1D44AF +:1014C00084EA02030B4063402B445F4D02EBF3635D +:1014D0003544059E0D4482EA0301214051402944D0 +:1014E0005A4D03EBF1516544254483EA010414404D +:1014F0005C402C44564D01EBB4443544099E1544E0 +:1015000081EA04021A404A402A44524D04EB323226 +:101510003544049E1D4484EA02030B4063402B447F +:101520004D4D02EBF36345440D4482EA0301214033 +:1015300051402944494D03EBF1513544089E2C4458 +:1015400083EA010515405D402C44454D01EBB44450 +:101550003544039E2A4481EA04051D404D402A4437 +:10156000404D04EB32323D442B4484EA020593445F +:101570000D4065402B443C4D02EBF3633544069E21 +:10158000294482EA0305254055402944374D03EBA1 +:10159000F1514D442C4483EA010515405D4025443A +:1015A00001EBB54581EA050404EA03024A405A44C6 +:1015B000A6F5B82B089E05EB3232ABF2BE6B544059 +:1015C0005B4423442A4C344402EB33730B9E0C449B +:1015D00085EA020159402144264C344403EB715101 +:1015E000029E254482EA03044C402544224C444494 +:1015F00001EB3545144483EA01026A40224443E08A +:1016000078A46AD7EECEBDC156B7C7E8DB702024F8 +:10161000AF0F7CF52AC68747134630A8019546FDD3 +:10162000D8988069AFF7448BBED75C892211906B44 +:101630002108B44962251EF640B340C0515A5E26C7 +:10164000AAC7B6E95D102FD65314440281E6A1D88B +:10165000C8FBD3E7E6CDE121D60737C3870DD5F424 +:10166000ED145A4505E9E3A9F8A3EFFCD9026F6729 +:1016700081F6718722619D6D0C38E5FD937198FDAF +:101680008A4C2A8D8E4379A6934C344405EB722202 +:10169000059E1C4481EA0503534023448F4C344487 +:1016A00002EB33730A9E0C4485EA0201594021443F +:1016B0008B4C4C4403EB7151254482EA03044C40AB +:1016C0002C44884D354401EB3444019E154483EA93 +:1016D000010262402A44844D3D4404EB72221D44C1 +:1016E00081EA040353402B44804D354402EB3373AD +:1016F000049E294484EA02055D4029447C4D35441A +:1017000003EB7151079E254482EA03044C402C44AC +:10171000784D354401EB3444099E2A4483EA01059F +:1017200065401544744A324404EB7525039E134406 +:1017300081EA04026A401A44704B734405EB32722A +:101740000B4484EA0501514019446D4B634402EB9C +:1017500071511C4485EA02034B401C44694B3344DD +:1017600001EB3444019E1D4482EA010363402B4493 +:10177000654D04EB73233544069E154463EA01026C +:1017800062402A44614D03EBB2624D4462EA0409AF +:1017900029445F4D89EA0309454449442C445D4D81 +:1017A00002EBB1513544049E61EA03081D4488EA06 +:1017B0000208444401EB744464EA02034B402B44A6 +:1017C000554D04EBF323754463EA010E15448EEA8C +:1017D000040E0EEB0502514D03EBB262354462EA92 +:1017E000040E29440A9D8EEA030EA5F580164C4D81 +:1017F0007144A6F6833602EBB151264461EA030434 +:1018000054403444029E01EB7444354464EA0206B9 +:101810001D444E407319089E424D04EBF32335449A +:1018200063EA01061544664072193F4D03EBB2624C +:10183000654462EA040629443C4D5E403144079EFB +:1018400002EBB151354461EA03062C44384D564051 +:101850003D443444059E1D4401EB744464EA020394 +:101860004B402B44334D04EBF32335440B9E15447E +:1018700063EA010262402A442F4D03EBB262354411 +:10188000039E0D4462EA0401594029442B4D02EBAA +:10189000B15135442A4E254461EA030454402C4496 +:1018A000099D01EB74442E4464EA02051E4485EA56 +:1018B00001039D1903681A440AEB040303EBF523A3 +:1018C0000260436083681C44C36819448460C1603B +:1018D0000DB0BDE8F08F00BF44EABEA4A9CFDE4B37 +:1018E000604BBBF670BCBFBEC67E9B28FA27A1EA40 +:1018F0008530EFD4051D880439D0D4D9E599DBE6CD +:10190000F87CA21F6556ACC4442229F497FF2A43F1 +:10191000A72394AB39A093FCC3595B6592CC0C8F81 +:10192000D15D84854F7EA86FE0E62CFE144301A3B1 +:10193000A111084E827E53F735F23ABDBBD2D72AA9 +:1019400091D386EB094B036003F18833436003F1C5 +:101950002943A3F59613A3F68B638360A3F1883321 +:10196000C3600023C0E90433704700BF012345670B +:101970002DE9F8431446026905460E46E300C2F31A +:10198000C50800F118079B18036122BF43690133A2 +:10199000436112F4FC7F436903EB5473436114D039 +:1019A000C8F1400907EB08004C4504D22246BDE8C7 +:1019B000F84307F00BBC403C4A464E4407F006FC97 +:1019C000444439462846FFF76FFCA04606EB04095D +:1019D000B8F13F0FA9EB08010AD94022384607F0B9 +:1019E000F5FB39462846A8F14008FFF75DFCEFE714 +:1019F000A1096FF03F02384602FB014206EB81115C +:101A0000D5E7000070B50B6901F1180506460C46D4 +:101A1000C3F3C503EA18501C8022EA54C3F13F0205 +:101A2000072A1FD8002100F087F929462046FFF732 +:101A30003BFC38220021284600F07EF92369294624 +:101A40002046236563696365FFF72EFC214610225B +:101A5000304607F0BBFB204658220021BDE870400D +:101A600000F06AB9C3F137020021E5E72DE9F84F2C +:101A70004FF47A7306460D46002402FB03F7DFF8A5 +:101A80005080DFF8509098F900305FFA84FA5A1CC1 +:101A900001D0A34210D159F824002A4631460368E8 +:101AA000D3F820B03B46D847854205D1074B0120EB +:101AB00083F800A0BDE8F88F0134042CE3D14FF483 +:101AC000FA7004F0D3FD0020F4E700BFE4330020F7 +:101AD0001022002014220020002307B50246012115 +:101AE0000DF107008DF80730FFF7C0FF20B19DF81A +:101AF000070003B05DF804FB4FF0FF30F9E700008A +:101B00000A46042108B5FFF7B1FF80F00100C0B21A +:101B1000404208BD074B0A4630B41978064B53F8CB +:101B20002140014623682046DD69044BAC4630BCA9 +:101B3000604700BFE433002014220020A08601008B +:101B400070B50A4E00240A4D05F010FA308028685E +:101B50003388834208D905F005FA2B680444013321 +:101B6000B4F5003F2B60F2D370BD00BFE633002018 +:101B7000A033002005F0C8BA00F1006000F5003085 +:101B80000068704700F10060920000F5003005F039 +:101B900049BA0000054B1A68054B1B889B1A834203 +:101BA00002D9104405F0DEB900207047A0330020B0 +:101BB000E633002038B50446074D29B12868204493 +:101BC000BDE8384005F0E6B92868204405F0D0F9B2 +:101BD0000028F3D038BD00BFA0330020002070479C +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7BFBF0120704700BFA43300207E +:101C1000014B1868704700BF0010005C194B013879 +:101C20000322084470B51D68174BC5F30B042D0C37 +:101C30001E88A6420BD15C680A46013C82421346CC +:101C40000FD214F9016F4EB102F8016BF6E7013AB9 +:101C500003F10803ECD181420B4602D22C2203F897 +:101C6000012B0424094A1688AE4204D1984284BF4D +:101C7000967803F8016B013C02F10402F3D1581A83 +:101C800070BD00BF0010005C2422002018930008E3 +:101C9000022803D1024B4FF080529A61704700BF77 +:101CA00000100258022803D1024B4FF480529A616F +:101CB000704700BF00100258022804D1024A53693D +:101CC00083F48053536170470010025870B5044686 +:101CD0004FF47A764CB1412C254628BF412506FBAE +:101CE00005F0641B04F0C2FCF4E770BD002310B5DE +:101CF000934203D0CC5CC4540133F9E710BD00001B +:101D0000013810B510F9013F3BB191F900409C42F8 +:101D100003D11AB10131013AF4E71AB191F9002067 +:101D2000981A10BD1046FCE703460246D01A12F975 +:101D3000011B0029FAD1704702440346934202D0A6 +:101D400003F8011BFAE770472DE9F8431F4D1446CD +:101D50000746884695F8242052BBDFF870909CB364 +:101D600095F824302BB92022FF2148462F62FFF737 +:101D7000E3FF95F824004146C0F1080205EB80001E +:101D8000A24228BF2246D6B29200FFF7AFFF95F8D5 +:101D90002430A41B17441E449044E4B2F6B2082E2B +:101DA00085F82460DBD1FFF723FF0028D7D108E0B6 +:101DB0002B6A03EB82038342CFD0FFF719FF002881 +:101DC000CBD10020BDE8F8830120FBE7A43300203D +:101DD000024B1A78024B1A70704700BFE4330020A0 +:101DE00010220020F8B5194C194803F047FF21468E +:101DF000174803F06FFF24684FF47A70154ED4F83B +:101E00009020154DD2F80438114F43F00203C2F868 +:101E10000438FFF75BFF2046104904F069F8D4F856 +:101E200090200424D2F8043823F00203C2F80438C6 +:101E30004FF4E133336055F8040BB84202D0314619 +:101E400003F07AFE013CF6D1F8BD00BF109B0008FC +:101E500018490020CC33002014220020189B0008D1 +:101E60000C4B70B50C4D04461E780C4B55F82620D3 +:101E70009A420DD00A4B002118221846FFF75CFF4A +:101E80000460014655F82600BDE8704003F054BEDA +:101E900070BD00BFE4330020142200201849002048 +:101EA000CC330020F8B571B6002301201A4619463C +:101EB00002F094FD0446802005F0C6F9002849D0C0 +:101EC0000025254A80274FF4D06C3D26136913F076 +:101ED000C06F26D1D2F8103113F0C06F21D1236822 +:101EE00005F1006199602368D86023685F6023680A +:101EF000C3F800C021680B6843F001030B60216840 +:101F00000B6823F01E030B6021680B68DB07FCD411 +:101F1000237B8035616806FA03F3B5F5001F0B607B +:101F2000D4D1204602F09AFDB5F5001F11D000244F +:101F30000A4E0B4D012005F0E7F83388A34205D97E +:101F400028682044013405F025F8F6E7002005F064 +:101F5000DBF861B6F8BD00BF00200052E633002078 +:101F6000A033002030B50A44084D91420DD011F83D +:101F7000013B5840082340F30004013B2C4013F080 +:101F8000FF0384EA5000F6D1EFE730BD2083B8EDBF +:101F90000121884238BF084605F08EB908B105F026 +:101FA0008FB9704710B5084C01220849002001F094 +:101FB000B3FE23783BB1064803F036FD044803F036 +:101FC00069FD0023237010BDE8330020289300082A +:101FD000C83600201D482DE9F041036D2BB90122C0 +:101FE0004FF48051503005F0CBFA194E33780BB1D5 +:101FF000FFF7D8FF0324174F4FF00008134D154982 +:102000002846C7F8048003F037FD284603F070FB2C +:1020100048B1013C284603F03DFD14F0FF04EED129 +:10202000204634700FE00C4901220C4801F074FE88 +:10203000014618B1284603F0F7FCEAE7084800F02B +:1020400011F801203070BDE8F08100BFC8360020D3 +:10205000E83300203C22002028930008EC330020C5 +:102060002C9300080FB4002004B07047006870473C +:1020700003460068596870470B0A017043700B0CE7 +:10208000090E8370C1707047110A027003714170AC +:10209000110C120E8170C2701A0A42711A0C1B0EBA +:1020A0008271C37170470000C36A0239023B8B42E0 +:1020B00083BF4389006C01FB0300002070470000D0 +:1020C000C2F307238A76CB760378032B01BF120C69 +:1020D0000A75120A4A75704700F10B010022D301FC +:1020E00043EA520310F8012B52FA83F38842DAB222 +:1020F000F5D110467047000010B541780446002025 +:10210000013102464901022A16BFA35C032203EBF8 +:10211000C03302F101021EBF9BB203EB500398B221 +:102120009142F0D810BD000002684AB1134613F87E +:10213000011B1F290DD93A29F9D1911C8B4202D0DC +:102140004FF0FF3070471278302AF9D10360002039 +:102150007047014B187870473836002038B50D4667 +:10216000044618B9092000232B6038BD0368002BF2 +:10217000F8D01A78002AF5D08188DA889142F1D116 +:10218000587804F00FFC10F00100EBD12368EBE766 +:1021900038B50D4640F25231144602F0B9F9FF2825 +:1021A00007D9012C0BD9030A022468702B70204632 +:1021B00038BD30B1002CFAD001242870F7E7002494 +:1021C000F5E70446F3E700002DE9F8430026D0F8D0 +:1021D000008005460C468E76836B002B4AD098F81B +:1021E0000030042B4BD133463546402720E0B7F56D +:1021F000187F80F0C480F90606F1010608BF023797 +:10220000D05B02372BB900F5205292B2B2F5006FC5 +:102210000DD305F11A01C5F1FF0240EA0340214444 +:10222000FFF7B6FF002800F0AA800544002003460F +:10223000D8F8102092F82310B142D8D8002B40F0E3 +:102240009E80002D00F09B8000232544AB766373B5 +:10225000D8F81020137903F03701DB0621730BD473 +:1022600002F13800FFF704FFC4E90001938963819C +:10227000D3892381BDE8F88300200146F4E7C36CCD +:1022800001335ED1EA6B00232E26551E184615F841 +:10229000011F013020290CD0052908BFE52109289C +:1022A00004D10B2B9EBFE71801337E73E71801336F +:1022B00079730B28EBD1E11800204873A17E002927 +:1022C0004BD1002B40D06FF00C0604F10D00082517 +:1022D000361B331810F8011B002938D02E298BB279 +:1022E0004AD0A3F14101192903D8117B0D4200D036 +:1022F00020330373EDE7B9F1000F05D100F520534A +:102300009BB2B3F5006F0BD307F11A01C7F1FF02BF +:1023100040EA09402144FFF73BFF48B10744002051 +:1023200002368146D8F80C30985B0028E3D1384655 +:10233000B9F1000F4FF0000218BF002023189A7661 +:10234000A0E7B1463746EDE73F23A37601232344B8 +:1023500000219976137B03B96373D37A02F11C00D1 +:1023600003F03F0323730023FFF780FE20606360C8 +:10237000D38A6381138B7CE710250B46B9E73F2393 +:102380000125A37660E7000038B50546002435F83E +:10239000020B08B9204638BD02F0EEF86308C2B25D +:1023A00003EBC43312FA83F39AB2C0F3072303EBAF +:1023B000520303EBC2339CB2E9E7000037B5C378A0 +:1023C00004461BB90025284603B030BD00F14C017E +:1023D000826C01234078019104F00AFB054680B924 +:1023E000A36BE070A06C226BC31A9342EAD2A3786D +:1023F0000199022BE6D102440123607804F0F8FA37 +:10240000E1E70125DFE7000038B5836C05460C469F +:102410008B4210D0FFF7D2FF60B92246012305F1AD +:102420004C01687804F0C0FA00281CBF4FF0FF345C +:102430000120AC6438BD0020FCE7000038B5002363 +:102440000446C3704FF0FF338364FFF7DDFF0028BD +:102450004BD1B4F84A524AF655239D4207D10B227C +:10246000254904F14C0006F0A1FE00283FD094F865 +:102470004C30EB2B03D01833DBB2012B2ED84AF6AD +:1024800055239D4206D108221C4904F19E0006F006 +:102490008DFE48B3B4F85730B3F5007F1ED194F8E1 +:1024A0005930DBB15A1E1A4218D1B4F85A30ABB1C8 +:1024B00094F85C30013B012B10D8B4F85D306BB15F +:1024C000B4F85F307F2B06D804F16C00FFF7CEFD27 +:1024D000B0F5803F02D3B4F8623053B94AF65520C4 +:1024E00085420CBF0220032038BD0420FCE70120F8 +:1024F000FAE70020F8E700BF58930008649300084B +:1025000002392DE9F04701F007044FF0010A466C4B +:1025100005460AFA04F41746984606EB1136C1F34D +:10252000C809E4B2314628460136FFF76DFF18B1FD +:102530000120BDE8F087994605EB090292F84C307E +:10254000234214BF01210021414513D06340013FC4 +:1025500082F84C3085F803A0EBD0640014F0FF043F +:10256000EAD109F1010301244FF00009B3F5007F1E +:10257000E1D1D7E70220DCE701290246F8B50C4695 +:1025800040F28C800668F36A8B4240F28780337891 +:10259000013B032B00F28280DFE803F00229384B75 +:1025A00004EB5405B16B304601EB5521FFF72CFFCE +:1025B00010B14FF0FF30F8BD6F1CC5F30805B16BCB +:1025C0003046354401EB572195F84C50FFF71CFF7E +:1025D0000028EED1C7F30807E3073E4496F84C0005 +:1025E00045EA00204CBF0009C0F30B00E3E7B16BE4 +:1025F000304601EB1421FFF707FF0028D9D1640012 +:1026000004F4FF742644B6F84C00D4E7B16B3046AE +:1026100001EBD411FFF7F8FE0028CAD1A40006F19F +:102620004C0004F4FE742044FFF720FD20F07040BD +:10263000C1E7D0E90430D57953EA000101D09168AF +:1026400001B95DBB9168022DA4EB01010DD1013BE5 +:10265000728940F1FF305B0A43EAC053B3FBF2F3E7 +:1026600099421BD81CD0601CA5E7032D02D19369A9 +:102670008B42F8D8D3699BB9B16B304601EBD411CA +:10268000FFF7C2FE002894D1A0004C3600F4FE7083 +:102690003044FFF7EBFC20F000408CE701208AE794 +:1026A0006FF0004087E70000F8B5066804460D4665 +:1026B0003378042B0CBF4FF080524FF400128A4243 +:1026C00001D80220F8BDCA06FBD182680163D2B9E5 +:1026D000022B13D83389B3EB551FF2D9F36BA363E5 +:1026E000A36B6263002BECD003EB55234C36C5F390 +:1026F00008050020A3633544E563E3E7F36BC2718B +:10270000002BE7D01A4677897F02BD42114604D2DA +:102710003046FFF7C9FCA063E2E72046FFF72CFF35 +:10272000431C024606D00128CBD9F36A8342C8D99C +:10273000ED1BEAE70120C5E701292DE9F047064630 +:102740000C46174608D9C36A8B4205D90378022B79 +:1027500062D003D8012B22D0022552E0033B012B8B +:10276000FAD8816B01EBD411FFF74EFE0546002825 +:1027700047D1A40006F14C0304F4FE741C443378E2 +:10278000042B07D0204627F07047FFF76FFC00F0BE +:102790007040074339462046FFF76EFC2FE001EBFF +:1027A0005108816B01EB5821FFF72EFE054640BB17 +:1027B00014F0010406F14C0908F1010AC8F30808F5 +:1027C00008BFFBB230461FBF19F8083003F00F02F4 +:1027D0003B0103F0F00318BF134309F8083001234D +:1027E000B16BF37001EB5A21FFF70EFE054640B9BD +:1027F000CAF3080A44B1C7F3071709F80A7001239E +:10280000F3702846BDE8F08719F80A30C7F30327AC +:1028100023F00F031F43F0E7816B01EB1421FFF757 +:10282000F3FD05460028ECD1640006F14C0304F4E6 +:10283000FF741F551919C7F307274F70DFE7000012 +:10284000F8B504460E461746E3690BB91846F8BDBD +:10285000012BA6EB0305206814BFAA1C3A46691C8D +:10286000FFF76AFF0028F2D1E369013BE361EBE780 +:1028700001292DE9F84306460C461746056802D89B +:102880000220BDE8F883EB6A8B42F9D97AB9A146F8 +:1028900021463046A046FFF76FFE0446B0B92B78BC +:1028A000042B02D1002F43D1F7710020E9E72B78E8 +:1028B000042B02D1C379022BE9D04FF0FF32394605 +:1028C0002846FFF739FF0028E1D0DAE70128D7D002 +:1028D000421C01D10120D4E72B78042B19D1EA6ADC +:1028E000AB69023A93421CD308F10102A2420CD018 +:1028F0002B78042B08D10023A2EB09024946284675 +:10290000FFF7FEFD0028BCD1A146EB6AA342BFD869 +:10291000C5E7002241462846FFF70EFF0028DED01B +:10292000AFE70133AB612B7943F001032B71DBE798 +:10293000F3798BB9B468BC4202D10223F371B4E7D6 +:1029400021463046FFF718FE012899D9431CC1D013 +:1029500001348442EFD0A8E7032BA6D1B368BB4271 +:10296000A3D8B2691344BB429FD3E6E770B5C379DD +:102970000446032B06D181688369CD18A94203D18F +:102980000023E371002070BD4E1C20683246FFF723 +:10299000D3FE0028F7D13146F0E700002DE9F743D8 +:1029A00005460191FFF70AFD0446002849D105F1CB +:1029B0004C09019928464FF40072FFF775FB214638 +:1029C000A86407464846FFF7B7F96C896402B4F576 +:1029D000004F28BF4FF40044B4F5007F2FD92046A4 +:1029E00004F072FC804630B122460021640A0026C1 +:1029F000FFF7A2F909E06408EEE72346BA19414659 +:102A0000687803F0F5FF18B926446B899E42F4D329 +:102A1000404604F069FC6889801B18BF012003B0A0 +:102A2000BDE8F08301366B899E42F4D20123BA19C6 +:102A30004946687803F0DCFF0028F3D0EBE7002676 +:102A4000F1E70120EBE70000F8B50446FFF7B6FC1C +:102A50000546002842D12378032B37D12779012F4F +:102A600034D104F14C0601464FF400723046FFF7B2 +:102A700063F955234122722184F84A32AA2304F5CE +:102A80000D7084F84F2084F84B32522384F83012B2 +:102A900084F84C3084F84D30612384F8311284F886 +:102AA0004E3084F83332A16984F83222FFF7E4FA19 +:102AB000616904F50E70FFF7DFFA626B3B46314641 +:102AC00001326078A26403F093FF257100226078E0 +:102AD000114603F0B1FF003818BF0120F8BD000017 +:102AE00000232DE9F0430B6085B00F461546FFF734 +:102AF0001BFB061EC0F2B281804B53F82640002C0F +:102B000000F0AE813C6005F0FE0523786BB1607883 +:102B100003F048FFC70708D41DB110F0040500D02A +:102B20000A25284605B0BDE8F0830023F0B22370E3 +:102B3000607003F023FFC10700F194810DB14207DB +:102B4000EED400212046FFF779FC022840F099805E +:102B50006E4604F2122304F2522132461846103314 +:102B6000FFF784FA42F8040B8B42F7D1002556F8A0 +:102B7000041B00297DD02046FFF760FC012879D88E +:102B80000128A26C40F0C08004F1570304F18C01CD +:102B900013F8015B002D7BD18B42F9D1B4F8B4302E +:102BA000B3F5807F74D194F8B830092B70D104F15B +:102BB0009400FFF75DFA4FF0FF33171841F1000161 +:102BC000BB4275EB010363D304F1A000FFF74EFA9B +:102BD00094F8BA302063012BA37059D194F8B990BE +:102BE00003FA09F91FFA89F36381002B50D0444B93 +:102BF00004F1A800FFF73AFA0646984248D8831C29 +:102C0000626304F1A400E362FFF730FA00EB02080C +:102C100004F19C00C4F84080FFF728FA10441FFA22 +:102C200089F2A06306FB02F313EB080345EB0502F0 +:102C30009F4271EB02032BD32E4604F1AC00FFF749 +:102C400015FAE06365B96389B34221D9E16B204687 +:102C5000FFF72AFA81192046FFF7D6FB98B901360B +:102C6000631993F84C30812B14D02035C5F3080537 +:102C7000E8E703200135042D7FF479AF042807D15C +:102C800001E0042801D101254BE701287FF678AF48 +:102C90000D2546E705F1140004F14C063044FFF71A +:102CA000E5F901280546F3D9E36A8342F0D9618941 +:102CB000821E236C02FB01336364A16B204601EB8F +:102CC000D511FFF7A1FB0028DDD105F07F0006EB51 +:102CD0008000FFF7CBF9431C03D00135A842ECD0AC +:102CE000D6E70425C4E90500064A257000251388A7 +:102CF000E56101339BB21380E38012E73C3600208C +:102D0000FDFFFF7F40360020B4F85730B3F5007F59 +:102D1000BED1B4F8626026B904F17000FFF7A6F9DD +:102D2000064694F85C302663591EA3700129AFD87B +:102D300094F859506581002DAAD0691E2942A7D167 +:102D4000B4F85D8018F00F0FA4F80880A0D1B4F893 +:102D50005F0018B904F16C00FFF788F9B4F85A1055 +:102D6000002995D006FB03FE01EB181CF4446045D6 +:102D70008ED3A0EB0C00A842B0FBF5F388D33E48FD +:102D8000834285D84FF6F57083426DD903259F1C89 +:102D9000114402EB0C03032DE7626263A163236419 +:102DA0004CD1B4F8763053EA08037FF471AFBB001E +:102DB00004F17800FFF75AF9E06303F2FF13B6EB72 +:102DC000532FFFF465AF4FF0FF33032DC4E90533F4 +:102DD0004FF08003237187D1B4F87C30012B83D16D +:102DE000511C2046FFF710FB00287FF47DAFB4F89C +:102DF0004A224AF6552320719A427FF475AF1F4B41 +:102E000004F14C00FFF732F998427FF46DAF03F103 +:102E1000FF5304F50C70FFF729F903F50053203335 +:102E200098427FF461AF04F50D70FFF71FF9A061C0 +:102E300004F50E70FFF71AF9606155E7B8F1000F5D +:102E40003FF426AF7144022D4FEA4703E1631EBFF2 +:102E5000D91907F0010303EB5103AEE70B2560E638 +:102E60000C255EE603255CE640F6F575AB428CBFAB +:102E7000022501258BE700BFF5FFFF0F525261418C +:102E80002DE9F84F07460568884649B96E69C6B10D +:102E9000EB6AB34298BF0126AB69A3B9002405E0F1 +:102EA000FFF76AFB0128044603D801242046BDE849 +:102EB000F88F421C00F0D280EB6A8342F6D8464677 +:102EC000EAE70126E8E72A78EB6A042A40F08380E3 +:102ED000A6F1020A023B4FF0010B9A4528BF4FF0C2 +:102EE000000AD146696C284601EB1931FFF78CFACC +:102EF00000283BD109F00703EA6AC9F3C8010BFABD +:102F000003F3901EDBB26A184C4609F1010992F8EE +:102F10004C20814502EA030233BF5B0000234FF4DB +:102F20000071DBB228BF9946B2B90234631E033385 +:102F3000BCD80123214628461A46FFF7E1FA0228A9 +:102F4000B3D0012800F08A80B8F1000F13D102231A +:102F5000FB710028A9D130E0CA450AD0002BD2D19C +:102F60000131B1F5007FBDD20123CCE74FF0FF3432 +:102F7000DCE70024DAE7FB79022B07D1731CA342BC +:102F8000E7D0BB68F31ABB610323FB7108F10102B0 +:102F9000FB69A24205D113B10133FB61D9E70223DA +:102FA000FBE70BB90123FB61224641463846FFF798 +:102FB00047FC00284FD10123FB61EA6AAB69023A62 +:102FC0006C6193429CBF03F1FF33AB612B7943F0FB +:102FD00001032B716AE7464514D1741C3846A3429D +:102FE00098BF02242146FFF7C7FA01283FF45DAFDE +:102FF000431C33D0E0B16B69012B03D9EA6A9342D9 +:1030000038BF1E4634460134EB6AA34203D8012E72 +:103010007FF644AF022421463846FFF7ADFA48B1A7 +:1030200001283FF442AF013018D0B442EBD135E76C +:10303000002CE7D04FF0FF3221462846FFF77CFBFB +:1030400048B9B8F1000FB8D0224641462846FFF7EC +:1030500073FB0028B1D001287FF427AF4FF0FF3475 +:1030600024E700002DE9F84306680446076B89460B +:1030700033782037042B0CBF4FF080534FF40013EC +:10308000BB429CBF00238363836B73B1C7F3080803 +:10309000B8F1000F3CD10133416B836339B93389F7 +:1030A000B3EB571F34D80023A36304200AE07389CD +:1030B000013B13EA57232BD1FFF75EFA012805469F +:1030C00002D80220BDE8F883421C01D10120F9E7B3 +:1030D000F36A834216D8B9F1000FE4D0616B204641 +:1030E000FFF7CEFE0546C8B10128EAD0431CEDD05B +:1030F00001463046FFF752FC0028E7D1E37943F060 +:103100000403E371294630466563FEF7CDFFA063F3 +:103110004C36002027634644E663D3E70720D1E717 +:10312000F8B50E46002104460768FFF7BDFA98B9C6 +:103130000546A16B3846FFF767F968B93A78E36B43 +:10314000042A1B780CD11B060ED50546012120460A +:10315000FFF788FF0028ECD0042808BF072006E00E +:10316000E52B01D0002BF0D10135B542EED1F8BDF1 +:10317000C16C4B1C2DE9F04104460568066B1FD15C +:10318000E5274FF00108A16B2846FFF73DF998B9F4 +:103190002A78E36B042A09BF1A781F7002F07F02B5 +:1031A0001A7085F80380236BB3420DD200212046AC +:1031B000FFF758FF0028E6D0042808BF022003E0EC +:1031C000FFF772FA0028DBD0BDE8F0812DE9F0416D +:1031D00005460068A96B0669FFF716F9044620B991 +:1031E000EB6B1A78852A03D002242046BDE8F081D3 +:1031F000324603F1200153F8040B8B4242F8040BD2 +:10320000F9D1777801377F01A7F16003B3F5007F2B +:10321000EAD800212846FFF725FF04280446E3D01A +:103220000028E2D1A96B2868FFF7EEF804460028D1 +:10323000DBD1EB6B1A78C02AD6D106F1200203F15C +:10324000200153F8040B8B4242F8040BF9D196F895 +:1032500023300F222C33B3FBF2F3B7EB431FC3D35E +:103260004FF0400800212846FFF7FCFE04280446E2 +:10327000BAD00028B9D1A96B2868FFF7C5F8044671 +:103280000028B2D1EB6B1A78C12AADD1B8F5187FFE +:1032900009D206EB080203F1200153F8040B8B421C +:1032A00042F8040BF9D108F120084745DAD8B8F5FF +:1032B000187F9AD83046FEF71FFF7388834294D058 +:1032C00092E700000B68002210B5036004460B6A09 +:1032D00083604B6AC261C37123F0FF03896AC0E94E +:1032E0000432C164FFF7E0F920B92046BDE8104080 +:1032F000FFF76CBF10BD0000F8B503680546012755 +:103300001C692046FEF7F8FEA070000A6678E0709F +:103310002846E96CFFF7C8F920B1022828BF02202F +:10332000C0B2F8BDA96B2868FFF76EF80028F4D189 +:10333000EB6B04F1200254F8041B944243F8041B85 +:10334000F9D12B68DF70002EE7D000212846013E1E +:10335000FFF788FEE0E700002DE9F8434FF0FF0893 +:1033600006460768042445464FF6FF79B16B11B94C +:10337000002C73D063E03846FFF746F80446002877 +:103380005DD1F06B0378002B6ED03A78042A11D10E +:10339000852B4DD1336B3046F364FFF717FF04469E +:1033A00000284CD13B691B7903F03F03B3712046E1 +:1033B000BDE8F883C27AE52B02F03F02B27143D038 +:1033C0002E2B41D022F0200108293DD00F2A40D1D8 +:1033D000590637D503F0BF05336B90F80D80F364C1 +:1033E000437B434530D1428B72BB03780D21FC688F +:1033F00023F04003DFF874E0013B4B4301211EF84A +:1034000001CB30F80CC009B3FF2B1DD824F813C032 +:103410006146013301320D2AF1D10278520605D5F9 +:1034200021B1FF2B10D8002224F81320013DEDB26A +:1034300000213046FFF716FE0446002896D00023F0 +:10344000B363B4E7AB42CBD0FF25F1E7CC45E1D085 +:10345000FAE72DB9FEF740FE404501D10024A6E76A +:103460004FF0FF33F364A2E70424E8E70094000878 +:103470002DE9F04F002187B00446D0F80090FFF707 +:1034800013F9804670B999F80030042B33D1D9F87C +:103490000C00FEF779FF07462046FFF75DFF054663 +:1034A00020B18046404607B0BDE8F08FD9F8103013 +:1034B0009A8CBA42F0D193F823B040265D4506D1EC +:1034C000D9F80C3033F81530002BE5D1EAE7F106D6 +:1034D000D9F8103008BF0236985B01F04DF8D9F8E2 +:1034E0000C30824633F8150001F046F88245D3D1FE +:1034F00002360135E2E74FF0FF0A4FF0FF3B554639 +:10350000C4F84CB0A16B4846FEF77EFF00285CD1A2 +:10351000E66B3778002F77D0F27AE52F02F03F0381 +:10352000A37103D0120704D50F2B04D0C4F84CB0FC +:103530004FE00F2B54D194F84B3058063FD4790606 +:1035400045D5236B07F0BF0796F80DA0E364737BA6 +:1035500053453ED1738B002B3BD135780121D9F8EF +:103560000C3005F03F0501930D23013D5D43284BD1 +:1035700013F8012BB25A71B3FF2D059329D81046C9 +:10358000049200F0F9FF6B1C03900293019B33F847 +:10359000150000F0F1FF039981421AD1049A029DAF +:1035A0001146059B1B4A9342E2D133785A0604D553 +:1035B00019B1019B33F815305BB97D1EEDB20021C6 +:1035C0002046FFF74FFD00289CD080466AE7BD42A9 +:1035D000BDD0FF25F3E74FF6FF708242E2D0F8E757 +:1035E0002DB93046FEF778FD50453FF45BAF94F8B7 +:1035F0004B30DB079AD40B2204F14001304605F032 +:10360000D5FD002892D14DE74FF004084AE700BFEE +:10361000009400080D9400082DE9F04F90F84BB08D +:1036200099B004461BF0A00540F068810668F26876 +:1036300032F81530002B4AD13378042B40F08780C4 +:103640000F230E352046B5FBF3F5A91CFFF768FDE7 +:103650008146002877D1236B0135A3EB4515E3792B +:103660005A07E56435D523F004032046E371FFF7DC +:103670007DF950BB4FF0FF32616B2046FFF7E0F859 +:1036800018BBA3682BB3214604A8FFF71BFEE0B9C3 +:1036900070894FF40071D4E90423E0FB0123306901 +:1036A000C4E904233830FEF7EFFC3069D4E9042381 +:1036B0002830FEF7E9FCE379326904A843F00103FE +:1036C00082F82130FFF718FE18B181463BE0013542 +:1036D000AEE7D6E90354402200212046FEF72CFB3A +:1036E0008523012140222370C0234FF0C10C04EB3D +:1036F000010884F8203000231E469E46571C04F81B +:1037000002C0F0B2023204F807E021B135F813101C +:1037100009B10133DBB20F0AA15408F8027002327A +:10372000D706F2D135F813700136002FE6D184F8B0 +:103730002330831C28466370FEF726FE84F824009D +:10374000000A84F82500484619B0BDE8F08F04F15E +:1037500040070DF1100A1BF0010F97E807008AE8F7 +:10376000070000F0D38040234FF0010884F84B306D +:10377000BC46F368B8F1050F9AE80700ACE803000F +:103780002CF8022B4FEA12428CF8002059D9981ECF +:10379000424630F8021F002942D10DF10F0C0721DB +:1037A00002F00F0E914612090EF13000392888BF41 +:1037B0000EF1370001390CF8010902D0B9F10F0FF1 +:1037C000EED818AB7E205A1802F8580C3846002262 +:1037D000914206D010F801CB02F1010EBCF1200F8E +:1037E00031D104F13F0C072902F1010297BF18AB58 +:1037F00020205818013198BF10F8580C072A0CF8EF +:103800000200F0D92046FFF733FE8146002878D128 +:1038100008F10108B8F1640FAAD14FF0070992E747 +:103820004FF0100C01F0010E49080EEB4202D303D9 +:1038300044BF82F4883282F02102BCF1010CF1D144 +:10384000A7E74246A9E77246C2E7216B2046A1EBF3 +:103850004511FEF729FF814600287FF474AF4FF62B +:10386000FF783846FEF738FC0190A16B3046FEF732 +:10387000CBFD814600287FF466AFE36BE9B2019A85 +:103880004FF00D0CD6F80CE05A734FF00F02DFF832 +:10389000E0A0DA724A1E18730CFB02F28446987696 +:1038A000D87640451AF8019B0CF1010C18BF3EF880 +:1038B000120003EB090B18BF013203F809004FEAAD +:1038C0001029002808BF4046BCF10D0F8BF801906D +:1038D000E7D1404502D03EF812200AB941F040013C +:1038E0001970012300212046F370FFF7BBFB8146CE +:1038F00000287FF428AF013DB7D11BE04FF0060947 +:1039000021E704287FF41FAF84F84BB01BF0020FAF +:1039100020461BBF0C350D210125B5FBF1F518BF65 +:1039200001352946FFF7FCFB814600287FF40BAFE9 +:10393000013D8AD1A16B3046FEF766FD8146002825 +:103940007FF401AF01462022E06BFEF7F5F9E36B4F +:1039500003CF18605960BA7839889A72198194F83F +:103960004B30E26B03F0180313730123F370EAE6A4 +:103970000094000810B504460A463430FEF776FB82 +:10398000886004F13800FEF773FBC2E9040194F883 +:10399000213003F00203D3710023D36110BD000076 +:1039A00003284B8B04BF8A8A43EA024318467047B8 +:1039B0002DE9F04F0B7899B0044689462F2BD0F8AB +:1039C00000B001D05C2B09D14A46137891460132F0 +:1039D0002F2BFAD05C2BF8D0002301E0DBF81C3051 +:1039E000A3600023E3619BF80030042B1ED1A36881 +:1039F000E3B1DBF82030214604A82362DBF8243051 +:103A00006362DBF82830A362FFF75CFC0346002802 +:103A100054D1DBF8102002F13800FEF727FBC4E98F +:103A2000040392F8213003F00203E37199F80030A7 +:103A30001F2B00F2358180230021204684F84B3073 +:103A400019B0BDE8F04FFEF72FBE49460B78894606 +:103A500001312F2BFAD05C2BF8D01F2B8CBF002507 +:103A60000425012F2FD113882E2B31D1002322F8CA +:103A7000173004F140029F428CBF2E2120210133D8 +:103A80000B2B02F8011BF6D145F02005204684F8E7 +:103A90004B50FFF7EDFC94F84B30002800F0E78026 +:103AA00004280BD1990603F0040240F1DC80002ABF +:103AB00000F0F6808023002084F84B3019B0BDE878 +:103AC000F08F0425CDE7022F02D153882E2BCAD0C8 +:103AD000911E87BB002322F81730002F00F01181C0 +:103AE00032F81300194601332028F9D009B92E28DD +:103AF00001D145F00305901E30F817302E2B01D070 +:103B0000013FF9D14FF020334FF0000A6364D046F3 +:103B10002364C4F847300823481C32F81160009031 +:103B2000F6B1202E03D02E2E0DD1B84210D045F084 +:103B300003050099F0E731F81730202B01D02E2B28 +:103B4000C8D1013FC5E79A4505D20099B9423BD19A +:103B50000B2B30D101E00B2B27D145F003050B23B4 +:103B600094F84020E52A04BF052284F84020082B61 +:103B700004BF4FEA88085FFA88F808F00C030C2BA2 +:103B800003D008F00303032B01D145F00205A80779 +:103B90003FF57CAF18F0010F18BF45F0100518F085 +:103BA000040F18BF45F0080570E70099B94202D02C +:103BB00045F00305D4D84FEA88080B234FF0080AD4 +:103BC00000975FFA88F8B4E77F2E15D9304640F2A7 +:103BD0005231CDE9022345F00203019300F098FC35 +:103BE00010F0800F0646DDE9022316D000F07F06B4 +:103BF00046498E5D019D46B331464548CDE90123D6 +:103C000005F0FEFADDE90123F8B9A6F1410189B218 +:103C100019291ED848F0020810E0FF28EAD9591ED9 +:103C20008A4503D345F003059A4682E704EB0A016F +:103C3000000A0AF1010A019D81F8400004EB0A0123 +:103C40000AF1010A81F8406073E745F003055F2639 +:103C5000F4E7A6F1610189B219299EBF203E48F020 +:103C60000108B6B2EAE7002A08BF052026E75A078E +:103C70003FF524AFA379DB0645D59BF80000042867 +:103C800035D1A3682146E27923622369DBF810006D +:103C900023F0FF0313436362E36CA362FFF76AFE42 +:103CA00023680027DA6819F8010B00283FF409AFF0 +:103CB00040F25231009200F04BFC054608B31F2839 +:103CC000009A7FF6FEAE2F283FF4BFAE5C283FF48B +:103CD000BCAE7F2805D801460E4805F091FA009A3F +:103CE00078B9FF2F0DD022F817500137DBE7216B91 +:103CF0000BF14C03C1F308011944FFF751FEA0601A +:103D0000CEE70620DAE60520D8E600BF809300085B +:103D100079930008709300081FB5CDE9001003A83F +:103D200014460391FEF700FA002815DB0B4A52F8FF +:103D300020300BB100211970019B0BB100211970CB +:103D400042F820302CB1002201A96846FEF7C8FED7 +:103D50000446204604B010BD0B24FAE73C36002090 +:103D60002DE9F04798B0904605460191002800F0F3 +:103D7000528102F03F0603A901A83246FEF7B0FEC9 +:103D8000002840F04681039B4FF48C60049303F0BD +:103D90009BFA0746002800F04081039B00F5007263 +:103DA0000199D86004A81A61FFF702FE044620B901 +:103DB0009DF95B30002BB8BF062418F01C0F00F0F3 +:103DC000CD80002C4CD0042C40D104A8FFF724FC5B +:103DD000044600283AD146F00806039B1A78042AC4 +:103DE00040F08380186929462B60FFF7C3FD039BD1 +:103DF0001E22002118690230FDF79EFF039C00215E +:103E00001A2220692630FDF797FF236920221A71B4 +:103E1000246903F093FA0146012208342046FEF794 +:103E20002BF9039B04A81B6983F82120FFF764FA90 +:103E3000044658B9A96801B302462846FEF718FDA2 +:103E4000AB68039A0446013B5361B4B1384603F0B2 +:103E50004BFA0CB100232B60204618B0BDE8F08768 +:103E60009DF8163013F0110F40F0848018F0040F05 +:103E700040F0C98018F0080FAFD1039A31071399A9 +:103E8000936C48BF46F04006E964AB6410780428A0 +:103E900072D1069B9DF817102B62089B106923F0C6 +:103EA000FF030B4329466B62179BAB62FFF762FD72 +:103EB000DDF80CA00024002205F15008BAF8063005 +:103EC00021464046C5F800A0AB80002385F830604D +:103ED00085F831406C64C5E90E234FF40072FDF79C +:103EE0002BFFB20653D40024B0E703F027FA0146B3 +:103EF000009013980E30FEF7BFF813980099163013 +:103F0000FEF7BAF8039C13992078FFF749FD2023A8 +:103F100000228046CB7220461399FEF7D1F8139BFE +:103F2000002201211A775A779A77DA77039BD970A2 +:103F3000B8F1000FA1D0414604A8D3F84890FEF78D +:103F400097FC0446002881D149460398FEF75CFAA5 +:103F5000039B044608F1FF30586176E7002C7FF49C +:103F600075AF9DF81630DC064FD418F0020F84D0E0 +:103F7000D80782D5072469E7FFF712FD0023A86060 +:103F800001F11C00FEF772F86B61286190E7D5E93A +:103F9000046956EA0903A6D0BAF80AA0A9684FEA4C +:103FA0004A2AC5E90E69B24574EB09031BD3002404 +:103FB0002964002C7FF44AAFC6F30803002B92D08B +:103FC000039C2046FEF770F808B3760A01234146A9 +:103FD00046EAC95682196A64607802F0E5FC041E5C +:103FE00018BF012432E72846FEF7C6FAB6EB0A06E8 +:103FF000014669F10009012803D9431CD3D10124EA +:10400000D6E70224D4E7082420E704241EE702248C +:104010001CE704461EE709241EE711241CE70000E4 +:104020002DE9F04F994685B00023884603A9044640 +:10403000C9F800301646FEF791F8054680BB94F8A3 +:1040400031506DBB94F8303013F00103009300F051 +:10405000A68004F1500AD4E90432D4E90E011B1AF7 +:1040600062EB0102B34272F1000238BF1E46BEB1DC +:10407000D4E90E10C1F30803002B40F08280039BAB +:104080005A894B0A013A43EAC0531A401BD151EAFC +:10409000000309D1A06801280DD8022584F8315009 +:1040A000284605B0BDE8F08F216C20460192FEF74E +:1040B00063FA019AEFE7431C04D10123009D84F8C1 +:1040C0003130EDE72064DDF80CB0216C5846FDF787 +:1040D000EBFF0028E1D0B6F5007F02EB000731D3FB +:1040E000BBF80A1002EB5620730A88429BF80100C5 +:1040F00088BF8B1A3A464146019302F055FC0028CE +:10410000DBD194F93020019B002A0BDA606CC01BD4 +:10411000984207D24FF40072514608EB4020FDF759 +:10412000E5FD019B5F02D9F80030F61BB8443B4423 +:10413000C9F80030D4E90E32DB1942F10002C4E9BB +:104140000E3294E7626CBA421AD094F93030002BE8 +:104150000DDA012351469BF8010002F049FC0028CA +:10416000ABD194F8303003F07F0384F830300398FB +:1041700001233A465146407802F016FC00289CD1B3 +:104180006764A16B4046C1F30801C1F50077514453 +:10419000B74228BF37463A46FDF7A8FDC3E70725D3 +:1041A0007EE7000070B596B00E460022019002A98D +:1041B00001A8FEF795FC0446E0B94FF48C6003F0CB +:1041C00083F80546D8B1029B00F500720199D860CA +:1041D00002A81A61FFF7ECFB044640B99DF9533081 +:1041E000002B0ADB1EB1314602A8FDF7EDFF284681 +:1041F00003F07AF8204616B070BD0624F7E71124C4 +:10420000F8E7000070B5B8B00222019003A901A838 +:10421000FEF766FC044608BB039B4FF48C601093CA +:1042200003F052F80546002866D0039B00F50072A3 +:104230000199D86010A81A61FFF7BAFB044650B97B +:104240009DF88B30980655D4190653D49DF8463006 +:10425000DA0706D50724284603F046F8204638B08A +:1042600070BD039B04931878042814D104A918691D +:10427000FFF780FB069E9DF84630DB0610D410A8A1 +:10428000FEF776FF04460028E5D156BB0398FEF7FB +:10429000DBFB0446DFE71F99FFF782FB0646EAE7F0 +:1042A000039BDA69B242D5D024930021269624A834 +:1042B0001B78042B01BFDDE90823CDE928239DF8F5 +:1042C00017308DF89730FEF7EFF904460028C2D179 +:1042D00024A8FFF741F804460028BBD00428BAD12F +:1042E000CDE70246314604A8FEF7C2FA044600288C +:1042F000B1D1CBE70624AEE71124AFE7F0B5BDB0EE +:10430000CDE900106846FDF70FFF022203A901A8BE +:10431000FEF7E6FB0446002841D1039B4FF48C6076 +:10432000149302F0D1FF0546002800F0EE80039BB5 +:1043300000F5007214AE0199D8601A613046FFF79B +:1043400037FB044640BB9DF89B3013F0A00F40F0B4 +:10435000D880039B009F1A78042A68D11B6904AC9B +:1043600003F1400C1868083353F8041C22466345D7 +:1043700003C21446F6D15022314628A8FDF7B6FCF8 +:10438000394628A8FFF714FB044600284CD12A9A86 +:10439000169B9A4206D00824284602F0A5FF204624 +:1043A0003DB0F0BD349A209B9A42F4D128A8FFF783 +:1043B00033F904460028EFD1039B04AF1B6993F83F +:1043C00001E093F823C09C8C3A46083303CAB242FA +:1043D00043F8080C43F8041C1746F5D1039B28A8A2 +:1043E0001B6983F801E0039B1A6982F823C01A69EC +:1043F00082F82440240A82F825401A691379D906E4 +:104400005CBF43F020031371FEF776FF04460028DB +:10441000C2D13046FEF7ACFE04460028BCD103985A +:10442000FEF712FB0446B7E70428B5D1BEE7239A8E +:1044300004AB02F1200C1068083252F8041C1C4630 +:10444000624503C42346F6D15022314628A8FDF721 +:104450004DFC394628A8FFF7ABFA044600284CD19A +:104460002A9A169B9A4296D1349A209B9A4292D1CC +:1044700028A8FFF7D1F8044600288DD137990DF10F +:104480001D030DF12D0001F10D0253F8044B834281 +:1044900042F8044BF9D11888012710809B7893705B +:1044A0009DF81B30039CDA0658BF43F02003CB7203 +:1044B000E770CB7ADB06ACD5169A2A9B9A42A8D035 +:1044C0002078FFF76DFA01462046FDF7EDFD014625 +:1044D000C8B12046FDF798FF044600287FF45CAF82 +:1044E000039890F86D302E2B93D12A9A00F16C012D +:1044F000FDF7E6FD039BDF708BE704287FF44CAFEC +:10450000B6E7062448E7022446E7112447E70000FF +:104510007F2810B501D880B210BDB0F5803F13D20E +:1045200040F2523399420FD10849002231F8024B30 +:1045300093B2844203D103F18000C0B2ECE70132B0 +:10454000802AF3D11346F6E70020E5E7C09600087D +:104550007F280DD940F25233994208D1FF2806D85E +:1045600000F10040034B803833F810007047002002 +:10457000704700BFC0960008B0F5803FF0B522D26A +:104580001F4A83B21F49B0F5805F28BF0A46141D39 +:1045900034F8042C2146AAB1934213D334F8025CB8 +:1045A0002E0AEFB252FA85F5A84222DA082E09D86F +:1045B000DFE806F0050A10121416181A1C00801AFB +:1045C00034F810301846F0BD981A00F001001B1A9C +:1045D0009BB2F7E7103BFBE7203BF9E7303BF7E7FF +:1045E0001A3BF5E70833F3E7503BF1E7A3F5E35354 +:1045F000EEE70434002ECBD101EB4702C7E700BF42 +:10460000109400080496000808B5074B074A19687B +:1046100001F03D01996053680BB190689847BDE87F +:10462000084003F09DB800BF00000240443600205F +:1046300008B5084B1968890901F03D018A019A60A3 +:10464000054AD3680BB110699847BDE8084003F0EC +:1046500087B800BF000002404436002008B5084B70 +:104660001968090C01F03D010A049A60054A536972 +:104670000BB190699847BDE8084003F071B800BFDE +:10468000000002404436002008B5084B1968890D27 +:1046900001F03D018A059A60054AD3690BB1106AA1 +:1046A0009847BDE8084003F05BB800BF0000024037 +:1046B0004436002008B5074B074A596801F03D0110 +:1046C000D960536A0BB1906A9847BDE8084003F07F +:1046D00047B800BF000002404436002008B5084B30 +:1046E0005968890901F03D018A01DA60054AD36AF7 +:1046F0000BB1106B9847BDE8084003F031B800BF1C +:10470000000002404436002008B5084B5968090CE7 +:1047100001F03D010A04DA60054A536B0BB1906B5E +:104720009847BDE8084003F01BB800BF00000240F6 +:104730004436002008B5084B5968890D01F03D0149 +:104740008A05DA60054AD36B0BB1106C9847BDE857 +:10475000084003F005B800BF0000024044360020C6 +:1047600008B5074B074A196801F03D019960536C81 +:104770000BB1906C9847BDE8084002F0F1BF00BF54 +:10478000000402404436002008B5084B1968890926 +:1047900001F03D018A019A60054AD36C0BB1106D9E +:1047A0009847BDE8084002F0DBBF00BF00040240AC +:1047B0004436002008B5084B1968090C01F03D018A +:1047C0000A049A60054A536D0BB1906D9847BDE895 +:1047D000084002F0C5BF00BF00040240443600207C +:1047E00008B5084B1968890D01F03D018A059A60EA +:1047F000054AD36D0BB1106E9847BDE8084002F032 +:10480000AFBF00BF000402404436002008B5074B8C +:10481000074A596801F03D01D960536E0BB1906EA3 +:104820009847BDE8084002F09BBF00BF000402406B +:104830004436002008B5084B5968890901F03D014C +:104840008A01DA60054AD36E0BB1106F9847BDE854 +:10485000084002F085BF00BF00040240443600203B +:1048600008B5084B5968090C01F03D010A04DA60EB +:10487000054A536F0BB1906F9847BDE8084002F0AE +:104880006FBF00BF000402404436002008B5084B4B +:104890005968890D01F03D018A05DA60054AD36F38 +:1048A00013B1D2F880009847BDE8084002F058BF25 +:1048B000000402404436002000230C4910B51A467B +:1048C0000B4C0B6054F82300026001EB43000433EF +:1048D0004260402BF6D1074A4FF0FF339360D3601C +:1048E000C2F80834C2F80C3410BD00BF44360020B2 +:1048F000C0970008000002400F28F8B510D9102812 +:1049000010D0112811D0122808D10F240720DFF869 +:10491000C8E00126DEF80050A04208D9002653E086 +:104920000446F4E70F240020F1E70724FBE706FA2A +:1049300000F73D424AD1264C4FEA001C3D4304EBB0 +:1049400000160EEBC000CEF80050C0E90123FBB208 +:1049500073B12048D0F8D83043F00103C0F8D83004 +:10496000D0F8003143F00103C0F80031D0F8003135 +:1049700017F47F4F0ED01748D0F8D83043F0020319 +:10498000C0F8D830D0F8003143F00203C0F800314D +:10499000D0F8003154F80C00036823F01F030360C3 +:1049A000056815F00105FBD104EB0C033D2493F8D9 +:1049B0000CC05F6804FA0CF43C602124056044617B +:1049C00012B1987B00F0CAFC3046F8BD0130A3E775 +:1049D000C0970008004402584436002010B5302427 +:1049E00084F31188FFF788FF002383F3118810BD3B +:1049F00010B50446807B00F0C7FC01231549627B9B +:104A000003FA02F20B6823EA0203DAB20B6072B90E +:104A1000114AD2F8D81021F00101C2F8D810D2F80A +:104A2000001121F00101C2F80011D2F8002113F4A5 +:104A30007F4F0ED1084BD3F8D82022F00202C3F8E2 +:104A4000D820D3F8002122F00202C3F80021D3F8C5 +:104A5000003110BD443600200044025808B5302310 +:104A600083F31188FFF7C4FF002383F3118808BD87 +:104A7000836CC26A8B42506810B506D95A1E4C002E +:104A800002EB4103B3FBF4F3184410BD01F0010342 +:104A90008A0748BF43F002034A0748BF43F00803B0 +:104AA0000A0748BF43F00403CA0648BF43F0100397 +:104AB0008A06426B48BF43F02003134343637047A9 +:104AC00010B5074C204600F0CBFF064B0022C4E98E +:104AD0001023054BA364054BE363054BE36410BD52 +:104AE000C83600200070005200B4C4041C370020F7 +:104AF0001C390020C36A0BB9104BC3620379012B28 +:104B000011D10F4B98420ED10E4BD3F8D42042F462 +:104B10008032C3F8D420D3F8FC2042F48032C3F8AA +:104B2000FC20D3F8FC30436C00221A65DA621A606C +:104B30005A605A624FF0FF329A637047C09800087B +:104B4000C8360020004402580379012B1BD0436C67 +:104B500000221A65DA621A605A605A624FF0FF3218 +:104B60009A63094B98420ED1084BD3F8D42022F413 +:104B70008032C3F8D420D3F8FC2022F48032C3F86A +:104B8000FC20D3F8FC307047C8360020004402589F +:104B900010B5446C0649FFF76BFF6060236842F272 +:104BA000107043F003032360BDE8104001F05EBDC8 +:104BB000801A06000129F8B5466C0B4F09D17568BB +:104BC0000A493D40FFF754FF054345F480557560A1 +:104BD000F8BD746806493C40FFF74AFF044344F4BB +:104BE00080547460F4E700BF00ECFFFF80F0FA022D +:104BF00040787D01436C00225A601A6070470000C3 +:104C0000426C0129536823F4404304D0022905D0A3 +:104C100001B95360704743F48043FAE743F400431B +:104C2000F7E70000436C41F480519A60D9605A6BF9 +:104C30001206FCD580229A637047000010B541F43B +:104C40008851446CA260E160616B11F04502FBD0B9 +:104C5000A26311F0040203D0FFF718FF012010BD7A +:104C6000616910461960FAE710B541F48851446C47 +:104C7000A260E160616B11F04502FBD0A26311F00C +:104C8000050203D0FFF702FF012010BD6169104645 +:104C90001960FAE773B5134604460E46302282F3D4 +:104CA0001188426CD26B32B14FF0FF31403001932A +:104CB00001F0E8FC019B606C00220265C263C262E5 +:104CC000456B15F4807504D185F31188012002B07D +:104CD00070BD4FF0FF31816382F31188012E06D938 +:104CE0000C21204602B0BDE87040FFF7BDBF104662 +:104CF000EDE7000073B5446C0E4600250192616B30 +:104D0000A1632565E562FFF7C1FE012E07D9019B6E +:104D10002A460C2102B0BDE87040FFF7A5BF02B0E3 +:104D200070BD000010B541F49851446CA260E16080 +:104D3000616B11F04502FBD0A26311F03F0203D07A +:104D4000FFF7A4FE012010BD216A10461960E16939 +:104D50005960A16999606169D960F4E72DE9F74369 +:104D600004460191006D01A91746984602F020FC07 +:104D7000064600284AD0626C2046DDF8049055684B +:104D8000C5F3090501356B00A56CB5FBF3F54FF4D0 +:104D90007A73B5FBF3F55D43556200F027FE50BB17 +:104DA000636C4FF0FF3201254146C3F8589020460E +:104DB0001D659A634FF49572DA6342F207029F62AF +:104DC000DA62E36C0A9AFFF74FFFA0B9E26C104B6E +:104DD00011680B407BB929462046FFF75BFF05466B +:104DE00048B92E463A460199206D02F019FC30462A +:104DF00003B0BDE8F0833A460199206D02F010FC43 +:104E0000E26C01212046FFF775FFF0E70126EEE78F +:104E100008E0FFFD2DE9F7431F46436C01924FF474 +:104E20007A725D6804468846C5F3090501356E004F +:104E3000856CB5FBF6F5B5FBF2F555435D6200F008 +:104E4000D5FD20B10125284603B0BDE8F0837E02E0 +:104E500001A9206D324602F0ABFB05460028F1D0D7 +:104E6000636C019AD4F84C909A6501221A654FF050 +:104E7000FF329A634FF49572DA639E62236BDB060E +:104E80004B4658BF4FEA4828012F42461BD91221F2 +:104E90002046FFF7E9FEC0B9D9F80020104B1340B7 +:104EA0009BB9636C42F2930239462046DA62E26CA7 +:104EB000FFF7F0FE804640B932460199206D454625 +:104EC00002F0AEFBBFE71121E2E732460199206D07 +:104ED00002F0A6FBE26C39462046FFF70BFFB2E773 +:104EE00008E0FFFD2DE9F3411F46436C01924FF4AA +:104EF0007A725D6804468846C5F3090501356E007F +:104F0000856CB5FBF6F5B5FBF2F555435D6200F037 +:104F10006DFD20B10125284602B0BDE8F0817E027A +:104F200001A9206D324602F089FB05460028F1D028 +:104F3000636C019A9A6501221A654FF0FF329A63F9 +:104F40004FF48D72DA639E62236BE66CDB063346A8 +:104F500058BF4FEA4828012F424619D91921204647 +:104F6000FFF782FEB0B932680F4B134093B9636C00 +:104F700042F2910239462046DA62E26CFFF78AFE7D +:104F8000064638B901993546206D02F093FBC2E719 +:104F90001821E4E70199206D02F08CFBE26C3946A0 +:104FA0002046FFF7A7FEB6E708E0FFFD12F0030F6B +:104FB0002DE9F04107460C4615461E4617D00E4413 +:104FC000B44202D10020BDE8F0810123FA6B2146F2 +:104FD0003846FFF71FFF0028F5D128464FF400722E +:104FE000F96B05F500750134FCF780FEE8E7BDE8D4 +:104FF000F041FFF70FBF000012F0030F2DE9F04161 +:1050000007460C4615461E4617D00E44B44202D140 +:105010000020BDE8F08129464FF40072F86B05F5D9 +:105020000075FCF763FE0123FA6B21463846FFF753 +:1050300059FF0028EDD10134E8E7BDE8F041FFF762 +:1050400051BF000000207047302310B583F3118852 +:105050000024436C40302146DC6301F021FB84F3E3 +:10506000118810BD026843681143016003B11847FD +:1050700070470000024A136843F0C0031360704792 +:1050800000440040024A136843F0C00313607047B5 +:1050900000480040024A136843F0C00313607047A1 +:1050A00000780040064BD3F8E8200243C3F8E8201C +:1050B000D3F810211043C3F81001D3F81031704712 +:1050C0000044025837B5274C274D204600F028FDF4 +:1050D00004F11400009400234FF40072234900F0FF +:1050E000C3F94FF40072224904F138000094214BB7 +:1050F00000F03CFA204BC4E91735204C204600F064 +:105100000FFD04F11400009400234FF400721C49B9 +:1051100000F0AAF94FF400721A4904F13800009423 +:10512000194B00F023FA194BC4E91735184C2046E7 +:1051300000F0F6FC04F1140000234FF4007215494E +:10514000009400F091F9144B4FF40072134904F1EC +:105150003800009400F00AFA114BC4E9173503B087 +:1051600030BD00BF2039002000E1F505643A002081 +:105170006440002075500008004400408C39002035 +:10518000643C002064420020855000080048004034 +:10519000F8390020643E0020955000086444002047 +:1051A0000078004038B5264D0446037C002918BF1E +:1051B0000D46012B06D1234B984230D14FF40030DD +:1051C000FFF770FF2A68236EE16D03EB5203A566BB +:1051D000B3FBF2F36A68100442BF23F0070003F048 +:1051E000070343EA4003CB60AB6843F040034B60E6 +:1051F000EB6843F001038B6042F4967343F00103C4 +:105200000B604FF0FF330B62510505D512F01022F1 +:1052100011D0B2F1805F10D084F8643038BD0A4BF1 +:10522000984205D0094B9842CCD14FF08040C7E757 +:105230004FF48020C4E77F23EEE73F23ECE700BF75 +:10524000C8980008203900208C390020F839002047 +:105250002DE9F047C66D05463768F46921073462C9 +:105260001AD014F0080118BF4FF48071E20748BF4C +:1052700041F02001A3074FF0300348BF41F0400147 +:10528000600748BF41F0800183F31188281DFFF7B4 +:10529000E9FE002383F31188E2050AD5302383F366 +:1052A00011884FF48061281DFFF7DCFE002383F393 +:1052B00011884FF030094FF0000A14F0200838D15F +:1052C0003B0616D54FF0300905F1380A200610D5F7 +:1052D00089F31188504600F07DF9002836DA08215C +:1052E000281DFFF7BFFE27F080033360002383F300 +:1052F0001188790614D5620612D5302383F31188FC +:10530000D5E913239A4208D12B6C33B127F040071B +:105310001021281DFFF7A6FE3760002383F31188B4 +:10532000E30618D5AA6E1369ABB15069BDE8F04722 +:10533000184789F31188736A284695F86410194054 +:1053400000F008FC8AF31188F469B6E7B06288F3CC +:105350001188F469BAE7BDE8F0870000090100F19F +:105360006043012203F56143C9B283F8001300F0E2 +:105370001F039A4043099B0003F1604303F5614317 +:10538000C3F880211A60704700F01F0301229A4081 +:10539000430900F160409B0000F5614003F1604368 +:1053A00003F56143C3F88020C3F88021002380F80F +:1053B00000337047F8B51546826804460B46AA428A +:1053C00000D28568A1692669761AB5420BD21846C3 +:1053D0002A46FCF78BFCA3692B44A3612846A368EB +:1053E0005B1BA360F8BD0CD9AF1B18463246FCF717 +:1053F0007DFC3A46E1683044FCF778FCE3683B44C6 +:10540000EBE718462A46FCF771FCE368E5E7000085 +:1054100083689342F7B50446154600D28568D4E9FF +:105420000460361AB5420BD22A46FCF75FFC63696A +:105430002B4463612846A3685B1BA36003B0F0BDE7 +:105440000DD93246AF1B0191FCF750FC01993A4649 +:10545000E0683144FCF74AFCE3683B44E9E72A464C +:10546000FCF744FCE368E4E710B50A440024C36198 +:10547000029B8460C16002610362C0E90000C0E970 +:10548000051110BD08B5D0E90532934201D18268FB +:1054900082B98268013282605A1C4261197000210F +:1054A000D0E904329A4224BFC368436101F012F983 +:1054B000002008BD4FF0FF30FBE7000070B530233F +:1054C00004460E4683F31188A568A5B1A368A269B6 +:1054D000013BA360531CA36115782269934224BF4A +:1054E000E368A361E3690BB120469847002383F387 +:1054F0001188284607E03146204601F0DBF80028F5 +:10550000E2DA85F3118870BD2DE9F74F04460E46A7 +:1055100017469846D0F81C904FF0300A8AF311884D +:105520004FF0000B154665B12A4631462046FFF77D +:1055300041FF034660B94146204601F0BBF8002810 +:10554000F1D0002383F31188781B03B0BDE8F08FFE +:10555000B9F1000F03D001902046C847019B8BF39F +:105560001188ED1A1E448AF31188DCE7C160C3611B +:10557000009B82600362C0E905111144C0E900008C +:1055800001617047F8B504460D461646302383F393 +:105590001188A768A7B1A368013BA36063695A1C7F +:1055A00062611D70D4E904329A4224BFE3686361EA +:1055B000E3690BB120469847002080F3118807E08B +:1055C0003146204601F076F80028E2DA87F31188A8 +:1055D000F8BD0000D0E9052310B59A4201D18268D8 +:1055E0007AB982680021013282605A1C82611C787B +:1055F00003699A4224BFC368836101F06BF82046B7 +:1056000010BD4FF0FF30FBE72DE9F74F04460E4683 +:1056100017469846D0F81C904FF0300A8AF311884C +:105620004FF0000B154665B12A4631462046FFF77C +:10563000EFFE034660B94146204601F03BF80028E2 +:10564000F1D0002383F31188781B03B0BDE8F08FFD +:10565000B9F1000F03D001902046C847019B8BF39E +:105660001188ED1A1E448AF31188DCE70379052BB3 +:1056700005BF836A002001204B6004BF4FF4007314 +:105680000B60704770B55D1E866A04460D44B542D6 +:1056900005D9436B43F080034363012070BD0625A9 +:1056A0000571FFF783FC05232371F7E770B55D1ED5 +:1056B000866A04460D44B54205D9436B43F0800326 +:1056C0004363012070BD07250571FFF795FC052395 +:1056D0002371F7E738B505790446052D05D1082370 +:1056E0000371FFF7AFFC257138BD0120FCE7000016 +:1056F0000323F0B5037185B00446FFF749FA002291 +:1057000020461146FFF78EFA4FF4D57203AB0821FD +:105710002046FFF7A9FA0246B8B901232363039B89 +:10572000C3F30323012B09D103AB37212046FFF735 +:105730009BFA18B9A44B039A1340ABB1204601253C +:10574000FFF758FA0223237137E103AB0022372118 +:105750002046FFF789FA28B99B4A039B1A40002A82 +:1057600000F0A78002232363236B03F00F03022BB7 +:1057700040F0A9806425954E42F2107000F076FF4B +:1057800003AB324601212046FFF758FA0028D5D155 +:10579000039B002B80F293805A0003D5236B43F0C8 +:1057A00010032363002204F1080302212046FFF7BF +:1057B000B9FA02460028C1D104F13803032120467A +:1057C000FFF752FA0028B9D104F11805A26B09219C +:1057D00020462B46FFF7A6FA0028AFD102ABA26BFA +:1057E00007212046FFF740FA06460028A6D1236B82 +:1057F00003F00F03022B40F08F807E227F2128468A +:1058000003F01CFA012840F28780E76B42F2107027 +:1058100000F02CFF08234FF4007239462046009612 +:10582000FFF79CFA002889D1384603F055FA236B1C +:10583000A06203F00F03022B72D103AB644A06216E +:105840002046FFF711FA002871D15F49039B1940E8 +:10585000B1FA81F149092046FFF7ACF902AB4FF4E8 +:10586000007210212046FFF7FFF9054600287FF45B +:1058700065AF554E029B33427FF460AF236B13F04C +:105880000E0F03F00F0273D0022A7FF457AFE36AC2 +:105890001978012900F09480022900F093800029F2 +:1058A00000F089804B4F2046FFF7AAF903AB3A4638 +:1058B00076E0114620462263FFF7B4F954E7013D34 +:1058C0007FF45AAF3AE7444D6426444A3E4F012BD9 +:1058D00018BF154603AB002237212046FFF7C4F955 +:1058E00000287FF42BAF039B3B427FF427AF03AB31 +:1058F0002A4629212046FFF7A1F900287FF41EAF90 +:10590000039B002BFFF648AF013E3FF417AF42F276 +:10591000107000F0ABFEDDE7284603F0B1F986E732 +:105920007E227F212846E66B03F088F908B9002122 +:1059300091E7002340223146204600930623FFF7DB +:105940000DFA0028F3D1B3895BBA9B07EFD5244B3E +:1059500040223146204600930623FFF7FFF9002836 +:10596000E5D1317C01F00F010F3918BF012172E739 +:10597000E36A1978F9B101297FF4E0AE2046FFF718 +:105980003FF903ABA26B37212046FFF76DF90028E2 +:105990007FF4D4AE039B33427FF4D0AE03AB02223C +:1059A00006212046FFF760F900287FF4C7AE039B6D +:1059B00033427FF4C3AE05232371284605B0F0BD02 +:1059C000084F70E7084F6EE708E0FFFD0080FFC05A +:1059D0000001B9030000B7030080FF5000001080F1 +:1059E000F1FFFF800001B7030002B70337B504469B +:1059F0000C4D01ABA26B0D212046FFF735F978B9AC +:105A0000019B2B420BD1C3F34323042B08D0053B4E +:105A1000022B04D84FF47A7000F028FEE9E7012049 +:105A200003B030BD08E0FFFD70B53023054683F3B9 +:105A3000118803790024022B03D184F311882046B6 +:105A400070BD0423037184F311880226FFF7CEFF93 +:105A500004462846FFF7CEF82E71F0E7FFF730B87E +:105A6000044B03600123037100234363C0E90A333D +:105A7000704700BFE098000810B53023044683F358 +:105A80001188C162FFF736F802230020237180F3EA +:105A9000118810BD10B53023044683F31188FFF739 +:105AA00053F800230122E362227183F3118810BDB1 +:105AB000026843681143016003B118477047000052 +:105AC0001430FFF721BD00004FF0FF331430FFF713 +:105AD0001BBD00003830FFF797BD00004FF0FF33CB +:105AE0003830FFF791BD00001430FFF7E7BC00002D +:105AF0004FF0FF311430FFF7E1BC00003830FFF702 +:105B000041BD00004FF0FF323830FFF73BBD0000D1 +:105B1000012914BF6FF0130000207047FFF7D2BABD +:105B2000044B036000234360C0E902330123037484 +:105B3000704700BF0499000810B53023044683F372 +:105B40001188FFF72FFB02230020237480F31188B4 +:105B500010BD000038B5C36904460D461BB90421C9 +:105B60000844FFF7A5FF294604F11400FFF78AFC5B +:105B7000002806DA201D4FF40061BDE83840FFF729 +:105B800097BF38BD026843681143016003B11847ED +:105B90007047000013B5406B00F58054D4F8A4386A +:105BA0001A681178042914D1017C022911D11979BC +:105BB000012312898B4013420BD101A94C3002F012 +:105BC0006BFFD4F8A4480246019B2179206800F0BD +:105BD000DFF902B010BD0000143002F0EDBE00008D +:105BE0004FF0FF33143002F0E7BE00004C3002F0FB +:105BF000BFBF00004FF0FF334C3002F0B9BF0000D0 +:105C0000143002F0BBBE00004FF0FF31143002F040 +:105C1000B5BE00004C3002F08BBF00004FF0FF32E9 +:105C20004C3002F085BF00000020704710B500F531 +:105C30008054D4F8A4381A681178042917D1017C4B +:105C4000022914D15979012352898B4013420ED174 +:105C5000143002F04DFE024648B1D4F8A4484FF487 +:105C6000407361792068BDE8104000F07FB910BD35 +:105C7000406BFFF7DBBF0000704700007FB5124BA1 +:105C800001250426044603600023057400F1840204 +:105C900043602946C0E902330C4B02901430019353 +:105CA0004FF44073009602F0FFFD094B04F6944256 +:105CB000294604F14C000294CDE900634FF440738F +:105CC00002F0C6FE04B070BD2C990008715C00089B +:105CD000955B00080A68302383F311880B790B3336 +:105CE00042F823004B79133342F823008B7913B128 +:105CF0000B3342F8230000F58053C3F8A4180223A5 +:105D00000374002080F311887047000038B5037FCA +:105D1000044613B190F85430ABB90125201D02217F +:105D2000FFF730FF04F114006FF00101257700F058 +:105D3000DDFC04F14C0084F854506FF00101BDE823 +:105D4000384000F0D3BC38BD10B501210446043002 +:105D5000FFF718FF0023237784F8543010BD0000AC +:105D600038B504460025143002F0B6FD04F14C00AD +:105D7000257702F085FE201D84F854500121FFF79D +:105D800001FF2046BDE83840FFF750BF90F8803053 +:105D900003F06003202B06D190F881200023212AF4 +:105DA00003D81F2A06D800207047222AFBD1C0E959 +:105DB0001D3303E0034A426707228267C36701205D +:105DC000704700BF4422002037B500F58055D5F854 +:105DD000A4381A68117804291AD1017C022917D134 +:105DE0001979012312898B40134211D100F14C041F +:105DF000204602F005FF58B101A9204602F04CFEF2 +:105E0000D5F8A4480246019B2179206800F0C0F82B +:105E100003B030BD01F10B03F0B550F8236085B03D +:105E200004460D46FEB1302383F3118804EB850749 +:105E3000301D0821FFF7A6FEFB6806F14C005B69E8 +:105E40001B681BB1019002F035FE019803A902F016 +:105E500023FE024648B1039B2946204600F098F8ED +:105E6000002383F3118805B0F0BDFB685A691268FE +:105E7000002AF5D01B8A013B1340F1D104F18002C6 +:105E8000EAE70000133138B550F82140ECB1302377 +:105E900083F3118804F58053D3F8A428136852794A +:105EA00003EB8203DB689B695D6845B104216018E0 +:105EB000FFF768FE294604F1140002F023FD204696 +:105EC000FFF7B4FE002383F3118838BD704700004C +:105ED00001F044BD01234022002110B5044600F822 +:105EE000303BFBF729FF0023C4E9013310BD00005C +:105EF00010B53023044683F3118824224160002129 +:105F00000C30FBF719FF204601F04AFD0223002068 +:105F1000237080F3118810BD70B500EB8103054636 +:105F200050690E461446DA6018B110220021FBF7C2 +:105F300003FFA06918B110220021FBF7FDFE3146D6 +:105F40002846BDE8704001F031BE00008368202281 +:105F5000002103F0011310B5044683601030FBF7F5 +:105F6000EBFE2046BDE8104001F0ACBEF0B40125C8 +:105F700000EB810447898D40E4683D43A469458175 +:105F800023600023A2606360F0BC01F0C9BE000082 +:105F9000F0B4012500EB810407898D40E4683D439E +:105FA0006469058123600023A2606360F0BC01F096 +:105FB0003FBF000070B50223002504462422037071 +:105FC0002946C0F888500C3040F8045CFBF7B4FE5A +:105FD000204684F8705001F07DFD63681B6823B192 +:105FE00029462046BDE87040184770BD0378052B50 +:105FF00010B504460AD080F88C300523037043683E +:106000001B680BB1042198470023A36010BD00005A +:106010000178052906D190F88C20436802701B682E +:1060200003B118477047000070B590F8703004460F +:1060300013B1002380F8703004F18002204601F093 +:1060400065FE63689B68B3B994F8803013F060050F +:1060500035D00021204602F057F90021204602F0F9 +:1060600047F963681B6813B1062120469847062349 +:1060700084F8703070BD204698470028E4D0B4F80A +:106080008630A26F9A4288BFA36794F98030A56FCB +:10609000002B4FF0300380F20381002D00F0F280DE +:1060A000092284F8702083F3118800212046D4E966 +:1060B0001D23FFF76DFF002383F31188DAE794F8BF +:1060C000812003F07F0343EA022340F2023293422D +:1060D00000F0C58021D8B3F5807F48D00DD8012BC2 +:1060E0003FD0022B00F09380002BB2D104F1880244 +:1060F00062670222A267E367C1E7B3F5817F00F020 +:106100009B80B3F5407FA4D194F88230012BA0D1BD +:10611000B4F8883043F0020332E0B3F5006F4DD09D +:1061200017D8B3F5A06F31D0A3F5C063012B90D879 +:106130006368204694F882205E6894F88310B4F86F +:106140008430B047002884D0436863670368A3673E +:106150001AE0B3F5106F36D040F6024293427FF456 +:1061600078AF5C4B63670223A3670023C3E794F80F +:106170008230012B7FF46DAFB4F8883023F0020336 +:10618000A4F88830C4E91D55E56778E7B4F8803095 +:10619000B3F5A06F0ED194F88230204684F88A308F +:1061A00001F0F6FC63681B6813B101212046984793 +:1061B000032323700023C4E91D339CE704F18B0300 +:1061C00063670123C3E72378042B10D1302383F3C3 +:1061D00011882046FFF7BAFE85F311880321636812 +:1061E00084F88B5021701B680BB12046984794F8B7 +:1061F0008230002BDED084F88B3004232370636858 +:106200001B68002BD6D0022120469847D2E794F88D +:10621000843020461D0603F00F010AD501F068FD09 +:10622000012804D002287FF414AF2B4B9AE72B4BA4 +:1062300098E701F04FFDF3E794F88230002B7FF4EC +:1062400008AF94F8843013F00F01B3D01A0620463B +:1062500002D502F071F8ADE702F062F8AAE794F80F +:106260008230002B7FF4F5AE94F8843013F00F01E8 +:10627000A0D01B06204602D502F046F89AE702F0AD +:1062800037F897E7142284F8702083F311882B469F +:106290002A4629462046FFF769FE85F31188E9E67C +:1062A0005DB1152284F8702083F311880021204607 +:1062B000D4E91D23FFF75AFEFDE60B2284F8702077 +:1062C00083F311882B462A4629462046FFF760FEB5 +:1062D000E3E700BF5C99000854990008589900084A +:1062E00038B590F870300446002B3ED0063BDAB249 +:1062F0000F2A34D80F2B32D8DFE803F037313108BA +:10630000223231313131313131313737856FB0F8A7 +:1063100086309D4214D2C3681B8AB5FBF3F203FB9F +:1063200012556DB9302383F311882B462A4629462E +:10633000FFF72EFE85F311880A2384F870300EE0F3 +:10634000142384F87030302383F31188002320460F +:106350001A461946FFF70AFE002383F3118838BD59 +:10636000C36F03B198470023E7E70021204601F0FF +:10637000CBFF0021204601F0BBFF63681B6813B10F +:106380000621204698470623D7E7000010B590F86D +:1063900070300446142B29D017D8062B05D001D80D +:1063A0001BB110BD093B022BFBD80021204601F098 +:1063B000ABFF0021204601F09BFF63681B6813B10F +:1063C000062120469847062319E0152BE9D10B2317 +:1063D00080F87030302383F3118800231A46194661 +:1063E000FFF7D6FD002383F31188DAE7C3689B69C2 +:1063F0005B68002BD5D1C36F03B19847002384F8A5 +:106400007030CEE70023826880F8243083691B68EF +:1064100099689142FBD25A680360426010605860EC +:10642000704700000023826880F8243083691B686D +:1064300099689142FBD85A680360426010605860C6 +:106440007047000008B50846302383F3118891F89F +:106450002430032B05D0042B0DD02BB983F31188E6 +:1064600008BD8B6A00221A604FF0FF338362FFF78A +:10647000C9FF0023F2E7D1E9003213605A60F3E765 +:10648000034610B51B68984203D09C688A68944202 +:10649000F8D25A680B604A601160596010BD000064 +:1064A000FFF7B0BF064BD96881F82400186802686E +:1064B00053601A600122D86080F82420F9F7A2BF47 +:1064C000684600200C4B30B5DD684B1C87B0044695 +:1064D0000FD02B46094A684600F09CF92046FFF78A +:1064E000E1FF009B13B1684600F09EF9A86A07B06F +:1064F00030BDFFF7D7FFF9E7684600204564000884 +:10650000044B1A68DB6890689B68984294BF00202F +:106510000120704768460020094B10B51C68D868F8 +:10652000226853601A600122DC6084F82420FFF79F +:1065300079FF01462046BDE81040F9F763BF00BF70 +:1065400068460020044B1A68DB6892689B689A4290 +:1065500001D9FFF7E1BF70476846002038B5012335 +:10656000084C00252370656002F0E4FB02F00AFC91 +:106570000549064802F0E0FC0223237085F31188E8 +:1065800038BD00BF1049002064990008684600200B +:1065900000F080B9034A516853685B1A9842FBD8EF +:1065A000704700BF001000E08B604B630023CA619E +:1065B00000F128020B6302230A618B8401238861A6 +:1065C00081F8263001F11003C26A4A611360C36288 +:1065D00001F12C030846CB6270470000D0E901317D +:1065E000026841F8183CA1F19C033839CB6003697B +:1065F00041F8243C436941F8203C034B41F8043CFA +:10660000C3680248FFF7D0BF1D0400086846002099 +:1066100008B5FFF7E3FFBDE80840FFF741BF000002 +:1066200038B50E4BDC6804F12C05A062E06AA84284 +:106630000FD194F826303BB994F825309B0702BF60 +:10664000D4E9043213605A600F20BDE83840FFF7E8 +:1066500029BF0368E362FFF723FFE7E768460020EE +:10666000302383F31188FFF7DBBF000008B5014634 +:10667000302383F311880820FFF724FF002383F3DE +:10668000118808BD054BDB6821B1036098620320C7 +:10669000FFF718BF4FF0FF30704700BF684600207B +:1066A00003682BB10022026018469962FFF7F8BE1A +:1066B00070470000064BDB6839B1426818605A60C9 +:1066C000136043600420FFF7FDBE4FF0FF307047BA +:1066D000684600200368984206D01A68026050603D +:1066E00018469962FFF7DCBE7047000038B50446D3 +:1066F0000D462068844200D138BD036823605C6089 +:106700008562FFF7CDFEF4E7036810B59C68A242EE +:106710000CD85C688A600B604C6021605960996895 +:106720008A1A9A604FF0FF33836010BD121B1B68FA +:10673000ECE700000A2938BF0A2170B504460D466F +:106740000A26601902F0F0FA02F0D8FA041BA542FA +:1067500003D8751C04462E46F3E70A2E04D90120FF +:10676000BDE8704002F0B0BC70BD0000F8B5144B3D +:106770000D460A2A4FF00A07D96103F11001826021 +:1067800038BF0A22416019691446016048601861E7 +:10679000A81802F0B9FA02F0B1FA431B0646A34268 +:1067A00006D37C1C28192746354602F0BDFAF2E7CD +:1067B0000A2F04D90120BDE8F84002F085BCF8BDDD +:1067C00068460020F8B506460D4602F097FA0F4AD3 +:1067D000134653F8107F9F4206D12A4601463046A1 +:1067E000BDE8F840FFF7C2BFD169BB68441A2C1955 +:1067F00028BF2C46A34202D92946FFF79BFF224619 +:1068000031460348BDE8F840FFF77EBF68460020E8 +:1068100078460020C0E90323002310B45DF8044B40 +:106820004361FFF7CFBF000010B5194C23699842B0 +:106830000DD08168D0E9003213605A609A680A442A +:106840009A60002303604FF0FF33A36110BD02681C +:10685000234643F8102F53600022026022699A42B7 +:1068600003D1BDE8104002F059BA936881680B4427 +:10687000936002F043FA2269E1699268441AA242E5 +:10688000E4D91144BDE81040091AFFF753BF00BF17 +:10689000684600202DE9F047DFF8BC8008F11007BA +:1068A0002C4ED8F8105002F029FAD8F81C40AA68EB +:1068B000031B9A423ED814444FF00009D5E9003238 +:1068C000C8F81C4013605A60C5F80090D8F8103022 +:1068D000B34201D102F022FA89F31188D5E90331DC +:1068E00028469847302383F311886B69002BD8D052 +:1068F00002F004FA6A69A0EB040982464A450DD207 +:10690000022002F0E1FB0022D8F81030B34208D197 +:1069100051462846BDE8F047FFF728BF121A224427 +:10692000F2E712EB09092946384638BF4A46FFF715 +:10693000EBFEB5E7D8F81030B34208D01444C8F8DD +:106940001C00211AA960BDE8F047FFF7F3BEBDE8BF +:10695000F08700BF784600206846002038B502F076 +:10696000CDF9054AD2E90845031B181945F1000184 +:10697000C2E9080138BD00BF6846002010B560B903 +:10698000074804790368053C9B6818BF01249847B1 +:1069900008B144F00404204610BD0124FBE700BF09 +:1069A000C8360020FFF7EABF2DE9F04788461746B2 +:1069B0009A460446B0B90D4E3579052D05D003240D +:1069C0000DE0013D15F0FF050ED032685346394603 +:1069D0003046D2F814904246C8470028F1D12046EC +:1069E000BDE8F0870424FAE70124F8E7C836002060 +:1069F0002DE9F047884617469A460446B0B90D4E31 +:106A00003579052D05D003240DE0013D15F0FF0576 +:106A10000ED03268534639463046D2F81890424676 +:106A2000C8470028F1D12046BDE8F0870424FAE7E2 +:106A30000124F8E7C836002037B50C46154670B972 +:106A400051B101290BD10748694603681B6A984771 +:106A500010B9019B04462B60204603B030BD0424CE +:106A6000FAE700BFC836002000207047FEE70000AC +:106A7000704700004FF0FF30704700004B684360E4 +:106A80008B688360CB68C3600B6943614B690362A9 +:106A90008B6943620B6803607047000008B53C4B8C +:106AA00040F2FF713B48D3F888200A43C3F888209E +:106AB000D3F8882022F4FF6222F00702C3F888206E +:106AC000D3F88820D3F8E0200A43C3F8E020D3F8B5 +:106AD00008210A43C3F808212F4AD3F80831114688 +:106AE000FFF7CCFF00F5806002F11C01FFF7C6FF45 +:106AF00000F5806002F13801FFF7C0FF00F580600B +:106B000002F15401FFF7BAFF00F5806002F1700155 +:106B1000FFF7B4FF00F5806002F18C01FFF7AEFFD4 +:106B200000F5806002F1A801FFF7A8FF00F5806082 +:106B300002F1C401FFF7A2FF00F5806002F1E0015D +:106B4000FFF79CFF00F5806002F1FC01FFF796FF64 +:106B500002F58C7100F58060FFF790FF01F084FC76 +:106B60000E4BD3F8902242F00102C3F89022D3F8E2 +:106B7000942242F00102C3F894220522C3F898201F +:106B80004FF06052C3F89C20054AC3F8A02008BD0E +:106B900000440258000002587899000800ED00E017 +:106BA0001F00080308B501F06BFEFFF7D7FC104B80 +:106BB000D3F8DC2042F04002C3F8DC20D3F80421F3 +:106BC00022F04002C3F80421D3F80431094B1A68BB +:106BD00042F008021A601A6842F004021A6000F0DB +:106BE00071FD00F035FBBDE8084000F0B5B800BF0E +:106BF00000440258001802480120704700207047E6 +:106C00007047000002290CD0032904D0012907484D +:106C100018BF00207047032A05D8054800EBC200C2 +:106C20007047044870470020704700BF749B0008FD +:106C300054220020289B000870B59AB005460846EB +:106C4000144601A900F0C2F801A8FBF76DF8431C37 +:106C50000022C6B25B001046C5E90034237003234E +:106C6000023404F8013C01ABD1B202348E4201D8A7 +:106C70001AB070BD13F8011B013204F8010C04F8BE +:106C8000021CF1E708B5302383F311880348FFF7AE +:106C90009BF8002383F3118808BD00BF184900202A +:106CA00090F8803003F01F02012A07D190F881206C +:106CB0000B2A03D10023C0E91D3315E003F0600364 +:106CC000202B08D1B0F884302BB990F88120212AEC +:106CD00003D81F2A04D8FFF759B8222AEBD0FAE7C5 +:106CE000034A426707228267C3670120704700BFDB +:106CF0004B22002007B5052917D8DFE801F0191647 +:106D000003191920302383F31188104A01210190BF +:106D1000FFF702F9019802210D4AFFF7FDF80D482F +:106D2000FFF71EF8002383F3118803B05DF804FB1E +:106D3000302383F311880748FEF7E8FFF2E730239A +:106D400083F311880348FEF7FFFFEBE7C89A0008BA +:106D5000EC9A00081849002038B50C4D0C4C2A4616 +:106D60000C4904F10800FFF767FF05F1CA0204F1BE +:106D700010000949FFF760FF05F5CA7204F1180019 +:106D80000649BDE83840FFF757BF00BFF06100205B +:106D900054220020AC9A0008B69A0008BE9A000857 +:106DA00070B5044608460D46FAF7BEFFC6B2204647 +:106DB000013403780BB9184670BD32462946FAF7FC +:106DC0009FFF0028F3D10120F6E700002DE9F047EE +:106DD00005460C46FAF7A8FF2C49C6B22846FFF72D +:106DE000DFFF08B10836F6B229492846FFF7D8FF79 +:106DF00008B11036F6B2632E0BD8DFF89080DFF8BA +:106E00009090244FDFF898A02E7846B92670BDE800 +:106E1000F08729462046BDE8F04702F0FFB9252E4D +:106E200030D1072241462846FAF76AFF80B91A4B4B +:106E3000224603F10C0153F8040B8B4242F8040B79 +:106E4000F9D1198807359B780F3411809370DBE7EF +:106E5000082249462846FAF753FF98B9A21C0F4B5F +:106E6000197802320909C95D02F8041C13F8011BE4 +:106E700001F00F015345C95D02F8031CF0D118342D +:106E80000835C1E7013504F8016BBDE7949B0008A4 +:106E9000BE9A0008AC9B00089C9B000800E8F11F0C +:106EA0000CE8F11FBFF34F8F044B1A695107FCD157 +:106EB000D3F810215207F8D1704700BF00200052CC +:106EC00008B50D4B1B78ABB9FFF7ECFF0B4BDA683D +:106ED000D10704D50A4A5A6002F188325A60D3F8C1 +:106EE0000C21D20706D5064AC3F8042102F18832E4 +:106EF000C3F8042108BD00BF4E64002000200052EA +:106F00002301674508B5114B1B78F3B9104B1A697B +:106F1000510703D5DA6842F04002DA60D3F8102155 +:106F2000520705D5D3F80C2142F04002C3F80C21DA +:106F3000FFF7B8FF064BDA6842F00102DA60D3F8D7 +:106F40000C2142F00102C3F80C2108BD4E64002060 +:106F5000002000520F289ABF00F5806040040020F6 +:106F6000704700004FF40030704700001020704759 +:106F70000F2808B50BD8FFF7EDFF00F500330268C6 +:106F8000013204D104308342F9D1012008BD002030 +:106F9000FCE700000F2838B505463FD8FFF782FF11 +:106FA0001F4CFFF78DFF4FF0FF3307286361C4F8D4 +:106FB00014311DD82361FFF775FF030243F024034A +:106FC000E360E36843F08003E36023695A07FCD47D +:106FD0002846FFF767FFFFF7BDFF4FF4003100F0D1 +:106FE000ABFA2846FFF78EFFBDE83840FFF7C0BF79 +:106FF000C4F81031FFF756FFA0F108031B0243F05D +:107000002403C4F80C31D4F80C3143F08003C4F8E5 +:107010000C31D4F810315B07FBD4D9E7002038BD20 +:10702000002000522DE9F84F05460C46104645EA6F +:107030000203DE0602D00020BDE8F88F20F01F001A +:10704000DFF8BCB0DFF8BCA0FFF73AFF04EB0008A4 +:10705000444503D10120FFF755FFEDE720222946E3 +:10706000204602F0A3F810B920352034F0E72B4673 +:1070700005F120021F68791CDDD104339A42F9D151 +:1070800005F178431B481C4EB3F5801F1B4B38BFDE +:10709000184603F1F80332BFD946D1461E46FFF722 +:1070A00001FF0760A5EB040C336804F11C0143F0F9 +:1070B00002033360231FD9F8007017F00507FAD1D7 +:1070C00053F8042F8B424CF80320F4D1BFF34F8FB9 +:1070D000FFF7E8FE4FF0FF332022214603602846E9 +:1070E000336823F00203336002F060F80028BBD05D +:1070F0003846B0E7142100520C20005214200052F0 +:10710000102000521021005210B5084C237828B1ED +:107110001BB9FFF7D5FE0123237010BD002BFCD057 +:107120002070BDE81040FFF7EDBE00BF4E640020A8 +:107130002DE9F04F0D4685B0814658B111F00D068E +:1071400014BF2022082211F00803019304D0431E2B +:10715000034269D0002435E0002E37D009F11F0129 +:1071600021F01F094FF00108314F05F00403DFF84B +:10717000CCA005EA080BBBF1000F32D07869C0073C +:107180002FD408F101080C37B8F1060FF3D19EB9DE +:10719000284D4946A819019201F016FE0446002820 +:1071A00039D12036019AA02EF3D1494601F00CFEC8 +:1071B000044600282FD1019A49461F4801F004FED9 +:1071C000044660BB204605B0BDE8F08F0029C9D158 +:1071D00001462846029201F0F7FD0446D8B9029A0A +:1071E000C0E713B178694107CBD5AC0702D5786900 +:1071F0008007C6D5019911B178690107C1D5494603 +:107200000AEB4810CDE9022301F0DEFD0446DDE97A +:1072100002230028B5D04A460021204601E04A4614 +:107220000021FAF789FDCDE70246002E96D199E7B5 +:10723000C09B00089064002050640020706400200F +:107240000021FFF775BF00000121FFF771BF0000AB +:1072500070B5144D0124144E40F2FF32002101207C +:10726000FAF76AFD06EB441001342A6955F80C1F41 +:1072700001F096FD062CF5D137254FF4C054204679 +:10728000FFF7E2FF014628B122460848BDE87040FA +:1072900001F086BDC4EBC404013D4FEAD404EED135 +:1072A00070BD00BFC09B00087064002050640020C7 +:1072B0000421FFF73DBF00004843FFF7C1BF0000B6 +:1072C00008B101F0F3BD7047B0F5805F10B504461A +:1072D00007D8FFF7EDFF28B92046BDE81040FFF7BB +:1072E000AFBF002010BD0000FFF7EABF70B5AAB124 +:1072F00040EA010313F01F030FD1094C0144A568B4 +:107300006D0706D52568A84203D366683544A942AF +:1073100004D903330C34122BF1D10022104670BD76 +:10732000C09B000808B501F0D7FE034AD2E900323D +:10733000C01842EB010108BD30650020434BD3E982 +:1073400000232DE9F34113437CD0FFF7EBFF404AC4 +:1073500000230027F9F770F806460D463D4A002342 +:10736000F9F76AF80023144630462946394AF9F7F6 +:1073700063F84FF461613C23ADF80170B4FBF1F5A3 +:10738000B4FBF3F601FB154103FB16464624B1FBA3 +:10739000F3F1314BF6B28DF8004098423CD84FF0F3 +:1073A000640C4FF4C87EA30704F26C7225D1B2FBC3 +:1073B000FCF30CFB132313BBB2FBFEF30EFB1322F7 +:1073C000B2FA82F35B0903F26D18621C8045D2B2F7 +:1073D00017D90FB18DF800400022204C4FF00C0C53 +:1073E00017460CFB0343D4B2013213F804C08445A2 +:1073F0000CD8A0EB0C000127F5E70023E3E70123FD +:10740000E1E7A0EB080014460127CCE70FB18DF8A7 +:107410000140431C8DF802309DF80100431C9DF88B +:1074200000005038400640EA43509DF8023040EAE0 +:10743000034040EA560040EAC52040EA411002B04D +:10744000BDE8F0814FF40410F9E700BF306500207B +:1074500040420F008051010090230B00089C00085F +:107460000244074BD2B210B5904200D110BD441C6B +:1074700000B253F8200041F8040BE0B2F4E700BF7B +:10748000504000580E4B30B51C6F240405D41C6FBF +:107490001C671C6F44F400441C670A4C02442368B8 +:1074A000D2B243F480732360074B904200D130BDC9 +:1074B000441C51F8045B00B243F82050E0B2F4E7FA +:1074C00000440258004802585040005807B50122B5 +:1074D00001A90020FFF7C4FF019803B05DF804FB89 +:1074E00013B50446FFF7F2FFA04205D0012201A91F +:1074F00000200194FFF7C6FF02B010BD10B5642450 +:10750000013C4FF47A70FFF7B1F814F0FF04F7D1A3 +:10751000084B4FF0807214249A6103F580530822BF +:107520009A61013C4FF47A70FFF7A0F814F0FF0461 +:10753000F7D110BD000002580144BFF34F8F064B36 +:10754000884204D3BFF34F8FBFF36F8F7047C3F8E8 +:107550005C022030F4E700BF00ED00E00144BFF31F +:107560004F8F064B884204D3BFF34F8FBFF36F8F0B +:107570007047C3F870022030F4E700BF00ED00E070 +:1075800070B5054616460C4601201021FFF794FE03 +:10759000286046733CB1204636B1FFF789FE2B6860 +:1075A000186000B19C6070BDFFF74EFEF7E7000069 +:1075B000F8B50F461546044648B905F11F010126E6 +:1075C000386821F01F01FFF7B7FF3046F8BD427B56 +:1075D00029463868FFF78AFE06460028EDD13B6849 +:1075E0006360A368AB4210D213B12068FFF768FE56 +:1075F000637B28462BB1FFF75BFE206020B9A060BB +:10760000E3E7FFF721FEF8E7A560206805F11F0119 +:10761000012621F01F013860FFF78EFF2673D4E7A3 +:1076200010B5044640B10068884205D1606808B1D1 +:10763000FAF75CFB0023237310BD0000F8B50F467A +:107640001446054648B904F11F010126386821F0A7 +:107650001F01FFF783FF3046F8BD427B21463868A3 +:10766000FFF744FE06460028EDD1AB68A34210D2D6 +:1076700013B12868FFF724FE6B7B20462BB1FFF780 +:1076800017FE286020B9A860E5E7FFF7DDFDF8E701 +:10769000AC60396819B122462868FAF727FB2868D8 +:1076A00004F11F01012621F01F013860FFF756FF8A +:1076B0002E73D0E720B103688B4204BF002303730D +:1076C00070470000034B1A681AB9034AD2F8D02455 +:1076D0001A607047386500200040025808B5FFF76F +:1076E000F1FF024B1868C0F3806008BD38650020C8 +:1076F000EFF30983054968334A6B22F001024A63BC +:1077000083F30988002383F31188704700EF00E0BA +:10771000302080F3118862B60D4B0E4AD96821F4EF +:10772000E0610904090C0A430B49DA60D3F8FC2034 +:1077300042F08072C3F8FC20084AC2F8B01F1168FA +:1077400041F0010111602022DA7783F822007047AE +:1077500000ED00E00003FA0555CEACC5001000E0D6 +:10776000302310B583F311880E4B5B6813F400636C +:1077700014D0F1EE103AEFF309844FF08073683CB7 +:10778000E361094BDB6B236684F30988FEF7B8FEDF +:1077900010B1064BA36110BD054BFBE783F31188C5 +:1077A000F9E700BF00ED00E000EF00E02F04000863 +:1077B0003204000870B5BFF34F8FBFF36F8F1A4AC2 +:1077C0000021C2F85012BFF34F8FBFF36F8F536980 +:1077D00043F400335361BFF34F8FBFF36F8FC2F891 +:1077E0008410BFF34F8FD2F8803043F6E074C3F3B8 +:1077F000C900C3F34E335B0103EA0406014646EABF +:1078000081750139C2F86052F9D2203B13F1200F83 +:10781000F2D1BFF34F8F536943F480335361BFF309 +:107820004F8FBFF36F8F70BD00ED00E0FEE70000EB +:10783000214B2248224A70B5904237D3214BC11EBA +:10784000DA1C121A22F003028B4238BF00220021F8 +:10785000FAF772FA1C4A0023C2F88430BFF34F8F44 +:10786000D2F8803043F6E074C3F3C900C3F34E335B +:107870005B0103EA0406014646EA81750139C2F854 +:107880006C52F9D2203B13F1200FF2D1BFF34F8F8E +:10789000BFF36F8FBFF34F8FBFF36F8F0023C2F81B +:1078A0005032BFF34F8FBFF36F8F70BD53F8041B7F +:1078B00040F8041BC0E700BF0C9D0008346700209F +:1078C000346700203467002000ED00E0074BD3F858 +:1078D000D81021EA0001C3F8D810D3F8002122EA19 +:1078E0000002C3F80021D3F8003170470044025869 +:1078F00070B5D0E9244300224FF0FF359E6804EBB9 +:1079000042135101D3F80009002805DAD3F8000921 +:1079100040F08040C3F80009D3F8000B002805DAD6 +:10792000D3F8000B40F08040C3F8000B013263181D +:107930009642C3F80859C3F8085BE0D24FF0011330 +:10794000C4F81C3870BD0000890141F020010161BC +:1079500003699B06FCD41220FEF71CBE10B50A4C2E +:107960002046FEF7B7FA094BC4F89030084BC4F82C +:107970009430084C2046FEF7ADFA074BC4F890301F +:10798000064BC4F8943010BD3C6500200000084050 +:10799000449C0008D865002000000440509C00086A +:1079A00070B503780546012B5CD1434BD0F890406D +:1079B000984258D1414B0E216520D3F8D82042F08F +:1079C0000062C3F8D820D3F8002142F00062C3F867 +:1079D0000021D3F80021D3F8802042F00062C3F8E0 +:1079E0008020D3F8802022F00062C3F88020D3F8F2 +:1079F0008030FDF7B3FC324BE360324BC4F8003803 +:107A00000023D5F89060C4F8003EC02323604FF4F3 +:107A10000413A3633369002BFCDA01230C203361C8 +:107A2000FEF7B8FD3369DB07FCD41220FEF7B2FD88 +:107A30003369002BFCDA00262846A660FFF758FFC2 +:107A40006B68C4F81068DB68C4F81468C4F81C6874 +:107A500083BB1D4BA3614FF0FF336361A36843F009 +:107A60000103A36070BD194B9842C9D1134B4FF06D +:107A70008060D3F8D82042F00072C3F8D820D3F841 +:107A8000002142F00072C3F80021D3F80021D3F89E +:107A9000802042F00072C3F88020D3F8802022F0CA +:107AA0000072C3F88020D3F88030FFF70FFF0E215B +:107AB0004D209EE7064BCDE73C6500200044025870 +:107AC0004014004003002002003C30C0D865002074 +:107AD000083C30C0F8B5D0F89040054600214FF082 +:107AE00000662046FFF730FFD5F8941000234FF0D2 +:107AF00001128F684FF0FF30C4F83438C4F81C28E6 +:107B000004EB431201339F42C2F80069C2F8006BD4 +:107B1000C2F80809C2F8080BF2D20B68D5F8902019 +:107B2000C5F89830636210231361166916F01006C9 +:107B3000FBD11220FEF72EFDD4F8003823F4FE63AB +:107B4000C4F80038A36943F4402343F01003A36151 +:107B50000923C4F81038C4F814380B4BEB604FF00D +:107B6000C043C4F8103B094BC4F8003BC4F810698B +:107B7000C4F80039D5F8983003F1100243F48013AB +:107B8000C5F89820A362F8BD209C00084080001032 +:107B9000D0F8902090F88A10D2F8003823F4FE63D1 +:107BA00043EA0113C2F80038704700002DE9F8439A +:107BB00000EB8103D0F890500C468046DA680FFA4B +:107BC00081F94801166806F00306731E022B05EBC7 +:107BD00041134FF0000194BFB604384EC3F8101B98 +:107BE0004FF0010104F1100398BF06F1805601FA2D +:107BF00003F3916998BF06F5004600293AD0578AE9 +:107C000004F15801374349016F50D5F81C180B4354 +:107C10000021C5F81C382B180127C3F81019A740FC +:107C20005369611E9BB3138A928B9B08012A88BFFC +:107C30005343D8F89820981842EA034301F14002D0 +:107C40002146C8F89800284605EB82025360FFF7EA +:107C50007BFE08EB8900C3681B8A43EA84534834DF +:107C60001E4364012E51D5F81C381F43C5F81C78FB +:107C7000BDE8F88305EB4917D7F8001B21F4004154 +:107C8000C7F8001BD5F81C1821EA0303C0E704F16C +:107C90003F030B4A2846214605EB83035A60FFF752 +:107CA00053FE05EB4910D0F8003923F40043C0F827 +:107CB0000039D5F81C3823EA0707D7E70080001001 +:107CC00000040002D0F894201268C0F89820FFF752 +:107CD0000FBE00005831D0F8903049015B5813F4C2 +:107CE000004004D013F4001F0CBF02200120704795 +:107CF0004831D0F8903049015B5813F4004004D06B +:107D000013F4001F0CBF02200120704700EB81011B +:107D1000CB68196A0B6813604B68536070470000AA +:107D200000EB810330B5DD68AA691368D36019B927 +:107D3000402B84BF402313606B8A1468D0F89020D6 +:107D40001C4402EB4110013C09B2B4FBF3F4634361 +:107D5000033323F0030343EAC44343F0C043C0F8B2 +:107D6000103B2B6803F00303012B0ED1D2F8083827 +:107D700002EB411013F4807FD0F8003B14BF43F0B6 +:107D8000805343F00053C0F8003B02EB4112D2F89D +:107D9000003B43F00443C2F8003B30BD2DE9F04105 +:107DA000D0F8906005460C4606EB4113D3F8087BEB +:107DB0003A07C3F8087B08D5D6F814381B0704D552 +:107DC00000EB8103DB685B689847FA071FD5D6F89C +:107DD0001438DB071BD505EB8403D968CCB98B6954 +:107DE000488A5A68B2FBF0F600FB16228AB9186876 +:107DF000DA6890420DD2121AC3E90024302383F3CB +:107E0000118821462846FFF78BFF84F31188BDE8CF +:107E1000F081012303FA04F26B8923EA02036B81E8 +:107E2000CB68002BF3D021462846BDE8F041184727 +:107E300000EB81034A0170B5DD68D0F890306C69C1 +:107E40002668E66056BB1A444FF40020C2F81009B9 +:107E50002A6802F00302012A0AB20ED1D3F80808F8 +:107E600003EB421410F4807FD4F8000914BF40F0F3 +:107E7000805040F00050C4F8000903EB4212D2F8E1 +:107E8000000940F00440C2F800090122D3F8340888 +:107E900002FA01F10143C3F8341870BD19B9402E3C +:107EA00084BF4020206020681A442E8A8419013C37 +:107EB000B4FBF6F440EAC44040F00050C6E70000CE +:107EC0002DE9F843D0F8906005460C464F0106EBCB +:107ED0004113D3F8088918F0010FC3F808891CD0A2 +:107EE000D6F81038DB0718D500EB8103D3F80CC0A7 +:107EF000DCF81430D3F800E0DA68964530D2A2EB13 +:107F00000E024FF000091A60C3F80490302383F387 +:107F10001188FFF78DFF89F3118818F0800F1DD0AD +:107F2000D6F834380126A640334217D005EB840337 +:107F30000134D5F89050D3F80CC0E4B22F44DCF8EB +:107F4000142005EB0434D2F800E05168714514D3D5 +:107F5000D5F8343823EA0606C5F83468BDE8F88356 +:107F6000012303FA01F2038923EA02030381DCF807 +:107F70000830002BD1D09847CFE7AEEB0103BCF817 +:107F80001000834228BF0346D7F8180980B2B3EB2C +:107F9000800FE3D89068A0F1040959F8048FC4F861 +:107FA0000080A0EB09089844B8F1040FF5D81844F4 +:107FB0000B4490605360C8E72DE9F84FD0F890501B +:107FC00004466E69AB691E4016F480586E6103D09A +:107FD000BDE8F84FFDF7EEBF002E12DAD5F8003EEF +:107FE0009B0705D0D5F8003E23F00303C5F8003EFB +:107FF000D5F80438204623F00103C5F80438FEF70D +:1080000007F8370505D52046FFF772FC2046FDF737 +:10801000EDFFB0040CD5D5F8083813F0060FEB6867 +:1080200023F470530CBF43F4105343F4A053EB609C +:1080300031071BD56368DB681BB9AB6923F0080304 +:10804000AB612378052B0CD1D5F8003E9A0705D0FB +:10805000D5F8003E23F00303C5F8003E2046FDF7A7 +:10806000D7FF6368DB680BB120469847F30200F145 +:10807000BA80B70226D5D4F8909000274FF0010AB5 +:1080800009EB4712D2F8003B03F44023B3F5802FED +:1080900011D1D2F8003B002B0DDA62890AFA07F3FE +:1080A00022EA0303638104EB8703DB68DB6813B117 +:1080B0003946204698470137D4F89430FFB29B6880 +:1080C0009F42DDD9F00619D5D4F89000026AC2F3B8 +:1080D0000A1702F00F0302F4F012B2F5802F00F03D +:1080E000CA80B2F5402F09D104EB8303002200F5CA +:1080F0008050DB681B6A974240F0B0803003D5F8AF +:10810000185835D5E90303D500212046FFF746FE70 +:10811000AA0303D501212046FFF740FE6B0303D5D8 +:1081200002212046FFF73AFE2F0303D50321204604 +:10813000FFF734FEE80203D504212046FFF72EFEA8 +:10814000A90203D505212046FFF728FE6A0203D5C0 +:1081500006212046FFF722FE2B0203D507212046E9 +:10816000FFF71CFEEF0103D508212046FFF716FE9E +:10817000700340F1A780E90703D500212046FFF7EF +:108180009FFEAA0703D501212046FFF799FE6B0742 +:1081900003D502212046FFF793FE2F0703D50321C5 +:1081A0002046FFF78DFEEE0603D504212046FFF79B +:1081B00087FEA80603D505212046FFF781FE690644 +:1081C00003D506212046FFF77BFE2A0603D50721AB +:1081D0002046FFF775FEEB0574D520460821BDE863 +:1081E000F84FFFF76DBED4F890904FF0000B4FF0B2 +:1081F000010AD4F894305FFA8BF79B689F423FF6F0 +:1082000038AF09EB4713D3F8002902F44022B2F546 +:10821000802F20D1D3F80029002A1CDAD3F80029B6 +:1082200042F09042C3F80029D3F80029002AFBDB72 +:108230003946D4F89000FFF787FB22890AFA07F342 +:1082400022EA0303238104EB8703DB689B6813B1F5 +:108250003946204698470BF1010BCAE7910701D137 +:10826000D0F80080072A02F101029CBF03F8018BBD +:108270004FEA18283FE704EB830300F58050DA68E3 +:10828000D2F818C0DCF80820DCE9001CA1EB0C0CCB +:1082900000218F4208D1DB689B699A683A449A6052 +:1082A0005A683A445A6029E711F0030F01D1D0F817 +:1082B00000808C4501F1010184BF02F8018B4FEA77 +:1082C0001828E6E7BDE8F88F08B50348FFF774FE05 +:1082D000BDE80840FFF744BA3C65002008B50348F4 +:1082E000FFF76AFEBDE80840FFF73ABAD8650020FC +:1082F000D0F8903003EB4111D1F8003B43F4001368 +:10830000C1F8003B70470000D0F8903003EB4111FA +:10831000D1F8003943F40013C1F800397047000068 +:10832000D0F8903003EB4111D1F8003B23F4001357 +:10833000C1F8003B70470000D0F8903003EB4111CA +:10834000D1F8003923F40013C1F800397047000058 +:10835000064BD3F8DC200243C3F8DC20D3F8042119 +:108360001043C3F80401D3F80431704700440258A5 +:1083700008B53C4B4FF0FF31D3F8802062F000424B +:10838000C3F88020D3F8802002F00042C3F8802098 +:10839000D3F88020D3F88420C3F88410D3F8842045 +:1083A0000022C3F88420D3F88400D86F40F0FF4047 +:1083B00040F4FF0040F4DF4040F07F00D867D86F02 +:1083C00020F0FF4020F4FF0020F4DF4020F07F0089 +:1083D000D867D86FD3F888006FEA40506FEA5050E2 +:1083E000C3F88800D3F88800C0F30A00C3F88800F7 +:1083F000D3F88800D3F89000C3F89010D3F8900019 +:10840000C3F89020D3F89000D3F89400C3F89410E8 +:10841000D3F89400C3F89420D3F89400D3F89800CC +:10842000C3F89810D3F89800C3F89820D3F89800B0 +:10843000D3F88C00C3F88C10D3F88C00C3F88C20D0 +:10844000D3F88C00D3F89C00C3F89C10D3F89C1090 +:10845000C3F89C20D3F89C30FCF72EFABDE8084006 +:1084600000F0D6B90044025808B50122534BC3F8B6 +:108470000821534BD3F8F42042F00202C3F8F42051 +:10848000D3F81C2142F00202C3F81C210222D3F8C7 +:108490001C314C4BDA605A689104FCD54A4A1A6088 +:1084A00001229A60494ADA6000221A614FF4404280 +:1084B0009A61444B9A699204FCD51A6842F480721E +:1084C0001A603F4B1A6F12F4407F04D04FF4803291 +:1084D0001A6700221A671A6842F001021A60384BC4 +:1084E0001A685007FCD500221A611A6912F0380286 +:1084F000FBD1012119604FF0804159605A67344A1D +:10850000DA62344A1A611A6842F480321A602C4BDB +:108510001A689103FCD51A6842F480521A601A68EE +:108520009204FCD52C4A2D499A6200225A631963A1 +:1085300001F57C01DA6301F5E77199635A64284A11 +:108540001A64284ADA621A6842F0A8521A601C4B70 +:108550001A6802F02852B2F1285FF9D148229A61D4 +:108560004FF48862DA6140221A621F4ADA641F4AB5 +:108570001A651F4A5A651F4A9A6532231E4A1360BC +:10858000136803F00F03022BFAD10D4A136943F06D +:1085900003031361136903F03803182BFAD14FF06A +:1085A0000050FFF7D5FE4FF08040FFF7D1FE4FF0AF +:1085B0000040BDE80840FFF7CBBE00BF008000517F +:1085C000004402580048025800C000F002000001B8 +:1085D0000000FF010088900832206000630209015A +:1085E000470E0508DD0BBF01200000200000011030 +:1085F0000910E00000010110002000524FF0B042CD +:1086000008B5D2F8883003F00103C2F8883023B1EE +:10861000044A13680BB150689847BDE80840FFF75B +:108620009FB800BFB46600204FF0B04208B5D2F842 +:10863000883003F00203C2F8883023B1044A9368FB +:108640000BB1D0689847BDE80840FFF789B800BF74 +:10865000B46600204FF0B04208B5D2F8883003F07D +:108660000403C2F8883023B1044A13690BB150697E +:108670009847BDE80840FFF773B800BFB466002014 +:108680004FF0B04208B5D2F8883003F00803C2F8C2 +:10869000883023B1044A93690BB1D0699847BDE88B +:1086A0000840FFF75DB800BFB46600204FF0B0424D +:1086B00008B5D2F8883003F01003C2F8883023B12F +:1086C000044A136A0BB1506A9847BDE80840FFF7A7 +:1086D00047B800BFB46600204FF0B04310B5D3F8E0 +:1086E000884004F47872C3F88820A30604D5124A9F +:1086F000936A0BB1D06A9847600604D50E4A136B93 +:108700000BB1506B9847210604D50B4A936B0BB104 +:10871000D06B9847E20504D5074A136C0BB1506C37 +:108720009847A30504D5044A936C0BB1D06C9847C5 +:10873000BDE81040FFF714B8B46600204FF0B04316 +:1087400010B5D3F8884004F47C42C3F88820620551 +:1087500004D5164A136D0BB1506D9847230504D507 +:10876000124A936D0BB1D06D9847E00404D50F4ABF +:10877000136E0BB1506E9847A10404D50B4A936E4B +:108780000BB1D06E9847620404D5084A136F0BB141 +:10879000506F9847230404D5044A936F0BB1D06FF0 +:1087A0009847BDE81040FEF7DBBF00BFB46600206D +:1087B00008B50348FCF748FCBDE80840FEF7D0BF09 +:1087C000C836002008B50348FCF742FDBDE8084064 +:1087D000FEF7C6BF2039002008B50348FCF738FD76 +:1087E000BDE80840FEF7BCBF8C39002008B503483F +:1087F000FCF72EFDBDE80840FEF7B2BFF8390020B7 +:1088000008B500F0BDFCBDE80840FEF7A9BF0000B8 +:10881000062108B50846FCF7A1FD06210720FCF754 +:108820009DFD06210820FCF799FD06210920FCF793 +:1088300095FD06210A20FCF791FD06211720FCF783 +:108840008DFD06212820FCF789FD09217A20FCF7FF +:1088500085FD09213120FCF781FD07213220FCF73D +:108860007DFD0C212620FCF779FD0C212720FCF74B +:1088700075FD0C215220BDE80840FCF76FBD0000DB +:1088800008B5FFF775FD00F043FCFDF747F9FDF76C +:10889000E5F8FDF71DFBFDF7EFF9FEF7B1F9BDE8CF +:1088A000084000F029BA000030B50433039C01727F +:1088B000002104FB0325C160C0E90653049B036348 +:1088C000059BC0E90000C0E90422C0E90842C0E9F4 +:1088D0000A11436330BD00000022416AC260C0E952 +:1088E0000411C0E90A226FF00101FDF7FFBE00008C +:1088F000D0E90432934201D1C2680AB9181D704709 +:1089000000207047036919600021C2680132C2600B +:10891000C269134482699342036124BF436A0361BD +:10892000FDF7D8BE38B504460D46E3683BB1626931 +:108930000020131D1268A3621344E36207E0237A48 +:1089400033B929462046FDF7B5FE0028EDDA38BDDB +:108950006FF00100FBE70000C368C269013BC36020 +:108960004369134482699342436124BF436A43616C +:1089700000238362036B03B11847704770B530233F +:10898000044683F31188866A3EB9FFF7CBFF05469C +:1089900018B186F31188284670BDA36AE26A13F8FD +:1089A000015B9342A36202D32046FFF7D5FF002369 +:1089B00083F31188EFE700002DE9F84F04460E46D7 +:1089C000174698464FF0300989F311880025AA46CA +:1089D000D4F828B0BBF1000F09D141462046FFF77B +:1089E000A1FF20B18BF311882846BDE8F88FD4E9A8 +:1089F0000A12A7EB050B521A934528BF9346BBF109 +:108A0000400F1BD9334601F1400251F8040B91424B +:108A100043F8040BF9D1A36A403640354033A362D2 +:108A2000D4E90A239A4202D32046FFF795FF8AF33E +:108A30001188BD42D8D289F31188C9E730465A4619 +:108A4000F9F754F9A36A5E445D445B44A362E7E727 +:108A500010B5029C0433017203FB0421C460C0E919 +:108A600006130023C0E90A33039B0363049BC0E998 +:108A70000000C0E90422C0E90842436310BD0000C1 +:108A8000026A6FF00101C260426AC0E9042200225A +:108A9000C0E90A22FDF72ABED0E904239A4201D197 +:108AA000C26822B9184650F8043B0B607047002397 +:108AB0001846FAE7C3680021C2690133C3604369FD +:108AC000134482699342436124BF436A4361FDF7C3 +:108AD00001BE000038B504460D46E3683BB123698A +:108AE00000201A1DA262E2691344E36207E0237AC0 +:108AF00033B929462046FDF7DDFD0028EDDA38BD03 +:108B00006FF00100FBE7000003691960C268013AD9 +:108B1000C260C269134482699342036124BF436AFD +:108B2000036100238362036B03B1184770470000A1 +:108B300070B530230D460446114683F31188866ACA +:108B40002EB9FFF7C7FF10B186F3118870BDA36A75 +:108B50001D70A36AE26A01339342A36204D3E16900 +:108B600020460439FFF7D0FF002080F31188EDE79D +:108B70002DE9F84F04460D46904699464FF0300ACD +:108B80008AF311880026B346A76A4FB949462046A2 +:108B9000FFF7A0FF20B187F311883046BDE8F88FBA +:108BA000D4E90A073A1AA8EB0607974228BF1746E6 +:108BB000402F1BD905F1400355F8042B9D4240F886 +:108BC000042BF9D1A36A40364033A362D4E90A23C7 +:108BD0009A4204D3E16920460439FFF795FF8BF3ED +:108BE00011884645D9D28AF31188CDE729463A46FD +:108BF000F9F77CF8A36A3D443E443B44A362E5E7B1 +:108C0000D0E904239A4217D1C3689BB1836A8BB120 +:108C1000043B9B1A0ED01360C368013BC360C36959 +:108C20001A4483699A42026124BF436A03610023A4 +:108C300083620123184670470023FBE701F01F03FE +:108C4000F0B502F01F0456095A1C0123B6EB511F60 +:108C500050F8265003FA02F34FEA511703F1FF339D +:108C60003DBF50F82720C4F12000134003EA05005F +:108C70003BBF03FA00F225FA04F0E0401043F0BDD8 +:108C800070B57E227F210546FFF7D8FF18B1012875 +:108C900019D0002070BD3E2249212846FFF7CEFFA3 +:108CA0002F22044631212846FFF7C8FF064601342B +:108CB0005022023653212846B440FFF7BFFF09383F +:108CC00004FA00F0E6E7302245212846FFF7B6FF18 +:108CD00001308002DEE7000090F8D63090F8D7200F +:108CE0001B0403EB026390F8D42090F8D5001344E2 +:108CF00003EB00207047000000F018BA014B586ADF +:108D0000704700BF000C0040034B002258631A61FB +:108D10000222DA60704700BF000C0040014B0022C5 +:108D2000DA607047000C0040014B5863704700BF89 +:108D3000000C0040024B034A1A60034A5A60704715 +:108D40008C6600203867002000000220074B494253 +:108D500010B55C68201A08401968821A8A4203D349 +:108D6000A24201D85A6010BD0020FCE78C660020AA +:108D700008B5302383F31188FFF7E8FF002383F35E +:108D8000118808BD0448054B03600023C0E9013386 +:108D90000C3000F017B900BF94660020718D0008F8 +:108DA000CB1D083A23F00703591A521A10B4D208FF +:108DB0000024C0E9004384600C301C605A605DF8F8 +:108DC000044B00F0FFB800002DE9F74F364FCD1DE2 +:108DD0008846002818BF0746082A4FEAD50538BF3D +:108DE000082207F10C003C1D9146019000F02CF97F +:108DF000019809F10701C9F1000E2246246864B9FF +:108E000000F02CF93B68CBB308224946E8009847AC +:108E1000044698B340E9027830E004EB010CD4F842 +:108E200004A00CEA0E0C0AF10106ACF1080304EBF5 +:108E3000C6069E42E1D9A6EB0C0CB5EBEC0F4FEA4F +:108E4000EC0BDAD89C421DD204F10802AB45A3EB2F +:108E500002024FEAE202626009D9691CED4303EBAA +:108E6000C1025D445560256843F8315022601C46BC +:108E7000C3F8048044F8087B00F0F0F8204603B003 +:108E8000BDE8F08FAA45216802D111602346EEE7C4 +:108E9000013504EBC50344F8351003F10801761AD7 +:108EA000F6105E601360F1E79466002073B5044627 +:108EB000A0F1080550F8080C54F8043C061D0C30CD +:108EC00007330190DB0844F8043C00F0BDF833465A +:108ED00001989E421A6801D0AB4228D20AB195424D +:108EE00025D244F8082C54F8042C1D60013254F8A3 +:108EF000081C05EBC206B14206D14E68324444F864 +:108F0000042C0A6844F8082C5E68711C03EBC1014C +:108F10008D4207D154F8042C013232445A6054F87F +:108F2000082C1A6002B0BDE8704000F097B81346F4 +:108F3000CFE70000FEE7000070B51E4B0025044699 +:108F400086B058600E4605638163FEF7E1FB04F1CD +:108F50002803A5606563C4E90A3304F11003C4E97A +:108F600004334FF0FF33C4E90044C4E90635FFF78A +:108F7000C5FE2B46024604F13C012046C4E9082305 +:108F800080230D4A6567FDF70FFB7368E0600B4AAD +:108F900003620123009280F824306846F26801924F +:108FA0003269CDE90223064BCDE90435FDF730FBEC +:108FB00006B070BD10490020649C00085C9C00084D +:108FC000358F00080023C0E900008360036170470B +:108FD00070B51C4B05468468DE685CB3B44213D19F +:108FE00003690133036170BDA36094F8243083B139 +:108FF000062B15D1A06A2146D4E9003213605A60CD +:10900000FDF73EFAA36A9C68B368A2689A42EBD364 +:1090100006E0D4E90032204613605A60FDF740FABA +:1090200028463146FDF72CFAB5620620BDE87040AF +:10903000FDF738BA0369866001330361336BC3609F +:109040003063D0E76846002008B5302383F31188E9 +:10905000FFF7BEFF002383F3118808BD194BD968C1 +:1090600083688B4210B520D1302383F311880269C5 +:10907000013A0261B2B90468C368A0420B631ED012 +:109080004A6B9BB901238A60036103681A68026016 +:1090900050601A6B8360C26018631846FDF700FACF +:1090A000FDF750FA002383F3118810BD1C68A3421A +:1090B00003D0A468A24238BF2246DB68E1E78260A1 +:1090C000F0E700BF68460020024A536B1843506324 +:1090D000704700BF6846002038B5EFF311859DB991 +:1090E000EFF30584C4F30804302334B183F311880B +:1090F000FDF734FC85F3118838BD83F31188FDF743 +:109100002DFC84F3118838BDBDE83840FDF726BC3E +:109110000023054A19460133102BC2E9001102F160 +:109120000802F8D1704700BFB4660020114BD3F895 +:10913000E82042F00802C3F8E820D3F8102142F0FA +:109140000802C3F810210C4AD3F81031D36B43F056 +:109150000803D363C722094B9A624FF0FF32DA62E9 +:1091600000229A615A63DA605A6001225A611A60D9 +:10917000704700BF004402580010005C000C004023 +:10918000094A08B51169D3680B40D9B29B076FEA49 +:109190000101116107D5302383F31188FDF7F8F938 +:1091A000002383F3118808BD000C004010B501397D +:1091B0000244904201D1002005E0037811F8014FEC +:1091C000A34201D0181B10BD0130F2E7884210B550 +:1091D00001EB020402D98442234607D8431EA14270 +:1091E00008D011F8012B03F8012FF8E702440146DB +:1091F0008A4200D110BD13F8014D02F8014DF7E786 +:10920000C9B2034610F8012B1AB18A42F9D11846A7 +:109210007047002918BF0023F9E70000034611F842 +:10922000012B03F8012B002AF9D1704710B5013941 +:10923000034632B111F8014F03F8014B013A002CFB +:10924000F7D11A440021934200D110BD03F8011B4D +:10925000F9E700004D4435002D2D0A002F6172649E +:109260007570696C6F742E6162696E002F61726433 +:109270007570696C6F742D7665726966792E61629E +:10928000696E002F6172647570696C6F742D666C05 +:109290006173682E6162696E002F61726475706916 +:1092A0006C6F742D666C61736865642E6162696EA3 +:1092B000000000000000000000000000050F000892 +:1092C000A10F000851110008D90F0008990F0008DC +:1092D0000000000000000000010F0008AD0F0008B2 +:1092E00089110008FD0E0008090F000853544D3382 +:1092F0003248373F3F3F0053544D3332483733787D +:109300002F3732780053544D3332483734332F37A8 +:1093100035332F373530000001105A000310590043 +:1093200001205800032056002F000000537563638E +:1093300065737366756C6C79206D6F756E7465649A +:10934000205344436172642028736C6F77646F7795 +:109350006E3D2575290A0000EB769045584641542C +:1093600020202000464154333220202000000000FD +:109370002A3A3C3E7C223F7F002B2C3B3D5B5D002C +:10938000435545414141414345454549494941418D +:109390004592924F4F4F5555594F554F9C4F9E9F59 +:1093A00041494F55A5A5A6A7A8A9AAABACADAEAF9C +:1093B000B0B1B2B3B4414141B8B9BABBBCBDBEBF94 +:1093C000C0C1C2C3C4C54141C8C9CACBCCCDCECF30 +:1093D000D1D145454549494949D9DADBDCDD49DF89 +:1093E0004FE14F4F4F4FE6E8E85555555959EEEFCD +:1093F000F0F1F2F3F4F5F6F7F8F9FAFBFCFDFEFFF5 +:1094000001030507090E10121416181C1E00000097 +:1094100061001A03E0001703F8000703FF000100D2 +:1094200078010001300132010601390110014A01C1 +:109430002E017901060180014D0043028101820164 +:1094400082018401840186018701870189018A01E3 +:109450008B018B018D018E018F0190019101910192 +:1094600093019401F60196019701980198013D023C +:109470009B019C019D0120029F01A001A001A2016E +:10948000A201A401A401A601A701A701A901AA01A3 +:10949000AB01AC01AC01AE01AF01AF01B101B20152 +:1094A000B301B301B501B501B701B801B801BA0103 +:1094B000BB01BC01BC01BE01F701C001C101C20179 +:1094C000C301C401C501C401C701C801C701CA0164 +:1094D000CB01CA01CD011001DD0101008E01DE01C9 +:1094E0001201F3010300F101F401F401F801280174 +:1094F000220212013A020900652C3B023B023D02A6 +:10950000662C3F0240024102410246020A01530218 +:10951000400081018601550289018A0158028F01AC +:109520005A0290015C025D025E025F0293016102D9 +:109530006202940164026502660267029701960165 +:109540006A02622C6C026D026E029C017002710252 +:109550009D01730274029F017602770278027902FC +:109560007A027B027C02642C7E027F02A6018102C9 +:109570008202A9018402850286028702AE014402AA +:10958000B101B20145028D028E028F02900291025A +:10959000B7017B030300FD03FE03FF03AC030400DC +:1095A0008603880389038A03B1031103C2030200FF +:1095B000A303A303C4030803CC0303008C038E039B +:1095C0008F03D8031801F2030A00F903F303F4032D +:1095D000F503F603F703F703F903FA03FA0330047C +:1095E000200350041007600422018A043601C104DC +:1095F0000E01CF040100C004D0044401610526041B +:10960000000000007D1D0100632C001E9601A01EBD +:109610005A01001F0806101F0606201F0806301FEB +:109620000806401F0606511F0700591F521F5B1FE7 +:10963000541F5D1F561F5F1F601F0806701F0E001E +:10964000BA1FBB1FC81FC91FCA1FCB1FDA1FDB1FD2 +:10965000F81FF91FEA1FEB1FFA1FFB1F801F0806E8 +:10966000901F0806A01F0806B01F0400B81FB91FEE +:10967000B21FBC1FCC1F0100C31FD01F0206E01F7A +:109680000206E51F0100EC1FF31F0100FC1F4E2125 +:109690000100322170211002842101008321D02495 +:1096A0001A05302C2F04602C0201672C0601752C42 +:1096B0000201802C6401002D260841FF1A030000DE +:1096C000C700FC00E900E200E400E000E500E7007C +:1096D000EA00EB00E800EF00EE00EC00C400C5007B +:1096E000C900E600C600F400F600F200FB00F90035 +:1096F000FF00D600DC00F800A300D800D7009201DC +:10970000E100ED00F300FA00F100D100AA00BA0078 +:10971000BF00AE00AC00BD00BC00A100AB00BB00B0 +:1097200091259225932502252425C100C200C00061 +:10973000A9006325512557255D25A200A500102508 +:10974000142534252C251C2500253C25E300C300C9 +:109750005A25542569256625602550256C25A400C9 +:10976000F000D000CA00CB00C8003101CD00CE000F +:10977000CF0018250C2588258425A600CC0080253F +:10978000D300DF00D400D200F500D500B500FE0004 +:10979000DE00DA00DB00D900FD00DD00AF00B40020 +:1097A000AD00B1001720BE00B600A700F700B8005A +:1097B000B000A800B700B900B300B200A025A00017 +:1097C00010000240080002400008024000000B00A8 +:1097D00028000240080002400408024006010C0074 +:1097E00040000240080002400808024010020D003C +:1097F00058000240080002400C08024016030E0008 +:10980000700002400C0002401008024000040F00EB +:10981000880002400C0002401408024006051000B7 +:10982000A00002400C00024018080240100611007F +:10983000B80002400C0002401C08024016072F002E +:1098400010040240080402402008024000083800CA +:109850002804024008040240240802400609390096 +:10986000400402400804024028080240100A3A005E +:1098700058040240080402402C080240160B3B002A +:10988000700402400C04024030080240000C3C000E +:10989000880402400C04024034080240060D4400D3 +:1098A000A00402400C04024038080240100E45009B +:1098B000B80402400C0402403C080240160F460067 +:1098C0000100000000000000009600000000000001 +:1098D0000000000000000000000000000000000088 +:1098E00000000000F96B0008FD6B0008F15600084D +:1098F000295A000885560008AD560008D5560008BC +:109900006D56000800000000DD5A0008C95A000822 +:10991000055B0008F15A0008FD5A0008E95A0008E2 +:10992000D55A0008C15A0008115B00080000000069 +:10993000F55B0008E15B00081D5C0008095C00089D +:10994000155C0008015C0008ED5B0008D95B0008AD +:10995000295C000800000000010000000000000079 +:109960006330000060990008000000000000000063 +:10997000E0460020104900200000812A000000007D +:10998000AAAAAAAA00000024FFFE0000000000000E +:1099900000A00A000001000000000000AAAAAAAA74 +:1099A00000000000FFFF00000000000000000000B9 +:1099B0001400AA5600000000AAAAAAAA140055542E +:1099C000FFFF000000000000CCCC0C0020681A0053 +:1099D00000000000AAAA8AAA10541500FFFF000088 +:1099E000000C7007770000004081020100100000A9 +:1099F000AAAAAAAA00410100F7FF00000000007017 +:109A0000070000000000000000000000AAAAAAAAA7 +:109A100000000000FFFF0000000000000000000048 +:109A20000000000000000000AAAAAAAA000000008E +:109A3000FFFF000000000000000000000000000028 +:109A400000000000AAAAAAAA00000000FFFF000070 +:109A50000000000000000000000000000000000006 +:109A6000AAAAAAAA00000000FFFF00000000000050 +:109A7000000000000000000000000000AAAAAAAA3E +:109A800000000000FFFF00000000000000000000D8 +:109A90000000000000000000AAAAAAAA000000001E +:109AA000FFFF000000000000000000004375626539 +:109AB00050696C6F74004A6F65792D424C002553D4 +:109AC000455249414C250000020000000000000002 +:109AD000155E0008855E000840004000C06100205F +:109AE000D061002002000000000000000300000020 +:109AF00000000000CD5E0008000000001000000023 +:109B0000E0610020000000000100000000000000F3 +:109B10003C65002001010200F56C0008056C00089E +:109B2000A16C0008856C000843000000309B000811 +:109B300009024300020100C03209040000010202D0 +:109B40000100052400100105240100010424020283 +:109B50000524060001070582030800FF090401002F +:109B6000020A00000007050102400000070581020B +:109B700040000000120000007C9B00081201100150 +:109B800002000040AE2D5610000201020301000049 +:109B90000403090425424F41524425004375626580 +:109BA0004F72616E67652D6A6F65790030313233AF +:109BB00034353637383941424344454600000000C9 +:109BC0000000002000000200020000000000003041 +:109BD000000004000800000000000024000008004D +:109BE000040000000004000000FC0000020000006F +:109BF0000000043000800000080000000000003871 +:109C000000000100010000001F1C1F1E1F1E1F1F5F +:109C10001E1F1E1F1F1D1F1E1F1E1F1F1E1F1E1F5C +:109C20000000000029600008E16200088D63000860 +:109C300040004000746600207466002001000000AF +:109C40008466002080000000400100000800000041 +:109C500000010000001000000800000069646C654D +:109C6000000000006D61696E002C0438040438089F +:109C70000C10141C202425260000000000006404A1 +:109C80000100040000000000000C00102830340027 +:109C9000D867FF7F010000000904000000000000F9 +:109CA00000001E0000000000FF0000001849002016 +:109CB000203900208C390020F839002000000000F5 +:109CC000EC92000883040000F792000850040000A2 +:109CD000059300080100000000000000009600004D +:109CE00000000800960000000008000004000000CA +:109CF000909B000800000000000000000000000031 +:0C9D000000000000000000000000000057 :00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin index cd09e9be90ed95..89300109d8aa37 100755 Binary files a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin 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 index d7433019f9d1c4..09ea9eb33f359c 100644 --- a/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000070020F1020008A1330008593300085E -:10001000813300085933000879330008F3020008DF -:10002000F3020008F3020008F30200088543000809 +:1000000000070020F102000839340008F13300082D +:1000100019340008F133000811340008F302000815 +:10002000F3020008F3020008F30200082544000868 :10003000F3020008F3020008F3020008F3020008CC :10004000F3020008F3020008F3020008F3020008BC -:10005000F3020008F3020008017800082D78000878 -:100060005978000885780008B178000849440008EC -:10007000714400089D440008C9440008F544000884 -:100080001D45000849450008F3020008093300082F -:10009000313300081D33000845330008DD780008BF +:10005000F3020008F3020008DD7C0008097D0008B7 +:10006000357D0008617D00088D7D0008E9440008A9 +:10007000114500083D450008694500089545000800 +:10008000BD450008E9450008F3020008A133000857 +:10009000C9330008B5330008DD330008B97D000816 :1000A000F3020008F3020008F3020008F30200085C :1000B000F3020008F3020008F3020008F30200084C :1000C000F3020008F3020008F3020008F30200083C :1000D000F3020008F3020008F3020008F30200082C -:1000E00041790008F3020008F3020008F302000857 -:1000F000F3020008F3020008F30200087545000847 -:10010000F3020008F3020008C9790008F3020008AE +:1000E0001D7E0008F3020008F3020008F302000876 +:1000F000F3020008F3020008F302000815460008A6 +:10010000F3020008F3020008A57E0008F3020008CD :10011000F3020008F3020008F3020008F3020008EB -:10012000A1450008C9450008F5450008214600081A -:100130004D460008F3020008F3020008F30200082D +:10012000414600086946000895460008C146000897 +:10013000ED460008F3020008F3020008F30200088D :10014000F3020008F3020008F3020008F3020008BB -:1001500075460008A1460008CD460008F3020008D5 +:1001500015470008414700086D470008F3020008F2 :10016000F3020008F3020008F3020008F30200089B -:10017000F3020008816E0008F3020008F302000891 -:10018000F3020008F3020008B5790008F302000842 +:10017000F3020008E5700008F3020008F30200082B +:10018000F3020008F3020008917E0008F302000861 :10019000F3020008F3020008F3020008F30200086B :1001A000F3020008F3020008F3020008F30200085B :1001B000F3020008F3020008F3020008F30200084B :1001C000F3020008F3020008F3020008F30200083B -:1001D000F30200086D6E0008F3020008F302000845 +:1001D000F3020008D1700008F3020008F3020008DF :1001E000F3020008F3020008F3020008F30200081B :1001F000F3020008F3020008F3020008F30200080B :10020000F3020008F3020008F3020008F3020008FA @@ -52,49 +52,49 @@ :100320004F8FBFF36F8F40F20000C0F2F0004EF627 :100330008851CEF200010860BFF34F8FBFF36F8F7B :100340004FF00000E1EE100A4EF63C71CEF20001D3 -:100350000860062080F31488BFF36F8F05F0FCFF60 -:1003600007F00AF84FF055301F491B4A91423CBF35 +:100350000860062080F31488BFF36F8F06F02EF933 +:1003600007F076FA4FF055301F491B4A91423CBFC7 :1003700041F8040BFAE71D49184A91423CBF41F885 :10038000040BFAE71A491B4A1B4B9A423EBF51F82D :10039000040B42F8040BF8E700201849184A914270 -:1003A0003CBF41F8040BFAE706F014F807F068F8D0 +:1003A0003CBF41F8040BFAE706F046F907F0D4FA2F :1003B000144C154DAC4203DA54F8041B8847F9E796 :1003C00000F042F8114C124DAC4203DA54F8041B11 -:1003D0008847F9E705F0FCBF000700200023002054 +:1003D0008847F9E706F02EB9000700200023002027 :1003E0000000000808ED00E00001002000070020E8 -:1003F0009880000800230020D0230020D023002074 -:10040000C8880020E0020008E4020008E4020008B6 +:1003F00060850008002300206C230020702300206B +:1004000030890020E0020008E4020008E40200084D :10041000E40200082DE9F04F2DED108AC1F80CD050 :10042000D0F80CD0BDEC108ABDE8F08F002383F328 -:1004300011882846A047002005F070FAFEE705F075 -:10044000EFF900DFFEE70000F8B501F0E9F901F08F -:100450007FFB05F005FF074605F074FF0546A8BBC6 +:1004300011882846A047002005F0E4FAFEE705F001 +:100440005FFA00DFFEE70000F8B501F0E9F901F01E +:100450007FFB06F037F8074606F0A6F80546A8BB6E :100460001F4B9F4232D001339F4232D027F0FF0210 :100470001C4B9A4230D12E4642F21074F8B200F072 -:100480009BFF00F09FFF08B10024264601F0A8FD65 +:100480009BFF00F09FFF08B10024264601F0F0FD1D :1004900020B10024032000F079F8264635B1124B34 -:1004A0009F4203D0002405F045FF2646002005F0BA -:1004B000E1FE0EB100F080F801F0E8FA00F0B6FFBE +:1004A0009F4203D0002406F077F82646002006F08D +:1004B00013F80EB100F080F801F0E8FA00F0B6FF92 :1004C000204600F037F900F077F8F9E72E460024CF :1004D000D7E704460126D4E7064641F28834D0E740 :1004E000010007B0000008B0263A09B008B501F0D5 :1004F00063F9A0F120035842584108BD07B541F205 :100500001203022101A8ADF8043001F073F903B021 :100510005DF804FB38B5302383F31188174803686E -:100520000BB105F0C7FA0023154A4FF47A7113484E -:1005300005F0B6FA002383F31188124C236813B137 +:100520000BB105F03BFB0023154A4FF47A711348D9 +:1005300005F02AFB002383F31188124C236813B1C2 :100540002368013B2360636813B16368013B636008 :100550000D4D2B7833B963687BB9022001F008FA9E :10056000322363602B78032B07D163682BB90220F9 -:1005700001F0FEF94FF47A73636038BDD023002098 -:1005800015050008F0240020E8230020084B18700F +:1005700001F0FEF94FF47A73636038BD70230020F8 +:10058000150500089024002088230020084B1870CF :1005900003280CD8DFE800F008050208022001F06B :1005A000E5B9022001F0E0B9024B00225A60704721 -:1005B000E8230020F0240020F8B501F011FD30B14F +:1005B0008823002090240020F8B501F059FD30B1C7 :1005C000544B03221A700022534B5A60F8BD534B10 :1005D000534A1C4619680131F8D004339342F9D1CB :1005E0006268504B9A42F1D94F4B9B6803F100630C -:1005F00003F500339A42E9D205F070FE05F082FE61 +:1005F00003F500339A42E9D205F0A2FF05F0B4FFFB :10060000002001F027F90220FFF7C0FF474B00212F :10061000D3F8E820C3F8E810D3F81021C3F810117C :10062000D3F81021D3F8EC20C3F8EC10D3F8142140 @@ -112,13 +112,13 @@ :1006E000BFF36F8FBFF34F8FBFF36F8F536923F447 :1006F000003353610023C2F85032BFF34F8FBFF372 :100700006F8F302383F31188854680F30888204754 -:100710005CE700BFE8230020F0240020000002086E +:100710005CE700BF8823002090240020000002082E :1007200020000208FFFF01080023002000440258B7 :1007300000ED00E02DE9F04F93B0B74B2022FF21F0 :1007400000900AA89D6801F04BF9B44A1378A3B948 :100750000121B34811700360302383F311880368CB -:100760000BB105F0A7F90023AE4A4FF47A71AC48FB -:1007700005F096F9002383F31188009B13B1AA4B6F +:100760000BB105F01BFA0023AE4A4FF47A71AC4886 +:1007700005F00AFA002383F31188009B13B1AA4BFA :10078000009A1A60A94A1378032B03D00023137030 :10079000A54A53604FF0000A009CD3465646D14606 :1007A000012001F0E3F824B19F4B1B68002B00F0FF @@ -160,9 +160,9 @@ :1009E000926893423FF642AFB8F5807F3FF73EAF43 :1009F000124BB845019323DD4FF47A7000F0DCFE12 :100A00000390039A002AFFF631AF039A0137019B46 -:100A100003F8012BEDE700BF00230020EC240020A9 -:100A2000D023002015050008F0240020E823002032 -:100A300004230020082300200C230020EC230020A6 +:100A100003F8012BEDE700BF002300208C24002009 +:100A20007023002015050008902400208823002052 +:100A300004230020082300200C2300208C23002006 :100A4000C820FFF753FD074600283FF40FAF1F2DC6 :100A500011D8C5F120020AAB25F0030084494245B4 :100A6000184428BF4246019200F094FF019AFF21EA @@ -172,7 +172,7 @@ :100AA0003FF4E4AE00F010FF00283FF4DFAE002773 :100AB000B846704B9B68BB4218D91F2F11D80A9BB0 :100AC00001330ED027F0030312AA134453F8203C3D -:100AD00005934046042205A9043701F06BFA8046CD +:100AD00005934046042205A9043701F0B3FA804685 :100AE000E7E7384600F0B8FE0590F2E7CDF814804D :100AF000042105A800F07EFE02E70023642104A87B :100B0000049300F06DFE00287FF4B0AE0220FFF7E2 @@ -191,14 +191,14 @@ :100BD000FFF78CFC00283FF449AE00F075FE0028BA :100BE00044D00A9B01330BD008220AA9002000F050 :100BF000FFFE00283AD02022FF210AA800F0F0FED4 -:100C0000FFF77CFC1C4804F08FFE13B0BDE8F08FAA +:100C0000FFF77CFC1C4804F003FF13B0BDE8F08F35 :100C1000002E3FF42BAE0BF00B030B2B7FF426AE14 :100C20000023642105A8059300F0DAFD074600289B :100C30007FF41CAE0220FFF759FC804600283FF4E9 -:100C400015AEFFF75BFC41F2883004F06DFE0598AD +:100C400015AEFFF75BFC41F2883004F0E1FE059839 :100C500000F05CFF46463C4600F00EFFA0E506466D :100C60004EE64FF0000901E6BA467EE637467CE6DE -:100C7000EC23002000230020A0860100094A49F24D +:100C70008C23002000230020A0860100094A49F2AD :100C80006900136899B21B0C00FB013344F25061F8 :100C90001360054B186882B2000C01FB020018605B :100CA00080B270471423002010230020002110225E @@ -206,51 +206,51 @@ :100CC0001868A06010BD00BF00E8F11F2DE9F041D9 :100CD000ADF5527D0D46002140F2751270AC07460D :100CE00012A8119100F07CFE4FF4C472002120463E -:100CF00000F076FE0DF1440802F05AFB4FF47A72D0 +:100CF00000F076FE0DF1440802F0A6FB4FF47A7284 :100D0000264BB0FBF2F0186093E80700022384E85A :100D100007000DF5F1702382FFF7C8FF47F60503C2 -:100D20001F4907A8238406F0F3FE25230DF2F322C2 +:100D20001F4907A8238407F057F925230DF2F32262 :100D30000DF13C0C84F8323107AB1E46083203CE6D :100D4000664542F8080C42F8041C3346F5D1306879 -:100D500041461060204633791371012200F04EFFA6 +:100D500041461060204633791371012200F058FF9C :100D6000002380B2E97E0393AB7E029305F1190361 :100D700001930123009307A3D3E90023CDE9048065 -:100D8000384602F0D3FE0DF5527DBDE8F08100BF7C -:100D9000AFF300809E6AC421818A46EEF8240020C9 -:100DA000207B00082DE9F0412C4CDAB080460D463E -:100DB000237A5BBB27A9284601F02EF807460028B6 +:100D8000384602F01FFF0DF5527DBDE8F08100BF2F +:100D9000AFF300809E6AC421818A46EE9824002029 +:100DA000E87F00082DE9F0412C4CDAB080460D4672 +:100DB000237A5BBB27A9284601F04EF80746002896 :100DC00042D19DF89D60C82E3ED801464FF4A662E0 :100DD000204600F005FE4FF4807332460DF19E016F :100DE000C4F8F8314FF4007304F109002644C4F844 :100DF0000C334FF44073C4F8203400F0CBFD9DF861 :100E00009C30777223720BB9EB7E237206AC812281 :100E1000002127A800F0E4FD0122214627A801F0C7 -:100E200037F8002380B2E97E0393AB7E029305F18D +:100E200061F8002380B2E97E0393AB7E029305F163 :100E3000190301932823CDE904400093404605A3FC -:100E4000D3E9002302F072FE5AB0BDE8F08100BF82 -:100E5000AFF3008026417272DF25D7B7C05E002055 +:100E4000D3E9002302F0BEFE5AB0BDE8F08100BF36 +:100E5000AFF3008026417272DF25D7B7605E0020B5 :100E6000F0B5254E4FF48A75F1B0002405FB0065FE :100E700096F8D830D822214685F8DC303AA885F893 :100E8000E84006AF00F0ACFD06F1090000F0A0FD5F :100E9000D5F8E430C2B206F109018DF8F0000DF189 :100EA000F100CDE93A3400F075FD394601223AA847 -:100EB00001F01AF8082380B2317ACDE904700127D5 +:100EB00001F04EF8082380B2317ACDE904700127A1 :100EC0000E48CDE9023706F1D80301933023009391 -:100ED00007A3D3E9002302F029FEA04206DD02F0B9 -:100EE00067FAC5F8E000384671B0F0BD2046FBE770 -:100EF00078F6339F93CACD8DC05E00201035002058 +:100ED00007A3D3E9002302F075FEA04206DD02F06D +:100EE000B3FAC5F8E000384671B0F0BD2046FBE724 +:100EF00078F6339F93CACD8D605E0020B034002019 :100F00002DE9F04F264F87B0DFF8A080254E3846F8 -:100F100002F038FE034600283AD00024224DADF8F6 +:100F100002F084FE034600283AD00024224DADF8AA :100F20001440A1460294A246CDE90344027B8DF809 :100F3000142003AA9968406803C21B6843F0004369 -:100F400002932B6804F5A664D3F810B002F032FACD +:100F400002932B6804F5A664D3F810B002F07EFA81 :100F500010EB0802CDF800A0284605F5A65541F192 :100F6000000302A9D8470028C8BF49F00109B4F519 -:100F7000266FE6D1B9F1000F05D0384602F006FE23 +:100F7000266FE6D1B9F1000F05D0384602F052FED7 :100F800086F800A0C3E73378072B04D80133337009 -:100F900007B0BDE8F08F024802F0F8FDF8E700BFA7 -:100FA00010350020F56300204035002040420F003E -:100FB00070B50D4614461E4602F014FD50B9022EBF +:100F900007B0BDE8F08F024802F044FEF8E700BF5A +:100FA000B034002095630020E034002040420F0060 +:100FB00070B50D4614461E4602F060FD50B9022E73 :100FC00010D1012C0ED112A3D3E900230120C5E9D1 :100FD000002307E0282C10D005D8012C09D0052CBF :100FE0000FD0002070BD302CFBD10BA3D3E9002320 @@ -262,22 +262,22 @@ :10104000013500F02FFCA4F82C55B4F82C0500F065 :1010500011FC78B1B4F82C0500F01CFC014648B92D :10106000B4F82C0500F01EFCB4F82C350133A4F8BC -:101070002C35EAE738BD00BFC05E0020F8B50D4C46 +:101070002C35EAE738BD00BF605E0020F8B50D4CA6 :1010800002260D4FA4F5805343F8307C237E3BB9F4 -:1010900065692DB1284601F01DF8284606F0EEFCE2 -:1010A0002046A4F5A65401F015F8012E00D1F8BD94 -:1010B0000126E7E7305A0020E87B00082DE9F04FD1 -:1010C0008FB005460C4600AF02F08CFC002849D1D9 -:1010D000237E022B1BD1E38A012B18D102F068F981 +:1010900065692DB1284601F065F8284601F09EF9F2 +:1010A0002046A4F5A65401F05DF8012E00D1F8BD4C +:1010B0000126E7E7D0590020B08000082DE9F04F65 +:1010C0008FB005460C4600AF02F0D8FC002849D18D +:1010D000237E022B1BD1E38A012B18D102F0B4F935 :1010E0000646FFF7CBFD03464FF4C87006F51676AB :1010F000DFF8C082B3FBF0F202FB103316FA83F381 :10110000C8F80030E37E33B9A34B00221A703C3795 -:10111000BD46BDE8F08F07F12401204600F03AFEFD +:10111000BD46BDE8F08F07F12401204600F050FEE7 :101120000028F4D107F11400FFF7C0FD97F826401E -:1011300007F1140107F12700224606F0B7FC00284A +:1011300007F1140107F12700224606F01BFF0028E3 :10114000E2D10F2C08D8944B1C70D8F80030A3F5CE :101150001673C8F80030DAE797F82410284602F032 -:1011600039FCD4E7E38A282B2BD010D8012B23D0CD +:1011600085FCD4E7E38A282B2BD010D8012B23D081 :10117000052BCCD1BFF34F8F8849894BCA6802F445 :10118000E0621343CB60BFF34F8F00BFFDE7302B0E :10119000BDD1844EE17E327A9142B8D1607E314633 @@ -297,14 +297,14 @@ :101270007260D6F8D42005EB0209C6F8D49000F0CD :10128000F9FA814509D396F8D220D6F8D400013274 :10129000001B86F8D220C6F8D400FF2D0FD80024FA -:1012A000347200F011FB204600F0D4FA00F098FEF2 +:1012A000347200F011FB204600F0D4FA00F0E0FEAA :1012B0003D4B188108B9FFF77FF9C54627E7BB68A2 :1012C00096F8D9000AFB0362FB68D2F8E41082F8B2 :1012D000E83001F58061C2F8E030C2F8E410FFF7B1 :1012E000BFFDFFF70DFE96F8D920013202F0030290 :1012F00086F8D920B6E74FF48A7A20460AFB02F531 -:1013000005F1EA01314400F01BFEF86000287FF48B -:10131000FEAE0122354485F8E82002F049F8D5F800 +:1013000005F1EA01314400F057FEF86000287FF44F +:10131000FEAE0122354485F8E82002F095F8D5F8B4 :10132000E020D6ED007A801A40F6B832B8EE677A3F :10133000DFED1E6A192838BF1920904228BF1046D9 :1013400007EE900AF8EEE77A67EEA67ADFED186A04 @@ -312,27 +312,27 @@ :10136000BB60BA6873680AFB02F4321992F8E8109D :1013700059B1D2F8E410E8468B423FF427AF002180 :1013800082F8E810C2F8E010C5467368064A9B0A66 -:1013900001331381BBE600BF0935002000ED00E0FA -:1013A0000400FA05C05E0020F8240020CDCCCC3D1E -:1013B0006666663F0C350020014B1870704700BF11 -:1013C0000425002038B54FF00054144B22689A428F -:1013D00021D1627D0025124B12481A70C922237D4B -:1013E0000930114900F8013C4FF48073C0F8DB501C -:1013F000C0F8EF314FF40073C0F803334FF440737B -:10140000C0F8173400F0C6FAE0222946204600F062 -:10141000E7FA012038BD0020FCE700BF9AAD44C5C3 -:1014200004250020C05E00201600002037B500F023 -:10143000D7FD1F4C1F4D022301221F496B712368EA +:1013900001331381BBE600BFA934002000ED00E05B +:1013A0000400FA05605E002098240020CDCCCC3DDE +:1013B0006666663FAC340020014B1870704700BF72 +:1013C000A424002038B54FF00054144B22689A42F0 +:1013D00022D1607DF8B1124B0025C9221149187045 +:1013E0001148237D0930C0F8DB5000F8013C4FF470 +:1013F0008073C0F8EF314FF40073C0F803334FF43B +:101400004073C0F8173400F0C5FAE02229462046A0 +:1014100000F0E6FA012038BD0020FCE79AAD44C593 +:10142000A424002016000020605E002037B500F0E4 +:101430001FFE1F4C1F4D022301221F496B712368A1 :10144000288120465B68984704F5805301221A4999 :10145000D3F8C03404F5A6505B68984700231749B9 :101460004FF480520193164B16480093164B02F02E -:1014700089FA164B197811B1124802F0ABFA01F053 -:1014800097FF0446FFF7FAFB4FF4C873B0FBF3F283 +:10147000D5FA164B197811B1124802F0F7FA01F0BB +:10148000E3FF0446FFF7FAFB4FF4C873B0FBF3F237 :1014900002FB130304F5167010FA83F00C4B18606E -:1014A00004F050FF08B10F232B8103B030BD00BF03 -:1014B00040350020F824002040420F00082500207D -:1014C000B10F000810350020BD10000804250020D1 -:1014D0000C3500202DE9F04F00242DED028B93B048 +:1014A00005F082F808B10F232B8103B030BD00BFD7 +:1014B000E03400209824002040420F00A82400209F +:1014C000B10F0008B0340020BD100008A424002093 +:1014D000AC3400202DE9F04F00242DED028B93B0A9 :1014E0000DF12C084FF0010ADFF814B2FFF708FDE8 :1014F0000A94ADF834400B94C8F804409FED798B02 :1015000000267E4D37462B680DF11D0207A928469F @@ -341,63 +341,63 @@ :1015300000210EA800F054FA2B6808AA0AA95F69D6 :1015400028460DF11E03B8470FAB4F4698E803003D :1015500083E803009DF834300EA958468DF84430D6 -:101560000A9B0E93DDE9082302F0EEFC06F5A66661 +:101560000A9B0E93DDE9082302F03AFD06F5A66614 :1015700005F5A655B6F5266FC5D1002FC0D1604838 -:1015800002F030FA00283FD15E4E01F011FF3368BF -:10159000984239D301F00CFF0546FFF76FFB4FF47B +:1015800002F07CFA00283FD15E4E01F05DFF336827 +:10159000984239D301F058FF0546FFF76FFB4FF42F :1015A000C8738DF82870B0FBF3F202FB130305F546 :1015B000167010FA83F03060534E377817B9012354 :1015C0008DF82830C7F110050EA8FFF76FFB0EABA2 :1015D000EDB20DF12900D919062D28BF06252A469E :1015E000013500F0D7F90AABEDB245480393182353 :1015F00004950293454B0193012300933BA3D3E948 -:10160000002302F035FA347001F0D2FE404A414D19 -:101610001368C31AB3F57A7F2FD3106001F0CAFEA6 -:1016200002460B46364802F0BBFA354802F0DAF9BA +:10160000002302F081FA347001F01EFF404A414D80 +:101610001368C31AB3F57A7F2FD3106001F016FF59 +:1016200002460B46364802F007FB354802F026FA20 :1016300018B32B7A0EAF384E002B14BF03230223AE -:10164000737101F0B5FE4FF47A7301223946B0FB95 -:10165000F3F03060304600F075FB182380B202933F +:10164000737101F001FF4FF47A7301223946B0FB48 +:10165000F3F03060304600F08BFB182380B2029329 :101660002E4B019340F25513CDE9037000932448AB -:1016700020A3D3E9002302F0FBF92B7A93B101F008 -:1016800097FE002607464FF48A7895F8D900304433 +:1016700020A3D3E9002302F047FA2B7A93B101F0BB +:10168000E3FE002607464FF48A7895F8D9003044E7 :1016900000F0030008FB005393F8E82072B1013614 -:1016A000042EF2D1C82004F03FF92B7A002B7FF4EE +:1016A000042EF2D1C82004F0B3F92B7A002B7FF47A :1016B00017AF13B0BDEC028BBDE8F08FD3F8E0207C :1016C00042B12B68BA1AFA2B38BFFA230533B2EBB2 :1016D000430FE4D3FFF7C4FB0028E0D1E2E700BFEB :1016E000AFF300800000000000000000401DA120BA -:1016F00026812A0BF1C6A7C1D068080F403500200B -:10170000103500200C350020093500200835002058 -:10171000F0630020C05E0020F8240020F463002065 -:1017200010B5074C204601F007F904F5A65001F06A -:1017300003F9044A04490020BDE8104006F098B9B6 -:1017400040350020506400207D1000082DE9F84F3E +:1016F00026812A0BF1C6A7C1D068080FE03400206C +:10170000B0340020AC340020A9340020A8340020DC +:1017100090630020605E00209824002094630020E5 +:1017200010B5074C204601F053F904F5A65001F01E +:101730004FF9044A04490020BDE8104006F006BCF9 +:10174000E0340020F06300207D1000082DE9F84F00 :101750004FF47A7306460D46002402FB03F7DFF8C8 :101760005080DFF8509098F900305FFA84FA5A1CE4 :1017700001D0A34212D159F824002A463146036809 :10178000D3F820B03B46D847854207D1074B01200C :1017900083F800A0BDE8F88F0124E4E7002CFBD01B -:1017A0004FF4FA7004F0C0F80020F3E73C64002026 +:1017A0004FF4FA7004F034F90020F3E7DC63002012 :1017B000182300201C230020002307B50246012126 :1017C0000DF107008DF80730FFF7C0FF20B19DF83D :1017D000070003B05DF804FB4FF0FF30F9E70000AD :1017E0000A46042108B5FFF7B1FF80F00100C0B23E :1017F000404208BD074B0A4630B41978064B53F8EF :101800002140014623682046DD69044BAC4630BCCC -:10181000604700BF3C6400201C230020A08601001C -:1018200070B50A4E00240A4D04F0ACFB30802868E5 -:101830003388834208D904F0A1FB2B6804440133A8 -:10184000B4F5003F2B60F2D370BD00BF3E640020B2 -:10185000F863002004F064BC00F1006000F5003083 +:10181000604700BFDC6300201C230020A08601007D +:1018200070B50A4E00240A4D04F020FC3080286870 +:101830003388834208D904F015FC2B680444013333 +:10184000B4F5003F2B60F2D370BD00BFDE63002013 +:101850009863002004F0D8BC00F1006000F500306F :101860000068704700F10060920000F5003004F05D -:10187000E5BB0000054B1A68054B1B889B1A834289 -:1018800002D9104404F07ABB00207047F8630020AE -:101890003E640020024B1B68184404F075BB00BF77 -:1018A000F8630020024B1B68184404F07FBB00BFA4 -:1018B000F86300200020704700F1FF5000F58F1002 +:1018700059BC0000054B1A68054B1B889B1A834214 +:1018800002D9104404F0EEBB00207047986300209A +:10189000DE630020024B1B68184404F0E9BB00BF64 +:1018A00098630020024B1B68184404F0F3BB00BF90 +:1018B000986300200020704700F1FF5000F58F1062 :1018C000D0F8000870470000064991F8243033B181 :1018D00000230822086A81F82430FFF7C3BF0120E3 -:1018E000704700BFFC630020014B1868704700BFC1 +:1018E000704700BF9C630020014B1868704700BF21 :1018F0000010005C194B01380322084470B51D68C4 :10190000174BC5F30B042D0C1E88A6420BD15C6847 :101910000A46013C824213460FD214F9016F4EB1C0 @@ -405,9 +405,9 @@ :101930000B4602D22C2203F8012B0424094A1688F4 :10194000AE4204D1984284BF967803F8016B013C03 :1019500002F10402F3D1581A70BD00BF0010005C00 -:1019600024230020747B00087047000070470000AB +:10196000242300203C8000087047000070470000DE :101970007047000070B504464FF47A764CB1412CA4 -:10198000254628BF412506FB05F0641B03F0CCFF6C +:10198000254628BF412506FB05F0641B04F040F8FE :10199000F4E770BD002310B5934203D0CC5CC4546F :1019A0000133F9E710BD0000013810B510F9013F0F :1019B0003BB191F900409C4203D11AB10131013A87 @@ -422,1652 +422,1722 @@ :101A40009044E4B2F6B2082E85F82460DBD1FFF7AB :101A50003BFF0028D7D108E02B6A03EB82038342C7 :101A6000CFD0FFF731FF0028CBD10020BDE8F883AD -:101A70000120FBE7FC630020024B1A78024B1A702E -:101A8000704700BF3C6400201823002038B51A4C72 -:101A90001A4D204603F08CFA2946204603F0B4FA8A +:101A70000120FBE79C630020024B1A78024B1A708E +:101A8000704700BFDC6300201823002038B51A4CD3 +:101A90001A4D204603F0DCFA2946204603F004FBE9 :101AA0002D684FF47A70D5F89020D2F8043843F0BE :101AB0000203C2F80438FFF75DFF1149284603F01E -:101AC000B1FBD5F890200F4DD2F80438286823F0E8 +:101AC00001FCD5F890200F4DD2F80438286823F097 :101AD00002030D49A042C2F804384FF4E1330B6011 -:101AE00001D003F0C3F96868A04204D00649BDE8FC -:101AF000384003F0BBB938BDB86B0020347E000815 -:101B00003C7E00081C230020246400200C4B70B590 +:101AE00001D003F013FA6868A04204D00649BDE8AB +:101AF000384003F00BBA38BD586B0020FC82000858 +:101B0000048300081C230020C46300200C4B70B524 :101B10000C4D04461E780C4B55F826209A420DD0E9 :101B20000A4B002118221846FFF75AFF04600146AD -:101B300055F82600BDE8704003F098B970BD00BFAD -:101B40003C6400201C230020B86B0020246400208B -:101B5000F0B5A1B071B600230120002480261A46FA -:101B6000194602F05BFE4FF4D067214A3D25136908 -:101B700023BBD2F810310BBB036804F100619960FC -:101B80000368C3F80CD003685E6003681F600168D7 -:101B90000B6843F001030B6001680B6823F01E0320 -:101BA0000B6001680B68DB07FCD4037B8034416861 -:101BB00005FA03F3B4F5001F0B60D8D102F06EFEF6 -:101BC000B4F5001F11D000240A4E0B4D012004F083 -:101BD000A7FA3388A34205D928682044013404F0C9 -:101BE000E5F9F6E7002004F09BFA61B621B0F0BDFC -:101BF000002000523E640020F86300202DE9F047E9 -:101C00000D46044600219046284640F27912FFF71F -:101C1000E7FE234620220021284604F1220702F095 -:101C200035F9231D022220212846C02602F02EF974 -:101C3000631D03222221284602F028F9A31D032256 -:101C40002521284602F022F904F108031022282158 -:101C5000284602F01BF904F1100308223821284617 -:101C600002F014F904F1110308224021284602F081 -:101C70000DF904F1120308224821284602F006F962 -:101C800004F1140320225021284602F0FFF804F149 -:101C9000180340227021284602F0F8F804F12003CE -:101CA0000822B021284602F0F1F804F121030822AD -:101CB000B821284602F0EAF8314608363B460822A9 -:101CC0002846013702F0E2F8B6F5A07FF4D10027EC -:101CD00004F1330A04F1320308223146284602F0A7 -:101CE000D5F894F832304FEAC7099F4209F5A47637 -:101CF00015D3B8F1000F08D1314609F24F1604F59B -:101D000099730722284602F0C1F827463B1B94F836 -:101D1000322193420CD3F01DC008BDE8F0870AEBD6 -:101D20000703082231462846013702F0AFF8D8E70A -:101D300007F233133146082228460836013702F0ED -:101D4000A5F8E3E713B50446084600212022234600 -:101D500001900160C0F8031002F098F8231D01986B -:101D60000222202102F092F8631D01980322222111 -:101D700002F08CF8A31D01980322252102F086F8B9 -:101D8000019804F108031022282102F07FF80720AF -:101D900002B010BD0023F7B50E46047F0722009164 -:101DA0001946054601F036FF731C012207210093F6 -:101DB0002846002301F02EFFC4B9B31C05220821D8 -:101DC0002846009323460D2401F024FF3746BB1B11 -:101DD000B278934211D307342B7FA88AE408BBB9A9 -:101DE000844294BF0020012003B0F0BDAB8A0824D8 -:101DF000DB00083BDB08B370E8E7FB1C2146082248 -:101E00002846009300230834013701F003FFDEE782 -:101E1000201A18BF0120E7E70023F7B50E46047F1C -:101E2000082200911946054601F0F4FE731CC4B95E -:101E300008220093234610241146284601F0EAFEAA -:101E400001235F1C7278013B934211D307342B7F2F -:101E5000A88AE408BBB9844294BF0020012003B0E3 -:101E6000F0BDAB8A0824DB00083BDB087370E7E7B2 -:101E7000F3192146082228460093002301F0CAFEE8 -:101E800008343B46DDE7201A18BF0120E7E70000D1 -:101E9000F8B50E4605461446002181223046FFF76C -:101EA0009FFD2B4608220021304601F0EFFF7CB950 -:101EB0000F246B1C07220821304601F0E7FF0123A5 -:101EC0005F1C6A78013B934204D3E01DC008F8BD53 -:101ED0000824F4E7EB1921460822304601F0D6FF2A -:101EE00008343B46ECE70000F8B50E4605461446BC -:101EF0000021CE223046FFF773FD2B462822002119 -:101F0000304601F0C3FF7CB9302405F108030822F4 -:101F10002821304601F0BAFF2F467B1B2A7A9342D4 -:101F200004D3E01DC008F8BD2824F5E707F1090334 -:101F30002146082230460834013701F0A7FFECE7BC -:101F4000F7B5047F0E4600910123102200210546BB -:101F500001F060FEC4B9B31C092210212846009389 -:101F60002346192401F056FE37467288BB1B9A425D -:101F700011D807342B7FA88AE408BBB9844294BFE8 -:101F80000020012003B0F0BDAB8A1024DB00103B21 -:101F9000DB087380E8E73B1D2146082228460093B2 -:101FA00000230834013701F035FEDEE7201A18BFA0 -:101FB0000120E7E730B50A44084D91420DD011F8F1 -:101FC000013B5840082340F30004013B2C4013F030 -:101FD000FF0384EA5000F6D1EFE730BD2083B8ED6F -:101FE000F7B5364A6B46106851686A4603C3082342 -:101FF0003349344805F06AFD044690BB0A25324A4D -:102000006B46106851686A4603C308232F492D4860 -:1020100005F05CFD0446002847D00369B3F5F01FC6 -:1020200043D8B0F86620B2F5AF6F3ED1284A0244DB -:1020300002F15C018B4238D35C3B224900209E1A9E -:10204000FFF7B8FF04F16401074632460020FFF7AE -:10205000B1FFA3689F4228D1E368984208BF0025DA -:1020600023E00369B3F5F01F26D8428BB2F5AF6FBA -:1020700020D1174A024402F110018B4218D3103BC1 -:10208000104900209D1AFFF795FF04F1180106463C -:102090002A460020FFF78EFFA3689E4202D1E36824 -:1020A000984201D00D25AAE70025284603B0F0BDCF -:1020B0001025A4E70C25A2E70B25A0E7847B0008E8 -:1020C000DCFF1D00000002088D7B000890FF1D0052 -:1020D0000800FEF710B5037C044613B9006805F04C -:1020E000DDFC204610BD00000023BFF35B8FC36002 -:1020F000BFF35B8FBFF35B8F8360BFF35B8F704772 -:10210000BFF35B8F0068BFF35B8F704770B5054608 -:102110000C30FFF7F5FF044605F108063046FFF7DF -:10212000EFFFA04206D96D683046FFF7E9FF25446E -:10213000281A70BD3046FFF7E3FF201AF9E70000C8 -:1021400070B505464068A0B105F10C0605F1080020 -:10215000FFF7D6FF04463046FFF7D2FF844204F172 -:10216000FF34304694BF6D680025FFF7C9FF2C444B -:10217000201A70BD38B50C460546FFF7C7FFA042D0 -:1021800010D305F10800FFF7BBFF04446868BFF3F4 -:102190005B8FB4FBF0F100FB11440120AC60BFF396 -:1021A0005B8F38BD0020FCE72DE9F041144607465F -:1021B0000D46FFF7C5FF844228BF0446D4B1B84698 -:1021C00058F80C6B4046FFF79BFF304428604046B0 -:1021D0007E68FFF795FF331A9C4203D801206C609C -:1021E000BDE8F081A41B6B603B682044AB60E860F5 -:1021F0000220F5E72046F3E738B50C460546FFF721 -:102200009FFFA04210D305F10C00FFF779FF0444B3 -:102210006868BFF35B8FB4FBF0F100FB1144012051 -:10222000EC60BFF35B8F38BD0020FCE72DE9FF4178 -:102230008846694607466C46FFF7B6FF002506B29A -:1022400004EBC606B4420AD0626808EB05012068B8 -:102250000834FFF79FFB54F8043C1D44F2E729467D -:102260003846FFF7C9FF284604B0BDE8F0810000FA -:10227000F8B505460C300F46FFF742FF05F108069A -:1022800004463046FFF73CFFA042304688BF6C68EA -:10229000FFF736FF201A386020B12C683046FFF770 -:1022A0002FFF2044F8BD000073B5144606460D46C6 -:1022B000FFF72CFF8442019028BF0446DCB101A93E -:1022C0003046FFF7D5FF019B33B93268C5E90233C9 -:1022D000C5E9002401200CE09C42286038BF01942D -:1022E000019884426860F5D93368241A0220AB60F3 -:1022F000EC6002B070BD2046FBE700002DE9FF4115 -:102300000F4669466C46FFF7CFFF00B2002604EB8C -:10231000C005AC4209D0D4F80480B81954F8081BA1 -:1023200042464644FFF736FBF3E7304604B0BDE8CB -:10233000F081000038B50546FFF7E0FF044601468E -:102340002846FFF717FF204638BD00007047000001 -:1023500010B41346026814680022A4465DF8044BCA -:102360006047000000F5805090F859047047000065 -:1023700000F5805090F852047047000000F580503E -:1023800090F95804704700004E207047302383F3C3 -:10239000118800F58052D2F89C34D2F89804184481 -:1023A000D2F894341844D2F87C341844D2F88C34DF -:1023B0001844D2F888341844002383F311887047F6 -:1023C00000F58050C0F85414012070472DE9F04FFB -:1023D0000C4600F5805185B01F4691F852340546F1 -:1023E0009046BDF838909BB1D1F878340133C1F8EC -:1023F00078342368980006D4237B082B0BD9627BA2 -:102400000AB10F2B07D9D1F87C340133C1F87C34E1 -:102410004FF0FF3010E0302383F31188EB6AD3F8DC -:10242000C42012F4001B0AD0D1F8803400200133FC -:10243000C1F8803480F3118805B0BDE8F08F2068C2 -:102440004822D3F8C4300028C3F3044A6B6AB4BFEF -:1024500040F08040800412FB0A334FEA4A161860AD -:10246000226852004FEA0A6244BF40F000501860F0 -:10247000207B42EA00425A60607B10B342F4401273 -:102480005A60D1F8B0240132C1F8B024AA1902F57B -:102490008352117B41F020011173207B039300F0E4 -:1024A000E3FF0330039B80105FFA8BF20BF1010B0B -:1024B00082420DDA04EB820103EB820249689160EB -:1024C000F2E7AA1902F58352117B60F34511E3E7A5 -:1024D0000122EB6A05EB4A1102FA0AF201F5825178 -:1024E000C3F8D020AB19183104F10C0203F5825364 -:1024F000C3E90487234653F8040B934241F8040BC5 -:10250000F9D11B882E440B8041F2680346F803A0E2 -:1025100006F5805609F0030396F86C2043F010038B -:1025200022F01F02134386F86C30002383F31188D6 -:1025300042463B4621462846CDF8009000F05AFF1F -:10254000012079E72DE9F04700F58056044696F81A -:102550005254002D40F00381037C032B40F0948003 -:1025600028462B462F465FFA80FC944510DA01EB93 -:10257000CC0E51F83CC0BCF1000F04DBDEF804C007 -:10258000BCF1000F02DB01370130ECE70133FBE760 -:10259000302080F31188E06AF3B9D0F8803043F03E -:1025A0000203C0F880304E23E06A002F6FD1D0F8CC -:1025B000803043F00103C0F880306A4B6A4A1B68E0 -:1025C00003F1805303F52C539B009342A36240F226 -:1025D000B080664800F0E6FE4D2B42D8DFF88481DB -:1025E0004FEA034EDFF88891D8F800C04EEA8C0E0F -:1025F000C0F884E00CF1805000F52C508000606140 -:1026000003EB0C00D4F82CC0C3F14E03C8F8000053 -:10261000DCF8800040F03000CCF880004FF0000C77 -:10262000D4F81480E6465FFA8CF08242BCDD01EB00 -:10263000C00A51F83000002810DBDAF804A0BAF123 -:10264000000F0BDA09EA00400AF07F0A40EA0A00AC -:1026500040F0084048F82E000EF1010E0CF1010C7C -:10266000E1E7836923F00103836100F0A1FE0646E0 -:10267000E36A9B69D90704D500F09AFE831BFA2B05 -:10268000F6D9002383F311882846BDE8F087B7EB1D -:10269000530F3DD2DFF8CCE04FEA074CDEF80030B4 -:1026A0004CEA830CC0F888C003F1805003EB470369 -:1026B000002700F52C50CEF80030BC468000A06109 -:1026C000E06AD0F8803043F00C03C0F88030D4F8D2 -:1026D00018E0FBB29A427FF770AF51F8330001EB7C -:1026E000C3080028D8F8043001DB002B0EDB20F0F3 -:1026F000604023F0604340F0005043F000434EF848 -:102700003C000EEBCC000CF1010C43600137E0E71C -:10271000836923F00103836100F04AFE0646E36A01 -:102720009B69DA07ADD500F043FE831BFA2BF6D97F -:10273000A7E7E26A936923F00103936100F038FE92 -:102740000746E36A9B69DB0705D500F031FEC31B32 -:10275000FA2BF6D995E7012586F8525491E7002522 -:1027600092E700BF4C640020FCB50040987B000855 -:102770000000FF0713B500F580540191606CFFF76E -:10278000DFFC1F280AD920220199606CFFF74EFD5B -:10279000A0F120035842584102B010BD0020FBE7D1 -:1027A00008B5302383F3118800F58050406CFFF7A3 -:1027B0009BFC002383F3118808BD00000022026007 -:1027C00082814260826070470022002310B5C0E918 -:1027D0000023002304460C3020F8043CFFF7EEFFF2 -:1027E000204610BD2DE9F0479A4688B00746884636 -:1027F0009146302383F3118807F580546846FFF72C -:10280000E3FF606CFFF782FC1F282ED92022694667 -:10281000606CFFF78FFD202827D194F8523423B342 -:1028200003AD444605AB2E46083403CE9E4244F821 -:10283000080C44F8041C3546F5D130682060B38894 -:10284000A380DDE90023C9E90023BDF80830AAF818 -:102850000030002383F3118853464A4641463846E8 -:1028600008B0BDE8F04700F0B3BD002080F3118848 -:1028700008B0BDE8F08700002DE9F84F00230646B8 -:1028800000F58154054688461034C0E90133274BD2 -:1028900046F8303B374638462037FFF795FFA742CA -:1028A000F9D105F580544FF4805305F5A3594FF045 -:1028B000000A26630026676405F5835709F11009AD -:1028C0004FF0000B1037E663C4E90D36012384F89E -:1028D000403084F84830A7F11800203747E910ABA2 -:1028E000FFF76CFF47F8286C4F45F4D1B8F1010FA2 -:1028F00084F85884A4F85A64A4F85C64A4F85E646C -:1029000084F86064A4F86264A4F86464A4F866645B -:1029100084F8686402D9064800F044FD054B284657 -:1029200053F82830EB62BDE8F88F00BFE87B000861 -:10293000BC7B0008D87B0008044B10B5197804460E -:102940004A1C1A70FFF798FF204610BD496400200A -:102950002DE9F04300295AD02E4E2F48B6FBF1F452 -:1029600081428CBF0A201120431EB4FBF0F700FB0C -:102970001740DDB220B1022B1846F5D8002032E016 -:102980007B1EB3F5806F2ED2C5EBC5084FF47A736A -:1029900008F103044FEAE40EC4F3C7040EF1010981 -:1029A000281B0EFB033E5FFA80FC59FA80F0BEFB49 -:1029B000F0F0B0F5617F18DC83B2601C5CFA80F047 -:1029C0007843B6FBF0F08142D8D1611E0F29D5D8EB -:1029D0000CF1FF310729D1D80120138057801071E5 -:1029E000547182F806C0BDE8F08308F1FF34E010AE -:1029F000C4F3C70400F1010E2D1B00FB03335FFA83 -:102A000085FC5EFA85F5B3FBF5F39BB2D5E7084686 -:102A1000E9E700BF00B4C4043F420F0030B50D4BDE -:102A200005200D4D1C786C438C420ED15978012045 -:102A3000518099785171D9789171197911715B79B7 -:102A400003EB83035B00138030BD013803F1060301 -:102A5000E8D1F9E7287C000840420F0038B540F281 -:102A60007772C36A154CC3F8BC200722C36AC3F847 -:102A7000C8202268C16A930043F4C023C1F8A03083 -:102A800002F1805302F16C01C56A03F52C53EA325E -:102A900089009B00226041F0E061094AC361C5F8EA -:102AA000C01003F5D87103F56A73416293428362E3 -:102AB00002D9044800F076FC38BD00BF4C64002009 -:102AC000FCB50040987B00082DE9F04F00F58055DB -:102AD0001F4689B0044695F8583489469046022B23 -:102AE00004D90026304609B0BDE8F08FA84A52F854 -:102AF000231009B942F82300A648C4F80C900178C5 -:102B00002774C9B9302383F31188A34BD3F8EC2081 -:102B100042F48072C3F8EC20D3F8942042F480721F -:102B2000C3F89420D3F8942022F48072C3F8942040 -:102B30000123037081F3118895F851347BB9302358 -:102B400083F31188954A95F85834D35C0BB3012B65 -:102B500028D0012385F85134002383F311883023D2 -:102B600083F31188E26A936923F01003936100F004 -:102B70001FFC8246E36A9E6916F0080619D000F031 -:102B800017FCA0EB0A03FA2BF4D9002686F3118870 -:102B9000A8E70321132001F09DFF0321152001F078 -:102BA00099FFD6E70321142001F094FF032116209A -:102BB000F5E79A6942F001029A6100F0F9FB82465A -:102BC000E36A9A69D00706D400F0F2FBA0EB0A038F -:102BD000FA2BF5D9D9E79A694FF0000A42F00202C0 -:102BE0009A61E36AC3F854A08AF3118804F5825B02 -:102BF000686CFFF779FA0BF1100B20220021684670 -:102C0000FEF7EEFE02A8FFF7D9FD6A460BEB0603BE -:102C10000DF1180ECDF818A094460833BCE8030057 -:102C2000F44543F8080C43F8041C6246F4D1DCF880 -:102C3000000020361860B6F5806F9CF804201A71E9 -:102C4000DBD1002304F5A252494620461A3285F80A -:102C5000503485F85334FFF77BFE064690B9E26A9C -:102C6000936923F00103936100F0A2FB0546E36A38 -:102C70009B69D9077FF535AF00F09AFB431BFA2B10 -:102C8000F5D92EE795F85E34C5F86C94591E95F881 -:102C90005F34E26A013B1B0243EA416395F860142A -:102CA00001390B43B5F85C14013943EA0143D361A0 -:102CB000B8F1000F36D004F5A35241462046023247 -:102CC000FFF7ACFE90B9E26A936923F001039361C8 -:102CD00000F06EFB0546E36A9B69DA077FF501AFFA -:102CE00000F066FB431BFA2BF5D9FAE695F867244A -:102CF000C5F87084511E95F86824E36A013A120100 -:102D000042EA012295F8661401390A43B5F86414C1 -:102D1000013942EA014242F40002DA604FF42062D3 -:102D2000E36A9A64E36A4FF000082046C3F8BC8067 -:102D3000FFF794FE85F859846FF04042E36A1A6504 -:102D4000174AE36A5A654FF00222E36A9A654FF028 -:102D5000FF32E36AC3F8E0200322E36A9742DA65B0 -:102D60003FF4C0AEE26A936923F00103936100F07F -:102D70001FFB0746E36A9B69DB0705D500F018FBDC -:102D8000C31BFA2BF6D9ACE6012385F85234A9E629 -:102D9000406400204864002000440258D07B0008B2 -:102DA000550200022DE9F04F054689B0904699463C -:102DB000002741F2680A00F58056EB6AD3F8D83054 -:102DC000FB40D80751D505EB47124FEA471B524449 -:102DD0001379190749D4D6F884340133C6F88434FA -:102DE00005F5A553C3E9008913799A0605EB0B0293 -:102DF00048BFD6F8B434524444BF0133C6F8B434A3 -:102E0000137943F008031371DB0723D596F8533485 -:102E100003B305F582546846FFF7D6FC03AB1834BC -:102E20005C4404F1080C2068083454F8041C1A4669 -:102E3000644503C21346F6D12068694610602846EF -:102E4000A2889A800123ADF808302B68CDE900896B -:102E5000DB6B9847D6F8A834D6F854040133C6F88B -:102E6000A83410B103681B6998470137202FA4D1FB -:102E700009B0BDE8F08F00002DE9F04F0F468DB08E -:102E8000044600F097FA82468946002F5BD1E36A38 -:102E9000D3F8A02012F4FE0F03D100200DB0BDE83E -:102EA000F08FD3F8A420920141BF04F58051D1F8EE -:102EB00098240132C1F89824D3F8A4205606ECD007 -:102EC000D3F8A450E669C5F305254823E8464FF03A -:102ED000000B03FB05664046FFF770FC32685100AB -:102EE0004ABF22F06043C2F38A4343F0004392009A -:102EF00048BF43F080430093736813F400131BBF73 -:102F0000012304F580528DF80D308DF80D301EBF71 -:102F1000D2F8B8340133C2F8B834F38803F00F03A1 -:102F20008DF80C309DF80C0000F09EFA5FFA8BF3E0 -:102F3000984225D9F2180CA90BF1010B127A0B4417 -:102F400003F82C2CEEE7012FA7D1E36AD3F8B020C9 -:102F500012F4FE0FA1D0D3F8B420950141BF04F5BF -:102F60008051D1F898240132C1F89824D3F8B420C4 -:102F7000500692D0D3F8B450266AC5F30525A4E7CD -:102F8000EFB9E36AC3F8A85004A807ADFFF71CFC2B -:102F900098E80F0007C52B800023204604A9ADF850 -:102FA0001830236804F58054DB6BCDE904A99847F9 -:102FB00058B1D4F890340133C4F890346EE7012F3F -:102FC000E2D1E36AC3F8B850DEE7D4F894340120C4 -:102FD0000133C4F8943461E72DE9F04105460F460A -:102FE00000F58054012639462846FFF745FF10B109 -:102FF00084F85364F7E7D4F8A834D4F854040133C0 -:10300000C4F8A83420B10368BDE8F0411B69184733 -:10301000BDE8F081C36AF0B51A6C12F47F0F2BD0B3 -:103020001B6C00F5805441F268054FF0010CC4F8A8 -:10303000AC340023471900EB43125E012A44117996 -:1030400011F0020F15D0490713D4B959C66A0CFA0A -:1030500001F1D6F8CCE011EA0E0F0AD0C6F8D41070 -:10306000117941F004011171D4F88C240132C4F8B3 -:103070008C240133202BDED1F0BD00002B4B70B52A -:103080001E561B5C012B30D8294D2A4A55F8233097 -:1030900052F8264013B349B3236D9A0510D54FF467 -:1030A0000073236500F086F950EA01020B4602D056 -:1030B000013861F10003024655F82600FFF772FE61 -:1030C000236D9B012CD54FF0007255F826302265F8 -:1030D00003F58053012283F8592421E0012323655D -:1030E000102323654FF48053236570BD236DDA07E9 -:1030F00002D4236D5B0706D50523002155F8260071 -:103100002365FFF769FF236DD80602D4236D5906A6 -:1031100006D55023012155F826002365FFF75CFFF3 -:1031200055F82600BDE87040FFF774BFD47B000857 -:1031300040640020D87B000808B5302383F3118851 -:10314000FFF768FF002383F3118808BDC36AD3F833 -:10315000C00010F07C5005D0D3F8C40080F40010FB -:10316000C0F340507047000008B5302383F3118846 -:1031700000F58050406CFEF7C9FF002383F31188EF -:1031800043090CBF0120002008BD000000F580535A -:1031900093F8592462B1C16A8A6922F001028A61F6 -:1031A000D3F89C240132C3F89C24002283F85924CC -:1031B000704700002DE9F743302181F3118800F5B5 -:1031C0008251002541F2680E4FF00108103100F5E0 -:1031D000805C00EB45147444267977071CD4F6060E -:1031E0001AD58E69D0F82C9008FA06F6D9F8CC706A -:1031F0003E4211D04F6801970F689742019F9F414F -:103200000AD2C9F8D460267946F004062671DCF8A3 -:1032100088440134CCF8884401352031202DD8D1A0 -:10322000002383F3118803B0BDE8F083F8B51E4690 -:1032300000230F46054613701446FFF795FF80F0F4 -:10324000010038701EB12846FFF780FF2070F8BDDE -:103250002DE9F04F85B099460D468046164691F807 -:1032600000B0DDE90EA302931378019300F0A2F8F9 -:103270002B7804460F4613B93378002B41D02246F1 -:103280003B464046FFF796FFFFF756FFFFF77EFFEE -:103290004B4632462946FFF7C9FF2B7833B1BBF1C5 -:1032A000000F03D0012005B0BDE8F08F337813B1D3 -:1032B000019B002BF6D108F5805303935445029BE4 -:1032C00077EB03031DD2039BD3F85404C8B1036802 -:1032D000AAEB04011B6898474B46324629464046F4 -:1032E000FFF7A4FF2B7813B1BBF1000FDAD13378CD -:1032F00013B1019B002BD5D100F05CF804460F46BA -:10330000DCE70020CFE70000002108B50846FFF702 -:10331000B5FEBDE8084001F06DB8000008B5012118 -:103320000020FFF7ABFEBDE8084001F063B80000E5 -:1033300008B500210120FFF7A1FEBDE8084001F01B -:1033400059B80000012108B50846FFF797FEBDE80F -:10335000084001F04FB8000000B59BB0EFF30981C1 -:1033600068226846FEF716FBEFF30583014B9B6B63 -:10337000FEE700BF00ED00E008B5FFF7EDFF00003D -:1033800000B59BB0EFF3098168226846FEF702FBA7 -:10339000EFF30583014B5B6BFEE700BF00ED00E040 -:1033A000FEE700000FB408B5029802F063FAFEE7EA -:1033B00002F0F8BE02F0DABE13B56C46031D84E8D5 -:1033C000060094E8030083E80500012002B010BD68 -:1033D00073B58568019155B11B885B0707D4D0E9A7 -:1033E00000369B6B9847019AC1B23046A84701202E -:1033F00002B070BDF0B5866889B005460C465EB176 -:10340000BDF838305B070AD4D0E900379B6B98478A -:103410002246C1B23846B047012009B0F0BD0022B3 -:10342000002301F10806CDE9002300230A46ADF888 -:10343000083003AB1068083252F8041C1C46B24234 -:1034400003C42346F6D1106820609288A280FFF75B -:10345000B1FF0423ADF808302B68CDE90001DB6B28 -:10346000694628469847D7E7082817D909280CD075 -:103470000A280CD00B280CD00C280CD00D280CD00E -:103480000E2814BF4020302070470C2070471020B9 -:1034900070471420704718207047202070470000A4 -:1034A0002DE9F041456A15B94162BDE8F0814B68EC -:1034B000AC4623F06047C3F38A464FEAD37EC3F39A -:1034C000807816EA230638BF3E462B465A68BEEB84 -:1034D000D27F22F060440AD0002A18DAA40CB44249 -:1034E00017D19D420FD10D60DEE71346EEE7A742EC -:1034F00007D102F08044C2F3807242450BD054B130 -:10350000EFE708D2EDE7CCF800100B60CDE7B4424E -:1035100001D0B442E5D81A689C46002AE5D119606A -:10352000C3E700002DE9F047089D01F0070400EB18 -:10353000D1004FF47F494FEAD508224405F0070532 -:10354000944201D1BDE8F08704F0070705F0070AAF -:10355000111B08EBD50E57453E4613F80EC038BF79 -:103560005646C6F108068E4228BF0E46E108415C69 -:1035700034443544B94029FA06F721FA0AF1FFB27A -:103580008CEA010147FA0AF739408CEA010C03F88A -:103590000EC0D5E780EA0120082341F2210201B2E2 -:1035A000013B4000002980B2B8BF504013F0FF0338 -:1035B000F5D1704738B50C468D18A54200D138BDFD -:1035C00014F8011BFFF7E6FFF7E7000042684AB175 -:1035D000136881894360438901339BB299424381D7 -:1035E00038BF83811046704770B588B004462022EA -:1035F0000D4668460021FEF7F3F920460495FFF7D3 -:10360000E5FF024660B16B46054608AE1C4608352C -:1036100003CCB44245F8080C45F8041C2346F5D108 -:10362000104608B070BD0000082817D909280CD032 -:103630000A280CD00B280CD00C280CD00D280CD04C -:103640000E2814BF4020302070470C2070471020F7 -:1036500070471420704718207047202070470000E2 -:10366000082817D90C280CD910280CD914280CD9E3 -:1036700018280CD920280CD930288CBF0F200E20F8 -:103680007047092070470A2070470B2070470C20B4 -:1036900070470D20704700002DE9F843078C044661 -:1036A000072F1ED900254FF6FF73D0E90298C5F108 -:1036B0002006A5F1200029FA05F1083508FA06F6DA -:1036C00028FA00F0314301431846C9B2FFF762FF00 -:1036D000402D0346EBD13A46E169BDE8F843FFF7D8 -:1036E00069BF4FF6FF70BDE8F883000010B54B6866 -:1036F00023B9CA8A63F30902CA8210BD04691A6831 -:103700001C600361C38A013BC3824A60EFE700008B -:103710002DE9F84F1D46CB8A0F468146C3F30901B8 -:10372000924605290B4630D00020AAB207F11A04B0 -:103730009EB21FFA80F8042E0FD8904503F10103C2 -:1037400006D30A44FB8A62F309030120FB821AE0D4 -:103750001AF800600130E654EAE79045F1D2A1F191 -:10376000050B1C237C68BBFBF3F203FB12BB1FFAA7 -:103770008BF6002C45D14846FFF728FF044638B9A0 -:1037800078606FF00200BDE8F88F4FF00008E6E7C0 -:10379000002606607860ADB24FF0000B454510D9A9 -:1037A0000AEB0803221D13F8011B08F101089155CB -:1037B000B1B21FFA88F81B292BD0454506F1010646 -:1037C000F1D8FB8AC3F30902154465F30903BCE78A -:1037D00001321C4692B22368002BF9D16B1F0B44B7 -:1037E0001C21B3FBF1F301339BB29A42D3D2BBF15C -:1037F000000FD0D14846FFF7E9FE20B9C4F800B069 -:10380000BFE70122E7E7C0F800B05E46206004464B -:10381000C1E74545D5D94846FFF7D8FE08B920602D -:10382000AFE7C0F800B0002620600446B6E700000D -:103830002DE9F04F1C46074688462DED028B83B0DC -:103840005B690192002B00F09A80238C2BB1E26916 -:10385000002A00F09480072B35D807F10C00FFF701 -:10386000B5FE054638B96FF00205284603B0BDEC39 -:10387000028BBDE8F08F14220021FEF7B1F8228CF4 -:10388000E16905F10800FEF785F8208C48F0004159 -:10389000013080B2FFF7E4FEFFF7C6FE013880B2C8 -:1038A00020840130287438466369228C1B782A44AE -:1038B00003F01F0363F03F03137269602946FFF7AB -:1038C000EFFD0125D1E74FF0000900F10C034FF0A7 -:1038D000800A4E464D4608EE103A18EE100AFFF7E1 -:1038E00075FE83460028BED014220021FEF778F82A -:1038F000002E3AD1019B0222ABF808300BF1080EE2 -:103900001FFA82FC218C0CF10100BCF1060F80B281 -:1039100001D88E422BD3FFF7A3FE8E4208BF4FF093 -:10392000400AFFF781FE62690138013512781BFAFF -:1039300080F1013002F01F022DB242EA491289F0F3 -:1039400001094AEA020A48F0004281F808A05946F3 -:103950008BF810003846CBF804204FF0000AFFF730 -:103960009FFD238CB342B8D17FE70022C6E7E1690F -:10397000895D01360EF80210B6B20132C0E76FF071 -:10398000010572E7F8B515460E46302200210446BF -:103990001F46FEF725F8069BB5F5001FA76063607C -:1039A00004F11000079B34BF6A094FF6FF72E6610D -:1039B000A362002397B29A4206D800230360A7822D -:1039C000E3822383E360F8BD06600133304620368E -:1039D000F1E7000003781BB94BB2002BC8BF0170A0 -:1039E0007047000000787047F8B50C46C969074673 -:1039F00011B9238C002B37D1257E1F2D34D8387870 -:103A000028BB228C072A2CD8268A36F003032BD118 -:103A10004FF6FF70FFF7CEFD20F0010031024FF6A8 -:103A2000FF72400441EA0561400C41EA402523460B -:103A300029463846FFF7FCFE002807DD6269137847 -:103A40000133DBB21F2B88BF00231370F8BD218A1E -:103A50002D0645EA012505432046FFF71DFE0246D7 -:103A6000E5E76FF00300F1E76FF00100EEE700001B -:103A700070B58AB0044616460021282268461D46C5 -:103A8000FDF7AEFFBDF8383069462046ADF810307E -:103A90000F9B05939DF840308DF81830119B0793CC -:103AA000BDF84830CDE90265ADF82030FFF79CFF46 -:103AB0000AB070BD2DE9F041D36905460C461646A3 -:103AC0000BB9138C5BBB377E1F2F28D895F800806D -:103AD000B8F1000F26D03046FFF7DEFD3378210223 -:103AE0000246284641EAC331338A41EA080141EAE5 -:103AF000076141EA0341334641F08001FFF798FE38 -:103B000000280ADD3378012B07D17269137801335D -:103B1000DBB21F2B88BF00231370BDE8F0816FF06C -:103B20000100FAE76FF00300F7E70000F0B58BB093 -:103B300004460D4617460021282268461E46FDF71A -:103B40004FFF9DF84C30294620465A1E53425341A0 -:103B50006A468DF800309DF84030ADF81030119B6A -:103B600005939DF848308DF81830149B0793BDF8E5 -:103B70005430CDE90276ADF82030FFF79BFF0BB053 -:103B8000F0BD0000406A00B104307047436A1A6813 -:103B9000426202691A600361C38A013BC3827047B3 -:103BA0002DE9F041D0F8208014461D46184E4146BC -:103BB000002709B9BDE8F081D1E90223A21A65EB1B -:103BC0000303964277EB03031ED2036A8B420DD1A7 -:103BD000FFF78CFD036A1B68036203690B60C38AED -:103BE0000161013B016AC3828846E2E7FFF77EFD7F -:103BF0000B68C8F8003003690B60C38A0161013BA0 -:103C0000C382D8F80010D4E788460968D1E700BF1E -:103C100080841E002DE9F04F8BB00D4614469B4664 -:103C2000DDF850908046002800F01881B9F1000FAF -:103C300000F01481531E3F2B00F21081012A03D1A2 -:103C4000BBF1000F40F00A810023CDE90833B8F83A -:103C50001430B5EBC30F4FEAC30703D300200BB0FA -:103C6000BDE8F08F2B199F42D8F80C3036BF7F1B70 -:103C70002746FFB21BB9D8F81030002B7AD0272D79 -:103C80004DD8C5F1280600232946B742009308AB5A -:103C9000D8F808002CBFF6B23E46A7EB060A35441A -:103CA00032465FFA8AFAFFF73DFCB8F81430282153 -:103CB00003F10053053BDB000493D8F80C30039369 -:103CC000039B13B1BAF1000F2CD1D8F8100040B10A -:103CD000BAF1000F05D008AB5246691A0096FFF7FB -:103CE00021FC38B2002FB9D066070AD00AAB624275 -:103CF00003EBD40102F0070211F8083C134101F86C -:103D0000083C082C3DD9102C40F2B580202C40F204 -:103D1000B780BBF1000F00F09C80082335E0BA4665 -:103D20000026C2E7049BE02B28BFE02306930B4448 -:103D3000AB42059315D95A1B0398691A0096924510 -:103D400008AB00F1040034BF5246D2B20792FFF72D -:103D5000E9FB079A1644AAEB020A1544F6B25FFA89 -:103D60008AFA049B069A05999B1A0493039B1B6885 -:103D70000393A5E700933A4608AB2946D8F8080014 -:103D8000ADE7BBF1000F13D00123B4EBC30F6BD031 -:103D9000082C12D89DF82030621E23FA02F2D507B3 -:103DA00006D54FF0FF3202FA04F423438DF8203099 -:103DB0009DF8203089F8003051E7102C12D8BDF85A -:103DC0002030621E23FA02F2D10706D54FF0FF32EF -:103DD00002FA04F42343ADF82030BDF82030A9F8EE -:103DE00000303CE7202C0FD80899631E21FA03F31A -:103DF000DA0705D54FF0FF3202FA04F40C430894B9 -:103E0000089BC9F800302AE7402C2AD0611EC4F173 -:103E10002102A4F12103DDE9086526FA01F105FA82 -:103E200002F225FA03F311431943CB0711D50122FE -:103E3000A4F12003C4F1200102FA03F322FA01F1F4 -:103E4000A2400B43524263EB430332432B43CDE981 -:103E50000823DDE90823C9E9002300E76FF001002A -:103E6000FDE66FF00800FAE6082CA1D9102CB4D9B1 -:103E7000202CEED8C4E7BBF1000FAED0022384E7BC -:103E8000BBF1000FBCD004237FE70000012A30B54E -:103E9000144638BF012485B00025402C28BF40249B -:103EA000012ACDE9025518D81B788DF80830630730 -:103EB0000AD004AB624203EBD40502F0070215F806 -:103EC000083C934005F8083C034600912246002137 -:103ED00002A8FFF727FB05B030BD082AE4D9102A55 -:103EE00003D81B88ADF80830E1E7202A95BF1B688E -:103EF000D3E900230293CDE90223D8E710B5CB68BC -:103F00001BB98B600B618B8210BD04691A681C6041 -:103F10000361C38A013BC382CA60F0E703064CBF5A -:103F2000C0F3C0300220704708B50246FFF7F6FF25 -:103F3000022806D15306C2F30F2001D100F003007E -:103F400008BDC2F30740FBE72DE9F04F93B00446EC -:103F50000D46CDE903230A681046FFF7DFFF02286C -:103F6000824614BFC2F306260026002A80F2F3819F -:103F700012F0C04940F0EF81097B002900F0EB818D -:103F8000022803D02378B34240F0E881C2F30463EF -:103F900010462944069302F07F030593FFF7C4FF00 -:103FA000059B002283464FEA8348002348EA0A48DB -:103FB00048EA4668CE78CDE90823F30948EA0008C4 -:103FC000029368D0059B024608A9204600935346F9 -:103FD0006768B847002800F0C481276A4FB9414696 -:103FE00004F10C00FFF700FB074690B96FF00200E8 -:103FF00055E03B6998450DD03F68002FF9D1414607 -:1040000004F10C00FFF7F0FA07460028EED0236A0F -:104010003B60276297F817C006F01F08CCF3840CAA -:10402000ACEB0800A8EB0C031FFA80FE0028B8BF19 -:104030000EF120001FFA83FEB8BF00B2002B0793D9 -:10404000B8BF0EF12003D7E90221BCBF1BB2079312 -:1040500052EA010338D0039B4FF0000CDFF820E355 -:104060009A1A049B63EB010196457CEB01032BD369 -:104070006B7B97F81AE0734519D1029B002B78D01F -:10408000012821DC7868F8B9DFF8F0C2944570EBBC -:10409000010316D337E0276A27B96FF00C0013B07D -:1040A000BDE8F08F3B699845B4D03F68F4E7B3486A -:1040B00090427CEB010301D30020F0E7029B002B30 -:1040C000FAD0079B0F2B17DCFA7DB3003946204648 -:1040D00002F0030203F07C031343FB75FFF706FBBA -:1040E0006B7BBB76029B3BB9FB7DC3F38402013241 -:1040F00062F38603FB75D0E76A7BBB7E9A42DBD115 -:10410000029B002B35D0B309022B32D0039B142223 -:1041100000210DA8BB60049BFB60FDF761FC039BC5 -:104120000AA920460A93049BADF83EB00B932B1DC1 -:104130008DF840A00C932B7B8DF84180013BDBB2C6 -:10414000ADF83C30069B8DF84230059B8DF843302E -:1041500094F82C3083F001038DF84430A36898471D -:10416000FB7DC3F38403013303F01F039B02FB8237 -:10417000A2E7FB7DC6F34012B2EBD31F40F0F48000 -:10418000C3F38403434540F0F280029AB6092B7BC7 -:10419000002A4DD0F2075DD4032B40F2EB80039B45 -:1041A000AE1D394604F10C00BB603246049BFB6037 -:1041B0002B7B033BDBB2FFF7ABFA00280CDA394666 -:1041C0002046FFF793FAFB7DC3F38403013303F02A -:1041D0001F039B02FB8209E7AB88DDE908843B8370 -:1041E0004FF6FF73C9F12000A9F1200228FA09F166 -:1041F00009F1080904FA00F024FA02F20143184612 -:104200001143C9B2FFF7C6F9B9F1400F0346E9D12E -:10421000B88231462A7B033AD2B2FFF7CBF9FB7D55 -:10422000B882DA43C2F3C01262F3C713FB7543E7E7 -:1042300086B92E1D013B394604F10C00DBB2324633 -:10424000FFF766FA0028BADB2A7B3146B88A013AC2 -:10425000D2B2E2E7F98A013BC1F30901DAB20429DB -:104260005BD8281D002307F11B069A4208D910F8D5 -:1042700001CB013306F801C00131DBB20529F4D1CD -:10428000039993420A9138BF043304992CBF002349 -:1042900055FA83F30B9107F11B010C9179680E938A -:1042A0000D91291DFB8AADF83EB0C3F309038DF8CB -:1042B00040A08DF841801A44069B8DF84230059B42 -:1042C000ADF83C208DF8433094F82C3083F0010396 -:1042D0008DF844300023B88A7B602A7B013AFFF7CF -:1042E00069F93B8BB882834203D1A3680AA92046AF -:1042F000984720460AA9FFF701FEFB7DBA8AC3F35F -:104300008403013303F01F039B02FB823B8B9A4221 -:104310000CBF00206FF01000C1E67B68002BAFD00F -:10432000052001E01C3033461E68002EFAD1091A20 -:104330002E1D081D184401EB090C5FFA89F3BCF12E -:104340001B0F9DD89A429BD916F8013B09F1010930 -:1043500000F8013BEFE76FF00900A0E66FF00A00FC -:104360009DE66FF00B009AE66FF00D0097E66FF098 -:104370000E0094E66FF00F0091E600BF40420F0080 -:1043800080841E00EFF30983054968334A6B22F0ED -:1043900001024A6383F30988002383F3118870477D -:1043A00000EF00E0302080F3118862B60D4B0E4A1A -:1043B000D96821F4E0610904090C0A430B49DA6069 -:1043C000D3F8FC2042F08072C3F8FC20084AC2F8FF -:1043D000B01F116841F0010111602022DA7783F8E3 -:1043E0002200704700ED00E00003FA0555CEACC591 -:1043F000001000E0302310B583F311880E4B5B688A -:1044000013F4006314D0F1EE103AEFF309844FF087 -:104410008073683CE361094BDB6B236684F3098896 -:1044200001F0F2F910B1064BA36110BD054BFBE79B -:1044300083F31188F9E700BF00ED00E000EF00E032 -:104440003F0400084204000808B5074B074A1968F2 -:1044500001F03D01996053680BB190689847BDE841 -:104460000840FFF7C7BF00BF0000024054640020AF -:1044700008B5084B1968890901F03D018A019A6065 -:10448000054AD3680BB110699847BDE80840FFF7AB -:10449000B1BF00BF000002405464002008B5084BC3 -:1044A0001968090C01F03D010A049A60054A536934 -:1044B0000BB190699847BDE80840FFF79BBF00BF6C -:1044C000000002405464002008B5084B1968890DAB -:1044D00001F03D018A059A60054AD3690BB1106A63 -:1044E0009847BDE80840FFF785BF00BF00000240C5 -:1044F0005464002008B5074B074A596801F03D0194 -:10450000D960536A0BB1906A9847BDE80840FFF73D -:1045100071BF00BF000002405464002008B5084B82 -:104520005968890901F03D018A01DA60054AD36AB8 -:104530000BB1106B9847BDE80840FFF75BBF00BFA9 -:10454000000002405464002008B5084B5968090C6B -:1045500001F03D010A04DA60054A536B0BB1906B20 -:104560009847BDE80840FFF745BF00BF0000024084 -:104570005464002008B5084B5968890D01F03D01CD -:104580008A05DA60054AD36B0BB1106C9847BDE819 -:104590000840FFF72FBF00BF000002405464002016 -:1045A00008B5074B074A196801F03D019960536C43 -:1045B0000BB1906C9847BDE80840FFF71BBF00BFE8 -:1045C000000402405464002008B5084B19688909AA -:1045D00001F03D018A019A60054AD36C0BB1106D60 -:1045E0009847BDE80840FFF705BF00BF0004024040 -:1045F0005464002008B5084B1968090C01F03D010E -:104600000A049A60054A536D0BB1906D9847BDE856 -:104610000840FFF7EFBE00BF0004024054640020D2 -:1046200008B5084B1968890D01F03D018A059A60AB -:10463000054AD36D0BB1106E9847BDE80840FFF7EF -:10464000D9BE00BF000402405464002008B5074BE7 -:10465000074A596801F03D01D960536E0BB1906E65 -:104660009847BDE80840FFF7C5BE00BF0004024000 -:104670005464002008B5084B5968890901F03D01D0 -:104680008A01DA60054AD36E0BB1106F9847BDE816 -:104690000840FFF7AFBE00BF000402405464002092 -:1046A00008B5084B5968090C01F03D010A04DA60AD -:1046B000054A536F0BB1906F9847BDE80840FFF76C -:1046C00099BE00BF000402405464002008B5084BA6 -:1046D0005968890D01F03D018A05DA60054AD36FFA -:1046E00013B1D2F880009847BDE80840FFF782BEBA -:1046F000000402405464002000230C4910B51A46FF -:104700000B4C0B6054F82300026001EB43000433B0 -:104710004260402BF6D1074A4FF0FF339360D360DD -:10472000C2F80834C2F80C3410BD00BF5464002035 -:10473000487C0008000002400F28F8B510D9102866 -:1047400010D0112811D0122808D10F240720DFF82B -:10475000C8E00126DEF80050A04208D9002653E048 -:104760000446F4E70F240020F1E70724FBE706FAEC -:1047700000F73D424AD1264C4FEA001C3D4304EB72 -:1047800000160EEBC000CEF80050C0E90123FBB2CA -:1047900073B12048D0F8D83043F00103C0F8D830C6 -:1047A000D0F8003143F00103C0F80031D0F80031F7 -:1047B00017F47F4F0ED01748D0F8D83043F00203DB -:1047C000C0F8D830D0F8003143F00203C0F800310F -:1047D000D0F8003154F80C00036823F01F03036085 -:1047E000056815F00105FBD104EB0C033D2493F89B -:1047F0000CC05F6804FA0CF43C602124056044613D -:1048000012B1987B00F066F93046F8BD0130A3E79D -:10481000487C0008004402585464002010B530243D -:1048200084F31188FFF788FF002383F3118810BDFC -:1048300010B50446807B00F063F901231549627BC3 -:1048400003FA02F20B6823EA0203DAB20B6072B9D0 -:10485000114AD2F8D81021F00101C2F8D810D2F8CC -:10486000001121F00101C2F80011D2F8002113F467 -:104870007F4F0ED1084BD3F8D82022F00202C3F8A4 -:10488000D820D3F8002122F00202C3F80021D3F887 -:10489000003110BD546400200044025808B5302394 -:1048A00083F31188FFF7C4FF002383F3118808BD49 -:1048B000026843681143016003B118477047000064 -:1048C000024A136843F0C003136070470078004049 -:1048D00013B50E4C204600F0BDFA04F1140000237D -:1048E0004FF400720A49009400F07AF9094B4FF432 -:1048F0000072094904F13800009400F0F3F9074A06 -:10490000074BC4E9172302B010BD00BFD8640020D4 -:1049100044650020C148000844670020007800403A -:1049200000E1F505037C30B5244C002918BF0C4686 -:10493000012B11D1224B98420ED1224BD3F8E82003 -:1049400042F08042C3F8E820D3F8102142F08042C0 -:10495000C3F81021D3F810312268036EC16D03EB48 -:1049600052038466B3FBF2F36268150442BF23F07E -:10497000070503F0070343EA4503CB60A36843F050 -:1049800040034B60E36843F001038B6042F496738D -:1049900043F001030B604FF0FF330B62510505D567 -:1049A00012F0102205D0B2F1805F04D080F864309C -:1049B00030BD7F23FAE73F23F8E700BF487D0008BA -:1049C000D8640020004402582DE9F047C66D054622 -:1049D0003768F469210734621AD014F0080118BF4F -:1049E0004FF48071E20748BF41F02001A3074FF068 -:1049F000300348BF41F04001600748BF41F08001EB -:104A000083F31188281DFFF753FF002383F31188D8 -:104A1000E2050AD5302383F311884FF48061281D05 -:104A2000FFF746FF002383F311884FF030094FF062 -:104A3000000A14F0200838D13B0616D54FF0300993 -:104A400005F1380A200610D589F31188504600F088 -:104A50007DF9002836DA0821281DFFF729FF27F005 -:104A600080033360002383F31188790614D562062E -:104A700012D5302383F31188D5E913239A4208D144 -:104A80002B6C33B127F040071021281DFFF710FFD2 -:104A90003760002383F31188E30618D5AA6E1369E3 -:104AA000ABB15069BDE8F047184789F31188736AC4 -:104AB000284695F86410194000F0E6F98AF3118849 -:104AC000F469B6E7B06288F31188F469BAE7BDE823 -:104AD000F0870000090100F16043012203F5614302 -:104AE000C9B283F8001300F01F039A4043099B00EA -:104AF00003F1604303F56143C3F880211A607047F6 -:104B000000F01F0301229A40430900F160409B001E -:104B100000F5614003F1604303F56143C3F8802071 -:104B2000C3F88021002380F800337047F8B515469C -:104B3000826804460B46AA4200D28568A1692669AC -:104B4000761AB5420BD218462A46FCF723FFA36912 -:104B50002B44A3612846A3685B1BA360F8BD0CD956 -:104B6000AF1B18463246FCF715FF3A46E168304461 -:104B7000FCF710FFE3683B44EBE718462A46FCF7D6 -:104B800009FFE368E5E7000083689342F7B5044650 -:104B9000154600D28568D4E90460361AB5420BD2B6 -:104BA0002A46FCF7F7FE63692B4463612846A36835 -:104BB0005B1BA36003B0F0BD0DD93246AF1B019162 -:104BC000FCF7E8FE01993A46E0683144FCF7E2FE62 -:104BD000E3683B44E9E72A46FCF7DCFEE368E4E7E8 -:104BE00010B50A440024C361029B8460C160026165 -:104BF0000362C0E90000C0E9051110BD08B5D0E9A5 -:104C00000532934201D1826882B9826801328260A2 -:104C10005A1C426119700021D0E904329A4224BF23 -:104C2000C368436100F09CFE002008BD4FF0FF30D8 -:104C3000FBE7000070B5302304460E4683F311886D -:104C4000A568A5B1A368A269013BA360531CA36139 -:104C500015782269934224BFE368A361E3690BB12D -:104C600020469847002383F31188284607E0314601 -:104C7000204600F065FE0028E2DA85F3118870BD59 -:104C80002DE9F74F04460E4617469846D0F81C907B -:104C90004FF0300A8AF311884FF0000B154665B1CA -:104CA0002A4631462046FFF741FF034660B9414698 -:104CB000204600F045FE0028F1D0002383F3118840 -:104CC000781B03B0BDE8F08FB9F1000F03D001905D -:104CD0002046C847019B8BF31188ED1A1E448AF3C6 -:104CE0001188DCE7C160C361009B82600362C0E998 -:104CF00005111144C0E9000001617047F8B5044690 -:104D00000D461646302383F31188A768A7B1A36820 -:104D1000013BA36063695A1C62611D70D4E90432CF -:104D20009A4224BFE3686361E3690BB12046984768 -:104D3000002080F3118807E03146204600F000FE95 -:104D40000028E2DA87F31188F8BD0000D0E90523D6 -:104D500010B59A4201D182687AB982680021013285 -:104D600082605A1C82611C7803699A4224BFC3681E -:104D7000836100F0F5FD204610BD4FF0FF30FBE7EA -:104D80002DE9F74F04460E4617469846D0F81C907A -:104D90004FF0300A8AF311884FF0000B154665B1C9 -:104DA0002A4631462046FFF7EFFE034660B94146EA -:104DB000204600F0C5FD0028F1D0002383F31188C0 -:104DC000781B03B0BDE8F08FB9F1000F03D001905C -:104DD0002046C847019B8BF31188ED1A1E448AF3C5 -:104DE0001188DCE7026843681143016003B118478A -:104DF000704700001430FFF743BF00004FF0FF334F -:104E00001430FFF73DBF00003830FFF7B9BF000096 -:104E10004FF0FF333830FFF7B3BF00001430FFF717 -:104E200009BF00004FF0FF311430FFF703BF00004F -:104E30003830FFF763BF00004FF0FF323830FFF724 -:104E40005DBF0000012914BF6FF013000020704700 -:104E5000FFF73EBD044B036000234360C0E902330B -:104E600001230374704700BF607D000810B5302334 -:104E7000044683F31188FFF755FD022300202374B5 -:104E800080F3118810BD000038B5C36904460D4693 -:104E90001BB904210844FFF7A5FF294604F11400BB -:104EA000FFF7ACFE002806DA201D4FF40061BDE8D4 -:104EB0003840FFF797BF38BD02684368114301606F -:104EC00003B118477047000013B5406B00F58054DC -:104ED000D4F8A4381A681178042914D1017C022965 -:104EE00011D11979012312898B4013420BD101A9E9 -:104EF0004C3002F0F7F8D4F8A4480246019B21791F -:104F0000206800F0DFF902B010BD0000143002F09C -:104F100079B800004FF0FF33143002F073B800008E -:104F20004C3002F04BB900004FF0FF334C3002F030 -:104F300045B90000143002F047B800004FF0FF31CF -:104F4000143002F041B800004C3002F017B90000F4 -:104F50004FF0FF324C3002F011B9000000207047D2 -:104F600010B500F58054D4F8A4381A6811780429D3 -:104F700017D1017C022914D15979012352898B4020 -:104F800013420ED1143001F0D9FF024648B1D4F8D3 -:104F9000A4484FF4407361792068BDE8104000F0E8 -:104FA0007FB910BD406BFFF7DBBF0000704700000A -:104FB0007FB5124B012504260446036000230574C7 -:104FC00000F1840243602946C0E902330C4B029091 -:104FD000143001934FF44073009601F08BFF094B9E -:104FE00004F69442294604F14C000294CDE9006392 -:104FF0004FF4407302F052F804B070BD887D000891 -:10500000A54F0008C94E00080A68302383F31188B1 -:105010000B790B3342F823004B79133342F823000A -:105020008B7913B10B3342F8230000F58053C3F89A -:10503000A41802230374002080F311887047000035 -:1050400038B5037F044613B190F85430ABB901254D -:10505000201D0221FFF730FF04F114006FF0010161 -:10506000257700F089FC04F14C0084F854506FF06F -:105070000101BDE8384000F07FBC38BD10B501210A -:1050800004460430FFF718FF0023237784F85430D8 -:1050900010BD000038B504460025143001F042FF71 -:1050A00004F14C00257702F011F8201D84F85450CB -:1050B0000121FFF701FF2046BDE83840FFF750BF50 -:1050C00090F8803003F06003202B06D190F8812007 -:1050D0000023212A03D81F2A06D800207047222A3D -:1050E000FBD1C0E91D3303E0034A42670722826710 -:1050F000C3670120704700BF3C23002037B500F58F -:105100008055D5F8A4381A68117804291AD1017C81 -:10511000022917D11979012312898B40134211D129 -:1051200000F14C04204602F091F858B101A9204644 -:1051300001F0D8FFD5F8A4480246019B21792068E8 -:1051400000F0C0F803B030BD01F10B03F0B550F82A -:10515000236085B004460D46FEB1302383F31188E9 -:1051600004EB8507301D0821FFF7A6FEFB6806F15A -:105170004C005B691B681BB1019001F0C1FF0198F5 -:1051800003A901F0AFFF024648B1039B2946204620 -:1051900000F098F8002383F3118805B0F0BDFB6898 -:1051A0005A691268002AF5D01B8A013B1340F1D1DD -:1051B00004F18002EAE70000133138B550F82140CD -:1051C000ECB1302383F3118804F58053D3F8A4287D -:1051D0001368527903EB8203DB689B695D6845B114 -:1051E00004216018FFF768FE294604F1140001F05D -:1051F000AFFE2046FFF7B4FE002383F3118838BDCD -:105200007047000001F07CB901234022002110B555 -:10521000044600F8303BFCF7E3FB0023C4E901330C -:1052200010BD000010B53023044683F311882422FA -:10523000416000210C30FCF7D3FB204601F082F9DD -:1052400002230020237080F3118810BD70B500EB9D -:105250008103054650690E461446DA6018B11022E3 -:105260000021FCF7BDFBA06918B110220021FCF75A -:10527000B7FB31462846BDE8704001F069BA00002E -:1052800083682022002103F0011310B504468360D7 -:105290001030FCF7A5FB2046BDE8104001F0E4BA51 -:1052A000F0B4012500EB810447898D40E4683D435B -:1052B000A469458123600023A2606360F0BC01F013 -:1052C00001BB0000F0B4012500EB810407898D408B -:1052D000E4683D436469058123600023A260636044 -:1052E000F0BC01F077BB000070B502230025044636 -:1052F000242203702946C0F888500C3040F8045C22 -:10530000FCF76EFB204684F8705001F0B5F9636835 -:105310001B6823B129462046BDE87040184770BD80 -:105320000378052B10B504460AD080F88C3005238D -:10533000037043681B680BB1042198470023A360E6 -:1053400010BD00000178052906D190F88C20436833 -:1053500002701B6803B118477047000070B590F8E1 -:105360007030044613B1002380F8703004F18002DD -:10537000204601F09DFA63689B68B3B994F88030C9 -:1053800013F0600535D00021204601F08FFD00218B -:10539000204601F07FFD63681B6813B1062120469B -:1053A0009847062384F8703070BD2046984700283F -:1053B000E4D0B4F88630A26F9A4288BFA36794F90C -:1053C0008030A56F002B4FF0300380F20381002D59 -:1053D00000F0F280092284F8702083F31188002104 -:1053E0002046D4E91D23FFF76DFF002383F31188C6 -:1053F000DAE794F8812003F07F0343EA022340F2C6 -:105400000232934200F0C58021D8B3F5807F48D0A6 -:105410000DD8012B3FD0022B00F09380002BB2D18E -:1054200004F1880262670222A267E367C1E7B3F56D -:10543000817F00F09B80B3F5407FA4D194F8823047 -:10544000012BA0D1B4F8883043F0020332E0B3F569 -:10545000006F4DD017D8B3F5A06F31D0A3F5C0635E -:10546000012B90D86368204694F882205E6894F8F7 -:105470008310B4F88430B047002884D04368636751 -:105480000368A3671AE0B3F5106F36D040F6024206 -:1054900093427FF478AF5C4B63670223A3670023DA -:1054A000C3E794F88230012B7FF46DAFB4F88830F5 -:1054B00023F00203A4F88830C4E91D55E56778E7B6 -:1054C000B4F88030B3F5A06F0ED194F88230204646 -:1054D00084F88A3001F02EF963681B6813B101214A -:1054E00020469847032323700023C4E91D339CE71B -:1054F00004F18B0363670123C3E72378042B10D1E6 -:10550000302383F311882046FFF7BAFE85F3118814 -:105510000321636884F88B5021701B680BB120460F -:10552000984794F88230002BDED084F88B30042327 -:10553000237063681B68002BD6D002212046984751 -:10554000D2E794F8843020461D0603F00F010AD5F7 -:1055500001F0A0F9012804D002287FF414AF2B4BEE -:105560009AE72B4B98E701F087F9F3E794F882303C -:10557000002B7FF408AF94F8843013F00F01B3D000 -:105580001A06204602D501F0A9FCADE701F09AFC0D -:10559000AAE794F88230002B7FF4F5AE94F88430BB -:1055A00013F00F01A0D01B06204602D501F07EFCAF -:1055B0009AE701F06FFC97E7142284F8702083F3D8 -:1055C00011882B462A4629462046FFF769FE85F3B7 -:1055D0001188E9E65DB1152284F8702083F3118803 -:1055E00000212046D4E91D23FFF75AFEFDE60B22D9 -:1055F00084F8702083F311882B462A4629462046DA -:10560000FFF760FEE3E700BFB87D0008B07D00084B -:10561000B47D000838B590F870300446002B3ED0B9 -:10562000063BDAB20F2A34D80F2B32D8DFE803F06A -:10563000373131082232313131313131313137377F -:10564000856FB0F886309D4214D2C3681B8AB5FBC3 -:10565000F3F203FB12556DB9302383F311882B4607 -:105660002A462946FFF72EFE85F311880A2384F87F -:1056700070300EE0142384F87030302383F31188E7 -:10568000002320461A461946FFF70AFE002383F33B -:10569000118838BDC36F03B198470023E7E70021A5 -:1056A000204601F003FC0021204601F0F3FB636873 -:1056B0001B6813B10621204698470623D7E7000050 -:1056C00010B590F870300446142B29D017D8062B4B -:1056D00005D001D81BB110BD093B022BFBD800211E -:1056E000204601F0E3FB0021204601F0D3FB636874 -:1056F0001B6813B1062120469847062319E0152B95 -:10570000E9D10B2380F87030302383F31188002314 -:105710001A461946FFF7D6FD002383F31188DAE70E -:10572000C3689B695B68002BD5D1C36F03B19847F1 -:10573000002384F87030CEE7002382680375036984 -:105740001B6899689142FBD25A68036042601060FE -:105750005860704700238268037503691B68996865 -:105760009142FBD85A6803604260106058607047ED -:1057700008B50846302383F311880B7D032B05D031 -:10578000042B0DD02BB983F3118808BD8B6900223F -:105790001A604FF0FF338361FFF7CEFF0023F2E77B -:1057A000D1E9003213605A60F3E70000FFF7C4BF8D -:1057B000054BD96808751868026853601A600122A1 -:1057C000D8600275FAF726BE486900200C4B30B548 -:1057D000DD684B1C87B004460FD02B46094A68464B -:1057E00000F05EF92046FFF7E3FF009B13B1684627 -:1057F00000F060F9A86907B030BDFFF7D9FFF9E7FD -:105800004869002071570008044B1A68DB689068EB -:105810009B68984294BF002001207047486900208F -:10582000084B10B51C68D868226853601A600122C2 -:10583000DC602275FFF78EFF01462046BDE8104070 -:10584000FAF7E8BD4869002038B5074C0123002568 -:10585000064907482370656001F036FD0223237076 -:1058600085F3118838BD00BFB06B0020C07D0008F3 -:105870004869002008B572B6044B186500F064FC56 -:1058800000F02AFD024B03221A70FEE7486900204F -:10589000B06B002000F044B9034A516853685B1AAA -:1058A0009842FBD8704700BF001000E08B600223D5 -:1058B000086108468B8270478368A3F1840243F82D -:1058C000142C026943F8442C426943F8402C094ADD -:1058D00043F8242CC268A3F1200043F8182C0222BC -:1058E00003F80C2C002203F80B2C034A43F8102C6D -:1058F000704700BF2D0400084869002008B5FFF775 -:10590000DBFFBDE80840FFF751BF0000024BDB683A -:1059100098610F20FFF74CBF48690020302383F3C4 -:105920001188FFF7F3BF000008B50146302383F369 -:1059300011880820FFF74AFF002383F3118808BD70 -:10594000064BDB6839B1426818605A6013604360E7 -:105950000420FFF73BBF4FF0FF307047486900203D -:105960000368984206D01A68026050601846996130 -:10597000FFF71CBF7047000038B504460D4620688D -:10598000844200D138BD036823605C608561FFF705 -:105990000DFFF4E7036810B59C68A2420CD85C6860 -:1059A0008A600B604C602160596099688A1A9A601D -:1059B0004FF0FF33836010BD121B1B68ECE7000043 -:1059C0000A2938BF0A2170B504460D460A26601917 -:1059D00001F072FC01F05AFC041BA54203D8751CAF -:1059E00004462E46F3E70A2E04D90120BDE8704094 -:1059F00001F0AABC70BD0000F8B5144B0D460A2A90 -:105A00004FF00A07D96103F11001826038BF0A2202 -:105A1000416019691446016048601861A81801F0D6 -:105A20003BFC01F033FC431B0646A34206D37C1C1F -:105A300028192746354601F03FFCF2E70A2F04D922 -:105A40000120BDE8F84001F07FBCF8BD48690020A6 -:105A5000F8B506460D4601F019FC0F4A134653F8F7 -:105A6000107F9F4206D12A4601463046BDE8F840E5 -:105A7000FFF7C2BFD169BB68441A2C1928BF2C4656 -:105A8000A34202D92946FFF79BFF2246314603482D -:105A9000BDE8F840FFF77EBF486900205869002044 -:105AA000C0E90323002310B45DF8044B4361FFF702 -:105AB000CFBF000010B5194C236998420DD0816802 -:105AC000D0E9003213605A609A680A449A60002351 -:105AD00003604FF0FF33A36110BD0268234643F813 -:105AE000102F53600022026022699A4203D1BDE860 -:105AF000104001F0DBBB936881680B44936001F0B8 -:105B0000C5FB2269E1699268441AA242E4D91144B2 -:105B1000BDE81040091AFFF753BF00BF48690020D5 -:105B20002DE9F047DFF8BC8008F110072C4ED8F8BB -:105B3000105001F0ABFBD8F81C40AA68031B9A4236 -:105B40003ED814444FF00009D5E90032C8F81C4093 -:105B500013605A60C5F80090D8F81030B34201D1F4 -:105B600001F0A4FB89F31188D5E903312846984751 -:105B7000302383F311886B69002BD8D001F086FBAA -:105B80006A69A0EB040982464A450DD2022001F061 -:105B9000DBFB0022D8F81030B34208D1514628462A -:105BA000BDE8F047FFF728BF121A2244F2E712EBD4 -:105BB00009092946384638BF4A46FFF7EBFEB5E7E4 -:105BC000D8F81030B34208D01444C8F81C00211A89 -:105BD000A960BDE8F047FFF7F3BEBDE8F08700BF5E -:105BE000586900204869002038B501F04FFB054A8C -:105BF000D2E90845031B181945F10001C2E9080163 -:105C000038BD00BF4869002000207047FEE7000053 -:105C1000704700004FF0FF307047000002290CD0A1 -:105C2000032904D00129074818BF00207047032A20 -:105C300005D8054800EBC2007047044870470020B3 -:105C4000704700BF987E00084C2300204C7E00085F -:105C500070B59AB005460846144601A900F0C2F88E -:105C600001A8FBF7B5FE431C0022C6B25B0010463C -:105C7000C5E9003423700323023404F8013C01AB6E -:105C8000D1B202348E4201D81AB070BD13F8011B94 -:105C9000013204F8010C04F8021CF1E708B53023C6 -:105CA00083F311880348FFF729FA002383F311884F -:105CB00008BD00BFB86B002090F8803003F01F02D1 -:105CC000012A07D190F881200B2A03D10023C0E9D3 -:105CD0001D3315E003F06003202B08D1B0F88430A9 -:105CE0002BB990F88120212A03D81F2A04D8FFF766 -:105CF000E7B9222AEBD0FAE7034A42670722826714 -:105D0000C3670120704700BF4323002007B5052962 -:105D100017D8DFE801F0191603191920302383F38F -:105D20001188104A01210190FFF790FA0198022191 -:105D30000D4AFFF78BFA0D48FFF7ACF9002383F308 -:105D4000118803B05DF804FB302383F31188074802 -:105D5000FFF776F9F2E7302383F311880348FFF762 -:105D60008DF9EBE7EC7D0008107E0008B86B002091 -:105D700038B50C4D0C4C2A460C4904F10800FFF7CD -:105D800067FF05F1CA0204F110000949FFF760FF3F -:105D900005F5CA7204F118000649BDE83840FFF75E -:105DA00057BF00BF908400204C230020CC7D00080A -:105DB000D67D0008E17D000870B5044608460D4612 -:105DC000FBF706FEC6B22046013403780BB918462D -:105DD00070BD32462946FBF7E7FD0028F3D10120CC -:105DE000F6E700002DE9F04705460C46FBF7F0FD0D -:105DF0002C49C6B22846FFF7DFFF08B11036F6B2CD -:105E000029492846FFF7D8FF08B11036F6B2632EAD -:105E10000BD8DFF89080DFF89090244FDFF898A03F -:105E20002E7846B92670BDE8F08729462046BDE8A1 -:105E3000F04701F06DBE252E30D10722414628469D -:105E4000FBF7B2FD80B91A4B224603F1140153F857 -:105E5000040B8B4242F8040BF9D1198807359B7863 -:105E6000173411809370DBE7082249462846FBF778 -:105E70009BFD98B9A21C0F4B197802320909C95D24 -:105E800002F8041C13F8011B01F00F015345C95D12 -:105E900002F8031CF0D118340835C1E7013504F8C5 -:105EA000016BBDE7B87E0008E17D0008C07E0008F8 -:105EB0002E7B000800E8F11F0CE8F11FBFF34F8FA5 -:105EC000044B1A695107FCD1D3F810215207F8D1BD -:105ED000704700BF0020005208B50D4B1B78ABB9CE -:105EE000FFF7ECFF0B4BDA68D10704D50A4A5A607A -:105EF00002F188325A60D3F80C21D20706D5064A3F -:105F0000C3F8042102F18832C3F8042108BD00BFA0 -:105F1000EE860020002000522301674508B5114B92 -:105F20001B78F3B9104B1A69510703D5DA6842F0B0 -:105F30004002DA60D3F81021520705D5D3F80C21BE -:105F400042F04002C3F80C21FFF7B8FF064BDA68B5 -:105F500042F00102DA60D3F80C2142F00102C3F8EA -:105F60000C2108BDEE860020002000520F289ABFA9 -:105F700000F5806040040020704700004FF40030BE -:105F800070470000102070470F2808B50BD8FFF7A6 -:105F9000EDFF00F500330268013204D10430834282 -:105FA000F9D1012008BD0020FCE700000F2838B51A -:105FB00005463FD8FFF782FF1F4CFFF78DFF4FF0DC -:105FC000FF3307286361C4F814311DD82361FFF73C -:105FD00075FF030243F02403E360E36843F08003AA -:105FE000E36023695A07FCD42846FFF767FFFFF7F1 -:105FF000BDFF4FF4003100F04BF92846FFF78EFF4C -:10600000BDE83840FFF7C0BFC4F81031FFF756FFB6 -:10601000A0F108031B0243F02403C4F80C31D4F8A8 -:106020000C3143F08003C4F80C31D4F810315B0715 -:10603000FBD4D9E7002038BD002000522DE9F84FED -:1060400005460C46104645EA0203DE0602D0002053 -:10605000BDE8F88F20F01F00DFF8BCB0DFF8BCA06F -:10606000FFF73AFF04EB0008444503D10120FFF796 -:1060700055FFEDE720222946204601F017FD10B913 -:1060800020352034F0E72B4605F120021F68791CEB -:10609000DDD104339A42F9D105F178431B481C4EF7 -:1060A000B3F5801F1B4B38BF184603F1F80332BF0E -:1060B000D946D1461E46FFF701FF0760A5EB040C49 -:1060C000336804F11C0143F002033360231FD9F845 -:1060D000007017F00507FAD153F8042F8B424CF8E3 -:1060E0000320F4D1BFF34F8FFFF7E8FE4FF0FF33EB -:1060F0002022214603602846336823F002033360E0 -:1061000001F0D4FC0028BBD03846B0E7142100527F -:106110000C20005214200052102000521021005276 -:1061200010B5084C237828B11BB9FFF7D5FE012321 -:10613000237010BD002BFCD02070BDE81040FFF78D -:10614000EDBE00BFEE86002038B5054D00240334B7 -:10615000696855F80C0B00F0ADF8122CF7D138BD7A -:10616000D47E0008084601F099BC000038B5EFF372 -:1061700011859DB9EFF30584C4F30804302334B1CD -:1061800083F31188FFF730FD85F3118838BD83F361 -:106190001188FFF729FD84F3118838BDBDE8384028 -:1061A000FFF722BD10B5FFF7E1FF104CC008104A01 -:1061B000002340EA4170C908A0FB04ECA0FB020EDA -:1061C0001CEB0000A1FB044CA1FB02125B41001977 -:1061D00043EB0C0011EB0E0142F10002411842F1B9 -:1061E0000000090941EA007010BD00BFCFF753E37A -:1061F000A59BC4200244074BD2B210B5904200D1F7 -:1062000010BD441C00B253F8200041F8040BE0B26A -:10621000F4E700BF504000580E4B30B51C6F24040B -:1062200005D41C6F1C671C6F44F400441C670A4CA7 -:1062300002442368D2B243F480732360074B904238 -:1062400000D130BD441C51F8045B00B243F820502B -:10625000E0B2F4E7004402580048025850400058A9 -:1062600007B5012201A90020FFF7C4FF019803B080 -:106270005DF804FB13B50446FFF7F2FFA04205D01A -:10628000012201A900200194FFF7C6FF02B010BD52 -:106290000144BFF34F8F064B884204D3BFF34F8FA7 -:1062A000BFF36F8F7047C3F85C022030F4E700BF84 -:1062B00000ED00E00144BFF34F8F064B884204D34A -:1062C000BFF34F8FBFF36F8F7047C3F8700220305A -:1062D000F4E700BF00ED00E070470000074B45F217 -:1062E00055521A6002225A6040F6FF729A604CF6CC -:1062F000CC421A600122024B1A70704700480058C5 -:10630000F4860020034B1B781BB1034B4AF6AA22EC -:106310001A607047F486002000480058034B1A6842 -:106320001AB9034AD2F8D0241A607047F0860020C8 -:1063300000400258024B4FF48032C3F8D02470471B -:106340000040025808B5FFF7E9FF024B1868C0F398 -:10635000806008BDF086002070B5BFF34F8FBFF39B -:106360006F8F1A4A0021C2F85012BFF34F8FBFF34C -:106370006F8F536943F400335361BFF34F8FBFF303 -:106380006F8FC2F88410BFF34F8FD2F8803043F67E -:10639000E074C3F3C900C3F34E335B0103EA0406A0 -:1063A000014646EA81750139C2F86052F9D2203BB4 -:1063B00013F1200FF2D1BFF34F8F536943F48033B1 -:1063C0005361BFF34F8FBFF36F8F70BD00ED00E0DF -:1063D000FEE70000214B2248224A70B5904237D395 -:1063E000214BC11EDA1C121A22F003028B4238BF65 -:1063F00000220021FBF7F4FA1C4A0023C2F8843083 -:10640000BFF34F8FD2F8803043F6E074C3F3C90076 -:10641000C3F34E335B0103EA0406014646EA817585 -:106420000139C2F86C52F9D2203B13F1200FF2D19E -:10643000BFF34F8FBFF36F8FBFF34F8FBFF36F8FDC -:106440000023C2F85032BFF34F8FBFF36F8F70BD80 -:1064500053F8041B40F8041BC0E700BF6881000824 -:10646000C8880020C8880020C888002000ED00E00F -:10647000074BD3F8D81021EA0001C3F8D810D3F89D -:10648000002122EA0002C3F80021D3F8003170474E -:106490000044025870B5D0E9244300224FF0FF3584 -:1064A0009E6804EB42135101D3F80009002805DA75 -:1064B000D3F8000940F08040C3F80009D3F8000B7E -:1064C000002805DAD3F8000B40F08040C3F8000B39 -:1064D000013263189642C3F80859C3F8085BE0D24A -:1064E0004FF00113C4F81C3870BD0000890141F061 -:1064F0002001016103699B06FCD41220FFF7CCB98F -:1065000010B50A4C2046FEF77FFE094BC4F89030C8 -:10651000084BC4F89430084C2046FEF775FE074B34 -:10652000C4F89030064BC4F8943010BDF8860020B3 -:1065300000000840407F00089487002000000440CD -:106540004C7F000870B503780546012B5CD1434BA6 -:10655000D0F89040984258D1414B0E216520D3F895 -:10656000D82042F00062C3F8D820D3F8002142F0CE -:106570000062C3F80021D3F80021D3F8802042F054 -:106580000062C3F88020D3F8802022F00062C3F8B4 -:106590008020D3F88030FEF79DFA324BE360324B17 -:1065A000C4F800380023D5F89060C4F8003EC0233A -:1065B00023604FF40413A3633369002BFCDA012337 -:1065C0000C203361FFF768F93369DB07FCD4122034 -:1065D000FFF762F93369002BFCDA00262846A66033 -:1065E000FFF758FF6B68C4F81068DB68C4F81468DC -:1065F000C4F81C6883BB1D4BA3614FF0FF3363617C -:10660000A36843F00103A36070BD194B9842C9D140 -:10661000134B4FF08060D3F8D82042F00072C3F8DB -:10662000D820D3F8002142F00072C3F80021D3F83B -:106630000021D3F8802042F00072C3F88020D3F804 -:10664000802022F00072C3F88020D3F88030FFF75A -:106650000FFF0E214D209EE7064BCDE7F886002068 -:10666000004402584014004003002002003C30C0A7 -:1066700094870020083C30C0F8B5D0F8904005461B -:1066800000214FF000662046FFF730FFD5F8941048 -:1066900000234FF001128F684FF0FF30C4F83438F8 -:1066A000C4F81C2804EB431201339F42C2F800696E -:1066B000C2F8006BC2F80809C2F8080BF2D20B68E6 -:1066C000D5F89020C5F898306362102313611669DD -:1066D00016F01006FBD11220FFF7DEF8D4F80038D0 -:1066E00023F4FE63C4F80038A36943F4402343F065 -:1066F0001003A3610923C4F81038C4F814380B4BF5 -:10670000EB604FF0C043C4F8103B094BC4F8003BAA -:10671000C4F81069C4F80039D5F8983003F11002B4 -:1067200043F48013C5F89820A362F8BD1C7F0008CD -:1067300040800010D0F8902090F88A10D2F80038ED -:1067400023F4FE6343EA0113C2F8003870470000E7 -:106750002DE9F84300EB8103D0F890500C468046B9 -:10676000DA680FFA81F94801166806F00306731E0D -:10677000022B05EB41134FF0000194BFB604384ED5 -:10678000C3F8101B4FF0010104F1100398BF06F18C -:10679000805601FA03F3916998BF06F50046002977 -:1067A0003AD0578A04F15801374349016F50D5F860 -:1067B0001C180B430021C5F81C382B180127C3F8FF -:1067C0001019A7405369611E9BB3138A928B9B08D3 -:1067D000012A88BF5343D8F89820981842EA034307 -:1067E00001F140022146C8F89800284605EB8202D4 -:1067F0005360FFF77BFE08EB8900C3681B8A43EAFE -:10680000845348341E4364012E51D5F81C381F436D -:10681000C5F81C78BDE8F88305EB4917D7F8001BCD -:1068200021F40041C7F8001BD5F81C1821EA030326 -:10683000C0E704F13F030B4A2846214605EB8303DA -:106840005A60FFF753FE05EB4910D0F8003923F4E6 -:106850000043C0F80039D5F81C3823EA0707D7E70A -:106860000080001000040002D0F894201268C0F8E4 -:106870009820FFF70FBE00005831D0F89030490142 -:106880005B5813F4004004D013F4001F0CBF022027 -:10689000012070474831D0F8903049015B5813F41B -:1068A000004004D013F4001F0CBF022001207047E9 -:1068B00000EB8101CB68196A0B6813604B68536069 -:1068C0007047000000EB810330B5DD68AA691368EA -:1068D000D36019B9402B84BF402313606B8A1468BE -:1068E000D0F890201C4402EB4110013C09B2B4FBEB -:1068F000F3F46343033323F0030343EAC44343F055 -:10690000C043C0F8103B2B6803F00303012B0ED1EA -:10691000D2F8083802EB411013F4807FD0F8003B26 -:1069200014BF43F0805343F00053C0F8003B02EB28 -:106930004112D2F8003B43F00443C2F8003B30BDA3 -:106940002DE9F041D0F8906005460C4606EB411366 -:10695000D3F8087B3A07C3F8087B08D5D6F8143873 -:106960001B0704D500EB8103DB685B689847FA07D7 -:106970001FD5D6F81438DB071BD505EB8403D9687F -:10698000CCB98B69488A5A68B2FBF0F600FB162234 -:106990008AB91868DA6890420DD2121AC3E9002445 -:1069A000302383F3118821462846FFF78BFF84F3B9 -:1069B0001188BDE8F081012303FA04F26B8923EA10 -:1069C00002036B81CB68002BF3D021462846BDE83B -:1069D000F041184700EB81034A0170B5DD68D0F83B -:1069E00090306C692668E66056BB1A444FF400206C -:1069F000C2F810092A6802F00302012A0AB20ED175 -:106A0000D3F8080803EB421410F4807FD4F800098F -:106A100014BF40F0805040F00050C4F8000903EB70 -:106A20004212D2F8000940F00440C2F800090122E5 -:106A3000D3F8340802FA01F10143C3F8341870BDE9 -:106A400019B9402E84BF4020206020681A442E8A45 -:106A50008419013CB4FBF6F440EAC44040F0005015 -:106A6000C6E700002DE9F843D0F8906005460C46D3 -:106A70004F0106EB4113D3F8088918F0010FC3F852 -:106A800008891CD0D6F81038DB0718D500EB810335 -:106A9000D3F80CC0DCF81430D3F800E0DA6896457F -:106AA00030D2A2EB0E024FF000091A60C3F8049036 -:106AB000302383F31188FFF78DFF89F3118818F0D5 -:106AC000800F1DD0D6F834380126A640334217D0A7 -:106AD00005EB84030134D5F89050D3F80CC0E4B230 -:106AE0002F44DCF8142005EB0434D2F800E05168A0 -:106AF000714514D3D5F8343823EA0606C5F834684E -:106B0000BDE8F883012303FA01F2038923EA0203B3 -:106B10000381DCF80830002BD1D09847CFE7AEEBEB -:106B20000103BCF81000834228BF0346D7F81809B8 -:106B300080B2B3EB800FE3D89068A0F1040959F854 -:106B4000048FC4F80080A0EB09089844B8F1040F42 -:106B5000F5D818440B4490605360C8E72DE9F84F0E -:106B6000D0F8905004466E69AB691E4016F4805808 -:106B70006E6103D0BDE8F84FFEF7B6BB002E12DA07 -:106B8000D5F8003E9B0705D0D5F8003E23F003035F -:106B9000C5F8003ED5F80438204623F00103C5F8B7 -:106BA0000438FEF7CFFB370505D52046FFF772FC0A -:106BB0002046FEF7B5FBB0040CD5D5F8083813F025 -:106BC000060FEB6823F470530CBF43F4105343F4E7 -:106BD000A053EB6031071BD56368DB681BB9AB6959 -:106BE00023F00803AB612378052B0CD1D5F8003EC8 -:106BF0009A0705D0D5F8003E23F00303C5F8003E00 -:106C00002046FEF79FFB6368DB680BB12046984780 -:106C1000F30200F1BA80B70226D5D4F8909000278D -:106C20004FF0010A09EB4712D2F8003B03F440236E -:106C3000B3F5802F11D1D2F8003B002B0DDA628919 -:106C40000AFA07F322EA0303638104EB8703DB6894 -:106C5000DB6813B13946204698470137D4F89430A1 -:106C6000FFB29B689F42DDD9F00619D5D4F8900099 -:106C7000026AC2F30A1702F00F0302F4F012B2F52F -:106C8000802F00F0CA80B2F5402F09D104EB8303B6 -:106C9000002200F58050DB681B6A974240F0B0800C -:106CA0003003D5F8185835D5E90303D5002120461F -:106CB000FFF746FEAA0303D501212046FFF740FE59 -:106CC0006B0303D502212046FFF73AFE2F0303D5BD -:106CD00003212046FFF734FEE80203D504212046B5 -:106CE000FFF72EFEA90203D505212046FFF728FE57 -:106CF0006A0203D506212046FFF722FE2B0203D5A8 -:106D000007212046FFF71CFEEF0103D5082120468E -:106D1000FFF716FE700340F1A780E90703D50021B5 -:106D20002046FFF79FFEAA0703D501212046FFF763 -:106D300099FE6B0703D502212046FFF793FE2F072C -:106D400003D503212046FFF78DFEEE0603D504216F -:106D50002046FFF787FEA80603D505212046FFF74A -:106D600081FE690603D506212046FFF77BFE2A0631 -:106D700003D507212046FFF775FEEB0574D52046A5 -:106D80000821BDE8F84FFFF76DBED4F890904FF0A2 -:106D9000000B4FF0010AD4F894305FFA8BF79B6830 -:106DA0009F423FF638AF09EB4713D3F8002902F4AE -:106DB0004022B2F5802F20D1D3F80029002A1CDA16 -:106DC000D3F8002942F09042C3F80029D3F80029F3 -:106DD000002AFBDB3946D4F89000FFF787FB2289B5 -:106DE0000AFA07F322EA0303238104EB8703DB6833 -:106DF0009B6813B13946204698470BF1010BCAE74F -:106E0000910701D1D0F80080072A02F101029CBF4E -:106E100003F8018B4FEA18283FE704EB830300F5E2 -:106E20008050DA68D2F818C0DCF80820DCE9001CD1 -:106E3000A1EB0C0C00218F4208D1DB689B699A689A -:106E40003A449A605A683A445A6029E711F0030FAD -:106E500001D1D0F800808C4501F1010184BF02F816 -:106E6000018B4FEA1828E6E7BDE8F88F08B503481C -:106E7000FFF774FEBDE80840FDF7BCBAF8860020B5 -:106E800008B50348FFF76AFEBDE80840FDF7B2BA4F -:106E900094870020D0F8903003EB4111D1F8003BEB -:106EA00043F40013C1F8003B70470000D0F8903065 -:106EB00003EB4111D1F8003943F40013C1F8003954 -:106EC00070470000D0F8903003EB4111D1F8003B3F -:106ED00023F40013C1F8003B70470000D0F8903055 -:106EE00003EB4111D1F8003923F40013C1F8003944 -:106EF0007047000030B50433039C0172002104FB8D -:106F00000325C160C0E90653049B0363059BC0E9E8 -:106F10000000C0E90422C0E90842C0E90A11436345 -:106F200030BD00000022416AC260C0E90411C0E91E -:106F30000A226FF00101FEF71FBD0000D0E9043204 -:106F4000934201D1C2680AB9181D704700207047EA -:106F5000036919600021C2680132C260C26913442A -:106F600082699342036124BF436A0361FEF7F8BC60 -:106F700038B504460D46E3683BB162690020131D35 -:106F80001268A3621344E36207E0237A33B9294607 -:106F90002046FEF7D5FC0028EDDA38BD6FF0010081 -:106FA000FBE70000C368C269013BC3604369134447 -:106FB00082699342436124BF436A43610023836231 -:106FC000036B03B11847704770B53023044683F351 -:106FD0001188866A3EB9FFF7CBFF054618B186F3E4 -:106FE0001188284670BDA36AE26A13F8015B9342D8 -:106FF000A36202D32046FFF7D5FF002383F3118855 -:10700000EFE700002DE9F84F04460E461746984674 -:107010004FF0300989F311880025AA46D4F828B02A -:10702000BBF1000F09D141462046FFF7A1FF20B177 -:107030008BF311882846BDE8F88FD4E90A12A7EB34 -:10704000050B521A934528BF9346BBF1400F1BD93D -:10705000334601F1400251F8040B914243F8040B0E -:10706000F9D1A36A403640354033A362D4E90A23FC -:107070009A4202D32046FFF795FF8AF31188BD425A -:10708000D8D289F31188C9E730465A46FAF782FC0C -:10709000A36A5E445D445B44A362E7E710B5029CCB -:1070A0000433017203FB0421C460C0E9061300230A -:1070B000C0E90A33039B0363049BC0E90000C0E9F5 -:1070C0000422C0E90842436310BD0000026A6FF069 -:1070D0000101C260426AC0E904220022C0E90A221A -:1070E000FEF74ABCD0E904239A4201D1C26822B912 -:1070F000184650F8043B0B60704700231846FAE727 -:10710000C3680021C2690133C360436913448269C3 -:107110009342436124BF436A4361FEF721BC0000F0 -:1071200038B504460D46E3683BB1236900201A1DBB -:10713000A262E2691344E36207E0237A33B9294685 -:107140002046FEF7FDFB0028EDDA38BD6FF00100A8 -:10715000FBE7000003691960C268013AC260C269B6 -:10716000134482699342036124BF436A036100238D -:107170008362036B03B118477047000070B530237A -:107180000D460446114683F31188866A2EB9FFF72F -:10719000C7FF10B186F3118870BDA36A1D70A36A82 -:1071A000E26A01339342A36204D3E16920460439C1 -:1071B000FFF7D0FF002080F31188EDE72DE9F84FAD -:1071C00004460D46904699464FF0300A8AF31188DE -:1071D0000026B346A76A4FB949462046FFF7A0FFED -:1071E00020B187F311883046BDE8F88FD4E90A074B -:1071F0003A1AA8EB0607974228BF1746402F1BD91B -:1072000005F1400355F8042B9D4240F8042BF9D1B9 -:10721000A36A40364033A362D4E90A239A4204D3D6 -:10722000E16920460439FFF795FF8BF31188464545 -:10723000D9D28AF31188CDE729463A46FAF7AAFB54 -:10724000A36A3D443E443B44A362E5E7D0E90423FE -:107250009A4217D1C3689BB1836A8BB1043B9B1AD6 -:107260000ED01360C368013BC360C3691A448369CD -:107270009A42026124BF436A0361002383620123AF -:10728000184670470023FBE700F024B9014B586A09 -:10729000704700BF000C0040034B002258631A6186 -:1072A0000222DA60704700BF000C0040014B002250 -:1072B000DA607047000C0040014B5863704700BF14 -:1072C000000C0040FEE7000070B51B4B0025044693 -:1072D00086B058600E4685620163FDF763F804F1DD -:1072E0001003A560E562C4E904334FF0FF33C4E93D -:1072F0000044C4E90635FFF7C9FF2B46024604F1F6 -:1073000034012046C4E9082380230C4A2565FEF792 -:10731000CDFA01230A4AE06000920375684672685C -:107320000192B268CDE90223064BCDE90435FEF7A0 -:10733000E5FA06B070BD00BFB06B0020587F0008B2 -:107340005D7F0008C5720008024AD36A1843D06204 -:10735000704700BF486900204B6843608B688360BA -:10736000CB68C3600B6943614B6903628B694362FD -:107370000B6803607047000008B53C4B40F2FF719A -:107380003B48D3F888200A43C3F88820D3F88820E4 -:1073900022F4FF6222F00702C3F88820D3F8882085 -:1073A000D3F8E0200A43C3F8E020D3F808210A43C9 -:1073B000C3F808212F4AD3F808311146FFF7CCFF54 -:1073C00000F5806002F11C01FFF7C6FF00F5806048 -:1073D00002F13801FFF7C0FF00F5806002F15401AF -:1073E000FFF7BAFF00F5806002F17001FFF7B4FF0C -:1073F00000F5806002F18C01FFF7AEFF00F58060C0 -:1074000002F1A801FFF7A8FF00F5806002F1C401B6 -:10741000FFF7A2FF00F5806002F1E001FFF79CFF9B -:1074200000F5806002F1FC01FFF796FF02F58C7118 -:1074300000F58060FFF790FF00F018F90E4BD3F8CD -:10744000902242F00102C3F89022D3F8942242F035 -:107450000102C3F894220522C3F898204FF060522D -:10746000C3F89C20054AC3F8A02008BD0044025878 -:1074700000000258647F000800ED00E01F000803D0 -:1074800008B500F0D5FAFEF7DFF90F4BD3F8DC2092 -:1074900042F04002C3F8DC20D3F8042122F040027D -:1074A000C3F80421D3F80431084B1A6842F00802EB -:1074B0001A601A6842F004021A60FEF72FFFBDE856 -:1074C0000840FEF755BC00BF0044025800180248AF -:1074D00070470000114BD3F8E82042F00802C3F8CF -:1074E000E820D3F8102142F00802C3F810210C4A1A -:1074F000D3F81031D36B43F00803D363C722094B91 -:107500009A624FF0FF32DA6200229A615A63DA60BF -:107510005A6001225A611A60704700BF0044025845 -:107520000010005C000C0040094A08B51169D368DE -:107530000B40D9B29B076FEA0101116107D53023D7 -:1075400083F31188FEF7A6F9002383F3118808BDA1 -:10755000000C0040064BD3F8DC200243C3F8DC20CB -:10756000D3F804211043C3F80401D3F80431704761 -:107570000044025808B53C4B4FF0FF31D3F880204F -:1075800062F00042C3F88020D3F8802002F000426D -:10759000C3F88020D3F88020D3F88420C3F8841067 -:1075A000D3F884200022C3F88420D3F88400D86F55 -:1075B00040F0FF4040F4FF0040F4DF4040F07F0027 -:1075C000D867D86F20F0FF4020F4FF0020F4DF40A0 -:1075D00020F07F00D867D86FD3F888006FEA40505A -:1075E0006FEA5050C3F88800D3F88800C0F30A004F -:1075F000C3F88800D3F88800D3F89000C3F890103F -:10760000D3F89000C3F89020D3F89000D3F89400FA -:10761000C3F89410D3F89400C3F89420D3F89400DE -:10762000D3F89800C3F89810D3F89800C3F89820BE -:10763000D3F89800D3F88C00C3F88C10D3F88C00E2 -:10764000C3F88C20D3F88C00D3F89C00C3F89C10AE -:10765000D3F89C10C3F89C20D3F89C30FDF74CF86D -:10766000BDE8084000F0B8B90044025808B501224E -:10767000534BC3F80821534BD3F8F42042F00202D5 -:10768000C3F8F420D3F81C2142F00202C3F81C21F5 -:107690000222D3F81C314C4BDA605A689104FCD5B5 -:1076A0004A4A1A6001229A60494ADA6000221A6145 -:1076B0004FF440429A61444B9A699204FCD51A688F -:1076C00042F480721A603F4B1A6F12F4407F04D06C -:1076D0004FF480321A6700221A671A6842F00102DA -:1076E0001A60384B1A685007FCD500221A611A69D3 -:1076F00012F03802FBD1012119604FF0804159602E -:107700005A67344ADA62344A1A611A6842F480329B -:107710001A602C4B1A689103FCD51A6842F4805207 -:107720001A601A689204FCD52C4A2D499A620022EC -:107730005A63196301F57C01DA6301F5E771996316 -:107740005A64284A1A64284ADA621A6842F0A8522F -:107750001A601C4B1A6802F02852B2F1285FF9D166 -:1077600048229A614FF48862DA6140221A621F4A05 -:10777000DA641F4A1A651F4A5A651F4A9A653223FE -:107780001E4A1360136803F00F03022BFAD10D4A4F -:10779000136943F003031361136903F03803182BD3 -:1077A000FAD14FF00050FFF7D5FE4FF08040FFF7C1 -:1077B000D1FE4FF00040BDE80840FFF7CBBE00BF50 -:1077C00000800051004402580048025800C000F0F8 -:1077D000020000010000FF010088900832206000D4 -:1077E00063020901470E0508DD0BBF0120000020E0 -:1077F000000001100910E0000001011000200052FB -:107800004FF0B04208B5D2F8883003F00103C2F857 -:10781000883023B1044A13680BB150689847BDE81B -:107820000840FCF7E7BD00BF488800204FF0B04299 -:1078300008B5D2F8883003F00203C2F8883023B1CB -:10784000044A93680BB1D0689847BDE80840FCF73C -:10785000D1BD00BF488800204FF0B04208B5D2F833 -:10786000883003F00403C2F8883023B1044A136956 -:107870000BB150699847BDE80840FCF7BBBD00BF9D -:10788000488800204FF0B04208B5D2F8883003F0A5 -:107890000803C2F8883023B1044A93690BB1D06958 -:1078A0009847BDE80840FCF7A5BD00BF4888002008 -:1078B0004FF0B04208B5D2F8883003F01003C2F898 -:1078C000883023B1044A136A0BB1506A9847BDE867 -:1078D0000840FCF78FBD00BF488800204FF0B04340 -:1078E00010B5D3F8884004F47872C3F88820A30652 -:1078F00004D5124A936A0BB1D06A9847600604D542 -:107900000E4A136B0BB1506B9847210604D50B4AF6 -:10791000936B0BB1D06B9847E20504D5074A136C03 -:107920000BB1506C9847A30504D5044A936C0BB176 -:10793000D06C9847BDE81040FCF75CBD488800203B -:107940004FF0B04310B5D3F8884004F47C42C3F83C -:107950008820620504D5164A136D0BB1506D984707 -:10796000230504D5124A936D0BB1D06D9847E004FE -:1079700004D50F4A136E0BB1506E9847A10404D57D -:107980000B4A936E0BB1D06E9847620404D5084A37 -:10799000136F0BB1506F9847230404D5044A936FBB -:1079A0000BB1D06F9847BDE81040FCF723BD00BF76 -:1079B0004888002008B50348FDF706F8BDE80840F0 -:1079C000FCF718BDD864002008B5FFF7ADFDBDE891 -:1079D0000840FCF70FBD0000062108B50846FDF77A -:1079E00079F806210720FDF775F806210820FDF734 -:1079F00071F806210920FDF76DF806210A20FDF730 -:107A000069F806211720FDF765F806212820FDF703 -:107A100061F809217A20FDF75DF807213220FDF792 -:107A200059F80C215220BDE80840FDF753B800007A -:107A300008B5FFF79FFD00F00DF8FDF709FAFDF717 -:107A4000E1FBFDF7B3FAFFF743FDBDE80840FFF7A0 -:107A50001BBC00000023054A19460133102BC2E964 -:107A6000001102F10802F8D1704700BF48880020D9 -:107A70000B460146184600F003B8000000F00EB8AF -:107A800010B5054C13462CB10A4601460220AFF34F -:107A9000008010BD2046FCE700000000024B0146BC -:107AA0001868FEF75FBB00BF6C23002010B50139DA -:107AB0000244904201D1002005E0037811F8014F03 -:107AC000A34201D0181B10BD0130F2E72DE9F041AF -:107AD000A3B1C91A17780144044603F1FF3C8C4254 -:107AE000204601D9002009E00578BD4204F10104D7 -:107AF000F5D10CEB0405D618A54201D1BDE8F08103 -:107B000015F8018D16F801EDF045F5D0E7E7000016 -:107B1000034611F8012B03F8012B002AF9D1704715 -:107B20006F72672E6172647570696C6F742E437525 -:107B300062654F72616E67652D7065726970682D40 -:107B4000686561767900000053544D333248373F01 -:107B50003F3F0053544D3332483733782F37327814 -:107B60000053544D3332483734332F3735332F37A2 -:107B70003530000001105A00031059000120580050 -:107B80000320560040A2E4F1646891060041A3E599 -:107B9000F26569920700000043414E464449666120 -:107BA00063653A204D6573736167652052414D20CE -:107BB0004F766572666C6F77210000004261642029 -:107BC00043414E496661636520696E6465782E00A5 -:107BD000000100000001FF0000A0004000A40040E0 -:107BE0000000000000000000C92A0008512300081E -:107BF00051320008C1230008CD230008E527000802 -:107C000045250008892300088D2300086523000806 -:107C10004D230008A127000871230008B93300088C -:107C20007D2300087527000801040E05054B02029C -:107C30000E05054B04010E05054B05010B04044B15 -:107C4000080106030346000010000240080002403D -:107C50000008024000000B0028000240080002401B -:107C60000408024006010C004000024008000240E7 -:107C70000808024010020D005800024008000240AF -:107C80000C08024016030E00700002400C00024077 -:107C90001008024000040F00880002400C0002405F -:107CA0001408024006051000A00002400C0002402B -:107CB0001808024010061100B80002400C000240F3 -:107CC0001C08024016072F0010040240080402405E -:107CD000200802400008380028040240080402403E -:107CE000240802400609390040040240080402400A -:107CF00028080240100A3A005804024008040240D2 -:107D00002C080240160B3B00700402400C04024099 -:107D100030080240000C3C00880402400C04024081 -:107D200034080240060D4400A00402400C04024046 -:107D300038080240100E4500B80402400C0402400E -:107D40003C080240160F46000096000000000000AC -:107D50000000000000000000000000000000000023 -:107D600000000000114E0008FD4D0008394E0008CB -:107D7000254E0008314E00081D4E0008094E00082F -:107D8000F54D0008454E000800000000294F00088E -:107D9000154F0008514F00083D4F0008494F00089B -:107DA000354F0008214F00080D4F00085D4F0008B7 -:107DB000000000000100000000000000633000002F -:107DC000BC7D0008A0690020B06B00204172647582 -:107DD00050696C6F740025424F415244252D424C2E -:107DE000002553455249414C250000000200000087 -:107DF0000000000049510008B9510008400040004F -:107E00006084002070840020020000000000000058 -:107E10000300000000000000015200080000000004 -:107E2000100000008084002000000000010000001D -:107E300000000000F8860020010102000D5D00082E -:107E40001D5C0008B95C00089D5C00084300000050 -:107E5000547E000809024300020100C032090400F8 -:107E600000010202010005240010010524010001A7 -:107E7000042402020524060001070582030800FF0E -:107E800009040100020A0000000705010240000089 -:107E9000070581024000000012000000A07E0008DB -:107EA00012011001020000400912415700020102B4 -:107EB000030100000403090425424F4152442500F8 -:107EC0003031323334353637383941424344454610 -:107ED000000000000001002000FF0100020000007F -:107EE0000000003000000400080000000000002432 -:107EF00000000800040000000004000000FC000076 -:107F000002000000000004300080000008000000B3 -:107F10000000003800000100010000000000000027 -:107F20005D53000815560008C15600084000400087 -:107F300030880020308800200100000040880020A8 -:107F40008000000040010000080000000001000067 -:107F500000100000080000006D61696E0069646C2B -:107F6000650000000000802A00000000AAAAAAAA5A -:107F700000000024FFFF00000000000000A00A0035 -:107F80000021000200000000AAAAAAAA0000000026 -:107F9000FFFF000000000009000009001400005469 -:107FA00000000000AAAAAAAA14000054FFFF0000C3 -:107FB00000000000000000000A4010000000000067 -:107FC000AAAA8AAA00401000FFFF00009900000042 -:107FD000000000000081020000000000AAAAAAAA76 -:107FE00000410100FFFF00000000007007000000DA -:107FF0000000000000000000AAAAAAAA00000000D9 -:10800000FFFF000000000000000000000000000072 -:1080100000000000AAAAAAAA00000000FFFF0000BA -:108020000000000000000000000000000000000050 -:10803000AAAAAAAA00000000FFFF0000000000009A -:10804000000000000000000000000000AAAAAAAA88 -:1080500000000000FFFF0000000000000000000022 -:108060000000000000000000AAAAAAAA0000000068 -:10807000FFFF000000000000000000000000000002 -:1080800000000000AAAAAAAA00000000FFFF00004A -:108090000000000000000000780500000000000063 -:1080A00000001E0000000000FE2A0100D2040000B3 -:1080B000FF000000B86B0020D86400200000000022 -:1080C000487B000883040000537B00085004000034 -:1080D000617B000800960000000008009600000088 -:1080E0000008000004000000B47E0008000000004A -:1080F0000000000000000000000000000000000080 -:1081000000000000702300200000000000000000BC -:10811000000000000000000000000000000000005F -:10812000000000000000000000000000000000004F -:10813000000000000000000000000000000000003F -:10814000000000000000000000000000000000002F -:10815000000000000000000000000000000000001F -:08816000000000000000000017 +:101B300055F82600BDE8704003F0E8B970BD00BF5D +:101B4000DC6300201C230020586B0020C4630020AD +:101B5000F8B571B6002301201A46194602F0AEFE10 +:101B60000446802004F0EEFB002849D00025254AD9 +:101B700080274FF4D06C3D26136913F0C06F26D137 +:101B8000D2F8103113F0C06F21D1236805F1006144 +:101B900099602368D86023685F602368C3F800C039 +:101BA00021680B6843F001030B6021680B6823F088 +:101BB0001E030B6021680B68DB07FCD4237B803598 +:101BC000616806FA03F3B5F5001F0B60D4D1204617 +:101BD00002F0B4FEB5F5001F11D000240A4E0B4DE3 +:101BE000012004F011FB3388A34205D92868204462 +:101BF000013404F04FFAF6E7002004F005FB61B66B +:101C0000F8BD00BF00200052DE6300209863002072 +:101C10002DE9F3470D46044600219046284640F240 +:101C20007912FFF7DDFE234620220021284604F129 +:101C3000220702F077F9231D022220212846C02620 +:101C400002F070F9631D03222221284602F06AF98E +:101C5000A31D03222521284602F064F904F108039C +:101C600010222821284602F05DF904F11003082211 +:101C70003821284602F056F904F1110308224021C8 +:101C8000284602F04FF904F11203082248212846A1 +:101C900002F048F904F1140320225021284602F0F2 +:101CA00041F904F1180340227021284602F03AF964 +:101CB00004F120030822B021284602F033F904F190 +:101CC00021030822B821284602F02CF931460836B3 +:101CD0003B4608222846013702F024F9B6F5A07FDA +:101CE000F4D194F83230314604F1330A00268DF8ED +:101CF000073008220DF10703284602F013F99DF87A +:101D000007304FEAC6099E4209F5A47720D394F81C +:101D10003231502B28BF50238DF80730B8F1000F17 +:101D200008D1394609F24F170DF10703072228465B +:101D300002F0F8F8002604F233149DF8073007EBA0 +:101D4000C6019E420DD30731C80802B0BDE8F08736 +:101D50000AEB0603082239462846013602F0E2F86B +:101D6000CDE7A31908222846013602F0DBF8E4E7A4 +:101D700013B5044608460021202223460190016045 +:101D8000C0F8031002F0CEF8231D01980222202192 +:101D900002F0C8F8631D01980322222102F0C2F864 +:101DA000A31D01980322252102F0BCF8019804F13B +:101DB00008031022282102F0B5F8072002B010BD58 +:101DC000F7B5047F05460E462CB1838A122B02D943 +:101DD000012003B0F0BD00230722284600961946D3 +:101DE00001F064FF731C01220721009328460023A1 +:101DF00001F05CFFD4B9B31C0522082128460093EA +:101E000023460D2401F052FFB378102BE0D837465B +:101E1000BB1BB278934210D307342B7FA88AE40807 +:101E2000B3B9844294BF00200120D2E7AB8A0824D2 +:101E3000DB00083BDB08B370E6E7FB1C2146082209 +:101E40002846009300230834013701F02FFFDFE715 +:101E5000201A18BF0120BCE7F7B5047F05460E46DF +:101E60002CB1838ACA2B02D9012003B0F0BD002314 +:101E7000082228460096194601F018FF731CD4B9B1 +:101E800008220093234610241146284601F00EFF35 +:101E90007378C82BE8D801235F1C7278013B93420A +:101EA00010D307342B7FA88AE408B3B9844294BFC7 +:101EB00000200120D9E7AB8A0824DB00083BDB08BF +:101EC0007370E5E7F31921460822284600930023A2 +:101ED00001F0ECFE08343B46DEE7201A18BF012073 +:101EE000C3E70000F7B50D46044600211646284614 +:101EF0008122FFF775FD234608220021284602F0C3 +:101F000011F894F901206378002AB8BF7F238DF877 +:101F100007309EB90F270DF1070307220821284635 +:101F200002F000F8002602349DF8073007EBC601E6 +:101F30009E4205D30731C80803B0F0BD0827F1E77A +:101F4000A31908222846013601F0ECFFECE7000057 +:101F5000F7B50E460546002114463046CE22FFF75F +:101F60003FFD2B4628220021304601F0DBFF2B7A73 +:101F7000C82B28BFC8238DF807308CB930240DF149 +:101F8000070308222821304601F0CCFF2F467B1B97 +:101F90009DF80720934205D3E01DC00803B0F0BDB3 +:101FA0002824F3E707F109032146082230460834C4 +:101FB000013701F0B7FFEAE7F7B5047F05460E46A3 +:101FC00034B1838AB3F5827F02D9012003B0F0BD1A +:101FD0000123102200212846009601F067FEDCB99B +:101FE000B31C09221021284600932346192401F02E +:101FF0005DFE7388B3F5807FE7D83746BB1B7288D8 +:10200000934210D307342B7FA88AE408B3B98442E3 +:1020100094BF00200120D9E7AB8A1024DB00103BDD +:10202000DB087380E5E73B1D214608222846009324 +:1020300000230834013701F039FEDFE7201A18BF0A +:102040000120C3E730B50A44084D91420DD011F884 +:10205000013B5840082340F30004013B2C4013F09F +:10206000FF0384EA5000F6D1EFE730BD2083B8EDDE +:10207000F7B5364A6B46106851686A4603C30823B1 +:102080003349344805F086FF044690BB0A25324A9E +:102090006B46106851686A4603C308232F492D48D0 +:1020A00005F078FF0446002847D00369B3F5F01F18 +:1020B00043D8B0F86620B2F5AF6F3ED1284A02444B +:1020C00002F15C018B4238D35C3B224900209E1A0E +:1020D000FFF7B8FF04F16401074632460020FFF71E +:1020E000B1FFA3689F4228D1E368984208BF00254A +:1020F00023E00369B3F5F01F26D8428BB2F5AF6F2A +:1021000020D1174A024402F110018B4218D3103B30 +:10211000104900209D1AFFF795FF04F118010646AB +:102120002A460020FFF78EFFA3689E4202D1E36893 +:10213000984201D00D25AAE70025284603B0F0BD3E +:102140001025A4E70C25A2E70B25A0E74C8000088A +:10215000DCFF1D00000002085580000890FF1D00F4 +:102160000800FEF710B5037C044613B9006804F0BC +:102170001DF9204610BD00000023BFF35B8FC36034 +:10218000BFF35B8FBFF35B8F8360BFF35B8F7047E1 +:10219000BFF35B8F0068BFF35B8F704770B5054678 +:1021A0000C30FFF7F5FF044605F108063046FFF74F +:1021B000EFFFA04206D96D683046FFF7E9FF2544DE +:1021C000281A70BD3046FFF7E3FF201AF9E7000038 +:1021D00070B505464068A0B105F10C0605F1080090 +:1021E000FFF7D6FF04463046FFF7D2FF844204F1E2 +:1021F000FF34304694BF6D680025FFF7C9FF2C44BB +:10220000201A70BD38B50C460546FFF7C7FFA0423F +:1022100010D305F10800FFF7BBFF04446868BFF363 +:102220005B8FB4FBF0F100FB11440120AC60BFF305 +:102230005B8F38BD0020FCE72DE9F04114460746CE +:102240000D46FFF7C5FF844228BF0446D4B1B84607 +:1022500058F80C6B4046FFF79BFF3044286040461F +:102260007E68FFF795FF331A9C4203D801206C600B +:10227000BDE8F081A41B6B603B682044AB60E86064 +:102280000220F5E72046F3E738B50C460546FFF790 +:102290009FFFA04210D305F10C00FFF779FF044423 +:1022A0006868BFF35B8FB4FBF0F100FB11440120C1 +:1022B000EC60BFF35B8F38BD0020FCE72DE9FF41E8 +:1022C0008846694607466C46FFF7B6FF002506B20A +:1022D00004EBC606B4420AD0626808EB0501206828 +:1022E0000834FFF757FB54F8043C1D44F2E7294635 +:1022F0003846FFF7C9FF284604B0BDE8F08100006A +:10230000F8B505460C300F46FFF742FF05F1080609 +:1023100004463046FFF73CFFA042304688BF6C6859 +:10232000FFF736FF201A386020B12C683046FFF7DF +:102330002FFF2044F8BD000073B5144606460D4635 +:10234000FFF72CFF8442019028BF0446DCB101A9AD +:102350003046FFF7D5FF019B33B93268C5E9023338 +:10236000C5E9002401200CE09C42286038BF01949C +:10237000019884426860F5D93368241A0220AB6062 +:10238000EC6002B070BD2046FBE700002DE9FF4184 +:102390000F4669466C46FFF7CFFF00B2002604EBFC +:1023A000C005AC4209D0D4F80480B81954F8081B11 +:1023B00042464644FFF7EEFAF3E7304604B0BDE884 +:1023C000F081000038B50546FFF7E0FF04460146FE +:1023D0002846FFF717FF204638BD000008B103F07C +:1023E000E5BF70477047000010B4134602681468D8 +:1023F0000022A4465DF8044B6047000000F58050C1 +:1024000090F859047047000000F5805090F852048D +:102410007047000000F5805090F9580470470000A4 +:102420004E207047302383F3118800F58052D2F894 +:102430009C34D2F898041844D2F894341844D2F852 +:102440007C341844D2F88C341844D2F888341844B8 +:10245000002383F31188704700F58050C0F85414AE +:10246000012070472DE9F04F0C4600F5805185B0F2 +:102470001F4691F8523405469046BDF838909BB1FE +:10248000D1F878340133C1F878342368980006D441 +:10249000237B082B0BD9627B0AB10F2B07D9D1F80C +:1024A0007C340133C1F87C344FF0FF3010E030232E +:1024B00083F31188EB6AD3F8C42012F4001B0AD00E +:1024C000D1F8803400200133C1F8803480F31188C2 +:1024D00005B0BDE8F08F20684822D3F8C43000284A +:1024E000C3F3044A6B6AB4BF40F08040800412FB1F +:1024F0000A334FEA4A161860226852004FEA0A620D +:1025000044BF40F000501860207B42EA00425A600D +:10251000607B10B342F440125A60D1F8B02401320B +:10252000C1F8B024AA1902F58352117B41F02001B1 +:102530001173207B039300F0E3FF0330039B8010B3 +:102540005FFA8BF20BF1010B82420DDA04EB820190 +:1025500003EB820249689160F2E7AA1902F58352FF +:10256000117B60F34511E3E70122EB6A05EB4A11A9 +:1025700002FA0AF201F58251C3F8D020AB191831E2 +:1025800004F10C0203F58253C3E90487234653F890 +:10259000040B934241F8040BF9D11B882E440B80A5 +:1025A00041F2680346F803A006F5805609F00303DC +:1025B00096F86C2043F0100322F01F02134386F8B4 +:1025C0006C30002383F3118842463B46214628465F +:1025D000CDF8009000F05AFF012079E72DE9F0478F +:1025E00000F58056044696F85254002D40F00381C1 +:1025F000037C032B40F0948028462B462F465FFA3D +:1026000080FC944510DA01EBCC0E51F83CC0BCF1D3 +:10261000000F04DBDEF804C0BCF1000F02DB013761 +:102620000130ECE70133FBE7302080F31188E06AEA +:10263000F3B9D0F8803043F00203C0F880304E2365 +:10264000E06A002F6FD1D0F8803043F00103C0F86A +:1026500080306A4B6A4A1B6803F1805303F52C53A0 +:102660009B009342A36240F2B080664800F0E6FE11 +:102670004D2B42D8DFF884814FEA034EDFF8889172 +:10268000D8F800C04EEA8C0EC0F884E00CF18050FF +:1026900000F52C508000606103EB0C00D4F82CC0D6 +:1026A000C3F14E03C8F80000DCF8800040F03000B1 +:1026B000CCF880004FF0000CD4F81480E6465FFAA6 +:1026C0008CF08242BCDD01EBC00A51F830000028DA +:1026D00010DBDAF804A0BAF1000F0BDA09EA0040C7 +:1026E0000AF07F0A40EA0A0040F0084048F82E004D +:1026F0000EF1010E0CF1010CE1E7836923F00103F7 +:10270000836100F0A1FE0646E36A9B69D90704D500 +:1027100000F09AFE831BFA2BF6D9002383F311886D +:102720002846BDE8F087B7EB530F3DD2DFF8CCE089 +:102730004FEA074CDEF800304CEA830CC0F888C042 +:1027400003F1805003EB4703002700F52C50CEF82F +:102750000030BC468000A061E06AD0F8803043F0D1 +:102760000C03C0F88030D4F818E0FBB29A427FF72F +:1027700070AF51F8330001EBC3080028D8F80430DB +:1027800001DB002B0EDB20F0604023F0604340F0C3 +:10279000005043F000434EF83C000EEBCC000CF12F +:1027A000010C43600137E0E7836923F00103836193 +:1027B00000F04AFE0646E36A9B69DA07ADD500F0F1 +:1027C00043FE831BFA2BF6D9A7E7E26A936923F04D +:1027D0000103936100F038FE0746E36A9B69DB075B +:1027E00005D500F031FEC31BFA2BF6D995E701257C +:1027F00086F8525491E7002592E700BFEC63002071 +:10280000FCB50040608000080000FF0713B500F52C +:1028100080540191606CFFF7DBFC1F280AD920224D +:102820000199606CFFF74AFDA0F12003584258411E +:1028300002B010BD0020FBE708B5302383F31188F8 +:1028400000F58050406CFFF797FC002383F311885C +:1028500008BD0000002202608281426082607047F1 +:102860000022002310B5C0E90023002304460C30E9 +:1028700020F8043CFFF7EEFF204610BD2DE9F0479D +:102880009A4688B0074688469146302383F31188DC +:1028900007F580546846FFF7E3FF606CFFF77EFCA6 +:1028A0001F282ED920226946606CFFF78BFD202857 +:1028B00027D194F8523423B303AD444605AB2E46DA +:1028C000083403CE9E4244F8080C44F8041C3546F4 +:1028D000F5D130682060B388A380DDE90023C9E921 +:1028E0000023BDF80830AAF80030002383F31188D4 +:1028F00053464A464146384608B0BDE8F04700F026 +:10290000B3BD002080F3118808B0BDE8F087000057 +:102910002DE9F84F0023064600F581540546884608 +:102920001034C0E90133274B46F8303B3746384670 +:102930002037FFF795FFA742F9D105F580544FF4F2 +:10294000805305F5A3594FF0000A266300266764FB +:1029500005F5835709F110094FF0000B1037E663B6 +:10296000C4E90D36012384F8403084F84830A7F1DB +:102970001800203747E910ABFFF76CFF47F8286CC9 +:102980004F45F4D1B8F1010F84F85884A4F85A6483 +:10299000A4F85C64A4F85E6484F86064A4F86264DB +:1029A000A4F86464A4F8666484F8686402D90648EC +:1029B00000F044FD054B284653F82830EB62BDE893 +:1029C000F88F00BFB080000884800008A080000855 +:1029D000044B10B5197804464A1C1A70FFF798FF8B +:1029E000204610BDE96300202DE9F04300295AD0AC +:1029F0002E4E2F48B6FBF1F481428CBF0A201120E5 +:102A0000431EB4FBF0F700FB1740DDB220B1022BF0 +:102A10001846F5D8002032E07B1EB3F5806F2ED229 +:102A2000C5EBC5084FF47A7308F103044FEAE40ECE +:102A3000C4F3C7040EF10109281B0EFB033E5FFA25 +:102A400080FC59FA80F0BEFBF0F0B0F5617F18DC35 +:102A500083B2601C5CFA80F07843B6FBF0F08142F0 +:102A6000D8D1611E0F29D5D80CF1FF310729D1D853 +:102A70000120138057801071547182F806C0BDE8A0 +:102A8000F08308F1FF34E010C4F3C70400F1010E35 +:102A90002D1B00FB03335FFA85FC5EFA85F5B3FB63 +:102AA000F5F39BB2D5E70846E9E700BF00B4C404DC +:102AB0003F420F0030B50D4B05200D4D1C786C4387 +:102AC0008C420ED159780120518099785171D97872 +:102AD0009171197911715B7903EB83035B001380AA +:102AE00030BD013803F10603E8D1F9E7F0800008B2 +:102AF00040420F0038B540F27772C36A154CC3F8F4 +:102B0000BC200722C36AC3F8C8202268C16A9300A8 +:102B100043F4C023C1F8A03002F1805302F16C01EC +:102B2000C56A03F52C53EA3289009B00226041F00C +:102B3000E061094AC361C5F8C01003F5D87103F517 +:102B40006A7341629342836202D9044800F076FCC2 +:102B500038BD00BFEC630020FCB500406080000879 +:102B60002DE9F04F00F580551F4689B0044695F8D1 +:102B7000583489469046022B04D90026304609B0C5 +:102B8000BDE8F08FA84A52F8231009B942F8230093 +:102B9000A648C4F80C9001782774C9B9302383F390 +:102BA0001188A34BD3F8EC2042F48072C3F8EC20D8 +:102BB000D3F8942042F48072C3F89420D3F8942080 +:102BC00022F48072C3F894200123037081F31188EA +:102BD00095F851347BB9302383F31188954A95F8E1 +:102BE0005834D35C0BB3012B28D0012385F8513422 +:102BF000002383F31188302383F31188E26A9369F9 +:102C000023F01003936100F01FFC8246E36A9E6983 +:102C100016F0080619D000F017FCA0EB0A03FA2BF7 +:102C2000F4D9002686F31188A8E70321132001F0C8 +:102C3000A1FF0321152001F09DFFD6E703211420F9 +:102C400001F098FF03211620F5E79A6942F001028E +:102C50009A6100F0F9FB8246E36A9A69D00706D4CC +:102C600000F0F2FBA0EB0A03FA2BF5D9D9E79A6939 +:102C70004FF0000A42F002029A61E36AC3F854A0DE +:102C80008AF3118804F5825B686CFFF775FA0BF123 +:102C9000100B202200216846FEF7A2FE02A8FFF7D3 +:102CA000D9FD6A460BEB06030DF1180ECDF818A0FE +:102CB00094460833BCE80300F44543F8080C43F895 +:102CC000041C6246F4D1DCF8000020361860B6F52A +:102CD000806F9CF804201A71DBD1002304F5A25206 +:102CE000494620461A3285F8503485F85334FFF7A8 +:102CF0007BFE064690B9E26A936923F00103936173 +:102D000000F0A2FB0546E36A9B69D9077FF535AF62 +:102D100000F09AFB431BFA2BF5D92EE795F85E34A9 +:102D2000C5F86C94591E95F85F34E26A013B1B02AA +:102D300043EA416395F8601401390B43B5F85C141C +:102D4000013943EA0143D361B8F1000F36D004F5ED +:102D5000A352414620460232FFF7ACFE90B9E26A28 +:102D6000936923F00103936100F06EFB0546E36A6B +:102D70009B69DA077FF501AF00F066FB431BFA2B76 +:102D8000F5D9FAE695F86724C5F87084511E95F8D0 +:102D90006824E36A013A120142EA012295F86614B6 +:102DA00001390A43B5F86414013942EA014242F498 +:102DB0000002DA604FF42062E36A9A64E36A4FF03B +:102DC00000082046C3F8BC80FFF794FE85F85984BC +:102DD0006FF04042E36A1A65174AE36A5A654FF09A +:102DE0000222E36A9A654FF0FF32E36AC3F8E020FB +:102DF0000322E36A9742DA653FF4C0AEE26A936960 +:102E000023F00103936100F01FFB0746E36A9B690F +:102E1000DB0705D500F018FBC31BFA2BF6D9ACE68F +:102E2000012385F85234A9E6E0630020E86300201E +:102E30000044025898800008550200022DE9F04F26 +:102E4000054689B090469946002741F2680A00F588 +:102E50008056EB6AD3F8D830FB40D80751D505EB44 +:102E600047124FEA471B52441379190749D4D6F841 +:102E700084340133C6F8843405F5A553C3E90089C9 +:102E800013799A0605EB0B0248BFD6F8B4345244C6 +:102E900044BF0133C6F8B434137943F00803137107 +:102EA000DB0723D596F8533403B305F582546846FF +:102EB000FFF7D6FC03AB18345C4404F1080C20681F +:102EC000083454F8041C1A46644503C21346F6D16C +:102ED0002068694610602846A2889A800123ADF8D0 +:102EE00008302B68CDE90089DB6B9847D6F8A83409 +:102EF000D6F854040133C6F8A83410B103681B692E +:102F000098470137202FA4D109B0BDE8F08F000009 +:102F10002DE9F04F0F468DB0044600F097FA824637 +:102F20008946002F5BD1E36AD3F8A02012F4FE0F8C +:102F300003D100200DB0BDE8F08FD3F8A42092019A +:102F400041BF04F58051D1F898240132C1F898248A +:102F5000D3F8A4205606ECD0D3F8A450E669C5F304 +:102F600005254823E8464FF0000B03FB0566404665 +:102F7000FFF770FC326851004ABF22F06043C2F391 +:102F80008A4343F00043920048BF43F080430093DC +:102F9000736813F400131BBF012304F580528DF8EE +:102FA0000D308DF80D301EBFD2F8B8340133C2F8A1 +:102FB000B834F38803F00F038DF80C309DF80C0043 +:102FC00000F09EFA5FFA8BF3984225D9F2180CA90B +:102FD0000BF1010B127A0B4403F82C2CEEE7012FB6 +:102FE000A7D1E36AD3F8B02012F4FE0FA1D0D3F832 +:102FF000B420950141BF04F58051D1F898240132E5 +:10300000C1F89824D3F8B420500692D0D3F8B45025 +:10301000266AC5F30525A4E7EFB9E36AC3F8A8500B +:1030200004A807ADFFF71CFC98E80F0007C52B802C +:103030000023204604A9ADF81830236804F5805415 +:10304000DB6BCDE904A9984758B1D4F8903401332B +:10305000C4F890346EE7012FE2D1E36AC3F8B850A8 +:10306000DEE7D4F8943401200133C4F8943461E7E6 +:103070002DE9F04105460F4600F5805401263946FA +:103080002846FFF745FF10B184F85364F7E7D4F8FA +:10309000A834D4F854040133C4F8A83420B1036828 +:1030A000BDE8F0411B691847BDE8F081C36AF0B57F +:1030B0001A6C12F47F0F2BD01B6C00F5805441F278 +:1030C00068054FF0010CC4F8AC340023471900EB3D +:1030D00043125E012A44117911F0020F15D04907FD +:1030E00013D4B959C66A0CFA01F1D6F8CCE011EA4A +:1030F0000E0F0AD0C6F8D410117941F004011171F5 +:10310000D4F88C240132C4F88C240133202BDED176 +:10311000F0BD00002B4B70B51E561B5C012B30D848 +:10312000294D2A4A55F8233052F8264013B349B3A3 +:10313000236D9A0510D54FF40073236500F086F9CE +:1031400050EA01020B4602D0013861F10003024649 +:1031500055F82600FFF772FE236D9B012CD54FF02A +:10316000007255F82630226503F58053012283F85A +:10317000592421E001232365102323654FF4805354 +:10318000236570BD236DDA0702D4236D5B0706D576 +:103190000523002155F826002365FFF769FF236DFD +:1031A000D80602D4236D590606D55023012155F8BF +:1031B00026002365FFF75CFF55F82600BDE8704048 +:1031C000FFF774BF9C800008E0630020A080000827 +:1031D00008B5302383F31188FFF768FF002383F3DA +:1031E000118808BDC36AD3F8C00010F07C5005D028 +:1031F000D3F8C40080F40010C0F3405070470000C2 +:1032000008B5302383F3118800F58050406CFEF739 +:10321000C5FF002383F3118843090CBF0120002060 +:1032200008BD000000F5805393F8592462B1C16ACB +:103230008A6922F001028A61D3F89C240132C3F822 +:103240009C24002283F85924704700002DE9F7439D +:10325000302181F3118800F58251002541F2680E7A +:103260004FF00108103100F5805C00EB4514744408 +:10327000267977071CD4F6061AD58E69D0F82C90DB +:1032800008FA06F6D9F8CC703E4211D04F68019783 +:103290000F689742019F9F410AD2C9F8D4602679EE +:1032A00046F004062671DCF888440134CCF88844E2 +:1032B00001352031202DD8D1002383F3118803B0AC +:1032C000BDE8F083F8B51E4600230F46054613708F +:1032D0001446FFF795FF80F0010038701EB12846B4 +:1032E000FFF780FF2070F8BD2DE9F04F85B09946BB +:1032F0000D468046164691F800B0DDE90EA3029314 +:103300001378019300F0A2F82B7804460F4613B906 +:103310003378002B41D022463B464046FFF796FFCC +:10332000FFF756FFFFF77EFF4B4632462946FFF771 +:10333000C9FF2B7833B1BBF1000F03D0012005B0DA +:10334000BDE8F08F337813B1019B002BF6D108F55F +:10335000805303935445029B77EB03031DD2039BD9 +:10336000D3F85404C8B10368AAEB04011B6898475A +:103370004B46324629464046FFF7A4FF2B7813B14F +:10338000BBF1000FDAD1337813B1019B002BD5D1FB +:1033900000F05CF804460F46DCE70020CFE70000B1 +:1033A000002108B50846FFF7B5FEBDE8084001F06A +:1033B00071B8000008B501210020FFF7ABFEBDE8A1 +:1033C000084001F067B8000008B500210120FFF7B0 +:1033D000A1FEBDE8084001F05DB80000012108B57C +:1033E0000846FFF797FEBDE8084001F053B800001B +:1033F00000B59BB0EFF3098168226846FEF7CAFA70 +:10340000EFF30583014B9B6BFEE700BF00ED00E08F +:1034100008B5FFF7EDFF000000B59BB0EFF30981A1 +:1034200068226846FEF7B6FAEFF30583014B5B6B43 +:10343000FEE700BF00ED00E0FEE700000FB408B5B6 +:10344000029802F08BFAFEE702F0DEBF02F0C0BF86 +:1034500013B56C46031D84E8060094E8030083E876 +:103460000500012002B010BD73B58568019155B10A +:103470001B885B0707D4D0E900369B6B9847019AFD +:10348000C1B23046A847012002B070BDF0B58668D1 +:1034900089B005460C465EB1BDF838305B070AD4EA +:1034A000D0E900379B6B98472246C1B23846B047F7 +:1034B000012009B0F0BD0022002301F10806CDE98A +:1034C000002300230A46ADF8083003AB1068083229 +:1034D00052F8041C1C46B24203C42346F6D11068BD +:1034E00020609288A280FFF7B1FF0423ADF8083076 +:1034F0002B68CDE90001DB6B694628469847D7E782 +:10350000082817D909280CD00A280CD00B280CD071 +:103510000C280CD00D280CD00E2814BF40203020D1 +:1035200070470C20704710207047142070471820F7 +:1035300070472020704700002DE9F041456A15B919 +:103540004162BDE8F0814B68AC4623F06047C3F3AD +:103550008A464FEAD37EC3F3807816EA230638BF43 +:103560003E462B465A68BEEBD27F22F060440AD01A +:10357000002A18DAA40CB44217D19D420FD10D6075 +:10358000DEE71346EEE7A74207D102F08044C2F31C +:10359000807242450BD054B1EFE708D2EDE7CCF88A +:1035A00000100B60CDE7B44201D0B442E5D81A68F0 +:1035B0009C46002AE5D11960C3E700002DE9F047D9 +:1035C000089D01F0070400EBD1004FF47F494FEA5A +:1035D000D508224405F00705944201D1BDE8F087E3 +:1035E00004F0070705F0070A111B08EBD50E574535 +:1035F0003E4613F80EC038BF5646C6F108068E4246 +:1036000028BF0E46E108415C34443544B94029FAEC +:1036100006F721FA0AF1FFB28CEA010147FA0AF72C +:1036200039408CEA010C03F80EC0D5E780EA01208E +:10363000082341F2210201B2013B4000002980B27F +:10364000B8BF504013F0FF03F5D1704738B50C46B2 +:103650008D18A54200D138BD14F8011BFFF7E6FF15 +:10366000F7E7000042684AB11368818943604389E3 +:1036700001339BB29942438138BF83811046704722 +:1036800070B588B0044620220D4668460021FEF73A +:10369000A7F920460495FFF7E5FF024660B16B46A7 +:1036A000054608AE1C46083503CCB44245F8080C64 +:1036B00045F8041C2346F5D1104608B070BD000043 +:1036C000082817D909280CD00A280CD00B280CD0B0 +:1036D0000C280CD00D280CD00E2814BF4020302010 +:1036E00070470C2070471020704714207047182036 +:1036F0007047202070470000082817D90C280CD9E3 +:1037000010280CD914280CD918280CD920280CD929 +:1037100030288CBF0F200E207047092070470A20E8 +:1037200070470B2070470C2070470D207047000039 +:103730002DE9F843078C0446072F1ED900254FF6C4 +:10374000FF73D0E90298C5F12006A5F1200029FAFF +:1037500005F1083508FA06F628FA00F0314301436E +:103760001846C9B2FFF762FF402D0346EBD13A4637 +:10377000E169BDE8F843FFF769BF4FF6FF70BDE8A8 +:10378000F883000010B54B6823B9CA8A63F30902B5 +:10379000CA8210BD04691A681C600361C38A013BB8 +:1037A000C3824A60EFE700002DE9F84F1D46CB8A3F +:1037B0000F468146C3F30901924605290B4630D0D6 +:1037C0000020AAB207F11A049EB21FFA80F8042E54 +:1037D0000FD8904503F1010306D30A44FB8A62F334 +:1037E00009030120FB821AE01AF800600130E65458 +:1037F000EAE79045F1D2A1F1050B1C237C68BBFBE5 +:10380000F3F203FB12BB1FFA8BF6002C45D148469E +:10381000FFF728FF044638B978606FF00200BDE872 +:10382000F88F4FF00008E6E7002606607860ADB23A +:103830004FF0000B454510D90AEB0803221D13F881 +:10384000011B08F101089155B1B21FFA88F81B2934 +:103850002BD0454506F10106F1D8FB8AC3F30902D6 +:10386000154465F30903BCE701321C4692B2236894 +:10387000002BF9D16B1F0B441C21B3FBF1F3013377 +:103880009BB29A42D3D2BBF1000FD0D14846FFF78A +:10389000E9FE20B9C4F800B0BFE70122E7E7C0F8AD +:1038A00000B05E4620600446C1E74545D5D948468C +:1038B000FFF7D8FE08B92060AFE7C0F800B00026D7 +:1038C00020600446B6E700002DE9F04F1C4607468D +:1038D00088462DED028B83B05B690192002B00F0CE +:1038E0009A80238C2BB1E269002A00F09480072B88 +:1038F00035D807F10C00FFF7B5FE054638B96FF073 +:103900000205284603B0BDEC028BBDE8F08F1422FF +:103910000021FEF765F8228CE16905F10800FEF749 +:1039200039F8208C48F00041013080B2FFF7E4FE06 +:10393000FFF7C6FE013880B2208401302874384673 +:103940006369228C1B782A4403F01F0363F03F0352 +:10395000137269602946FFF7EFFD0125D1E74FF0AB +:10396000000900F10C034FF0800A4E464D4608EE68 +:10397000103A18EE100AFFF775FE83460028BED0F5 +:1039800014220021FEF72CF8002E3AD1019B0222CE +:10399000ABF808300BF1080E1FFA82FC218C0CF1F9 +:1039A0000100BCF1060F80B201D88E422BD3FFF785 +:1039B000A3FE8E4208BF4FF0400AFFF781FE626906 +:1039C0000138013512781BFA80F1013002F01F0234 +:1039D0002DB242EA491289F001094AEA020A48F086 +:1039E000004281F808A059468BF810003846CBF801 +:1039F00004204FF0000AFFF79FFD238CB342B8D19B +:103A00007FE70022C6E7E169895D01360EF8021002 +:103A1000B6B20132C0E76FF0010572E7F8B515469E +:103A20000E463022002104461F46FDF7D9FF069BB3 +:103A3000B5F5001FA760636004F11000079B34BF59 +:103A40006A094FF6FF72E661A362002397B29A42B9 +:103A500006D800230360A782E3822383E360F8BDD6 +:103A60000660013330462036F1E7000003781BB9C9 +:103A70004BB2002BC8BF0170704700000078704740 +:103A8000F8B50C46C969074611B9238C002B37D10C +:103A9000257E1F2D34D8387828BB228C072A2CD8B5 +:103AA000268A36F003032BD14FF6FF70FFF7CEFDC9 +:103AB00020F0010031024FF6FF72400441EA056137 +:103AC000400C41EA4025234629463846FFF7FCFED4 +:103AD000002807DD626913780133DBB21F2B88BF32 +:103AE00000231370F8BD218A2D0645EA0125054300 +:103AF0002046FFF71DFE0246E5E76FF00300F1E701 +:103B00006FF00100EEE7000070B58AB0044616467B +:103B10000021282268461D46FDF762FFBDF83830B7 +:103B200069462046ADF810300F9B05939DF8403054 +:103B30008DF81830119B0793BDF84830CDE9026528 +:103B4000ADF82030FFF79CFF0AB070BD2DE9F041C1 +:103B5000D36905460C4616460BB9138C5BBB377E02 +:103B60001F2F28D895F80080B8F1000F26D03046D6 +:103B7000FFF7DEFD337821020246284641EAC331D1 +:103B8000338A41EA080141EA076141EA03413346C9 +:103B900041F08001FFF798FE00280ADD3378012B01 +:103BA00007D1726913780133DBB21F2B88BF002362 +:103BB0001370BDE8F0816FF00100FAE76FF00300C9 +:103BC000F7E70000F0B58BB004460D46174600211C +:103BD000282268461E46FDF703FF9DF84C30294613 +:103BE00020465A1E534253416A468DF800309DF8D4 +:103BF0004030ADF81030119B05939DF848308DF89A +:103C00001830149B0793BDF85430CDE90276ADF817 +:103C10002030FFF79BFF0BB0F0BD0000406A00B101 +:103C200004307047436A1A68426202691A6003618D +:103C3000C38A013BC38270472DE9F041D0F8208050 +:103C400014461D46184E4146002709B9BDE8F081CB +:103C5000D1E90223A21A65EB0303964277EB030333 +:103C60001ED2036A8B420DD1FFF78CFD036A1B68DD +:103C7000036203690B60C38A0161013B016AC3826D +:103C80008846E2E7FFF77EFD0B68C8F8003003695D +:103C90000B60C38A0161013BC382D8F80010D4E7EE +:103CA00088460968D1E700BF80841E002DE9F04FE7 +:103CB0008BB00D4614469B46DDF850908046002898 +:103CC00000F01881B9F1000F00F01481531E3F2B52 +:103CD00000F21081012A03D1BBF1000F40F00A81EC +:103CE0000023CDE90833B8F81430B5EBC30F4FEA21 +:103CF000C30703D300200BB0BDE8F08F2B199F4200 +:103D0000D8F80C3036BF7F1B2746FFB21BB9D8F856 +:103D10001030002B7AD0272D4DD8C5F1280600236E +:103D20002946B742009308ABD8F808002CBFF6B27A +:103D30003E46A7EB060A354432465FFA8AFAFFF799 +:103D40003DFCB8F81430282103F10053053BDB009B +:103D50000493D8F80C300393039B13B1BAF1000F0E +:103D60002CD1D8F8100040B1BAF1000F05D008AB43 +:103D70005246691A0096FFF721FC38B2002FB9D0DD +:103D800066070AD00AAB624203EBD40102F00702D5 +:103D900011F8083C134101F8083C082C3DD9102CBF +:103DA00040F2B580202C40F2B780BBF1000F00F04C +:103DB0009C80082335E0BA460026C2E7049BE02B2E +:103DC00028BFE02306930B44AB42059315D95A1B39 +:103DD0000398691A0096924508AB00F1040034BFBD +:103DE0005246D2B20792FFF7E9FB079A1644AAEBB4 +:103DF000020A1544F6B25FFA8AFA049B069A0599FC +:103E00009B1A0493039B1B680393A5E700933A4610 +:103E100008AB2946D8F80800ADE7BBF1000F13D076 +:103E20000123B4EBC30F6BD0082C12D89DF82030BF +:103E3000621E23FA02F2D50706D54FF0FF3202FACE +:103E400004F423438DF820309DF8203089F80030A9 +:103E500051E7102C12D8BDF82030621E23FA02F26E +:103E6000D10706D54FF0FF3202FA04F42343ADF830 +:103E70002030BDF82030A9F800303CE7202C0FD8C6 +:103E80000899631E21FA03F3DA0705D54FF0FF32D4 +:103E900002FA04F40C430894089BC9F800302AE79E +:103EA000402C2AD0611EC4F12102A4F12103DDE9D6 +:103EB000086526FA01F105FA02F225FA03F3114327 +:103EC0001943CB0711D50122A4F12003C4F120012D +:103ED00002FA03F322FA01F1A2400B43524263EBD0 +:103EE000430332432B43CDE90823DDE90823C9E925 +:103EF000002300E76FF00100FDE66FF00800FAE62E +:103F0000082CA1D9102CB4D9202CEED8C4E7BBF1D1 +:103F1000000FAED0022384E7BBF1000FBCD0042316 +:103F20007FE70000012A30B5144638BF012485B070 +:103F30000025402C28BF4024012ACDE9025518D87D +:103F40001B788DF8083063070AD004AB624203EB9C +:103F5000D40502F0070215F8083C934005F8083C28 +:103F6000034600912246002102A8FFF727FB05B077 +:103F700030BD082AE4D9102A03D81B88ADF80830D0 +:103F8000E1E7202A95BF1B68D3E900230293CDE91E +:103F90000223D8E710B5CB681BB98B600B618B820D +:103FA00010BD04691A681C600361C38A013BC382A7 +:103FB000CA60F0E703064CBFC0F3C0300220704770 +:103FC00008B50246FFF7F6FF022806D15306C2F3F2 +:103FD0000F2001D100F0030008BDC2F30740FBE74A +:103FE0002DE9F04F93B004460D46CDE903230A684E +:103FF0001046FFF7DFFF0228824614BFC2F30626F1 +:104000000026002A80F2F88112F0C04940F0F481C5 +:10401000097B002900F0F081022803D02378B34205 +:1040200040F0ED81C2F3046310462944069302F088 +:104030007F030593FFF7C4FF059B002283464FEAE9 +:104040008348002348EA0A4848EA4668CE78CDE922 +:104050000823F30948EA0008029368D0059B02464A +:1040600008A92046009353466768B847002800F027 +:10407000C981276A4FB9414604F10C00FFF700FBE4 +:10408000074690B96FF0020055E03B6998450DD0A6 +:104090003F68002FF9D1414604F10C00FFF7F0FA18 +:1040A00007460028EED0236A3B60276297F817C0C6 +:1040B00006F01F08CCF3840CACEB0800A8EB0C0353 +:1040C0001FFA80FE0028B8BF0EF120001FFA83FE01 +:1040D000B8BF00B2002B0793B8BF0EF12003D7E999 +:1040E0000221BCBF1BB2079352EA010338D0039BE5 +:1040F0004FF0000CDFF81CE39A1A049B63EB0101FC +:1041000096457CEB01032BD36B7B97F81AE0734544 +:1041100019D1029B002B78D0012821DC7868F8B9EE +:10412000DFF8ECC2944570EB010316D337E0276A41 +:1041300027B96FF00C0013B0BDE8F08F3B699845CC +:10414000B4D03F68F4E7B24890427CEB010301D35E +:104150000020F0E7029B002BFAD0079B0F2B17DC07 +:10416000FA7DB3003946204602F0030203F07C03D7 +:104170001343FB75FFF706FB6B7BBB76029B3BB9DA +:10418000FB7DC3F38402013262F38603FB75D0E743 +:104190006A7BBB7E9A42DBD1029B002B35D0B309F0 +:1041A000022B32D0039B142200210DA8BB60049B7C +:1041B000FB60FDF715FC039B0AA920460A93049BAC +:1041C000ADF83EB00B932B1D8DF840A00C932B7BCC +:1041D0008DF84180013BDBB2ADF83C30069B8DF899 +:1041E0004230059B8DF8433094F82C3083F0010366 +:1041F0008DF84430A3689847FB7DC3F384030133F3 +:1042000003F01F039B02FB82A2E7FB7DC6F3401273 +:10421000B2EBD31F40F0F980C3F38403434540F071 +:10422000FB80029AB6092B7B002A52D016F00106B9 +:1042300061D1032B40F2F380039B394604F10C005B +:10424000BB60049BFB60FB8A66F30903AE1DFB8227 +:1042500032462B7B033BDBB2FFF7A6FA00280CDAD1 +:1042600039462046FFF78EFAFB7DC3F38403013302 +:1042700003F01F039B02FB8204E7AB88DDE908849F +:104280003B834FF6FF73C9F12000A9F1200228FA01 +:1042900009F109F1080904FA00F024FA02F20143D5 +:1042A00018461143C9B2FFF7C1F9B9F1400F0346EF +:1042B000E9D1B88231462A7B033AD2B2FFF7C6F978 +:1042C000FB7DB882DA43C2F3C01262F3C713FB75F9 +:1042D0003EE786B92E1D013B394604F10C00DBB2E6 +:1042E0003246FFF761FA0028BADB2A7B3146B88AEA +:1042F000013AD2B2E2E7F98A013BC1F30901DAB22D +:1043000004295BD8281D002307F11B069A4208D90F +:1043100010F801CB013306F801C00131DBB20529E9 +:10432000F4D1039993420A9138BF043304992CBF06 +:10433000002355FA83F30B9107F11B010C91796867 +:104340000E930D91291DFB8AADF83EB0C3F309030E +:104350008DF840A08DF841801A44069B8DF84230BC +:10436000059BADF83C208DF8433094F82C3083F059 +:1043700001038DF844300023B88A7B602A7B013A20 +:10438000FFF764F93B8BB882834203D1A3680AA983 +:104390002046984720460AA9FFF7FCFDFB7DBA8A14 +:1043A000C3F38403013303F01F039B02FB823B8BA7 +:1043B0009A420CBF00206FF01000BCE67B68002B17 +:1043C000AFD0052001E01C3033461E68002EFAD124 +:1043D000091A2E1D081D184401EB090C5FFA89F318 +:1043E000BCF11B0F9DD89A429BD916F8013B09F1ED +:1043F000010900F8013BEFE76FF009009BE66FF061 +:104400000A0098E66FF00B0095E66FF00D0092E65B +:1044100040420F0080841E006FF00E008BE66FF0AC +:104420000F0088E6EFF30983054968334A6B22F0F1 +:1044300001024A6383F30988002383F311887047DC +:1044400000EF00E0302080F3118862B60D4B0E4A79 +:10445000D96821F4E0610904090C0A430B49DA60C8 +:10446000D3F8FC2042F08072C3F8FC20084AC2F85E +:10447000B01F116841F0010111602022DA7783F842 +:104480002200704700ED00E00003FA0555CEACC5F0 +:10449000001000E0302310B583F311880E4B5B68E9 +:1044A00013F4006314D0F1EE103AEFF309844FF0E7 +:1044B0008073683CE361094BDB6B236684F30988F6 +:1044C00001F012FA10B1064BA36110BD054BFBE7DA +:1044D00083F31188F9E700BF00ED00E000EF00E092 +:1044E0003F0400084204000808B5074B074A196852 +:1044F00001F03D01996053680BB190689847BDE8A1 +:104500000840FFF7C7BF00BF00000240F46300206F +:1045100008B5084B1968890901F03D018A019A60C4 +:10452000054AD3680BB110699847BDE80840FFF70A +:10453000B1BF00BF00000240F463002008B5084B83 +:104540001968090C01F03D010A049A60054A536993 +:104550000BB190699847BDE80840FFF79BBF00BFCB +:1045600000000240F463002008B5084B1968890D6B +:1045700001F03D018A059A60054AD3690BB1106AC2 +:104580009847BDE80840FFF785BF00BF0000024024 +:10459000F463002008B5074B074A596801F03D0154 +:1045A000D960536A0BB1906A9847BDE80840FFF79D +:1045B00071BF00BF00000240F463002008B5084B43 +:1045C0005968890901F03D018A01DA60054AD36A18 +:1045D0000BB1106B9847BDE80840FFF75BBF00BF09 +:1045E00000000240F463002008B5084B5968090C2C +:1045F00001F03D010A04DA60054A536B0BB1906B80 +:104600009847BDE80840FFF745BF00BF00000240E3 +:10461000F463002008B5084B5968890D01F03D018D +:104620008A05DA60054AD36B0BB1106C9847BDE878 +:104630000840FFF72FBF00BF00000240F4630020D6 +:1046400008B5074B074A196801F03D019960536CA2 +:104650000BB1906C9847BDE80840FFF71BBF00BF47 +:1046600000040240F463002008B5084B196889096A +:1046700001F03D018A019A60054AD36C0BB1106DBF +:104680009847BDE80840FFF705BF00BF000402409F +:10469000F463002008B5084B1968090C01F03D01CE +:1046A0000A049A60054A536D0BB1906D9847BDE8B6 +:1046B0000840FFF7EFBE00BF00040240F463002093 +:1046C00008B5084B1968890D01F03D018A059A600B +:1046D000054AD36D0BB1106E9847BDE80840FFF74F +:1046E000D9BE00BF00040240F463002008B5074BA8 +:1046F000074A596801F03D01D960536E0BB1906EC5 +:104700009847BDE80840FFF7C5BE00BF000402405F +:10471000F463002008B5084B5968890901F03D0190 +:104720008A01DA60054AD36E0BB1106F9847BDE875 +:104730000840FFF7AFBE00BF00040240F463002052 +:1047400008B5084B5968090C01F03D010A04DA600C +:10475000054A536F0BB1906F9847BDE80840FFF7CB +:1047600099BE00BF00040240F463002008B5084B66 +:104770005968890D01F03D018A05DA60054AD36F59 +:1047800013B1D2F880009847BDE80840FFF782BE19 +:1047900000040240F463002000230C4910B51A46BF +:1047A0000B4C0B6054F82300026001EB4300043310 +:1047B0004260402BF6D1074A4FF0FF339360D3603D +:1047C000C2F80834C2F80C3410BD00BFF4630020F6 +:1047D00010810008000002400F28F8B510D91028F9 +:1047E00010D0112811D0122808D10F240720DFF88B +:1047F000C8E00126DEF80050A04208D9002653E0A8 +:104800000446F4E70F240020F1E70724FBE706FA4B +:1048100000F73D424AD1264C4FEA001C3D4304EBD1 +:1048200000160EEBC000CEF80050C0E90123FBB229 +:1048300073B12048D0F8D83043F00103C0F8D83025 +:10484000D0F8003143F00103C0F80031D0F8003156 +:1048500017F47F4F0ED01748D0F8D83043F002033A +:10486000C0F8D830D0F8003143F00203C0F800316E +:10487000D0F8003154F80C00036823F01F030360E4 +:10488000056815F00105FBD104EB0C033D2493F8FA +:104890000CC05F6804FA0CF43C602124056044619C +:1048A00012B1987B00F066F93046F8BD0130A3E7FD +:1048B0001081000800440258F463002010B5302431 +:1048C00084F31188FFF788FF002383F3118810BD5C +:1048D00010B50446807B00F063F901231549627B23 +:1048E00003FA02F20B6823EA0203DAB20B6072B930 +:1048F000114AD2F8D81021F00101C2F8D810D2F82C +:10490000001121F00101C2F80011D2F8002113F4C6 +:104910007F4F0ED1084BD3F8D82022F00202C3F803 +:10492000D820D3F8002122F00202C3F80021D3F8E6 +:10493000003110BDF46300200044025808B5302354 +:1049400083F31188FFF7C4FF002383F3118808BDA8 +:10495000026843681143016003B1184770470000C3 +:10496000024A136843F0C0031360704700780040A8 +:1049700013B50E4C204600F0BDFA04F114000023DC +:104980004FF400720A49009400F07AF9094B4FF491 +:104990000072094904F13800009400F0F3F9074A65 +:1049A000074BC4E9172302B010BD00BF7864002094 +:1049B000E464002061490008E466002000780040BB +:1049C00000E1F505037C30B5244C002918BF0C46E6 +:1049D000012B11D1224B98420ED1224BD3F8E82063 +:1049E00042F08042C3F8E820D3F8102142F0804220 +:1049F000C3F81021D3F810312268036EC16D03EBA8 +:104A000052038466B3FBF2F36268150442BF23F0DD +:104A1000070503F0070343EA4503CB60A36843F0AF +:104A200040034B60E36843F001038B6042F49673EC +:104A300043F001030B604FF0FF330B62510505D5C6 +:104A400012F0102205D0B2F1805F04D080F86430FB +:104A500030BD7F23FAE73F23F8E700BF108200084C +:104A600078640020004402582DE9F047C66D0546E1 +:104A70003768F469210734621AD014F0080118BFAE +:104A80004FF48071E20748BF41F02001A3074FF0C7 +:104A9000300348BF41F04001600748BF41F080014A +:104AA00083F31188281DFFF753FF002383F3118838 +:104AB000E2050AD5302383F311884FF48061281D65 +:104AC000FFF746FF002383F311884FF030094FF0C2 +:104AD000000A14F0200838D13B0616D54FF03009F3 +:104AE00005F1380A200610D589F31188504600F0E8 +:104AF0007DF9002836DA0821281DFFF729FF27F065 +:104B000080033360002383F31188790614D562068D +:104B100012D5302383F31188D5E913239A4208D1A3 +:104B20002B6C33B127F040071021281DFFF710FF31 +:104B30003760002383F31188E30618D5AA6E136942 +:104B4000ABB15069BDE8F047184789F31188736A23 +:104B5000284695F86410194000F0E6F98AF31188A8 +:104B6000F469B6E7B06288F31188F469BAE7BDE882 +:104B7000F0870000090100F16043012203F5614361 +:104B8000C9B283F8001300F01F039A4043099B0049 +:104B900003F1604303F56143C3F880211A60704755 +:104BA00000F01F0301229A40430900F160409B007E +:104BB00000F5614003F1604303F56143C3F88020D1 +:104BC000C3F88021002380F800337047F8B51546FC +:104BD000826804460B46AA4200D28568A16926690C +:104BE000761AB5420BD218462A46FCF7D3FEA369C3 +:104BF0002B44A3612846A3685B1BA360F8BD0CD9B6 +:104C0000AF1B18463246FCF7C5FE3A46E168304411 +:104C1000FCF7C0FEE3683B44EBE718462A46FCF786 +:104C2000B9FEE368E5E7000083689342F7B5044600 +:104C3000154600D28568D4E90460361AB5420BD215 +:104C40002A46FCF7A7FE63692B4463612846A368E4 +:104C50005B1BA36003B0F0BD0DD93246AF1B0191C1 +:104C6000FCF798FE01993A46E0683144FCF792FE61 +:104C7000E3683B44E9E72A46FCF78CFEE368E4E797 +:104C800010B50A440024C361029B8460C1600261C4 +:104C90000362C0E90000C0E9051110BD08B5D0E904 +:104CA0000532934201D1826882B982680132826002 +:104CB0005A1C426119700021D0E904329A4224BF83 +:104CC000C368436100F0C0FE002008BD4FF0FF3014 +:104CD000FBE7000070B5302304460E4683F31188CD +:104CE000A568A5B1A368A269013BA360531CA36199 +:104CF00015782269934224BFE368A361E3690BB18D +:104D000020469847002383F31188284607E0314660 +:104D1000204600F089FE0028E2DA85F3118870BD94 +:104D20002DE9F74F04460E4617469846D0F81C90DA +:104D30004FF0300A8AF311884FF0000B154665B129 +:104D40002A4631462046FFF741FF034660B94146F7 +:104D5000204600F069FE0028F1D0002383F311887B +:104D6000781B03B0BDE8F08FB9F1000F03D00190BC +:104D70002046C847019B8BF31188ED1A1E448AF325 +:104D80001188DCE7C160C361009B82600362C0E9F7 +:104D900005111144C0E9000001617047F8B50446EF +:104DA0000D461646302383F31188A768A7B1A36880 +:104DB000013BA36063695A1C62611D70D4E904322F +:104DC0009A4224BFE3686361E3690BB120469847C8 +:104DD000002080F3118807E03146204600F024FED1 +:104DE0000028E2DA87F31188F8BD0000D0E9052336 +:104DF00010B59A4201D182687AB9826800210132E5 +:104E000082605A1C82611C7803699A4224BFC3687D +:104E1000836100F019FE204610BD4FF0FF30FBE724 +:104E20002DE9F74F04460E4617469846D0F81C90D9 +:104E30004FF0300A8AF311884FF0000B154665B128 +:104E40002A4631462046FFF7EFFE034660B9414649 +:104E5000204600F0E9FD0028F1D0002383F31188FB +:104E6000781B03B0BDE8F08FB9F1000F03D00190BB +:104E70002046C847019B8BF31188ED1A1E448AF324 +:104E80001188DCE7026843681143016003B11847E9 +:104E9000704700001430FFF743BF00004FF0FF33AE +:104EA0001430FFF73DBF00003830FFF7B9BF0000F6 +:104EB0004FF0FF333830FFF7B3BF00001430FFF777 +:104EC00009BF00004FF0FF311430FFF703BF0000AF +:104ED0003830FFF763BF00004FF0FF323830FFF784 +:104EE0005DBF0000012914BF6FF013000020704760 +:104EF000FFF73EBD044B036000234360C0E902336B +:104F000001230374704700BF2882000810B53023C6 +:104F1000044683F31188FFF755FD02230020237414 +:104F200080F3118810BD000038B5C36904460D46F2 +:104F30001BB904210844FFF7A5FF294604F114001A +:104F4000FFF7ACFE002806DA201D4FF40061BDE833 +:104F50003840FFF797BF38BD0268436811430160CE +:104F600003B118477047000013B5406B00F580543B +:104F7000D4F8A4381A681178042914D1017C0229C4 +:104F800011D11979012312898B4013420BD101A948 +:104F90004C3002F0D9F9D4F8A4480246019B21799B +:104FA000206800F0DFF902B010BD0000143002F0FC +:104FB0005BB900004FF0FF33143002F055B9000028 +:104FC0004C3002F02DBA00004FF0FF334C3002F0AD +:104FD00027BA0000143002F029B900004FF0FF3169 +:104FE000143002F023B900004C3002F0F9B900008F +:104FF0004FF0FF324C3002F0F3B900000020704750 +:1050000010B500F58054D4F8A4381A681178042932 +:1050100017D1017C022914D15979012352898B407F +:1050200013420ED1143002F0BBF8024648B1D4F856 +:10503000A4484FF4407361792068BDE8104000F047 +:105040007FB910BD406BFFF7DBBF00007047000069 +:105050007FB5124B01250426044603600023057426 +:1050600000F1840243602946C0E902330C4B0290F0 +:10507000143001934FF44073009602F06DF8094B21 +:1050800004F69442294604F14C000294CDE90063F1 +:105090004FF4407302F034F904B070BD5082000840 +:1050A00045500008694F00080A68302383F31188CF +:1050B0000B790B3342F823004B79133342F823006A +:1050C0008B7913B10B3342F8230000F58053C3F8FA +:1050D000A41802230374002080F311887047000095 +:1050E00038B5037F044613B190F85430ABB90125AD +:1050F000201D0221FFF730FF04F114006FF00101C1 +:10510000257700F0ADFC04F14C0084F854506FF0AA +:105110000101BDE8384000F0A3BC38BD10B5012145 +:1051200004460430FFF718FF0023237784F8543037 +:1051300010BD000038B504460025143002F024F8F4 +:1051400004F14C00257702F0F3F8201D84F8545048 +:105150000121FFF701FF2046BDE83840FFF750BFAF +:1051600090F8803003F06003202B06D190F8812066 +:105170000023212A03D81F2A06D800207047222A9C +:10518000FBD1C0E91D3303E0034A4267072282676F +:10519000C3670120704700BF3C23002037B500F5EE +:1051A0008055D5F8A4381A68117804291AD1017CE1 +:1051B000022917D11979012312898B40134211D189 +:1051C00000F14C04204602F073F958B101A92046C1 +:1051D00002F0BAF8D5F8A4480246019B217920686C +:1051E00000F0C0F803B030BD01F10B03F0B550F88A +:1051F000236085B004460D46FEB1302383F3118849 +:1052000004EB8507301D0821FFF7A6FEFB6806F1B9 +:105210004C005B691B681BB1019002F0A3F8019878 +:1052200003A902F091F8024648B1039B29462046A3 +:1052300000F098F8002383F3118805B0F0BDFB68F7 +:105240005A691268002AF5D01B8A013B1340F1D13C +:1052500004F18002EAE70000133138B550F821402C +:10526000ECB1302383F3118804F58053D3F8A428DC +:105270001368527903EB8203DB689B695D6845B173 +:1052800004216018FFF768FE294604F1140001F0BC +:1052900091FF2046FFF7B4FE002383F3118838BD49 +:1052A0007047000001F05EBA01234022002110B5D2 +:1052B000044600F8303BFCF793FB0023C4E90133BC +:1052C00010BD000010B53023044683F3118824225A +:1052D000416000210C30FCF783FB204601F064FAAA +:1052E00002230020237080F3118810BD70B500EBFD +:1052F0008103054650690E461446DA6018B1102243 +:105300000021FCF76DFBA06918B110220021FCF709 +:1053100067FB31462846BDE8704001F04BBB0000FA +:1053200083682022002103F0011310B50446836036 +:105330001030FCF755FB2046BDE8104001F0C6BB1D +:10534000F0B4012500EB810447898D40E4683D43BA +:10535000A469458123600023A2606360F0BC01F072 +:10536000E3BB0000F0B4012500EB810407898D4008 +:10537000E4683D436469058123600023A2606360A3 +:10538000F0BC01F059BC000070B5022300250446B2 +:10539000242203702946C0F888500C3040F8045C81 +:1053A000FCF71EFB204684F8705001F097FA636802 +:1053B0001B6823B129462046BDE87040184770BDE0 +:1053C0000378052B10B504460AD080F88C300523ED +:1053D000037043681B680BB1042198470023A36046 +:1053E00010BD00000178052906D190F88C20436893 +:1053F00002701B6803B118477047000070B590F841 +:105400007030044613B1002380F8703004F180023C +:10541000204601F07FFB63689B68B3B994F8803045 +:1054200013F0600535D00021204601F071FE002107 +:10543000204601F061FE63681B6813B10621204617 +:105440009847062384F8703070BD2046984700289E +:10545000E4D0B4F88630A26F9A4288BFA36794F96B +:105460008030A56F002B4FF0300380F20381002DB8 +:1054700000F0F280092284F8702083F31188002163 +:105480002046D4E91D23FFF76DFF002383F3118825 +:10549000DAE794F8812003F07F0343EA022340F225 +:1054A0000232934200F0C58021D8B3F5807F48D006 +:1054B0000DD8012B3FD0022B00F09380002BB2D1EE +:1054C00004F1880262670222A267E367C1E7B3F5CD +:1054D000817F00F09B80B3F5407FA4D194F88230A7 +:1054E000012BA0D1B4F8883043F0020332E0B3F5C9 +:1054F000006F4DD017D8B3F5A06F31D0A3F5C063BE +:10550000012B90D86368204694F882205E6894F856 +:105510008310B4F88430B047002884D043686367B0 +:105520000368A3671AE0B3F5106F36D040F6024265 +:1055300093427FF478AF5C4B63670223A367002339 +:10554000C3E794F88230012B7FF46DAFB4F8883054 +:1055500023F00203A4F88830C4E91D55E56778E715 +:10556000B4F88030B3F5A06F0ED194F882302046A5 +:1055700084F88A3001F010FA63681B6813B10121C6 +:1055800020469847032323700023C4E91D339CE77A +:1055900004F18B0363670123C3E72378042B10D145 +:1055A000302383F311882046FFF7BAFE85F3118874 +:1055B0000321636884F88B5021701B680BB120466F +:1055C000984794F88230002BDED084F88B30042387 +:1055D000237063681B68002BD6D0022120469847B1 +:1055E000D2E794F8843020461D0603F00F010AD557 +:1055F00001F082FA012804D002287FF414AF2B4B6B +:105600009AE72B4B98E701F069FAF3E794F88230B8 +:10561000002B7FF408AF94F8843013F00F01B3D05F +:105620001A06204602D501F08BFDADE701F07CFDA6 +:10563000AAE794F88230002B7FF4F5AE94F884301A +:1056400013F00F01A0D01B06204602D501F060FD2B +:105650009AE701F051FD97E7142284F8702083F354 +:1056600011882B462A4629462046FFF769FE85F316 +:105670001188E9E65DB1152284F8702083F3118862 +:1056800000212046D4E91D23FFF75AFEFDE60B2238 +:1056900084F8702083F311882B462A462946204639 +:1056A000FFF760FEE3E700BF808200087882000811 +:1056B0007C82000838B590F870300446002B3ED04C +:1056C000063BDAB20F2A34D80F2B32D8DFE803F0CA +:1056D00037313108223231313131313131313737DF +:1056E000856FB0F886309D4214D2C3681B8AB5FB23 +:1056F000F3F203FB12556DB9302383F311882B4667 +:105700002A462946FFF72EFE85F311880A2384F8DE +:1057100070300EE0142384F87030302383F3118846 +:10572000002320461A461946FFF70AFE002383F39A +:10573000118838BDC36F03B198470023E7E7002104 +:10574000204601F0E5FC0021204601F0D5FC63680D +:105750001B6813B10621204698470623D7E70000AF +:1057600010B590F870300446142B29D017D8062BAA +:1057700005D001D81BB110BD093B022BFBD800217D +:10578000204601F0C5FC0021204601F0B5FC63680D +:105790001B6813B1062120469847062319E0152BF4 +:1057A000E9D10B2380F87030302383F31188002374 +:1057B0001A461946FFF7D6FD002383F31188DAE76E +:1057C000C3689B695B68002BD5D1C36F03B1984751 +:1057D000002384F87030CEE70023826803750369E4 +:1057E0001B6899689142FBD25A680360426010605E +:1057F0005860704700238268037503691B689968C5 +:105800009142FBD85A68036042601060586070474C +:1058100008B50846302383F311880A7D0023052A42 +:1058200006D8DFE802F00B050503120E826913604B +:105830004FF0FF338361FFF7CFFF002383F311881D +:1058400008BD8269936801339360D0E90032136028 +:105850005A60EDE7FFF7C0BF054BD96808751868B7 +:10586000026853601A600122D8600275FAF7D2BD4F +:10587000E86800200C4B30B5DD684B1C87B004464F +:105880000FD02B46094A684600F07EF92046FFF704 +:10589000E3FF009B13B1684600F080F9A86907B0E8 +:1058A00030BDFFF7D9FFF9E7E8680020115800087C +:1058B00038B50C4D04468161EB6881689A68914265 +:1058C00003D8BDE83840FFF787BF1846FFF792FFBF +:1058D00001230146EC6020462375BDE83840FAF705 +:1058E00099BD00BFE8680020044B1A68DB68906827 +:1058F0009B68984294BF002001207047E868002010 +:10590000084B10B51C68D868226853601A600122E1 +:10591000DC602275FFF76EFF01462046BDE81040AF +:10592000FAF778BDE868002038B50123084C002557 +:105930002370656001F0F8FD01F01EFE0549064880 +:1059400001F0F2FE0223237085F3118838BD00BFF9 +:10595000506B002088820008E868002008B572B605 +:10596000044B186500F026FD00F0E8FD024B032211 +:105970001A70FEE7E8680020506B002000F044B980 +:10598000034A516853685B1A9842FBD8704700BFBE +:10599000001000E08B600223086108468B8270478C +:1059A0008368A3F1840243F8142C026943F8442C61 +:1059B000426943F8402C094A43F8242CC268A3F1F9 +:1059C000200043F8182C022203F80C2C002203F8C4 +:1059D0000B2C034A43F8102C704700BF2D0400081D +:1059E000E868002008B5FFF7DBFFBDE80840FFF7D7 +:1059F00031BF0000024BDB6898610F20FFF72CBF1E +:105A0000E8680020302383F31188FFF7F3BF00001C +:105A100008B50146302383F311880820FFF72AFFD9 +:105A2000002383F3118808BD064BDB6839B1426857 +:105A300018605A60136043600420FFF71BBF4FF0EB +:105A4000FF307047E86800200368984206D01A6863 +:105A50000260506018469961FFF7FCBE7047000075 +:105A600038B504460D462068844200D138BD03682D +:105A700023605C608561FFF7EDFEF4E7036810B515 +:105A80009C68A2420CD85C688A600B604C60216004 +:105A9000596099688A1A9A604FF0FF33836010BD8D +:105AA000121B1B68ECE700000A2938BF0A2170B5F9 +:105AB00004460D460A26601901F030FD01F018FD7C +:105AC000041BA54203D8751C04462E46F3E70A2E94 +:105AD00004D90120BDE8704001F066BE70BD000031 +:105AE000F8B5144B0D460A2A4FF00A07D96103F1A5 +:105AF0001001826038BF0A224160196914460160B2 +:105B000048601861A81801F0F9FC01F0F1FC431B92 +:105B10000646A34206D37C1C28192746354601F0C9 +:105B2000FDFCF2E70A2F04D90120BDE8F84001F09E +:105B30003BBEF8BDE8680020F8B506460D4601F00A +:105B4000D7FC0F4A134653F8107F9F4206D12A46CE +:105B500001463046BDE8F840FFF7C2BFD169BB68D7 +:105B6000441A2C1928BF2C46A34202D92946FFF714 +:105B70009BFF224631460348BDE8F840FFF77EBF51 +:105B8000E8680020F8680020C0E90323002310B46F +:105B90005DF8044B4361FFF7CFBF000010B5194C0F +:105BA000236998420DD08168D0E9003213605A60B1 +:105BB0009A680A449A60002303604FF0FF33A361A0 +:105BC00010BD0268234643F8102F53600022026084 +:105BD00022699A4203D1BDE8104001F099BC936854 +:105BE00081680B44936001F083FC2269E16992684B +:105BF000441AA242E4D91144BDE81040091AFFF743 +:105C000053BF00BFE86800202DE9F047DFF8BC80F3 +:105C100008F110072C4ED8F8105001F069FCD8F8A4 +:105C20001C40AA68031B9A423ED814444FF0000956 +:105C3000D5E90032C8F81C4013605A60C5F80090DE +:105C4000D8F81030B34201D101F062FC89F3118819 +:105C5000D5E9033128469847302383F311886B69CF +:105C6000002BD8D001F044FC6A69A0EB04098246FD +:105C70004A450DD2022001F097FD0022D8F81030DD +:105C8000B34208D151462846BDE8F047FFF728BF88 +:105C9000121A2244F2E712EB09092946384638BFA6 +:105CA0004A46FFF7EBFEB5E7D8F81030B34208D00C +:105CB0001444C8F81C00211AA960BDE8F047FFF79A +:105CC000F3BEBDE8F08700BFF8680020E868002058 +:105CD00038B501F00DFC054AD2E90845031B181937 +:105CE00045F10001C2E9080138BD00BFE8680020A5 +:105CF00000207047FEE70000704700004FF0FF30C3 +:105D00007047000002290CD0032904D0012907485C +:105D100018BF00207047032A05D8054800EBC200D1 +:105D20007047044870470020704700BF6083000838 +:105D30004C2300201483000870B59AB0054608462D +:105D4000144601A900F0C2F801A8FBF741FE431C6C +:105D50000022C6B25B001046C5E90034237003235D +:105D6000023404F8013C01ABD1B202348E4201D8B6 +:105D70001AB070BD13F8011B013204F8010C04F8CD +:105D8000021CF1E708B5302383F311880348FFF7BD +:105D900005FA002383F3118808BD00BF586B00206B +:105DA00090F8803003F01F02012A07D190F881207B +:105DB0000B2A03D10023C0E91D3315E003F0600373 +:105DC000202B08D1B0F884302BB990F88120212AFB +:105DD00003D81F2A04D8FFF7C3B9222AEBD0FAE769 +:105DE000034A426707228267C3670120704700BFEA +:105DF0004323002007B5052917D8DFE801F019165D +:105E000003191920302383F31188104A01210190CE +:105E1000FFF76CFA019802210D4AFFF767FA0D4867 +:105E2000FFF788F9002383F3118803B05DF804FBC2 +:105E3000302383F311880748FFF752F9F2E7302344 +:105E400083F311880348FFF769F9EBE7B482000890 +:105E5000D8820008586B002038B50C4D0C4C2A46EF +:105E60000C4904F10800FFF767FF05F1CA0204F1CD +:105E700010000949FFF760FF05F5CA7204F1180028 +:105E80000649BDE83840FFF757BF00BF3084002007 +:105E90004C230020948200089E820008A9820008FA +:105EA00070B5044608460D46FBF792FDC6B2204683 +:105EB000013403780BB9184670BD32462946FBF70A +:105EC00073FD0028F3D10120F6E700002DE9F0472B +:105ED00005460C46FBF77CFD2C49C6B22846FFF769 +:105EE000DFFF08B11036F6B229492846FFF7D8FF80 +:105EF00008B11036F6B2632E0BD8DFF89080DFF8C9 +:105F00009090244FDFF898A02E7846B92670BDE80F +:105F1000F08729462046BDE8F04702F05DB8252EFF +:105F200030D1072241462846FBF73EFD80B91A4B87 +:105F3000224603F1140153F8040B8B4242F8040B80 +:105F4000F9D1198807359B78173411809370DBE7F6 +:105F5000082249462846FBF727FD98B9A21C0F4B9B +:105F6000197802320909C95D02F8041C13F8011BF3 +:105F700001F00F015345C95D02F8031CF0D118343C +:105F80000835C1E7013504F8016BBDE780830008DF +:105F9000A982000888830008F67F000800E8F11F46 +:105FA0000CE8F11FBFF34F8F044B1A695107FCD166 +:105FB000D3F810215207F8D1704700BF00200052DB +:105FC00008B50D4B1B78ABB9FFF7ECFF0B4BDA684C +:105FD000D10704D50A4A5A6002F188325A60D3F8D0 +:105FE0000C21D20706D5064AC3F8042102F18832F3 +:105FF000C3F8042108BD00BF8E8600200020005297 +:106000002301674508B5114B1B78F3B9104B1A698A +:10601000510703D5DA6842F04002DA60D3F8102164 +:10602000520705D5D3F80C2142F04002C3F80C21E9 +:10603000FFF7B8FF064BDA6842F00102DA60D3F8E6 +:106040000C2142F00102C3F80C2108BD8E8600200D +:10605000002000520F289ABF00F580604004002005 +:10606000704700004FF40030704700001020704768 +:106070000F2808B50BD8FFF7EDFF00F500330268D5 +:10608000013204D104308342F9D1012008BD00203F +:10609000FCE700000F2838B505463FD8FFF782FF20 +:1060A0001F4CFFF78DFF4FF0FF3307286361C4F8E3 +:1060B00014311DD82361FFF775FF030243F0240359 +:1060C000E360E36843F08003E36023695A07FCD48C +:1060D0002846FFF767FFFFF7BDFF4FF4003100F0E0 +:1060E00009FA2846FFF78EFFBDE83840FFF7C0BF2A +:1060F000C4F81031FFF756FFA0F108031B0243F06C +:106100002403C4F80C31D4F80C3143F08003C4F8F4 +:106110000C31D4F810315B07FBD4D9E7002038BD2F +:10612000002000522DE9F84F05460C46104645EA7E +:106130000203DE0602D00020BDE8F88F20F01F0029 +:10614000DFF8BCB0DFF8BCA0FFF73AFF04EB0008B3 +:10615000444503D10120FFF755FFEDE720222946F2 +:10616000204601F007FF10B920352034F0E72B4618 +:1061700005F120021F68791CDDD104339A42F9D160 +:1061800005F178431B481C4EB3F5801F1B4B38BFED +:10619000184603F1F80332BFD946D1461E46FFF731 +:1061A00001FF0760A5EB040C336804F11C0143F008 +:1061B00002033360231FD9F8007017F00507FAD1E6 +:1061C00053F8042F8B424CF80320F4D1BFF34F8FC8 +:1061D000FFF7E8FE4FF0FF332022214603602846F8 +:1061E000336823F00203336001F0C4FE0028BBD003 +:1061F0003846B0E7142100520C20005214200052FF +:10620000102000521021005210B5084C237828B1FC +:106210001BB9FFF7D5FE0123237010BD002BFCD066 +:106220002070BDE81040FFF7EDBE00BF8E86002055 +:106230002DE9F04F0D4685B0814658B111F00D069D +:1062400014BF2022082211F00803019304D0431E3A +:1062500003426AD0002435E0002E37D009F11F0137 +:1062600021F01F094FF00108324F05F00403DFF859 +:10627000D0A005EA080BBBF1000F32D07869C00747 +:106280002FD408F101080C37B8F1060FF3D19EB9ED +:10629000294D4946A819019201F090F904460028B9 +:1062A0003AD11836019A782EF3D1494601F086F991 +:1062B0000446002830D1019A4946204801F07EF971 +:1062C000044668BB204605B0BDE8F08F0029C9D15F +:1062D00001462846029201F071F90446E0B9029A9B +:1062E000C0E713B178694107CBD5AC0702D578690F +:1062F0008007C6D5019911B178690107C1D5182069 +:10630000494600FB08A0CDE9022301F057F90446F5 +:10631000DDE902230028B4D04A460021204601E0EE +:106320004A460021FBF75CFBCCE70246002E95D1E4 +:1063300098E700BF9C830008C0860020908600205C +:10634000A88600200121FFF773BF0000F8B5144DA7 +:1063500001241827134E40F2FF3200210120FBF7E1 +:106360003FFB07FB046001342A6955F80C1F01F05C +:1063700011F9062CF5D137254FF4C0542046FFF70C +:10638000E1FF014628B122460748BDE8F84001F088 +:1063900001B9C4EBC404013D4FEAD404EED1F8BD09 +:1063A0009C830008A88600209086002008B101F098 +:1063B00077B9704738B5054D00240334696855F83E +:1063C0000C0B00F0A9F8122CF7D138BD9C83000803 +:1063D00038B5EFF311859DB9EFF30584C4F30804D4 +:1063E000302334B183F31188FFF772FC85F31188F1 +:1063F00038BD83F31188FFF76BFC84F3118838BD37 +:10640000BDE83840FFF764BC10B5FFF7E1FF104C62 +:10641000C008104A002340EA4170C908A0FB04EC00 +:10642000A0FB020E1CEB0000A1FB044CA1FB02121E +:106430005B41001943EB0C0011EB0E0142F100022D +:10644000411842F10000090941EA007010BD00BF87 +:10645000CFF753E3A59BC4200244074BD2B210B53B +:10646000904200D110BD441C00B253F8200041F806 +:10647000040BE0B2F4E700BF504000580E4B30B5BB +:106480001C6F240405D41C6F1C671C6F44F400446B +:106490001C670A4C02442368D2B243F48073236021 +:1064A000074B904200D130BD441C51F8045B00B250 +:1064B00043F82050E0B2F4E7004402580048025884 +:1064C0005040005807B5012201A90020FFF7C4FF82 +:1064D000019803B05DF804FB13B50446FFF7F2FF23 +:1064E000A04205D0012201A900200194FFF7C6FFB8 +:1064F00002B010BD0144BFF34F8F064B884204D356 +:10650000BFF34F8FBFF36F8F7047C3F85C0220302B +:10651000F4E700BF00ED00E00144BFF34F8F064BEE +:10652000884204D3BFF34F8FBFF36F8F7047C3F818 +:1065300070022030F4E700BF00ED00E0704700007B +:10654000074B45F255521A6003225A6040F2FF721F +:106550009A604CF6CC421A600122024B1A707047C6 +:10656000004800583C870020034B1B781BB1034BAD +:106570004AF6AA221A6070473C870020004800585B +:10658000034B1A681AB9034AD2F8D0241A6070472C +:106590003887002000400258024B4FF48032C3F885 +:1065A000D02470470040025808B5FFF7E9FF024BBE +:1065B0001868C0F3806008BD3887002070B5BFF34D +:1065C0004F8FBFF36F8F1A4A0021C2F85012BFF3EA +:1065D0004F8FBFF36F8F536943F400335361BFF3A1 +:1065E0004F8FBFF36F8FC2F88410BFF34F8FD2F875 +:1065F000803043F6E074C3F3C900C3F34E335B014C +:1066000003EA0406014646EA81750139C2F8605280 +:10661000F9D2203B13F1200FF2D1BFF34F8F536912 +:1066200043F480335361BFF34F8FBFF36F8F70BD5F +:1066300000ED00E0FEE70000214B2248224A70B541 +:10664000904237D3214BC11EDA1C121A22F00302EA +:106650008B4238BF00220021FBF7C2F91C4A0023FD +:10666000C2F88430BFF34F8FD2F8803043F6E07425 +:10667000C3F3C900C3F34E335B0103EA04060146CA +:1066800046EA81750139C2F86C52F9D2203B13F108 +:10669000200FF2D1BFF34F8FBFF36F8FBFF34F8F38 +:1066A000BFF36F8F0023C2F85032BFF34F8FBFF399 +:1066B0006F8F70BD53F8041B40F8041BC0E700BF88 +:1066C000CC850008308900203089002030890020E6 +:1066D00000ED00E0074BD3F8D81021EA0001C3F821 +:1066E000D810D3F8002122EA0002C3F80021D3F821 +:1066F000003170470044025870B5D0E924430022AD +:106700004FF0FF359E6804EB42135101D3F80009A6 +:10671000002805DAD3F8000940F08040C3F80009EA +:10672000D3F8000B002805DAD3F8000B40F08040C6 +:10673000C3F8000B013263189642C3F80859C3F836 +:10674000085BE0D24FF00113C4F81C3870BD0000A4 +:10675000890141F02001016103699B06FCD41220EC +:10676000FFF70EB910B50A4C2046FEF79DFD094B08 +:10677000C4F89030084BC4F89430084C2046FEF71B +:1067800093FD074BC4F89030064BC4F8943010BD0D +:10679000408700200000084008840008DC870020B3 +:1067A000000004401484000870B503780546012BEE +:1067B0005CD1434BD0F89040984258D1414B0E21C8 +:1067C0006520D3F8D82042F00062C3F8D820D3F86F +:1067D000002142F00062C3F80021D3F80021D3F871 +:1067E000802042F00062C3F88020D3F8802022F09D +:1067F0000062C3F88020D3F88030FEF7BBF9324B3B +:10680000E360324BC4F800380023D5F89060C4F838 +:10681000003EC02323604FF40413A3633369002BAD +:10682000FCDA01230C203361FFF7AAF83369DB0798 +:10683000FCD41220FFF7A4F83369002BFCDA002601 +:106840002846A660FFF758FF6B68C4F81068DB683D +:10685000C4F81468C4F81C6883BB1D4BA3614FF0D7 +:10686000FF336361A36843F00103A36070BD194B5C +:106870009842C9D1134B4FF08060D3F8D82042F032 +:106880000072C3F8D820D3F8002142F00072C3F898 +:106890000021D3F80021D3F8802042F00072C3F821 +:1068A0008020D3F8802022F00072C3F88020D3F833 +:1068B0008030FFF70FFF0E214D209EE7064BCDE7FE +:1068C000408700200044025840140040030020028A +:1068D000003C30C0DC870020083C30C0F8B5D0F860 +:1068E0009040054600214FF000662046FFF730FF3C +:1068F000D5F8941000234FF001128F684FF0FF304D +:10690000C4F83438C4F81C2804EB431201339F4206 +:10691000C2F80069C2F8006BC2F80809C2F8080B97 +:10692000F2D20B68D5F89020C5F898306362102336 +:106930001361166916F01006FBD11220FFF720F83C +:10694000D4F8003823F4FE63C4F80038A36943F494 +:10695000402343F01003A3610923C4F81038C4F89E +:1069600014380B4BEB604FF0C043C4F8103B094B9D +:10697000C4F8003BC4F81069C4F80039D5F8983061 +:1069800003F1100243F48013C5F89820A362F8BD08 +:10699000E483000840800010D0F8902090F88A101E +:1069A000D2F8003823F4FE6343EA0113C2F800383A +:1069B000704700002DE9F84300EB8103D0F89050B8 +:1069C0000C468046DA680FFA81F94801166806F02D +:1069D0000306731E022B05EB41134FF0000194BF19 +:1069E000B604384EC3F8101B4FF0010104F1100338 +:1069F00098BF06F1805601FA03F3916998BF06F536 +:106A0000004600293AD0578A04F15801374349011A +:106A10006F50D5F81C180B430021C5F81C382B18F3 +:106A20000127C3F81019A7405369611E9BB3138A4D +:106A3000928B9B08012A88BF5343D8F89820981856 +:106A400042EA034301F140022146C8F89800284673 +:106A500005EB82025360FFF77BFE08EB8900C368F9 +:106A60001B8A43EA845348341E4364012E51D5F8EF +:106A70001C381F43C5F81C78BDE8F88305EB49179F +:106A8000D7F8001B21F40041C7F8001BD5F81C18EB +:106A900021EA0303C0E704F13F030B4A28462146DD +:106AA00005EB83035A60FFF753FE05EB4910D0F85E +:106AB000003923F40043C0F80039D5F81C3823EA24 +:106AC0000707D7E70080001000040002D0F89420E8 +:106AD0001268C0F89820FFF70FBE00005831D0F8B8 +:106AE000903049015B5813F4004004D013F4001FA8 +:106AF0000CBF0220012070474831D0F89030490186 +:106B00005B5813F4004004D013F4001F0CBF0220A4 +:106B10000120704700EB8101CB68196A0B68136094 +:106B20004B6853607047000000EB810330B5DD68AF +:106B3000AA691368D36019B9402B84BF402313603E +:106B40006B8A1468D0F890201C4402EB4110013C81 +:106B500009B2B4FBF3F46343033323F0030343EAC2 +:106B6000C44343F0C043C0F8103B2B6803F0030359 +:106B7000012B0ED1D2F8083802EB411013F4807FBC +:106B8000D0F8003B14BF43F0805343F00053C0F8EB +:106B9000003B02EB4112D2F8003B43F00443C2F841 +:106BA000003B30BD2DE9F041D0F8906005460C4621 +:106BB00006EB4113D3F8087B3A07C3F8087B08D5E6 +:106BC000D6F814381B0704D500EB8103DB685B683B +:106BD0009847FA071FD5D6F81438DB071BD505EB05 +:106BE0008403D968CCB98B69488A5A68B2FBF0F63D +:106BF00000FB16228AB91868DA6890420DD2121A80 +:106C0000C3E90024302383F3118821462846FFF787 +:106C10008BFF84F31188BDE8F081012303FA04F2AD +:106C20006B8923EA02036B81CB68002BF3D02146EA +:106C30002846BDE8F041184700EB81034A0170B5D2 +:106C4000DD68D0F890306C692668E66056BB1A445F +:106C50004FF40020C2F810092A6802F00302012A4A +:106C60000AB20ED1D3F8080803EB421410F4807F67 +:106C7000D4F8000914BF40F0805040F00050C4F830 +:106C8000000903EB4212D2F8000940F00440C2F8B8 +:106C900000090122D3F8340802FA01F10143C3F8D4 +:106CA000341870BD19B9402E84BF40202060206880 +:106CB0001A442E8A8419013CB4FBF6F440EAC4401D +:106CC00040F00050C6E700002DE9F843D0F890608E +:106CD00005460C464F0106EB4113D3F8088918F01E +:106CE000010FC3F808891CD0D6F81038DB0718D577 +:106CF00000EB8103D3F80CC0DCF81430D3F800E0CB +:106D0000DA68964530D2A2EB0E024FF000091A6005 +:106D1000C3F80490302383F31188FFF78DFF89F3C4 +:106D2000118818F0800F1DD0D6F834380126A640FF +:106D3000334217D005EB84030134D5F89050D3F8D3 +:106D40000CC0E4B22F44DCF8142005EB0434D2F874 +:106D500000E05168714514D3D5F8343823EA0606AB +:106D6000C5F83468BDE8F883012303FA01F203890A +:106D700023EA02030381DCF80830002BD1D09847C6 +:106D8000CFE7AEEB0103BCF81000834228BF0346F7 +:106D9000D7F8180980B2B3EB800FE3D89068A0F160 +:106DA000040959F8048FC4F80080A0EB090898443E +:106DB000B8F1040FF5D818440B4490605360C8E74D +:106DC0002DE9F84FD0F8905004466E69AB691E402B +:106DD00016F480586E6103D0BDE8F84FFEF7D4BAC0 +:106DE000002E12DAD5F8003E9B0705D0D5F8003EFC +:106DF00023F00303C5F8003ED5F80438204623F0FD +:106E00000103C5F80438FEF7EDFA370505D520462D +:106E1000FFF772FC2046FEF7D3FAB0040CD5D5F884 +:106E2000083813F0060FEB6823F470530CBF43F4DB +:106E3000105343F4A053EB6031071BD56368DB6844 +:106E40001BB9AB6923F00803AB612378052B0CD188 +:106E5000D5F8003E9A0705D0D5F8003E23F003038D +:106E6000C5F8003E2046FEF7BDFA6368DB680BB14B +:106E700020469847F30200F1BA80B70226D5D4F82D +:106E8000909000274FF0010A09EB4712D2F8003B1F +:106E900003F44023B3F5802F11D1D2F8003B002B2F +:106EA0000DDA62890AFA07F322EA0303638104EB2D +:106EB0008703DB68DB6813B1394620469847013702 +:106EC000D4F89430FFB29B689F42DDD9F00619D503 +:106ED000D4F89000026AC2F30A1702F00F0302F41A +:106EE000F012B2F5802F00F0CA80B2F5402F09D120 +:106EF00004EB8303002200F58050DB681B6A974295 +:106F000040F0B0803003D5F8185835D5E90303D5E3 +:106F100000212046FFF746FEAA0303D501212046A3 +:106F2000FFF740FE6B0303D502212046FFF73AFE30 +:106F30002F0303D503212046FFF734FEE80203D5D3 +:106F400004212046FFF72EFEA90203D50521204685 +:106F5000FFF728FE6A0203D506212046FFF722FE2E +:106F60002B0203D507212046FFF71CFEEF0103D5B6 +:106F700008212046FFF716FE700340F1A780E907BD +:106F800003D500212046FFF79FFEAA0703D5012164 +:106F90002046FFF799FE6B0703D502212046FFF735 +:106FA00093FE2F0703D503212046FFF78DFEEE0643 +:106FB00003D504212046FFF787FEA80603D5052147 +:106FC0002046FFF781FE690603D506212046FFF71C +:106FD0007BFE2A0603D507212046FFF775FEEB0549 +:106FE00074D520460821BDE8F84FFFF76DBED4F8F0 +:106FF00090904FF0000B4FF0010AD4F894305FFAF4 +:107000008BF79B689F423FF638AF09EB4713D3F8E5 +:10701000002902F44022B2F5802F20D1D3F80029B4 +:10702000002A1CDAD3F8002942F09042C3F8002964 +:10703000D3F80029002AFBDB3946D4F89000FFF78B +:1070400087FB22890AFA07F322EA0303238104EB70 +:107050008703DB689B6813B13946204698470BF1DC +:10706000010BCAE7910701D1D0F80080072A02F18D +:1070700001029CBF03F8018B4FEA18283FE704EB9D +:10708000830300F58050DA68D2F818C0DCF80820D5 +:10709000DCE9001CA1EB0C0C00218F4208D1DB685D +:1070A0009B699A683A449A605A683A445A6029E758 +:1070B00011F0030F01D1D0F800808C4501F10101DE +:1070C00084BF02F8018B4FEA1828E6E7BDE8F88F85 +:1070D00008B50348FFF774FEBDE80840FDF7DAB9CC +:1070E0004087002008B50348FFF76AFEBDE8084066 +:1070F000FDF7D0B9DC870020D0F8903003EB4111C8 +:10710000D1F8003B43F40013C1F8003B7047000086 +:10711000D0F8903003EB4111D1F8003943F400135B +:10712000C1F8003970470000D0F8903003EB4111EE +:10713000D1F8003B23F40013C1F8003B7047000076 +:10714000D0F8903003EB4111D1F8003923F400134B +:10715000C1F800397047000030B50433039C017258 +:10716000002104FB0325C160C0E90653049B0363AF +:10717000059BC0E90000C0E90422C0E90842C0E95B +:107180000A11436330BD00000022416AC260C0E9B9 +:107190000411C0E90A226FF00101FEF761BC000092 +:1071A000D0E90432934201D1C2680AB9181D704770 +:1071B00000207047036919600021C2680132C26073 +:1071C000C269134482699342036124BF436A036125 +:1071D000FEF73ABC38B504460D46E3683BB1626938 +:1071E0000020131D1268A3621344E36207E0237AB0 +:1071F00033B929462046FEF717FC0028EDDA38BDE2 +:107200006FF00100FBE70000C368C269013BC36087 +:107210004369134482699342436124BF436A4361D3 +:1072200000238362036B03B11847704770B53023A6 +:10723000044683F31188866A3EB9FFF7CBFF054603 +:1072400018B186F31188284670BDA36AE26A13F864 +:10725000015B9342A36202D32046FFF7D5FF0023D0 +:1072600083F31188EFE700002DE9F84F04460E463E +:10727000174698464FF0300989F311880025AA4631 +:10728000D4F828B0BBF1000F09D141462046FFF7E2 +:10729000A1FF20B18BF311882846BDE8F88FD4E90F +:1072A0000A12A7EB050B521A934528BF9346BBF170 +:1072B000400F1BD9334601F1400251F8040B9142B3 +:1072C00043F8040BF9D1A36A403640354033A3623A +:1072D000D4E90A239A4202D32046FFF795FF8AF3A6 +:1072E0001188BD42D8D289F31188C9E730465A4681 +:1072F000FAF750FBA36A5E445D445B44A362E7E790 +:1073000010B5029C0433017203FB0421C460C0E980 +:1073100006130023C0E90A33039B0363049BC0E9FF +:107320000000C0E90422C0E90842436310BD000028 +:10733000026A6FF00101C260426AC0E904220022C1 +:10734000C0E90A22FEF78CBBD0E904239A4201D19E +:10735000C26822B9184650F8043B0B6070470023FE +:107360001846FAE7C3680021C2690133C360436964 +:10737000134482699342436124BF436A4361FEF729 +:1073800063BB000038B504460D46E3683BB1236992 +:1073900000201A1DA262E2691344E36207E0237A27 +:1073A00033B929462046FEF73FFB0028EDDA38BD09 +:1073B0006FF00100FBE7000003691960C268013A41 +:1073C000C260C269134482699342036124BF436A65 +:1073D000036100238362036B03B118477047000009 +:1073E00070B530230D460446114683F31188866A32 +:1073F0002EB9FFF7C7FF10B186F3118870BDA36ADD +:107400001D70A36AE26A01339342A36204D3E16967 +:1074100020460439FFF7D0FF002080F31188EDE704 +:107420002DE9F84F04460D46904699464FF0300A34 +:107430008AF311880026B346A76A4FB94946204609 +:10744000FFF7A0FF20B187F311883046BDE8F88F21 +:10745000D4E90A073A1AA8EB0607974228BF17464D +:10746000402F1BD905F1400355F8042B9D4240F8ED +:10747000042BF9D1A36A40364033A362D4E90A232E +:107480009A4204D3E16920460439FFF795FF8BF354 +:1074900011884645D9D28AF31188CDE729463A4664 +:1074A000FAF778FAA36A3D443E443B44A362E5E719 +:1074B000D0E904239A4217D1C3689BB1836A8BB188 +:1074C000043B9B1A0ED01360C368013BC360C369C1 +:1074D0001A4483699A42026124BF436A036100230C +:1074E00083620123184670470023FBE700F060BA6F +:1074F000014B586A704700BF000C0040034B00224C +:1075000058631A610222DA60704700BF000C004025 +:10751000014B0022DA607047000C0040014B5863B9 +:10752000704700BF000C0040024B034A1A60034A38 +:107530005A607047908800203089002000000220A7 +:10754000074B494210B55C68201A08401968821A36 +:107550008A4203D3A24201D85A6010BD0020FCE742 +:107560009088002008B5302383F31188FFF7E8FFE7 +:10757000002383F3118808BD04480121044B0360F4 +:107580000023C0E901330C3000F016B998880020C0 +:1075900065750008CB1D083A23F00703591A521AE3 +:1075A000012110B4D2080024C0E9004384600C30EB +:1075B0001C605A605DF8044B00F0FEB82DE9F84FEE +:1075C000364ECD1D0F46002818BF0646082A4FEA42 +:1075D000D50538BF082206F10C08341D91464046F7 +:1075E00000F006F909F10701C9F1000E22462468EE +:1075F0006CB9404600F006F93368CBB3082249461F +:10760000E8009847044698B340E9026730E004EB8D +:10761000010CD4F804A00CEA0E0C0AF10100ACF144 +:10762000080304EBC0009842E0D9A0EB0C0CB5EBCA +:10763000EC0F4FEAEC0BD9D89C421CD204F10802A3 +:10764000AB45A3EB02024FEAE202626009D9691C72 +:10765000ED43206803EBC1025D44556043F83100FF +:1076600022601C465F60404644F8086B00F0CAF890 +:107670002046BDE8F88FAA45216802D11160234653 +:10768000EFE7013504EBC50344F8351003F10801B9 +:10769000401AC01058601360F1E700BF98880020BE +:1076A000F8B550F8043C044650F8085CA0F1080610 +:1076B00007332F1D0C35DB0840F8043C284600F04A +:1076C00097F83B469F421A6801D0B34228D20AB1CC +:1076D000964225D244F8082C54F8042C1E6001323E +:1076E00054F8081C06EBC200814206D148680244E7 +:1076F00044F8042C0A6844F8082C5868411C03EB31 +:10770000C1018E4207D154F8042C013202445A6060 +:1077100054F8082C1A602846BDE8F84000F072B80A +:107720001346CFE7FEE7000070B51B4B002504466B +:1077300086B058600E4685620163FCF783FE04F153 +:107740001003A560E562C4E904334FF0FF33C4E9D8 +:107750000044C4E90635FFF7CBFE2B46024604F190 +:1077600034012046C4E9082380230C4A2565FEF72E +:1077700011F901230A4AE0600092037568467268B5 +:107780000192B268CDE90223064BCDE90435FEF73C +:1077900029F906B070BD00BF506B0020208400089E +:1077A0002584000825770008024AD36A1843D0626E +:1077B000704700BFE8680020C0E9000081607047A2 +:1077C0008368013B002B10B583600CDA074BDC6843 +:1077D0004368A061206063601C6044600520FEF780 +:1077E0003BF8A06910BD0020FCE700BFE86800205E +:1077F00008B5302383F31188FFF7E2FF002383F3FA +:10780000118808BD08B5302383F3118883680133DC +:10781000002B836007DC036800211A680260506057 +:107820001846FEF745F8002383F3118808BD0000D1 +:107830004B6843608B688360CB68C3600B694361AE +:107840004B6903628B6943620B68036070470000F9 +:1078500008B53C4B40F2FF713B48D3F888200A43FF +:10786000C3F88820D3F8882022F4FF6222F00702B0 +:10787000C3F88820D3F88820D3F8E0200A43C3F85F +:10788000E020D3F808210A43C3F808212F4AD3F88F +:1078900008311146FFF7CCFF00F5806002F11C01B2 +:1078A000FFF7C6FF00F5806002F13801FFF7C0FF67 +:1078B00000F5806002F15401FFF7BAFF00F5806027 +:1078C00002F17001FFF7B4FF00F5806002F18C0156 +:1078D000FFF7AEFF00F5806002F1A801FFF7A8FFF7 +:1078E00000F5806002F1C401FFF7A2FF00F580609F +:1078F00002F1E001FFF79CFF00F5806002F1FC015E +:10790000FFF796FF02F58C7100F58060FFF790FF9E +:1079100000F01AF90E4BD3F8902242F00102C3F89E +:107920009022D3F8942242F00102C3F89422052257 +:10793000C3F898204FF06052C3F89C20054AC3F862 +:10794000A02008BD00440258000002582C84000802 +:1079500000ED00E01F00080308B500F0D7FAFDF7BE +:10796000E3FF104BD3F8DC2042F04002C3F8DC20E8 +:10797000D3F8042122F04002C3F80421D3F80431E3 +:10798000094B1A6842F008021A601A6842F00402B1 +:107990001A60FEF7F5FDFEF7D9FCBDE80840FEF7DA +:1079A0005BBA00BF0044025800180248704700004C +:1079B000114BD3F8E82042F00802C3F8E820D3F8CE +:1079C000102142F00802C3F810210C4AD3F81031FC +:1079D000D36B43F00803D363C722094B9A624FF07D +:1079E000FF32DA6200229A615A63DA605A60012239 +:1079F0005A611A60704700BF004402580010005CD2 +:107A0000000C0040094A08B51169D3680B40D9B28F +:107A10009B076FEA0101116107D5302383F31188B9 +:107A2000FDF7ACFF002383F3118808BD000C004074 +:107A3000064BD3F8DC200243C3F8DC20D3F8042142 +:107A40001043C3F80401D3F80431704700440258CE +:107A500008B53C4B4FF0FF31D3F8802062F0004274 +:107A6000C3F88020D3F8802002F00042C3F88020C1 +:107A7000D3F88020D3F88420C3F88410D3F884206E +:107A80000022C3F88420D3F88400D86F40F0FF4070 +:107A900040F4FF0040F4DF4040F07F00D867D86F2B +:107AA00020F0FF4020F4FF0020F4DF4020F07F00B2 +:107AB000D867D86FD3F888006FEA40506FEA50500B +:107AC000C3F88800D3F88800C0F30A00C3F8880020 +:107AD000D3F88800D3F89000C3F89010D3F8900042 +:107AE000C3F89020D3F89000D3F89400C3F8941012 +:107AF000D3F89400C3F89420D3F89400D3F89800F6 +:107B0000C3F89810D3F89800C3F89820D3F89800D9 +:107B1000D3F88C00C3F88C10D3F88C00C3F88C20F9 +:107B2000D3F88C00D3F89C00C3F89C10D3F89C10B9 +:107B3000C3F89C20D3F89C30FCF72EFEBDE808402B +:107B400000F0B8B90044025808B50122534BC3F8FD +:107B50000821534BD3F8F42042F00202C3F8F4207A +:107B6000D3F81C2142F00202C3F81C210222D3F8F0 +:107B70001C314C4BDA605A689104FCD54A4A1A60B1 +:107B800001229A60494ADA6000221A614FF44042A9 +:107B90009A61444B9A699204FCD51A6842F4807247 +:107BA0001A603F4B1A6F12F4407F04D04FF48032BA +:107BB0001A6700221A671A6842F001021A60384BED +:107BC0001A685007FCD500221A611A6912F03802AF +:107BD000FBD1012119604FF0804159605A67344A46 +:107BE000DA62344A1A611A6842F480321A602C4B05 +:107BF0001A689103FCD51A6842F480521A601A6818 +:107C00009204FCD52C4A2D499A6200225A631963CA +:107C100001F57C01DA6301F5E77199635A64284A3A +:107C20001A64284ADA621A6842F0A8521A601C4B99 +:107C30001A6802F02852B2F1285FF9D148229A61FD +:107C40004FF48862DA6140221A621F4ADA641F4ADE +:107C50001A651F4A5A651F4A9A6532231E4A1360E5 +:107C6000136803F00F03022BFAD10D4A136943F096 +:107C700003031361136903F03803182BFAD14FF093 +:107C80000050FFF7D5FE4FF08040FFF7D1FE4FF0D8 +:107C90000040BDE80840FFF7CBBE00BF00800051A8 +:107CA000004402580048025800C000F002000001E1 +:107CB0000000FF0100889008322060006302090183 +:107CC000470E0508DD0BBF01200000200000011059 +:107CD0000910E00000010110002000524FF0B042F6 +:107CE00008B5D2F8883003F00103C2F8883023B118 +:107CF000044A13680BB150689847BDE80840FCF788 +:107D0000C9BB00BFB08800204FF0B04208B5D2F820 +:107D1000883003F00203C2F8883023B1044A936824 +:107D20000BB1D0689847BDE80840FCF7B3BB00BF73 +:107D3000B08800204FF0B04208B5D2F8883003F088 +:107D40000403C2F8883023B1044A13690BB15069A7 +:107D50009847BDE80840FCF79DBB00BFB0880020F5 +:107D60004FF0B04208B5D2F8883003F00803C2F8EB +:107D7000883023B1044A93690BB1D0699847BDE8B4 +:107D80000840FCF787BB00BFB08800204FF0B0422E +:107D900008B5D2F8883003F01003C2F8883023B158 +:107DA000044A136A0BB1506A9847BDE80840FCF7D3 +:107DB00071BB00BFB08800204FF0B04310B5D3F8BE +:107DC000884004F47872C3F88820A30604D5124AC8 +:107DD000936A0BB1D06A9847600604D50E4A136BBC +:107DE0000BB1506B9847210604D50B4A936B0BB12E +:107DF000D06B9847E20504D5074A136C0BB1506C61 +:107E00009847A30504D5044A936C0BB1D06C9847EE +:107E1000BDE81040FCF73EBBB08800204FF0B043F7 +:107E200010B5D3F8884004F47C42C3F8882062057A +:107E300004D5164A136D0BB1506D9847230504D530 +:107E4000124A936D0BB1D06D9847E00404D50F4AE8 +:107E5000136E0BB1506E9847A10404D50B4A936E74 +:107E60000BB1D06E9847620404D5084A136F0BB16A +:107E7000506F9847230404D5044A936F0BB1D06F19 +:107E80009847BDE81040FCF705BB00BFB088002054 +:107E900008B50348FCF7E8FDBDE80840FCF7FABA6E +:107EA0007864002008B5FFF7ADFDBDE80840FCF799 +:107EB000F1BA0000062108B50846FCF75BFE062172 +:107EC0000720FCF757FE06210820FCF753FE062189 +:107ED0000920FCF74FFE06210A20FCF74BFE062185 +:107EE0001720FCF747FE06212820FCF743FE092156 +:107EF0007A20FCF73FFE07213220FCF73BFE0C21E5 +:107F00005220BDE80840FCF735BE000008B5FFF779 +:107F10009FFD00F00DF8FCF7EBFFFDF7C3F9FDF74F +:107F200095F8FFF743FDBDE80840FFF7DFBA000012 +:107F30000023054A19460133102BC2E9001102F152 +:107F40000802F8D1704700BFB08800200B460146F8 +:107F5000184600F001B8000010B5054C13462CB1CE +:107F60000A4601460220AFF3008010BD2046FCE720 +:107F70000000000010B501390244904201D10020F8 +:107F800005E0037811F8014FA34201D0181B10BD82 +:107F90000130F2E72DE9F041A3B1C91A1778014485 +:107FA000044603F1FF3C8C42204601D9002009E041 +:107FB0000578BD4204F10104F5D10CEB0405D61897 +:107FC000A54201D1BDE8F08115F8018D16F801ED4B +:107FD000F045F5D0E7E70000034611F8012B03F860 +:107FE000012B002AF9D170476F72672E6172647598 +:107FF00070696C6F742E437562654F72616E676550 +:108000002D7065726970682D686561767900000071 +:1080100053544D333248373F3F3F0053544D333272 +:10802000483733782F3732780053544D333248373E +:1080300034332F3735332F373530000001105A00D5 +:1080400003105900012058000320560040A2E4F11B +:10805000646891060041A3E5F2656992070000009B +:1080600043414E464449666163653A204D657373EA +:108070006167652052414D204F766572666C6F775F +:10808000210000004261642043414E4966616365FE +:1080900020696E6465782E00000100000001FF0079 +:1080A00000A0004000A4004000000000000000000C +:1080B000612B0008E9230008E93200085924000870 +:1080C000652400087D280008DD250008212400081B +:1080D00025240008FD230008E523000839280008AE +:1080E0000924000851340008152400080D28000850 +:1080F00001040E05054B02020E05054B04010E0599 +:10810000054B05010B04044B080106030346000060 +:1081100010000240080002400008024000000B006E +:1081200028000240080002400408024006010C003A +:1081300040000240080002400808024010020D0002 +:1081400058000240080002400C08024016030E00CE +:10815000700002400C0002401008024000040F00B2 +:10816000880002400C00024014080240060510007E +:10817000A00002400C000240180802401006110046 +:10818000B80002400C0002401C08024016072F00F5 +:108190001004024008040240200802400008380091 +:1081A000280402400804024024080240060939005D +:1081B000400402400804024028080240100A3A0025 +:1081C00058040240080402402C080240160B3B00F1 +:1081D000700402400C04024030080240000C3C00D5 +:1081E000880402400C04024034080240060D44009A +:1081F000A00402400C04024038080240100E450062 +:10820000B80402400C0402403C080240160F46002D +:1082100000960000000000000000000000000000C8 +:10822000000000000000000000000000B14E000847 +:108230009D4E0008D94E0008C54E0008D14E0008DA +:10824000BD4E0008A94E0008954E0008E54E0008F6 +:1082500000000000C94F0008B54F0008F14F0008AA +:10826000DD4F0008E94F0008D54F0008C14F000856 +:10827000AD4F0008FD4F00080000000001000000A5 +:108280000000000063300000848200084069002084 +:10829000506B00204172647550696C6F7400254208 +:1082A0004F415244252D424C002553455249414CE3 +:1082B000250000000200000000000000E951000855 +:1082C0005952000840004000008400201084002023 +:1082D0000200000000000000030000000000000099 +:1082E000A1520008000000001000000020840020BF +:1082F0000000000001000000000000004087002096 +:1083000001010200F55D0008055D0008A15D00089F +:10831000855D0008430000001C830008090243003B +:10832000020100C03209040000010202010005241C +:1083300000100105240100010424020205240600A6 +:1083400001070582030800FF09040100020A00007A +:1083500000070501024000000705810240000000FF +:1083600012000000688300081201100102000040A2 +:10837000091241570002010203010000040309042D +:1083800025424F415244250030313233343536379F +:1083900038394142434445460000000000010020B6 +:1083A00000FF010002000000000000300000040097 +:1083B0000800000000000024000008000400000085 +:1083C0000004000000FC0000020000000000043077 +:1083D00000800000080000000000003800000100DC +:1083E0000100000000000000FD530008B556000821 +:1083F00061570008400040007888002078880020FD +:10840000010000008888002080000000400100007A +:10841000080000000001000000100000080000003B +:108420006D61696E0069646C650000000000802A5F +:1084300000000000AAAAAAAA00000024FFFF000072 +:108440000000000000A00A0000210002000000005F +:10845000AAAAAAAA00000000FFFF0000000000096D +:10846000000009001400005400000000AAAAAAAAF3 +:1084700014000054FFFF0000000000000000000096 +:108480000A40100000000000AAAA8AAA00401000BA +:10849000FFFF0000990000000000000000810200C2 +:1084A00000000000AAAAAAAA00410100FFFF0000E4 +:1084B0000000007007000000000000000000000045 +:1084C000AAAAAAAA00000000FFFF00000000000006 +:1084D000000000000000000000000000AAAAAAAAF4 +:1084E00000000000FFFF000000000000000000008E +:1084F0000000000000000000AAAAAAAA00000000D4 +:10850000FFFF00000000000000000000000000006D +:1085100000000000AAAAAAAA00000000FFFF0000B5 +:10852000000000000000000000000000000000004B +:10853000AAAAAAAA00000000FFFF00000000000095 +:10854000000000000000000000000000AAAAAAAA83 +:1085500000000000FFFF000000000000000000001D +:10856000780500000000000000001E000000000070 +:10857000FE2A0100D2040000FF000000586B00201A +:1085800078640020000000001080000883040000D0 +:108590001B8000085004000029800008009600009D +:1085A0000000080096000000000800000400000021 +:1085B0007C830008000000000000000000000000B4 +:0C85C000000000000000000000000000AF :00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph_bl.bin b/Tools/bootloaders/CubeOrange-periph_bl.bin index a470da6051a965..7968f86fed1bdf 100755 Binary files a/Tools/bootloaders/CubeOrange-periph_bl.bin 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 index c5edc232014275..3d90b77c7a270e 100644 --- a/Tools/bootloaders/CubeOrange-periph_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000070020F1020008A1330008593300085E -:10001000813300085933000879330008F3020008DF -:10002000F3020008F3020008F30200088543000809 +:1000000000070020F102000839340008F13300082D +:1000100019340008F133000811340008F302000815 +:10002000F3020008F3020008F30200082544000868 :10003000F3020008F3020008F3020008F3020008CC :10004000F3020008F3020008F3020008F3020008BC -:10005000F3020008F3020008FD7700082978000881 -:100060005578000881780008AD78000849440008F8 -:10007000714400089D440008C9440008F544000884 -:100080001D45000849450008F3020008093300082F -:10009000313300081D33000845330008D9780008C3 +:10005000F3020008F3020008D97C0008057D0008BF +:10006000317D00085D7D0008897D0008E9440008B5 +:10007000114500083D450008694500089545000800 +:10008000BD450008E9450008F3020008A133000857 +:10009000C9330008B5330008DD330008B57D00081A :1000A000F3020008F3020008F3020008F30200085C :1000B000F3020008F3020008F3020008F30200084C :1000C000F3020008F3020008F3020008F30200083C :1000D000F3020008F3020008F3020008F30200082C -:1000E0003D790008F3020008F3020008F30200085B -:1000F000F3020008F3020008F30200087545000847 -:10010000F3020008F3020008C5790008F3020008B2 +:1000E000197E0008F3020008F3020008F30200087A +:1000F000F3020008F3020008F302000815460008A6 +:10010000F3020008F3020008A17E0008F3020008D1 :10011000F3020008F3020008F3020008F3020008EB -:10012000A1450008C9450008F5450008214600081A -:100130004D460008F3020008F3020008F30200082D +:10012000414600086946000895460008C146000897 +:10013000ED460008F3020008F3020008F30200088D :10014000F3020008F3020008F3020008F3020008BB -:1001500075460008A1460008CD460008F3020008D5 +:1001500015470008414700086D470008F3020008F2 :10016000F3020008F3020008F3020008F30200089B -:10017000F30200087D6E0008F3020008F302000895 -:10018000F3020008F3020008B1790008F302000846 +:10017000F3020008E1700008F3020008F30200082F +:10018000F3020008F30200088D7E0008F302000865 :10019000F3020008F3020008F3020008F30200086B :1001A000F3020008F3020008F3020008F30200085B :1001B000F3020008F3020008F3020008F30200084B :1001C000F3020008F3020008F3020008F30200083B -:1001D000F3020008696E0008F3020008F302000849 +:1001D000F3020008CD700008F3020008F3020008E3 :1001E000F3020008F3020008F3020008F30200081B :1001F000F3020008F3020008F3020008F30200080B :10020000F3020008F3020008F3020008F3020008FA @@ -52,49 +52,49 @@ :100320004F8FBFF36F8F40F20000C0F2F0004EF627 :100330008851CEF200010860BFF34F8FBFF36F8F7B :100340004FF00000E1EE100A4EF63C71CEF20001D3 -:100350000860062080F31488BFF36F8F05F0FAFF62 -:1003600007F008F84FF055301F491B4A91423CBF37 +:100350000860062080F31488BFF36F8F06F02CF935 +:1003600007F074FA4FF055301F491B4A91423CBFC9 :1003700041F8040BFAE71D49184A91423CBF41F885 :10038000040BFAE71A491B4A1B4B9A423EBF51F82D :10039000040B42F8040BF8E700201849184A914270 -:1003A0003CBF41F8040BFAE706F012F807F066F8D4 +:1003A0003CBF41F8040BFAE706F044F907F0D2FA33 :1003B000144C154DAC4203DA54F8041B8847F9E796 :1003C00000F042F8114C124DAC4203DA54F8041B11 -:1003D0008847F9E705F0FABF000700200023002056 +:1003D0008847F9E706F02CB9000700200023002029 :1003E0000000000808ED00E00001002000070020E8 -:1003F0009080000800230020D0230020D02300207C -:10040000C8880020E0020008E4020008E4020008B6 +:1003F00058850008002300206C2300207023002073 +:1004000030890020E0020008E4020008E40200084D :10041000E40200082DE9F04F2DED108AC1F80CD050 :10042000D0F80CD0BDEC108ABDE8F08F002383F328 -:1004300011882846A047002005F070FAFEE705F075 -:10044000EFF900DFFEE70000F8B501F0E9F901F08F -:100450007FFB05F003FF074605F072FF0546A8BBCA +:1004300011882846A047002005F0E4FAFEE705F001 +:100440005FFA00DFFEE70000F8B501F0E9F901F01E +:100450007FFB06F035F8074606F0A4F80546A8BB72 :100460001F4B9F4232D001339F4232D027F0FF0210 :100470001C4B9A4230D12E4642F21074F8B200F072 -:100480009BFF00F09FFF08B10024264601F0A8FD65 +:100480009BFF00F09FFF08B10024264601F0F0FD1D :1004900020B10024032000F079F8264635B1124B34 -:1004A0009F4203D0002405F043FF2646002005F0BC -:1004B000DFFE0EB100F080F801F0E8FA00F0B6FFC0 +:1004A0009F4203D0002406F075F82646002006F08F +:1004B00011F80EB100F080F801F0E8FA00F0B6FF94 :1004C000204600F037F900F077F8F9E72E460024CF :1004D000D7E704460126D4E7064641F28834D0E740 :1004E000010007B0000008B0263A09B008B501F0D5 :1004F00063F9A0F120035842584108BD07B541F205 :100500001203022101A8ADF8043001F073F903B021 :100510005DF804FB38B5302383F31188174803686E -:100520000BB105F0C7FA0023154A4FF47A7113484E -:1005300005F0B6FA002383F31188124C236813B137 +:100520000BB105F03BFB0023154A4FF47A711348D9 +:1005300005F02AFB002383F31188124C236813B1C2 :100540002368013B2360636813B16368013B636008 :100550000D4D2B7833B963687BB9022001F008FA9E :10056000322363602B78032B07D163682BB90220F9 -:1005700001F0FEF94FF47A73636038BDD023002098 -:1005800015050008F0240020E8230020084B18700F +:1005700001F0FEF94FF47A73636038BD70230020F8 +:10058000150500089024002088230020084B1870CF :1005900003280CD8DFE800F008050208022001F06B :1005A000E5B9022001F0E0B9024B00225A60704721 -:1005B000E8230020F0240020F8B501F011FD30B14F +:1005B0008823002090240020F8B501F059FD30B1C7 :1005C000544B03221A700022534B5A60F8BD534B10 :1005D000534A1C4619680131F8D004339342F9D1CB :1005E0006268504B9A42F1D94F4B9B6803F100630C -:1005F00003F500339A42E9D205F06EFE05F080FE65 +:1005F00003F500339A42E9D205F0A0FF05F0B2FFFF :10060000002001F027F90220FFF7C0FF474B00212F :10061000D3F8E820C3F8E810D3F81021C3F810117C :10062000D3F81021D3F8EC20C3F8EC10D3F8142140 @@ -112,13 +112,13 @@ :1006E000BFF36F8FBFF34F8FBFF36F8F536923F447 :1006F000003353610023C2F85032BFF34F8FBFF372 :100700006F8F302383F31188854680F30888204754 -:100710005CE700BFE8230020F0240020000002086E +:100710005CE700BF8823002090240020000002082E :1007200020000208FFFF01080023002000440258B7 :1007300000ED00E02DE9F04F93B0B74B2022FF21F0 :1007400000900AA89D6801F04BF9B44A1378A3B948 :100750000121B34811700360302383F311880368CB -:100760000BB105F0A7F90023AE4A4FF47A71AC48FB -:1007700005F096F9002383F31188009B13B1AA4B6F +:100760000BB105F01BFA0023AE4A4FF47A71AC4886 +:1007700005F00AFA002383F31188009B13B1AA4BFA :10078000009A1A60A94A1378032B03D00023137030 :10079000A54A53604FF0000A009CD3465646D14606 :1007A000012001F0E3F824B19F4B1B68002B00F0FF @@ -160,9 +160,9 @@ :1009E000926893423FF642AFB8F5807F3FF73EAF43 :1009F000124BB845019323DD4FF47A7000F0DCFE12 :100A00000390039A002AFFF631AF039A0137019B46 -:100A100003F8012BEDE700BF00230020EC240020A9 -:100A2000D023002015050008F0240020E823002032 -:100A300004230020082300200C230020EC230020A6 +:100A100003F8012BEDE700BF002300208C24002009 +:100A20007023002015050008902400208823002052 +:100A300004230020082300200C2300208C23002006 :100A4000C820FFF753FD074600283FF40FAF1F2DC6 :100A500011D8C5F120020AAB25F0030084494245B4 :100A6000184428BF4246019200F094FF019AFF21EA @@ -172,7 +172,7 @@ :100AA0003FF4E4AE00F010FF00283FF4DFAE002773 :100AB000B846704B9B68BB4218D91F2F11D80A9BB0 :100AC00001330ED027F0030312AA134453F8203C3D -:100AD00005934046042205A9043701F06BFA8046CD +:100AD00005934046042205A9043701F0B3FA804685 :100AE000E7E7384600F0B8FE0590F2E7CDF814804D :100AF000042105A800F07EFE02E70023642104A87B :100B0000049300F06DFE00287FF4B0AE0220FFF7E2 @@ -191,14 +191,14 @@ :100BD000FFF78CFC00283FF449AE00F075FE0028BA :100BE00044D00A9B01330BD008220AA9002000F050 :100BF000FFFE00283AD02022FF210AA800F0F0FED4 -:100C0000FFF77CFC1C4804F08FFE13B0BDE8F08FAA +:100C0000FFF77CFC1C4804F003FF13B0BDE8F08F35 :100C1000002E3FF42BAE0BF00B030B2B7FF426AE14 :100C20000023642105A8059300F0DAFD074600289B :100C30007FF41CAE0220FFF759FC804600283FF4E9 -:100C400015AEFFF75BFC41F2883004F06DFE0598AD +:100C400015AEFFF75BFC41F2883004F0E1FE059839 :100C500000F05CFF46463C4600F00EFFA0E506466D :100C60004EE64FF0000901E6BA467EE637467CE6DE -:100C7000EC23002000230020A0860100094A49F24D +:100C70008C23002000230020A0860100094A49F2AD :100C80006900136899B21B0C00FB013344F25061F8 :100C90001360054B186882B2000C01FB020018605B :100CA00080B270471423002010230020002110225E @@ -206,51 +206,51 @@ :100CC0001868A06010BD00BF00E8F11F2DE9F041D9 :100CD000ADF5507D0D46002140F275126EAC074611 :100CE00010A80F9100F07CFE4FF4C4720021204642 -:100CF00000F076FE0DF13C0802F05AFB4FF47A72D8 +:100CF00000F076FE0DF13C0802F0A6FB4FF47A728C :100D0000264BB0FBF2F0186093E80700022384E85A :100D100007000DF5ED702382FFF7C8FF47F60503C6 -:100D20001F4907A8238406F0F1FE1F230DF2EB22D2 +:100D20001F4907A8238407F055F91F230DF2EB2272 :100D30000DF1340C84F8323107AB1E46083203CE75 :100D4000664542F8080C42F8041C3346F5D1306879 :100D500010602046B188B379918041469371012299 -:100D600000F04CFF002380B2E97E0393AB7E029338 +:100D600000F056FF002380B2E97E0393AB7E02932E :100D700005F1190301930123009306A3D3E900238E -:100D8000CDE90480384602F0D1FE0DF5507DBDE876 -:100D9000F08100BF9E6AC421818A46EEF8240020BB -:100DA0001C7B00082DE9F0412C4CDAB080460D4642 -:100DB000237A5BBB27A9284601F02EF807460028B6 +:100D8000CDE90480384602F01DFF0DF5507DBDE829 +:100D9000F08100BF9E6AC421818A46EE982400201B +:100DA000E47F00082DE9F0412C4CDAB080460D4676 +:100DB000237A5BBB27A9284601F04EF80746002896 :100DC00042D19DF89D60C82E3ED801464FF4A662E0 :100DD000204600F005FE4FF4807332460DF19E016F :100DE000C4F8F8314FF4007304F109002644C4F844 :100DF0000C334FF44073C4F8203400F0CBFD9DF861 :100E00009C30777223720BB9EB7E237206AC812281 :100E1000002127A800F0E4FD0122214627A801F0C7 -:100E200037F8002380B2E97E0393AB7E029305F18D +:100E200061F8002380B2E97E0393AB7E029305F163 :100E3000190301932823CDE904400093404605A3FC -:100E4000D3E9002302F072FE5AB0BDE8F08100BF82 -:100E5000AFF3008026417272DF25D7B7C05E002055 +:100E4000D3E9002302F0BEFE5AB0BDE8F08100BF36 +:100E5000AFF3008026417272DF25D7B7605E0020B5 :100E6000F0B5254E4FF48A75F1B0002405FB0065FE :100E700096F8D830D822214685F8DC303AA885F893 :100E8000E84006AF00F0ACFD06F1090000F0A0FD5F :100E9000D5F8E430C2B206F109018DF8F0000DF189 :100EA000F100CDE93A3400F075FD394601223AA847 -:100EB00001F01AF8082380B2317ACDE904700127D5 +:100EB00001F04EF8082380B2317ACDE904700127A1 :100EC0000E48CDE9023706F1D80301933023009391 -:100ED00007A3D3E9002302F029FEA04206DD02F0B9 -:100EE00067FAC5F8E000384671B0F0BD2046FBE770 -:100EF00078F6339F93CACD8DC05E00201035002058 +:100ED00007A3D3E9002302F075FEA04206DD02F06D +:100EE000B3FAC5F8E000384671B0F0BD2046FBE724 +:100EF00078F6339F93CACD8D605E0020B034002019 :100F00002DE9F04F264F87B0DFF8A080254E3846F8 -:100F100002F038FE034600283AD00024224DADF8F6 +:100F100002F084FE034600283AD00024224DADF8AA :100F20001440A1460294A246CDE90344027B8DF809 :100F3000142003AA9968406803C21B6843F0004369 -:100F400002932B6804F5A664D3F810B002F032FACD +:100F400002932B6804F5A664D3F810B002F07EFA81 :100F500010EB0802CDF800A0284605F5A65541F192 :100F6000000302A9D8470028C8BF49F00109B4F519 -:100F7000266FE6D1B9F1000F05D0384602F006FE23 +:100F7000266FE6D1B9F1000F05D0384602F052FED7 :100F800086F800A0C3E73378072B04D80133337009 -:100F900007B0BDE8F08F024802F0F8FDF8E700BFA7 -:100FA00010350020F56300204035002040420F003E -:100FB00070B50D4614461E4602F014FD50B9022EBF +:100F900007B0BDE8F08F024802F044FEF8E700BF5A +:100FA000B034002095630020E034002040420F0060 +:100FB00070B50D4614461E4602F060FD50B9022E73 :100FC00010D1012C0ED112A3D3E900230120C5E9D1 :100FD000002307E0282C10D005D8012C09D0052CBF :100FE0000FD0002070BD302CFBD10BA3D3E9002320 @@ -262,22 +262,22 @@ :10104000013500F02FFCA4F82C55B4F82C0500F065 :1010500011FC78B1B4F82C0500F01CFC014648B92D :10106000B4F82C0500F01EFCB4F82C350133A4F8BC -:101070002C35EAE738BD00BFC05E0020F8B50D4C46 +:101070002C35EAE738BD00BF605E0020F8B50D4CA6 :1010800002260D4FA4F5805343F8307C237E3BB9F4 -:1010900065692DB1284601F01DF8284606F0ECFCE4 -:1010A0002046A4F5A65401F015F8012E00D1F8BD94 -:1010B0000126E7E7305A0020DC7B00082DE9F04FDD -:1010C0008FB005460C4600AF02F08CFC002849D1D9 -:1010D000237E022B1BD1E38A012B18D102F068F981 +:1010900065692DB1284601F065F8284601F09EF9F2 +:1010A0002046A4F5A65401F05DF8012E00D1F8BD4C +:1010B0000126E7E7D0590020A48000082DE9F04F71 +:1010C0008FB005460C4600AF02F0D8FC002849D18D +:1010D000237E022B1BD1E38A012B18D102F0B4F935 :1010E0000646FFF7CBFD03464FF4C87006F51676AB :1010F000DFF8C082B3FBF0F202FB103316FA83F381 :10110000C8F80030E37E33B9A34B00221A703C3795 -:10111000BD46BDE8F08F07F12401204600F03AFEFD +:10111000BD46BDE8F08F07F12401204600F050FEE7 :101120000028F4D107F11400FFF7C0FD97F826401E -:1011300007F1140107F12700224606F0B5FC00284C +:1011300007F1140107F12700224606F019FF0028E5 :10114000E2D10F2C08D8944B1C70D8F80030A3F5CE :101150001673C8F80030DAE797F82410284602F032 -:1011600039FCD4E7E38A282B2BD010D8012B23D0CD +:1011600085FCD4E7E38A282B2BD010D8012B23D081 :10117000052BCCD1BFF34F8F8849894BCA6802F445 :10118000E0621343CB60BFF34F8F00BFFDE7302B0E :10119000BDD1844EE17E327A9142B8D1607E314633 @@ -297,14 +297,14 @@ :101270007260D6F8D42005EB0209C6F8D49000F0CD :10128000F9FA814509D396F8D220D6F8D400013274 :10129000001B86F8D220C6F8D400FF2D0FD80024FA -:1012A000347200F011FB204600F0D4FA00F098FEF2 +:1012A000347200F011FB204600F0D4FA00F0E0FEAA :1012B0003D4B188108B9FFF77FF9C54627E7BB68A2 :1012C00096F8D9000AFB0362FB68D2F8E41082F8B2 :1012D000E83001F58061C2F8E030C2F8E410FFF7B1 :1012E000BFFDFFF70DFE96F8D920013202F0030290 :1012F00086F8D920B6E74FF48A7A20460AFB02F531 -:1013000005F1EA01314400F01BFEF86000287FF48B -:10131000FEAE0122354485F8E82002F049F8D5F800 +:1013000005F1EA01314400F057FEF86000287FF44F +:10131000FEAE0122354485F8E82002F095F8D5F8B4 :10132000E020D6ED007A801A40F6B832B8EE677A3F :10133000DFED1E6A192838BF1920904228BF1046D9 :1013400007EE900AF8EEE77A67EEA67ADFED186A04 @@ -312,27 +312,27 @@ :10136000BB60BA6873680AFB02F4321992F8E8109D :1013700059B1D2F8E410E8468B423FF427AF002180 :1013800082F8E810C2F8E010C5467368064A9B0A66 -:1013900001331381BBE600BF0935002000ED00E0FA -:1013A0000400FA05C05E0020F8240020CDCCCC3D1E -:1013B0006666663F0C350020014B1870704700BF11 -:1013C0000425002038B54FF00054144B22689A428F -:1013D00021D1627D0025124B12481A70C922237D4B -:1013E0000930114900F8013C4FF48073C0F8DB501C -:1013F000C0F8EF314FF40073C0F803334FF440737B -:10140000C0F8173400F0C6FAE0222946204600F062 -:10141000E7FA012038BD0020FCE700BF9AAD44C5C3 -:1014200004250020C05E00201600002037B500F023 -:10143000D7FD1F4C1F4D022301221F496B712368EA +:1013900001331381BBE600BFA934002000ED00E05B +:1013A0000400FA05605E002098240020CDCCCC3DDE +:1013B0006666663FAC340020014B1870704700BF72 +:1013C000A424002038B54FF00054144B22689A42F0 +:1013D00022D1607DF8B1124B0025C9221149187045 +:1013E0001148237D0930C0F8DB5000F8013C4FF470 +:1013F0008073C0F8EF314FF40073C0F803334FF43B +:101400004073C0F8173400F0C5FAE02229462046A0 +:1014100000F0E6FA012038BD0020FCE79AAD44C593 +:10142000A424002016000020605E002037B500F0E4 +:101430001FFE1F4C1F4D022301221F496B712368A1 :10144000288120465B68984704F5805301221A4999 :10145000D3F8C03404F5A6505B68984700231749B9 :101460004FF480520193164B16480093164B02F02E -:1014700089FA164B197811B1124802F0ABFA01F053 -:1014800097FF0446FFF7FAFB4FF4C873B0FBF3F283 +:10147000D5FA164B197811B1124802F0F7FA01F0BB +:10148000E3FF0446FFF7FAFB4FF4C873B0FBF3F237 :1014900002FB130304F5167010FA83F00C4B18606E -:1014A00004F04EFF08B10F232B8103B030BD00BF05 -:1014B00040350020F824002040420F00082500207D -:1014C000B10F000810350020BD10000804250020D1 -:1014D0000C3500202DE9F04F00242DED028B93B048 +:1014A00005F080F808B10F232B8103B030BD00BFD9 +:1014B000E03400209824002040420F00A82400209F +:1014C000B10F0008B0340020BD100008A424002093 +:1014D000AC3400202DE9F04F00242DED028B93B0A9 :1014E0000DF12C084FF0010ADFF814B2FFF708FDE8 :1014F0000A94ADF834400B94C8F804409FED798B02 :1015000000267E4D37462B680DF11D0207A928469F @@ -341,63 +341,63 @@ :1015300000210EA800F054FA2B6808AA0AA95F69D6 :1015400028460DF11E03B8470FAB4F4698E803003D :1015500083E803009DF834300EA958468DF84430D6 -:101560000A9B0E93DDE9082302F0EEFC06F5A66661 +:101560000A9B0E93DDE9082302F03AFD06F5A66614 :1015700005F5A655B6F5266FC5D1002FC0D1604838 -:1015800002F030FA00283FD15E4E01F011FF3368BF -:10159000984239D301F00CFF0546FFF76FFB4FF47B +:1015800002F07CFA00283FD15E4E01F05DFF336827 +:10159000984239D301F058FF0546FFF76FFB4FF42F :1015A000C8738DF82870B0FBF3F202FB130305F546 :1015B000167010FA83F03060534E377817B9012354 :1015C0008DF82830C7F110050EA8FFF76FFB0EABA2 :1015D000EDB20DF12900D919062D28BF06252A469E :1015E000013500F0D7F90AABEDB245480393182353 :1015F00004950293454B0193012300933BA3D3E948 -:10160000002302F035FA347001F0D2FE404A414D19 -:101610001368C31AB3F57A7F2FD3106001F0CAFEA6 -:1016200002460B46364802F0BBFA354802F0DAF9BA +:10160000002302F081FA347001F01EFF404A414D80 +:101610001368C31AB3F57A7F2FD3106001F016FF59 +:1016200002460B46364802F007FB354802F026FA20 :1016300018B32B7A0EAF384E002B14BF03230223AE -:10164000737101F0B5FE4FF47A7301223946B0FB95 -:10165000F3F03060304600F075FB182380B202933F +:10164000737101F001FF4FF47A7301223946B0FB48 +:10165000F3F03060304600F08BFB182380B2029329 :101660002E4B019340F25513CDE9037000932448AB -:1016700020A3D3E9002302F0FBF92B7A93B101F008 -:1016800097FE002607464FF48A7895F8D900304433 +:1016700020A3D3E9002302F047FA2B7A93B101F0BB +:10168000E3FE002607464FF48A7895F8D9003044E7 :1016900000F0030008FB005393F8E82072B1013614 -:1016A000042EF2D1C82004F03FF92B7A002B7FF4EE +:1016A000042EF2D1C82004F0B3F92B7A002B7FF47A :1016B00017AF13B0BDEC028BBDE8F08FD3F8E0207C :1016C00042B12B68BA1AFA2B38BFFA230533B2EBB2 :1016D000430FE4D3FFF7C4FB0028E0D1E2E700BFEB :1016E000AFF300800000000000000000401DA120BA -:1016F00026812A0BF1C6A7C1D068080F403500200B -:10170000103500200C350020093500200835002058 -:10171000F0630020C05E0020F8240020F463002065 -:1017200010B5074C204601F007F904F5A65001F06A -:1017300003F9044A04490020BDE8104006F096B9B8 -:1017400040350020506400207D1000082DE9F84F3E +:1016F00026812A0BF1C6A7C1D068080FE03400206C +:10170000B0340020AC340020A9340020A8340020DC +:1017100090630020605E00209824002094630020E5 +:1017200010B5074C204601F053F904F5A65001F01E +:101730004FF9044A04490020BDE8104006F004BCFB +:10174000E0340020F06300207D1000082DE9F84F00 :101750004FF47A7306460D46002402FB03F7DFF8C8 :101760005080DFF8509098F900305FFA84FA5A1CE4 :1017700001D0A34212D159F824002A463146036809 :10178000D3F820B03B46D847854207D1074B01200C :1017900083F800A0BDE8F88F0124E4E7002CFBD01B -:1017A0004FF4FA7004F0C0F80020F3E73C64002026 +:1017A0004FF4FA7004F034F90020F3E7DC63002012 :1017B000182300201C230020002307B50246012126 :1017C0000DF107008DF80730FFF7C0FF20B19DF83D :1017D000070003B05DF804FB4FF0FF30F9E70000AD :1017E0000A46042108B5FFF7B1FF80F00100C0B23E :1017F000404208BD074B0A4630B41978064B53F8EF :101800002140014623682046DD69044BAC4630BCCC -:10181000604700BF3C6400201C230020A08601001C -:1018200070B50A4E00240A4D04F0AAFB30802868E7 -:101830003388834208D904F09FFB2B6804440133AA -:10184000B4F5003F2B60F2D370BD00BF3E640020B2 -:10185000F863002004F062BC00F1006000F5003085 +:10181000604700BFDC6300201C230020A08601007D +:1018200070B50A4E00240A4D04F01EFC3080286872 +:101830003388834208D904F013FC2B680444013335 +:10184000B4F5003F2B60F2D370BD00BFDE63002013 +:101850009863002004F0D6BC00F1006000F5003071 :101860000068704700F10060920000F5003004F05D -:10187000E3BB0000054B1A68054B1B889B1A83428B -:1018800002D9104404F078BB00207047F8630020B0 -:101890003E640020024B1B68184404F073BB00BF79 -:1018A000F8630020024B1B68184404F07DBB00BFA6 -:1018B000F86300200020704700F1FF5000F58F1002 +:1018700057BC0000054B1A68054B1B889B1A834216 +:1018800002D9104404F0ECBB00207047986300209C +:10189000DE630020024B1B68184404F0E7BB00BF66 +:1018A00098630020024B1B68184404F0F1BB00BF92 +:1018B000986300200020704700F1FF5000F58F1062 :1018C000D0F8000870470000064991F8243033B181 :1018D00000230822086A81F82430FFF7C3BF0120E3 -:1018E000704700BFFC630020014B1868704700BFC1 +:1018E000704700BF9C630020014B1868704700BF21 :1018F0000010005C194B01380322084470B51D68C4 :10190000174BC5F30B042D0C1E88A6420BD15C6847 :101910000A46013C824213460FD214F9016F4EB1C0 @@ -405,9 +405,9 @@ :101930000B4602D22C2203F8012B0424094A1688F4 :10194000AE4204D1984284BF967803F8016B013C03 :1019500002F10402F3D1581A70BD00BF0010005C00 -:1019600024230020687B00087047000070470000B7 +:1019600024230020308000087047000070470000EA :101970007047000070B504464FF47A764CB1412CA4 -:10198000254628BF412506FB05F0641B03F0CCFF6C +:10198000254628BF412506FB05F0641B04F040F8FE :10199000F4E770BD002310B5934203D0CC5CC4546F :1019A0000133F9E710BD0000013810B510F9013F0F :1019B0003BB191F900409C4203D11AB10131013A87 @@ -422,1651 +422,1722 @@ :101A40009044E4B2F6B2082E85F82460DBD1FFF7AB :101A50003BFF0028D7D108E02B6A03EB82038342C7 :101A6000CFD0FFF731FF0028CBD10020BDE8F883AD -:101A70000120FBE7FC630020024B1A78024B1A702E -:101A8000704700BF3C6400201823002038B51A4C72 -:101A90001A4D204603F08CFA2946204603F0B4FA8A +:101A70000120FBE79C630020024B1A78024B1A708E +:101A8000704700BFDC6300201823002038B51A4CD3 +:101A90001A4D204603F0DCFA2946204603F004FBE9 :101AA0002D684FF47A70D5F89020D2F8043843F0BE :101AB0000203C2F80438FFF75DFF1149284603F01E -:101AC000B1FBD5F890200F4DD2F80438286823F0E8 +:101AC00001FCD5F890200F4DD2F80438286823F097 :101AD00002030D49A042C2F804384FF4E1330B6011 -:101AE00001D003F0C3F96868A04204D00649BDE8FC -:101AF000384003F0BBB938BDB86B0020287E000821 -:101B0000307E00081C230020246400200C4B70B59C +:101AE00001D003F013FA6868A04204D00649BDE8AB +:101AF000384003F00BBA38BD586B0020F082000864 +:101B0000F88200081C230020C46300200C4B70B531 :101B10000C4D04461E780C4B55F826209A420DD0E9 :101B20000A4B002118221846FFF75AFF04600146AD -:101B300055F82600BDE8704003F098B970BD00BFAD -:101B40003C6400201C230020B86B0020246400208B -:101B5000F0B5A1B071B600230120002480261A46FA -:101B6000194602F05BFE4FF4D067214A3D25136908 -:101B700023BBD2F810310BBB036804F100619960FC -:101B80000368C3F80CD003685E6003681F600168D7 -:101B90000B6843F001030B6001680B6823F01E0320 -:101BA0000B6001680B68DB07FCD4037B8034416861 -:101BB00005FA03F3B4F5001F0B60D8D102F06EFEF6 -:101BC000B4F5001F11D000240A4E0B4D012004F083 -:101BD000A5FA3388A34205D928682044013404F0CB -:101BE000E3F9F6E7002004F099FA61B621B0F0BD00 -:101BF000002000523E640020F86300202DE9F047E9 -:101C00000D46044600219046284640F27912FFF71F -:101C1000E7FE234620220021284604F1220702F095 -:101C200035F9231D022220212846C02602F02EF974 -:101C3000631D03222221284602F028F9A31D032256 -:101C40002521284602F022F904F108031022282158 -:101C5000284602F01BF904F1100308223821284617 -:101C600002F014F904F1110308224021284602F081 -:101C70000DF904F1120308224821284602F006F962 -:101C800004F1140320225021284602F0FFF804F149 -:101C9000180340227021284602F0F8F804F12003CE -:101CA0000822B021284602F0F1F804F121030822AD -:101CB000B821284602F0EAF8314608363B460822A9 -:101CC0002846013702F0E2F8B6F5A07FF4D10027EC -:101CD00004F1330A04F1320308223146284602F0A7 -:101CE000D5F894F832304FEAC7099F4209F5A47637 -:101CF00015D3B8F1000F08D1314609F24F1604F59B -:101D000099730722284602F0C1F827463B1B94F836 -:101D1000322193420CD3F01DC008BDE8F0870AEBD6 -:101D20000703082231462846013702F0AFF8D8E70A -:101D300007F233133146082228460836013702F0ED -:101D4000A5F8E3E713B50446084600212022234600 -:101D500001900160C0F8031002F098F8231D01986B -:101D60000222202102F092F8631D01980322222111 -:101D700002F08CF8A31D01980322252102F086F8B9 -:101D8000019804F108031022282102F07FF80720AF -:101D900002B010BD0023F7B50E46047F0722009164 -:101DA0001946054601F036FF731C012207210093F6 -:101DB0002846002301F02EFFC4B9B31C05220821D8 -:101DC0002846009323460D2401F024FF3746BB1B11 -:101DD000B278934211D307342B7FA88AE408BBB9A9 -:101DE000844294BF0020012003B0F0BDAB8A0824D8 -:101DF000DB00083BDB08B370E8E7FB1C2146082248 -:101E00002846009300230834013701F003FFDEE782 -:101E1000201A18BF0120E7E70023F7B50E46047F1C -:101E2000082200911946054601F0F4FE731CC4B95E -:101E300008220093234610241146284601F0EAFEAA -:101E400001235F1C7278013B934211D307342B7F2F -:101E5000A88AE408BBB9844294BF0020012003B0E3 -:101E6000F0BDAB8A0824DB00083BDB087370E7E7B2 -:101E7000F3192146082228460093002301F0CAFEE8 -:101E800008343B46DDE7201A18BF0120E7E70000D1 -:101E9000F8B50E4605461446002181223046FFF76C -:101EA0009FFD2B4608220021304601F0EFFF7CB950 -:101EB0000F246B1C07220821304601F0E7FF0123A5 -:101EC0005F1C6A78013B934204D3E01DC008F8BD53 -:101ED0000824F4E7EB1921460822304601F0D6FF2A -:101EE00008343B46ECE70000F8B50E4605461446BC -:101EF0000021CE223046FFF773FD2B462822002119 -:101F0000304601F0C3FF7CB9302405F108030822F4 -:101F10002821304601F0BAFF2F467B1B2A7A9342D4 -:101F200004D3E01DC008F8BD2824F5E707F1090334 -:101F30002146082230460834013701F0A7FFECE7BC -:101F4000F7B5047F0E4600910123102200210546BB -:101F500001F060FEC4B9B31C092210212846009389 -:101F60002346192401F056FE37467288BB1B9A425D -:101F700011D807342B7FA88AE408BBB9844294BFE8 -:101F80000020012003B0F0BDAB8A1024DB00103B21 -:101F9000DB087380E8E73B1D2146082228460093B2 -:101FA00000230834013701F035FEDEE7201A18BFA0 -:101FB0000120E7E730B50A44084D91420DD011F8F1 -:101FC000013B5840082340F30004013B2C4013F030 -:101FD000FF0384EA5000F6D1EFE730BD2083B8ED6F -:101FE000F7B5364A6B46106851686A4603C3082342 -:101FF0003349344805F068FD044690BB0A25324A4F -:102000006B46106851686A4603C308232F492D4860 -:1020100005F05AFD0446002847D00369B3F5F01FC8 -:1020200043D8B0F86620B2F5AF6F3ED1284A0244DB -:1020300002F15C018B4238D35C3B224900209E1A9E -:10204000FFF7B8FF04F16401074632460020FFF7AE -:10205000B1FFA3689F4228D1E368984208BF0025DA -:1020600023E00369B3F5F01F26D8428BB2F5AF6FBA -:1020700020D1174A024402F110018B4218D3103BC1 -:10208000104900209D1AFFF795FF04F1180106463C -:102090002A460020FFF78EFFA3689E4202D1E36824 -:1020A000984201D00D25AAE70025284603B0F0BDCF -:1020B0001025A4E70C25A2E70B25A0E7787B0008F4 -:1020C000DCFF1D0000000208817B000890FF1D005E -:1020D0000800FEF710B5037C044613B9006805F04C -:1020E000DBFC204610BD00000023BFF35B8FC36004 -:1020F000BFF35B8FBFF35B8F8360BFF35B8F704772 -:10210000BFF35B8F0068BFF35B8F704770B5054608 -:102110000C30FFF7F5FF044605F108063046FFF7DF -:10212000EFFFA04206D96D683046FFF7E9FF25446E -:10213000281A70BD3046FFF7E3FF201AF9E70000C8 -:1021400070B505464068A0B105F10C0605F1080020 -:10215000FFF7D6FF04463046FFF7D2FF844204F172 -:10216000FF34304694BF6D680025FFF7C9FF2C444B -:10217000201A70BD38B50C460546FFF7C7FFA042D0 -:1021800010D305F10800FFF7BBFF04446868BFF3F4 -:102190005B8FB4FBF0F100FB11440120AC60BFF396 -:1021A0005B8F38BD0020FCE72DE9F041144607465F -:1021B0000D46FFF7C5FF844228BF0446D4B1B84698 -:1021C00058F80C6B4046FFF79BFF304428604046B0 -:1021D0007E68FFF795FF331A9C4203D801206C609C -:1021E000BDE8F081A41B6B603B682044AB60E860F5 -:1021F0000220F5E72046F3E738B50C460546FFF721 -:102200009FFFA04210D305F10C00FFF779FF0444B3 -:102210006868BFF35B8FB4FBF0F100FB1144012051 -:10222000EC60BFF35B8F38BD0020FCE72DE9FF4178 -:102230008846694607466C46FFF7B6FF002506B29A -:1022400004EBC606B4420AD0626808EB05012068B8 -:102250000834FFF79FFB54F8043C1D44F2E729467D -:102260003846FFF7C9FF284604B0BDE8F0810000FA -:10227000F8B505460C300F46FFF742FF05F108069A -:1022800004463046FFF73CFFA042304688BF6C68EA -:10229000FFF736FF201A386020B12C683046FFF770 -:1022A0002FFF2044F8BD000073B5144606460D46C6 -:1022B000FFF72CFF8442019028BF0446DCB101A93E -:1022C0003046FFF7D5FF019B33B93268C5E90233C9 -:1022D000C5E9002401200CE09C42286038BF01942D -:1022E000019884426860F5D93368241A0220AB60F3 -:1022F000EC6002B070BD2046FBE700002DE9FF4115 -:102300000F4669466C46FFF7CFFF00B2002604EB8C -:10231000C005AC4209D0D4F80480B81954F8081BA1 -:1023200042464644FFF736FBF3E7304604B0BDE8CB -:10233000F081000038B50546FFF7E0FF044601468E -:102340002846FFF717FF204638BD00007047000001 -:1023500010B41346026814680022A4465DF8044BCA -:102360006047000000F5805090F859047047000065 -:1023700000F5805090F852047047000000F580503E -:1023800090F95804704700004E207047302383F3C3 -:10239000118800F58052D2F89C34D2F89804184481 -:1023A000D2F894341844D2F87C341844D2F88C34DF -:1023B0001844D2F888341844002383F311887047F6 -:1023C00000F58050C0F85414012070472DE9F04FFB -:1023D0000C4600F5805185B01F4691F852340546F1 -:1023E0009046BDF838909BB1D1F878340133C1F8EC -:1023F00078342368980006D4237B082B0BD9627BA2 -:102400000AB10F2B07D9D1F87C340133C1F87C34E1 -:102410004FF0FF3010E0302383F31188EB6AD3F8DC -:10242000C42012F4001B0AD0D1F8803400200133FC -:10243000C1F8803480F3118805B0BDE8F08F2068C2 -:102440004822D3F8C4300028C3F3044A6B6AB4BFEF -:1024500040F08040800412FB0A334FEA4A161860AD -:10246000226852004FEA0A6244BF40F000501860F0 -:10247000207B42EA00425A60607B10B342F4401273 -:102480005A60D1F8B0240132C1F8B024AA1902F57B -:102490008352117B41F020011173207B039300F0E4 -:1024A000E3FF0330039B80105FFA8BF20BF1010B0B -:1024B00082420DDA04EB820103EB820249689160EB -:1024C000F2E7AA1902F58352117B60F34511E3E7A5 -:1024D0000122EB6A05EB4A1102FA0AF201F5825178 -:1024E000C3F8D020AB19183104F10C0203F5825364 -:1024F000C3E90487234653F8040B934241F8040BC5 -:10250000F9D11B882E440B8041F2680346F803A0E2 -:1025100006F5805609F0030396F86C2043F010038B -:1025200022F01F02134386F86C30002383F31188D6 -:1025300042463B4621462846CDF8009000F05AFF1F -:10254000012079E72DE9F04700F58056044696F81A -:102550005254002D40F00381037C032B40F0948003 -:1025600028462B462F465FFA80FC944510DA01EB93 -:10257000CC0E51F83CC0BCF1000F04DBDEF804C007 -:10258000BCF1000F02DB01370130ECE70133FBE760 -:10259000302080F31188E06AF3B9D0F8803043F03E -:1025A0000203C0F880304E23E06A002F6FD1D0F8CC -:1025B000803043F00103C0F880306A4B6A4A1B68E0 -:1025C00003F1805303F52C539B009342A36240F226 -:1025D000B080664800F0E6FE4D2B42D8DFF88481DB -:1025E0004FEA034EDFF88891D8F800C04EEA8C0E0F -:1025F000C0F884E00CF1805000F52C508000606140 -:1026000003EB0C00D4F82CC0C3F14E03C8F8000053 -:10261000DCF8800040F03000CCF880004FF0000C77 -:10262000D4F81480E6465FFA8CF08242BCDD01EB00 -:10263000C00A51F83000002810DBDAF804A0BAF123 -:10264000000F0BDA09EA00400AF07F0A40EA0A00AC -:1026500040F0084048F82E000EF1010E0CF1010C7C -:10266000E1E7836923F00103836100F0A1FE0646E0 -:10267000E36A9B69D90704D500F09AFE831BFA2B05 -:10268000F6D9002383F311882846BDE8F087B7EB1D -:10269000530F3DD2DFF8CCE04FEA074CDEF80030B4 -:1026A0004CEA830CC0F888C003F1805003EB470369 -:1026B000002700F52C50CEF80030BC468000A06109 -:1026C000E06AD0F8803043F00C03C0F88030D4F8D2 -:1026D00018E0FBB29A427FF770AF51F8330001EB7C -:1026E000C3080028D8F8043001DB002B0EDB20F0F3 -:1026F000604023F0604340F0005043F000434EF848 -:102700003C000EEBCC000CF1010C43600137E0E71C -:10271000836923F00103836100F04AFE0646E36A01 -:102720009B69DA07ADD500F043FE831BFA2BF6D97F -:10273000A7E7E26A936923F00103936100F038FE92 -:102740000746E36A9B69DB0705D500F031FEC31B32 -:10275000FA2BF6D995E7012586F8525491E7002522 -:1027600092E700BF4C640020FCB500408C7B000861 -:102770000000FF0713B500F580540191606CFFF76E -:10278000DFFC1F280AD920220199606CFFF74EFD5B -:10279000A0F120035842584102B010BD0020FBE7D1 -:1027A00008B5302383F3118800F58050406CFFF7A3 -:1027B0009BFC002383F3118808BD00000022026007 -:1027C00082814260826070470022002310B5C0E918 -:1027D0000023002304460C3020F8043CFFF7EEFFF2 -:1027E000204610BD2DE9F0479A4688B00746884636 -:1027F0009146302383F3118807F580546846FFF72C -:10280000E3FF606CFFF782FC1F282ED92022694667 -:10281000606CFFF78FFD202827D194F8523423B342 -:1028200003AD444605AB2E46083403CE9E4244F821 -:10283000080C44F8041C3546F5D130682060B38894 -:10284000A380DDE90023C9E90023BDF80830AAF818 -:102850000030002383F3118853464A4641463846E8 -:1028600008B0BDE8F04700F0B3BD002080F3118848 -:1028700008B0BDE8F08700002DE9F84F00230646B8 -:1028800000F58154054688461034C0E90133274BD2 -:1028900046F8303B374638462037FFF795FFA742CA -:1028A000F9D105F580544FF4805305F5A3594FF045 -:1028B000000A26630026676405F5835709F11009AD -:1028C0004FF0000B1037E663C4E90D36012384F89E -:1028D000403084F84830A7F11800203747E910ABA2 -:1028E000FFF76CFF47F8286C4F45F4D1B8F1010FA2 -:1028F00084F85884A4F85A64A4F85C64A4F85E646C -:1029000084F86064A4F86264A4F86464A4F866645B -:1029100084F8686402D9064800F044FD054B284657 -:1029200053F82830EB62BDE8F88F00BFDC7B00086D -:10293000B07B0008CC7B0008044B10B51978044626 -:102940004A1C1A70FFF798FF204610BD496400200A -:102950002DE9F04300295AD02E4E2F48B6FBF1F452 -:1029600081428CBF0A201120431EB4FBF0F700FB0C -:102970001740DDB220B1022B1846F5D8002032E016 -:102980007B1EB3F5806F2ED2C5EBC5084FF47A736A -:1029900008F103044FEAE40EC4F3C7040EF1010981 -:1029A000281B0EFB033E5FFA80FC59FA80F0BEFB49 -:1029B000F0F0B0F5617F18DC83B2601C5CFA80F047 -:1029C0007843B6FBF0F08142D8D1611E0F29D5D8EB -:1029D0000CF1FF310729D1D80120138057801071E5 -:1029E000547182F806C0BDE8F08308F1FF34E010AE -:1029F000C4F3C70400F1010E2D1B00FB03335FFA83 -:102A000085FC5EFA85F5B3FBF5F39BB2D5E7084686 -:102A1000E9E700BF00B4C4043F420F0030B50D4BDE -:102A200005200D4D1C786C438C420ED15978012045 -:102A3000518099785171D9789171197911715B79B7 -:102A400003EB83035B00138030BD013803F1060301 -:102A5000E8D1F9E71C7C000840420F0038B540F28D -:102A60007772C36A154CC3F8BC200722C36AC3F847 -:102A7000C8202268C16A930043F4C023C1F8A03083 -:102A800002F1805302F16C01C56A03F52C53EA325E -:102A900089009B00226041F0E061094AC361C5F8EA -:102AA000C01003F5D87103F56A73416293428362E3 -:102AB00002D9044800F076FC38BD00BF4C64002009 -:102AC000FCB500408C7B00082DE9F04F00F58055E7 -:102AD0001F4689B0044695F8583489469046022B23 -:102AE00004D90026304609B0BDE8F08FA84A52F854 -:102AF000231009B942F82300A648C4F80C900178C5 -:102B00002774C9B9302383F31188A34BD3F8EC2081 -:102B100042F48072C3F8EC20D3F8942042F480721F -:102B2000C3F89420D3F8942022F48072C3F8942040 -:102B30000123037081F3118895F851347BB9302358 -:102B400083F31188954A95F85834D35C0BB3012B65 -:102B500028D0012385F85134002383F311883023D2 -:102B600083F31188E26A936923F01003936100F004 -:102B70001FFC8246E36A9E6916F0080619D000F031 -:102B800017FCA0EB0A03FA2BF4D9002686F3118870 -:102B9000A8E70321132001F09DFF0321152001F078 -:102BA00099FFD6E70321142001F094FF032116209A -:102BB000F5E79A6942F001029A6100F0F9FB82465A -:102BC000E36A9A69D00706D400F0F2FBA0EB0A038F -:102BD000FA2BF5D9D9E79A694FF0000A42F00202C0 -:102BE0009A61E36AC3F854A08AF3118804F5825B02 -:102BF000686CFFF779FA0BF1100B20220021684670 -:102C0000FEF7EEFE02A8FFF7D9FD6A460BEB0603BE -:102C10000DF1180ECDF818A094460833BCE8030057 -:102C2000F44543F8080C43F8041C6246F4D1DCF880 -:102C3000000020361860B6F5806F9CF804201A71E9 -:102C4000DBD1002304F5A252494620461A3285F80A -:102C5000503485F85334FFF77BFE064690B9E26A9C -:102C6000936923F00103936100F0A2FB0546E36A38 -:102C70009B69D9077FF535AF00F09AFB431BFA2B10 -:102C8000F5D92EE795F85E34C5F86C94591E95F881 -:102C90005F34E26A013B1B0243EA416395F860142A -:102CA00001390B43B5F85C14013943EA0143D361A0 -:102CB000B8F1000F36D004F5A35241462046023247 -:102CC000FFF7ACFE90B9E26A936923F001039361C8 -:102CD00000F06EFB0546E36A9B69DA077FF501AFFA -:102CE00000F066FB431BFA2BF5D9FAE695F867244A -:102CF000C5F87084511E95F86824E36A013A120100 -:102D000042EA012295F8661401390A43B5F86414C1 -:102D1000013942EA014242F40002DA604FF42062D3 -:102D2000E36A9A64E36A4FF000082046C3F8BC8067 -:102D3000FFF794FE85F859846FF04042E36A1A6504 -:102D4000174AE36A5A654FF00222E36A9A654FF028 -:102D5000FF32E36AC3F8E0200322E36A9742DA65B0 -:102D60003FF4C0AEE26A936923F00103936100F07F -:102D70001FFB0746E36A9B69DB0705D500F018FBDC -:102D8000C31BFA2BF6D9ACE6012385F85234A9E629 -:102D9000406400204864002000440258C47B0008BE -:102DA000550200022DE9F04F054689B0904699463C -:102DB000002741F2680A00F58056EB6AD3F8D83054 -:102DC000FB40D80751D505EB47124FEA471B524449 -:102DD0001379190749D4D6F884340133C6F88434FA -:102DE00005F5A553C3E9008913799A0605EB0B0293 -:102DF00048BFD6F8B434524444BF0133C6F8B434A3 -:102E0000137943F008031371DB0723D596F8533485 -:102E100003B305F582546846FFF7D6FC03AB1834BC -:102E20005C4404F1080C2068083454F8041C1A4669 -:102E3000644503C21346F6D12068694610602846EF -:102E4000A2889A800123ADF808302B68CDE900896B -:102E5000DB6B9847D6F8A834D6F854040133C6F88B -:102E6000A83410B103681B6998470137202FA4D1FB -:102E700009B0BDE8F08F00002DE9F04F0F468DB08E -:102E8000044600F097FA82468946002F5BD1E36A38 -:102E9000D3F8A02012F4FE0F03D100200DB0BDE83E -:102EA000F08FD3F8A420920141BF04F58051D1F8EE -:102EB00098240132C1F89824D3F8A4205606ECD007 -:102EC000D3F8A450E669C5F305254823E8464FF03A -:102ED000000B03FB05664046FFF770FC32685100AB -:102EE0004ABF22F06043C2F38A4343F0004392009A -:102EF00048BF43F080430093736813F400131BBF73 -:102F0000012304F580528DF80D308DF80D301EBF71 -:102F1000D2F8B8340133C2F8B834F38803F00F03A1 -:102F20008DF80C309DF80C0000F09EFA5FFA8BF3E0 -:102F3000984225D9F2180CA90BF1010B127A0B4417 -:102F400003F82C2CEEE7012FA7D1E36AD3F8B020C9 -:102F500012F4FE0FA1D0D3F8B420950141BF04F5BF -:102F60008051D1F898240132C1F89824D3F8B420C4 -:102F7000500692D0D3F8B450266AC5F30525A4E7CD -:102F8000EFB9E36AC3F8A85004A807ADFFF71CFC2B -:102F900098E80F0007C52B800023204604A9ADF850 -:102FA0001830236804F58054DB6BCDE904A99847F9 -:102FB00058B1D4F890340133C4F890346EE7012F3F -:102FC000E2D1E36AC3F8B850DEE7D4F894340120C4 -:102FD0000133C4F8943461E72DE9F04105460F460A -:102FE00000F58054012639462846FFF745FF10B109 -:102FF00084F85364F7E7D4F8A834D4F854040133C0 -:10300000C4F8A83420B10368BDE8F0411B69184733 -:10301000BDE8F081C36AF0B51A6C12F47F0F2BD0B3 -:103020001B6C00F5805441F268054FF0010CC4F8A8 -:10303000AC340023471900EB43125E012A44117996 -:1030400011F0020F15D0490713D4B959C66A0CFA0A -:1030500001F1D6F8CCE011EA0E0F0AD0C6F8D41070 -:10306000117941F004011171D4F88C240132C4F8B3 -:103070008C240133202BDED1F0BD00002B4B70B52A -:103080001E561B5C012B30D8294D2A4A55F8233097 -:1030900052F8264013B349B3236D9A0510D54FF467 -:1030A0000073236500F086F950EA01020B4602D056 -:1030B000013861F10003024655F82600FFF772FE61 -:1030C000236D9B012CD54FF0007255F826302265F8 -:1030D00003F58053012283F8592421E0012323655D -:1030E000102323654FF48053236570BD236DDA07E9 -:1030F00002D4236D5B0706D50523002155F8260071 -:103100002365FFF769FF236DD80602D4236D5906A6 -:1031100006D55023012155F826002365FFF75CFFF3 -:1031200055F82600BDE87040FFF774BFC87B000863 -:1031300040640020CC7B000808B5302383F311885D -:10314000FFF768FF002383F3118808BDC36AD3F833 -:10315000C00010F07C5005D0D3F8C40080F40010FB -:10316000C0F340507047000008B5302383F3118846 -:1031700000F58050406CFEF7C9FF002383F31188EF -:1031800043090CBF0120002008BD000000F580535A -:1031900093F8592462B1C16A8A6922F001028A61F6 -:1031A000D3F89C240132C3F89C24002283F85924CC -:1031B000704700002DE9F743302181F3118800F5B5 -:1031C0008251002541F2680E4FF00108103100F5E0 -:1031D000805C00EB45147444267977071CD4F6060E -:1031E0001AD58E69D0F82C9008FA06F6D9F8CC706A -:1031F0003E4211D04F6801970F689742019F9F414F -:103200000AD2C9F8D460267946F004062671DCF8A3 -:1032100088440134CCF8884401352031202DD8D1A0 -:10322000002383F3118803B0BDE8F083F8B51E4690 -:1032300000230F46054613701446FFF795FF80F0F4 -:10324000010038701EB12846FFF780FF2070F8BDDE -:103250002DE9F04F85B099460D468046164691F807 -:1032600000B0DDE90EA302931378019300F0A2F8F9 -:103270002B7804460F4613B93378002B41D02246F1 -:103280003B464046FFF796FFFFF756FFFFF77EFFEE -:103290004B4632462946FFF7C9FF2B7833B1BBF1C5 -:1032A000000F03D0012005B0BDE8F08F337813B1D3 -:1032B000019B002BF6D108F5805303935445029BE4 -:1032C00077EB03031DD2039BD3F85404C8B1036802 -:1032D000AAEB04011B6898474B46324629464046F4 -:1032E000FFF7A4FF2B7813B1BBF1000FDAD13378CD -:1032F00013B1019B002BD5D100F05CF804460F46BA -:10330000DCE70020CFE70000002108B50846FFF702 -:10331000B5FEBDE8084001F06DB8000008B5012118 -:103320000020FFF7ABFEBDE8084001F063B80000E5 -:1033300008B500210120FFF7A1FEBDE8084001F01B -:1033400059B80000012108B50846FFF797FEBDE80F -:10335000084001F04FB8000000B59BB0EFF30981C1 -:1033600068226846FEF716FBEFF30583014B9B6B63 -:10337000FEE700BF00ED00E008B5FFF7EDFF00003D -:1033800000B59BB0EFF3098168226846FEF702FBA7 -:10339000EFF30583014B5B6BFEE700BF00ED00E040 -:1033A000FEE700000FB408B5029802F063FAFEE7EA -:1033B00002F0F6BE02F0D8BE13B56C46031D84E8D9 -:1033C000060094E8030083E80500012002B010BD68 -:1033D00073B58568019155B11B885B0707D4D0E9A7 -:1033E00000369B6B9847019AC1B23046A84701202E -:1033F00002B070BDF0B5866889B005460C465EB176 -:10340000BDF838305B070AD4D0E900379B6B98478A -:103410002246C1B23846B047012009B0F0BD0022B3 -:10342000002301F10806CDE9002300230A46ADF888 -:10343000083003AB1068083252F8041C1C46B24234 -:1034400003C42346F6D1106820609288A280FFF75B -:10345000B1FF0423ADF808302B68CDE90001DB6B28 -:10346000694628469847D7E7082817D909280CD075 -:103470000A280CD00B280CD00C280CD00D280CD00E -:103480000E2814BF4020302070470C2070471020B9 -:1034900070471420704718207047202070470000A4 -:1034A0002DE9F041456A15B94162BDE8F0814B68EC -:1034B000AC4623F06047C3F38A464FEAD37EC3F39A -:1034C000807816EA230638BF3E462B465A68BEEB84 -:1034D000D27F22F060440AD0002A18DAA40CB44249 -:1034E00017D19D420FD10D60DEE71346EEE7A742EC -:1034F00007D102F08044C2F3807242450BD054B130 -:10350000EFE708D2EDE7CCF800100B60CDE7B4424E -:1035100001D0B442E5D81A689C46002AE5D119606A -:10352000C3E700002DE9F047089D01F0070400EB18 -:10353000D1004FF47F494FEAD508224405F0070532 -:10354000944201D1BDE8F08704F0070705F0070AAF -:10355000111B08EBD50E57453E4613F80EC038BF79 -:103560005646C6F108068E4228BF0E46E108415C69 -:1035700034443544B94029FA06F721FA0AF1FFB27A -:103580008CEA010147FA0AF739408CEA010C03F88A -:103590000EC0D5E780EA0120082341F2210201B2E2 -:1035A000013B4000002980B2B8BF504013F0FF0338 -:1035B000F5D1704738B50C468D18A54200D138BDFD -:1035C00014F8011BFFF7E6FFF7E7000042684AB175 -:1035D000136881894360438901339BB299424381D7 -:1035E00038BF83811046704770B588B004462022EA -:1035F0000D4668460021FEF7F3F920460495FFF7D3 -:10360000E5FF024660B16B46054608AE1C4608352C -:1036100003CCB44245F8080C45F8041C2346F5D108 -:10362000104608B070BD0000082817D909280CD032 -:103630000A280CD00B280CD00C280CD00D280CD04C -:103640000E2814BF4020302070470C2070471020F7 -:1036500070471420704718207047202070470000E2 -:10366000082817D90C280CD910280CD914280CD9E3 -:1036700018280CD920280CD930288CBF0F200E20F8 -:103680007047092070470A2070470B2070470C20B4 -:1036900070470D20704700002DE9F843078C044661 -:1036A000072F1ED900254FF6FF73D0E90298C5F108 -:1036B0002006A5F1200029FA05F1083508FA06F6DA -:1036C00028FA00F0314301431846C9B2FFF762FF00 -:1036D000402D0346EBD13A46E169BDE8F843FFF7D8 -:1036E00069BF4FF6FF70BDE8F883000010B54B6866 -:1036F00023B9CA8A63F30902CA8210BD04691A6831 -:103700001C600361C38A013BC3824A60EFE700008B -:103710002DE9F84F1D46CB8A0F468146C3F30901B8 -:10372000924605290B4630D00020AAB207F11A04B0 -:103730009EB21FFA80F8042E0FD8904503F10103C2 -:1037400006D30A44FB8A62F309030120FB821AE0D4 -:103750001AF800600130E654EAE79045F1D2A1F191 -:10376000050B1C237C68BBFBF3F203FB12BB1FFAA7 -:103770008BF6002C45D14846FFF728FF044638B9A0 -:1037800078606FF00200BDE8F88F4FF00008E6E7C0 -:10379000002606607860ADB24FF0000B454510D9A9 -:1037A0000AEB0803221D13F8011B08F101089155CB -:1037B000B1B21FFA88F81B292BD0454506F1010646 -:1037C000F1D8FB8AC3F30902154465F30903BCE78A -:1037D00001321C4692B22368002BF9D16B1F0B44B7 -:1037E0001C21B3FBF1F301339BB29A42D3D2BBF15C -:1037F000000FD0D14846FFF7E9FE20B9C4F800B069 -:10380000BFE70122E7E7C0F800B05E46206004464B -:10381000C1E74545D5D94846FFF7D8FE08B920602D -:10382000AFE7C0F800B0002620600446B6E700000D -:103830002DE9F04F1C46074688462DED028B83B0DC -:103840005B690192002B00F09A80238C2BB1E26916 -:10385000002A00F09480072B35D807F10C00FFF701 -:10386000B5FE054638B96FF00205284603B0BDEC39 -:10387000028BBDE8F08F14220021FEF7B1F8228CF4 -:10388000E16905F10800FEF785F8208C48F0004159 -:10389000013080B2FFF7E4FEFFF7C6FE013880B2C8 -:1038A00020840130287438466369228C1B782A44AE -:1038B00003F01F0363F03F03137269602946FFF7AB -:1038C000EFFD0125D1E74FF0000900F10C034FF0A7 -:1038D000800A4E464D4608EE103A18EE100AFFF7E1 -:1038E00075FE83460028BED014220021FEF778F82A -:1038F000002E3AD1019B0222ABF808300BF1080EE2 -:103900001FFA82FC218C0CF10100BCF1060F80B281 -:1039100001D88E422BD3FFF7A3FE8E4208BF4FF093 -:10392000400AFFF781FE62690138013512781BFAFF -:1039300080F1013002F01F022DB242EA491289F0F3 -:1039400001094AEA020A48F0004281F808A05946F3 -:103950008BF810003846CBF804204FF0000AFFF730 -:103960009FFD238CB342B8D17FE70022C6E7E1690F -:10397000895D01360EF80210B6B20132C0E76FF071 -:10398000010572E7F8B515460E46302200210446BF -:103990001F46FEF725F8069BB5F5001FA76063607C -:1039A00004F11000079B34BF6A094FF6FF72E6610D -:1039B000A362002397B29A4206D800230360A7822D -:1039C000E3822383E360F8BD06600133304620368E -:1039D000F1E7000003781BB94BB2002BC8BF0170A0 -:1039E0007047000000787047F8B50C46C969074673 -:1039F00011B9238C002B37D1257E1F2D34D8387870 -:103A000028BB228C072A2CD8268A36F003032BD118 -:103A10004FF6FF70FFF7CEFD20F0010031024FF6A8 -:103A2000FF72400441EA0561400C41EA402523460B -:103A300029463846FFF7FCFE002807DD6269137847 -:103A40000133DBB21F2B88BF00231370F8BD218A1E -:103A50002D0645EA012505432046FFF71DFE0246D7 -:103A6000E5E76FF00300F1E76FF00100EEE700001B -:103A700070B58AB0044616460021282268461D46C5 -:103A8000FDF7AEFFBDF8383069462046ADF810307E -:103A90000F9B05939DF840308DF81830119B0793CC -:103AA000BDF84830CDE90265ADF82030FFF79CFF46 -:103AB0000AB070BD2DE9F041D36905460C461646A3 -:103AC0000BB9138C5BBB377E1F2F28D895F800806D -:103AD000B8F1000F26D03046FFF7DEFD3378210223 -:103AE0000246284641EAC331338A41EA080141EAE5 -:103AF000076141EA0341334641F08001FFF798FE38 -:103B000000280ADD3378012B07D17269137801335D -:103B1000DBB21F2B88BF00231370BDE8F0816FF06C -:103B20000100FAE76FF00300F7E70000F0B58BB093 -:103B300004460D4617460021282268461E46FDF71A -:103B40004FFF9DF84C30294620465A1E53425341A0 -:103B50006A468DF800309DF84030ADF81030119B6A -:103B600005939DF848308DF81830149B0793BDF8E5 -:103B70005430CDE90276ADF82030FFF79BFF0BB053 -:103B8000F0BD0000406A00B104307047436A1A6813 -:103B9000426202691A600361C38A013BC3827047B3 -:103BA0002DE9F041D0F8208014461D46184E4146BC -:103BB000002709B9BDE8F081D1E90223A21A65EB1B -:103BC0000303964277EB03031ED2036A8B420DD1A7 -:103BD000FFF78CFD036A1B68036203690B60C38AED -:103BE0000161013B016AC3828846E2E7FFF77EFD7F -:103BF0000B68C8F8003003690B60C38A0161013BA0 -:103C0000C382D8F80010D4E788460968D1E700BF1E -:103C100080841E002DE9F04F8BB00D4614469B4664 -:103C2000DDF850908046002800F01881B9F1000FAF -:103C300000F01481531E3F2B00F21081012A03D1A2 -:103C4000BBF1000F40F00A810023CDE90833B8F83A -:103C50001430B5EBC30F4FEAC30703D300200BB0FA -:103C6000BDE8F08F2B199F42D8F80C3036BF7F1B70 -:103C70002746FFB21BB9D8F81030002B7AD0272D79 -:103C80004DD8C5F1280600232946B742009308AB5A -:103C9000D8F808002CBFF6B23E46A7EB060A35441A -:103CA00032465FFA8AFAFFF73DFCB8F81430282153 -:103CB00003F10053053BDB000493D8F80C30039369 -:103CC000039B13B1BAF1000F2CD1D8F8100040B10A -:103CD000BAF1000F05D008AB5246691A0096FFF7FB -:103CE00021FC38B2002FB9D066070AD00AAB624275 -:103CF00003EBD40102F0070211F8083C134101F86C -:103D0000083C082C3DD9102C40F2B580202C40F204 -:103D1000B780BBF1000F00F09C80082335E0BA4665 -:103D20000026C2E7049BE02B28BFE02306930B4448 -:103D3000AB42059315D95A1B0398691A0096924510 -:103D400008AB00F1040034BF5246D2B20792FFF72D -:103D5000E9FB079A1644AAEB020A1544F6B25FFA89 -:103D60008AFA049B069A05999B1A0493039B1B6885 -:103D70000393A5E700933A4608AB2946D8F8080014 -:103D8000ADE7BBF1000F13D00123B4EBC30F6BD031 -:103D9000082C12D89DF82030621E23FA02F2D507B3 -:103DA00006D54FF0FF3202FA04F423438DF8203099 -:103DB0009DF8203089F8003051E7102C12D8BDF85A -:103DC0002030621E23FA02F2D10706D54FF0FF32EF -:103DD00002FA04F42343ADF82030BDF82030A9F8EE -:103DE00000303CE7202C0FD80899631E21FA03F31A -:103DF000DA0705D54FF0FF3202FA04F40C430894B9 -:103E0000089BC9F800302AE7402C2AD0611EC4F173 -:103E10002102A4F12103DDE9086526FA01F105FA82 -:103E200002F225FA03F311431943CB0711D50122FE -:103E3000A4F12003C4F1200102FA03F322FA01F1F4 -:103E4000A2400B43524263EB430332432B43CDE981 -:103E50000823DDE90823C9E9002300E76FF001002A -:103E6000FDE66FF00800FAE6082CA1D9102CB4D9B1 -:103E7000202CEED8C4E7BBF1000FAED0022384E7BC -:103E8000BBF1000FBCD004237FE70000012A30B54E -:103E9000144638BF012485B00025402C28BF40249B -:103EA000012ACDE9025518D81B788DF80830630730 -:103EB0000AD004AB624203EBD40502F0070215F806 -:103EC000083C934005F8083C034600912246002137 -:103ED00002A8FFF727FB05B030BD082AE4D9102A55 -:103EE00003D81B88ADF80830E1E7202A95BF1B688E -:103EF000D3E900230293CDE90223D8E710B5CB68BC -:103F00001BB98B600B618B8210BD04691A681C6041 -:103F10000361C38A013BC382CA60F0E703064CBF5A -:103F2000C0F3C0300220704708B50246FFF7F6FF25 -:103F3000022806D15306C2F30F2001D100F003007E -:103F400008BDC2F30740FBE72DE9F04F93B00446EC -:103F50000D46CDE903230A681046FFF7DFFF02286C -:103F6000824614BFC2F306260026002A80F2F3819F -:103F700012F0C04940F0EF81097B002900F0EB818D -:103F8000022803D02378B34240F0E881C2F30463EF -:103F900010462944069302F07F030593FFF7C4FF00 -:103FA000059B002283464FEA8348002348EA0A48DB -:103FB00048EA4668CE78CDE90823F30948EA0008C4 -:103FC000029368D0059B024608A9204600935346F9 -:103FD0006768B847002800F0C481276A4FB9414696 -:103FE00004F10C00FFF700FB074690B96FF00200E8 -:103FF00055E03B6998450DD03F68002FF9D1414607 -:1040000004F10C00FFF7F0FA07460028EED0236A0F -:104010003B60276297F817C006F01F08CCF3840CAA -:10402000ACEB0800A8EB0C031FFA80FE0028B8BF19 -:104030000EF120001FFA83FEB8BF00B2002B0793D9 -:10404000B8BF0EF12003D7E90221BCBF1BB2079312 -:1040500052EA010338D0039B4FF0000CDFF820E355 -:104060009A1A049B63EB010196457CEB01032BD369 -:104070006B7B97F81AE0734519D1029B002B78D01F -:10408000012821DC7868F8B9DFF8F0C2944570EBBC -:10409000010316D337E0276A27B96FF00C0013B07D -:1040A000BDE8F08F3B699845B4D03F68F4E7B3486A -:1040B00090427CEB010301D30020F0E7029B002B30 -:1040C000FAD0079B0F2B17DCFA7DB3003946204648 -:1040D00002F0030203F07C031343FB75FFF706FBBA -:1040E0006B7BBB76029B3BB9FB7DC3F38402013241 -:1040F00062F38603FB75D0E76A7BBB7E9A42DBD115 -:10410000029B002B35D0B309022B32D0039B142223 -:1041100000210DA8BB60049BFB60FDF761FC039BC5 -:104120000AA920460A93049BADF83EB00B932B1DC1 -:104130008DF840A00C932B7B8DF84180013BDBB2C6 -:10414000ADF83C30069B8DF84230059B8DF843302E -:1041500094F82C3083F001038DF84430A36898471D -:10416000FB7DC3F38403013303F01F039B02FB8237 -:10417000A2E7FB7DC6F34012B2EBD31F40F0F48000 -:10418000C3F38403434540F0F280029AB6092B7BC7 -:10419000002A4DD0F2075DD4032B40F2EB80039B45 -:1041A000AE1D394604F10C00BB603246049BFB6037 -:1041B0002B7B033BDBB2FFF7ABFA00280CDA394666 -:1041C0002046FFF793FAFB7DC3F38403013303F02A -:1041D0001F039B02FB8209E7AB88DDE908843B8370 -:1041E0004FF6FF73C9F12000A9F1200228FA09F166 -:1041F00009F1080904FA00F024FA02F20143184612 -:104200001143C9B2FFF7C6F9B9F1400F0346E9D12E -:10421000B88231462A7B033AD2B2FFF7CBF9FB7D55 -:10422000B882DA43C2F3C01262F3C713FB7543E7E7 -:1042300086B92E1D013B394604F10C00DBB2324633 -:10424000FFF766FA0028BADB2A7B3146B88A013AC2 -:10425000D2B2E2E7F98A013BC1F30901DAB20429DB -:104260005BD8281D002307F11B069A4208D910F8D5 -:1042700001CB013306F801C00131DBB20529F4D1CD -:10428000039993420A9138BF043304992CBF002349 -:1042900055FA83F30B9107F11B010C9179680E938A -:1042A0000D91291DFB8AADF83EB0C3F309038DF8CB -:1042B00040A08DF841801A44069B8DF84230059B42 -:1042C000ADF83C208DF8433094F82C3083F0010396 -:1042D0008DF844300023B88A7B602A7B013AFFF7CF -:1042E00069F93B8BB882834203D1A3680AA92046AF -:1042F000984720460AA9FFF701FEFB7DBA8AC3F35F -:104300008403013303F01F039B02FB823B8B9A4221 -:104310000CBF00206FF01000C1E67B68002BAFD00F -:10432000052001E01C3033461E68002EFAD1091A20 -:104330002E1D081D184401EB090C5FFA89F3BCF12E -:104340001B0F9DD89A429BD916F8013B09F1010930 -:1043500000F8013BEFE76FF00900A0E66FF00A00FC -:104360009DE66FF00B009AE66FF00D0097E66FF098 -:104370000E0094E66FF00F0091E600BF40420F0080 -:1043800080841E00EFF30983054968334A6B22F0ED -:1043900001024A6383F30988002383F3118870477D -:1043A00000EF00E0302080F3118862B60D4B0E4A1A -:1043B000D96821F4E0610904090C0A430B49DA6069 -:1043C000D3F8FC2042F08072C3F8FC20084AC2F8FF -:1043D000B01F116841F0010111602022DA7783F8E3 -:1043E0002200704700ED00E00003FA0555CEACC591 -:1043F000001000E0302310B583F311880E4B5B688A -:1044000013F4006314D0F1EE103AEFF309844FF087 -:104410008073683CE361094BDB6B236684F3098896 -:1044200001F0F2F910B1064BA36110BD054BFBE79B -:1044300083F31188F9E700BF00ED00E000EF00E032 -:104440003F0400084204000808B5074B074A1968F2 -:1044500001F03D01996053680BB190689847BDE841 -:104460000840FFF7C7BF00BF0000024054640020AF -:1044700008B5084B1968890901F03D018A019A6065 -:10448000054AD3680BB110699847BDE80840FFF7AB -:10449000B1BF00BF000002405464002008B5084BC3 -:1044A0001968090C01F03D010A049A60054A536934 -:1044B0000BB190699847BDE80840FFF79BBF00BF6C -:1044C000000002405464002008B5084B1968890DAB -:1044D00001F03D018A059A60054AD3690BB1106A63 -:1044E0009847BDE80840FFF785BF00BF00000240C5 -:1044F0005464002008B5074B074A596801F03D0194 -:10450000D960536A0BB1906A9847BDE80840FFF73D -:1045100071BF00BF000002405464002008B5084B82 -:104520005968890901F03D018A01DA60054AD36AB8 -:104530000BB1106B9847BDE80840FFF75BBF00BFA9 -:10454000000002405464002008B5084B5968090C6B -:1045500001F03D010A04DA60054A536B0BB1906B20 -:104560009847BDE80840FFF745BF00BF0000024084 -:104570005464002008B5084B5968890D01F03D01CD -:104580008A05DA60054AD36B0BB1106C9847BDE819 -:104590000840FFF72FBF00BF000002405464002016 -:1045A00008B5074B074A196801F03D019960536C43 -:1045B0000BB1906C9847BDE80840FFF71BBF00BFE8 -:1045C000000402405464002008B5084B19688909AA -:1045D00001F03D018A019A60054AD36C0BB1106D60 -:1045E0009847BDE80840FFF705BF00BF0004024040 -:1045F0005464002008B5084B1968090C01F03D010E -:104600000A049A60054A536D0BB1906D9847BDE856 -:104610000840FFF7EFBE00BF0004024054640020D2 -:1046200008B5084B1968890D01F03D018A059A60AB -:10463000054AD36D0BB1106E9847BDE80840FFF7EF -:10464000D9BE00BF000402405464002008B5074BE7 -:10465000074A596801F03D01D960536E0BB1906E65 -:104660009847BDE80840FFF7C5BE00BF0004024000 -:104670005464002008B5084B5968890901F03D01D0 -:104680008A01DA60054AD36E0BB1106F9847BDE816 -:104690000840FFF7AFBE00BF000402405464002092 -:1046A00008B5084B5968090C01F03D010A04DA60AD -:1046B000054A536F0BB1906F9847BDE80840FFF76C -:1046C00099BE00BF000402405464002008B5084BA6 -:1046D0005968890D01F03D018A05DA60054AD36FFA -:1046E00013B1D2F880009847BDE80840FFF782BEBA -:1046F000000402405464002000230C4910B51A46FF -:104700000B4C0B6054F82300026001EB43000433B0 -:104710004260402BF6D1074A4FF0FF339360D360DD -:10472000C2F80834C2F80C3410BD00BF5464002035 -:104730003C7C0008000002400F28F8B510D9102872 -:1047400010D0112811D0122808D10F240720DFF82B -:10475000C8E00126DEF80050A04208D9002653E048 -:104760000446F4E70F240020F1E70724FBE706FAEC -:1047700000F73D424AD1264C4FEA001C3D4304EB72 -:1047800000160EEBC000CEF80050C0E90123FBB2CA -:1047900073B12048D0F8D83043F00103C0F8D830C6 -:1047A000D0F8003143F00103C0F80031D0F80031F7 -:1047B00017F47F4F0ED01748D0F8D83043F00203DB -:1047C000C0F8D830D0F8003143F00203C0F800310F -:1047D000D0F8003154F80C00036823F01F03036085 -:1047E000056815F00105FBD104EB0C033D2493F89B -:1047F0000CC05F6804FA0CF43C602124056044613D -:1048000012B1987B00F066F93046F8BD0130A3E79D -:104810003C7C0008004402585464002010B5302449 -:1048200084F31188FFF788FF002383F3118810BDFC -:1048300010B50446807B00F063F901231549627BC3 -:1048400003FA02F20B6823EA0203DAB20B6072B9D0 -:10485000114AD2F8D81021F00101C2F8D810D2F8CC -:10486000001121F00101C2F80011D2F8002113F467 -:104870007F4F0ED1084BD3F8D82022F00202C3F8A4 -:10488000D820D3F8002122F00202C3F80021D3F887 -:10489000003110BD546400200044025808B5302394 -:1048A00083F31188FFF7C4FF002383F3118808BD49 -:1048B000026843681143016003B118477047000064 -:1048C000024A136843F0C003136070470078004049 -:1048D00013B50E4C204600F0BDFA04F1140000237D -:1048E0004FF400720A49009400F07AF9094B4FF432 -:1048F0000072094904F13800009400F0F3F9074A06 -:10490000074BC4E9172302B010BD00BFD8640020D4 -:1049100044650020C148000844670020007800403A -:1049200000E1F505037C30B5244C002918BF0C4686 -:10493000012B11D1224B98420ED1224BD3F8E82003 -:1049400042F08042C3F8E820D3F8102142F08042C0 -:10495000C3F81021D3F810312268036EC16D03EB48 -:1049600052038466B3FBF2F36268150442BF23F07E -:10497000070503F0070343EA4503CB60A36843F050 -:1049800040034B60E36843F001038B6042F496738D -:1049900043F001030B604FF0FF330B62510505D567 -:1049A00012F0102205D0B2F1805F04D080F864309C -:1049B00030BD7F23FAE73F23F8E700BF3C7D0008C6 -:1049C000D8640020004402582DE9F047C66D054622 -:1049D0003768F469210734621AD014F0080118BF4F -:1049E0004FF48071E20748BF41F02001A3074FF068 -:1049F000300348BF41F04001600748BF41F08001EB -:104A000083F31188281DFFF753FF002383F31188D8 -:104A1000E2050AD5302383F311884FF48061281D05 -:104A2000FFF746FF002383F311884FF030094FF062 -:104A3000000A14F0200838D13B0616D54FF0300993 -:104A400005F1380A200610D589F31188504600F088 -:104A50007DF9002836DA0821281DFFF729FF27F005 -:104A600080033360002383F31188790614D562062E -:104A700012D5302383F31188D5E913239A4208D144 -:104A80002B6C33B127F040071021281DFFF710FFD2 -:104A90003760002383F31188E30618D5AA6E1369E3 -:104AA000ABB15069BDE8F047184789F31188736AC4 -:104AB000284695F86410194000F0E6F98AF3118849 -:104AC000F469B6E7B06288F31188F469BAE7BDE823 -:104AD000F0870000090100F16043012203F5614302 -:104AE000C9B283F8001300F01F039A4043099B00EA -:104AF00003F1604303F56143C3F880211A607047F6 -:104B000000F01F0301229A40430900F160409B001E -:104B100000F5614003F1604303F56143C3F8802071 -:104B2000C3F88021002380F800337047F8B515469C -:104B3000826804460B46AA4200D28568A1692669AC -:104B4000761AB5420BD218462A46FCF723FFA36912 -:104B50002B44A3612846A3685B1BA360F8BD0CD956 -:104B6000AF1B18463246FCF715FF3A46E168304461 -:104B7000FCF710FFE3683B44EBE718462A46FCF7D6 -:104B800009FFE368E5E7000083689342F7B5044650 -:104B9000154600D28568D4E90460361AB5420BD2B6 -:104BA0002A46FCF7F7FE63692B4463612846A36835 -:104BB0005B1BA36003B0F0BD0DD93246AF1B019162 -:104BC000FCF7E8FE01993A46E0683144FCF7E2FE62 -:104BD000E3683B44E9E72A46FCF7DCFEE368E4E7E8 -:104BE00010B50A440024C361029B8460C160026165 -:104BF0000362C0E90000C0E9051110BD08B5D0E9A5 -:104C00000532934201D1826882B9826801328260A2 -:104C10005A1C426119700021D0E904329A4224BF23 -:104C2000C368436100F09CFE002008BD4FF0FF30D8 -:104C3000FBE7000070B5302304460E4683F311886D -:104C4000A568A5B1A368A269013BA360531CA36139 -:104C500015782269934224BFE368A361E3690BB12D -:104C600020469847002383F31188284607E0314601 -:104C7000204600F065FE0028E2DA85F3118870BD59 -:104C80002DE9F74F04460E4617469846D0F81C907B -:104C90004FF0300A8AF311884FF0000B154665B1CA -:104CA0002A4631462046FFF741FF034660B9414698 -:104CB000204600F045FE0028F1D0002383F3118840 -:104CC000781B03B0BDE8F08FB9F1000F03D001905D -:104CD0002046C847019B8BF31188ED1A1E448AF3C6 -:104CE0001188DCE7C160C361009B82600362C0E998 -:104CF00005111144C0E9000001617047F8B5044690 -:104D00000D461646302383F31188A768A7B1A36820 -:104D1000013BA36063695A1C62611D70D4E90432CF -:104D20009A4224BFE3686361E3690BB12046984768 -:104D3000002080F3118807E03146204600F000FE95 -:104D40000028E2DA87F31188F8BD0000D0E90523D6 -:104D500010B59A4201D182687AB982680021013285 -:104D600082605A1C82611C7803699A4224BFC3681E -:104D7000836100F0F5FD204610BD4FF0FF30FBE7EA -:104D80002DE9F74F04460E4617469846D0F81C907A -:104D90004FF0300A8AF311884FF0000B154665B1C9 -:104DA0002A4631462046FFF7EFFE034660B94146EA -:104DB000204600F0C5FD0028F1D0002383F31188C0 -:104DC000781B03B0BDE8F08FB9F1000F03D001905C -:104DD0002046C847019B8BF31188ED1A1E448AF3C5 -:104DE0001188DCE7026843681143016003B118478A -:104DF000704700001430FFF743BF00004FF0FF334F -:104E00001430FFF73DBF00003830FFF7B9BF000096 -:104E10004FF0FF333830FFF7B3BF00001430FFF717 -:104E200009BF00004FF0FF311430FFF703BF00004F -:104E30003830FFF763BF00004FF0FF323830FFF724 -:104E40005DBF0000012914BF6FF013000020704700 -:104E5000FFF73EBD044B036000234360C0E902330B -:104E600001230374704700BF547D000810B5302340 -:104E7000044683F31188FFF755FD022300202374B5 -:104E800080F3118810BD000038B5C36904460D4693 -:104E90001BB904210844FFF7A5FF294604F11400BB -:104EA000FFF7ACFE002806DA201D4FF40061BDE8D4 -:104EB0003840FFF797BF38BD02684368114301606F -:104EC00003B118477047000013B5406B00F58054DC -:104ED000D4F8A4381A681178042914D1017C022965 -:104EE00011D11979012312898B4013420BD101A9E9 -:104EF0004C3002F0F5F8D4F8A4480246019B217921 -:104F0000206800F0DFF902B010BD0000143002F09C -:104F100077B800004FF0FF33143002F071B8000092 -:104F20004C3002F049B900004FF0FF334C3002F032 -:104F300043B90000143002F045B800004FF0FF31D3 -:104F4000143002F03FB800004C3002F015B90000F8 -:104F50004FF0FF324C3002F00FB9000000207047D4 -:104F600010B500F58054D4F8A4381A6811780429D3 -:104F700017D1017C022914D15979012352898B4020 -:104F800013420ED1143001F0D7FF024648B1D4F8D5 -:104F9000A4484FF4407361792068BDE8104000F0E8 -:104FA0007FB910BD406BFFF7DBBF0000704700000A -:104FB0007FB5124B012504260446036000230574C7 -:104FC00000F1840243602946C0E902330C4B029091 -:104FD000143001934FF44073009601F089FF094BA0 -:104FE00004F69442294604F14C000294CDE9006392 -:104FF0004FF4407302F050F804B070BD7C7D00089F -:10500000A54F0008C94E00080A68302383F31188B1 -:105010000B790B3342F823004B79133342F823000A -:105020008B7913B10B3342F8230000F58053C3F89A -:10503000A41802230374002080F311887047000035 -:1050400038B5037F044613B190F85430ABB901254D -:10505000201D0221FFF730FF04F114006FF0010161 -:10506000257700F089FC04F14C0084F854506FF06F -:105070000101BDE8384000F07FBC38BD10B501210A -:1050800004460430FFF718FF0023237784F85430D8 -:1050900010BD000038B504460025143001F040FF73 -:1050A00004F14C00257702F00FF8201D84F85450CD -:1050B0000121FFF701FF2046BDE83840FFF750BF50 -:1050C00090F8803003F06003202B06D190F8812007 -:1050D0000023212A03D81F2A06D800207047222A3D -:1050E000FBD1C0E91D3303E0034A42670722826710 -:1050F000C3670120704700BF3C23002037B500F58F -:105100008055D5F8A4381A68117804291AD1017C81 -:10511000022917D11979012312898B40134211D129 -:1051200000F14C04204602F08FF858B101A9204646 -:1051300001F0D6FFD5F8A4480246019B21792068EA -:1051400000F0C0F803B030BD01F10B03F0B550F82A -:10515000236085B004460D46FEB1302383F31188E9 -:1051600004EB8507301D0821FFF7A6FEFB6806F15A -:105170004C005B691B681BB1019001F0BFFF0198F7 -:1051800003A901F0ADFF024648B1039B2946204622 -:1051900000F098F8002383F3118805B0F0BDFB6898 -:1051A0005A691268002AF5D01B8A013B1340F1D1DD -:1051B00004F18002EAE70000133138B550F82140CD -:1051C000ECB1302383F3118804F58053D3F8A4287D -:1051D0001368527903EB8203DB689B695D6845B114 -:1051E00004216018FFF768FE294604F1140001F05D -:1051F000ADFE2046FFF7B4FE002383F3118838BDCF -:105200007047000001F07AB901234022002110B557 -:10521000044600F8303BFCF7E3FB0023C4E901330C -:1052200010BD000010B53023044683F311882422FA -:10523000416000210C30FCF7D3FB204601F080F9DF -:1052400002230020237080F3118810BD70B500EB9D -:105250008103054650690E461446DA6018B11022E3 -:105260000021FCF7BDFBA06918B110220021FCF75A -:10527000B7FB31462846BDE8704001F067BA000030 -:1052800083682022002103F0011310B504468360D7 -:105290001030FCF7A5FB2046BDE8104001F0E2BA53 -:1052A000F0B4012500EB810447898D40E4683D435B -:1052B000A469458123600023A2606360F0BC01F013 -:1052C000FFBA0000F0B4012500EB810407898D408E -:1052D000E4683D436469058123600023A260636044 -:1052E000F0BC01F075BB000070B502230025044638 -:1052F000242203702946C0F888500C3040F8045C22 -:10530000FCF76EFB204684F8705001F0B3F9636837 -:105310001B6823B129462046BDE87040184770BD80 -:105320000378052B10B504460AD080F88C3005238D -:10533000037043681B680BB1042198470023A360E6 -:1053400010BD00000178052906D190F88C20436833 -:1053500002701B6803B118477047000070B590F8E1 -:105360007030044613B1002380F8703004F18002DD -:10537000204601F09BFA63689B68B3B994F88030CB -:1053800013F0600535D00021204601F08DFD00218D -:10539000204601F07DFD63681B6813B1062120469D -:1053A0009847062384F8703070BD2046984700283F -:1053B000E4D0B4F88630A26F9A4288BFA36794F90C -:1053C0008030A56F002B4FF0300380F20381002D59 -:1053D00000F0F280092284F8702083F31188002104 -:1053E0002046D4E91D23FFF76DFF002383F31188C6 -:1053F000DAE794F8812003F07F0343EA022340F2C6 -:105400000232934200F0C58021D8B3F5807F48D0A6 -:105410000DD8012B3FD0022B00F09380002BB2D18E -:1054200004F1880262670222A267E367C1E7B3F56D -:10543000817F00F09B80B3F5407FA4D194F8823047 -:10544000012BA0D1B4F8883043F0020332E0B3F569 -:10545000006F4DD017D8B3F5A06F31D0A3F5C0635E -:10546000012B90D86368204694F882205E6894F8F7 -:105470008310B4F88430B047002884D04368636751 -:105480000368A3671AE0B3F5106F36D040F6024206 -:1054900093427FF478AF5C4B63670223A3670023DA -:1054A000C3E794F88230012B7FF46DAFB4F88830F5 -:1054B00023F00203A4F88830C4E91D55E56778E7B6 -:1054C000B4F88030B3F5A06F0ED194F88230204646 -:1054D00084F88A3001F02CF963681B6813B101214C -:1054E00020469847032323700023C4E91D339CE71B -:1054F00004F18B0363670123C3E72378042B10D1E6 -:10550000302383F311882046FFF7BAFE85F3118814 -:105510000321636884F88B5021701B680BB120460F -:10552000984794F88230002BDED084F88B30042327 -:10553000237063681B68002BD6D002212046984751 -:10554000D2E794F8843020461D0603F00F010AD5F7 -:1055500001F09EF9012804D002287FF414AF2B4BF0 -:105560009AE72B4B98E701F085F9F3E794F882303E -:10557000002B7FF408AF94F8843013F00F01B3D000 -:105580001A06204602D501F0A7FCADE701F098FC11 -:10559000AAE794F88230002B7FF4F5AE94F88430BB -:1055A00013F00F01A0D01B06204602D501F07CFCB1 -:1055B0009AE701F06DFC97E7142284F8702083F3DA -:1055C00011882B462A4629462046FFF769FE85F3B7 -:1055D0001188E9E65DB1152284F8702083F3118803 -:1055E00000212046D4E91D23FFF75AFEFDE60B22D9 -:1055F00084F8702083F311882B462A4629462046DA -:10560000FFF760FEE3E700BFAC7D0008A47D000863 -:10561000A87D000838B590F870300446002B3ED0C5 -:10562000063BDAB20F2A34D80F2B32D8DFE803F06A -:10563000373131082232313131313131313137377F -:10564000856FB0F886309D4214D2C3681B8AB5FBC3 -:10565000F3F203FB12556DB9302383F311882B4607 -:105660002A462946FFF72EFE85F311880A2384F87F -:1056700070300EE0142384F87030302383F31188E7 -:10568000002320461A461946FFF70AFE002383F33B -:10569000118838BDC36F03B198470023E7E70021A5 -:1056A000204601F001FC0021204601F0F1FB636877 -:1056B0001B6813B10621204698470623D7E7000050 -:1056C00010B590F870300446142B29D017D8062B4B -:1056D00005D001D81BB110BD093B022BFBD800211E -:1056E000204601F0E1FB0021204601F0D1FB636878 -:1056F0001B6813B1062120469847062319E0152B95 -:10570000E9D10B2380F87030302383F31188002314 -:105710001A461946FFF7D6FD002383F31188DAE70E -:10572000C3689B695B68002BD5D1C36F03B19847F1 -:10573000002384F87030CEE7002382680375036984 -:105740001B6899689142FBD25A68036042601060FE -:105750005860704700238268037503691B68996865 -:105760009142FBD85A6803604260106058607047ED -:1057700008B50846302383F311880B7D032B05D031 -:10578000042B0DD02BB983F3118808BD8B6900223F -:105790001A604FF0FF338361FFF7CEFF0023F2E77B -:1057A000D1E9003213605A60F3E70000FFF7C4BF8D -:1057B000054BD96808751868026853601A600122A1 -:1057C000D8600275FAF726BE486900200C4B30B548 -:1057D000DD684B1C87B004460FD02B46094A68464B -:1057E00000F05EF92046FFF7E3FF009B13B1684627 -:1057F00000F060F9A86907B030BDFFF7D9FFF9E7FD -:105800004869002071570008044B1A68DB689068EB -:105810009B68984294BF002001207047486900208F -:10582000084B10B51C68D868226853601A600122C2 -:10583000DC602275FFF78EFF01462046BDE8104070 -:10584000FAF7E8BD4869002038B5074C0123002568 -:10585000064907482370656001F034FD0223237078 -:1058600085F3118838BD00BFB06B0020B47D0008FF -:105870004869002008B572B6044B186500F062FC58 -:1058800000F028FD024B03221A70FEE74869002051 -:10589000B06B002000F044B9034A516853685B1AAA -:1058A0009842FBD8704700BF001000E08B600223D5 -:1058B000086108468B8270478368A3F1840243F82D -:1058C000142C026943F8442C426943F8402C094ADD -:1058D00043F8242CC268A3F1200043F8182C0222BC -:1058E00003F80C2C002203F80B2C034A43F8102C6D -:1058F000704700BF2D0400084869002008B5FFF775 -:10590000DBFFBDE80840FFF751BF0000024BDB683A -:1059100098610F20FFF74CBF48690020302383F3C4 -:105920001188FFF7F3BF000008B50146302383F369 -:1059300011880820FFF74AFF002383F3118808BD70 -:10594000064BDB6839B1426818605A6013604360E7 -:105950000420FFF73BBF4FF0FF307047486900203D -:105960000368984206D01A68026050601846996130 -:10597000FFF71CBF7047000038B504460D4620688D -:10598000844200D138BD036823605C608561FFF705 -:105990000DFFF4E7036810B59C68A2420CD85C6860 -:1059A0008A600B604C602160596099688A1A9A601D -:1059B0004FF0FF33836010BD121B1B68ECE7000043 -:1059C0000A2938BF0A2170B504460D460A26601917 -:1059D00001F070FC01F058FC041BA54203D8751CB3 -:1059E00004462E46F3E70A2E04D90120BDE8704094 -:1059F00001F0A8BC70BD0000F8B5144B0D460A2A92 -:105A00004FF00A07D96103F11001826038BF0A2202 -:105A1000416019691446016048601861A81801F0D6 -:105A200039FC01F031FC431B0646A34206D37C1C23 -:105A300028192746354601F03DFCF2E70A2F04D924 -:105A40000120BDE8F84001F07DBCF8BD48690020A8 -:105A5000F8B506460D4601F017FC0F4A134653F8F9 -:105A6000107F9F4206D12A4601463046BDE8F840E5 -:105A7000FFF7C2BFD169BB68441A2C1928BF2C4656 -:105A8000A34202D92946FFF79BFF2246314603482D -:105A9000BDE8F840FFF77EBF486900205869002044 -:105AA000C0E90323002310B45DF8044B4361FFF702 -:105AB000CFBF000010B5194C236998420DD0816802 -:105AC000D0E9003213605A609A680A449A60002351 -:105AD00003604FF0FF33A36110BD0268234643F813 -:105AE000102F53600022026022699A4203D1BDE860 -:105AF000104001F0D9BB936881680B44936001F0BA -:105B0000C3FB2269E1699268441AA242E4D91144B4 -:105B1000BDE81040091AFFF753BF00BF48690020D5 -:105B20002DE9F047DFF8BC8008F110072C4ED8F8BB -:105B3000105001F0A9FBD8F81C40AA68031B9A4238 -:105B40003ED814444FF00009D5E90032C8F81C4093 -:105B500013605A60C5F80090D8F81030B34201D1F4 -:105B600001F0A2FB89F31188D5E903312846984753 -:105B7000302383F311886B69002BD8D001F084FBAC -:105B80006A69A0EB040982464A450DD2022001F061 -:105B9000D9FB0022D8F81030B34208D1514628462C -:105BA000BDE8F047FFF728BF121A2244F2E712EBD4 -:105BB00009092946384638BF4A46FFF7EBFEB5E7E4 -:105BC000D8F81030B34208D01444C8F81C00211A89 -:105BD000A960BDE8F047FFF7F3BEBDE8F08700BF5E -:105BE000586900204869002038B501F04DFB054A8E -:105BF000D2E90845031B181945F10001C2E9080163 -:105C000038BD00BF4869002000207047FEE7000053 -:105C1000704700004FF0FF307047000002290CD0A1 -:105C2000032904D00129074818BF00207047032A20 -:105C300005D8054800EBC2007047044870470020B3 -:105C4000704700BF8C7E00084C230020407E000877 -:105C500070B59AB005460846144601A900F0C2F88E -:105C600001A8FBF7B5FE431C0022C6B25B0010463C -:105C7000C5E9003423700323023404F8013C01AB6E -:105C8000D1B202348E4201D81AB070BD13F8011B94 -:105C9000013204F8010C04F8021CF1E708B53023C6 -:105CA00083F311880348FFF729FA002383F311884F -:105CB00008BD00BFB86B002090F8803003F01F02D1 -:105CC000012A07D190F881200B2A03D10023C0E9D3 -:105CD0001D3315E003F06003202B08D1B0F88430A9 -:105CE0002BB990F88120212A03D81F2A04D8FFF766 -:105CF000E7B9222AEBD0FAE7034A42670722826714 -:105D0000C3670120704700BF4323002007B5052962 -:105D100017D8DFE801F0191603191920302383F38F -:105D20001188104A01210190FFF790FA0198022191 -:105D30000D4AFFF78BFA0D48FFF7ACF9002383F308 -:105D4000118803B05DF804FB302383F31188074802 -:105D5000FFF776F9F2E7302383F311880348FFF762 -:105D60008DF9EBE7E07D0008047E0008B86B0020A9 -:105D700038B50C4D0C4C2A460C4904F10800FFF7CD -:105D800067FF05F1CA0204F110000949FFF760FF3F -:105D900005F5CA7204F118000649BDE83840FFF75E -:105DA00057BF00BF908400204C230020C07D000816 -:105DB000CA7D0008D57D000870B5044608460D462A -:105DC000FBF706FEC6B22046013403780BB918462D -:105DD00070BD32462946FBF7E7FD0028F3D10120CC -:105DE000F6E700002DE9F04705460C46FBF7F0FD0D -:105DF0002B49C6B22846FFF7DFFF08B10A36F6B2D4 -:105E000028492846FFF7D8FF08B11036F6B2632EAE -:105E10000BD8DFF88C80DFF88C90234FDFF894A04C -:105E20002E7846B92670BDE8F08729462046BDE8A1 -:105E3000F04701F06BBE252E2ED1072241462846A1 -:105E4000FBF7B2FD70B9194B224603F1100153F86C -:105E5000040B8B4242F8040BF9D11B78073511343F -:105E60001370DDE7082249462846FBF79DFD98B9E7 -:105E7000A21C0F4B197802320909C95D02F8041CF3 -:105E800013F8011B01F00F015345C95D02F8031C13 -:105E9000F0D118340835C3E7013504F8016BBFE7CA -:105EA000AC7E0008D57D0008B47E00082A7B00087F -:105EB00000E8F11F0CE8F11FBFF34F8F044B1A6984 -:105EC0005107FCD1D3F810215207F8D1704700BF19 -:105ED0000020005208B50D4B1B78ABB9FFF7ECFF63 -:105EE0000B4BDA68D10704D50A4A5A6002F18832AE -:105EF0005A60D3F80C21D20706D5064AC3F804210C -:105F000002F18832C3F8042108BD00BFEE860020EC -:105F1000002000522301674508B5114B1B78F3B9E7 -:105F2000104B1A69510703D5DA6842F04002DA6073 -:105F3000D3F81021520705D5D3F80C2142F04002C6 -:105F4000C3F80C21FFF7B8FF064BDA6842F00102F4 -:105F5000DA60D3F80C2142F00102C3F80C2108BD2D -:105F6000EE860020002000520F289ABF00F58060C6 -:105F700040040020704700004FF4003070470000DC -:105F8000102070470F2808B50BD8FFF7EDFF00F57C -:105F900000330268013204D104308342F9D1012078 -:105FA00008BD0020FCE700000F2838B505463FD8A3 -:105FB000FFF782FF1F4CFFF78DFF4FF0FF330728DD -:105FC0006361C4F814311DD82361FFF775FF030224 -:105FD00043F02403E360E36843F08003E360236954 -:105FE0005A07FCD42846FFF767FFFFF7BDFF4FF4C1 -:105FF000003100F04BF92846FFF78EFFBDE838402E -:10600000FFF7C0BFC4F81031FFF756FFA0F1080337 -:106010001B0243F02403C4F80C31D4F80C3143F0D4 -:106020008003C4F80C31D4F810315B07FBD4D9E7F6 -:10603000002038BD002000522DE9F84F05460C46DF -:10604000104645EA0203DE0602D00020BDE8F88FC4 -:1060500020F01F00DFF8BCB0DFF8BCA0FFF73AFF6C -:1060600004EB0008444503D10120FFF755FFEDE79D -:1060700020222946204601F017FD10B92035203492 -:10608000F0E72B4605F120021F68791CDDD10433AF -:106090009A42F9D105F178431B481C4EB3F5801F95 -:1060A0001B4B38BF184603F1F80332BFD946D1461F -:1060B0001E46FFF701FF0760A5EB040C336804F1EF -:1060C0001C0143F002033360231FD9F8007017F05E -:1060D0000507FAD153F8042F8B424CF80320F4D172 -:1060E000BFF34F8FFFF7E8FE4FF0FF33202221462A -:1060F00003602846336823F00203336001F0D4FCC8 -:106100000028BBD03846B0E7142100520C200052C2 -:1061100014200052102000521021005210B5084CDB -:10612000237828B11BB9FFF7D5FE0123237010BDDA -:10613000002BFCD02070BDE81040FFF7EDBE00BF83 -:10614000EE86002038B5054D00240334696855F803 -:106150000C0B00F0ADF8122CF7D138BDC87E00084A -:10616000084601F099BC000038B5EFF311859DB9E0 -:10617000EFF30584C4F30804302334B183F31188AA -:10618000FFF732FD85F3118838BD83F31188FFF7DF -:106190002BFD84F3118838BDBDE83840FFF724BDDE -:1061A00010B5FFF7E1FF104CC008104A002340EA89 -:1061B0004170C908A0FB04ECA0FB020E1CEB000020 -:1061C000A1FB044CA1FB02125B41001943EB0C0044 -:1061D00011EB0E0142F10002411842F100000909E1 -:1061E00041EA007010BD00BFCFF753E3A59BC42068 -:1061F0000244074BD2B210B5904200D110BD441CEE -:1062000000B253F8200041F8040BE0B2F4E700BFFD -:10621000504000580E4B30B51C6F240405D41C6F41 -:106220001C671C6F44F400441C670A4C024423683A -:10623000D2B243F480732360074B904200D130BD4B -:10624000441C51F8045B00B243F82050E0B2F4E77C -:1062500000440258004802585040005807B5012237 -:1062600001A90020FFF7C4FF019803B05DF804FB0B -:1062700013B50446FFF7F2FFA04205D0012201A9A1 -:1062800000200194FFF7C6FF02B010BD0144BFF328 -:106290004F8F064B884204D3BFF34F8FBFF36F8FEE -:1062A0007047C3F85C022030F4E700BF00ED00E067 -:1062B0000144BFF34F8F064B884204D3BFF34F8F87 -:1062C000BFF36F8F7047C3F870022030F4E700BF50 -:1062D00000ED00E070470000074B45F255521A6090 -:1062E00002225A6040F6FF729A604CF6CC421A6065 -:1062F0000122024B1A70704700480058F4860020B3 -:10630000034B1B781BB1034B4AF6AA221A60704755 -:10631000F486002000480058034B1A681AB9034A53 -:10632000D2F8D0241A607047F0860020004002584E -:10633000024B4FF48032C3F8D0247047004002581B -:1063400008B5FFF7E9FF024B1868C0F3806008BD8D -:10635000F086002070B5BFF34F8FBFF36F8F1A4ADE -:106360000021C2F85012BFF34F8FBFF36F8F5369F4 -:1063700043F400335361BFF34F8FBFF36F8FC2F805 -:106380008410BFF34F8FD2F8803043F6E074C3F32C -:10639000C900C3F34E335B0103EA0406014646EA33 -:1063A00081750139C2F86052F9D2203B13F1200FF8 -:1063B000F2D1BFF34F8F536943F480335361BFF37E -:1063C0004F8FBFF36F8F70BD00ED00E0FEE7000060 -:1063D000214B2248224A70B5904237D3214BC11E2F -:1063E000DA1C121A22F003028B4238BF002200216D -:1063F000FBF7F6FA1C4A0023C2F88430BFF34F8F34 -:10640000D2F8803043F6E074C3F3C900C3F34E33CF -:106410005B0103EA0406014646EA81750139C2F8C8 -:106420006C52F9D2203B13F1200FF2D1BFF34F8F02 -:10643000BFF36F8FBFF34F8FBFF36F8F0023C2F88F -:106440005032BFF34F8FBFF36F8F70BD53F8041BF3 -:1064500040F8041BC0E700BF60810008C888002026 -:10646000C8880020C888002000ED00E0074BD3F862 -:10647000D81021EA0001C3F8D810D3F8002122EA8D -:106480000002C3F80021D3F80031704700440258DD -:1064900070B5D0E9244300224FF0FF359E6804EB2D -:1064A00042135101D3F80009002805DAD3F8000996 -:1064B00040F08040C3F80009D3F8000B002805DA4B -:1064C000D3F8000B40F08040C3F8000B0132631892 -:1064D0009642C3F80859C3F8085BE0D24FF00113A5 -:1064E000C4F81C3870BD0000890141F02001016131 -:1064F00003699B06FCD41220FFF7CEB910B50A4CF5 -:106500002046FEF781FE094BC4F89030084BC4F8D2 -:106510009430084C2046FEF777FE074BC4F89030C5 -:10652000064BC4F8943010BDF886002000000840E7 -:10653000347F00089487002000000440407F00085A -:1065400070B503780546012B5CD1434BD0F89040E1 -:10655000984258D1414B0E216520D3F8D82042F003 -:106560000062C3F8D820D3F8002142F00062C3F8DB -:106570000021D3F80021D3F8802042F00062C3F854 -:106580008020D3F8802022F00062C3F88020D3F866 -:106590008030FEF79FFA324BE360324BC4F800388C -:1065A0000023D5F89060C4F8003EC02323604FF468 -:1065B0000413A3633369002BFCDA01230C2033613D -:1065C000FFF76AF93369DB07FCD41220FFF764F99F -:1065D0003369002BFCDA00262846A660FFF758FF37 -:1065E0006B68C4F81068DB68C4F81468C4F81C68E9 -:1065F00083BB1D4BA3614FF0FF336361A36843F07E -:106600000103A36070BD194B9842C9D1134B4FF0E1 -:106610008060D3F8D82042F00072C3F8D820D3F8B5 -:10662000002142F00072C3F80021D3F80021D3F812 -:10663000802042F00072C3F88020D3F8802022F03E -:106640000072C3F88020D3F88030FFF70FFF0E21CF -:106650004D209EE7064BCDE7F88600200044025807 -:106660004014004003002002003C30C0948700200A -:10667000083C30C0F8B5D0F89040054600214FF0F6 -:1066800000662046FFF730FFD5F8941000234FF046 -:1066900001128F684FF0FF30C4F83438C4F81C285A -:1066A00004EB431201339F42C2F80069C2F8006B49 -:1066B000C2F80809C2F8080BF2D20B68D5F890208E -:1066C000C5F89830636210231361166916F010063E -:1066D000FBD11220FFF7E0F8D4F8003823F4FE6372 -:1066E000C4F80038A36943F4402343F01003A361C6 -:1066F0000923C4F81038C4F814380B4BEB604FF082 -:10670000C043C4F8103B094BC4F8003BC4F81069FF -:10671000C4F80039D5F8983003F1100243F480131F -:10672000C5F89820A362F8BD107F000840800010D3 -:10673000D0F8902090F88A10D2F8003823F4FE6345 -:1067400043EA0113C2F80038704700002DE9F8430E -:1067500000EB8103D0F890500C468046DA680FFABF -:1067600081F94801166806F00306731E022B05EB3B -:1067700041134FF0000194BFB604384EC3F8101B0C -:106780004FF0010104F1100398BF06F1805601FAA1 -:1067900003F3916998BF06F5004600293AD0578A5D -:1067A00004F15801374349016F50D5F81C180B43C9 -:1067B0000021C5F81C382B180127C3F81019A74071 -:1067C0005369611E9BB3138A928B9B08012A88BF71 -:1067D0005343D8F89820981842EA034301F1400245 -:1067E0002146C8F89800284605EB82025360FFF75F -:1067F0007BFE08EB8900C3681B8A43EA8453483454 -:106800001E4364012E51D5F81C381F43C5F81C786F -:10681000BDE8F88305EB4917D7F8001B21F40041C8 -:10682000C7F8001BD5F81C1821EA0303C0E704F1E0 -:106830003F030B4A2846214605EB83035A60FFF7C6 -:1068400053FE05EB4910D0F8003923F40043C0F89B -:106850000039D5F81C3823EA0707D7E70080001075 -:1068600000040002D0F894201268C0F89820FFF7C6 -:106870000FBE00005831D0F8903049015B5813F436 -:10688000004004D013F4001F0CBF02200120704709 -:106890004831D0F8903049015B5813F4004004D0DF -:1068A00013F4001F0CBF02200120704700EB810190 -:1068B000CB68196A0B6813604B685360704700001F -:1068C00000EB810330B5DD68AA691368D36019B99C -:1068D000402B84BF402313606B8A1468D0F890204B -:1068E0001C4402EB4110013C09B2B4FBF3F46343D6 -:1068F000033323F0030343EAC44343F0C043C0F827 -:10690000103B2B6803F00303012B0ED1D2F808389B -:1069100002EB411013F4807FD0F8003B14BF43F02A -:10692000805343F00053C0F8003B02EB4112D2F811 -:10693000003B43F00443C2F8003B30BD2DE9F04179 -:10694000D0F8906005460C4606EB4113D3F8087B5F -:106950003A07C3F8087B08D5D6F814381B0704D5C6 -:1069600000EB8103DB685B689847FA071FD5D6F810 -:106970001438DB071BD505EB8403D968CCB98B69C8 -:10698000488A5A68B2FBF0F600FB16228AB91868EA -:10699000DA6890420DD2121AC3E90024302383F33F -:1069A000118821462846FFF78BFF84F31188BDE844 -:1069B000F081012303FA04F26B8923EA02036B815D -:1069C000CB68002BF3D021462846BDE8F04118479C -:1069D00000EB81034A0170B5DD68D0F890306C6936 -:1069E0002668E66056BB1A444FF40020C2F810092E -:1069F0002A6802F00302012A0AB20ED1D3F808086D -:106A000003EB421410F4807FD4F8000914BF40F067 -:106A1000805040F00050C4F8000903EB4212D2F855 -:106A2000000940F00440C2F800090122D3F83408FC -:106A300002FA01F10143C3F8341870BD19B9402EB0 -:106A400084BF4020206020681A442E8A8419013CAB -:106A5000B4FBF6F440EAC44040F00050C6E7000042 -:106A60002DE9F843D0F8906005460C464F0106EB3F -:106A70004113D3F8088918F0010FC3F808891CD016 -:106A8000D6F81038DB0718D500EB8103D3F80CC01B -:106A9000DCF81430D3F800E0DA68964530D2A2EB87 -:106AA0000E024FF000091A60C3F80490302383F3FC -:106AB0001188FFF78DFF89F3118818F0800F1DD022 -:106AC000D6F834380126A640334217D005EB8403AC -:106AD0000134D5F89050D3F80CC0E4B22F44DCF860 -:106AE000142005EB0434D2F800E05168714514D34A -:106AF000D5F8343823EA0606C5F83468BDE8F883CB -:106B0000012303FA01F2038923EA02030381DCF87B -:106B10000830002BD1D09847CFE7AEEB0103BCF88B -:106B20001000834228BF0346D7F8180980B2B3EBA0 -:106B3000800FE3D89068A0F1040959F8048FC4F8D5 -:106B40000080A0EB09089844B8F1040FF5D8184468 -:106B50000B4490605360C8E72DE9F84FD0F890508F -:106B600004466E69AB691E4016F480586E6103D00E -:106B7000BDE8F84FFEF7B8BB002E12DAD5F8003E9C -:106B80009B0705D0D5F8003E23F00303C5F8003E6F -:106B9000D5F80438204623F00103C5F80438FEF781 -:106BA000D1FB370505D52046FFF772FC2046FEF7DE -:106BB000B7FBB0040CD5D5F8083813F0060FEB6816 -:106BC00023F470530CBF43F4105343F4A053EB6011 -:106BD00031071BD56368DB681BB9AB6923F0080379 -:106BE000AB612378052B0CD1D5F8003E9A0705D070 -:106BF000D5F8003E23F00303C5F8003E2046FEF71B -:106C0000A1FB6368DB680BB120469847F30200F1F3 -:106C1000BA80B70226D5D4F8909000274FF0010A29 -:106C200009EB4712D2F8003B03F44023B3F5802F61 -:106C300011D1D2F8003B002B0DDA62890AFA07F372 -:106C400022EA0303638104EB8703DB68DB6813B18B -:106C50003946204698470137D4F89430FFB29B68F4 -:106C60009F42DDD9F00619D5D4F89000026AC2F32C -:106C70000A1702F00F0302F4F012B2F5802F00F0B1 -:106C8000CA80B2F5402F09D104EB8303002200F53E -:106C90008050DB681B6A974240F0B0803003D5F823 -:106CA000185835D5E90303D500212046FFF746FEE5 -:106CB000AA0303D501212046FFF740FE6B0303D54D -:106CC00002212046FFF73AFE2F0303D50321204679 -:106CD000FFF734FEE80203D504212046FFF72EFE1D -:106CE000A90203D505212046FFF728FE6A0203D535 -:106CF00006212046FFF722FE2B0203D5072120465E -:106D0000FFF71CFEEF0103D508212046FFF716FE12 -:106D1000700340F1A780E90703D500212046FFF763 -:106D20009FFEAA0703D501212046FFF799FE6B07B6 -:106D300003D502212046FFF793FE2F0703D5032139 -:106D40002046FFF78DFEEE0603D504212046FFF70F -:106D500087FEA80603D505212046FFF781FE6906B8 -:106D600003D506212046FFF77BFE2A0603D507211F -:106D70002046FFF775FEEB0574D520460821BDE8D7 -:106D8000F84FFFF76DBED4F890904FF0000B4FF026 -:106D9000010AD4F894305FFA8BF79B689F423FF664 -:106DA00038AF09EB4713D3F8002902F44022B2F5BB -:106DB000802F20D1D3F80029002A1CDAD3F800292B -:106DC00042F09042C3F80029D3F80029002AFBDBE7 -:106DD0003946D4F89000FFF787FB22890AFA07F3B7 -:106DE00022EA0303238104EB8703DB689B6813B16A -:106DF0003946204698470BF1010BCAE7910701D1AC -:106E0000D0F80080072A02F101029CBF03F8018B31 -:106E10004FEA18283FE704EB830300F58050DA6857 -:106E2000D2F818C0DCF80820DCE9001CA1EB0C0C3F -:106E300000218F4208D1DB689B699A683A449A60C6 -:106E40005A683A445A6029E711F0030F01D1D0F88B -:106E500000808C4501F1010184BF02F8018B4FEAEB -:106E60001828E6E7BDE8F88F08B50348FFF774FE79 -:106E7000BDE80840FDF7BEBAF886002008B5034813 -:106E8000FFF76AFEBDE80840FDF7B4BA948700201A -:106E9000D0F8903003EB4111D1F8003B43F40013DC -:106EA000C1F8003B70470000D0F8903003EB41116F -:106EB000D1F8003943F40013C1F8003970470000DD -:106EC000D0F8903003EB4111D1F8003B23F40013CC -:106ED000C1F8003B70470000D0F8903003EB41113F -:106EE000D1F8003923F40013C1F8003970470000CD -:106EF00030B50433039C0172002104FB0325C160FB -:106F0000C0E90653049B0363059BC0E90000C0E988 -:106F10000422C0E90842C0E90A11436330BD000001 -:106F20000022416AC260C0E90411C0E90A226FF080 -:106F30000101FEF721BD0000D0E90432934201D1E6 -:106F4000C2680AB9181D70470020704703691960AC -:106F50000021C2680132C260C2691344826993424F -:106F6000036124BF436A0361FEF7FABC38B50446E7 -:106F70000D46E3683BB162690020131D1268A362ED -:106F80001344E36207E0237A33B929462046FEF72B -:106F9000D7FC0028EDDA38BD6FF00100FBE70000F8 -:106FA000C368C269013BC360436913448269934269 -:106FB000436124BF436A436100238362036B03B1CF -:106FC0001847704770B53023044683F31188866AEA -:106FD0003EB9FFF7CBFF054618B186F31188284666 -:106FE00070BDA36AE26A13F8015B9342A36202D305 -:106FF0002046FFF7D5FF002383F31188EFE7000059 -:107000002DE9F84F04460E46174698464FF03009D2 -:1070100089F311880025AA46D4F828B0BBF1000FE7 -:1070200009D141462046FFF7A1FF20B18BF311881B -:107030002846BDE8F88FD4E90A12A7EB050B521ACF -:10704000934528BF9346BBF1400F1BD9334601F14E -:10705000400251F8040B914243F8040BF9D1A36AA2 -:10706000403640354033A362D4E90A239A4202D322 -:107070002046FFF795FF8AF31188BD42D8D289F3E5 -:107080001188C9E730465A46FAF784FCA36A5E4481 -:107090005D445B44A362E7E710B5029C04330172D0 -:1070A00003FB0421C460C0E906130023C0E90A33CE -:1070B000039B0363049BC0E90000C0E90422C0E90C -:1070C0000842436310BD0000026A6FF00101C26014 -:1070D000426AC0E904220022C0E90A22FEF74CBC41 -:1070E000D0E904239A4201D1C26822B9184650F867 -:1070F000043B0B60704700231846FAE7C368002181 -:10710000C2690133C3604369134482699342436196 -:1071100024BF436A4361FEF723BC000038B5044630 -:107120000D46E3683BB1236900201A1DA262E269A3 -:107130001344E36207E0237A33B929462046FEF779 -:10714000FFFB0028EDDA38BD6FF00100FBE700001F -:1071500003691960C268013AC260C2691344826956 -:107160009342036124BF436A036100238362036B7C -:1071700003B118477047000070B530230D46044630 -:10718000114683F31188866A2EB9FFF7C7FF10B145 -:1071900086F3118870BDA36A1D70A36AE26A013389 -:1071A0009342A36204D3E16920460439FFF7D0FF7C -:1071B000002080F31188EDE72DE9F84F04460D46D5 -:1071C000904699464FF0300A8AF311880026B3465C -:1071D000A76A4FB949462046FFF7A0FF20B187F3C1 -:1071E00011883046BDE8F88FD4E90A073A1AA8EBAF -:1071F0000607974228BF1746402F1BD905F14003C9 -:1072000055F8042B9D4240F8042BF9D1A36A40366F -:107210004033A362D4E90A239A4204D3E1692046A9 -:107220000439FFF795FF8BF311884645D9D28AF3CD -:107230001188CDE729463A46FAF7ACFBA36A3D44EC -:107240003E443B44A362E5E7D0E904239A4217D1C8 -:10725000C3689BB1836A8BB1043B9B1A0ED0136049 -:10726000C368013BC360C3691A4483699A420261DF -:1072700024BF436A036100238362012318467047D9 -:107280000023FBE700F024B9014B586A704700BFA8 -:10729000000C0040034B002258631A610222DA609E -:1072A000704700BF000C0040014B0022DA607047BD -:1072B000000C0040014B5863704700BF000C0040B9 -:1072C000FEE7000070B51B4B0025044686B05860F1 -:1072D0000E4685620163FDF765F804F11003A560B1 -:1072E000E562C4E904334FF0FF33C4E90044C4E964 -:1072F0000635FFF7C9FF2B46024604F1340120464C -:10730000C4E9082380230C4A2565FEF7CFFA012340 -:107310000A4AE06000920375684672680192B2689A -:10732000CDE90223064BCDE90435FEF7E7FA06B0B6 -:1073300070BD00BFB06B00204C7F0008517F00087B -:10734000C1720008024AD36A1843D062704700BF76 -:10735000486900204B6843608B688360CB68C360DA -:107360000B6943614B6903628B6943620B6803607D -:107370007047000008B53C4B40F2FF713B48D3F822 -:1073800088200A43C3F88820D3F8882022F4FF62BB -:1073900022F00702C3F88820D3F88820D3F8E02031 -:1073A0000A43C3F8E020D3F808210A43C3F80821B0 -:1073B0002F4AD3F808311146FFF7CCFF00F5806063 -:1073C00002F11C01FFF7C6FF00F5806002F13801F1 -:1073D000FFF7C0FF00F5806002F15401FFF7BAFF2C -:1073E00000F5806002F17001FFF7B4FF00F58060E6 -:1073F00002F18C01FFF7AEFF00F5806002F1A801F9 -:10740000FFF7A8FF00F5806002F1C401FFF7A2FFBB -:1074100000F5806002F1E001FFF79CFF00F580605D -:1074200002F1FC01FFF796FF02F58C7100F5806018 -:10743000FFF790FF00F018F90E4BD3F8902242F0BE -:107440000102C3F89022D3F8942242F00102C3F85B -:1074500094220522C3F898204FF06052C3F89C2074 -:10746000054AC3F8A02008BD004402580000025895 -:10747000587F000800ED00E01F00080308B500F089 -:10748000D5FAFEF7E1F90F4BD3F8DC2042F04002C9 -:10749000C3F8DC20D3F8042122F04002C3F8042111 -:1074A000D3F80431084B1A6842F008021A601A68CF -:1074B00042F004021A60FEF72FFFBDE80840FEF715 -:1074C00057BC00BF00440258001802487047000033 -:1074D000114BD3F8E82042F00802C3F8E820D3F8B3 -:1074E000102142F00802C3F810210C4AD3F81031E1 -:1074F000D36B43F00803D363C722094B9A624FF062 -:10750000FF32DA6200229A615A63DA605A6001221D -:107510005A611A60704700BF004402580010005CB6 -:10752000000C0040094A08B51169D3680B40D9B274 -:107530009B076FEA0101116107D5302383F311889E -:10754000FEF7A8F9002383F3118808BD000C004062 -:10755000064BD3F8DC200243C3F8DC20D3F8042127 -:107560001043C3F80401D3F80431704700440258B3 -:1075700008B53C4B4FF0FF31D3F8802062F0004259 -:10758000C3F88020D3F8802002F00042C3F88020A6 -:10759000D3F88020D3F88420C3F88410D3F8842053 -:1075A0000022C3F88420D3F88400D86F40F0FF4055 -:1075B00040F4FF0040F4DF4040F07F00D867D86F10 -:1075C00020F0FF4020F4FF0020F4DF4020F07F0097 -:1075D000D867D86FD3F888006FEA40506FEA5050F0 -:1075E000C3F88800D3F88800C0F30A00C3F8880005 -:1075F000D3F88800D3F89000C3F89010D3F8900027 -:10760000C3F89020D3F89000D3F89400C3F89410F6 -:10761000D3F89400C3F89420D3F89400D3F89800DA -:10762000C3F89810D3F89800C3F89820D3F89800BE -:10763000D3F88C00C3F88C10D3F88C00C3F88C20DE -:10764000D3F88C00D3F89C00C3F89C10D3F89C109E -:10765000C3F89C20D3F89C30FDF74EF8BDE80840F5 -:1076600000F0B8B90044025808B50122534BC3F8E2 -:107670000821534BD3F8F42042F00202C3F8F4205F -:10768000D3F81C2142F00202C3F81C210222D3F8D5 -:107690001C314C4BDA605A689104FCD54A4A1A6096 -:1076A00001229A60494ADA6000221A614FF440428E -:1076B0009A61444B9A699204FCD51A6842F480722C -:1076C0001A603F4B1A6F12F4407F04D04FF480329F -:1076D0001A6700221A671A6842F001021A60384BD2 -:1076E0001A685007FCD500221A611A6912F0380294 -:1076F000FBD1012119604FF0804159605A67344A2B -:10770000DA62344A1A611A6842F480321A602C4BE9 -:107710001A689103FCD51A6842F480521A601A68FC -:107720009204FCD52C4A2D499A6200225A631963AF -:1077300001F57C01DA6301F5E77199635A64284A1F -:107740001A64284ADA621A6842F0A8521A601C4B7E -:107750001A6802F02852B2F1285FF9D148229A61E2 -:107760004FF48862DA6140221A621F4ADA641F4AC3 -:107770001A651F4A5A651F4A9A6532231E4A1360CA -:10778000136803F00F03022BFAD10D4A136943F07B -:1077900003031361136903F03803182BFAD14FF078 -:1077A0000050FFF7D5FE4FF08040FFF7D1FE4FF0BD -:1077B0000040BDE80840FFF7CBBE00BF008000518D -:1077C000004402580048025800C000F002000001C6 -:1077D0000000FF0100889008322060006302090168 -:1077E000470E0508DD0BBF0120000020000001103E -:1077F0000910E00000010110002000524FF0B042DB -:1078000008B5D2F8883003F00103C2F8883023B1FC -:10781000044A13680BB150689847BDE80840FCF76C -:10782000E9BD00BF488800204FF0B04208B5D2F84B -:10783000883003F00203C2F8883023B1044A936809 -:107840000BB1D0689847BDE80840FCF7D3BD00BF36 -:10785000488800204FF0B04208B5D2F8883003F0D5 -:107860000403C2F8883023B1044A13690BB150698C -:107870009847BDE80840FCF7BDBD00BF4888002020 -:107880004FF0B04208B5D2F8883003F00803C2F8D0 -:10789000883023B1044A93690BB1D0699847BDE899 -:1078A0000840FCF7A7BD00BF488800204FF0B04259 -:1078B00008B5D2F8883003F01003C2F8883023B13D -:1078C000044A136A0BB1506A9847BDE80840FCF7B8 -:1078D00091BD00BF488800204FF0B04310B5D3F8E9 -:1078E000884004F47872C3F88820A30604D5124AAD -:1078F000936A0BB1D06A9847600604D50E4A136BA1 -:107900000BB1506B9847210604D50B4A936B0BB112 -:10791000D06B9847E20504D5074A136C0BB1506C45 -:107920009847A30504D5044A936C0BB1D06C9847D3 -:10793000BDE81040FCF75EBD488800204FF0B04322 -:1079400010B5D3F8884004F47C42C3F8882062055F -:1079500004D5164A136D0BB1506D9847230504D515 -:10796000124A936D0BB1D06D9847E00404D50F4ACD -:10797000136E0BB1506E9847A10404D50B4A936E59 -:107980000BB1D06E9847620404D5084A136F0BB14F -:10799000506F9847230404D5044A936F0BB1D06FFE -:1079A0009847BDE81040FCF725BD00BF488800207F -:1079B00008B50348FDF708F8BDE80840FCF71ABD14 -:1079C000D864002008B5FFF7ADFDBDE80840FCF71E -:1079D00011BD0000062108B50846FDF77BF8062119 -:1079E0000720FDF777F806210820FDF773F8062138 -:1079F0000920FDF76FF806210A20FDF76BF8062134 -:107A00001720FDF767F806212820FDF763F8092104 -:107A10007A20FDF75FF807213220FDF75BF80C2193 -:107A20005220BDE80840FDF755B8000008B5FFF743 -:107A30009FFD00F00DF8FDF70BFAFDF7E3FBFDF7F6 -:107A4000B5FAFFF743FDBDE80840FFF71BBC000097 -:107A50000023054A19460133102BC2E9001102F137 -:107A60000802F8D1704700BF488800200B46014645 -:107A7000184600F003B8000000F00EB810B5054C31 -:107A800013462CB10A4601460220AFF3008010BD18 -:107A90002046FCE700000000024B01461868FEF794 -:107AA0005FBB00BF6C23002010B501390244904237 -:107AB00001D1002005E0037811F8014FA34201D065 -:107AC000181B10BD0130F2E72DE9F041A3B1C91A2E -:107AD00017780144044603F1FF3C8C42204601D94B -:107AE000002009E00578BD4204F10104F5D10CEB5A -:107AF0000405D618A54201D1BDE8F08115F8018D25 -:107B000016F801EDF045F5D0E7E70000034611F85F -:107B1000012B03F8012B002AF9D170476F72672EF1 -:107B20006172647570696C6F742E437562654F7213 -:107B3000616E67652D7065726970680053544D33CE -:107B40003248373F3F3F0053544D33324837337844 -:107B50002F3732780053544D3332483734332F3770 -:107B600035332F373530000001105A00031059000B -:107B7000012058000320560040A2E4F164689106F9 -:107B80000041A3E5F26569920700000043414E46BB -:107B90004449666163653A204D657373616765208A -:107BA00052414D204F766572666C6F772100000060 -:107BB0004261642043414E496661636520696E6499 -:107BC00065782E00000100000001FF0000A00040C9 -:107BD00000A400400000000000000000C92A0008C6 -:107BE0005123000851320008C1230008CD230008AA -:107BF000E527000845250008892300088D23000893 -:107C0000652300084D230008A12700087123000800 -:107C1000B93300087D2300087527000801040E050C -:107C2000054B02020E05054B04010E05054B05012F -:107C30000B04044B08010603034600001000024039 -:107C4000080002400008024000000B00280002402B -:107C5000080002400408024006010C0040000240F7 -:107C6000080002400808024010020D0058000240BF -:107C7000080002400C08024016030E00700002408B -:107C80000C0002401008024000040F00880002406F -:107C90000C0002401408024006051000A00002403B -:107CA0000C0002401808024010061100B800024003 -:107CB0000C0002401C08024016072F00100402406E -:107CC000080402402008024000083800280402404E -:107CD000080402402408024006093900400402401A -:107CE0000804024028080240100A3A0058040240E2 -:107CF000080402402C080240160B3B0070040240AE -:107D00000C04024030080240000C3C008804024091 -:107D10000C04024034080240060D4400A004024056 -:107D20000C04024038080240100E4500B80402401E -:107D30000C0402403C080240160F4600009600006A -:107D40000000000000000000000000000000000033 -:107D50000000000000000000114E0008FD4D00086A -:107D6000394E0008254E0008314E00081D4E00080F -:107D7000094E0008F54D0008454E000800000000BF -:107D8000294F0008154F0008514F00083D4F0008CB -:107D9000494F0008354F0008214F00080D4F0008DB -:107DA0005D4F00080000000001000000000000001E -:107DB00063300000B07D0008A0690020B06B002097 -:107DC0004172647550696C6F740025424F41524492 -:107DD000252D424C002553455249414C25000000B9 -:107DE000020000000000000049510008B9510008DD -:107DF00040004000608400207084002002000000E9 -:107E00000000000003000000000000000152000814 -:107E1000000000001000000080840020000000002E -:107E20000100000000000000F886002001010200AF -:107E30000D5D00081D5C0008B95C00089D5C000831 -:107E400043000000487E000809024300020100C010 -:107E5000320904000001020201000524001001059E -:107E60002401000104240202052406000107058202 -:107E7000030800FF09040100020A000000070501D1 -:107E800002400000070581024000000012000000CF -:107E9000947E0008120110010200004009124157AF -:107EA00000020102030100000403090425424F41BE -:107EB0005244250030313233343536373839414277 -:107EC00043444546000000000001002000FF01007F -:107ED0000200000000000030000004000800000064 -:107EE000000000240000080004000000000400005E -:107EF00000FC0000020000000000043000800000D0 -:107F0000080000000000003800000100010000002F -:107F1000000000005D53000815560008C156000817 -:107F20004000400030880020308800200100000020 -:107F30004088002080000000400100000800000090 -:107F40000001000000100000080000006D61696E73 -:107F50000069646C650000000000802A00000000D9 -:107F6000AAAAAAAA00000024FFFF00000000000047 -:107F700000A00A000021000200000000AAAAAAAA8C -:107F800000000000FFFF00000000000900000900E1 -:107F90001400005400000000AAAAAAAA1400005469 -:107FA000FFFF000000000000000000000A40100079 -:107FB00000000000AAAA8AAA00401000FFFF0000EB -:107FC0009900000000000000008102000000000095 -:107FD000AAAAAAAA00410100FFFF00000000007049 -:107FE000070000000000000000000000AAAAAAAAE2 -:107FF00000000000FFFF0000000000000000000083 -:108000000000000000000000AAAAAAAA00000000C8 -:10801000FFFF000000000000000000000000000062 -:1080200000000000AAAAAAAA00000000FFFF0000AA -:108030000000000000000000000000000000000040 -:10804000AAAAAAAA00000000FFFF0000000000008A -:10805000000000000000000000000000AAAAAAAA78 -:1080600000000000FFFF0000000000000000000012 -:108070000000000000000000AAAAAAAA0000000058 -:10808000FFFF0000000000000000000000000000F2 -:10809000780500000000000000001E000000000045 -:1080A000FE2A0100D2040000FF000000B86B00208F -:1080B000D8640020000000003C7B0008830400001E -:1080C000477B000850040000557B00080096000024 -:1080D00000000800960000000008000004000000F6 -:1080E000A87E000800000000000000000000000062 -:1080F00000000000000000000000000070230020CD -:10810000000000000000000000000000000000006F -:10811000000000000000000000000000000000005F -:10812000000000000000000000000000000000004F -:10813000000000000000000000000000000000003F -:10814000000000000000000000000000000000002F -:10815000000000000000000000000000000000001F +:101B300055F82600BDE8704003F0E8B970BD00BF5D +:101B4000DC6300201C230020586B0020C4630020AD +:101B5000F8B571B6002301201A46194602F0AEFE10 +:101B60000446802004F0ECFB002849D00025254ADB +:101B700080274FF4D06C3D26136913F0C06F26D137 +:101B8000D2F8103113F0C06F21D1236805F1006144 +:101B900099602368D86023685F602368C3F800C039 +:101BA00021680B6843F001030B6021680B6823F088 +:101BB0001E030B6021680B68DB07FCD4237B803598 +:101BC000616806FA03F3B5F5001F0B60D4D1204617 +:101BD00002F0B4FEB5F5001F11D000240A4E0B4DE3 +:101BE000012004F00FFB3388A34205D92868204464 +:101BF000013404F04DFAF6E7002004F003FB61B66F +:101C0000F8BD00BF00200052DE6300209863002072 +:101C10002DE9F3470D46044600219046284640F240 +:101C20007912FFF7DDFE234620220021284604F129 +:101C3000220702F077F9231D022220212846C02620 +:101C400002F070F9631D03222221284602F06AF98E +:101C5000A31D03222521284602F064F904F108039C +:101C600010222821284602F05DF904F11003082211 +:101C70003821284602F056F904F1110308224021C8 +:101C8000284602F04FF904F11203082248212846A1 +:101C900002F048F904F1140320225021284602F0F2 +:101CA00041F904F1180340227021284602F03AF964 +:101CB00004F120030822B021284602F033F904F190 +:101CC00021030822B821284602F02CF931460836B3 +:101CD0003B4608222846013702F024F9B6F5A07FDA +:101CE000F4D194F83230314604F1330A00268DF8ED +:101CF000073008220DF10703284602F013F99DF87A +:101D000007304FEAC6099E4209F5A47720D394F81C +:101D10003231502B28BF50238DF80730B8F1000F17 +:101D200008D1394609F24F170DF10703072228465B +:101D300002F0F8F8002604F233149DF8073007EBA0 +:101D4000C6019E420DD30731C80802B0BDE8F08736 +:101D50000AEB0603082239462846013602F0E2F86B +:101D6000CDE7A31908222846013602F0DBF8E4E7A4 +:101D700013B5044608460021202223460190016045 +:101D8000C0F8031002F0CEF8231D01980222202192 +:101D900002F0C8F8631D01980322222102F0C2F864 +:101DA000A31D01980322252102F0BCF8019804F13B +:101DB00008031022282102F0B5F8072002B010BD58 +:101DC000F7B5047F05460E462CB1838A122B02D943 +:101DD000012003B0F0BD00230722284600961946D3 +:101DE00001F064FF731C01220721009328460023A1 +:101DF00001F05CFFD4B9B31C0522082128460093EA +:101E000023460D2401F052FFB378102BE0D837465B +:101E1000BB1BB278934210D307342B7FA88AE40807 +:101E2000B3B9844294BF00200120D2E7AB8A0824D2 +:101E3000DB00083BDB08B370E6E7FB1C2146082209 +:101E40002846009300230834013701F02FFFDFE715 +:101E5000201A18BF0120BCE7F7B5047F05460E46DF +:101E60002CB1838ACA2B02D9012003B0F0BD002314 +:101E7000082228460096194601F018FF731CD4B9B1 +:101E800008220093234610241146284601F00EFF35 +:101E90007378C82BE8D801235F1C7278013B93420A +:101EA00010D307342B7FA88AE408B3B9844294BFC7 +:101EB00000200120D9E7AB8A0824DB00083BDB08BF +:101EC0007370E5E7F31921460822284600930023A2 +:101ED00001F0ECFE08343B46DEE7201A18BF012073 +:101EE000C3E70000F7B50D46044600211646284614 +:101EF0008122FFF775FD234608220021284602F0C3 +:101F000011F894F901206378002AB8BF7F238DF877 +:101F100007309EB90F270DF1070307220821284635 +:101F200002F000F8002602349DF8073007EBC601E6 +:101F30009E4205D30731C80803B0F0BD0827F1E77A +:101F4000A31908222846013601F0ECFFECE7000057 +:101F5000F7B50E460546002114463046CE22FFF75F +:101F60003FFD2B4628220021304601F0DBFF2B7A73 +:101F7000C82B28BFC8238DF807308CB930240DF149 +:101F8000070308222821304601F0CCFF2F467B1B97 +:101F90009DF80720934205D3E01DC00803B0F0BDB3 +:101FA0002824F3E707F109032146082230460834C4 +:101FB000013701F0B7FFEAE7F7B5047F05460E46A3 +:101FC00034B1838AB3F5827F02D9012003B0F0BD1A +:101FD0000123102200212846009601F067FEDCB99B +:101FE000B31C09221021284600932346192401F02E +:101FF0005DFE7388B3F5807FE7D83746BB1B7288D8 +:10200000934210D307342B7FA88AE408B3B98442E3 +:1020100094BF00200120D9E7AB8A1024DB00103BDD +:10202000DB087380E5E73B1D214608222846009324 +:1020300000230834013701F039FEDFE7201A18BF0A +:102040000120C3E730B50A44084D91420DD011F884 +:10205000013B5840082340F30004013B2C4013F09F +:10206000FF0384EA5000F6D1EFE730BD2083B8EDDE +:10207000F7B5364A6B46106851686A4603C30823B1 +:102080003349344805F084FF044690BB0A25324AA0 +:102090006B46106851686A4603C308232F492D48D0 +:1020A00005F076FF0446002847D00369B3F5F01F1A +:1020B00043D8B0F86620B2F5AF6F3ED1284A02444B +:1020C00002F15C018B4238D35C3B224900209E1A0E +:1020D000FFF7B8FF04F16401074632460020FFF71E +:1020E000B1FFA3689F4228D1E368984208BF00254A +:1020F00023E00369B3F5F01F26D8428BB2F5AF6F2A +:1021000020D1174A024402F110018B4218D3103B30 +:10211000104900209D1AFFF795FF04F118010646AB +:102120002A460020FFF78EFFA3689E4202D1E36893 +:10213000984201D00D25AAE70025284603B0F0BD3E +:102140001025A4E70C25A2E70B25A0E74080000896 +:10215000DCFF1D00000002084980000890FF1D0000 +:102160000800FEF710B5037C044613B9006804F0BC +:102170001BF9204610BD00000023BFF35B8FC36036 +:10218000BFF35B8FBFF35B8F8360BFF35B8F7047E1 +:10219000BFF35B8F0068BFF35B8F704770B5054678 +:1021A0000C30FFF7F5FF044605F108063046FFF74F +:1021B000EFFFA04206D96D683046FFF7E9FF2544DE +:1021C000281A70BD3046FFF7E3FF201AF9E7000038 +:1021D00070B505464068A0B105F10C0605F1080090 +:1021E000FFF7D6FF04463046FFF7D2FF844204F1E2 +:1021F000FF34304694BF6D680025FFF7C9FF2C44BB +:10220000201A70BD38B50C460546FFF7C7FFA0423F +:1022100010D305F10800FFF7BBFF04446868BFF363 +:102220005B8FB4FBF0F100FB11440120AC60BFF305 +:102230005B8F38BD0020FCE72DE9F04114460746CE +:102240000D46FFF7C5FF844228BF0446D4B1B84607 +:1022500058F80C6B4046FFF79BFF3044286040461F +:102260007E68FFF795FF331A9C4203D801206C600B +:10227000BDE8F081A41B6B603B682044AB60E86064 +:102280000220F5E72046F3E738B50C460546FFF790 +:102290009FFFA04210D305F10C00FFF779FF044423 +:1022A0006868BFF35B8FB4FBF0F100FB11440120C1 +:1022B000EC60BFF35B8F38BD0020FCE72DE9FF41E8 +:1022C0008846694607466C46FFF7B6FF002506B20A +:1022D00004EBC606B4420AD0626808EB0501206828 +:1022E0000834FFF757FB54F8043C1D44F2E7294635 +:1022F0003846FFF7C9FF284604B0BDE8F08100006A +:10230000F8B505460C300F46FFF742FF05F1080609 +:1023100004463046FFF73CFFA042304688BF6C6859 +:10232000FFF736FF201A386020B12C683046FFF7DF +:102330002FFF2044F8BD000073B5144606460D4635 +:10234000FFF72CFF8442019028BF0446DCB101A9AD +:102350003046FFF7D5FF019B33B93268C5E9023338 +:10236000C5E9002401200CE09C42286038BF01949C +:10237000019884426860F5D93368241A0220AB6062 +:10238000EC6002B070BD2046FBE700002DE9FF4184 +:102390000F4669466C46FFF7CFFF00B2002604EBFC +:1023A000C005AC4209D0D4F80480B81954F8081B11 +:1023B00042464644FFF7EEFAF3E7304604B0BDE884 +:1023C000F081000038B50546FFF7E0FF04460146FE +:1023D0002846FFF717FF204638BD000008B103F07C +:1023E000E3BF70477047000010B4134602681468DA +:1023F0000022A4465DF8044B6047000000F58050C1 +:1024000090F859047047000000F5805090F852048D +:102410007047000000F5805090F9580470470000A4 +:102420004E207047302383F3118800F58052D2F894 +:102430009C34D2F898041844D2F894341844D2F852 +:102440007C341844D2F88C341844D2F888341844B8 +:10245000002383F31188704700F58050C0F85414AE +:10246000012070472DE9F04F0C4600F5805185B0F2 +:102470001F4691F8523405469046BDF838909BB1FE +:10248000D1F878340133C1F878342368980006D441 +:10249000237B082B0BD9627B0AB10F2B07D9D1F80C +:1024A0007C340133C1F87C344FF0FF3010E030232E +:1024B00083F31188EB6AD3F8C42012F4001B0AD00E +:1024C000D1F8803400200133C1F8803480F31188C2 +:1024D00005B0BDE8F08F20684822D3F8C43000284A +:1024E000C3F3044A6B6AB4BF40F08040800412FB1F +:1024F0000A334FEA4A161860226852004FEA0A620D +:1025000044BF40F000501860207B42EA00425A600D +:10251000607B10B342F440125A60D1F8B02401320B +:10252000C1F8B024AA1902F58352117B41F02001B1 +:102530001173207B039300F0E3FF0330039B8010B3 +:102540005FFA8BF20BF1010B82420DDA04EB820190 +:1025500003EB820249689160F2E7AA1902F58352FF +:10256000117B60F34511E3E70122EB6A05EB4A11A9 +:1025700002FA0AF201F58251C3F8D020AB191831E2 +:1025800004F10C0203F58253C3E90487234653F890 +:10259000040B934241F8040BF9D11B882E440B80A5 +:1025A00041F2680346F803A006F5805609F00303DC +:1025B00096F86C2043F0100322F01F02134386F8B4 +:1025C0006C30002383F3118842463B46214628465F +:1025D000CDF8009000F05AFF012079E72DE9F0478F +:1025E00000F58056044696F85254002D40F00381C1 +:1025F000037C032B40F0948028462B462F465FFA3D +:1026000080FC944510DA01EBCC0E51F83CC0BCF1D3 +:10261000000F04DBDEF804C0BCF1000F02DB013761 +:102620000130ECE70133FBE7302080F31188E06AEA +:10263000F3B9D0F8803043F00203C0F880304E2365 +:10264000E06A002F6FD1D0F8803043F00103C0F86A +:1026500080306A4B6A4A1B6803F1805303F52C53A0 +:102660009B009342A36240F2B080664800F0E6FE11 +:102670004D2B42D8DFF884814FEA034EDFF8889172 +:10268000D8F800C04EEA8C0EC0F884E00CF18050FF +:1026900000F52C508000606103EB0C00D4F82CC0D6 +:1026A000C3F14E03C8F80000DCF8800040F03000B1 +:1026B000CCF880004FF0000CD4F81480E6465FFAA6 +:1026C0008CF08242BCDD01EBC00A51F830000028DA +:1026D00010DBDAF804A0BAF1000F0BDA09EA0040C7 +:1026E0000AF07F0A40EA0A0040F0084048F82E004D +:1026F0000EF1010E0CF1010CE1E7836923F00103F7 +:10270000836100F0A1FE0646E36A9B69D90704D500 +:1027100000F09AFE831BFA2BF6D9002383F311886D +:102720002846BDE8F087B7EB530F3DD2DFF8CCE089 +:102730004FEA074CDEF800304CEA830CC0F888C042 +:1027400003F1805003EB4703002700F52C50CEF82F +:102750000030BC468000A061E06AD0F8803043F0D1 +:102760000C03C0F88030D4F818E0FBB29A427FF72F +:1027700070AF51F8330001EBC3080028D8F80430DB +:1027800001DB002B0EDB20F0604023F0604340F0C3 +:10279000005043F000434EF83C000EEBCC000CF12F +:1027A000010C43600137E0E7836923F00103836193 +:1027B00000F04AFE0646E36A9B69DA07ADD500F0F1 +:1027C00043FE831BFA2BF6D9A7E7E26A936923F04D +:1027D0000103936100F038FE0746E36A9B69DB075B +:1027E00005D500F031FEC31BFA2BF6D995E701257C +:1027F00086F8525491E7002592E700BFEC63002071 +:10280000FCB50040548000080000FF0713B500F538 +:1028100080540191606CFFF7DBFC1F280AD920224D +:102820000199606CFFF74AFDA0F12003584258411E +:1028300002B010BD0020FBE708B5302383F31188F8 +:1028400000F58050406CFFF797FC002383F311885C +:1028500008BD0000002202608281426082607047F1 +:102860000022002310B5C0E90023002304460C30E9 +:1028700020F8043CFFF7EEFF204610BD2DE9F0479D +:102880009A4688B0074688469146302383F31188DC +:1028900007F580546846FFF7E3FF606CFFF77EFCA6 +:1028A0001F282ED920226946606CFFF78BFD202857 +:1028B00027D194F8523423B303AD444605AB2E46DA +:1028C000083403CE9E4244F8080C44F8041C3546F4 +:1028D000F5D130682060B388A380DDE90023C9E921 +:1028E0000023BDF80830AAF80030002383F31188D4 +:1028F00053464A464146384608B0BDE8F04700F026 +:10290000B3BD002080F3118808B0BDE8F087000057 +:102910002DE9F84F0023064600F581540546884608 +:102920001034C0E90133274B46F8303B3746384670 +:102930002037FFF795FFA742F9D105F580544FF4F2 +:10294000805305F5A3594FF0000A266300266764FB +:1029500005F5835709F110094FF0000B1037E663B6 +:10296000C4E90D36012384F8403084F84830A7F1DB +:102970001800203747E910ABFFF76CFF47F8286CC9 +:102980004F45F4D1B8F1010F84F85884A4F85A6483 +:10299000A4F85C64A4F85E6484F86064A4F86264DB +:1029A000A4F86464A4F8666484F8686402D90648EC +:1029B00000F044FD054B284653F82830EB62BDE893 +:1029C000F88F00BFA4800008788000089480000879 +:1029D000044B10B5197804464A1C1A70FFF798FF8B +:1029E000204610BDE96300202DE9F04300295AD0AC +:1029F0002E4E2F48B6FBF1F481428CBF0A201120E5 +:102A0000431EB4FBF0F700FB1740DDB220B1022BF0 +:102A10001846F5D8002032E07B1EB3F5806F2ED229 +:102A2000C5EBC5084FF47A7308F103044FEAE40ECE +:102A3000C4F3C7040EF10109281B0EFB033E5FFA25 +:102A400080FC59FA80F0BEFBF0F0B0F5617F18DC35 +:102A500083B2601C5CFA80F07843B6FBF0F08142F0 +:102A6000D8D1611E0F29D5D80CF1FF310729D1D853 +:102A70000120138057801071547182F806C0BDE8A0 +:102A8000F08308F1FF34E010C4F3C70400F1010E35 +:102A90002D1B00FB03335FFA85FC5EFA85F5B3FB63 +:102AA000F5F39BB2D5E70846E9E700BF00B4C404DC +:102AB0003F420F0030B50D4B05200D4D1C786C4387 +:102AC0008C420ED159780120518099785171D97872 +:102AD0009171197911715B7903EB83035B001380AA +:102AE00030BD013803F10603E8D1F9E7E4800008BE +:102AF00040420F0038B540F27772C36A154CC3F8F4 +:102B0000BC200722C36AC3F8C8202268C16A9300A8 +:102B100043F4C023C1F8A03002F1805302F16C01EC +:102B2000C56A03F52C53EA3289009B00226041F00C +:102B3000E061094AC361C5F8C01003F5D87103F517 +:102B40006A7341629342836202D9044800F076FCC2 +:102B500038BD00BFEC630020FCB500405480000885 +:102B60002DE9F04F00F580551F4689B0044695F8D1 +:102B7000583489469046022B04D90026304609B0C5 +:102B8000BDE8F08FA84A52F8231009B942F8230093 +:102B9000A648C4F80C9001782774C9B9302383F390 +:102BA0001188A34BD3F8EC2042F48072C3F8EC20D8 +:102BB000D3F8942042F48072C3F89420D3F8942080 +:102BC00022F48072C3F894200123037081F31188EA +:102BD00095F851347BB9302383F31188954A95F8E1 +:102BE0005834D35C0BB3012B28D0012385F8513422 +:102BF000002383F31188302383F31188E26A9369F9 +:102C000023F01003936100F01FFC8246E36A9E6983 +:102C100016F0080619D000F017FCA0EB0A03FA2BF7 +:102C2000F4D9002686F31188A8E70321132001F0C8 +:102C3000A1FF0321152001F09DFFD6E703211420F9 +:102C400001F098FF03211620F5E79A6942F001028E +:102C50009A6100F0F9FB8246E36A9A69D00706D4CC +:102C600000F0F2FBA0EB0A03FA2BF5D9D9E79A6939 +:102C70004FF0000A42F002029A61E36AC3F854A0DE +:102C80008AF3118804F5825B686CFFF775FA0BF123 +:102C9000100B202200216846FEF7A2FE02A8FFF7D3 +:102CA000D9FD6A460BEB06030DF1180ECDF818A0FE +:102CB00094460833BCE80300F44543F8080C43F895 +:102CC000041C6246F4D1DCF8000020361860B6F52A +:102CD000806F9CF804201A71DBD1002304F5A25206 +:102CE000494620461A3285F8503485F85334FFF7A8 +:102CF0007BFE064690B9E26A936923F00103936173 +:102D000000F0A2FB0546E36A9B69D9077FF535AF62 +:102D100000F09AFB431BFA2BF5D92EE795F85E34A9 +:102D2000C5F86C94591E95F85F34E26A013B1B02AA +:102D300043EA416395F8601401390B43B5F85C141C +:102D4000013943EA0143D361B8F1000F36D004F5ED +:102D5000A352414620460232FFF7ACFE90B9E26A28 +:102D6000936923F00103936100F06EFB0546E36A6B +:102D70009B69DA077FF501AF00F066FB431BFA2B76 +:102D8000F5D9FAE695F86724C5F87084511E95F8D0 +:102D90006824E36A013A120142EA012295F86614B6 +:102DA00001390A43B5F86414013942EA014242F498 +:102DB0000002DA604FF42062E36A9A64E36A4FF03B +:102DC00000082046C3F8BC80FFF794FE85F85984BC +:102DD0006FF04042E36A1A65174AE36A5A654FF09A +:102DE0000222E36A9A654FF0FF32E36AC3F8E020FB +:102DF0000322E36A9742DA653FF4C0AEE26A936960 +:102E000023F00103936100F01FFB0746E36A9B690F +:102E1000DB0705D500F018FBC31BFA2BF6D9ACE68F +:102E2000012385F85234A9E6E0630020E86300201E +:102E3000004402588C800008550200022DE9F04F32 +:102E4000054689B090469946002741F2680A00F588 +:102E50008056EB6AD3F8D830FB40D80751D505EB44 +:102E600047124FEA471B52441379190749D4D6F841 +:102E700084340133C6F8843405F5A553C3E90089C9 +:102E800013799A0605EB0B0248BFD6F8B4345244C6 +:102E900044BF0133C6F8B434137943F00803137107 +:102EA000DB0723D596F8533403B305F582546846FF +:102EB000FFF7D6FC03AB18345C4404F1080C20681F +:102EC000083454F8041C1A46644503C21346F6D16C +:102ED0002068694610602846A2889A800123ADF8D0 +:102EE00008302B68CDE90089DB6B9847D6F8A83409 +:102EF000D6F854040133C6F8A83410B103681B692E +:102F000098470137202FA4D109B0BDE8F08F000009 +:102F10002DE9F04F0F468DB0044600F097FA824637 +:102F20008946002F5BD1E36AD3F8A02012F4FE0F8C +:102F300003D100200DB0BDE8F08FD3F8A42092019A +:102F400041BF04F58051D1F898240132C1F898248A +:102F5000D3F8A4205606ECD0D3F8A450E669C5F304 +:102F600005254823E8464FF0000B03FB0566404665 +:102F7000FFF770FC326851004ABF22F06043C2F391 +:102F80008A4343F00043920048BF43F080430093DC +:102F9000736813F400131BBF012304F580528DF8EE +:102FA0000D308DF80D301EBFD2F8B8340133C2F8A1 +:102FB000B834F38803F00F038DF80C309DF80C0043 +:102FC00000F09EFA5FFA8BF3984225D9F2180CA90B +:102FD0000BF1010B127A0B4403F82C2CEEE7012FB6 +:102FE000A7D1E36AD3F8B02012F4FE0FA1D0D3F832 +:102FF000B420950141BF04F58051D1F898240132E5 +:10300000C1F89824D3F8B420500692D0D3F8B45025 +:10301000266AC5F30525A4E7EFB9E36AC3F8A8500B +:1030200004A807ADFFF71CFC98E80F0007C52B802C +:103030000023204604A9ADF81830236804F5805415 +:10304000DB6BCDE904A9984758B1D4F8903401332B +:10305000C4F890346EE7012FE2D1E36AC3F8B850A8 +:10306000DEE7D4F8943401200133C4F8943461E7E6 +:103070002DE9F04105460F4600F5805401263946FA +:103080002846FFF745FF10B184F85364F7E7D4F8FA +:10309000A834D4F854040133C4F8A83420B1036828 +:1030A000BDE8F0411B691847BDE8F081C36AF0B57F +:1030B0001A6C12F47F0F2BD01B6C00F5805441F278 +:1030C00068054FF0010CC4F8AC340023471900EB3D +:1030D00043125E012A44117911F0020F15D04907FD +:1030E00013D4B959C66A0CFA01F1D6F8CCE011EA4A +:1030F0000E0F0AD0C6F8D410117941F004011171F5 +:10310000D4F88C240132C4F88C240133202BDED176 +:10311000F0BD00002B4B70B51E561B5C012B30D848 +:10312000294D2A4A55F8233052F8264013B349B3A3 +:10313000236D9A0510D54FF40073236500F086F9CE +:1031400050EA01020B4602D0013861F10003024649 +:1031500055F82600FFF772FE236D9B012CD54FF02A +:10316000007255F82630226503F58053012283F85A +:10317000592421E001232365102323654FF4805354 +:10318000236570BD236DDA0702D4236D5B0706D576 +:103190000523002155F826002365FFF769FF236DFD +:1031A000D80602D4236D590606D55023012155F8BF +:1031B00026002365FFF75CFF55F82600BDE8704048 +:1031C000FFF774BF90800008E0630020948000083F +:1031D00008B5302383F31188FFF768FF002383F3DA +:1031E000118808BDC36AD3F8C00010F07C5005D028 +:1031F000D3F8C40080F40010C0F3405070470000C2 +:1032000008B5302383F3118800F58050406CFEF739 +:10321000C5FF002383F3118843090CBF0120002060 +:1032200008BD000000F5805393F8592462B1C16ACB +:103230008A6922F001028A61D3F89C240132C3F822 +:103240009C24002283F85924704700002DE9F7439D +:10325000302181F3118800F58251002541F2680E7A +:103260004FF00108103100F5805C00EB4514744408 +:10327000267977071CD4F6061AD58E69D0F82C90DB +:1032800008FA06F6D9F8CC703E4211D04F68019783 +:103290000F689742019F9F410AD2C9F8D4602679EE +:1032A00046F004062671DCF888440134CCF88844E2 +:1032B00001352031202DD8D1002383F3118803B0AC +:1032C000BDE8F083F8B51E4600230F46054613708F +:1032D0001446FFF795FF80F0010038701EB12846B4 +:1032E000FFF780FF2070F8BD2DE9F04F85B09946BB +:1032F0000D468046164691F800B0DDE90EA3029314 +:103300001378019300F0A2F82B7804460F4613B906 +:103310003378002B41D022463B464046FFF796FFCC +:10332000FFF756FFFFF77EFF4B4632462946FFF771 +:10333000C9FF2B7833B1BBF1000F03D0012005B0DA +:10334000BDE8F08F337813B1019B002BF6D108F55F +:10335000805303935445029B77EB03031DD2039BD9 +:10336000D3F85404C8B10368AAEB04011B6898475A +:103370004B46324629464046FFF7A4FF2B7813B14F +:10338000BBF1000FDAD1337813B1019B002BD5D1FB +:1033900000F05CF804460F46DCE70020CFE70000B1 +:1033A000002108B50846FFF7B5FEBDE8084001F06A +:1033B00071B8000008B501210020FFF7ABFEBDE8A1 +:1033C000084001F067B8000008B500210120FFF7B0 +:1033D000A1FEBDE8084001F05DB80000012108B57C +:1033E0000846FFF797FEBDE8084001F053B800001B +:1033F00000B59BB0EFF3098168226846FEF7CAFA70 +:10340000EFF30583014B9B6BFEE700BF00ED00E08F +:1034100008B5FFF7EDFF000000B59BB0EFF30981A1 +:1034200068226846FEF7B6FAEFF30583014B5B6B43 +:10343000FEE700BF00ED00E0FEE700000FB408B5B6 +:10344000029802F08BFAFEE702F0DCBF02F0BEBF8A +:1034500013B56C46031D84E8060094E8030083E876 +:103460000500012002B010BD73B58568019155B10A +:103470001B885B0707D4D0E900369B6B9847019AFD +:10348000C1B23046A847012002B070BDF0B58668D1 +:1034900089B005460C465EB1BDF838305B070AD4EA +:1034A000D0E900379B6B98472246C1B23846B047F7 +:1034B000012009B0F0BD0022002301F10806CDE98A +:1034C000002300230A46ADF8083003AB1068083229 +:1034D00052F8041C1C46B24203C42346F6D11068BD +:1034E00020609288A280FFF7B1FF0423ADF8083076 +:1034F0002B68CDE90001DB6B694628469847D7E782 +:10350000082817D909280CD00A280CD00B280CD071 +:103510000C280CD00D280CD00E2814BF40203020D1 +:1035200070470C20704710207047142070471820F7 +:1035300070472020704700002DE9F041456A15B919 +:103540004162BDE8F0814B68AC4623F06047C3F3AD +:103550008A464FEAD37EC3F3807816EA230638BF43 +:103560003E462B465A68BEEBD27F22F060440AD01A +:10357000002A18DAA40CB44217D19D420FD10D6075 +:10358000DEE71346EEE7A74207D102F08044C2F31C +:10359000807242450BD054B1EFE708D2EDE7CCF88A +:1035A00000100B60CDE7B44201D0B442E5D81A68F0 +:1035B0009C46002AE5D11960C3E700002DE9F047D9 +:1035C000089D01F0070400EBD1004FF47F494FEA5A +:1035D000D508224405F00705944201D1BDE8F087E3 +:1035E00004F0070705F0070A111B08EBD50E574535 +:1035F0003E4613F80EC038BF5646C6F108068E4246 +:1036000028BF0E46E108415C34443544B94029FAEC +:1036100006F721FA0AF1FFB28CEA010147FA0AF72C +:1036200039408CEA010C03F80EC0D5E780EA01208E +:10363000082341F2210201B2013B4000002980B27F +:10364000B8BF504013F0FF03F5D1704738B50C46B2 +:103650008D18A54200D138BD14F8011BFFF7E6FF15 +:10366000F7E7000042684AB11368818943604389E3 +:1036700001339BB29942438138BF83811046704722 +:1036800070B588B0044620220D4668460021FEF73A +:10369000A7F920460495FFF7E5FF024660B16B46A7 +:1036A000054608AE1C46083503CCB44245F8080C64 +:1036B00045F8041C2346F5D1104608B070BD000043 +:1036C000082817D909280CD00A280CD00B280CD0B0 +:1036D0000C280CD00D280CD00E2814BF4020302010 +:1036E00070470C2070471020704714207047182036 +:1036F0007047202070470000082817D90C280CD9E3 +:1037000010280CD914280CD918280CD920280CD929 +:1037100030288CBF0F200E207047092070470A20E8 +:1037200070470B2070470C2070470D207047000039 +:103730002DE9F843078C0446072F1ED900254FF6C4 +:10374000FF73D0E90298C5F12006A5F1200029FAFF +:1037500005F1083508FA06F628FA00F0314301436E +:103760001846C9B2FFF762FF402D0346EBD13A4637 +:10377000E169BDE8F843FFF769BF4FF6FF70BDE8A8 +:10378000F883000010B54B6823B9CA8A63F30902B5 +:10379000CA8210BD04691A681C600361C38A013BB8 +:1037A000C3824A60EFE700002DE9F84F1D46CB8A3F +:1037B0000F468146C3F30901924605290B4630D0D6 +:1037C0000020AAB207F11A049EB21FFA80F8042E54 +:1037D0000FD8904503F1010306D30A44FB8A62F334 +:1037E00009030120FB821AE01AF800600130E65458 +:1037F000EAE79045F1D2A1F1050B1C237C68BBFBE5 +:10380000F3F203FB12BB1FFA8BF6002C45D148469E +:10381000FFF728FF044638B978606FF00200BDE872 +:10382000F88F4FF00008E6E7002606607860ADB23A +:103830004FF0000B454510D90AEB0803221D13F881 +:10384000011B08F101089155B1B21FFA88F81B2934 +:103850002BD0454506F10106F1D8FB8AC3F30902D6 +:10386000154465F30903BCE701321C4692B2236894 +:10387000002BF9D16B1F0B441C21B3FBF1F3013377 +:103880009BB29A42D3D2BBF1000FD0D14846FFF78A +:10389000E9FE20B9C4F800B0BFE70122E7E7C0F8AD +:1038A00000B05E4620600446C1E74545D5D948468C +:1038B000FFF7D8FE08B92060AFE7C0F800B00026D7 +:1038C00020600446B6E700002DE9F04F1C4607468D +:1038D00088462DED028B83B05B690192002B00F0CE +:1038E0009A80238C2BB1E269002A00F09480072B88 +:1038F00035D807F10C00FFF7B5FE054638B96FF073 +:103900000205284603B0BDEC028BBDE8F08F1422FF +:103910000021FEF765F8228CE16905F10800FEF749 +:1039200039F8208C48F00041013080B2FFF7E4FE06 +:10393000FFF7C6FE013880B2208401302874384673 +:103940006369228C1B782A4403F01F0363F03F0352 +:10395000137269602946FFF7EFFD0125D1E74FF0AB +:10396000000900F10C034FF0800A4E464D4608EE68 +:10397000103A18EE100AFFF775FE83460028BED0F5 +:1039800014220021FEF72CF8002E3AD1019B0222CE +:10399000ABF808300BF1080E1FFA82FC218C0CF1F9 +:1039A0000100BCF1060F80B201D88E422BD3FFF785 +:1039B000A3FE8E4208BF4FF0400AFFF781FE626906 +:1039C0000138013512781BFA80F1013002F01F0234 +:1039D0002DB242EA491289F001094AEA020A48F086 +:1039E000004281F808A059468BF810003846CBF801 +:1039F00004204FF0000AFFF79FFD238CB342B8D19B +:103A00007FE70022C6E7E169895D01360EF8021002 +:103A1000B6B20132C0E76FF0010572E7F8B515469E +:103A20000E463022002104461F46FDF7D9FF069BB3 +:103A3000B5F5001FA760636004F11000079B34BF59 +:103A40006A094FF6FF72E661A362002397B29A42B9 +:103A500006D800230360A782E3822383E360F8BDD6 +:103A60000660013330462036F1E7000003781BB9C9 +:103A70004BB2002BC8BF0170704700000078704740 +:103A8000F8B50C46C969074611B9238C002B37D10C +:103A9000257E1F2D34D8387828BB228C072A2CD8B5 +:103AA000268A36F003032BD14FF6FF70FFF7CEFDC9 +:103AB00020F0010031024FF6FF72400441EA056137 +:103AC000400C41EA4025234629463846FFF7FCFED4 +:103AD000002807DD626913780133DBB21F2B88BF32 +:103AE00000231370F8BD218A2D0645EA0125054300 +:103AF0002046FFF71DFE0246E5E76FF00300F1E701 +:103B00006FF00100EEE7000070B58AB0044616467B +:103B10000021282268461D46FDF762FFBDF83830B7 +:103B200069462046ADF810300F9B05939DF8403054 +:103B30008DF81830119B0793BDF84830CDE9026528 +:103B4000ADF82030FFF79CFF0AB070BD2DE9F041C1 +:103B5000D36905460C4616460BB9138C5BBB377E02 +:103B60001F2F28D895F80080B8F1000F26D03046D6 +:103B7000FFF7DEFD337821020246284641EAC331D1 +:103B8000338A41EA080141EA076141EA03413346C9 +:103B900041F08001FFF798FE00280ADD3378012B01 +:103BA00007D1726913780133DBB21F2B88BF002362 +:103BB0001370BDE8F0816FF00100FAE76FF00300C9 +:103BC000F7E70000F0B58BB004460D46174600211C +:103BD000282268461E46FDF703FF9DF84C30294613 +:103BE00020465A1E534253416A468DF800309DF8D4 +:103BF0004030ADF81030119B05939DF848308DF89A +:103C00001830149B0793BDF85430CDE90276ADF817 +:103C10002030FFF79BFF0BB0F0BD0000406A00B101 +:103C200004307047436A1A68426202691A6003618D +:103C3000C38A013BC38270472DE9F041D0F8208050 +:103C400014461D46184E4146002709B9BDE8F081CB +:103C5000D1E90223A21A65EB0303964277EB030333 +:103C60001ED2036A8B420DD1FFF78CFD036A1B68DD +:103C7000036203690B60C38A0161013B016AC3826D +:103C80008846E2E7FFF77EFD0B68C8F8003003695D +:103C90000B60C38A0161013BC382D8F80010D4E7EE +:103CA00088460968D1E700BF80841E002DE9F04FE7 +:103CB0008BB00D4614469B46DDF850908046002898 +:103CC00000F01881B9F1000F00F01481531E3F2B52 +:103CD00000F21081012A03D1BBF1000F40F00A81EC +:103CE0000023CDE90833B8F81430B5EBC30F4FEA21 +:103CF000C30703D300200BB0BDE8F08F2B199F4200 +:103D0000D8F80C3036BF7F1B2746FFB21BB9D8F856 +:103D10001030002B7AD0272D4DD8C5F1280600236E +:103D20002946B742009308ABD8F808002CBFF6B27A +:103D30003E46A7EB060A354432465FFA8AFAFFF799 +:103D40003DFCB8F81430282103F10053053BDB009B +:103D50000493D8F80C300393039B13B1BAF1000F0E +:103D60002CD1D8F8100040B1BAF1000F05D008AB43 +:103D70005246691A0096FFF721FC38B2002FB9D0DD +:103D800066070AD00AAB624203EBD40102F00702D5 +:103D900011F8083C134101F8083C082C3DD9102CBF +:103DA00040F2B580202C40F2B780BBF1000F00F04C +:103DB0009C80082335E0BA460026C2E7049BE02B2E +:103DC00028BFE02306930B44AB42059315D95A1B39 +:103DD0000398691A0096924508AB00F1040034BFBD +:103DE0005246D2B20792FFF7E9FB079A1644AAEBB4 +:103DF000020A1544F6B25FFA8AFA049B069A0599FC +:103E00009B1A0493039B1B680393A5E700933A4610 +:103E100008AB2946D8F80800ADE7BBF1000F13D076 +:103E20000123B4EBC30F6BD0082C12D89DF82030BF +:103E3000621E23FA02F2D50706D54FF0FF3202FACE +:103E400004F423438DF820309DF8203089F80030A9 +:103E500051E7102C12D8BDF82030621E23FA02F26E +:103E6000D10706D54FF0FF3202FA04F42343ADF830 +:103E70002030BDF82030A9F800303CE7202C0FD8C6 +:103E80000899631E21FA03F3DA0705D54FF0FF32D4 +:103E900002FA04F40C430894089BC9F800302AE79E +:103EA000402C2AD0611EC4F12102A4F12103DDE9D6 +:103EB000086526FA01F105FA02F225FA03F3114327 +:103EC0001943CB0711D50122A4F12003C4F120012D +:103ED00002FA03F322FA01F1A2400B43524263EBD0 +:103EE000430332432B43CDE90823DDE90823C9E925 +:103EF000002300E76FF00100FDE66FF00800FAE62E +:103F0000082CA1D9102CB4D9202CEED8C4E7BBF1D1 +:103F1000000FAED0022384E7BBF1000FBCD0042316 +:103F20007FE70000012A30B5144638BF012485B070 +:103F30000025402C28BF4024012ACDE9025518D87D +:103F40001B788DF8083063070AD004AB624203EB9C +:103F5000D40502F0070215F8083C934005F8083C28 +:103F6000034600912246002102A8FFF727FB05B077 +:103F700030BD082AE4D9102A03D81B88ADF80830D0 +:103F8000E1E7202A95BF1B68D3E900230293CDE91E +:103F90000223D8E710B5CB681BB98B600B618B820D +:103FA00010BD04691A681C600361C38A013BC382A7 +:103FB000CA60F0E703064CBFC0F3C0300220704770 +:103FC00008B50246FFF7F6FF022806D15306C2F3F2 +:103FD0000F2001D100F0030008BDC2F30740FBE74A +:103FE0002DE9F04F93B004460D46CDE903230A684E +:103FF0001046FFF7DFFF0228824614BFC2F30626F1 +:104000000026002A80F2F88112F0C04940F0F481C5 +:10401000097B002900F0F081022803D02378B34205 +:1040200040F0ED81C2F3046310462944069302F088 +:104030007F030593FFF7C4FF059B002283464FEAE9 +:104040008348002348EA0A4848EA4668CE78CDE922 +:104050000823F30948EA0008029368D0059B02464A +:1040600008A92046009353466768B847002800F027 +:10407000C981276A4FB9414604F10C00FFF700FBE4 +:10408000074690B96FF0020055E03B6998450DD0A6 +:104090003F68002FF9D1414604F10C00FFF7F0FA18 +:1040A00007460028EED0236A3B60276297F817C0C6 +:1040B00006F01F08CCF3840CACEB0800A8EB0C0353 +:1040C0001FFA80FE0028B8BF0EF120001FFA83FE01 +:1040D000B8BF00B2002B0793B8BF0EF12003D7E999 +:1040E0000221BCBF1BB2079352EA010338D0039BE5 +:1040F0004FF0000CDFF81CE39A1A049B63EB0101FC +:1041000096457CEB01032BD36B7B97F81AE0734544 +:1041100019D1029B002B78D0012821DC7868F8B9EE +:10412000DFF8ECC2944570EB010316D337E0276A41 +:1041300027B96FF00C0013B0BDE8F08F3B699845CC +:10414000B4D03F68F4E7B24890427CEB010301D35E +:104150000020F0E7029B002BFAD0079B0F2B17DC07 +:10416000FA7DB3003946204602F0030203F07C03D7 +:104170001343FB75FFF706FB6B7BBB76029B3BB9DA +:10418000FB7DC3F38402013262F38603FB75D0E743 +:104190006A7BBB7E9A42DBD1029B002B35D0B309F0 +:1041A000022B32D0039B142200210DA8BB60049B7C +:1041B000FB60FDF715FC039B0AA920460A93049BAC +:1041C000ADF83EB00B932B1D8DF840A00C932B7BCC +:1041D0008DF84180013BDBB2ADF83C30069B8DF899 +:1041E0004230059B8DF8433094F82C3083F0010366 +:1041F0008DF84430A3689847FB7DC3F384030133F3 +:1042000003F01F039B02FB82A2E7FB7DC6F3401273 +:10421000B2EBD31F40F0F980C3F38403434540F071 +:10422000FB80029AB6092B7B002A52D016F00106B9 +:1042300061D1032B40F2F380039B394604F10C005B +:10424000BB60049BFB60FB8A66F30903AE1DFB8227 +:1042500032462B7B033BDBB2FFF7A6FA00280CDAD1 +:1042600039462046FFF78EFAFB7DC3F38403013302 +:1042700003F01F039B02FB8204E7AB88DDE908849F +:104280003B834FF6FF73C9F12000A9F1200228FA01 +:1042900009F109F1080904FA00F024FA02F20143D5 +:1042A00018461143C9B2FFF7C1F9B9F1400F0346EF +:1042B000E9D1B88231462A7B033AD2B2FFF7C6F978 +:1042C000FB7DB882DA43C2F3C01262F3C713FB75F9 +:1042D0003EE786B92E1D013B394604F10C00DBB2E6 +:1042E0003246FFF761FA0028BADB2A7B3146B88AEA +:1042F000013AD2B2E2E7F98A013BC1F30901DAB22D +:1043000004295BD8281D002307F11B069A4208D90F +:1043100010F801CB013306F801C00131DBB20529E9 +:10432000F4D1039993420A9138BF043304992CBF06 +:10433000002355FA83F30B9107F11B010C91796867 +:104340000E930D91291DFB8AADF83EB0C3F309030E +:104350008DF840A08DF841801A44069B8DF84230BC +:10436000059BADF83C208DF8433094F82C3083F059 +:1043700001038DF844300023B88A7B602A7B013A20 +:10438000FFF764F93B8BB882834203D1A3680AA983 +:104390002046984720460AA9FFF7FCFDFB7DBA8A14 +:1043A000C3F38403013303F01F039B02FB823B8BA7 +:1043B0009A420CBF00206FF01000BCE67B68002B17 +:1043C000AFD0052001E01C3033461E68002EFAD124 +:1043D000091A2E1D081D184401EB090C5FFA89F318 +:1043E000BCF11B0F9DD89A429BD916F8013B09F1ED +:1043F000010900F8013BEFE76FF009009BE66FF061 +:104400000A0098E66FF00B0095E66FF00D0092E65B +:1044100040420F0080841E006FF00E008BE66FF0AC +:104420000F0088E6EFF30983054968334A6B22F0F1 +:1044300001024A6383F30988002383F311887047DC +:1044400000EF00E0302080F3118862B60D4B0E4A79 +:10445000D96821F4E0610904090C0A430B49DA60C8 +:10446000D3F8FC2042F08072C3F8FC20084AC2F85E +:10447000B01F116841F0010111602022DA7783F842 +:104480002200704700ED00E00003FA0555CEACC5F0 +:10449000001000E0302310B583F311880E4B5B68E9 +:1044A00013F4006314D0F1EE103AEFF309844FF0E7 +:1044B0008073683CE361094BDB6B236684F30988F6 +:1044C00001F012FA10B1064BA36110BD054BFBE7DA +:1044D00083F31188F9E700BF00ED00E000EF00E092 +:1044E0003F0400084204000808B5074B074A196852 +:1044F00001F03D01996053680BB190689847BDE8A1 +:104500000840FFF7C7BF00BF00000240F46300206F +:1045100008B5084B1968890901F03D018A019A60C4 +:10452000054AD3680BB110699847BDE80840FFF70A +:10453000B1BF00BF00000240F463002008B5084B83 +:104540001968090C01F03D010A049A60054A536993 +:104550000BB190699847BDE80840FFF79BBF00BFCB +:1045600000000240F463002008B5084B1968890D6B +:1045700001F03D018A059A60054AD3690BB1106AC2 +:104580009847BDE80840FFF785BF00BF0000024024 +:10459000F463002008B5074B074A596801F03D0154 +:1045A000D960536A0BB1906A9847BDE80840FFF79D +:1045B00071BF00BF00000240F463002008B5084B43 +:1045C0005968890901F03D018A01DA60054AD36A18 +:1045D0000BB1106B9847BDE80840FFF75BBF00BF09 +:1045E00000000240F463002008B5084B5968090C2C +:1045F00001F03D010A04DA60054A536B0BB1906B80 +:104600009847BDE80840FFF745BF00BF00000240E3 +:10461000F463002008B5084B5968890D01F03D018D +:104620008A05DA60054AD36B0BB1106C9847BDE878 +:104630000840FFF72FBF00BF00000240F4630020D6 +:1046400008B5074B074A196801F03D019960536CA2 +:104650000BB1906C9847BDE80840FFF71BBF00BF47 +:1046600000040240F463002008B5084B196889096A +:1046700001F03D018A019A60054AD36C0BB1106DBF +:104680009847BDE80840FFF705BF00BF000402409F +:10469000F463002008B5084B1968090C01F03D01CE +:1046A0000A049A60054A536D0BB1906D9847BDE8B6 +:1046B0000840FFF7EFBE00BF00040240F463002093 +:1046C00008B5084B1968890D01F03D018A059A600B +:1046D000054AD36D0BB1106E9847BDE80840FFF74F +:1046E000D9BE00BF00040240F463002008B5074BA8 +:1046F000074A596801F03D01D960536E0BB1906EC5 +:104700009847BDE80840FFF7C5BE00BF000402405F +:10471000F463002008B5084B5968890901F03D0190 +:104720008A01DA60054AD36E0BB1106F9847BDE875 +:104730000840FFF7AFBE00BF00040240F463002052 +:1047400008B5084B5968090C01F03D010A04DA600C +:10475000054A536F0BB1906F9847BDE80840FFF7CB +:1047600099BE00BF00040240F463002008B5084B66 +:104770005968890D01F03D018A05DA60054AD36F59 +:1047800013B1D2F880009847BDE80840FFF782BE19 +:1047900000040240F463002000230C4910B51A46BF +:1047A0000B4C0B6054F82300026001EB4300043310 +:1047B0004260402BF6D1074A4FF0FF339360D3603D +:1047C000C2F80834C2F80C3410BD00BFF4630020F6 +:1047D00004810008000002400F28F8B510D9102805 +:1047E00010D0112811D0122808D10F240720DFF88B +:1047F000C8E00126DEF80050A04208D9002653E0A8 +:104800000446F4E70F240020F1E70724FBE706FA4B +:1048100000F73D424AD1264C4FEA001C3D4304EBD1 +:1048200000160EEBC000CEF80050C0E90123FBB229 +:1048300073B12048D0F8D83043F00103C0F8D83025 +:10484000D0F8003143F00103C0F80031D0F8003156 +:1048500017F47F4F0ED01748D0F8D83043F002033A +:10486000C0F8D830D0F8003143F00203C0F800316E +:10487000D0F8003154F80C00036823F01F030360E4 +:10488000056815F00105FBD104EB0C033D2493F8FA +:104890000CC05F6804FA0CF43C602124056044619C +:1048A00012B1987B00F066F93046F8BD0130A3E7FD +:1048B0000481000800440258F463002010B530243D +:1048C00084F31188FFF788FF002383F3118810BD5C +:1048D00010B50446807B00F063F901231549627B23 +:1048E00003FA02F20B6823EA0203DAB20B6072B930 +:1048F000114AD2F8D81021F00101C2F8D810D2F82C +:10490000001121F00101C2F80011D2F8002113F4C6 +:104910007F4F0ED1084BD3F8D82022F00202C3F803 +:10492000D820D3F8002122F00202C3F80021D3F8E6 +:10493000003110BDF46300200044025808B5302354 +:1049400083F31188FFF7C4FF002383F3118808BDA8 +:10495000026843681143016003B1184770470000C3 +:10496000024A136843F0C0031360704700780040A8 +:1049700013B50E4C204600F0BDFA04F114000023DC +:104980004FF400720A49009400F07AF9094B4FF491 +:104990000072094904F13800009400F0F3F9074A65 +:1049A000074BC4E9172302B010BD00BF7864002094 +:1049B000E464002061490008E466002000780040BB +:1049C00000E1F505037C30B5244C002918BF0C46E6 +:1049D000012B11D1224B98420ED1224BD3F8E82063 +:1049E00042F08042C3F8E820D3F8102142F0804220 +:1049F000C3F81021D3F810312268036EC16D03EBA8 +:104A000052038466B3FBF2F36268150442BF23F0DD +:104A1000070503F0070343EA4503CB60A36843F0AF +:104A200040034B60E36843F001038B6042F49673EC +:104A300043F001030B604FF0FF330B62510505D5C6 +:104A400012F0102205D0B2F1805F04D080F86430FB +:104A500030BD7F23FAE73F23F8E700BF0482000858 +:104A600078640020004402582DE9F047C66D0546E1 +:104A70003768F469210734621AD014F0080118BFAE +:104A80004FF48071E20748BF41F02001A3074FF0C7 +:104A9000300348BF41F04001600748BF41F080014A +:104AA00083F31188281DFFF753FF002383F3118838 +:104AB000E2050AD5302383F311884FF48061281D65 +:104AC000FFF746FF002383F311884FF030094FF0C2 +:104AD000000A14F0200838D13B0616D54FF03009F3 +:104AE00005F1380A200610D589F31188504600F0E8 +:104AF0007DF9002836DA0821281DFFF729FF27F065 +:104B000080033360002383F31188790614D562068D +:104B100012D5302383F31188D5E913239A4208D1A3 +:104B20002B6C33B127F040071021281DFFF710FF31 +:104B30003760002383F31188E30618D5AA6E136942 +:104B4000ABB15069BDE8F047184789F31188736A23 +:104B5000284695F86410194000F0E6F98AF31188A8 +:104B6000F469B6E7B06288F31188F469BAE7BDE882 +:104B7000F0870000090100F16043012203F5614361 +:104B8000C9B283F8001300F01F039A4043099B0049 +:104B900003F1604303F56143C3F880211A60704755 +:104BA00000F01F0301229A40430900F160409B007E +:104BB00000F5614003F1604303F56143C3F88020D1 +:104BC000C3F88021002380F800337047F8B51546FC +:104BD000826804460B46AA4200D28568A16926690C +:104BE000761AB5420BD218462A46FCF7D3FEA369C3 +:104BF0002B44A3612846A3685B1BA360F8BD0CD9B6 +:104C0000AF1B18463246FCF7C5FE3A46E168304411 +:104C1000FCF7C0FEE3683B44EBE718462A46FCF786 +:104C2000B9FEE368E5E7000083689342F7B5044600 +:104C3000154600D28568D4E90460361AB5420BD215 +:104C40002A46FCF7A7FE63692B4463612846A368E4 +:104C50005B1BA36003B0F0BD0DD93246AF1B0191C1 +:104C6000FCF798FE01993A46E0683144FCF792FE61 +:104C7000E3683B44E9E72A46FCF78CFEE368E4E797 +:104C800010B50A440024C361029B8460C1600261C4 +:104C90000362C0E90000C0E9051110BD08B5D0E904 +:104CA0000532934201D1826882B982680132826002 +:104CB0005A1C426119700021D0E904329A4224BF83 +:104CC000C368436100F0C0FE002008BD4FF0FF3014 +:104CD000FBE7000070B5302304460E4683F31188CD +:104CE000A568A5B1A368A269013BA360531CA36199 +:104CF00015782269934224BFE368A361E3690BB18D +:104D000020469847002383F31188284607E0314660 +:104D1000204600F089FE0028E2DA85F3118870BD94 +:104D20002DE9F74F04460E4617469846D0F81C90DA +:104D30004FF0300A8AF311884FF0000B154665B129 +:104D40002A4631462046FFF741FF034660B94146F7 +:104D5000204600F069FE0028F1D0002383F311887B +:104D6000781B03B0BDE8F08FB9F1000F03D00190BC +:104D70002046C847019B8BF31188ED1A1E448AF325 +:104D80001188DCE7C160C361009B82600362C0E9F7 +:104D900005111144C0E9000001617047F8B50446EF +:104DA0000D461646302383F31188A768A7B1A36880 +:104DB000013BA36063695A1C62611D70D4E904322F +:104DC0009A4224BFE3686361E3690BB120469847C8 +:104DD000002080F3118807E03146204600F024FED1 +:104DE0000028E2DA87F31188F8BD0000D0E9052336 +:104DF00010B59A4201D182687AB9826800210132E5 +:104E000082605A1C82611C7803699A4224BFC3687D +:104E1000836100F019FE204610BD4FF0FF30FBE724 +:104E20002DE9F74F04460E4617469846D0F81C90D9 +:104E30004FF0300A8AF311884FF0000B154665B128 +:104E40002A4631462046FFF7EFFE034660B9414649 +:104E5000204600F0E9FD0028F1D0002383F31188FB +:104E6000781B03B0BDE8F08FB9F1000F03D00190BB +:104E70002046C847019B8BF31188ED1A1E448AF324 +:104E80001188DCE7026843681143016003B11847E9 +:104E9000704700001430FFF743BF00004FF0FF33AE +:104EA0001430FFF73DBF00003830FFF7B9BF0000F6 +:104EB0004FF0FF333830FFF7B3BF00001430FFF777 +:104EC00009BF00004FF0FF311430FFF703BF0000AF +:104ED0003830FFF763BF00004FF0FF323830FFF784 +:104EE0005DBF0000012914BF6FF013000020704760 +:104EF000FFF73EBD044B036000234360C0E902336B +:104F000001230374704700BF1C82000810B53023D2 +:104F1000044683F31188FFF755FD02230020237414 +:104F200080F3118810BD000038B5C36904460D46F2 +:104F30001BB904210844FFF7A5FF294604F114001A +:104F4000FFF7ACFE002806DA201D4FF40061BDE833 +:104F50003840FFF797BF38BD0268436811430160CE +:104F600003B118477047000013B5406B00F580543B +:104F7000D4F8A4381A681178042914D1017C0229C4 +:104F800011D11979012312898B4013420BD101A948 +:104F90004C3002F0D7F9D4F8A4480246019B21799D +:104FA000206800F0DFF902B010BD0000143002F0FC +:104FB00059B900004FF0FF33143002F053B900002C +:104FC0004C3002F02BBA00004FF0FF334C3002F0AF +:104FD00025BA0000143002F027B900004FF0FF316D +:104FE000143002F021B900004C3002F0F7B9000093 +:104FF0004FF0FF324C3002F0F1B900000020704752 +:1050000010B500F58054D4F8A4381A681178042932 +:1050100017D1017C022914D15979012352898B407F +:1050200013420ED1143002F0B9F8024648B1D4F858 +:10503000A4484FF4407361792068BDE8104000F047 +:105040007FB910BD406BFFF7DBBF00007047000069 +:105050007FB5124B01250426044603600023057426 +:1050600000F1840243602946C0E902330C4B0290F0 +:10507000143001934FF44073009602F06BF8094B23 +:1050800004F69442294604F14C000294CDE90063F1 +:105090004FF4407302F032F904B070BD448200084E +:1050A00045500008694F00080A68302383F31188CF +:1050B0000B790B3342F823004B79133342F823006A +:1050C0008B7913B10B3342F8230000F58053C3F8FA +:1050D000A41802230374002080F311887047000095 +:1050E00038B5037F044613B190F85430ABB90125AD +:1050F000201D0221FFF730FF04F114006FF00101C1 +:10510000257700F0ADFC04F14C0084F854506FF0AA +:105110000101BDE8384000F0A3BC38BD10B5012145 +:1051200004460430FFF718FF0023237784F8543037 +:1051300010BD000038B504460025143002F022F8F6 +:1051400004F14C00257702F0F1F8201D84F854504A +:105150000121FFF701FF2046BDE83840FFF750BFAF +:1051600090F8803003F06003202B06D190F8812066 +:105170000023212A03D81F2A06D800207047222A9C +:10518000FBD1C0E91D3303E0034A4267072282676F +:10519000C3670120704700BF3C23002037B500F5EE +:1051A0008055D5F8A4381A68117804291AD1017CE1 +:1051B000022917D11979012312898B40134211D189 +:1051C00000F14C04204602F071F958B101A92046C3 +:1051D00002F0B8F8D5F8A4480246019B217920686E +:1051E00000F0C0F803B030BD01F10B03F0B550F88A +:1051F000236085B004460D46FEB1302383F3118849 +:1052000004EB8507301D0821FFF7A6FEFB6806F1B9 +:105210004C005B691B681BB1019002F0A1F801987A +:1052200003A902F08FF8024648B1039B29462046A5 +:1052300000F098F8002383F3118805B0F0BDFB68F7 +:105240005A691268002AF5D01B8A013B1340F1D13C +:1052500004F18002EAE70000133138B550F821402C +:10526000ECB1302383F3118804F58053D3F8A428DC +:105270001368527903EB8203DB689B695D6845B173 +:1052800004216018FFF768FE294604F1140001F0BC +:105290008FFF2046FFF7B4FE002383F3118838BD4B +:1052A0007047000001F05CBA01234022002110B5D4 +:1052B000044600F8303BFCF793FB0023C4E90133BC +:1052C00010BD000010B53023044683F3118824225A +:1052D000416000210C30FCF783FB204601F062FAAC +:1052E00002230020237080F3118810BD70B500EBFD +:1052F0008103054650690E461446DA6018B1102243 +:105300000021FCF76DFBA06918B110220021FCF709 +:1053100067FB31462846BDE8704001F049BB0000FC +:1053200083682022002103F0011310B50446836036 +:105330001030FCF755FB2046BDE8104001F0C4BB1F +:10534000F0B4012500EB810447898D40E4683D43BA +:10535000A469458123600023A2606360F0BC01F072 +:10536000E1BB0000F0B4012500EB810407898D400A +:10537000E4683D436469058123600023A2606360A3 +:10538000F0BC01F057BC000070B5022300250446B4 +:10539000242203702946C0F888500C3040F8045C81 +:1053A000FCF71EFB204684F8705001F095FA636804 +:1053B0001B6823B129462046BDE87040184770BDE0 +:1053C0000378052B10B504460AD080F88C300523ED +:1053D000037043681B680BB1042198470023A36046 +:1053E00010BD00000178052906D190F88C20436893 +:1053F00002701B6803B118477047000070B590F841 +:105400007030044613B1002380F8703004F180023C +:10541000204601F07DFB63689B68B3B994F8803047 +:1054200013F0600535D00021204601F06FFE002109 +:10543000204601F05FFE63681B6813B10621204619 +:105440009847062384F8703070BD2046984700289E +:10545000E4D0B4F88630A26F9A4288BFA36794F96B +:105460008030A56F002B4FF0300380F20381002DB8 +:1054700000F0F280092284F8702083F31188002163 +:105480002046D4E91D23FFF76DFF002383F3118825 +:10549000DAE794F8812003F07F0343EA022340F225 +:1054A0000232934200F0C58021D8B3F5807F48D006 +:1054B0000DD8012B3FD0022B00F09380002BB2D1EE +:1054C00004F1880262670222A267E367C1E7B3F5CD +:1054D000817F00F09B80B3F5407FA4D194F88230A7 +:1054E000012BA0D1B4F8883043F0020332E0B3F5C9 +:1054F000006F4DD017D8B3F5A06F31D0A3F5C063BE +:10550000012B90D86368204694F882205E6894F856 +:105510008310B4F88430B047002884D043686367B0 +:105520000368A3671AE0B3F5106F36D040F6024265 +:1055300093427FF478AF5C4B63670223A367002339 +:10554000C3E794F88230012B7FF46DAFB4F8883054 +:1055500023F00203A4F88830C4E91D55E56778E715 +:10556000B4F88030B3F5A06F0ED194F882302046A5 +:1055700084F88A3001F00EFA63681B6813B10121C8 +:1055800020469847032323700023C4E91D339CE77A +:1055900004F18B0363670123C3E72378042B10D145 +:1055A000302383F311882046FFF7BAFE85F3118874 +:1055B0000321636884F88B5021701B680BB120466F +:1055C000984794F88230002BDED084F88B30042387 +:1055D000237063681B68002BD6D0022120469847B1 +:1055E000D2E794F8843020461D0603F00F010AD557 +:1055F00001F080FA012804D002287FF414AF2B4B6D +:105600009AE72B4B98E701F067FAF3E794F88230BA +:10561000002B7FF408AF94F8843013F00F01B3D05F +:105620001A06204602D501F089FDADE701F07AFDAA +:10563000AAE794F88230002B7FF4F5AE94F884301A +:1056400013F00F01A0D01B06204602D501F05EFD2D +:105650009AE701F04FFD97E7142284F8702083F356 +:1056600011882B462A4629462046FFF769FE85F316 +:105670001188E9E65DB1152284F8702083F3118862 +:1056800000212046D4E91D23FFF75AFEFDE60B2238 +:1056900084F8702083F311882B462A462946204639 +:1056A000FFF760FEE3E700BF748200086C82000829 +:1056B0007082000838B590F870300446002B3ED058 +:1056C000063BDAB20F2A34D80F2B32D8DFE803F0CA +:1056D00037313108223231313131313131313737DF +:1056E000856FB0F886309D4214D2C3681B8AB5FB23 +:1056F000F3F203FB12556DB9302383F311882B4667 +:105700002A462946FFF72EFE85F311880A2384F8DE +:1057100070300EE0142384F87030302383F3118846 +:10572000002320461A461946FFF70AFE002383F39A +:10573000118838BDC36F03B198470023E7E7002104 +:10574000204601F0E3FC0021204601F0D3FC636811 +:105750001B6813B10621204698470623D7E70000AF +:1057600010B590F870300446142B29D017D8062BAA +:1057700005D001D81BB110BD093B022BFBD800217D +:10578000204601F0C3FC0021204601F0B3FC636811 +:105790001B6813B1062120469847062319E0152BF4 +:1057A000E9D10B2380F87030302383F31188002374 +:1057B0001A461946FFF7D6FD002383F31188DAE76E +:1057C000C3689B695B68002BD5D1C36F03B1984751 +:1057D000002384F87030CEE70023826803750369E4 +:1057E0001B6899689142FBD25A680360426010605E +:1057F0005860704700238268037503691B689968C5 +:105800009142FBD85A68036042601060586070474C +:1058100008B50846302383F311880A7D0023052A42 +:1058200006D8DFE802F00B050503120E826913604B +:105830004FF0FF338361FFF7CFFF002383F311881D +:1058400008BD8269936801339360D0E90032136028 +:105850005A60EDE7FFF7C0BF054BD96808751868B7 +:10586000026853601A600122D8600275FAF7D2BD4F +:10587000E86800200C4B30B5DD684B1C87B004464F +:105880000FD02B46094A684600F07EF92046FFF704 +:10589000E3FF009B13B1684600F080F9A86907B0E8 +:1058A00030BDFFF7D9FFF9E7E8680020115800087C +:1058B00038B50C4D04468161EB6881689A68914265 +:1058C00003D8BDE83840FFF787BF1846FFF792FFBF +:1058D00001230146EC6020462375BDE83840FAF705 +:1058E00099BD00BFE8680020044B1A68DB68906827 +:1058F0009B68984294BF002001207047E868002010 +:10590000084B10B51C68D868226853601A600122E1 +:10591000DC602275FFF76EFF01462046BDE81040AF +:10592000FAF778BDE868002038B50123084C002557 +:105930002370656001F0F6FD01F01CFE0549064884 +:1059400001F0F0FE0223237085F3118838BD00BFFB +:10595000506B00207C820008E868002008B572B611 +:10596000044B186500F024FD00F0E6FD024B032215 +:105970001A70FEE7E8680020506B002000F044B980 +:10598000034A516853685B1A9842FBD8704700BFBE +:10599000001000E08B600223086108468B8270478C +:1059A0008368A3F1840243F8142C026943F8442C61 +:1059B000426943F8402C094A43F8242CC268A3F1F9 +:1059C000200043F8182C022203F80C2C002203F8C4 +:1059D0000B2C034A43F8102C704700BF2D0400081D +:1059E000E868002008B5FFF7DBFFBDE80840FFF7D7 +:1059F00031BF0000024BDB6898610F20FFF72CBF1E +:105A0000E8680020302383F31188FFF7F3BF00001C +:105A100008B50146302383F311880820FFF72AFFD9 +:105A2000002383F3118808BD064BDB6839B1426857 +:105A300018605A60136043600420FFF71BBF4FF0EB +:105A4000FF307047E86800200368984206D01A6863 +:105A50000260506018469961FFF7FCBE7047000075 +:105A600038B504460D462068844200D138BD03682D +:105A700023605C608561FFF7EDFEF4E7036810B515 +:105A80009C68A2420CD85C688A600B604C60216004 +:105A9000596099688A1A9A604FF0FF33836010BD8D +:105AA000121B1B68ECE700000A2938BF0A2170B5F9 +:105AB00004460D460A26601901F02EFD01F016FD80 +:105AC000041BA54203D8751C04462E46F3E70A2E94 +:105AD00004D90120BDE8704001F064BE70BD000033 +:105AE000F8B5144B0D460A2A4FF00A07D96103F1A5 +:105AF0001001826038BF0A224160196914460160B2 +:105B000048601861A81801F0F7FC01F0EFFC431B96 +:105B10000646A34206D37C1C28192746354601F0C9 +:105B2000FBFCF2E70A2F04D90120BDE8F84001F0A0 +:105B300039BEF8BDE8680020F8B506460D4601F00C +:105B4000D5FC0F4A134653F8107F9F4206D12A46D0 +:105B500001463046BDE8F840FFF7C2BFD169BB68D7 +:105B6000441A2C1928BF2C46A34202D92946FFF714 +:105B70009BFF224631460348BDE8F840FFF77EBF51 +:105B8000E8680020F8680020C0E90323002310B46F +:105B90005DF8044B4361FFF7CFBF000010B5194C0F +:105BA000236998420DD08168D0E9003213605A60B1 +:105BB0009A680A449A60002303604FF0FF33A361A0 +:105BC00010BD0268234643F8102F53600022026084 +:105BD00022699A4203D1BDE8104001F097BC936856 +:105BE00081680B44936001F081FC2269E16992684D +:105BF000441AA242E4D91144BDE81040091AFFF743 +:105C000053BF00BFE86800202DE9F047DFF8BC80F3 +:105C100008F110072C4ED8F8105001F067FCD8F8A6 +:105C20001C40AA68031B9A423ED814444FF0000956 +:105C3000D5E90032C8F81C4013605A60C5F80090DE +:105C4000D8F81030B34201D101F060FC89F311881B +:105C5000D5E9033128469847302383F311886B69CF +:105C6000002BD8D001F042FC6A69A0EB04098246FF +:105C70004A450DD2022001F095FD0022D8F81030DF +:105C8000B34208D151462846BDE8F047FFF728BF88 +:105C9000121A2244F2E712EB09092946384638BFA6 +:105CA0004A46FFF7EBFEB5E7D8F81030B34208D00C +:105CB0001444C8F81C00211AA960BDE8F047FFF79A +:105CC000F3BEBDE8F08700BFF8680020E868002058 +:105CD00038B501F00BFC054AD2E90845031B181939 +:105CE00045F10001C2E9080138BD00BFE8680020A5 +:105CF00000207047FEE70000704700004FF0FF30C3 +:105D00007047000002290CD0032904D0012907485C +:105D100018BF00207047032A05D8054800EBC200D1 +:105D20007047044870470020704700BF5483000844 +:105D30004C2300200883000870B59AB00546084639 +:105D4000144601A900F0C2F801A8FBF741FE431C6C +:105D50000022C6B25B001046C5E90034237003235D +:105D6000023404F8013C01ABD1B202348E4201D8B6 +:105D70001AB070BD13F8011B013204F8010C04F8CD +:105D8000021CF1E708B5302383F311880348FFF7BD +:105D900005FA002383F3118808BD00BF586B00206B +:105DA00090F8803003F01F02012A07D190F881207B +:105DB0000B2A03D10023C0E91D3315E003F0600373 +:105DC000202B08D1B0F884302BB990F88120212AFB +:105DD00003D81F2A04D8FFF7C3B9222AEBD0FAE769 +:105DE000034A426707228267C3670120704700BFEA +:105DF0004323002007B5052917D8DFE801F019165D +:105E000003191920302383F31188104A01210190CE +:105E1000FFF76CFA019802210D4AFFF767FA0D4867 +:105E2000FFF788F9002383F3118803B05DF804FBC2 +:105E3000302383F311880748FFF752F9F2E7302344 +:105E400083F311880348FFF769F9EBE7A88200089C +:105E5000CC820008586B002038B50C4D0C4C2A46FB +:105E60000C4904F10800FFF767FF05F1CA0204F1CD +:105E700010000949FFF760FF05F5CA7204F1180028 +:105E80000649BDE83840FFF757BF00BF3084002007 +:105E90004C23002088820008928200089D8200081E +:105EA00070B5044608460D46FBF792FDC6B2204683 +:105EB000013403780BB9184670BD32462946FBF70A +:105EC00073FD0028F3D10120F6E700002DE9F0472B +:105ED00005460C46FBF77CFD2B49C6B22846FFF76A +:105EE000DFFF08B10A36F6B228492846FFF7D8FF87 +:105EF00008B11036F6B2632E0BD8DFF88C80DFF8CD +:105F00008C90234FDFF894A02E7846B92670BDE818 +:105F1000F08729462046BDE8F04702F05BB8252E01 +:105F20002ED1072241462846FBF73EFD70B9194B9A +:105F3000224603F1100153F8040B8B4242F8040B84 +:105F4000F9D11B78073511341370DDE70822494673 +:105F50002846FBF729FD98B9A21C0F4B197802328D +:105F60000909C95D02F8041C13F8011B01F00F01B7 +:105F70005345C95D02F8031CF0D118340835C3E756 +:105F8000013504F8016BBFE7748300089D820008A7 +:105F90007C830008F27F000800E8F11F0CE8F11F85 +:105FA000BFF34F8F044B1A695107FCD1D3F810216E +:105FB0005207F8D1704700BF0020005208B50D4BC2 +:105FC0001B78ABB9FFF7ECFF0B4BDA68D10704D5B0 +:105FD0000A4A5A6002F188325A60D3F80C21D2077B +:105FE00006D5064AC3F8042102F18832C3F8042119 +:105FF00008BD00BF8E8600200020005223016745A7 +:1060000008B5114B1B78F3B9104B1A69510703D52A +:10601000DA6842F04002DA60D3F81021520705D561 +:10602000D3F80C2142F04002C3F80C21FFF7B8FF6F +:10603000064BDA6842F00102DA60D3F80C2142F034 +:106040000102C3F80C2108BD8E86002000200052FA +:106050000F289ABF00F580604004002070470000C0 +:106060004FF4003070470000102070470F2808B52B +:106070000BD8FFF7EDFF00F500330268013204D1C1 +:1060800004308342F9D1012008BD0020FCE7000064 +:106090000F2838B505463FD8FFF782FF1F4CFFF7A2 +:1060A0008DFF4FF0FF3307286361C4F814311DD80A +:1060B0002361FFF775FF030243F02403E360E36805 +:1060C00043F08003E36023695A07FCD42846FFF7B6 +:1060D00067FFFFF7BDFF4FF4003100F009FA2846D3 +:1060E000FFF78EFFBDE83840FFF7C0BFC4F810319E +:1060F000FFF756FFA0F108031B0243F02403C4F886 +:106100000C31D4F80C3143F08003C4F80C31D4F8CE +:1061100010315B07FBD4D9E7002038BD00200052C6 +:106120002DE9F84F05460C46104645EA0203DE0607 +:1061300002D00020BDE8F88F20F01F00DFF8BCB0CF +:10614000DFF8BCA0FFF73AFF04EB0008444503D199 +:106150000120FFF755FFEDE720222946204601F0F8 +:1061600007FF10B920352034F0E72B4605F1200257 +:106170001F68791CDDD104339A42F9D105F17843C7 +:106180001B481C4EB3F5801F1B4B38BF184603F14C +:10619000F80332BFD946D1461E46FFF701FF07601C +:1061A000A5EB040C336804F11C0143F002033360D7 +:1061B000231FD9F8007017F00507FAD153F8042F00 +:1061C0008B424CF80320F4D1BFF34F8FFFF7E8FE6A +:1061D0004FF0FF332022214603602846336823F026 +:1061E0000203336001F0C4FE0028BBD03846B0E79C +:1061F000142100520C200052142000521020005292 +:106200001021005210B5084C237828B11BB9FFF7B4 +:10621000D5FE0123237010BD002BFCD02070BDE8FB +:106220001040FFF7EDBE00BF8E8600202DE9F04F35 +:106230000D4685B0814658B111F00D0614BF2022DD +:10624000082211F00803019304D0431E03426AD0D0 +:10625000002435E0002E37D009F11F0121F01F097D +:106260004FF00108324F05F00403DFF8D0A005EA33 +:10627000080BBBF1000F32D07869C0072FD408F1AA +:1062800001080C37B8F1060FF3D19EB9294D4946E4 +:10629000A819019201F090F9044600283AD1183665 +:1062A000019A782EF3D1494601F086F90446002878 +:1062B00030D1019A4946204801F07EF9044668BB76 +:1062C000204605B0BDE8F08F0029C9D10146284617 +:1062D000029201F071F90446E0B9029AC0E713B1E5 +:1062E00078694107CBD5AC0702D578698007C6D558 +:1062F000019911B178690107C1D51820494600FB01 +:1063000008A0CDE9022301F057F90446DDE9022394 +:106310000028B4D04A460021204601E04A46002128 +:10632000FBF75EFBCCE70246002E95D198E700BF55 +:1063300090830008C086002090860020A886002058 +:106340000121FFF773BF0000F8B5144D0124182791 +:10635000134E40F2FF3200210120FBF741FB07FB07 +:10636000046001342A6955F80C1F01F011F9062C5C +:10637000F5D137254FF4C0542046FFF7E1FF014621 +:1063800028B122460748BDE8F84001F001B9C4EB46 +:10639000C404013D4FEAD404EED1F8BD9083000857 +:1063A000A88600209086002008B101F077B97047D8 +:1063B00038B5054D00240334696855F80C0B00F01E +:1063C000A9F8122CF7D138BD9083000838B5EFF347 +:1063D00011859DB9EFF30584C4F30804302334B16B +:1063E00083F31188FFF774FC85F3118838BD83F3BC +:1063F0001188FFF76DFC84F3118838BDBDE8384083 +:10640000FFF766BC10B5FFF7E1FF104CC008104A5B +:10641000002340EA4170C908A0FB04ECA0FB020E77 +:106420001CEB0000A1FB044CA1FB02125B41001914 +:1064300043EB0C0011EB0E0142F10002411842F156 +:106440000000090941EA007010BD00BFCFF753E317 +:10645000A59BC4200244074BD2B210B5904200D194 +:1064600010BD441C00B253F8200041F8040BE0B208 +:10647000F4E700BF504000580E4B30B51C6F2404A9 +:1064800005D41C6F1C671C6F44F400441C670A4C45 +:1064900002442368D2B243F480732360074B9042D6 +:1064A00000D130BD441C51F8045B00B243F82050C9 +:1064B000E0B2F4E700440258004802585040005847 +:1064C00007B5012201A90020FFF7C4FF019803B01E +:1064D0005DF804FB13B50446FFF7F2FFA04205D0B8 +:1064E000012201A900200194FFF7C6FF02B010BDF0 +:1064F0000144BFF34F8F064B884204D3BFF34F8F45 +:10650000BFF36F8F7047C3F85C022030F4E700BF21 +:1065100000ED00E00144BFF34F8F064B884204D3E7 +:10652000BFF34F8FBFF36F8F7047C3F870022030F7 +:10653000F4E700BF00ED00E070470000074B45F2B4 +:1065400055521A6003225A6040F2FF729A604CF66C +:10655000CC421A600122024B1A7070470048005862 +:106560003C870020034B1B781BB1034B4AF6AA2241 +:106570001A6070473C87002000480058034B1A6897 +:106580001AB9034AD2F8D0241A607047388700201D +:1065900000400258024B4FF48032C3F8D0247047B9 +:1065A0000040025808B5FFF7E9FF024B1868C0F336 +:1065B000806008BD3887002070B5BFF34F8FBFF3F0 +:1065C0006F8F1A4A0021C2F85012BFF34F8FBFF3EA +:1065D0006F8F536943F400335361BFF34F8FBFF3A1 +:1065E0006F8FC2F88410BFF34F8FD2F8803043F61C +:1065F000E074C3F3C900C3F34E335B0103EA04063E +:10660000014646EA81750139C2F86052F9D2203B51 +:1066100013F1200FF2D1BFF34F8F536943F480334E +:106620005361BFF34F8FBFF36F8F70BD00ED00E07C +:10663000FEE70000214B2248224A70B5904237D332 +:10664000214BC11EDA1C121A22F003028B4238BF02 +:1066500000220021FBF7C4F91C4A0023C2F8843051 +:10666000BFF34F8FD2F8803043F6E074C3F3C90014 +:10667000C3F34E335B0103EA0406014646EA817523 +:106680000139C2F86C52F9D2203B13F1200FF2D13C +:10669000BFF34F8FBFF36F8FBFF34F8FBFF36F8F7A +:1066A0000023C2F85032BFF34F8FBFF36F8F70BD1E +:1066B00053F8041B40F8041BC0E700BFC485000862 +:1066C00030890020308900203089002000ED00E072 +:1066D000074BD3F8D81021EA0001C3F8D810D3F83B +:1066E000002122EA0002C3F80021D3F800317047EC +:1066F0000044025870B5D0E9244300224FF0FF3522 +:106700009E6804EB42135101D3F80009002805DA12 +:10671000D3F8000940F08040C3F80009D3F8000B1B +:10672000002805DAD3F8000B40F08040C3F8000BD6 +:10673000013263189642C3F80859C3F8085BE0D2E7 +:106740004FF00113C4F81C3870BD0000890141F0FE +:106750002001016103699B06FCD41220FFF710B9E8 +:1067600010B50A4C2046FEF79FFD094BC4F8903047 +:10677000084BC4F89430084C2046FEF795FD074BB3 +:10678000C4F89030064BC4F8943010BD4087002008 +:1067900000000840FC830008DC8700200000044063 +:1067A0000884000870B503780546012B5CD1434B83 +:1067B000D0F89040984258D1414B0E216520D3F833 +:1067C000D82042F00062C3F8D820D3F8002142F06C +:1067D0000062C3F80021D3F80021D3F8802042F0F2 +:1067E0000062C3F88020D3F8802022F00062C3F852 +:1067F0008020D3F88030FEF7BDF9324BE360324B96 +:10680000C4F800380023D5F89060C4F8003EC023D7 +:1068100023604FF40413A3633369002BFCDA0123D4 +:106820000C203361FFF7ACF83369DB07FCD412208E +:10683000FFF7A6F83369002BFCDA00262846A6608D +:10684000FFF758FF6B68C4F81068DB68C4F8146879 +:10685000C4F81C6883BB1D4BA3614FF0FF33636119 +:10686000A36843F00103A36070BD194B9842C9D1DE +:10687000134B4FF08060D3F8D82042F00072C3F879 +:10688000D820D3F8002142F00072C3F80021D3F8D9 +:106890000021D3F8802042F00072C3F88020D3F8A2 +:1068A000802022F00072C3F88020D3F88030FFF7F8 +:1068B0000FFF0E214D209EE7064BCDE740870020BD +:1068C000004402584014004003002002003C30C045 +:1068D000DC870020083C30C0F8B5D0F89040054671 +:1068E00000214FF000662046FFF730FFD5F89410E6 +:1068F00000234FF001128F684FF0FF30C4F8343896 +:10690000C4F81C2804EB431201339F42C2F800690B +:10691000C2F8006BC2F80809C2F8080BF2D20B6883 +:10692000D5F89020C5F8983063621023136116697A +:1069300016F01006FBD11220FFF722F8D4F8003829 +:1069400023F4FE63C4F80038A36943F4402343F002 +:106950001003A3610923C4F81038C4F814380B4B92 +:10696000EB604FF0C043C4F8103B094BC4F8003B48 +:10697000C4F81069C4F80039D5F8983003F1100252 +:1069800043F48013C5F89820A362F8BDD8830008AB +:1069900040800010D0F8902090F88A10D2F800388B +:1069A00023F4FE6343EA0113C2F800387047000085 +:1069B0002DE9F84300EB8103D0F890500C46804657 +:1069C000DA680FFA81F94801166806F00306731EAB +:1069D000022B05EB41134FF0000194BFB604384E73 +:1069E000C3F8101B4FF0010104F1100398BF06F12A +:1069F000805601FA03F3916998BF06F50046002915 +:106A00003AD0578A04F15801374349016F50D5F8FD +:106A10001C180B430021C5F81C382B180127C3F89C +:106A20001019A7405369611E9BB3138A928B9B0870 +:106A3000012A88BF5343D8F89820981842EA0343A4 +:106A400001F140022146C8F89800284605EB820271 +:106A50005360FFF77BFE08EB8900C3681B8A43EA9B +:106A6000845348341E4364012E51D5F81C381F430B +:106A7000C5F81C78BDE8F88305EB4917D7F8001B6B +:106A800021F40041C7F8001BD5F81C1821EA0303C4 +:106A9000C0E704F13F030B4A2846214605EB830378 +:106AA0005A60FFF753FE05EB4910D0F8003923F484 +:106AB0000043C0F80039D5F81C3823EA0707D7E7A8 +:106AC0000080001000040002D0F894201268C0F882 +:106AD0009820FFF70FBE00005831D0F890304901E0 +:106AE0005B5813F4004004D013F4001F0CBF0220C5 +:106AF000012070474831D0F8903049015B5813F4B9 +:106B0000004004D013F4001F0CBF02200120704786 +:106B100000EB8101CB68196A0B6813604B68536006 +:106B20007047000000EB810330B5DD68AA69136887 +:106B3000D36019B9402B84BF402313606B8A14685B +:106B4000D0F890201C4402EB4110013C09B2B4FB88 +:106B5000F3F46343033323F0030343EAC44343F0F2 +:106B6000C043C0F8103B2B6803F00303012B0ED188 +:106B7000D2F8083802EB411013F4807FD0F8003BC4 +:106B800014BF43F0805343F00053C0F8003B02EBC6 +:106B90004112D2F8003B43F00443C2F8003B30BD41 +:106BA0002DE9F041D0F8906005460C4606EB411304 +:106BB000D3F8087B3A07C3F8087B08D5D6F8143811 +:106BC0001B0704D500EB8103DB685B689847FA0775 +:106BD0001FD5D6F81438DB071BD505EB8403D9681D +:106BE000CCB98B69488A5A68B2FBF0F600FB1622D2 +:106BF0008AB91868DA6890420DD2121AC3E90024E3 +:106C0000302383F3118821462846FFF78BFF84F356 +:106C10001188BDE8F081012303FA04F26B8923EAAD +:106C200002036B81CB68002BF3D021462846BDE8D8 +:106C3000F041184700EB81034A0170B5DD68D0F8D8 +:106C400090306C692668E66056BB1A444FF4002009 +:106C5000C2F810092A6802F00302012A0AB20ED112 +:106C6000D3F8080803EB421410F4807FD4F800092D +:106C700014BF40F0805040F00050C4F8000903EB0E +:106C80004212D2F8000940F00440C2F80009012283 +:106C9000D3F8340802FA01F10143C3F8341870BD87 +:106CA00019B9402E84BF4020206020681A442E8AE3 +:106CB0008419013CB4FBF6F440EAC44040F00050B3 +:106CC000C6E700002DE9F843D0F8906005460C4671 +:106CD0004F0106EB4113D3F8088918F0010FC3F8F0 +:106CE00008891CD0D6F81038DB0718D500EB8103D3 +:106CF000D3F80CC0DCF81430D3F800E0DA6896451D +:106D000030D2A2EB0E024FF000091A60C3F80490D3 +:106D1000302383F31188FFF78DFF89F3118818F072 +:106D2000800F1DD0D6F834380126A640334217D044 +:106D300005EB84030134D5F89050D3F80CC0E4B2CD +:106D40002F44DCF8142005EB0434D2F800E051683D +:106D5000714514D3D5F8343823EA0606C5F83468EB +:106D6000BDE8F883012303FA01F2038923EA020351 +:106D70000381DCF80830002BD1D09847CFE7AEEB89 +:106D80000103BCF81000834228BF0346D7F8180956 +:106D900080B2B3EB800FE3D89068A0F1040959F8F2 +:106DA000048FC4F80080A0EB09089844B8F1040FE0 +:106DB000F5D818440B4490605360C8E72DE9F84FAC +:106DC000D0F8905004466E69AB691E4016F48058A6 +:106DD0006E6103D0BDE8F84FFEF7D6BA002E12DA86 +:106DE000D5F8003E9B0705D0D5F8003E23F00303FD +:106DF000C5F8003ED5F80438204623F00103C5F855 +:106E00000438FEF7EFFA370505D52046FFF772FC88 +:106E10002046FEF7D5FAB0040CD5D5F8083813F0A3 +:106E2000060FEB6823F470530CBF43F4105343F484 +:106E3000A053EB6031071BD56368DB681BB9AB69F6 +:106E400023F00803AB612378052B0CD1D5F8003E65 +:106E50009A0705D0D5F8003E23F00303C5F8003E9D +:106E60002046FEF7BFFA6368DB680BB120469847FF +:106E7000F30200F1BA80B70226D5D4F8909000272B +:106E80004FF0010A09EB4712D2F8003B03F440230C +:106E9000B3F5802F11D1D2F8003B002B0DDA6289B7 +:106EA0000AFA07F322EA0303638104EB8703DB6832 +:106EB000DB6813B13946204698470137D4F894303F +:106EC000FFB29B689F42DDD9F00619D5D4F8900037 +:106ED000026AC2F30A1702F00F0302F4F012B2F5CD +:106EE000802F00F0CA80B2F5402F09D104EB830354 +:106EF000002200F58050DB681B6A974240F0B080AA +:106F00003003D5F8185835D5E90303D500212046BC +:106F1000FFF746FEAA0303D501212046FFF740FEF6 +:106F20006B0303D502212046FFF73AFE2F0303D55A +:106F300003212046FFF734FEE80203D50421204652 +:106F4000FFF72EFEA90203D505212046FFF728FEF4 +:106F50006A0203D506212046FFF722FE2B0203D545 +:106F600007212046FFF71CFEEF0103D5082120462C +:106F7000FFF716FE700340F1A780E90703D5002153 +:106F80002046FFF79FFEAA0703D501212046FFF701 +:106F900099FE6B0703D502212046FFF793FE2F07CA +:106FA00003D503212046FFF78DFEEE0603D504210D +:106FB0002046FFF787FEA80603D505212046FFF7E8 +:106FC00081FE690603D506212046FFF77BFE2A06CF +:106FD00003D507212046FFF775FEEB0574D5204643 +:106FE0000821BDE8F84FFFF76DBED4F890904FF040 +:106FF000000B4FF0010AD4F894305FFA8BF79B68CE +:107000009F423FF638AF09EB4713D3F8002902F44B +:107010004022B2F5802F20D1D3F80029002A1CDAB3 +:10702000D3F8002942F09042C3F80029D3F8002990 +:10703000002AFBDB3946D4F89000FFF787FB228952 +:107040000AFA07F322EA0303238104EB8703DB68D0 +:107050009B6813B13946204698470BF1010BCAE7EC +:10706000910701D1D0F80080072A02F101029CBFEC +:1070700003F8018B4FEA18283FE704EB830300F580 +:107080008050DA68D2F818C0DCF80820DCE9001C6F +:10709000A1EB0C0C00218F4208D1DB689B699A6838 +:1070A0003A449A605A683A445A6029E711F0030F4B +:1070B00001D1D0F800808C4501F1010184BF02F8B4 +:1070C000018B4FEA1828E6E7BDE8F88F08B50348BA +:1070D000FFF774FEBDE80840FDF7DCB940870020EB +:1070E00008B50348FFF76AFEBDE80840FDF7D2B9CE +:1070F000DC870020D0F8903003EB4111D1F8003B41 +:1071000043F40013C1F8003B70470000D0F8903002 +:1071100003EB4111D1F8003943F40013C1F80039F1 +:1071200070470000D0F8903003EB4111D1F8003BDC +:1071300023F40013C1F8003B70470000D0F89030F2 +:1071400003EB4111D1F8003923F40013C1F80039E1 +:107150007047000030B50433039C0172002104FB2A +:107160000325C160C0E90653049B0363059BC0E986 +:107170000000C0E90422C0E90842C0E90A114363E3 +:1071800030BD00000022416AC260C0E90411C0E9BC +:107190000A226FF00101FEF763BC0000D0E904325F +:1071A000934201D1C2680AB9181D70470020704788 +:1071B000036919600021C2680132C260C2691344C8 +:1071C00082699342036124BF436A0361FEF73CBCBA +:1071D00038B504460D46E3683BB162690020131DD3 +:1071E0001268A3621344E36207E0237A33B92946A5 +:1071F0002046FEF719FC0028EDDA38BD6FF00100DB +:10720000FBE70000C368C269013BC36043691344E4 +:1072100082699342436124BF436A436100238362CE +:10722000036B03B11847704770B53023044683F3EE +:107230001188866A3EB9FFF7CBFF054618B186F381 +:107240001188284670BDA36AE26A13F8015B934275 +:10725000A36202D32046FFF7D5FF002383F31188F2 +:10726000EFE700002DE9F84F04460E461746984612 +:107270004FF0300989F311880025AA46D4F828B0C8 +:10728000BBF1000F09D141462046FFF7A1FF20B115 +:107290008BF311882846BDE8F88FD4E90A12A7EBD2 +:1072A000050B521A934528BF9346BBF1400F1BD9DB +:1072B000334601F1400251F8040B914243F8040BAC +:1072C000F9D1A36A403640354033A362D4E90A239A +:1072D0009A4202D32046FFF795FF8AF31188BD42F8 +:1072E000D8D289F31188C9E730465A46FAF752FBDB +:1072F000A36A5E445D445B44A362E7E710B5029C69 +:107300000433017203FB0421C460C0E906130023A7 +:10731000C0E90A33039B0363049BC0E90000C0E992 +:107320000422C0E90842436310BD0000026A6FF006 +:107330000101C260426AC0E904220022C0E90A22B7 +:10734000FEF78EBBD0E904239A4201D1C26822B96C +:10735000184650F8043B0B60704700231846FAE7C4 +:10736000C3680021C2690133C36043691344826961 +:107370009342436124BF436A4361FEF765BB00004B +:1073800038B504460D46E3683BB1236900201A1D59 +:10739000A262E2691344E36207E0237A33B9294623 +:1073A0002046FEF741FB0028EDDA38BD6FF0010002 +:1073B000FBE7000003691960C268013AC260C26954 +:1073C000134482699342036124BF436A036100232B +:1073D0008362036B03B118477047000070B5302318 +:1073E0000D460446114683F31188866A2EB9FFF7CD +:1073F000C7FF10B186F3118870BDA36A1D70A36A20 +:10740000E26A01339342A36204D3E169204604395E +:10741000FFF7D0FF002080F31188EDE72DE9F84F4A +:1074200004460D46904699464FF0300A8AF311887B +:107430000026B346A76A4FB949462046FFF7A0FF8A +:1074400020B187F311883046BDE8F88FD4E90A07E8 +:107450003A1AA8EB0607974228BF1746402F1BD9B8 +:1074600005F1400355F8042B9D4240F8042BF9D157 +:10747000A36A40364033A362D4E90A239A4204D374 +:10748000E16920460439FFF795FF8BF311884645E3 +:10749000D9D28AF31188CDE729463A46FAF77AFA23 +:1074A000A36A3D443E443B44A362E5E7D0E904239C +:1074B0009A4217D1C3689BB1836A8BB1043B9B1A74 +:1074C0000ED01360C368013BC360C3691A4483696B +:1074D0009A42026124BF436A03610023836201234D +:1074E000184670470023FBE700F060BA014B586A6A +:1074F000704700BF000C0040034B002258631A6124 +:107500000222DA60704700BF000C0040014B0022ED +:10751000DA607047000C0040014B5863704700BFB1 +:10752000000C0040024B034A1A60034A5A6070473D +:10753000908800203089002000000220074B49423B +:1075400010B55C68201A08401968821A8A4203D371 +:10755000A24201D85A6010BD0020FCE790880020AC +:1075600008B5302383F31188FFF7E8FF002383F386 +:10757000118808BD04480121044B03600023C0E9C1 +:1075800001330C3000F016B99888002061750008AE +:10759000CB1D083A23F00703591A521A012110B4DF +:1075A000D2080024C0E9004384600C301C605A609B +:1075B0005DF8044B00F0FEB82DE9F84F364ECD1DB6 +:1075C0000F46002818BF0646082A4FEAD50538BFDF +:1075D000082206F10C08341D9146404600F006F9D9 +:1075E00009F10701C9F1000E224624686CB9404632 +:1075F00000F006F93368CBB308224946E800984703 +:10760000044698B340E9026730E004EB010CD4F87B +:1076100004A00CEA0E0C0AF10100ACF1080304EB23 +:10762000C0009842E0D9A0EB0C0CB5EBEC0F4FEA90 +:10763000EC0BD9D89C421CD204F10802AB45A3EB59 +:1076400002024FEAE202626009D9691CED43206838 +:1076500003EBC1025D44556043F8310022601C46D3 +:107660005F60404644F8086B00F0CAF82046BDE869 +:10767000F88FAA45216802D111602346EFE7013552 +:1076800004EBC50344F8351003F10801401AC0109B +:1076900058601360F1E700BF98880020F8B550F8F3 +:1076A000043C044650F8085CA0F1080607332F1D7F +:1076B0000C35DB0840F8043C284600F097F83B46C0 +:1076C0009F421A6801D0B34228D20AB1964225D20D +:1076D00044F8082C54F8042C1E60013254F8081C9D +:1076E00006EBC200814206D14868024444F8042CEB +:1076F0000A6844F8082C5868411C03EBC1018E420B +:1077000007D154F8042C013202445A6054F8082C72 +:107710001A602846BDE8F84000F072B81346CFE77B +:10772000FEE7000070B51B4B0025044686B058608C +:107730000E4685620163FCF785FE04F11003A56027 +:10774000E562C4E904334FF0FF33C4E90044C4E9FF +:107750000635FFF7CBFE2B46024604F134012046E6 +:10776000C4E9082380230C4A2565FEF713F9012399 +:107770000A4AE06000920375684672680192B26836 +:10778000CDE90223064BCDE90435FEF72BF906B00F +:1077900070BD00BF506B00201484000819840008DD +:1077A00021770008024AD36A1843D062704700BFAD +:1077B000E8680020C0E90000816070478368013BF1 +:1077C000002B10B583600CDA074BDC684368A061BE +:1077D000206063601C6044600520FEF73DF8A069EE +:1077E00010BD0020FCE700BFE868002008B530238A +:1077F00083F31188FFF7E2FF002383F3118808BDAC +:1078000008B5302383F3118883680133002B83602C +:1078100007DC036800211A68026050601846FEF712 +:1078200047F8002383F3118808BD00004B684360CC +:107830008B688360CB68C3600B6943614B690362EB +:107840008B6943620B6803607047000008B53C4BCE +:1078500040F2FF713B48D3F888200A43C3F88820E0 +:10786000D3F8882022F4FF6222F00702C3F88820B0 +:10787000D3F88820D3F8E0200A43C3F8E020D3F8F7 +:1078800008210A43C3F808212F4AD3F808311146CA +:10789000FFF7CCFF00F5806002F11C01FFF7C6FF87 +:1078A00000F5806002F13801FFF7C0FF00F580604D +:1078B00002F15401FFF7BAFF00F5806002F1700198 +:1078C000FFF7B4FF00F5806002F18C01FFF7AEFF17 +:1078D00000F5806002F1A801FFF7A8FF00F58060C5 +:1078E00002F1C401FFF7A2FF00F5806002F1E001A0 +:1078F000FFF79CFF00F5806002F1FC01FFF796FFA7 +:1079000002F58C7100F58060FFF790FF00F01AF926 +:107910000E4BD3F8902242F00102C3F89022D3F824 +:10792000942242F00102C3F894220522C3F8982061 +:107930004FF06052C3F89C20054AC3F8A02008BD50 +:1079400000440258000002582084000800ED00E0C6 +:107950001F00080308B500F0D7FAFDF7E5FF104B4C +:10796000D3F8DC2042F04002C3F8DC20D3F8042135 +:1079700022F04002C3F80421D3F80431094B1A68FD +:1079800042F008021A601A6842F004021A60FEF718 +:10799000F5FDFEF7D9FCBDE80840FEF75DBA00BF73 +:1079A000004402580018024870470000114BD3F8F9 +:1079B000E82042F00802C3F8E820D3F8102142F092 +:1079C0000802C3F810210C4AD3F81031D36B43F0EE +:1079D0000803D363C722094B9A624FF0FF32DA6281 +:1079E00000229A615A63DA605A6001225A611A6071 +:1079F000704700BF004402580010005C000C0040BB +:107A0000094A08B51169D3680B40D9B29B076FEAE0 +:107A10000101116107D5302383F31188FDF7AEFF13 +:107A2000002383F3118808BD000C0040064BD3F8F7 +:107A3000DC200243C3F8DC20D3F804211043C3F850 +:107A40000401D3F8043170470044025808B53C4B98 +:107A50004FF0FF31D3F8802062F00042C3F880205D +:107A6000D3F8802002F00042C3F88020D3F88020B1 +:107A7000D3F88420C3F88410D3F884200022C3F8FC +:107A80008420D3F88400D86F40F0FF4040F4FF001A +:107A900040F4DF4040F07F00D867D86F20F0FF400F +:107AA00020F4FF0020F4DF4020F07F00D867D86F7B +:107AB000D3F888006FEA40506FEA5050C3F888004E +:107AC000D3F88800C0F30A00C3F88800D3F8880010 +:107AD000D3F89000C3F89010D3F89000C3F890202A +:107AE000D3F89000D3F89400C3F89410D3F894001E +:107AF000C3F89420D3F89400D3F89800C3F89810F2 +:107B0000D3F89800C3F89820D3F89800D3F88C00E5 +:107B1000C3F88C10D3F88C00C3F88C20D3F88C00F9 +:107B2000D3F89C00C3F89C10D3F89C10C3F89C2099 +:107B3000D3F89C30FCF730FEBDE8084000F0B8B93F +:107B40000044025808B50122534BC3F80821534B97 +:107B5000D3F8F42042F00202C3F8F420D3F81C2139 +:107B600042F00202C3F81C210222D3F81C314C4B14 +:107B7000DA605A689104FCD54A4A1A6001229A6078 +:107B8000494ADA6000221A614FF440429A61444B3C +:107B90009A699204FCD51A6842F480721A603F4BCD +:107BA0001A6F12F4407F04D04FF480321A6700221B +:107BB0001A671A6842F001021A60384B1A685007B7 +:107BC000FCD500221A611A6912F03802FBD101219A +:107BD00019604FF0804159605A67344ADA62344A7A +:107BE0001A611A6842F480321A602C4B1A689103A9 +:107BF000FCD51A6842F480521A601A689204FCD5C7 +:107C00002C4A2D499A6200225A63196301F57C01BE +:107C1000DA6301F5E77199635A64284A1A64284ABD +:107C2000DA621A6842F0A8521A601C4B1A6802F015 +:107C30002852B2F1285FF9D148229A614FF4886244 +:107C4000DA6140221A621F4ADA641F4A1A651F4A23 +:107C50005A651F4A9A6532231E4A1360136803F05F +:107C60000F03022BFAD10D4A136943F0030313618A +:107C7000136903F03803182BFAD14FF00050FFF7C7 +:107C8000D5FE4FF08040FFF7D1FE4FF00040BDE839 +:107C90000840FFF7CBBE00BF0080005100440258EF +:107CA0000048025800C000F0020000010000FF017F +:107CB000008890083220600063020901470E050821 +:107CC000DD0BBF0120000020000001100910E000C2 +:107CD00000010110002000524FF0B04208B5D2F868 +:107CE000883003F00103C2F8883023B1044A1368D6 +:107CF0000BB150689847BDE80840FCF7CBBB00BF0C +:107D0000B08800204FF0B04208B5D2F8883003F0B8 +:107D10000203C2F8883023B1044A93680BB1D068DB +:107D20009847BDE80840FCF7B5BB00BFB08800200D +:107D30004FF0B04208B5D2F8883003F00403C2F81F +:107D4000883023B1044A13690BB150699847BDE8E4 +:107D50000840FCF79FBB00BFB08800204FF0B04246 +:107D600008B5D2F8883003F00803C2F8883023B190 +:107D7000044A93690BB1D0699847BDE80840FCF705 +:107D800089BB00BFB08800204FF0B04208B5D2F8E0 +:107D9000883003F01003C2F8883023B1044A136A14 +:107DA0000BB1506A9847BDE80840FCF773BB00BFB1 +:107DB000B08800204FF0B04310B5D3F8884004F4E9 +:107DC0007872C3F88820A30604D5124A936A0BB1CF +:107DD000D06A9847600604D50E4A136B0BB1506BFE +:107DE0009847210604D50B4A936B0BB1D06B98478B +:107DF000E20504D5074A136C0BB1506C9847A305F4 +:107E000004D5044A936C0BB1D06C9847BDE8104080 +:107E1000FCF740BBB08800204FF0B04310B5D3F85A +:107E2000884004F47C42C3F88820620504D5164AD1 +:107E3000136D0BB1506D9847230504D5124A936D0D +:107E40000BB1D06D9847E00404D50F4A136E0BB107 +:107E5000506E9847A10404D50B4A936E0BB1D06EB7 +:107E60009847620404D5084A136F0BB1506F9847C6 +:107E7000230404D5044A936F0BB1D06F9847BDE833 +:107E80001040FCF707BB00BFB088002008B50348CE +:107E9000FCF7EAFDBDE80840FCF7FCBA7864002076 +:107EA00008B5FFF7ADFDBDE80840FCF7F3BA0000E8 +:107EB000062108B50846FCF75DFE06210720FCF701 +:107EC00059FE06210820FCF755FE06210920FCF783 +:107ED00051FE06210A20FCF74DFE06211720FCF773 +:107EE00049FE06212820FCF745FE09217A20FCF7EF +:107EF00041FE07213220FCF73DFE0C215220BDE857 +:107F00000840FCF737BE000008B5FFF79FFD00F002 +:107F10000DF8FCF7EDFFFDF7C5F9FDF797F8FFF752 +:107F200043FDBDE80840FFF7DFBA00000023054A23 +:107F300019460133102BC2E9001102F10802F8D1F1 +:107F4000704700BFB08800200B460146184600F07D +:107F500001B8000010B5054C13462CB10A46014685 +:107F60000220AFF3008010BD2046FCE700000000B7 +:107F700010B501390244904201D1002005E0037898 +:107F800011F8014FA34201D0181B10BD0130F2E7D8 +:107F90002DE9F041A3B1C91A17780144044603F151 +:107FA000FF3C8C42204601D9002009E00578BD4203 +:107FB00004F10104F5D10CEB0405D618A54201D15A +:107FC000BDE8F08115F8018D16F801EDF045F5D00A +:107FD000E7E70000034611F8012B03F8012B002A04 +:107FE000F9D170476F72672E6172647570696C6F3A +:107FF000742E437562654F72616E67652D70657290 +:108000006970680053544D333248373F3F3F005347 +:10801000544D3332483733782F3732780053544D2C +:108020003332483734332F3735332F37353000006C +:1080300001105A0003105900012058000320560077 +:1080400040A2E4F1646891060041A3E5F2656992FB +:108050000700000043414E464449666163653A208B +:108060004D6573736167652052414D204F7665728F +:10807000666C6F77210000004261642043414E49E5 +:108080006661636520696E6465782E0000010000FA +:108090000001FF0000A0004000A40040000000001C +:1080A00000000000612B0008E9230008E932000805 +:1080B00059240008652400087D280008DD250008F3 +:1080C0002124000825240008FD230008E5230008DA +:1080D0003928000809240008513400081524000834 +:1080E0000D28000801040E05054B02020E05054B84 +:1080F00004010E05054B05010B04044B08010603A2 +:108100000346000010000240080002400008024040 +:1081100000000B0028000240080002400408024052 +:1081200006010C004000024008000240080802401E +:1081300010020D0058000240080002400C080240E6 +:1081400016030E00700002400C00024010080240AE +:1081500000040F00880002400C0002401408024096 +:1081600006051000A00002400C0002401808024062 +:1081700010061100B80002400C0002401C0802402A +:1081800016072F0010040240080402402008024095 +:108190000008380028040240080402402408024075 +:1081A0000609390040040240080402402808024041 +:1081B000100A3A0058040240080402402C08024009 +:1081C000160B3B00700402400C04024030080240D1 +:1081D000000C3C00880402400C04024034080240B9 +:1081E000060D4400A00402400C040240380802407E +:1081F000100E4500B80402400C0402403C08024046 +:10820000160F46000096000000000000000000006D +:10821000000000000000000000000000000000005E +:10822000B14E00089D4E0008D94E0008C54E00080A +:10823000D14E0008BD4E0008A94E0008954E00081A +:10824000E54E000800000000C94F0008B54F0008C7 +:10825000F14F0008DD4F0008E94F0008D54F000836 +:10826000C14F0008AD4F0008FD4F0008000000009E +:108270000100000000000000633000007882000868 +:1082800040690020506B00204172647550696C6F2A +:10829000740025424F415244252D424C0025534540 +:1082A0005249414C2500000002000000000000007F +:1082B000E9510008595200084000400000840020A5 +:1082C00010840020020000000000000003000000F5 +:1082D00000000000A1520008000000001000000093 +:1082E00020840020000000000100000000000000C9 +:1082F0004087002001010200F55D0008055D0008CF +:10830000A15D0008855D000843000000108300089F +:1083100009024300020100C0320904000001020208 +:1083200001000524001001052401000104240202BB +:108330000524060001070582030800FF0904010067 +:10834000020A000000070501024000000705810243 +:1083500040000000120000005C83000812011001C0 +:10836000020000400912415700020102030100000F +:108370000403090425424F41524425003031323371 +:108380003435363738394142434445460000000011 +:108390000001002000FF010002000000000000308A +:1083A0000000040008000000000000240000080095 +:1083B000040000000004000000FC000002000000B7 +:1083C00000000430008000000800000000000038B9 +:1083D000000001000100000000000000FD53000843 +:1083E000B55600086157000840004000788800201A +:1083F00078880020010000008888002080000000AC +:108400004001000008000000000100000010000012 +:10841000080000006D61696E0069646C6500000011 +:108420000000802A00000000AAAAAAAA00000024D6 +:10843000FFFF00000000000000A00A000021000271 +:1084400000000000AAAAAAAA00000000FFFF000086 +:1084500000000009000009001400005400000000A2 +:10846000AAAAAAAA14000054FFFF000000000000FE +:10847000000000000A40100000000000AAAA8AAA1A +:1084800000401000FFFF0000990000000000000005 +:108490000081020000000000AAAAAAAA004101006F +:1084A000FFFF000000000070070000000000000057 +:1084B00000000000AAAAAAAA00000000FFFF000016 +:1084C00000000000000000000000000000000000AC +:1084D000AAAAAAAA00000000FFFF000000000000F6 +:1084E000000000000000000000000000AAAAAAAAE4 +:1084F00000000000FFFF000000000000000000007E +:108500000000000000000000AAAAAAAA00000000C3 +:10851000FFFF00000000000000000000000000005D +:1085200000000000AAAAAAAA00000000FFFF0000A5 +:10853000000000000000000000000000000000003B +:10854000AAAAAAAA00000000FFFF00000000000085 +:10855000000000000000000078050000000000009E +:1085600000001E0000000000FE2A0100D2040000EE +:10857000FF000000586B002078640020000000001D +:1085800004800008830400000F80000850040000ED +:108590001D80000800960000000008009600000002 +:1085A00000080000040000007083000800000000C4 +:1085B00000000000000000000000000000000000BB +:0485C00000000000B7 :00000001FF diff --git a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin index fcbf811dfc76cd..746f60652b9c43 100755 Binary files a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin 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 index 3b7850fc5a908c..71453c9b8e9785 100644 --- a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex +++ b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex @@ -1,2396 +1,2512 @@ :020000040800F2 -:1000000000060020A50500086D1F0008251F000838 -:100010004D1F0008251F0008451F0008A705000800 -:10002000A7050008A7050008A705000895730008A4 -:10003000A7050008A7050008A7050008A7050008F0 -:10004000A7050008A7050008A7050008A7050008E0 -:10005000A7050008A70500082D820008598200089E -:1000600085820008B1820008DD820008A70500082B -:10007000A7050008A7050008A7050008A7050008B0 -:10008000A7050008A7050008A7050008A7050008A0 -:10009000A7050008A7050008A705000809830008B0 -:1000A000A7050008A7050008A7050008A705000880 -:1000B000A7050008A7050008A7050008A705000870 -:1000C000A7050008A7050008A7050008A705000860 -:1000D000A7050008A7050008E1830008F5830008CC -:1000E0006D830008A7050008A7050008A7050008FC -:1000F000A7050008A7050008A7050008A705000830 -:10010000A7050008714500081D840008A705000820 -:10011000A7050008A7050008A7050008A70500080F -:10012000A7050008A7050008A7050008A7050008FF -:10013000A7050008A7050008A7050008A7050008EF -:10014000A7050008A7050008A7050008A7050008DF -:10015000A7050008A7050008A7050008A7050008CF -:10016000A7050008A7050008A7050008A7050008BF -:10017000A7050008017F0008A7050008A7050008DB -:10018000A7050008A705000809840008A7050008BE -:10019000A7050008A7050008A7050008A70500088F -:1001A000A7050008A7050008A7050008A70500087F -:1001B000A7050008A7050008A7050008A70500086F -:1001C000A7050008A7050008A7050008A70500085F -:1001D000A7050008ED7E0008A7050008A705000890 -:1001E000A7050008A7050008A7050008A70500083F -:1001F000A7050008A7050008A7050008A70500082F -:10020000A7050008A7050008A7050008A70500081E -:10021000A7050008A7050008A7050008A70500080E -:10022000A7050008A7050008A7050008A7050008FE -:10023000A7050008A7050008A7050008A7050008EE -:10024000A7050008A7050008A7050008A7050008DE -:10025000A7050008A7050008A7050008A7050008CE -:10026000A7050008A7050008A7050008A7050008BE -:10027000A7050008A7050008A7050008A7050008AE -:10028000A7050008A7050008A7050008A70500089E -:10029000A7050008A7050008A7050008A70500088E -:1002A00053B94AB9002908BF00281CBF4FF0FF31DD -:1002B0004FF0FF3000F074B9ADF1080C6DE904CED9 -:1002C00000F006F8DDF804E0DDE9022304B0704731 -:1002D0002DE9F047089D04468E46002B4DD18A42F9 -:1002E000944669D9B2FA82F252B101FA02F3C2F12C -:1002F000200120FA01F10CFA02FC41EA030E9440BD -:100300004FEA1C48210CBEFBF8F61FFA8CF708FBDD -:1003100016E341EA034306FB07F199420AD91CEBB5 -:10032000030306F1FF3080F01F81994240F21C81E7 -:10033000023E63445B1AA4B2B3FBF8F008FB10332F -:1003400044EA034400FB07F7A7420AD91CEB040464 -:1003500000F1FF3380F00A81A74240F20781644434 -:10036000023840EA0640E41B00261DB1D4400023B9 -:10037000C5E900433146BDE8F0878B4209D9002D1D -:1003800000F0EF800026C5E9000130463146BDE8A7 -:10039000F087B3FA83F6002E4AD18B4202D3824211 -:1003A00000F2F980841A61EB030301209E46002DC0 -:1003B000E0D0C5E9004EDDE702B9FFDEB2FA82F215 -:1003C000002A40F09280A1EB0C014FEA1C471FFA73 -:1003D0008CFE0126200CB1FBF7F307FB131140EA5A -:1003E00001410EFB03F0884208D91CEB010103F127 -:1003F000FF3802D2884200F2CB804346091AA4B2E9 -:10040000B1FBF7F007FB101144EA01440EFB00FEBC -:10041000A64508D91CEB040400F1FF3102D2A64521 -:1004200000F2BB800846A4EB0E0440EA03409CE7C0 -:10043000C6F12007B34022FA07FC4CEA030C20FA6D -:1004400007F401FA06F31C43F9404FEA1C4900FA8D -:1004500006F3B1FBF9F8200C1FFA8CFE09FB18110A -:1004600040EA014108FB0EF0884202FA06F20BD97D -:100470001CEB010108F1FF3A80F08880884240F2CD -:100480008580A8F102086144091AA4B2B1FBF9F011 -:1004900009FB101144EA014100FB0EFE8E4508D90C -:1004A0001CEB010100F1FF346CD28E456AD9023891 -:1004B000614440EA0840A0FB0294A1EB0E01A14276 -:1004C000C846A64656D353D05DB1B3EB080261EBE4 -:1004D0000E0101FA07F722FA06F3F1401F43C5E9BE -:1004E000007100263146BDE8F087C2F12003D840F4 -:1004F0000CFA02FC21FA03F3914001434FEA1C4736 -:100500001FFA8CFEB3FBF7F007FB10360B0C43EA27 -:10051000064300FB0EF69E4204FA02F408D91CEBD7 -:10052000030300F1FF382FD29E422DD902386344D5 -:100530009B1B89B2B3FBF7F607FB163341EA034175 -:1005400006FB0EF38B4208D91CEB010106F1FF38C4 -:1005500016D28B4214D9023E6144C91A46EA0046BB -:1005600038E72E46284605E70646E3E61846F8E64D -:100570004B45A9D2B9EB020864EB0C0E0138A3E796 -:100580004646EAE7204694E74046D1E7D0467BE777 -:10059000023B614432E7304609E76444023842E7EF -:1005A000704700BF02E000F000F8FEE73B488047DC -:1005B00072B63B4880F308883A4880F309883A4885 -:1005C0004EF60851CEF20001086040F20000CCF275 -:1005D00000004EF63471CEF200010860BFF34F8F79 -:1005E000BFF36F8F40F20000C0F2F0004EF688516A -:1005F000CEF200010860BFF34F8FBFF36F8F4FF053 -:100600000000E1EE100A4EF63C71CEF200010860E7 -:10061000062080F31488BFF36F8F06F079FF06F091 -:100620001BFF06F0A9F84FF0553020491C4A9142B3 -:100630003CBF41F8040BFAE71D491A4A91423CBFFE -:1006400041F8040BFAE71B491B4A1C4B9A423EBF78 -:1006500051F8040B42F8040BF8E700201849194A36 -:1006600091423CBF41F8040BFAE706F033FF06F075 -:1006700007F9154C154DAC4203DA54F8041B8847B2 -:10068000F9E700F043F8124C124DAC4203DA54F88B -:10069000041B8847F9E706F01BBF0000711F000824 -:1006A00000060020002200200000000800000020BA -:1006B00000060020C894000800220020D822002054 -:1006C000D822002064680020A0020008A0020008D0 -:1006D000A0020008A00200082DE9F04F2DED108ABD -:1006E000C1F80CD0D0F80CD0BDEC108ABDE8F08F6A -:1006F000002383F311882846A047002005F0A0FEC0 -:10070000FEE705F0EDFD00DFFEE7000038B506F07E -:1007100043FD054606F028FE0446E0B9104B9D4215 -:100720001BD001339D4241F2883504BF01240025CE -:10073000002006F03BFD0CB100F07AF801F02CFB34 -:1007400001F0E4F900F026FD08B100F071F8284648 -:1007500000F01CF9F9E70025EAE70546E8E700BFE5 -:10076000010007B008B501F09DF9A0F1200358423F -:10077000584108BD07B541F21203022101A8ADF8A6 -:10078000043001F0ADF903B05DF804FB38B5202367 -:1007900083F311881748C3680BB105F0EFFE0023FF -:1007A000154A4FF47A71134805F0ACFE002383F329 -:1007B0001188124C236813B12368013B23606368DE -:1007C00013B16368013B63600D4D2B7833B96368E7 -:1007D0007BB9022001F05AFA322363602B78032B95 -:1007E00007D163682BB9022001F050FA4FF47A73F5 -:1007F000636038BDD82200208D070008F423002054 -:10080000EC220020084B187003280CD8DFE800F019 -:1008100008050208022001F02FBA022001F022BAD6 -:10082000024B00225A607047EC220020F423002083 -:10083000F8B5504B504A1C461968013100F09980B8 -:1008400004339342F8D162684C4B9A4240F2918053 -:100850004B4B9B6803F1006303F500339A4280F031 -:100860008880002001F06CF90220FFF7CBFF454B98 -:100870000021D3F8E820C3F8E810D3F81021C3F81A -:100880001011D3F81021D3F8EC20C3F8EC10D3F8F2 -:100890001421C3F81411D3F81421D3F8F020C3F8AD -:1008A000F010D3F81821C3F81811D3F81821D3F891 -:1008B000802042F00062C3F88020D3F8802022F02C -:1008C0000062C3F88020D3F88020D3F8802042F063 -:1008D0000072C3F88020D3F8802022F00072C3F8A1 -:1008E0008020D3F8803072B64FF0E023C3F8084D73 -:1008F000D4E90004BFF34F8FBFF36F8F224AC2F8D1 -:100900008410BFF34F8F536923F480335361BFF3D7 -:100910004F8FD2F8803043F6E076C3F3C905C3F3B6 -:100920004E335B0103EA060C29464CEA8177013914 -:10093000C2F87472F9D2203B13F1200FF2D1BFF349 -:100940004F8FBFF36F8FBFF34F8FBFF36F8F53691D -:1009500023F4003353610023C2F85032BFF34F8FAA -:10096000BFF36F8F202383F31188854680F30888B7 -:100970002047F8BD0000020820000208FFFF010820 -:10098000002200200044025800ED00E02DE9F04F65 -:1009900093B0B44B2022FF2100900AA89D6801F07B -:1009A000A5F9B14A1378A3B90121B0481170C36009 -:1009B000202383F31188C3680BB105F0DFFD00230A -:1009C000AB4A4FF47A71A94805F09CFD002383F3EC -:1009D0001188009B13B1A74B009A1A60A64A13789E -:1009E000032B03D000231370A24A53604FF0000A78 -:1009F000009CD3465646D146012001F03DF924B172 -:100A00009C4B1B68002B00F02682002001F04AF866 -:100A10000390039B002BF2DB012001F023F9039BE1 -:100A2000213B1F2BE8D801A252F823F0AD0A0008A1 -:100A3000D50A0008690B0008F9090008F90900083F -:100A4000F9090008FB0B0008CB0D0008E50C0008B5 -:100A5000470D00086F0D0008950D0008F909000802 -:100A6000A70D0008F9090008190E00084D0B000831 -:100A7000F90900085D0E0008B90A00084D0B0008CE -:100A8000F9090008470D0008F9090008F9090008EC -:100A9000F9090008F9090008F9090008F90900082E -:100AA000F9090008F9090008690B00080220FFF79E -:100AB00059FE002840F0F981009B022105A8BAF1F7 -:100AC000000F08BF1C4641F21233ADF8143001F09C -:100AD00007F891E74FF47A7000F0E4FF071EEBDBB4 -:100AE0000220FFF73FFE0028E6D0013F052F00F26D -:100AF000DE81DFE807F0030A0D1013360523042119 -:100B000005A8059300F0ECFF17E004215548F9E72C -:100B100004215A48F6E704215948F3E74FF01C082E -:100B2000404608F1040801F00DF80421059005A8DD -:100B300000F0D6FFB8F12C0FF2D101204FF00009E0 -:100B400000FA07F747EA0B0B5FFA8BFB01F01AF983 -:100B500026B10BF00B030B2B08BF0024FFF70AFE96 -:100B60004AE704214748CDE7002EA5D00BF00B0340 -:100B70000B2BA1D10220FFF7F5FD074600289BD0E3 -:100B80000120002600F0DCFF0220FFF73BFE5FFAA9 -:100B900086F8404600F0E4FF0446B0B103994046B1 -:100BA0000136A1F140025142514100F0E9FF002815 -:100BB000EDD1BA46044641F21213022105A83E4681 -:100BC000ADF8143000F08CFF16E725460120FFF742 -:100BD00019FE244B9B68AB4207D9284600F0B2FFB0 -:100BE000013040F067810435F3E70025224BBA4617 -:100BF0003E461D701F4B5D60A8E7002E3FF45CAFC2 -:100C00000BF00B030B2B7FF457AF0220FFF7FAFD1D -:100C1000322000F047FFB0F10008FFF64DAF18F0AA -:100C200003077FF449AF0F4A08EB0503926893422C -:100C30003FF642AFB8F5807F3FF73EAF124BB84565 -:100C4000019323DD4FF47A7000F02CFF0390039A98 -:100C5000002AFFF631AF039A0137019B03F8012BFD -:100C6000EDE700BF00220020F0230020D822002062 -:100C70008D070008F4230020EC220020042200202D -:100C8000082200200C220020F0220020C820FFF7BC -:100C900069FD074600283FF40FAF1F2D11D8C5F19D -:100CA00020020AAB25F0030084494245184428BFBE -:100CB0004246019200F0F4FF019AFF217F4801F0C3 -:100CC00015F84FEAA803C8F387027C492846019328 -:100CD00001F014F8064600283FF46DAF019B05EBC8 -:100CE000830533E70220FFF73DFD00283FF4E4AE23 -:100CF00000F064FF00283FF4DFAE0027B846704BD9 -:100D00009B68BB4218D91F2F11D80A9B01330ED004 -:100D100027F0030312AA134453F8203C05934046DE -:100D2000042205A9043701F041F98046E7E7384677 -:100D300000F008FF0590F2E7CDF81480042105A823 -:100D400000F0CEFE02E70023642104A8049300F023 -:100D5000BDFE00287FF4B0AE0220FFF703FD00289F -:100D60003FF4AAAE049800F01FFF0590E6E70023C9 -:100D7000642104A8049300F0A9FE00287FF49CAE2F -:100D80000220FFF7EFFC00283FF496AE049800F035 -:100D90000DFFEAE70220FFF7E5FC00283FF48CAEE8 -:100DA00000F01CFFE1E70220FFF7DCFC00283FF425 -:100DB00083AE05A9142000F017FF07460421049014 -:100DC00004A800F08DFE3946B9E7322000F06AFE33 -:100DD000071EFFF671AEBB077FF46EAE384A07EB15 -:100DE0000903926893423FF667AE0220FFF7BAFC10 -:100DF00000283FF461AE27F003074F44B9453FF4A4 -:100E0000A5AE484609F1040900F09CFE04210590B6 -:100E100005A800F065FEF1E74FF47A70FFF7A2FC39 -:100E200000283FF449AE00F0C9FE002844D00A9BD8 -:100E300001330BD008220AA9002000F05FFF002830 -:100E40003AD02022FF210AA800F050FFFFF792FCC1 -:100E50001C4805F0FBFA13B0BDE8F08F002E3FF4FC -:100E60002BAE0BF00B030B2B7FF426AE002364217B -:100E700005A8059300F02AFE074600287FF41CAE63 -:100E80000220FFF76FFC804600283FF415AEFFF705 -:100E900071FC41F2883005F0D9FA059800F0BAFFEC -:100EA00046463C4600F06EFFA6E506464EE64FF08D -:100EB000000901E6BA467EE637467CE6F0220020CD -:100EC00000220020A086010070470000704700004B -:100ED000704700002DE9F04100F5803704461646C2 -:100EE0003B7C5BB9C0681030204400F0D9FEE56857 -:100EF0003544B5F5004FE56002D816B1BDE8F08184 -:100F0000DEB905F07F0605F110000021C6F180066C -:100F10002044F6B232462E4400F0E8FEA06804F108 -:100F20001008324600F10060414600F5003005F03F -:100F3000EBFE30B901233B74E0E74FF40046354641 -:100F4000ECE7A26805F11001404632442144A2605A -:100F5000E268521BE26000F0A3FE0220BDE8F0410F -:100F600000F094BE183000F0E9BC000010B5044653 -:100F700007F064FD204610BD10B5044607F05EFD85 -:100F8000204610BDC3B280B2A3F14102052A02D8A7 -:100F9000373800B27047613B052B94BF5738303863 -:100FA000F7E70000F8B504461546084603220C4949 -:100FB00000F080FE014688B908346F1C15F9110055 -:100FC000FFF7E0FF064617F911000131FFF7DAFFDE -:100FD000102940EA061004F8010BEFD1F8BD00BF5C -:100FE000988B00082DE9F04FADF53F7D074641682D -:100FF00001222AA802F05EFE002840F08780064603 -:10100000824681461125DFF80C81DFF80CB101AB77 -:101010004FF4805241462AA802F0A8FF002875D15B -:10102000019AB2F5805F71D8002A65D00446019A12 -:101030009442ECD2282D0FD008DC132D2DD01E2D7C -:1010400039D0112D13D00134A4B2F0E7322D2DD0B8 -:10105000372D2FD02D2DF6D13B68121B08EB040144 -:1010600038461B692D259847BDF80440EBE7121B55 -:10107000022A09D9594608EB040000F01BFE18B9F2 -:1010800002342825A4B2DEE718F804303A2B3DD00C -:101090000A2B1CBFA1461325D5E718F804300A2BEC -:1010A00034D03A2B04BFA2463225CCE718F80430DE -:1010B000202BC8D0264618F804300A2B1AD1AAEBE8 -:1010C000090208EB090102A811254F2A28BF4F2267 -:1010D00007F04EFDA21B08EB060116A84F2A28BFF9 -:1010E0004F2207F045FD3B6816AA02A9DB68384687 -:1010F0009847A8E71E25A6E73B68384604491B69C0 -:10110000984701200DF53F7DBDE8F08F0020F9E7FD -:101110008A8C0008FC2300209C8B000800F1180139 -:1011200010B5044686B00846019100F0F1FB204658 -:10113000FFF758FF60B1019902A800F049FC1022A6 -:1011400004F1080102A807F09DFCB0FA80F0400904 -:1011500006B010BD70B504460025EEB2304600F072 -:10116000FFFC58B100213046013500F009FD08B9F7 -:10117000002070BD022000F089FDEEE72046FFF759 -:1011800031FF0028F4D004F58034207C80F0010089 -:10119000EFE70000F0B5C9B006F016F800F074FEF5 -:1011A00018B90025284649B0F0BD69462A4802F022 -:1011B0009FFF00284BD1294C204602F0C9FF284848 -:1011C00002F0C6FF274802F0C3FF2146224803F081 -:1011D0003BF80028E5D1702007F032FC064610B13C -:1011E000214B44600360336830469B68984705464E -:1011F00000282ED01A4F1948394603F025F8054625 -:101200000028CED1194807F01BFC044638B1184B12 -:101210004760036000F58033C0E902551D74236800 -:1012200020469B689847054628B10E490C4803F0B4 -:101230000BF80028B5D1336830465B6898471CB17D -:10124000236820465B68984700F006FEAAE7002561 -:10125000FAE70446EFE700BFA08B0008B08B000858 -:10126000C78B0008DD8B0008008C0008140001000B -:101270001C8C00082DE9F04FD44A8DB00B68D0F8D3 -:1012800004A001931A440368D14E1A44D1F81C906B -:10129000DFF8B4C3DFF8B4B3D0E90234634003EA43 -:1012A0000A03634013444A6802920AEB7363029C88 -:1012B000C84A2244C468224484688AEA04051D405E -:1012C000654015448A68039203EB3555039CC24A76 -:1012D0002244846822448AEA03042C4084EA0A04F3 -:1012E0001444CA6805EBF4340492164483EA0502F8 -:1012F000224056445A4032440E69059604EBB2220D -:10130000059FB64E3E441E4485EA040313406B40DD -:1013100033444E69069602EB7363069FB04E3E441B -:101320002E4484EA02051D40654035448E690796C7 -:1013300003EB3555079FAB4E3E44264482EA030437 -:101340002C4054403444A84E4E4405EBF43416442B -:1013500083EA050222405A4032440E6A089604EBA2 -:10136000B222089FA14E3E441E4485EA0403134066 -:101370006B4033444E6A099602EB7363099F9C4E9F -:10138000D1F830E03E44D1F83880F3442E4484EA6A -:1013900002051D40654035448E6AA6F5244703EBDF -:1013A00035550A964F3F274482EA03042C405440A7 -:1013B0003C44CF6A0B9705EBF4340B9E8D4F3744BA -:1013C000029E174483EA050222405A403A448A4F5B -:1013D000774404EBB2221F4485EA040313406B40B8 -:1013E0003B444F6BBC4402EB7363654484EA020CDC -:1013F0000CEA030C8CEA040C6544DFF854C2C444C4 -:1014000003EB3555A44482EA03042C405440644461 -:10141000D1F83CC0794905EBF4346144114483EAC6 -:10142000050222405A400A44754904EBB222314475 -:10143000079E194484EA02032B4063400B44714920 -:1014400002EBF36331440B9E0D4482EA0301214019 -:10145000514029446C4D03EBF1513544019E254424 -:1014600083EA010414405C402C44684D01EBB44411 -:101470003544069E154481EA04021A404A402A4433 -:10148000634D04EB323235440A9E1D4484EA020364 -:101490000B4063402B445F4D02EBF3633544059EE4 -:1014A0000D4482EA03012140514029445A4D03EB87 -:1014B000F1516544254483EA010414405C402C4406 -:1014C000564D01EBB4443544099E154481EA0402AB -:1014D0001A404A402A44524D04EB32323544049EAD -:1014E0001D4484EA02030B4063402B444D4D02EB44 -:1014F000F36345440D4482EA0301214051402944ED -:10150000494D03EBF1513544089E2C4483EA010513 -:1015100015405D402C44454D01EBB4443544039ED9 -:101520002A4481EA04051D404D402A44404D04EB05 -:1015300032323D442B4484EA020593440D40654019 -:101540002B443C4D02EBF3633544069E294482EA6A -:101550000305254055402944374D03EBF1514D44D7 -:101560002C4483EA010515405D40254401EBB54557 -:1015700081EA050404EA03024A405A44A6F5B82B5E -:10158000089E05EB3232ABF2BE6B54405B44234401 -:101590002A4C344402EB33730B9E0C4485EA02015F -:1015A00059402144264C344403EB7151029E25449A -:1015B00082EA03044C402544224C444401EB354567 -:1015C000144483EA01026A40224443E078A46AD7C3 -:1015D000EECEBDC156B7C7E8DB702024AF0F7CF557 -:1015E0002AC68747134630A8019546FDD8988069DA -:1015F000AFF7448BBED75C892211906B2108B449A8 -:1016000062251EF640B340C0515A5E26AAC7B6E90D -:101610005D102FD65314440281E6A1D8C8FBD3E74E -:10162000E6CDE121D60737C3870DD5F4ED145A4531 -:1016300005E9E3A9F8A3EFFCD9026F6781F671878A -:1016400022619D6D0C38E5FD937198FD8A4C2A8DC1 -:101650008E4379A6934C344405EB7222059E1C44BC -:1016600081EA0503534023448F4C344402EB337327 -:101670000A9E0C4485EA0201594021448B4C4C449B -:1016800003EB7151254482EA03044C402C44884DFD -:10169000354401EB3444019E154483EA0102624063 -:1016A0002A44844D3D4404EB72221D4481EA040324 -:1016B00053402B44804D354402EB3373049E294440 -:1016C00084EA02055D4029447C4D354403EB7151A9 -:1016D000079E254482EA03044C402C44784D35444F -:1016E00001EB3444099E2A4483EA01056540154410 -:1016F000744A324404EB7525039E134481EA0402C4 -:101700006A401A44704B734405EB32720B4484EA0E -:101710000501514019446D4B634402EB71511C4467 -:1017200085EA02034B401C44694B334401EB3444CB -:10173000019E1D4482EA010363402B44654D04EB86 -:1017400073233544069E154463EA010262402A442D -:10175000614D03EBB2624D4462EA040929445F4DD6 -:1017600089EA0309454449442C445D4D02EBB151DB -:101770003544049E61EA03081D4488EA0208444493 -:1017800001EB744464EA02034B402B44554D04EBD7 -:10179000F323754463EA010E15448EEA040E0EEB42 -:1017A0000502514D03EBB262354462EA040E29444E -:1017B0000A9D8EEA030EA5F580164C4D7144A6F6DF -:1017C000833602EBB151264461EA030454403444A9 -:1017D000029E01EB7444354464EA02061D444E4007 -:1017E0007319089E424D04EBF323354463EA010666 -:1017F0001544664072193F4D03EBB262654462EADC -:10180000040629443C4D5E403144079E02EBB15131 -:10181000354461EA03062C44384D56403D44344477 -:10182000059E1D4401EB744464EA02034B402B44C3 -:10183000334D04EBF32335440B9E154463EA010258 -:1018400062402A442F4D03EBB2623544039E0D449F -:1018500062EA0401594029442B4D02EBB151354451 -:101860002A4E254461EA030454402C44099D01EBAF -:1018700074442E4464EA02051E4485EA01039D195E -:1018800003681A440AEB040303EBF5230260436088 -:1018900083681C44C36819448460C1600DB0BDE80E -:1018A000F08F00BF44EABEA4A9CFDE4B604BBBF66D -:1018B00070BCBFBEC67E9B28FA27A1EA8530EFD454 -:1018C000051D880439D0D4D9E599DBE6F87CA21F40 -:1018D0006556ACC4442229F497FF2A43A72394AB4E -:1018E00039A093FCC3595B6592CC0C8FD15D848584 -:1018F0004F7EA86FE0E62CFE144301A3A111084E11 -:10190000827E53F735F23ABDBBD2D72A91D386EB0C -:10191000094B036003F18833436003F12943A3F5C6 -:101920009613A3F68B638360A3F18833C36000230F -:10193000C0E90433704700BF012345672DE9F84330 -:101940001446026905460E46E300C2F3C50800F1DD -:1019500018079B18036122BF43690133436112F4E6 -:10196000FC7F436903EB5473436114D0C8F1400911 -:1019700007EB08004C4504D22246BDE8F84307F0C7 -:1019800091B8403C4A464E4407F08CF844443946EE -:101990002846FFF76FFCA04606EB0409B8F13F0F9D -:1019A000A9EB08010AD94022384607F07BF83946EE -:1019B0002846A8F14008FFF75DFCEFE7A1096FF0AA -:1019C0003F02384602FB014206EB8111D5E70000D9 -:1019D00070B50B6901F1180506460C46C3F3C50343 -:1019E000EA18501C8022EA54C3F13F02072A1FD88C -:1019F000002100F07BF929462046FFF73BFC382206 -:101A00000021284600F072F9236929462046236503 -:101A100063696365FFF72EFC21461022304607F00C -:101A200041F8204658220021BDE8704000F05EB920 -:101A3000C3F137020021E5E72DE9F84F4FF47A733F -:101A400006460D46002402FB03F7DFF85080DFF85E -:101A5000509098F900305FFA84FA5A1C01D0A342E2 -:101A600010D159F824002A4631460368D3F820B033 -:101A70003B46D847854205D1074B012083F800A09B -:101A8000BDE8F88F0134042CE3D14FF4FA7004F070 -:101A9000DDFC0020F4E700BF4034002010220020CD -:101AA00014220020002307B5024601210DF1070092 -:101AB0008DF80730FFF7C0FF20B19DF8070003B095 -:101AC0005DF804FB4FF0FF30F9E700000A460421FF -:101AD00008B5FFF7B1FF80F00100C0B2404208BD79 -:101AE000074B0A4630B41978064B53F8214001469B -:101AF00023682046DD69044BAC4630BC604700BF1C -:101B00004034002014220020A086010070B50A4E47 -:101B100000240A4D05F096F8308028683388834207 -:101B200008D905F08BF82B6804440133B4F5003F65 -:101B30002B60F2D370BD00BF42340020FC33002084 -:101B400005F05EB900F1006000F5003000687047F4 -:101B500000F10060920000F5003005F0D5B80000FB -:101B6000054B1A68054B1B889B1A834202D9104407 -:101B700005F064B800207047FC3300204234002098 -:101B800038B50446074D29B128682044BDE83840DF -:101B900005F06CB82868204405F056F80028F3D00A -:101BA00038BD00BFFC3300200020704700F1FF501B -:101BB00000F58F10D0F8000870470000064991F832 -:101BC000243033B100230822086A81F82430FFF75B -:101BD000BFBF0120704700BF00340020014B1868D0 -:101BE000704700BF0010005C1B4B0246F0B5186840 -:101BF0001A4BC0F30B06000C1F885C68BE4293F9B9 -:101C0000085003D09F89BE4203D10C335C6893F91E -:101C100008500426124B1F880433874208BF13F96B -:101C2000025C013EF7D1013A013C0B460A44934263 -:101C300007D214F9016F581C2EB1034600F8016C4D -:101C4000F5E7184605E02C2482421C7001D9981C47 -:101C50005D70401AF0BD00BF0010005C242200201F -:101C60004C8C0008022803D1024B4FF080529A613D -:101C7000704700BF00100258022803D1024B4FF4F6 -:101C800080529A61704700BF00100258022804D1A8 -:101C9000024A536983F4805353617047001002581D -:101CA000002310B5934203D0CC5CC4540133F9E750 -:101CB00010BD0000013810B510F9013F3BB191F99A -:101CC00000409C4203D11AB10131013AF4E71AB144 -:101CD00091F90020981A10BD1046FCE70346024611 -:101CE000D01A12F9011B0029FAD1704702440346A9 -:101CF000934202D003F8011BFAE770472DE9F8433D -:101D00001F4D14460746884695F8242052BBDFF83D -:101D100070909CB395F824302BB92022FF214846BF -:101D20002F62FFF7E3FF95F824004146C0F1080257 -:101D300005EB8000A24228BF2246D6B29200FFF7F0 -:101D4000AFFF95F82430A41B17441E449044E4B21E -:101D5000F6B2082E85F82460DBD1FFF72FFF0028AC -:101D6000D7D108E02B6A03EB82038342CFD0FFF781 -:101D700025FF0028CBD10020BDE8F8830120FBE738 -:101D800000340020024B1A78024B1A70704700BFD3 -:101D90004034002010220020F8B5184C184803F0F9 -:101DA000B9FC2146164803F0E1FC24681548D4F834 -:101DB0009020154ED2F80438144D43F00203104F12 -:101DC000C2F8043804F042FB2046114903F0DCFD60 -:101DD000D4F890200424D2F8043823F00203C2F887 -:101DE00004384FF4E133336055F8040BB84202D0A5 -:101DF000314603F0EDFB013CF6D1F8BD54930008E9 -:101E0000504A002040420F002834002014220020B5 -:101E10005C9300080C4B70B50C4D04461E780C4BBF -:101E200055F826209A420DD00A4B00211822184658 -:101E3000FFF75CFF0460014655F82600BDE87040DE -:101E400003F0C6BB70BD00BF403400201422002048 -:101E5000504A00202834002010B5084C01220849BF -:101E6000002001F003FF23783BB1064803F02CFB70 -:101E7000044803F05FFB0023237010BD44340020AE -:101E80005C8C0008A03600201E482DE9F041D0F8F7 -:101E9000503233B901224FF4805100F5147005F02F -:101EA000D5F9194E33780BB1FFF7D6FF0324174F3E -:101EB0004FF00008134D2846144987F8058003F0B9 -:101EC0002BFB284603F054F948B1013C284603F0A7 -:101ED00031FB14F0FF04EED1204634700FE00C49C2 -:101EE00001220C4801F0C2FE014618B1284603F059 -:101EF000EBFAEAE7084800F011F801203070BDE87D -:101F0000F08100BFA0360020443400203C22002095 -:101F10005C8C000848340020608C00080FB400205E -:101F200004B0704700B59BB0EFF3098168226846A2 -:101F3000FFF7B6FEEFF30583014B9B6BFEE700BF97 -:101F400000ED00E008B5FFF7EDFF000000B59BB025 -:101F5000EFF3098168226846FFF7A2FEEFF30583DD -:101F6000014B5B6BFEE700BF00ED00E0FEE7000009 -:101F700000B595B0132101A805F006FA9DF84F3081 -:101F80007BB10023132101A88DF84F3005F0F6F93D -:101F9000054BD3F8002882F30888D3F80438984713 -:101FA000FEE715B05DF804FB0090F01F30B50A4461 -:101FB000084D91420DD011F8013B5840082340F3E1 -:101FC0000004013B2C4013F0FF0384EA5000F6D1DB -:101FD000EFE730BD2083B8ED006870470346006826 -:101FE000596870470B0A017043700B0C090E83701F -:101FF000C1707047110A027003714170110C120E0A -:102000008170C2701A0A42711A0C1B0E8271C37160 -:1020100070470000024400F8011B9042FBD170475A -:10202000024410B510F8013B11F8014B9042A3EBAC -:10203000040301D0002BF5D0184610BDC36A023945 -:10204000023B8B4283BF4389006C01FB03000020ED -:1020500070470000C2F307238A76CB760378032B00 -:1020600001BF120C0A75120A4A75704700F10B0184 -:102070000022D30143EA520310F8012B52FA83F3F2 -:102080008842DAB2F5D110467047000010B54178A9 -:1020900004460020013102464901022A16BFA35C12 -:1020A000032203EBC03302F101021EBF9BB203EB1C -:1020B000500398B29142F0D810BD000002684AB1B6 -:1020C000134613F8011B1F290DD93A29F9D1911C88 -:1020D0008B4202D04FF0FF3070471278302AF9D18E -:1020E000036000207047014B187870479436002039 -:1020F00038B50D46044618B9092000232B6038BDB9 -:102100000368002BF8D01A78002AF5D08188DA8885 -:102110009142F1D1587804F0B3FA10F00100EBD1FC -:102120002368EBE738B50D4640F25231144602F011 -:1021300073F9FF2806D9012C0AD9030A6870022016 -:102140002B7038BD0028FCD024B128700120F8E79E -:102150000020F6E72046F4E72DE9F8430026D0F802 -:10216000008007460C468E76836B3BB398F80030B0 -:10217000042B4BD1D8F8108040273546334698F8C9 -:10218000232096421CD3002B40F0BF80002D00F08E -:10219000BC8000232544AB76637398F80430237326 -:1021A000DB0630D408F13800FFF718FFC4E900015E -:1021B000B8F80C306381B8F80E302381BDE8F8839D -:1021C000B7F5187F80F0A180FA0606F1010608BF76 -:1021D000023738F8070002372BB900F5205292B2C7 -:1021E000B2F5006F0DD305F11A01C5F1FF0240EA07 -:1021F00003402144FFF796FF002800F08680054445 -:1022000000200346BBE700200146CFE7C36C013343 -:102210005DD1FA6B00232E26551E184615F8011FB6 -:10222000013020290CD0052908BFE521092804D157 -:102230000B2B9EBFE71801337E73E71801337973C8 -:102240000B28EBD1E11800204873A17E00294CD166 -:10225000002B41D06FF00C0604F10D000825361B51 -:10226000331810F8011B002939D02E298BB249D020 -:10227000A3F14101192903D8117B0D4200D020336D -:102280000373EDE7B9F1000F05D100F520539BB2C0 -:10229000B3F5006F0BD305F11A01C5F1FF0240EA57 -:1022A00009402144FFF73EFFA0B10544002002365B -:1022B0008146D8F80C30985B0028E3D1B9F1000FC3 -:1022C0004FF0000318BF00252544AB76A1E7B146C7 -:1022D0003546EEE70546F1E73F23A3760123234485 -:1022E00000219976137B03B96373D37A02F11C0042 -:1022F00023730023FFF770FE20606360D38A63813D -:10230000138B5AE710250B46BAE73F230125A37626 -:102310003FE7000038B50546002435F8020B08B940 -:10232000204638BD02F0ACF86308C2B203EBC433F8 -:1023300012FA83F39AB2C0F3072303EB520303EBC1 -:10234000C2339CB2E9E7000001380A4411F8013BAE -:10235000914200F8013FF9D17047000037B5C378CA -:1023600004461BB90025284603B030BD00F14C01DE -:10237000826C01234078019104F0A8F9054680B9E8 -:10238000A36BE070A06C226BC31A9342EAD2A378CD -:102390000199022BE6D102440123607804F096F9FA -:1023A000E1E70125DFE7000038B5836C05460C4600 -:1023B0008B4210D0FFF7D2FF60B92246012305F10E -:1023C0004C01687804F05EF900281CBF4FF0FF3420 -:1023D0000120AC6438BD0020FCE7000038B50023C4 -:1023E0000446C3704FF0FF338364FFF7DDFF00281E -:1023F0003FD1B4F84A524AF655239D4206D10B22EA -:102400001E4904F14C00FFF70BFEA0B394F84C30CA -:10241000EB2B03D01833DBB2012B23D84AF655231C -:102420009D4206D10822164904F19E00FFF7F8FDEF -:10243000F0B1B4F857305A1E1A4213D1B3F5007FE9 -:1024400010D194F8590068B1431E18400AD194F88D -:102450005C30013B012B05D8B4F85D3013B1B4F802 -:1024600062302BB94AF6552085420CBF022003206A -:1024700038BD0420FCE70120FAE700BF8C8C00087F -:10248000988C000802392DE9F04701F007044FF05D -:10249000010A466C05460AFA04F41746984606EB0C -:1024A0001136C1F3C809E4B2314628460136FFF7B8 -:1024B0007BFF18B10120BDE8F087994605EB0902C2 -:1024C00092F84C30234214BF01210021414513D022 -:1024D0006340013F82F84C3085F803A0EBD06400E4 -:1024E00014F0FF04EAD109F1010301244FF00009BF -:1024F000B3F5007FE1D1D7E70220DCE701290246EE -:10250000F8B50C4640F28C800668F36A8B4240F2C4 -:1025100087803378013B032B00F28280DFE803F0F1 -:102520000229384B04EB5405B16B304601EB5521C1 -:10253000FFF73AFF10B14FF0FF30F8BD6F1CC5F345 -:102540000805B16B3046354401EB572195F84C50E6 -:10255000FFF72AFF0028EED1C7F30807E3073E4440 -:1025600096F84C0045EA00204CBF0009C0F30B0070 -:10257000E3E7B16B304601EB1421FFF715FF0028AC -:10258000D9D1640004F4FF742644B6F84C00D4E7B3 -:10259000B16B304601EBD411FFF706FF0028CAD11A -:1025A000A40006F14C0004F4FE742044FFF714FD6F -:1025B00020F07040C1E7D0E90430D57953EA00013A -:1025C00001D0916801B95DBB9168022DA4EB0101B6 -:1025D0000DD1013B728940F1FF305B0A43EAC053E1 -:1025E000B3FBF2F399421BD81CD0601CA5E7032D66 -:1025F00002D193698B42F8D8D3699BB9B16B30464D -:1026000001EBD411FFF7D0FE002894D1A0004C3686 -:1026100000F4FE703044FFF7DFFC20F000408CE750 -:1026200001208AE76FF0004087E70000F8B50668F0 -:1026300004460D463378042B0CBF4FF080524FF404 -:1026400000128A4201D80220F8BDCA06FBD1826876 -:102650000163D2B9022B13D83389B3EB551FF2D9DA -:10266000F36BA363A36B6263002BECD003EB5523E6 -:102670004C36C5F308050020A3633544E563E3E762 -:10268000F36BC271002BE7D01A4677897F02BD42F7 -:10269000114604D23046FFF7D1FCA063E2E72046A2 -:1026A000FFF72CFF431C024606D00128CBD9F36A62 -:1026B0008342C8D9ED1BEAE70120C5E701292DE9CE -:1026C000F04706460C46174608D9C36A8B4205D91F -:1026D0000378022B62D003D8012B22D0022552E0CE -:1026E000033B012BFAD8816B01EBD411FFF75CFEA1 -:1026F0000546002847D1A40006F14C0304F4FE74FB -:102700001C443378042B07D0204627F07047FFF78E -:1027100063FC00F07040074339462046FFF762FC37 -:102720002FE001EB5108816B01EB5821FFF73CFED4 -:10273000054640BB14F0010406F14C0908F1010AFA -:10274000C8F3080808BFFBB230461FBF19F80830AD -:1027500003F00F023B0103F0F00318BF134309F825 -:1027600008300123B16BF37001EB5A21FFF71CFE17 -:10277000054640B9CAF3080A44B1C7F3071709F878 -:102780000A700123F3702846BDE8F08719F80A3073 -:10279000C7F3032723F00F031F43F0E7816B01EB1F -:1027A0001421FFF701FE05460028ECD1640006F174 -:1027B0004C0304F4FF741F551919C7F307274F7012 -:1027C000DFE70000F8B504460E461746E3690BB98B -:1027D0001846F8BD012BA6EB0305206814BFAA1C00 -:1027E0003A46691CFFF76AFF0028F2D1E369013B12 -:1027F000E361EBE701292DE9F84306460C4617464D -:10280000056802D80220BDE8F883EB6A8B42F9D94B -:102810007AB9A14621463046A046FFF76FFE04462E -:10282000B0B92B78042B02D1002F43D1F7710020CF -:10283000E9E72B78042B02D1C379022BE9D04FF0C2 -:10284000FF3239462846FFF739FF0028E1D0DAE7A2 -:102850000128D7D0421C01D10120D4E72B78042BCA -:1028600019D1EA6AAB69023A93421CD308F101021A -:10287000A2420CD02B78042B08D10023A2EB090232 -:1028800049462846FFF7FEFD0028BCD1A146EB6A69 -:10289000A342BFD8C5E7002241462846FFF70EFFF6 -:1028A0000028DED0AFE70133AB612B7943F00103A1 -:1028B0002B71DBE7F3798BB9B468BC4202D10223F8 -:1028C000F371B4E721463046FFF718FE012899D985 -:1028D000431CC1D001348442EFD0A8E7032BA6D11A -:1028E000B368BB42A3D8B2691344BB429FD3E6E7A7 -:1028F00070B5C3790446032B06D181688369CD186E -:10290000A94203D10023E371002070BD4E1C206852 -:102910003246FFF7D3FE0028F7D13146F0E700003A -:102920002DE9F74306460191FFF718FD04460028FC -:1029300049D106F14C09019930464FF40072FFF776 -:102940007DFB2146B06407464846FFF763FB748968 -:102950006402B4F5006F28BF4FF40064B4F5007F43 -:102960002FD9204603F0EAFE804630B100212246EE -:10297000FFF750FB640A0D4609E06408EEE72346C2 -:102980007A194146707803F0A1FE18B9254473897D -:102990009D42F4D3404603F0D3FE7089401B18BF1C -:1029A000012003B0BDE8F083013573899D42F4D264 -:1029B00001237A194946707803F088FE0028F3D085 -:1029C000EBE70025F1E70120EBE70000F8B504464E -:1029D000FFF7C4FC0546002842D12378032B37D1EA -:1029E0002779012F34D104F14C06552301464FF4C9 -:1029F00000723046FFF70EFB84F84A32AA234122C8 -:102A0000722104F50D7084F84B32522384F84F2064 -:102A100084F84C3084F84D30612384F8301284F807 -:102A20004E3084F8333284F8311284F83222A169AE -:102A3000FFF7D8FA616904F50E70FFF7D3FA626BFD -:102A40003B46314601326078A26403F03FFE2571B7 -:102A500000226078114603F05DFE003818BF0120A7 -:102A6000F8BD000000232DE9F0430B6085B00F4650 -:102A70001546FFF723FB061EC0F2B281804B53F8C8 -:102A80002640002C00F0AE813C6005F0FE05237866 -:102A90006BB1607803F0F4FDC70708D41DB110F0E6 -:102AA000040500D00A25284605B0BDE8F0830023C0 -:102AB000F0B22370607003F0D1FDC10700F1948182 -:102AC0000DB14207EED400212046FFF787FC022813 -:102AD00040F099806E4604F2122304F252213246ED -:102AE00018461033FFF778FA42F8040B8B42F7D1FF -:102AF000002556F8041B00297DD02046FFF76EFC08 -:102B0000012879D80128A26C40F0C08004F1570355 -:102B100004F18C0113F8015B002D7BD18B42F9D1BC -:102B2000B4F8B430B3F5807F74D194F8B830092B81 -:102B300070D104F19400FFF751FA4FF0FF331718EA -:102B400041F10001BB4275EB010363D304F1A00026 -:102B5000FFF742FA94F8BA302063012BA37059D1E1 -:102B600094F8B99003FA09F91FFA89F36381002BED -:102B700050D0444B04F1A800FFF72EFA06469842C5 -:102B800048D8831C626304F1A400E362FFF724FACF -:102B900000EB020804F19C00C4F84080FFF71CFA27 -:102BA00010441FFA89F2A06306FB02F313EB08033B -:102BB00045EB05029F4271EB02032BD32E4604F135 -:102BC000AC00FFF709FAE06365B96389B34221D924 -:102BD000E16B2046FFF732FA81192046FFF7E4FB4C -:102BE00098B90136631993F84C30812B14D02035F5 -:102BF000C5F30805E8E703200135042D7FF479AF1C -:102C0000042807D101E0042801D101254BE7012860 -:102C10007FF678AF0D2546E705F1140004F14C0668 -:102C20003044FFF7D9F901280546F3D9E36A834216 -:102C3000F0D96189821E236C02FB01336364A16BAE -:102C4000204601EBD511FFF7AFFB0028DDD105F0E1 -:102C50007F0006EB8000FFF7BFF9431C03D001356E -:102C6000A842ECD0D6E70425C4E90500064A257041 -:102C700000251388E56101339BB21380E38012E7DE -:102C800098360020FDFFFF7F9C360020B4F85730B7 -:102C9000B3F5007FBED1B4F8626026B904F17000CC -:102CA000FFF79AF9064694F85C302663591EA37024 -:102CB0000129AFD894F859506581002DAAD0691E1A -:102CC0002942A7D1B4F85D8018F00F0FA4F808804E -:102CD000A0D1B4F85F0018B904F16C00FFF77CF9DB -:102CE000B4F85A10002995D006FB03FE01EB181C1E -:102CF000F44460458ED3A0EB0C00A842B0FBF5F382 -:102D000088D33E48834285D84FF6F57083426DD90B -:102D100003259F1C114402EB0C03032DE762626341 -:102D2000A16323644CD1B4F8763053EA08037FF4EE -:102D300071AFBB0004F17800FFF74EF9E06303F2D6 -:102D4000FF13B6EB532FFFF465AF4FF0FF33032DA6 -:102D5000C4E905334FF08003237187D1B4F87C3088 -:102D6000012B83D1511C2046FFF71EFB00287FF466 -:102D70007DAFB4F84A224AF6552320719A427FF477 -:102D800075AF1F4B04F14C00FFF726F998427FF412 -:102D90006DAF03F1FF5304F50C70FFF71DF903F558 -:102DA0000053203398427FF461AF04F50D70FFF7B4 -:102DB00013F9A06104F50E70FFF70EF9606155E795 -:102DC000B8F1000F3FF426AF7144022D4FEA4703DC -:102DD000E1631EBFD91907F0010303EB5103AEE70E -:102DE0000B2560E60C255EE603255CE640F6F575EE -:102DF000AB428CBF022501258BE700BFF5FFFF0F1B -:102E0000525261412DE9F84F07460568884649B995 -:102E10006E69C6B1EB6AB34298BF0126AB69A3B92C -:102E2000002405E0FFF76AFB0128044603D80124CB -:102E30002046BDE8F88F421C00F0D280EB6A834246 -:102E4000F6D84646EAE70126E8E72A78EB6A042A3C -:102E500040F08380A6F1020A023B4FF0010B9A4535 -:102E600028BF4FF0000AD146696C284601EB1931A2 -:102E7000FFF79AFA00283BD109F00703EA6AC9F381 -:102E8000C8010BFA03F3901EDBB26A184C4609F135 -:102E9000010992F84C20814502EA030233BF5B002E -:102EA00000234FF40071DBB228BF9946B2B9023457 -:102EB000631E0333BCD80123214628461A46FFF778 -:102EC000E1FA0228B3D0012800F08A80B8F1000F9F -:102ED00013D10223FB710028A9D130E0CA450AD0E2 -:102EE000002BD2D10131B1F5007FBDD20123CCE757 -:102EF0004FF0FF34DCE70024DAE7FB79022B07D13F -:102F0000731CA342E7D0BB68F31ABB610323FB71B8 -:102F100008F10102FB69A24205D113B10133FB6143 -:102F2000D9E70223FBE70BB90123FB6122464146A7 -:102F30003846FFF747FC00284FD10123FB61EA6ABE -:102F4000AB69023A6C6193429CBF03F1FF33AB6102 -:102F50002B7943F001032B716AE7464514D1741CA9 -:102F60003846A34298BF02242146FFF7C7FA01283A -:102F70003FF45DAF431C33D0E0B16B69012B03D943 -:102F8000EA6A934238BF1E4634460134EB6AA342D4 -:102F900003D8012E7FF644AF022421463846FFF7BE -:102FA000ADFA48B101283FF442AF013018D0B44225 -:102FB000EBD135E7002CE7D04FF0FF322146284611 -:102FC000FFF77CFB48B9B8F1000FB8D02246414664 -:102FD0002846FFF773FB0028B1D001287FF427AF04 -:102FE0004FF0FF3424E700002DE9F843066804465B -:102FF000076B894633782037042B0CBF4FF0805382 -:103000004FF40013BB429CBF00238363836B73B1F7 -:10301000C7F30808B8F1000F3CD10133416B83635B -:1030200039B93389B3EB571F34D80023A363042085 -:103030000AE07389013B13EA57232BD1FFF75EFAAD -:103040000128054602D80220BDE8F883421C01D1C0 -:103050000120F9E7F36A834216D8B9F1000FE4D0F2 -:10306000616B2046FFF7CEFE0546C8B10128EAD0C5 -:10307000431CEDD001463046FFF752FC0028E7D153 -:10308000E37943F00403E371294630466563FEF7B4 -:10309000D5FFA0634C36002027634644E663D3E7A0 -:1030A0000720D1E72DE9F04105460068A96B0669C4 -:1030B000FFF77AF9044620B9E96B0B78852B03D02A -:1030C00002242046BDE8F08120223046FFF73CF97B -:1030D000777801377F01A7F16003B3F5007FEFD860 -:1030E00021462846FFF780FF04280446E8D0002840 -:1030F000E7D1A96B2868FFF757F904460028E0D10B -:10310000E96B0B78C02BDBD12022B018FFF71CF93C -:1031100096F823300F222C33B3FBF2F3B7EB431FA7 -:10312000CED34FF0400800212846FFF75DFF04286A -:103130000446C5D00028C4D1A96B2868FFF734F92C -:1031400004460028BDD1E96B0B78C12BB8D1B8F586 -:10315000187F04D2202206EB0800FFF7F5F808F1EB -:1031600020084745DFD8B8F5187FAAD83046FEF7C3 -:103170008DFF73888342A4D0A2E700000B68002271 -:1031800010B5036004460B6A83604B6AC261C37169 -:1031900023F0FF03896AC0E90432C164FFF746FAED -:1031A00020B92046BDE81040FFF77CBF10BD0000ED -:1031B000F8B50E46002104460768FFF737FA98B9BC -:1031C0000546A16B3846FFF7EFF868B93A78E36B2C -:1031D000042A1B780CD11B060ED50546012120467A -:1031E000FFF702FF0028ECD0042808BF072006E004 -:1031F000E52B01D0002BF0D10135B542EED1F8BD61 -:1032000003682DE9F0411E6905464FF0010830467C -:10321000FEF73CFFB070000A7778F0702846E96C42 -:10322000FFF704FA04462CB1022C28BF0224E0B2B6 -:10323000BDE8F081A96B2868FFF7B6F804460028BE -:10324000F2D120223146E86BFFF77EF82B6883F835 -:103250000380002FE8D021462846FFF7C5FE203620 -:103260000446013FDFE70000C16C4B1C2DE9F04133 -:1032700004460568066B1FD1E5274FF00108A16BD6 -:103280002846FFF791F898B92A78E36B042A09BF1A -:103290001A781F7002F07F021A7085F80380236B82 -:1032A000B3420DD200212046FFF79EFE0028E6D053 -:1032B000042808BF022003E0FFF7B8F90028DBD09C -:1032C000BDE8F0812DE9F8434FF0FF080646076896 -:1032D000042445464FF6FF79B16B11B9002C73D029 -:1032E00063E03846FFF760F8044600285DD1F06BD4 -:1032F0000378002B6ED03A78042A11D1852B4DD15A -:10330000336B3046F364FFF7CDFE044600284CD102 -:103310003B691B7903F03F03B3712046BDE8F88396 -:10332000C27AE52B02F03F02B27143D02E2B41D07E -:1033300022F0200108293DD00F2A40D1590637D567 -:1033400003F0BF05336B90F80D80F364437B434576 -:1033500030D1428B72BB03780D21FC6823F040030F -:10336000DFF874E0013B4B4301211EF801CB30F83C -:103370000CC009B3FF2B1DD824F813C061460133DC -:1033800001320D2AF1D10278520605D521B1FF2B69 -:1033900010D8002224F81320013DEDB20021304660 -:1033A000FFF722FE0446002896D00023B363B4E75B -:1033B000AB42CBD0FF25F1E7CC45E1D0FAE72DB900 -:1033C000FEF754FE404501D10024A6E74FF0FF333D -:1033D000F364A2E70424E8E7348D00082DE9F04FF8 -:1033E000002187B00446D0F80090FFF71FF980460F -:1033F00070B999F80030042B33D1D9F80C00FEF7DE -:1034000089FF07462046FFF75DFF054620B180464D -:10341000404607B0BDE8F08FD9F810309A8CBA4218 -:10342000F0D193F823B040265D4506D1D9F80C3091 -:1034300033F81530002BE5D1EAE7F106D9F8103062 -:1034400008BF0236985B01F01BF8D9F80C308246B1 -:1034500033F8150001F014F88245D3D10236013556 -:10346000E2E74FF0FF0A4FF0FF3B5546C4F84CB07F -:10347000A16B4846FEF798FF00285CD1E66B3778D1 -:10348000002F77D0F27AE52F02F03F03A37103D02B -:10349000120704D50F2B04D0C4F84CB04FE00F2B0B -:1034A00054D194F84B3058063FD4790645D5236B58 -:1034B00007F0BF0796F80DA0E364737B53453ED138 -:1034C000738B002B3BD135780121D9F80C3005F0F6 -:1034D0003F0501930D23013D5D43284B13F8012B5C -:1034E000B25A71B3FF2D059329D81046049200F00B -:1034F000C7FF6B1C03900293019B33F8150000F08B -:10350000BFFF039981421AD1049A029D1146059B7F -:103510001B4A9342E2D133785A0604D519B1019B74 -:1035200033F815305BB97D1EEDB200212046FFF760 -:103530005BFD00289CD080466AE7BD42BDD0FF25D8 -:10354000F3E74FF6FF708242E2D0F8E72DB930463C -:10355000FEF78CFD50453FF45BAF94F84B30DB0732 -:103560009AD40B2204F140013046FEF759FD0028A1 -:1035700092D14DE74FF004084AE700BF348D0008B0 -:10358000418D00082DE9F04F90F84B5099B004465A -:1035900015F0A00540F061810668F26832F8153038 -:1035A000002B4AD13378042B40F086800F230E3550 -:1035B0002046B5FBF3F5A91CFFF7FAFD814600286C -:1035C00076D1236B0135A3EB4515E3795A07E56402 -:1035D00035D523F004032046E371FFF789F950BB8A -:1035E0004FF0FF32616B2046FFF7ECF818BBA36881 -:1035F0002BB3214604A8FFF7C1FDE0B970894FF451 -:103600000071D4E90423E0FB01233069C4E90423F9 -:103610003830FEF7EFFC3069D4E904232830FEF798 -:10362000E9FCE379326904A843F0010382F8213010 -:10363000FFF7E6FD18B181463AE00135AEE7D6E97D -:1036400003548523002140222046FEF7E3FC01229B -:103650002370C0230E464FF0C10C84F820308E46F4 -:10366000402304EB02085F1C04F803C0F0B20233ED -:1036700004F807E022B135F811200AB10131C9B2CE -:10368000170AE25408F803700233DF06F2D135F866 -:1036900011700136002FE6D1831C84F823102846D0 -:1036A0006370FEF737FE84F82400000A84F82500D2 -:1036B000484619B0BDE8F08F04F140070C2204A879 -:1036C0003946FEF741FE9DF81B30DB0740F1CF8005 -:1036D00040234FF0010ADFF8F88184F84B300B22C9 -:1036E00004A93846D6F80C90FEF72EFEBAF1050F65 -:1036F00054D9A9F10201534631F8022F002A3FD1D3 -:103700000DF10F00072203F00F0C0CF130013929E5 -:1037100088BF0CF13701013A00F801194FEA131183 -:1037200001D00F2B3CD818AB7E21134403F8581C52 -:1037300039460023934205D011F8010B03F1010C27 -:1037400020282FD104F13F00072A03F1010397BF7E -:1037500018A920218918013298BF11F8581C072B8D -:10376000C154F1D92046FFF739FE8146002877D1B0 -:103770000AF1010ABAF1640FB1D14FF0070997E7D6 -:10378000102002F0010C52080CEB430313F4803FAD -:1037900018BF83EA08030138F3D1ADE75346AFE71A -:1037A0000B46B0E76346C5E7216B2046A1EB451108 -:1037B000FEF73CFF814600287FF47AAF4FF6FF7892 -:1037C0003846FEF753FC0190A16B3046FEF7ECFD46 -:1037D000814600287FF46CAFE36BE9B2019A4FF0A9 -:1037E0000D0CD6F80CE05A734FF00F02DFF8E4A08E -:1037F000DA724A1E18730CFB02F284469876D87669 -:1038000040451AF8019B0CF1010C18BF3EF812005C -:1038100003EB090B18BF013203F809004FEA102926 -:10382000002808BF4046BCF10D0F8BF80190E7D18E -:10383000404502D03EF812200AB941F0400119700B -:10384000012300212046F370FFF7CEFB81460028BC -:103850007FF42EAF013DB7D11EE04FF0060927E7F8 -:1038600004287FF425AF9DF81B3084F84B309DF879 -:103870001B3020469B0745BF0C350D210125B5FBAC -:10388000F1F548BF01352946FFF792FC8146002833 -:103890007FF40EAF013D87D1A16B3046FEF784FD6A -:1038A000814600287FF404AF01462022E06BFEF73A -:1038B000B1FB0B223946E06BFEF746FD94F84B3026 -:1038C000E26B03F0180313730123F370F0E600BFFB -:1038D00021100100348D000810B504460A4634302A -:1038E000FEF77AFB886004F13800FEF777FBC2E947 -:1038F000040194F8213003F00203D3710023D36153 -:1039000010BD000003284B8B04BF8A8A43EA0243A0 -:10391000184670472DE9F04F0B7899B00446884659 -:103920002F2BD0F800B001D05C2B09D14246137880 -:10393000904601322F2BFAD05C2BF8D0002301E007 -:10394000DBF81C30A3600023E3619BF80030042BFC -:103950001ED1A368E3B1DBF82030214604A823621E -:10396000DBF824306362DBF82830A362FFF706FC43 -:103970000346002859D1DBF8102002F13800FEF789 -:103980002BFBC4E9040392F8213003F00203E37136 -:1039900098F800301F2B00F223818023002120465D -:1039A00084F84B3019B0BDE8F04FFEF73FBEFF2E54 -:1039B00000F038812AF81600013615E142461378E6 -:1039C000904601322F2BFAD05C2BF8D00025012E27 -:1039D00030D1BAF800302E2B32D1002304F140024E -:1039E0002AF816309E428CBF2E21202101330B2B4A -:1039F00002F8011BF6D145F02005204684F84B5013 -:103A0000FFF7ECFC94F84B30002800F0D08004283D -:103A10000BD1990603F0040240F1C580002A00F0A2 -:103A2000DF808023002084F84B3019B0BDE8F08F90 -:103A30000425CCE7022E03D1BAF802302E2BC8D0D1 -:103A4000AAF102028EBB00222AF81620002E00F0F6 -:103A5000E9803AF81210134601322029F9D00BB947 -:103A60002E2901D145F00305AAF1020131F81620F3 -:103A70002E2A01D0013EF9D14FF000090B2220215E -:103A800004F14000FEF7C6FA4F460822591C3AF8E6 -:103A900013000191F0B1202803D02E280DD1B1429E -:103AA00010D045F00305019BF0E732F81630202BCB -:103AB00001D02E2BC7D1013EC4E7914505D2019B11 -:103AC000B34235D10B2A2CD101E00B2A23D145F08A -:103AD00003050B2294F84030E52B04BF052384F83E -:103AE0004030082A04BFBF00FFB207F00C030C2BC4 -:103AF00003D007F00303032B01D145F00205AB0708 -:103B00003FF57BAFFE0748BF45F01005780748BF7B -:103B100045F0080571E7019BB34202D045F003056B -:103B2000D8D8BF000B224FF008090196FFB2BAE7C0 -:103B30007F2812D945F0020340F2523103920293DA -:103B400000F06AFC10F0800FDDE9023210D000F0C6 -:103B50007F004349085C1D4630B1424911F8013BE2 -:103B6000002B6DD08342F9D145F003055F2010E0B2 -:103B7000FF28F0D9511E894503D345F0030591462E -:103B800091E704EB0901050A09F1010981F84050A8 -:103B90001D4604EB090309F1010983F8400082E79F -:103BA00047F00207F5E7002A08BF05203DE75A075E -:103BB0003FF53BAFA379DB0640D59BF80000042816 -:103BC00032D1A3682146E27923622369DBF8100031 -:103BD00023F0FF0313436362E36CA362FFF77CFEF1 -:103BE00023680026D3F80CA018F8010B00283FF436 -:103BF0001FAF40F2523100F02FFC98B11F287FF622 -:103C000017AF2F283FF4DAAE5C283FF4D7AE7F28F9 -:103C10003FF6CDAE144A12F8013B002B3FF4C7AE7D -:103C20008342F8D1062000E7216B0BF14C03C1F36E -:103C300008011944FFF766FEA060D1E70520F4E60D -:103C4000A0F141039BB2192BAAD9A0F161039BB249 -:103C5000192B9EBF203847F0010780B299E700BFBB -:103C6000B48C0008AD8C0008A48C00081FB5CDE909 -:103C7000001003A814460391FEF720FA002815DB74 -:103C80000B4A52F820300BB100211970019B0BB187 -:103C90000021197042F820302CB1002201A9684699 -:103CA000FEF7E0FE0446204604B010BD0B24FAE700 -:103CB000983600202DE9F04798B0904605460191CE -:103CC000002800F04F8102F03F0603A901A8324608 -:103CD000FEF7C8FE002840F04381039B4FF48C6040 -:103CE000049302F02BFD0746002800F03D81039B62 -:103CF00000F500720199D86004A81A61FFF70AFE66 -:103D0000044620B99DF95B30002BB8BF062418F09B -:103D10001C0F00F0C980002C4BD0042C3FD104A80C -:103D2000FFF730FC0446002839D146F00806039B13 -:103D30001A78042A7FD1186929462B60FFF7CCFD39 -:103D4000039B00211E2218690230FEF763F9039BD2 -:103D50001A2218692630FEF75DF9039B20211A69A3 -:103D600011711C6903F050F9014601220834204604 -:103D7000FEF738F9039B04A81B6983F82120FFF79D -:103D80003FFA044658B9A96801B302462846FEF72F -:103D900031FDAB68039A0446013B5361B4B1384628 -:103DA00002F0CEFC0CB100232B60204618B0BDE819 -:103DB000F0879DF8163013F0110F40F0818018F055 -:103DC000040F40F0C78018F0080FB0D1039A3107F4 -:103DD0001399936C48BF46F04006E964AB641078D1 -:103DE00004286FD1069B9DF817102B62089B106961 -:103DF00023F0FF030B4329466B62179BAB62FFF76F -:103E00006BFD039B0024002205F150082B60214626 -:103E1000DB88404685F83060AB80002385F8314070 -:103E20006C64C5E90E234FF40072FEF7F3F8B20696 -:103E300053D40024B3E703F0E7F801460090139849 -:103E40000E30FEF7CFF8139800991630FEF7CAF837 -:103E5000039C13992078FFF755FD2023002280460C -:103E6000CB7220461399FEF7F5F8139B002201212F -:103E70001A775A779A77DA77039BD970B8F1000FDF -:103E8000A4D0414604A8D3F84890FEF7B3FC0446FA -:103E9000002884D149460398FEF786FA039B04461E -:103EA00008F1FF30586179E7002C7FF478AF9DF876 -:103EB0001630DC0650D418F0020F87D0D80785D50D -:103EC00007246CE7FFF71EFD0023A86001F11C002A -:103ED000FEF782F86B61286193E7D5E9046956EA39 -:103EE0000903A6D0039BA968B3F80AA04FEA4A2A9F -:103EF000C5E90E69B24574EB09031BD3002429649C -:103F0000002C7FF44CAFC6F30803002B91D0039C28 -:103F10002046FEF793F808B3760A0123414646EAA5 -:103F2000C95682196A64607802F0ACFB041E18BF9F -:103F3000012434E72846FEF7E1FAB6EB0A0601460B -:103F400069F10009012803D9431CD3D10124D6E724 -:103F50000224D4E7082422E7042420E702241EE7F1 -:103F6000044620E7092420E711241EE72DE9F04F3D -:103F7000994685B00023884603A90446C9F8003055 -:103F80001646FEF7B5F8054680BB94F831506DBB78 -:103F900094F8303013F00103009300F0A68004F190 -:103FA000500AD4E90432D4E90E011B1A62EB010273 -:103FB000B34272F1000238BF1E46BEB1D4E90E1002 -:103FC000C1F30803002B40F08280039B5A894B0AFF -:103FD000013A43EAC0531A401BD151EA000309D108 -:103FE000A06801280DD8022584F83150284605B074 -:103FF000BDE8F08F216C20460192FEF77FFA019A0E -:10400000EFE7431C04D10123009D84F83130EDE734 -:104010002064DDF80CB0216C5846FEF70FF800283C -:10402000E1D0B6F5007F02EB000731D3BBF80A10F0 -:1040300002EB5620730A88429BF8010088BF8B1A56 -:104040003A464146019302F01DFB0028DBD194F96A -:104050003020019B002A0BDA606CC01B984207D20B -:104060004FF40072514608EB4020FEF76DF9019BBA -:104070005F02D9F80030F61BB8443B44C9F8003061 -:10408000D4E90E32DB1942F10002C4E90E3294E7A2 -:10409000626CBA421AD094F93030002B0DDA012349 -:1040A00051469BF8010002F011FB0028ABD194F8B7 -:1040B000303003F07F0384F83030039801233A4610 -:1040C0005146407802F0DEFA00289CD16764A16B6B -:1040D0004046C1F30801C1F500775144B74228BFFB -:1040E00037463A46FEF730F9C3E707257EE700007A -:1040F00070B596B00E460022019002A901A8FEF705 -:10410000B1FC0446E0B94FF48C6002F017FB0546A1 -:10411000D8B1029B00F500720199D86002A81A611B -:10412000FFF7F8FB044640B99DF95330002B0ADB3A -:104130001EB1314602A8FEF70FF8284602F000FB38 -:10414000204616B070BD0624F7E71124F8E70000FA -:1041500070B5B8B00222019003A901A8FEF782FC55 -:10416000044608BB039B4FF48C60109302F0E6FA00 -:104170000546002866D0039B00F500720199D860BF -:1041800010A81A61FFF7C6FB044650B99DF88B30A2 -:10419000980655D4190653D49DF84630DA0706D54B -:1041A0000724284602F0CCFA204638B070BD039BA5 -:1041B00004931878042814D104A91869FFF78CFB1C -:1041C000069E9DF84630DB0610D410A8FFF74CF889 -:1041D00004460028E5D156BB0398FEF7F7FB0446DA -:1041E000DFE71F99FFF78EFB0646EAE7039BDA69D4 -:1041F000B242D5D024930021269624A81B78042B04 -:1042000001BFDDE90823CDE928239DF817308DF89B -:104210009730FEF70BFA04460028C2D124A8FFF716 -:1042200051F804460028BBD00428BAD1CDE7024695 -:10423000314604A8FEF7DEFA04460028B1D1CBE7E8 -:104240000624AEE71124AFE7F0B5BDB0CDE900100C -:104250006846FDF733FF022203A901A8FEF702FC1E -:104260000446002838D1039B4FF48C60149302F06D -:1042700065FA0546002800F0CD80039B00F500722A -:104280000199D86014A81A61FFF744FB044600BBEB -:104290009DF89B3013F0A00F40F0B880039B1A7874 -:1042A000042A58D11969402204A8FEF74DF850227B -:1042B00028A80DEB0201FEF747F8009928A8FFF7A0 -:1042C00029FB0446002843D12A9A169B9A4206D01D -:1042D0000824284602F034FA20463DB0F0BD349A56 -:1042E000209B9A42F4D128A8FFF74CF904460028F5 -:1042F000EFD1039B04A940221869848C477890F879 -:104300002360FEF721F8039B28A81B695F70039BBD -:104310001A6982F823601A6982F82440240A82F814 -:1043200025401A691379D9065CBF43F02003137145 -:10433000FEF766FF04460028CBD114A8FEF794FFD1 -:1043400004460028C5D10398FEF740FB0446C0E7A9 -:104350000428BED1C7E72022239904A8FDF7F4FF63 -:10436000502228A80DEB0201FDF7EEFF009928A8C6 -:10437000FFF7D0FA0446002844D12A9A169B9A42A5 -:10438000A6D1349A209B9A42A2D128A8FFF7FAF826 -:10439000044600289DD1379C13220DF11D010127F1 -:1043A00004F10D00FDF7D0FF9DF81B30039EDA06E7 -:1043B00058BF43F02003E372F770E37ADB06BCD505 -:1043C000169A2A9B9A42B8D021463078FFF79AFA7B -:1043D00001463046FDF732FE0146C8B13046FDF7D2 -:1043E000E3FF044600287FF474AF039890F86D3023 -:1043F0002E2BA2D12A9A00F16C01FDF72BFE039B14 -:10440000DF709AE704287FF464AFBEE7062460E714 -:1044100002245EE711245FE77F2810B501D880B23F -:1044200010BDB0F5803F13D240F2523399420FD104 -:104430000849002231F8024B93B2844203D103F1C0 -:104440008000C0B2ECE70132802AF3D11346F6E7D0 -:104450000020E5E7F48F00087F280DD940F25233A1 -:10446000994208D1FF2806D800F10040034B80385C -:1044700033F8100070470020704700BFF48F000829 -:10448000B0F5803FF0B522D21F4A83B21F49B0F584 -:10449000805F28BF0A46141D34F8042C2146AAB1B7 -:1044A000934213D334F8025C2E0AEFB252FA85F528 -:1044B000A84222DA082E09D8DFE806F0050A101211 -:1044C0001416181A1C00801A34F810301846F0BD63 -:1044D000981A00F001001B1A9BB2F7E7103BFBE7AC -:1044E000203BF9E7303BF7E71A3BF5E70833F3E702 -:1044F000503BF1E7A3F5E353EEE70434002ECBD1B4 -:1045000001EB4702C7E700BF448D0008388F000861 -:1045100001F001038A0748BF43F002034A0748BF7E -:1045200043F008030A0748BF43F00403CA0648BF24 -:1045300043F010038A06426B48BF43F02003134345 -:1045400043637047094BC26A994228BF1946D0F8A5 -:104550004C328B4210B5507906D95A1E4C0002EBF2 -:104560004103B3FBF4F3184410BD00BF20BCBE00F0 -:1045700010B5202383F311880024064B06482146FA -:10458000DC6301F07DFF84F31188BDE8104002F088 -:1045900039BF00BF00700052DC36002010B5094C56 -:1045A000204600F0ADFF084B00220849636431202B -:1045B000C4E90F23064BC4E992130921BDE810405A -:1045C00000F022BCA0360020005A620200700052A7 -:1045D00000B4C404C36A0BB90F4BC3620379012B47 -:1045E00011D10E4B98420ED10D4BD3F8D42042F48A -:1045F0008032C3F8D420D3F8FC2042F48032C3F8D0 -:10460000FC20D3F8FC30D0F8483200221A605A60FF -:10461000DA625A62704700BFF4900008A0360020AA -:10462000004402580379012B18D0D0F848320022F8 -:104630001A605A60DA625A62094B98420ED1094BED -:10464000D3F8D42022F48032C3F8D420D3F8FC204D -:1046500022F48032C3F8FC20D3F8FC30704700BF4E -:10466000A03600200044025810B5D0F8484207494F -:10467000FFF768FF6060236842F2107043F00303A5 -:104680002360BDE8104001F0E1BE00BF801A0600C3 -:1046900038B5D0F8485201296C6808BF054924F0A4 -:1046A000FF0418BF0449FFF74DFF044344F480544E -:1046B0006C6038BD80F0FA0240787D01D0F8483255 -:1046C00000225A601A607047D0F8482201295368C6 -:1046D00023F4404304D0022905D001B95360704748 -:1046E00043F48043FAE743F40043F7E7D0F8483255 -:1046F00041F480519A60D9605A6B1206FCD5802231 -:104700009A63704710B541F48851D0F84842A260CE -:10471000E160616B11F04502FBD0A26311F004026D -:1047200003D0FFF7F5FE012010BD61691046196046 -:10473000FAE7000010B541F48851D0F84842A26071 -:10474000E160616B11F04502FBD0A26311F005023C -:1047500003D0FFF7DDFE012010BD6169104619602E -:10476000FAE700002DE9F041044628200F461646DE -:1047700001F06CFED4F84802C56A00F1580115F04A -:1047800002053FD0826AD4F8500202F077FD10B9DA -:104790000120BDE8F081202383F311884FF0FF3121 -:1047A000D4F848024FF49D738163C363012303650A -:1047B000C36A43F00103C36204F13C0001F052FEFE -:1047C000D4F848220023136583F31188D4F84832C3 -:1047D000D4F85002996D9A6A02F078FDD4F8483204 -:1047E0005A6BD205D4D54FF0FF32012F9A634FF0A8 -:1047F0000002DA6231D9334620460C21BDE8F0418F -:10480000FFF798BF4FF0FF384FF49D73C0F8388022 -:10481000C363826AD4F8500202F066FD0028B7D064 -:10482000202383F311880122D4F84832414604F151 -:104830003C001A65DA6A42F00102DA6201F012FE07 -:10484000D4F848321D6585F31188D4F84832D4F87D -:104850005002996D02F074FDC0E7104699E7000020 -:1048600073B5D0F84842002501924FF0FF320E4652 -:10487000616B2565A263E562FFF74AFE012E07D949 -:10488000019B2A460C2102B0BDE87040FFF752BFE1 -:1048900002B070BD10B541F49851D0F84842A26002 -:1048A000E160616B11F04502FBD0A26311F03F02A1 -:1048B00003D0FFF72DFE012010BD216A10461960BC -:1048C000E1695960A16999606169D960F4E7000004 -:1048D0007FB516460193026C0D46D0F84832044667 -:1048E0005A6200F0D3FD019938B1204603AA012194 -:1048F000FFF7B6FF012004B070BDD4F84802089A53 -:10490000C36A43F40053C3624FF0FF33836306234B -:1049100086628565C36203AB2046FFF70BFF002864 -:10492000E3D1064B039A1340002BDED103AA0121E9 -:104930002046FFF717FF0028DDD0D6E708E0FFFD8F -:10494000F7B517461D46026C0446D0F848320E46AD -:104950005A6200F09BFD00BBD4F84832DA6A42F498 -:104960000052DA624FF0FF329A636A029A62922230 -:104970009F65DA62236BDB0601AB58BF7602012D1F -:1049800032460CD912212046FFF7D4FE48B120460A -:1049900001AA2946FFF764FF012003B0F0BD1121F1 -:1049A000F1E7064B019A1340002BF0D101AA2946EA -:1049B0002046FFF7D7FE0028EFD0E8E708E0FFFD2C -:1049C000F7B517461D46426C0446D0F848320E46ED -:1049D0005A6200F05BFDE8B9D4F84832DA6A42F472 -:1049E0000052DA624FF0FF329A636A029A62236BD6 -:1049F000DB0601AB58BF7602012D32460CD91921D6 -:104A00002046FFF797FE48B1204601AA2946FFF746 -:104A100027FF012003B0F0BD1821F1E7084B019AF0 -:104A20001340002BF0D1D4F848329022294620467A -:104A30009F65DA6201AAFFF795FE0028EAD0E3E756 -:104A400008E0FFFD12F0030F2DE9F04107460C4688 -:104A500015461E461CD0C1EBC1520E44DFF838800B -:104A600005EB4225B44202D10020BDE8F0810123CC -:104A7000094A21463846FFF763FF0028F5D105EBC8 -:104A800044204FF4007241460134FDF709F9E9E78B -:104A9000BDE8F041FFF754BFF438002012F0030FD7 -:104AA0002DE9F04107460C4615461E461CD0C1EBC9 -:104AB000C1520E44DFF8388005EB4225B44202D1E2 -:104AC0000020BDE8F0814FF4007205EB4421404620 -:104AD000FDF7E6F80123424621463846FFF770FF0E -:104AE0000028EED10134E9E7BDE8F041FFF768BFE7 -:104AF000F4380020002070470268436811430160C9 -:104B000003B1184770470000024A136843F0C0031E -:104B10001360704700440040024A136843F0C0032A -:104B20001360704700480040024A136843F0C00316 -:104B3000136070470078004037B5274C274D20465A -:104B400000F03AFD04F11400009400234FF40072C9 -:104B5000234900F0C9F94FF40072224904F13800EA -:104B60000094214B00F042FA204BC4E91735204C49 -:104B7000204600F021FD04F11400009400234FF4BE -:104B800000721C4900F0B0F94FF400721A4904F1A8 -:104B900038000094194B00F029FA194BC4E9173575 -:104BA000184C204600F008FD04F1140000234FF4D7 -:104BB00000721549009400F097F9144B4FF40072FD -:104BC000134904F13800009400F010FA114BC4E9C5 -:104BD000173503B030BD00BFF43A002000E1F50501 -:104BE000383C002038420020094B000800440040B7 -:104BF000603B0020383E002038440020194B00085C -:104C000000480040CC3B002038400020294B0008E1 -:104C10003846002000780040037C30B5334C002932 -:104C200018BF0C46012B18D1314B98420FD1314B94 -:104C3000D3F8E82042F40032C3F8E820D3F810217A -:104C400042F40032C3F81021D3F8103105E02A4BAA -:104C500098422FD0294B984238D02268036EC16DFC -:104C600003EB52038466B3FBF2F36268150442BFA0 -:104C700023F0070503F0070343EA4503CB60A3686D -:104C800043F040034B60E36843F001038B6042F460 -:104C9000967343F001030B604FF0FF330B62510535 -:104CA00005D512F010221DD0B2F1805F1CD080F823 -:104CB000643030BD0F4BD3F8E82042F48022C3F8B3 -:104CC000E820D3F8102142F48022BBE7094BD3F847 -:104CD000E82042F08042C3F8E820D3F8102142F0E7 -:104CE0008042AFE77F23E2E73F23E0E7FC90000844 -:104CF000F43A002000440258603B0020CC3B0020E6 -:104D00002DE9F047C66D05463768F469210734621E -:104D100019D014F0080118BF8021E20748BF41F004 -:104D20002001A3074FF0200348BF41F04001600776 -:104D300048BF41F4807183F31188281DFFF7DCFE22 -:104D4000002383F31188E2050AD5202383F3118819 -:104D50004FF40071281DFFF7CFFE002383F3118865 -:104D60004FF020094FF0000A14F0200838D13B061C -:104D700016D54FF0200905F1380A200610D589F321 -:104D80001188504600F066F9002836DA0821281DFF -:104D9000FFF7B2FE27F080033360002383F311880E -:104DA000790614D5620612D5202383F31188D5E93C -:104DB00013239A4208D12B6C33B127F040071021FE -:104DC000281DFFF799FE3760002383F31188E3065F -:104DD00018D5AA6E1369ABB15069BDE8F047184702 -:104DE00089F31188736A284695F86410194000F019 -:104DF000FDFB8AF31188F469B6E7B06288F3118885 -:104E0000F469BAE7BDE8F087090100F160430122C7 -:104E100003F56143C9B283F8001300F01F039A4001 -:104E200043099B0003F1604303F56143C3F880210C -:104E30001A607047F8B51546826804460B46AA42C8 -:104E400000D28568A1692669761AB5420BD2184648 -:104E50002A46FCF725FFA3692B44A3612846A368D3 -:104E60005B1BA360F8BD0CD9AF1B18463246FCF79C -:104E700017FF3A46E1683044FCF712FFE3683B4411 -:104E8000EBE718462A46FCF70BFFE368E5E700006E -:104E900083689342F7B50446154600D28568D4E985 -:104EA0000460361AB5420BD22A46FCF7F9FE636954 -:104EB0002B4463612846A3685B1BA36003B0F0BD6D -:104EC0000DD93246AF1B0191FCF7EAFE01993A4633 -:104ED000E0683144FCF7E4FEE3683B44E9E72A4636 -:104EE000FCF7DEFEE368E4E710B50A440024C36182 -:104EF000029B8460C16002610362C0E90000C0E9F6 -:104F0000051110BD08B5D0E90532934201D1826880 -:104F100082B98268013282605A1C42611970002194 -:104F2000D0E904329A4224BFC368436101F0C2FA57 -:104F3000002008BD4FF0FF30FBE7000070B52023D4 -:104F400004460E4683F31188A568A5B1A368A2693B -:104F5000013BA360531CA36115782269934224BFCF -:104F6000E368A361E3690BB120469847002383F30C -:104F70001188284607E03146204601F08BFA0028C8 -:104F8000E2DA85F3118870BD2DE9F74F04460E462D -:104F900017469846D0F81C904FF0200A8AF31188E3 -:104FA0004FF0000B154665B12A4631462046FFF703 -:104FB00041FF034660B94146204601F06BFA0028E4 -:104FC000F1D0002383F31188781B03B0BDE8F08F84 -:104FD000B9F1000F03D001902046C847019B8BF325 -:104FE0001188ED1A1E448AF31188DCE7C160C361A1 -:104FF000009B82600362C0E905111144C0E9000012 -:1050000001617047F8B504460D461646202383F328 -:105010001188A768A7B1A368013BA36063695A1C04 -:1050200062611D70D4E904329A4224BFE36863616F -:10503000E3690BB120469847002080F3118807E010 -:105040003146204601F026FA0028E2DA87F311887B -:10505000F8BD0000D0E9052310B59A4201D182685D -:105060007AB982680021013282605A1C82611C7800 -:1050700003699A4224BFC368836101F01BFA20468A -:1050800010BD4FF0FF30FBE72DE9F74F04460E4609 -:1050900017469846D0F81C904FF0200A8AF31188E2 -:1050A0004FF0000B154665B12A4631462046FFF702 -:1050B000EFFE034660B94146204601F0EBF90028B7 -:1050C000F1D0002383F31188781B03B0BDE8F08F83 -:1050D000B9F1000F03D001902046C847019B8BF324 -:1050E0001188ED1A1E448AF31188DCE70379052B39 -:1050F00005BF836A002001204B6004BF4FF400739A -:105100000B60704770B55D1E866A04460D44B5425B -:1051100005D9436B43F080034363012070BD06252E -:105120000571FFF78FFC05232371F7E770B55D1E4E -:10513000866A04460D44B54205D9436B43F08003AB -:105140004363012070BD07250571FFF7A7FC052308 -:105150002371F7E738B505790446052D05D10823F5 -:105160000371FFF7C7FC257138BD0120FCE7000083 -:105170002DE9F041032384B0044602AF0371FFF729 -:1051800073FA002220461146FFF7B0FA4FF4D572A9 -:105190003B1D08212046FFF7CDFA0246B8B901238E -:1051A00023637B68C3F30323012B09D13B1D372104 -:1051B0002046FFF7BFFA18B9AB4B7A681340ABB182 -:1051C00020460125FFF77AFA0223237140E13B1DB7 -:1051D000002237212046FFF7ADFA28B9A24A7B68A2 -:1051E0001A40002A00F0A98002232363236B03F0F6 -:1051F0000F03022B40F0AB8064259C4E42F21070EE -:1052000001F024F93B1D324601212046FFF77AFACE -:105210000028D5D17B68002B80F295805A0003D5F9 -:10522000236B43F010032363002204F108030221DF -:105230002046FFF72FFB02460028C1D104F13803B6 -:1052400003212046FFF776FA0028B9D104F11805AA -:10525000A26B092120462B46FFF71CFB0028AFD18B -:105260003B46A26B07212046FFF764FA064600285A -:10527000A6D1236B03F00F03022B40F093807E2214 -:105280007F21284603F0E8FA012840F28B8004F1E0 -:1052900048084FF47A7001F0D9F808234FF40072EF -:1052A000414620460096FFF713FB002888D1404670 -:1052B00003F020FB236BA06203F00F03022B77D1D6 -:1052C0003B1D6B4A06212046FFF734FA00286DD1BA -:1052D00065497B681940B1FA81F149092046FFF719 -:1052E000D7F93B464FF4007210212046FFF722FA0F -:1052F000054600287FF464AF5B4E3B6833427FF481 -:105300005FAF236B13F00E0F03F00F027BD0022A66 -:105310007FF456AFE36A1979012900F09E800229D3 -:1053200000F09E80002900F09180DFF85481204633 -:10533000FFF7CAF93B1D42467DE011462046226335 -:10534000FFF7D4F952E7013D7FF458AF38E7494DF4 -:105350006426494ADFF81081012B18BF15463B1D12 -:10536000002237212046FFF7E5F900287FF428AF17 -:105370007B6813EA080F7FF423AF3B1D2A462921DF -:105380002046FFF7BFF900287FF41AAF7B68002B97 -:10539000FFF644AF013E3FF413AF42F2107001F04C -:1053A00055F8DCE7284603F079FA83E7002195E712 -:1053B000E84690B07E227F21284602AE03F04CFAE8 -:1053C00010B90021C54689E7002340223146204616 -:1053D00000930623FFF77CFA0028F2D1B3895BBA69 -:1053E0009B07EED5254B40223146204600930623ED -:1053F000FFF76EFA0028E4D1317C01F00F010F397C -:1054000018BF0121DEE7E36A1979F9B101297FF4B8 -:10541000D7AE2046FFF758F93B1DA26B3721204637 -:10542000FFF788F900287FF4CBAE7B6833427FF426 -:10543000C7AE3B1D022206212046FFF77BF900285C -:105440007FF4BEAE7B6833427FF4BAAE052323718E -:1054500028460837BD46BDE8F081DFF8288066E7BA -:10546000DFF8248063E700BF08E0FFFD0080FFC095 -:105470000001B9030080FF5000001080F1FFFF80A1 -:105480000000B7030001B7030002B70337B50446B5 -:105490000C4D01ABA26B0D212046FFF74BF978B9FB -:1054A000019B2B420BD1C3F34323042B08D0053BB4 -:1054B000022B04D84FF47A7000F0C8FFE9E701200E -:1054C00003B030BD08E0FFFD70B52023054683F32F -:1054D000118803790024022B03D184F3118820461C -:1054E00070BD0423037184F311880226FFF7CEFFF9 -:1054F00004462846FFF7E2F82E71F0E7FFF74EB8B2 -:10550000044B03600123037100234363C0E90A33A2 -:10551000704700BF1491000810B52023044683F3A0 -:105520001188C162FFF756F802232371002383F329 -:10553000118810BD10B52023044683F31188FFF7AE -:1055400071F800230122E362227183F3118810BDF8 -:10555000026843681143016003B1184770470000B7 -:105560001430FFF711BD00004FF0FF331430FFF788 -:105570000BBD00003830FFF787BD00004FF0FF3350 -:105580003830FFF781BD00001430FFF7D7BC0000B2 -:105590004FF0FF311430FFF7D1BC00003830FFF777 -:1055A00031BD00004FF0FF323830FFF72BBD000057 -:1055B00000207047FFF7C0BA044B0360002343602C -:1055C000C0E9023301230374704700BF389100081B -:1055D00010B52023044683F31188FFF71DFB022337 -:1055E0002374002383F3118810BD000038B5C3690C -:1055F00004460D461BB904210844FFF7A9FF2946BC -:1056000004F11400FFF77EFC002806DA201D4FF499 -:105610008061BDE83840FFF79BBF38BD0268436832 -:105620001143016003B118477047000013B5406B88 -:1056300000F58054D4F8A4381A681178042914D1DC -:10564000017C022911D11979012312898B4013425F -:105650000BD101A94C3003F02DF8D4F8A448024630 -:10566000019B2179206800F0DFF902B010BD000035 -:10567000143002F0AFBF00004FF0FF33143002F0DF -:10568000A9BF00004C3003F081B800004FF0FF3399 -:105690004C3003F07BB80000143002F07DBF0000F6 -:1056A0004FF0FF31143002F077BF00004C3003F0B0 -:1056B0004DB800004FF0FF324C3003F047B8000007 -:1056C0000020704710B500F58054D4F8A4381A684B -:1056D0001178042917D1017C022914D159790123A9 -:1056E00052898B4013420ED1143002F00FFF024654 -:1056F00048B1D4F8A4484FF4407361792068BDE8FC -:10570000104000F07FB910BD406BFFF7DBBF000019 -:10571000704700007FB5124B012504260446036044 -:105720000023057400F1840243602946C0E9023376 -:105730000C4B0290143001934FF44073009602F02A -:10574000C1FE094B04F69442294604F14C00029430 -:10575000CDE900634FF4407302F088FF04B070BDE0 -:1057600060910008095700082D5600080A68202398 -:1057700083F311880B790B3342F823004B791333F1 -:1057800042F823008B7913B10B3342F8230000F564 -:105790008053C3F8A41802230374002383F31188F1 -:1057A0007047000038B5037F044613B190F85430B9 -:1057B000ABB90125201D0221FFF730FF04F11400D1 -:1057C0006FF00101257700F081FE04F14C0084F8B0 -:1057D00054506FF00101BDE8384000F077BE38BD8D -:1057E00010B5012104460430FFF718FF002323778A -:1057F00084F8543010BD000038B50446002514303C -:1058000002F078FE04F14C00257702F047FF201DDE -:1058100084F854500121FFF701FF2046BDE83840CD -:10582000FFF750BF90F8803003F06003202B06D1C3 -:1058300090F881200023212A03D81F2A06D80020AF -:105840007047222AFBD1C0E91D3303E0034A4267B7 -:1058500007228267C3670120704700BF44220020EF -:1058600037B500F58055D5F8A4381A6811780429A1 -:105870001AD1017C022917D11979012312898B4091 -:10588000134211D100F14C04204602F0C7FF58B179 -:1058900001A9204602F00EFFD5F8A4480246019B5C -:1058A0002179206800F0C0F803B030BD01F10B038E -:1058B000F0B550F8236085B004460D46FEB12023B4 -:1058C00083F3118804EB8507301D0821FFF7A6FE3E -:1058D000FB6806F14C005B691B681BB1019002F08C -:1058E000F7FE019803A902F0E5FE024648B1039BCA -:1058F0002946204600F098F8002383F3118805B06C -:10590000F0BDFB685A691268002AF5D01B8A013B7A -:105910001340F1D104F18002EAE70000133138B5F9 -:1059200050F82140ECB1202383F3118804F5805313 -:10593000D3F8A4281368527903EB8203DB689B69D0 -:105940005D6845B104216018FFF768FE294604F13F -:10595000140002F0E5FD2046FFF7B4FE002383F3B8 -:10596000118838BD7047000001F046BE0123402277 -:10597000002110B5044600F8303BFCF7B7F90023CE -:10598000C4E9013310BD000010B52023044683F3A1 -:1059900011882422416000210C30FCF7A7F9204631 -:1059A00001F04CFE02232370002383F3118810BD05 -:1059B00070B500EB8103054650690E461446DA6067 -:1059C00018B110220021FCF791F9A06918B110223A -:1059D0000021FCF78BF931462846BDE8704001F004 -:1059E0003FBF000083682022002103F0011310B59F -:1059F000044683601030FCF779F92046BDE810407A -:105A000001F0BABFF0B4012500EB810447898D4055 -:105A1000E4683D43A469458123600023A26063607C -:105A2000F0BC01F0D7BF0000F0B4012500EB810409 -:105A300007898D40E4683D43646905812360002344 -:105A4000A2606360F0BC02F04DB8000070B50223A4 -:105A500000250446242203702946C0F888500C30E3 -:105A600040F8045CFCF742F9204684F8705001F0DD -:105A70008BFE63681B6823B129462046BDE8704051 -:105A8000184770BD037880F88C3005230370436895 -:105A90001B6810B504460BB1042198470023A3608E -:105AA00010BD000090F88C20436802701B680BB199 -:105AB000052118477047000070B590F87030044613 -:105AC00013B1002380F8703004F18002204601F009 -:105AD00077FF63689B68B3B994F8803013F0600572 -:105AE00035D00021204602F021FA0021204602F0A4 -:105AF00011FA63681B6813B10621204698470623F4 -:105B000084F8703070BD204698470028E4D0B4F87F -:105B10008630A26F9A4288BFA36794F98030A56F40 -:105B2000002B4FF0200380F20381002D00F0F28063 -:105B3000092284F8702083F3118800212046D4E9DB -:105B40001D23FFF771FF002383F31188DAE794F830 -:105B5000812003F07F0343EA022340F202329342A2 -:105B600000F0C58021D8B3F5807F48D00DD8012B37 -:105B70003FD0022B00F09380002BB2D104F18802B9 -:105B800062670222A267E367C1E7B3F5817F00F095 -:105B90009B80B3F5407FA4D194F88230012BA0D133 -:105BA000B4F8883043F0020332E0B3F5006F4DD013 -:105BB00017D8B3F5A06F31D0A3F5C063012B90D8EF -:105BC0006368204694F882205E6894F88310B4F8E5 -:105BD0008430B047002884D0436863670368A367B4 -:105BE0001AE0B3F5106F36D040F6024293427FF4CC -:105BF00078AF5C4B63670223A3670023C3E794F885 -:105C00008230012B7FF46DAFB4F8883023F00203AB -:105C1000A4F88830C4E91D55E56778E7B4F880300A -:105C2000B3F5A06F0ED194F88230204684F88A3004 -:105C300001F008FE63681B6813B1012120469847F4 -:105C4000032323700023C4E91D339CE704F18B0375 -:105C500063670123C3E72378042B10D1202383F348 -:105C600011882046FFF7BEFE85F311880321636883 -:105C700084F88B5021701B680BB12046984794F82C -:105C80008230002BDED084F88B30042323706368CD -:105C90001B68002BD6D0022120469847D2E794F803 -:105CA000843020461D0603F00F010AD501F07AFE6C -:105CB000012804D002287FF414AF2B4B9AE72B4B1A -:105CC00098E701F061FEF3E794F88230002B7FF44F -:105CD00008AF94F8843013F00F01B3D01A062046B1 -:105CE00002D502F03BF9ADE702F02CF9AAE794F8EF -:105CF0008230002B7FF4F5AE94F8843013F00F015E -:105D0000A0D01B06204602D502F010F99AE702F057 -:105D100001F997E7142284F8702083F311882B4649 -:105D20002A4629462046FFF76DFE85F31188E9E6ED -:105D30005DB1152284F8702083F31188002120467C -:105D4000D4E91D23FFF75EFEFDE60B2284F87020E8 -:105D500083F311882B462A4629462046FFF764FE26 -:105D6000E3E700BF90910008889100088C9100083B -:105D700038B590F870300446002B3ED0063BDAB2BE -:105D80000F2A34D80F2B32D8DFE803F0373131082F -:105D9000223231313131313131313737856FB0F81D -:105DA00086309D4214D2C3681B8AB5FBF3F203FB15 -:105DB00012556DB9202383F311882B462A462946B4 -:105DC000FFF732FE85F311880A2384F870300EE065 -:105DD000142384F87030202383F311880023204695 -:105DE0001A461946FFF70EFE002383F3118838BDCB -:105DF000C36F03B198470023E7E70021204602F074 -:105E000095F80021204602F085F863681B6813B1FD -:105E10000621204698470623D7E7000010B590F8E2 -:105E200070300446142B29D017D8062B05D001D882 -:105E30001BB110BD093B022BFBD80021204602F00C -:105E400075F80021204602F065F863681B6813B1FD -:105E5000062120469847062319E0152BE9D10B238C -:105E600080F87030202383F3118800231A461946E6 -:105E7000FFF7DAFD002383F31188DAE7C3689B6933 -:105E80005B68002BD5D1C36F03B19847002384F81A -:105E90007030CEE70448054B03600023C0E90133AE -:105EA0000C3000F0DFB800BF384800208D890008B2 -:105EB000CB1D083A23F00703591A521A10B4D2081E -:105EC0000024C0E9004384600C301C605A605DF817 -:105ED000044B00F0C7B800002DE9F74F364FCD1D39 -:105EE0008846002818BF0746082A4FEAD50538BF5C -:105EF000082207F10C003C1D9146019000F0F2F8D9 -:105F0000019809F10701C9F1000E2246246864B91D -:105F100000F0F2F83B68CBB308224946E800984706 -:105F2000044698B340E9027830E004EB010CD4F861 -:105F300004A00CEA0E0C0AF10106ACF1080304EB14 -:105F4000C6069E42E1D9A6EB0C0CB5EBEC0F4FEA6E -:105F5000EC0BDAD89C421DD204F10802AB45A3EB4E -:105F600002024FEAE202626009D9691CED4303EBC9 -:105F7000C1025D445560256843F8315022601C46DB -:105F8000C3F8048044F8087B00F0B6F8204603B05C -:105F9000BDE8F08FAA45216802D111602346EEE7E3 -:105FA000013504EBC50344F8351003F10801761AF6 -:105FB000F6105E601360F1E73848002073B50446C0 -:105FC000A0F1080550F8080C54F8043C061D0C30EC -:105FD00007330190DB0844F8043C00F083F83346B3 -:105FE0000198B3421A6801D09D4228D90AB195425E -:105FF00025D244F8082C54F8042C1D60013254F8C2 -:10600000081C05EBC206B14206D14E68324444F882 -:10601000042C0A6844F8082C5E68711C03EBC1016B -:106020008D4207D154F8042C013232445A6054F89E -:10603000082C1A6002B0BDE8704000F05DB813464D -:10604000CFE700000B4610B51B68994203D09C684F -:1060500082689442F8D25A680360426010605860C7 -:1060600010BD00000023C0E9000083600361704799 -:1060700038B504461A4B80689D6948B3A84212D1CE -:1060800023690133236138BD836090F820307BB1F0 -:10609000062B13D1416AD0E9003213605A60FFF732 -:1060A000D1FF436A9868AB6882689A42ECD305E0F6 -:1060B000D0E9003213605A6000F05AF828462146B1 -:1060C000FFF7C0FF6C620620BDE8384000F092B8D0 -:1060D0002369A56001332361EB6AE360EC62D2E7D8 -:1060E0005848002008B5202383F31188FFF7C0FF2C -:1060F000002383F3118808BD174B10B5996920233D -:1061000083F311880269013A0261B2B90468C36875 -:106110008442CB621ED00A6B9BB901238A60036163 -:1061200003681A6802605060DA6A8360C260D862ED -:10613000184600F01DF800F0C9F8002383F3118819 -:1061400010BD1C68A34203D0A468A24238BF2246F7 -:10615000DB68E1E7A260F0E758480020034B00222B -:10616000C3E900339A60C3E90433704758480020FC -:106170000023826880F82030054B1B6899689142A3 -:10618000FBD25A680360426010605860704700BFDD -:106190005848002008B5202383F3118890F8203058 -:1061A000032B05D0042B0DD02BB983F3118808BD28 -:1061B000436A00221A604FF0FF334362FFF7D8FFB3 -:1061C0000023F2E7D0E9003213605A60F3E70000E1 -:1061D0000023826880F82030054B1B689968914243 -:1061E000FBD85A680360426010605860704700BF77 -:1061F00058480020064B996981F820001868026809 -:1062000053601A609861012380F82030FAF764BA6D -:10621000584800204B1C30B5044687B00A4D10D0BA -:10622000AB6901A8094A00F06DF92046FFF7E2FFCB -:10623000049B13B101A800F0A1F9AB69586A07B03B -:1062400030BDFFF7D7FFF8E75848002095610008F8 -:1062500038B50C4D04464162AB6981689A68914239 -:1062600003D8BDE83840FFF783BF1846FFF7B0FFFB -:1062700001230146AC61204684F82030BDE8384057 -:10628000FAF72ABA58480020044B1A689B699068AC -:106290009B68984294BF0020012070475848002016 -:1062A00010B5094C2368A0691A6854602260012265 -:1062B000A36183F82020FFF78BFF0146A069BDE8AA -:1062C0001040FAF709BA00BF5848002008B5FFF798 -:1062D000DBFF18B1BDE80840FFF7E2BF08BD0000D2 -:1062E000FFF7DEBFFEE7000010B50F4CFFF736FFEB -:1062F00000F0FAF802F02CFBFFF7CCFD80220B49EE -:10630000204600F03DF8012344F8180C002480F8E2 -:106310002030C46101F04EF884F3118862B604485D -:10632000BDE8104000F05CB888480020A494000844 -:106330009C91000800F05CB9EFF3118020B9EFF3F5 -:106340000583202282F311887047000010B530B910 -:10635000EFF30584C4F3080414B180F3118810BD71 -:10636000FFF7B4FF84F31188F9E70000034A51688E -:1063700053685B1A9842FBD8704700BF001000E0DA -:106380008260026300228161C262022202840122D1 -:1063900080F82220044A516902614161086150611C -:1063A00000F128028262704758480020D0E901239A -:1063B000016843F81C2CA3F19C0243F82C2C0269C1 -:1063C00043F85C2C426943F8582C044A43F83C2CAF -:1063D000C268A3F13800FFF7D3BF00BFF106000881 -:1063E00010B5202383F31188FFF7E0FF0021044656 -:1063F000FFF72EFF002383F31188204610BD000015 -:1064000038B50E4B9C6904F128056062A06AA84269 -:106410000FD194F822303BB994F821309B0702BF8A -:10642000D4E9043213615A610F20BDE83840FFF708 -:10643000E1BE0368A362FFF79BFEE7E75848002030 -:10644000202383F31188FFF7DBBF000008B5014666 -:10645000202383F311880820FFF7DCFE002383F359 -:10646000118808BD054B9B6921B103605862032068 -:10647000FFF7D0BE4FF0FF30704700BF58480020F4 -:1064800003682BB10022026018465962FFF770BE04 -:106490007047000049B1064B42689B6918605A601A -:1064A000136043600420FFF7B5BE4FF0FF30704724 -:1064B000584800200368984206D01A68026050606D -:1064C00018465962FFF754BE7047000038B50446BD -:1064D0000D462068844200D138BD036823605C60AB -:1064E0004562FFF745FEF4E7054B4FF0FF3103F13E -:1064F0001C02C3E907220022C3E90912704700BF4A -:106500005848002070B51C4E05460C46C0E90323D0 -:1065100002F018FA334653F81C2F9A420DD1B0629C -:106520000A2C2CBF00190A302A60C5E90124C6E9EB -:106530000755BDE8704002F0EFB9B16A431AE3189D -:1065400038BF1C469368A34202D9081902F0F4F937 -:10655000F3699A6894420CD85A68AC602B606A6000 -:1065600015609A685D60121B9A604FF0FF3373628A -:1065700070BDA41A1B68ECE75848002038B51B4CC6 -:10658000E36998420DD08168D0E9003213605A6007 -:106590000022C2609A680A449A604FF0FF33636237 -:1065A00038BD03682246002142F81C3F93425A60DE -:1065B000C16003D1BDE8384002F0B8B99A6881687B -:1065C000A56A0A449A6002F0BDF9E369411B9A6822 -:1065D0008A42E5D9AB181D1AA06A092D98BF01F1AE -:1065E0000A02BDE83840104402F0A6B9584800201D -:1065F0002DE9F041184C002704F11C06E56902F072 -:10660000A1F9A36AAA68C11A8A4215D81344D5F819 -:106610000C80A362D5E9003213605A60E369EF6031 -:10662000B34201D102F082F987F311882869C0478B -:10663000202383F31188E1E7E169B14209D01344D3 -:106640001B1ABDE8F0410A2B2CBFC0180A3002F01B -:1066500073B9BDE8F08100BF5848002010B558B9A3 -:1066600006480479053C18BF012400F035F908B14B -:1066700044F00404204610BD0124FBE7A0360020AE -:10668000FFF7ECBF2DE9F8430F461646994604463E -:10669000B0B9DFF8348098F80450052D05D00324F4 -:1066A0000BE0013D15F0FF050CD04B463A46314654 -:1066B0004046FEF727FD0028F3D12046BDE8F883C9 -:1066C0000424FAE70124F8E7A03600202DE9F84376 -:1066D0000F46164699460446B0B9DFF8348098F85C -:1066E0000450052D05D003240BE0013D15F0FF05F6 -:1066F0000CD04B463A4631464046FEF717FD00287F -:10670000F3D12046BDE8F8830424FAE70124F8E732 -:10671000A036002070B9012905D0032907D000292F -:1067200018BF04207047044B9B6A136070474FF4F6 -:106730008073FAE704207047A036002000F0F2BB17 -:1067400000F02CBC00207047FEE7000070470000FE -:106750004FF0FF30704700004B6843608B688360E8 -:10676000CB68C3600B6943614B6903628B69436209 -:106770000B6803607047000008B53C4B40F2FF71A6 -:106780003B48D3F888200A43C3F88820D3F88820F0 -:1067900022F4FF6222F00702C3F88820D3F8882091 -:1067A000D3F8E0200A43C3F8E020D3F808210A43D5 -:1067B000C3F808212F4AD3F808311146FFF7CCFF60 -:1067C00000F5806002F11C01FFF7C6FF00F5806054 -:1067D00002F13801FFF7C0FF00F5806002F15401BB -:1067E000FFF7BAFF00F5806002F17001FFF7B4FF18 -:1067F00000F5806002F18C01FFF7AEFF00F58060CC -:1068000002F1A801FFF7A8FF00F5806002F1C401C2 -:10681000FFF7A2FF00F5806002F1E001FFF79CFFA7 -:1068200000F5806002F1FC01FFF796FF02F58C7124 -:1068300000F58060FFF790FF01F014FC0E4BD3F8D9 -:10684000902242F00102C3F89022D3F8942242F041 -:106850000102C3F894220522C3F898204FF0605239 -:10686000C3F89C20054AC3F8A02008BD0044025884 -:1068700000000258B491000800ED00E01F0008037A -:1068800008B501F00BFEFFF72FFD104BD3F8DC200D -:1068900042F04002C3F8DC20D3F8042122F0400289 -:1068A000C3F80421D3F80431094B1A6842F00802F6 -:1068B0001A601A6842F004021A6000F049FD00F004 -:1068C00035FBBDE8084000F0B5B800BF00440258F1 -:1068D00000180248012070470020704770470000F0 -:1068E00002290CD0032904D00129074818BF002031 -:1068F0007047032A05D8054800EBC20070470448DA -:1069000070470020704700BFB89300085422002051 -:106910006C93000870B59AB005460846144601A964 -:1069200000F0C2F801A8FBF7D9F9431C0022C6B257 -:106930005B001046C5E9003423700323023404F8D9 -:10694000013C01ABD1B202348E4201D81AB070BD05 -:1069500013F8011B013204F8010C04F8021CF1E7E2 -:1069600008B5202383F311880348FEF779FF00233D -:1069700083F3118808BD00BF504A002090F8803092 -:1069800003F01F02012A07D190F881200B2A03D1BE -:106990000023C0E91D3315E003F06003202B08D16C -:1069A000B0F884302BB990F88120212A03D81F2A0F -:1069B00004D8FEF737BF222AEBD0FAE7034A426732 -:1069C00007228267C3670120704700BF4B22002067 -:1069D00007B5052917D8DFE801F0191603191920A2 -:1069E000202383F31188104A01210190FEF7E0FF74 -:1069F000019802210D4AFEF7DBFF0D48FEF7FCFE71 -:106A0000002383F3118803B05DF804FB202383F394 -:106A100011880748FEF7C6FEF2E7202383F31188AA -:106A20000348FEF7DDFEEBE70C9300083093000807 -:106A3000504A002038B50C4D0C4C2A460C4904F144 -:106A40000800FFF767FF05F1CA0204F110000949C9 -:106A5000FFF760FF05F5CA7204F118000649BDE8AA -:106A60003840FFF757BF00BF2863002054220020A2 -:106A7000E8920008F29200080193000870B50446FD -:106A800008460D46FBF72AF9C6B2204601340378C2 -:106A90000BB9184670BD32462946FBF70BF90028A2 -:106AA000F3D10120F6E700002DE9F04705460C463A -:106AB000FBF714F92B49C6B22846FFF7DFFF08B1F0 -:106AC0000E36F6B228492846FFF7D8FF08B110362F -:106AD000F6B2632E0BD8DFF88C80DFF88C90234F52 -:106AE000DFF894A02E7846B92670BDE8F0872946D5 -:106AF0002046BDE8F04702F033B8252E2ED10722FC -:106B000041462846FBF7D6F870B9194B224603F1E7 -:106B1000140153F8040B8B4242F8040BF9D11B7893 -:106B2000073515341370DDE7082249462846FBF780 -:106B3000C1F898B9A21C0F4B197802320909C95D36 -:106B400002F8041C13F8011B01F00F015345C95D45 -:106B500002F8031CF0D118340835C3E7013504F8F6 -:106B6000016BBFE7D893000801930008F693000873 -:106B7000E093000800E8F11F0CE8F11FBFF34F8F0E -:106B8000044B1A695107FCD1D3F810215207F8D1F0 -:106B9000704700BF0020005208B50D4B1B78ABB901 -:106BA000FFF7ECFF0B4BDA68D10704D50A4A5A60AD -:106BB00002F188325A60D3F80C21D20706D5064A72 -:106BC000C3F8042102F18832C3F8042108BD00BFD4 -:106BD00086650020002000522301674508B5114B4F -:106BE0001B78F3B9104B1A69510703D5DA6842F0E4 -:106BF0004002DA60D3F81021520705D5D3F80C21F2 -:106C000042F04002C3F80C21FFF7B8FF064BDA68E8 -:106C100042F00102DA60D3F80C2142F00102C3F81D -:106C20000C2108BD86650020002000520F289ABF65 -:106C300000F5806040040020704700004FF40030F1 -:106C400070470000102070470F2808B50BD8FFF7D9 -:106C5000EDFF00F500330268013204D104308342B5 -:106C6000F9D1012008BD0020FCE700000F2870B515 -:106C7000054645D8FFF760FB224CFFF77FFF06462D -:106C8000FFF78AFF4FF0FF33072D6361C4F814311B -:106C900020D82361FFF772FF2B0243F02403E36047 -:106CA000E36843F08003E36023695A07FCD4284675 -:106CB000FFF764FF4FF40031FFF7B8FF00F0A2FACE -:106CC0003046FFF78BFFFFF741FB2846BDE87040D9 -:106CD000FFF7BABFC4F81031FFF750FFA5F1080362 -:106CE0001B0243F02403C4F80C31D4F80C3143F0F8 -:106CF0008003C4F80C31D4F810315B07FBD4D6E71D -:106D0000002070BD002000522DE9F84F40EA020338 -:106D100005460C461746D80602D00020BDE8F88F7D -:106D200027F01F07DFF8D4B0FFF736FF2744BC4237 -:106D300003D10120FFF752FFF0E720222946204629 -:106D400001F0A0FE10B920352034F0E72B4605F104 -:106D500020021E68711CE0D104339A42F9D1FFF77A -:106D6000EBFA05F17843234AB3F5801F224B28BF85 -:106D70009A4603F1040338BF9046A2F1080228BFE7 -:106D80009846A3F108033ABF9146DA469946FFF7C1 -:106D9000F5FEC8F80060A5EB040CD9F8002004F15A -:106DA0001C0142F00202C9F80020221FDAF800603C -:106DB00016F00506FAD152F8043F8A424CF8023028 -:106DC000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F871 -:106DD0000020D9F8002022F00202C9F80020FFF7B5 -:106DE000B5FA20222146284601F04CFE0028AAD000 -:106DF00030469FE71420005210210052102000520C -:106E000010B5084C237828B11BB9FFF7C5FE012344 -:106E1000237010BD002BFCD02070BDE81040FFF7A0 -:106E2000DDBE00BF866500202DE9F74F0E46054602 -:106E3000002863D011F0050762D139B9082229462C -:106E40003046FFF749F80446002847D108224FF0A2 -:106E50000109DFF8C08006F00403DFF8BCA006EAF1 -:106E6000090BBBF1000F27D0D8F81410C80723D4A2 -:106E700009F1010908F10C08B9F1060FF1D18FB938 -:106E8000224E2946F0190092FFF726F8044628BB47 -:106E90002037009AA02FF4D12946FFF71DF80446A9 -:106EA000E0B9009A29461A48FFF716F8044600BBD5 -:106EB000204603B0BDE8F08FA3B1D8F8141011F04C -:106EC000040FD5D029460AEB4910CDE90023FFF77E -:106ED00003F80446DDE900230028C9D02A46002132 -:106EE000204608E0B107EDD5D8F8141011F0020FD4 -:106EF000E7E72A460021FAF7F9FED9E70446D7E783 -:106F00001F35202225F01F05A1E700BFC86500201E -:106F10008865002008940008A86500200021FFF77C -:106F200083BF00000121FFF77FBF000070B5144D43 -:106F30000124144E40F2FF3200210120FAF7D6FE60 -:106F400006EB441001342A6955F80C1FFEF7B0FF18 -:106F5000062CF5D137254FF4C0542046FFF7E2FF49 -:106F6000014628B122460848BDE87040FEF7A0BFA0 -:106F7000C4EBC404013D4FEAD404EED170BD00BFA0 -:106F800008940008A8650020886500200421FFF708 -:106F90004BBF00004843FFF7C1BF000008B1FFF737 -:106FA0000DB8704770B5104E82B0FFF7C5F90546B1 -:106FB00001F0C8FC326803469042336037BF0B4A89 -:106FC0000A495168146836BF0131D1E90041516066 -:106FD0000419284641F100010191FFF7B7F9204655 -:106FE000019902B070BD00BF686600207066002085 -:106FF00008B5FFF7D7FF034AD2E90032C01842EBC9 -:10700000010108BD78660020434BD3E900232DE938 -:10701000F34113437CD0FFF7EBFF404A00230027E6 -:10702000F9F73EF906460D463D4A0023F9F738F9CF -:107030000023144630462946394AF9F731F94FF40E -:1070400061613C23ADF80170B4FBF1F5B4FBF3F6DC -:1070500001FB154103FB16464624B1FBF3F1314B0E -:10706000F6B28DF8004098423CD84FF0640C4FF4D3 -:10707000C87EA30704F26C7225D1B2FBFCF30CFBB3 -:10708000132313BBB2FBFEF30EFB1322B2FA82F3FF -:107090005B0903F26D18621C8045D2B217D90FB19B -:1070A0008DF800400022204C4FF00C0C17460CFBD2 -:1070B0000343D4B2013213F804C084450CD8A0EBCA -:1070C0000C000127F5E70023E3E70123E1E7A0EB4C -:1070D000080014460127CCE70FB18DF80140431C8E -:1070E0008DF802309DF80100431C9DF800005038D7 -:1070F000400640EA43509DF8023040EA034040EA2F -:10710000560040EAC52040EA411002B0BDE8F081D7 -:107110004FF40410F9E700BF7866002040420F00EA -:107120008051010090230B00509400080244074B4B -:10713000D2B210B5904200D110BD441C00B253F839 -:10714000200041F8040BE0B2F4E700BF50400058C3 -:107150000E4B30B51C6F240405D41C6F1C671C6FCC -:1071600044F400441C670A4C02442368D2B243F43E -:1071700080732360074B904200D130BD441C51F80E -:10718000045B00B243F82050E0B2F4E70044025838 -:10719000004802585040005807B5012201A90020BC -:1071A000FFF7C4FF019803B05DF804FB13B5044674 -:1071B000FFF7F2FFA04205D0012201A900200194AF -:1071C000FFF7C6FF02B010BD10B56424013C4FF4B8 -:1071D0007A70FFF73BF914F0FF04F7D1084B4FF03A -:1071E000807214249A6103F5805308229A61013C4D -:1071F0004FF47A70FFF72AF914F0FF04F7D110BDAD -:10720000000002580144BFF34F8F064B884204D35D -:10721000BFF34F8FBFF36F8F7047C3F85C0220300E -:10722000F4E700BF00ED00E00144BFF34F8F064BD1 -:10723000884204D3BFF34F8FBFF36F8F7047C3F8FB -:1072400070022030F4E700BF00ED00E070B50546A5 -:1072500016460C4601201021FFF79CFE286046735D -:107260003CB1204636B1FFF791FE2B68186000B1A3 -:107270009C6070BDFFF756FEF7E7000070B50E4644 -:107280001546044600B30B6843608368934210D2EE -:1072900013B10068FFF782FE637B28462BB1FFF72E -:1072A00075FE206020B9A06070BDFFF73BFEF8E7D7 -:1072B000A560206805F11F01306021F01F01FFF774 -:1072C000A1FF01202073EFE70120EDE710B5044690 -:1072D00040B10068884205D1606808B1FAF7E0FC67 -:1072E0000023237310BD000070B50E4615460446FA -:1072F00020B38368934210D213B10068FFF74EFEAB -:10730000637B28462BB1FFF741FE206020B9A060C7 -:1073100070BDFFF707FEF8E7A560316819B12A468E -:107320002068FAF7BDFC206805F11F01306021F0EC -:107330001F01FFF779FF01202073E9E70120E7E74C -:1073400020B103688B4204BF002303737047000021 -:10735000034B1A681AB9034AD2F8D0241A6070474E -:10736000806600200040025808B5FFF7F1FF024B8D -:107370001868C0F3806008BD80660020CAB201466C -:107380000120FFF7E5BE0000CAB201460120FFF769 -:10739000CDBE0000EFF30983054968334A6B22F044 -:1073A00001024A6383F30988002383F3118870473D -:1073B00000EF00E0202080F3118862B60D4B0E4AEA -:1073C000D96821F4E0610904090C0A430B49DA6029 -:1073D000D3F8FC2042F08072C3F8FC20084AC2F8BF -:1073E000B01F116841F0010111601022DA7783F8B3 -:1073F0002200704700ED00E00003FA0555CEACC551 -:10740000001000E0202310B583F311880E4B5B6859 -:1074100013F4006314D0F1EE103AEFF309844FF047 -:107420008073683CE361094BDB6B236684F3098856 -:10743000FEF72AFF10B1064BA36110BD054BFBE719 -:1074400083F31188F9E700BF00ED00E000EF00E0F2 -:10745000030700080607000870B5BFF34F8FBFF39E -:107460006F8F1A4A0021C2F85012BFF34F8FBFF33B -:107470006F8F536943F400335361BFF34F8FBFF3F2 -:107480006F8FC2F88410BFF34F8FD2F8803043F66D -:10749000E074C3F3C900C3F34E335B0103EA04068F -:1074A000014646EA81750139C2F86052F9D2203BA3 -:1074B00013F1200FF2D1BFF34F8F536943F48033A0 -:1074C0005361BFF34F8FBFF36F8F70BD00ED00E0CE -:1074D000FEE700000A4B0B480B4A90420BD30B4BC4 -:1074E000C11EDA1C121A22F003028B4238BF00229E -:1074F0000021FAF7FBBB53F8041B40F8041BECE730 -:10750000A09500086468002064680020646800207A -:107510007047000070B5D0E9244300224FF0FF35DA -:107520009E6804EB42135101D3F80009002805DAE4 -:10753000D3F8000940F08040C3F80009D3F8000BED -:10754000002805DAD3F8000B40F08040C3F8000BA8 -:10755000013263189642C3F80859C3F8085BE0D2B9 -:107560004FF00113C4F81C3870BD000000EB81031C -:10757000D3F80CC02DE9F043DCF814204E1CD0F8F1 -:107580009050D2F800E005EB063605EB4118506844 -:1075900070450AD30122D5F8343802FA01F123EA02 -:1075A0000101C5F83418BDE8F083AEEB0003BCF868 -:1075B0001040A34228BF2346D8F81849A4B2B3EB21 -:1075C000840FF0D89468A4F1040959F8047F376057 -:1075D000A4EB09071F44042FF7D81C44034494600C -:1075E0005360D4E7890141F02001016103699B06E2 -:1075F000FCD41220FEF7BABE10B50A4C2046FEF7A6 -:10760000B5F9094BC4F89030084BC4F89430084CD5 -:107610002046FEF7ABF9074BC4F89030064BC4F890 -:10762000943010BD84660020000008408C9400084F -:1076300020670020000004409894000870B503788B -:107640000546012B5DD1494BD0F89040984259D165 -:10765000474B0E216520D3F8D82042F00062C3F8D2 -:10766000D820D3F8002142F00062C3F80021D3F8FB -:107670000021D3F8802042F00062C3F88020D3F8C4 -:10768000802022F00062C3F88020D3F88030FDF71C -:10769000BBFB384BE360384BC4F800380023D5F807 -:1076A0009060C4F8003EC02323604FF40413A3632A -:1076B0003369002BFCDA01230C203361FEF756FE00 -:1076C0003369DB07FCD41220FEF750FE3369002B30 -:1076D000FCDA00262846A660FFF71CFF6B68C4F89A -:1076E0001068DB68C4F81468C4F81C68002B3AD131 -:1076F000224BA3614FF0FF336361A36843F00103A2 -:10770000A36070BD1E4B9842C8D1194B0E214D206D -:10771000D3F8D82042F00072C3F8D820D3F8002163 -:1077200042F00072C3F80021D3F80021D3F8802082 -:1077300042F00072C3F88020D3F8802022F000725B -:10774000C3F88020D3F88020D3F8D82022F08062BC -:10775000C3F8D820D3F8002122F08062C3F80021BA -:10776000D3F8003193E7074BC3E700BF84660020DE -:10777000004402584014004003002002003C30C086 -:1077800020670020083C30C0F8B5D0F8904005468E -:1077900000214FF000662046FFF724FFD5F8941033 -:1077A00000234FF001128F684FF0FF30C4F83438D7 -:1077B000C4F81C2804EB431201339F42C2F800694D -:1077C000C2F8006BC2F80809C2F8080BF2D20B68C5 -:1077D000D5F89020C5F898306362102313611669BC -:1077E00016F01006FBD11220FEF7C0FDD4F80038C9 -:1077F00023F4FE63C4F80038A36943F4402343F044 -:107800001003A3610923C4F81038C4F814380B4BD3 -:10781000EB604FF0C043C4F8103B094BC4F8003B89 -:10782000C4F81069C4F80039D5F8983003F1100293 -:1078300043F48013C5F89820A362F8BD689400084B -:1078400040800010D0F8902090F88A10D2F80038CC -:1078500023F4FE6343EA0113C2F8003870470000C6 -:107860002DE9F84300EB8103D0F890500C46804698 -:10787000DA680FFA81F94801166806F00306731EEC -:10788000022B05EB41134FF0000194BFB604384EB4 -:10789000C3F8101B4FF0010104F1100398BF06F16B -:1078A000805601FA03F3916998BF06F50046002956 -:1078B0003AD0578A04F15801374349016F50D5F83F -:1078C0001C180B430021C5F81C382B180127C3F8DE -:1078D0001019A7405369611E9BB3138A928B9B08B2 -:1078E000012A88BF5343D8F89820981842EA0343E6 -:1078F00001F140022146C8F89800284605EB8202B3 -:107900005360FFF76FFE08EB8900C3681B8A43EAE8 -:10791000845348341E4364012E51D5F81C381F434C -:10792000C5F81C78BDE8F88305EB4917D7F8001BAC -:1079300021F40041C7F8001BD5F81C1821EA030305 -:10794000C0E704F13F030B4A2846214605EB8303B9 -:107950005A60FFF747FE05EB4910D0F8003923F4D1 -:107960000043C0F80039D5F81C3823EA0707D7E7E9 -:107970000080001000040002D0F894201268C0F8C3 -:107980009820FFF7C7BD00005831D0F8903049016A -:107990005B5813F4004004D013F4001F0CBF022006 -:1079A000012070474831D0F8903049015B5813F4FA -:1079B000004004D013F4001F0CBF022001207047C8 -:1079C00000EB8101CB68196A0B6813604B68536048 -:1079D0007047000000EB810330B5DD68AA691368C9 -:1079E000D36019B9402B84BF402313606B8A14689D -:1079F000D0F890201C4402EB4110013C09B2B4FBCA -:107A0000F3F46343033323F0030343EAC44343F033 -:107A1000C043C0F8103B2B6803F00303012B0ED1C9 -:107A2000D2F8083802EB411013F4807FD0F8003B05 -:107A300014BF43F0805343F00053C0F8003B02EB07 -:107A40004112D2F8003B43F00443C2F8003B30BD82 -:107A50002DE9F041D0F8906005460C4606EB411345 -:107A6000D3F8087B3A07C3F8087B08D5D6F8143852 -:107A70001B0704D500EB8103DB685B689847FA07B6 -:107A80001FD5D6F81438DB071BD505EB8403D9685E -:107A9000CCB98B69488A5A68B2FBF0F600FB162213 -:107AA0008AB91868DA6890420DD2121AC3E9002424 -:107AB000202383F3118821462846FFF78BFF84F3A8 -:107AC0001188BDE8F081012303FA04F26B8923EAEF -:107AD00002036B81CB68002BF3D021462846BDE81A -:107AE000F041184700EB81034A0170B5DD68D0F81A -:107AF00090306C692668E66056BB1A444FF400204B -:107B0000C2F810092A6802F00302012A0AB20ED153 -:107B1000D3F8080803EB421410F4807FD4F800096E -:107B200014BF40F0805040F00050C4F8000903EB4F -:107B30004212D2F8000940F00440C2F800090122C4 -:107B4000D3F8340802FA01F10143C3F8341870BDC8 -:107B500019B9402E84BF4020206020681A442E8A24 -:107B60008419013CB4FBF6F440EAC44040F00050F4 -:107B7000C6E700002DE9F041D0F8906004460D46BC -:107B800006EB4113D3F80879C3F80879FB071CD535 -:107B9000D6F81038DA0718D500EB8103D3F80CC0FB -:107BA000DCF81430D3F800E0DA6896451BD2A2EB7B -:107BB0000E024FF000081A60C3F80480202383F3FC -:107BC0001188FFF78FFF88F311883B0618D5012332 -:107BD000D6F83428AB40134212D029462046BDE8DF -:107BE000F041FFF7C3BC012303FA01F2038923EA42 -:107BF00002030381DCF80830002BE6D09847E4E765 -:107C0000BDE8F0812DE9F84FD0F8905004466E6938 -:107C1000AB691E4016F480586E6103D0BDE8F84F82 -:107C2000FDF714BF002E12DAD5F8003E9F0705D0ED -:107C3000D5F8003E23F00303C5F8003ED5F804381C -:107C4000204623F00103C5F80438FDF72BFF30056B -:107C500005D52046FFF75EFC2046FDF713FFB10473 -:107C60000CD5D5F8083813F0060FEB6823F47053E1 -:107C70000CBF43F4105343F4A053EB60320704D518 -:107C80006368DB680BB120469847F30200F1BA80C5 -:107C9000B70226D5D4F8909000274FF0010A09EBDF -:107CA0004712D2F8003B03F44023B3F5802F11D1E3 -:107CB000D2F8003B002B0DDA62890AFA07F322EAB8 -:107CC0000303638104EB8703DB68DB6813B1394688 -:107CD000204698470137D4F89430FFB29B689F4202 -:107CE000DDD9F00619D5D4F89000026AC2F30A175C -:107CF00002F00F0302F4F012B2F5802F00F0CC80F6 -:107D0000B2F5402F09D104EB8303002200F5805027 -:107D1000DB681B6A974240F0B2803003D5F81858F0 -:107D200035D5E90303D500212046FFF791FEAA03CC -:107D300003D501212046FFF78BFE6B0303D50221FB -:107D40002046FFF785FE2F0303D503212046FFF7CA -:107D50007FFEE80203D504212046FFF779FEA90241 -:107D600003D505212046FFF773FE6A0203D50621DD -:107D70002046FFF76DFE2B0203D507212046FFF7B3 -:107D800067FEEF0103D508212046FFF761FE70036F -:107D900040F1A980E90703D500212046FFF7EAFE5C -:107DA000AA0703D501212046FFF7E4FE6B0703D5A0 -:107DB00002212046FFF7DEFE2F0703D503212046D0 -:107DC000FFF7D8FEEE0603D504212046FFF7D2FECA -:107DD000A80603D505212046FFF7CCFE690603D58A -:107DE00006212046FFF7C6FE2A0603D507212046B6 -:107DF000FFF7C0FEEB0576D520460821BDE8F84F19 -:107E0000FFF7B8BED4F8909000274FF0010AD4F8DD -:107E100094305FFA87FB9B689B453FF639AF09EBCF -:107E20004B13D3F8002902F44022B2F5802F24D15D -:107E3000D3F80029002A20DAD3F8002942F0904232 -:107E4000C3F80029D3F80029002AFBDB5946D4F8EF -:107E50009000FFF7C7FB22890AFA0BF322EA03031B -:107E6000238104EB8B03DB689B6813B159462046E2 -:107E7000984759462046FFF779FB0137C7E7910736 -:107E800001D1D0F80080072A02F101029CBF03F85B -:107E9000018B4FEA18283DE704EB830300F580507F -:107EA000DA68D2F818C0DCF80820DCE9001CA1EB85 -:107EB0000C0C00218F4208D1DB689B699A683A4418 -:107EC0009A605A683A445A6027E711F0030F01D1CB -:107ED000D0F800808C4501F1010184BF02F8018BCC -:107EE0004FEA1828E6E7BDE8F88F000008B5034818 -:107EF000FFF788FEBDE80840FFF784BA84660020DB -:107F000008B50348FFF77EFEBDE80840FFF77ABAE0 -:107F100020670020D0F8903003EB4111D1F8003BEE -:107F200043F40013C1F8003B70470000D0F89030D4 -:107F300003EB4111D1F8003943F40013C1F80039C3 -:107F400070470000D0F8903003EB4111D1F8003BAE -:107F500023F40013C1F8003B70470000D0F89030C4 -:107F600003EB4111D1F8003923F40013C1F80039B3 -:107F7000704700003A4B4FF0FF31D3F8802062F099 -:107F80000042C3F88020D3F8802002F00042C3F8FA -:107F90008020D3F88020D3F88420C3F88410D3F84D -:107FA00084200022C3F88420D3F88400D86F40F0E6 -:107FB000FF4040F4FF0040F43F5040F03F00D867DE -:107FC000D86F20F0FF4020F4FF0020F43F5020F055 -:107FD0003F00D867D86FD3F888006FEA40506FEA47 -:107FE0005050C3F88800D3F88800C0F30A00C3F8E3 -:107FF0008800D3F88800D3F89000C3F89010D3F825 -:108000009000C3F89020D3F89000D3F89400C3F800 -:108010009410D3F89400C3F89420D3F89400D3F8C4 -:108020009800C3F89810D3F89800C3F89820D3F8B4 -:108030009800D3F88C00C3F88C10D3F88C00C3F8E8 -:108040008C20D3F88C00D3F89C00C3F89C10D3F894 -:108050009C10C3F89C20D3F89C3000F0E7B900BF17 -:1080600000440258614B0122C3F80821604BD3F849 -:10807000F42042F00202C3F8F420D3F81C2142F0AD -:108080000202C3F81C210422D3F81C31594BDA60D8 -:108090005A689104FCD5584A1A6001229A60574ADE -:1080A000DA6000221A614FF440429A61514B9A699A -:1080B0009204FCD51A6842F480721A604C4B1A6F15 -:1080C00012F4407F04D04FF480321A6700221A67FE -:1080D0001A6842F001021A60454B1A685007FCD535 -:1080E00000221A611A6912F03802FBD101211960CD -:1080F0004FF0804159605A67414ADA62414A1A6139 -:108100001A6842F480321A60394B1A689103FCD520 -:108110001A6842F480521A601A689204FCD53A4AEE -:108120003A499A6200225A6319633949DA639963BA -:108130005A64384A1A64384ADA621A6842F0A85215 -:108140001A602B4B1A6802F02852B2F1285FF9D15D -:1081500048229A614FF48862DA6140221A622F4AFB -:10816000DA644FF080521A652D4A5A652D4A9A6595 -:1081700032232D4A1360136803F00F03022BFAD148 -:108180001B4B1A6942F003021A611A6902F03802A5 -:10819000182AFAD1D3F8DC2042F00052C3F8DC20D0 -:1081A000D3F8042142F00052C3F80421D3F804218B -:1081B000D3F8DC2042F08042C3F8DC20D3F804215D -:1081C00042F08042C3F80421D3F80421D3F8DC2024 -:1081D00042F00042C3F8DC20D3F8042142F0004210 -:1081E000C3F80421D3F80431704700BF0080005168 -:1081F000004402580048025800C000F0040000018A -:108200000000FF010088900832206000630209012D -:108210001D02040047040508FD0BFF01200000209B -:108220000010E00000010100002000524FF0B042B9 -:1082300008B5D2F8883003F00103C2F8883023B1C2 -:10824000044A13680BB150689847BDE80840FFF72F -:10825000D9B800BFDC6700204FF0B04208B5D2F8B3 -:10826000883003F00203C2F8883023B1044A9368CF -:108270000BB1D0689847BDE80840FFF7C3B800BF0E -:10828000DC6700204FF0B04208B5D2F8883003F028 -:108290000403C2F8883023B1044A13690BB1506952 -:1082A0009847BDE80840FFF7ADB800BFDC67002085 -:1082B0004FF0B04208B5D2F8883003F00803C2F896 -:1082C000883023B1044A93690BB1D0699847BDE85F -:1082D0000840FFF797B800BFDC6700204FF0B042BE -:1082E00008B5D2F8883003F01003C2F8883023B103 -:1082F000044A136A0BB1506A9847BDE80840FFF77B -:1083000081B800BFDC6700204FF0B04310B5D3F850 -:10831000884004F47872C3F88820A30604D5124A72 -:10832000936A0BB1D06A9847600604D50E4A136B66 -:108330000BB1506B9847210604D50B4A936B0BB1D8 -:10834000D06B9847E20504D5074A136C0BB1506C0B -:108350009847A30504D5044A936C0BB1D06C984799 -:10836000BDE81040FFF74EB8DC6700204FF0B04387 -:1083700010B5D3F8884004F47C42C3F88820620525 -:1083800004D5164A136D0BB1506D9847230504D5DB -:10839000124A936D0BB1D06D9847E00404D50F4A93 -:1083A000136E0BB1506E9847A10404D50B4A936E1F -:1083B0000BB1D06E9847620404D5084A136F0BB115 -:1083C000506F9847230404D5044A936F0BB1D06FC4 -:1083D0009847BDE81040FFF715B800BFDC670020E4 -:1083E00008B50348FCF78CFCBDE80840FFF70AB865 -:1083F000F43A002008B50348FCF782FCBDE80840C9 -:10840000FFF700B8603B002008B50348FCF778FC94 -:10841000BDE80840FEF7F6BFCC3B002008B500F0F1 -:10842000F7FABDE80840FEF7EDBF0000062108B5E9 -:108430000846FCF7E9FC06210720FCF7E5FC0621CD -:108440000820FCF7E1FC06210920FCF7DDFC0621F1 -:108450000A20FCF7D9FC06211720FCF7D5FC0621E1 -:108460002820FCF7D1FC09217A20FCF7CDFC09215A -:108470003120FCF7C9FC07213220FCF7C5FC0C2198 -:108480002620FCF7C1FC0C212720FCF7BDFC0C21A9 -:108490005220BDE80840FCF7B7BC000008B5FFF764 -:1084A00069FD00F07DFAFDF785F8FDF727F8FDF787 -:1084B0005BFAFDF72DF9FEF711FABDE8084000F070 -:1084C00029BA000030B50433039C0172002104FB7B -:1084D0000325C160C0E90653049B0363059BC0E903 -:1084E0000000C0E90422C0E90842C0E90A11436360 -:1084F00030BD00000022416AC260C0E90411C0E939 -:108500000A226FF00101FDF7E1BF0000D0E904325B -:10851000934201D1C2680AB9181D70470020704704 -:10852000036919600021C2680132C260C269134444 -:1085300082699342036124BF436A0361FDF7BABFB6 -:1085400038B504460D46E3683BB162690020131D4F -:108550001268A3621344E36207E0237A33B9294621 -:108560002046FDF797FF0028EDDA38BD6FF00100D7 -:10857000FBE70000C368C269013BC3604369134461 -:1085800082699342436124BF436A4361002383624B -:10859000036B03B11847704770B52023044683F37B -:1085A0001188866A3EB9FFF7CBFF054618B186F3FE -:1085B0001188284670BDA36AE26A13F8015B9342F2 -:1085C000A36202D32046FFF7D5FF002383F311886F -:1085D000EFE700002DE9F84F04460E46174698468F -:1085E0004FF0200989F311880025AA46D4F828B055 -:1085F000BBF1000F09D141462046FFF7A1FF20B192 -:108600008BF311882846BDE8F88FD4E90A12A7EB4E -:10861000050B521A934528BF9346BBF1400F1BD957 -:10862000334601F1400251F8040B914243F8040B28 -:10863000F9D1A36A403640354033A362D4E90A2316 -:108640009A4202D32046FFF795FF8AF31188BD4274 -:10865000D8D289F31188C9E730465A46F9F720FB8A -:10866000A36A5E445D445B44A362E7E710B5029CE5 -:108670000433017204FB0321C460C0E90613002324 -:10868000C0E90A33039B0363049BC0E90000C0E90F -:108690000422C0E90842436310BD0000026A6FF083 -:1086A0000101C260426AC0E904220022C0E90A2234 -:1086B000FDF70CBFD0E904239A4201D1C26822B968 -:1086C000184650F8043B0B607047002070470000CC -:1086D000C3680021C2690133C360436913448269DE -:1086E0009342436124BF436A4361FDF7E3BE000048 -:1086F00038B504460D46E3683BB1236900201A1DD6 -:10870000A262E2691344E36207E0237A33B929469F -:108710002046FDF7BFFE0028EDDA38BD6FF00100FE -:10872000FBE7000003691960C268013AC260C269D0 -:10873000134482699342036124BF436A03610023A7 -:108740008362036B03B118477047000070B52023A4 -:108750000D460446114683F31188866A2EB9FFF749 -:10876000C7FF10B186F3118870BDA36A1D70A36A9C -:10877000E26A01339342A36204D3E16920460439DB -:10878000FFF7D0FF002080F31188EDE72DE9F84FC7 -:1087900004460D46904699464FF0200A8AF3118808 -:1087A0000026B346A76A4FB949462046FFF7A0FF07 -:1087B00020B187F311883046BDE8F88FD4E90A0765 -:1087C0003A1AA8EB0607974228BF1746402F1BD935 -:1087D00005F1400355F8042B9D4240F8042BF9D1D4 -:1087E000A36A40364033A362D4E90A239A4204D3F1 -:1087F000E16920460439FFF795FF8BF31188464560 -:10880000D9D28AF31188CDE729463A46F9F748FAD2 -:10881000A36A3D443E443B44A362E5E7D0E9042318 -:108820009A4217D1C3689BB1836A8BB1043B9B1AF0 -:108830000ED01360C368013BC360C3691A448369E7 -:108840009A42026124BF436A0361002383620123C9 -:10885000184670470023FBE701F01F03F0B502F054 -:108860001F0456095A1C0123B6EB511F50F826501D -:1088700003FA02F34FEA511703F1FF333DBF50F8FB -:108880002720C4F12000134003EA05003BBF03FA90 -:1088900000F225FA04F0E0401043F0BD70B57E22EE -:1088A0007F210546FFF7D8FF18B1012819D0002015 -:1088B00070BD3E2249212846FFF7CEFF2F220446F5 -:1088C00031212846FFF7C8FF064601345022023600 -:1088D00053212846B440FFF7BFFF093804FA00F0DF -:1088E000E6E7302245212846FFF7B6FF0130800237 -:1088F000DEE7000090F8D63090F8D7201B0403EB99 -:10890000026390F8D42090F8D500134403EB0020C4 -:108910007047000000F052B8034B002258631A6100 -:108920000222DA60704700BF000C0040014B0022B9 -:10893000DA607047000C0040014B5863704700BF7D -:10894000000C0040014B586A704700BF000C00400B -:10895000024B034A1A60034A5A607047D4670020EA -:108960006868002000000220074B494210B55C688F -:10897000201A08401968821A914203D8944201D300 -:108980005A6010BD0020FCE7D467002008B5202302 -:1089900083F31188FFF7E8FF002383F3118808BDF4 -:1089A0000023054A19460133102BC2E9001102F1D8 -:1089B0000802F8D1704700BFDC670020114BD3F8E4 -:1089C000E82042F00802C3F8E820D3F8102142F072 -:1089D0000802C3F810210C4AD3F81031D36B43F0CE -:1089E0000803D363C722094B9A624FF0FF32DA6261 -:1089F00000229A615A63DA605A6001225A611A6051 -:108A0000704700BF004402580010005C000C00409A -:108A1000094A08B51169D3680B40D9B29B076FEAC0 -:108A20000101116107D5202383F31188FDF782FC32 -:108A3000002383F3118808BD000C0040FEF7AEBA96 -:108A4000012838BF012010B504462046FEF766FA1B -:108A500030B900F007F808B900F00CF88047F4E7E7 -:108A600010BD0000024B1868BFF35B8F704700BF5A -:108A70005C68002008B5062000F056F80120FDF7DC -:108A800063FE000010B501390244904201D100207C -:108A900005E0037811F8014FA34201D0181B10BD67 -:108AA0000130F2E7884210B501EB020402D984429A -:108AB000234607D8431EA14208D011F8012B03F822 -:108AC000012FF8E7024401468A4200D110BD13F895 -:108AD000014D02F8014DF7E71F2938B504460D4650 -:108AE00004D9162303604FF0FF3038BD426C12B139 -:108AF00052F821304BB9204600F030F82A460146A2 -:108B00002046BDE8384000F017B8012B0AD0591CA8 -:108B100003D1162303600120E7E7002442F8254033 -:108B2000284698470020E0E7024B01461868FFF707 -:108B3000D3BF00BF7422002038B5074D0023044680 -:108B4000084611462B60FDF703FE431C02D12B683B -:108B500003B1236038BD00BF60680020FDF7F2BD9F -:108B6000034611F8012B03F8012B002AF9D17047B5 -:108B700010B50139034632B111F8014F03F8014B2A -:108B8000013A002CF7D11A440021934200D110BDC4 -:108B900003F8011BF9E700004D4435002D2D0A00B4 -:108BA0002F6172647570696C6F742E6162696E00FA -:108BB0002F6172647570696C6F742D766572696669 -:108BC000792E6162696E002F6172647570696C6FD5 -:108BD000742D666C6173682E6162696E002F61721C -:108BE000647570696C6F742D666C61736865642E52 -:108BF0006162696E000000000000000000000000DB -:108C0000D10E00086D0F00081D110008A50F000807 -:108C1000650F00080000000000000000CD0E0008F5 -:108C2000790F000855110008C90E0008D50E00087C -:108C300053544D333248373F3F3F0053544D333246 -:108C4000483734332F3735330000000001105A0005 -:108C50000310590001205800032056002F00000087 -:108C60005375636365737366756C6C79206D6F758E -:108C70006E746564205344436172642028736C6F82 -:108C800077646F776E3D2575290A0000EB76904575 -:108C900058464154202020004641543332202020A1 -:108CA00000000000222A3A3C3E3F7C7F002B2C3BF8 -:108CB0003D5B5D0043554541414141434545454983 -:108CC000494941414592924F4F4F5555594F554F44 -:108CD0009C4F9E9F41494F55A5A5A6A7A8A9AAAB01 -:108CE000ACADAEAFB0B1B2B3B4414141B8B9BABBAB -:108CF000BCBDBEBFC0C1C2C3C4C54141C8C9CACB47 -:108D0000CCCDCECFD1D145454549494949D9DADB0A -:108D1000DCDD49DF4FE14F4F4F4FE6E8E855555551 -:108D20005959EEEFF0F1F2F3F4F5F6F7F8F9FAFB32 -:108D3000FCFDFEFF01030507090E10121416181C96 -:108D40001E00000061001A03E0001703F80007038B -:108D5000FF000100780100013001320106013901F4 -:108D600010014A012E017901060180014D004302E4 -:108D700081018201820184018401860187018701CA -:108D800089018A018B018B018D018E018F01900178 -:108D90009101910193019401F601960197019801C7 -:108DA00098013D029B019C019D0120029F01A001B1 -:108DB000A001A201A201A401A401A601A701A7018B -:108DC000A901AA01AB01AC01AC01AE01AF01AF0139 -:108DD000B101B201B301B301B501B501B701B801E9 -:108DE000B801BA01BB01BC01BC01BE01F701C00161 -:108DF000C101C201C301C401C501C401C701C80149 -:108E0000C701CA01CB01CA01CD011001DD0101007A -:108E10008E01DE011201F3010300F101F401F401FE -:108E2000F8012801220212013A020900652C3B02D6 -:108E30003B023D02662C3F024002410241024602D3 -:108E40000A015302400081018601550289018A010D -:108E500058028F015A0290015C025D025E025F02BD -:108E60009301610262029401640265026602670274 -:108E7000970196016A02622C6C026D026E029C01DF -:108E8000700271029D01730274029F0176027702E3 -:108E9000780279027A027B027C02642C7E027F02D5 -:108EA000A60181028202A90184028502860287024C -:108EB000AE014402B101B20145028D028E028F0261 -:108EC00090029102B7017B030300FD03FE03FF0341 -:108ED000AC0304008603880389038A03B1031103EA -:108EE000C2030200A303A303C4030803CC030300CB -:108EF0008C038E038F03D8031801F2030A00F903D1 -:108F0000F303F403F503F603F703F703F903FA0396 -:108F1000FA033004200350041007600422018A047D -:108F20003601C1040E01CF040100C004D004440185 -:108F300061052604000000007D1D0100632C001E59 -:108F40009601A01E5A01001F0806101F0606201FCA -:108F50000806301F0806401F0606511F0700591F4C -:108F6000521F5B1F541F5D1F561F5F1F601F0806A7 -:108F7000701F0E00BA1FBB1FC81FC91FCA1FCB1FFF -:108F8000DA1FDB1FF81FF91FEA1FEB1FFA1FFB1F79 -:108F9000801F0806901F0806A01F0806B01F0400C7 -:108FA000B81FB91FB21FBC1FCC1F0100C31FD01FA9 -:108FB0000206E01F0206E51F0100EC1FF31F01007F -:108FC000FC1F4E210100322170211002842101007A -:108FD0008321D0241A05302C2F04602C0201672C29 -:108FE0000601752C0201802C6401002D260841FF2A -:108FF0001A030000C700FC00E900E200E400E00002 -:10900000E500E700EA00EB00E800EF00EE00EC000E -:10901000C400C500C900E600C600F400F600F20076 -:10902000FB00F900FF00D600DC00F800A300D80028 -:10903000D7009201E100ED00F300FA00F100D10049 -:10904000AA00BA00BF00AE00AC00BD00BC00A10089 -:10905000AB00BB0091259225932502252425C10054 -:10906000C200C000A9006325512557255D25A20037 -:10907000A5001025142534252C251C2500253C256C -:10908000E300C3005A25542569256625602550252F -:109090006C25A400F000D000CA00CB00C80031014C -:1090A000CD00CE00CF0018250C2588258425A600EC -:1090B000CC008025D300DF00D400D200F500D5001D -:1090C000B500FE00DE00DA00DB00D900FD00DD00A7 -:1090D000AF00B400AD00B1001720BE00B600A7007D -:1090E000F700B800B000A800B700B900B300B200A4 -:1090F000A025A00000000000010000000096000074 -:10910000000000000000000000000000000000005F -:109110000000000000000000D5680008D9680008C1 -:1091200071510008C9540008055100082D5100086C -:1091300055510008ED500008000000007D55000862 -:1091400069550008A5550008915500089D5500086F -:10915000895500087555000861550008B15500088B -:10916000000000008D56000879560008B55600082A -:10917000A1560008AD56000899560008855600080B -:1091800071560008C15600080000000001000000F0 -:109190000000000069646C65000000009491000804 -:1091A000C0480020504A002001000000E56200088D -:1091B000000000000000812A00000000AAAAAAAA5C -:1091C00000000024FFFE00000000000000A00A00D4 -:1091D0000001000000000000AAAAAAAA00000000E6 -:1091E000FFFF000000000000000000001400AA566D -:1091F00000000000AAAAAAAA14005554FFFF00000C -:1092000000000000CCCC0C0020681A000000000018 -:10921000AAAA8AAA10541500FFFF0000000C7007CC -:10922000770000004081020100100000AAAAAAAA4B -:1092300000410100F7FF000000000070070000007F -:109240000000000000000000AAAAAAAA0000000076 -:10925000FFFF000000000000000000000000000010 -:1092600000000000AAAAAAAA00000000FFFF000058 -:1092700000000000000000000000000000000000EE -:10928000AAAAAAAA00000000FFFF00000000000038 -:10929000000000000000000000000000AAAAAAAA26 -:1092A00000000000FFFF00000000000000000000C0 -:1092B0000000000000000000AAAAAAAA0000000006 -:1092C000FFFF0000000000000000000000000000A0 -:1092D00000000000AAAAAAAA00000000FFFF0000E8 -:1092E00000000000000000004375626550696C6F6B -:1092F0007400437562654F72616E67652B2D424C39 -:10930000002553455249414C250000000200000051 -:1093100000000000AD5800081D5900084000400042 -:10932000F862002008630020020000000000000036 -:109330000300000000000000655900080000000064 -:109340001000000018630020000000000100000071 -:10935000000000008466002001010200D1690008BD -:10936000E16800087D6900086169000843000000A9 -:109370007493000809024300020100C0320904008E -:109380000001020201000524001001052401000172 -:10939000042402020524060001070582030800FFD9 -:1093A00009040100020A0000000705010240000054 -:1093B000070581024000000012000000C093000871 -:1093C0001201100102000040AE2D581000020102EF -:1093D000030100000403090425424F4152442500C3 -:1093E000437562654F72616E6765506C75732D626F -:1093F0006473686F7400303132333435363738393E -:1094000041424344454600000000002000000200A5 -:109410000200000000000030000004000000000016 -:109420000000002400000800040000000004000008 -:1094300000FC00000200000000000430008000007A -:1094400000000000000000380000010001000000E2 -:109450001F1C1F1E1F1E1F1F1E1F1E1F1F1D1F1E26 -:109460001F1E1F1F1E1F1E1F00000000B95A0008EC -:10947000715D00081D5E000840004000BC670020D0 -:10948000BC67002001000000CC67002080000000C5 -:10949000400100000800000000010000000400007E -:1094A000080000006D61696E001643300404340842 -:1094B0000C1014181C20212200000000146EFF7FE5 -:1094C0000100000000000000270400000000000070 -:1094D00000001E0000000000FF000000504A0020B5 -:1094E000F43A0020603B0020CC3B0020000000004C -:1094F000308C00083F000000500400003B8C000846 -:109500003F00000000000000010000000096000085 -:1095100000000800960000000008000004000000A1 -:10952000D4930008000000000000000000000000CC -:109530000000000000000000000000007822002071 -:10954000000000000000000000000000000000001B -:10955000000000000000000000000000000000000B -:1095600000000000000000000000000000000000FB -:1095700000000000000000000000000000000000EB -:1095800000000000000000000000000000000000DB -:1095900000000000000000000000000000000000CB +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008DD760008AE +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008C5850008F1850008F6 +:100060001D8600084986000875860008F1450008CD +:100070001946000845460008714600089D460008DC +:10008000C5460008F1460008E3020008E302000844 +:10009000E3020008E3020008E3020008A18600086A +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E30200088D870008A1870008FA +:1000E00005870008E3020008E3020008E3020008B5 +:1000F000E3020008E3020008E30200081D470008CD +:10010000E302000879870008C9870008E3020008B5 +:10011000E3020008E3020008E3020008E30200082B +:1001200049470008714700089D470008C947000873 +:10013000F5470008E3020008E3020008E3020008B4 +:10014000E3020008E3020008E3020008E3020008FB +:100150001D4800084948000875480008E3020008E7 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008B5820008E3020008E302000879 +:10018000E3020008E3020008B5870008E302000864 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008A1820008E3020008E30200082D +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F028FA47 +:1003500006F078FB4FF055301F491B4A91423CBFD5 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F040FA06F0D8FB3F +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F028BA00060020002200203D +:1003D0000000000808ED00E00000002000060020FA +:1003E000609C000800220020742200207822002057 +:1003F00034670020E0020008E0020008E002000884 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F0EEF8FEE706F007 +:1004300047F800DFFEE7000053B94AB9002908BFBA +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000F3F901F0A3FB06F08FFE054606F0BCFFAF +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F087FE0CB167 +:1007700000F078F801F02AFB00F01AFD08B100F053 +:1007800071F8284600F010F9F9E70025ECE7054676 +:10079000EAE700BF010007B008B501F091F9A0F148 +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0A1F903B05DF804FB25 +:1007C00038B5302383F31188174803680BB105F05F +:1007D000FFFF0023154A4FF47A71134805F0EEFF2E +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F04AFA322363608E +:100810002B78032B07D163682BB9022001F040FA33 +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F01FBA0220CC +:1008500001F012BA024B00225A6070479022002029 +:1008600098230020F8B5494B494A1C4619680131C4 +:1008700000F08A8004339342F8D16268454B9A4273 +:1008800040F28280444B9B6803F1006303F5003320 +:100890009A4279D2002001F061F90220FFF7CCFFE3 +:1008A0003E4B00219A6C99641A6F19671A6FDA6CC3 +:1008B000D9645A6F59675A6F1A6D19659A6F99679B +:1008C0009B6F374BD3F8802042F00062C3F8802042 +:1008D000D3F8802022F00062C3F88020D3F8802073 +:1008E000D3F8802042F00072C3F88020D3F8802033 +:1008F00022F00072C3F88020D3F8803072B64FF037 +:10090000E023C3F8084DD4E90004BFF34F8FBFF3D1 +:100910006F8F244AC2F88410BFF34F8F536923F4BA +:1009200080335361BFF34F8FD2F8803043F6E076C7 +:10093000C3F3C905C3F34E335B0103EA060C294632 +:100940004CEA81770139C2F87472F9D2203B13F175 +:10095000200FF2D1BFF34F8FBFF36F8FBFF34F8FD5 +:10096000BFF36F8F536923F4003353610023C2F840 +:100970005032BFF34F8FBFF36F8F302383F3118853 +:10098000854680F308882047F8BD00BF00000208B4 +:1009900020000208FFFF0108002200200045025845 +:1009A0000044025800ED00E02DE9F04F93B0B44B45 +:1009B0002022FF2100900AA89D6801F0B1F9B14AF8 +:1009C0001378A3B90121B04811700360302383F379 +:1009D000118803680BB105F0FBFE0023AB4A4FF40E +:1009E0007A71A94805F0EAFE002383F31188009B81 +:1009F00013B1A74B009A1A60A64A1378032B03D0B1 +:100A000000231370A24A53604FF0000A009CD346A3 +:100A10005646D146012001F039F924B19C4B1B68A0 +:100A2000002B00F02682002001F04AF80390039B7F +:100A3000002BF2DB012001F01FF9039B213B1F2B50 +:100A4000E8D801A252F823F0C90A0008F10A000808 +:100A5000850B0008150A0008150A0008150A000889 +:100A6000170C0008E70D0008010D0008630D0008D1 +:100A70008B0D0008B10D0008150A0008C30D000811 +:100A8000150A0008350E0008690B0008150A000851 +:100A9000790E0008D50A0008690B0008150A00083D +:100AA000630D0008150A0008150A0008150A000859 +:100AB000150A0008150A0008150A0008150A00089A +:100AC000150A0008850B00080220FFF765FE0028C4 +:100AD00040F0F981009B022105A8BAF1000F08BF80 +:100AE0001C4641F21233ADF8143001F007F891E7DB +:100AF0004FF47A7000F0E4FF071EEBDB0220FFF7F3 +:100B00004BFE0028E6D0013F052F00F2DE81DFE832 +:100B100007F0030A0D1013360523042105A80593D9 +:100B200000F0ECFF17E004215548F9E704215A488A +:100B3000F6E704215948F3E74FF01C08404608F156 +:100B4000040801F00DF80421059005A800F0D6FF77 +:100B5000B8F12C0FF2D101204FF0000900FA07F78D +:100B600047EA0B0B5FFA8BFB01F026F926B10BF07D +:100B70000B030B2B08BF0024FFF716FE4AE70421E6 +:100B80004748CDE7002EA5D00BF00B030B2BA1D1CE +:100B90000220FFF701FE074600289BD00120002617 +:100BA00000F0DCFF0220FFF747FE1FFA86F8404600 +:100BB00000F0E4FF0446B0B1039940460136A1F1CC +:100BC00040025142514100F0E9FF0028EDD1BA4600 +:100BD000044641F21213022105A83E46ADF8143036 +:100BE00000F08CFF16E725460120FFF725FE244B79 +:100BF0009B68AB4207D9284600F0B2FF013040F0B5 +:100C000067810435F3E70025224BBA463E461D7046 +:100C10001F4B5D60A8E7002E3FF45CAF0BF00B03A9 +:100C20000B2B7FF457AF0220FFF706FE322000F0B7 +:100C300047FFB0F10008FFF64DAF18F003077FF44F +:100C400049AF0F4A08EB0503926893423FF642AF63 +:100C5000B8F5807F3FF73EAF124BB845019323DDD7 +:100C60004FF47A7000F02CFF0390039A002AFFF6ED +:100C700031AF039A0137019B03F8012BEDE700BF69 +:100C8000002200209423002078220020C1070008C1 +:100C90009823002090220020042200200822002017 +:100CA0000C22002094220020C820FFF775FD074683 +:100CB00000283FF40FAF1F2D11D8C5F120020AAB59 +:100CC00025F0030084494245184428BF424601925A +:100CD00001F000F8019AFF217F4801F021F84FEA66 +:100CE000A803C8F387027C492846019301F020F845 +:100CF000064600283FF46DAF019B05EB830533E703 +:100D00000220FFF749FD00283FF4E4AE00F064FF45 +:100D100000283FF4DFAE0027B846704B9B68BB420B +:100D200018D91F2F11D80A9B01330ED027F00303C7 +:100D300012AA134453F8203C05934046042205A907 +:100D4000043701F003F98046E7E7384600F008FF72 +:100D50000590F2E7CDF81480042105A800F0CEFE3E +:100D600002E70023642104A8049300F0BDFE0028DC +:100D70007FF4B0AE0220FFF70FFD00283FF4AAAECB +:100D8000049800F01FFF0590E6E70023642104A803 +:100D9000049300F0A9FE00287FF49CAE0220FFF728 +:100DA000FBFC00283FF496AE049800F00DFFEAE744 +:100DB0000220FFF7F1FC00283FF48CAE00F01CFF8E +:100DC000E1E70220FFF7E8FC00283FF483AE05A925 +:100DD000142000F017FF07460421049004A800F037 +:100DE0008DFE3946B9E7322000F06AFE071EFFF695 +:100DF00071AEBB077FF46EAE384A07EB0903926809 +:100E000093423FF667AE0220FFF7C6FC00283FF48E +:100E100061AE27F003074F44B9453FF4A5AE4846FD +:100E200009F1040900F09CFE0421059005A800F0DA +:100E300065FEF1E74FF47A70FFF7AEFC00283FF44F +:100E400049AE00F0C9FE002844D00A9B01330BD004 +:100E500008220AA9002000F06BFF00283AD02022C7 +:100E6000FF210AA800F05CFFFFF79EFC1C4805F07C +:100E7000D1FB13B0BDE8F08F002E3FF42BAE0BF08A +:100E80000B030B2B7FF426AE0023642105A80593EA +:100E900000F02AFE074600287FF41CAE0220FFF770 +:100EA0007BFC804600283FF415AEFFF77DFC41F245 +:100EB000883005F0AFFB059800F0C6FF46463C467B +:100EC00000F07AFFA6E506464EE64FF0000901E67F +:100ED000BA467EE637467CE69422002000220020B7 +:100EE000A0860100704700007047000070470000B6 +:100EF0002DE9F04100F58037044616463B7C5BB98E +:100F0000C0681030204400F0E5FEE5683544B5F5D2 +:100F1000004FE56002D816B1BDE8F081DEB905F0FA +:100F20007F0605F110000021C6F180062044F6B2CC +:100F300032462E4400F0F4FEA06804F11008324658 +:100F400000F10060414600F5003006F039F830B994 +:100F500001233B74E0E74FF400463546ECE7A26816 +:100F600005F11001404632442144A260E268521B60 +:100F7000E26000F0AFFE0220BDE8F04100F090BE5C +:100F8000183000F0E9BC000010B5044600F0FAFF8C +:100F9000204610BD10B5044600F0F4FF204610BDF9 +:100FA000C3B280B2A3F14102052A02D8373800B299 +:100FB0007047613B052B94BF57383038F7E7000086 +:100FC000F8B504461546084603220C4900F08CFE8D +:100FD000014688B908346F1C15F91100FFF7E0FFCE +:100FE000064617F911000131FFF7DAFF102940EA30 +:100FF000061004F8010BEFD1F8BD00BF10920008F5 +:101000002DE9F04FADF53F7D0746416801222AA842 +:1010100002F09AFE002840F087800646824681460C +:101020001125DFF80C81DFF80CB101AB4FF48052D1 +:1010300041462AA802F0E8FF002875D1019AB2F5CE +:10104000805F71D8002A65D00446019A9442ECD2A0 +:10105000282D0FD008DC132D2DD01E2D39D0112DA9 +:1010600013D00134A4B2F0E7322D2DD0372D2FD07C +:101070002D2DF6D13B68121B08EB040138461B6985 +:101080002D259847BDF80440EBE7121B022A09D929 +:10109000594608EB040000F027FE18B90234282551 +:1010A000A4B2DEE718F804303A2B3DD00A2B1CBF5F +:1010B000A1461325D5E718F804300A2B34D03A2B73 +:1010C00004BFA2463225CCE718F80430202BC8D044 +:1010D000264618F804300A2B1AD1AAEB090208EBAD +:1010E000090102A811254F2A28BF4F2208F07CF8D9 +:1010F000A21B08EB060116A84F2A28BF4F2208F0B2 +:1011000073F83B6816AA02A9DB6838469847A8E737 +:101110001E25A6E73B68384604491B69984701200D +:101120000DF53F7DBDE8F08F0020F9E71293000830 +:10113000A02300201492000800F1180110B5044605 +:1011400086B00846019100F0F1FB2046FFF758FFFA +:1011500060B1019902A800F049FC102204F10801D5 +:1011600002A808F001F8B0FA80F0400906B010BDFE +:1011700070B504460025EEB2304600F0FFFC58B1D1 +:1011800000213046013500F009FD08B9002070BD8E +:10119000022000F085FDEEE72046FFF731FF002832 +:1011A000F4D004F58034207C80F00100EFE70000EB +:1011B000F0B5C9B006F070F900F000FF18B90025CD +:1011C000284649B0F0BD69462A4802F0DFFF0028F2 +:1011D0004BD1294C204603F009F8284803F006F8C3 +:1011E000274803F003F82146224803F07BF8002843 +:1011F000E5D1702000F0C0FE064610B1214B4460DE +:101200000360336830469B689847054600282ED017 +:101210001A4F1948394603F065F805460028CED123 +:10122000194800F0A9FE044638B1184B4760036026 +:1012300000F58033C0E902551D74236820469B6881 +:101240009847054628B10E490C4803F04BF8002892 +:10125000B5D1336830465B6898471CB12368204697 +:101260005B68984700F092FEAAE70025FAE704467B +:10127000EFE700BF18920008289200083F9200088C +:10128000559200087892000814000100949200081A +:101290002DE9F04FD44A8DB00B68D0F804A001932B +:1012A0001A440368D14E1A44D1F81C90DFF8B4C335 +:1012B000DFF8B4B3D0E90234634003EA0A036340C1 +:1012C00013444A6802920AEB7363029CC84A2244A0 +:1012D000C468224484688AEA04051D4065401544B8 +:1012E0008A68039203EB3555039CC24A2244846802 +:1012F00022448AEA03042C4084EA0A041444CA689B +:1013000005EBF4340492164483EA05022240564465 +:101310005A4032440E69059604EBB222059FB64E40 +:101320003E441E4485EA040313406B4033444E6937 +:10133000069602EB7363069FB04E3E442E4484EA49 +:1013400002051D40654035448E69079603EB35550F +:10135000079FAB4E3E44264482EA03042C4054408F +:101360003444A84E4E4405EBF434164483EA050297 +:1013700022405A4032440E6A089604EBB222089F7B +:10138000A14E3E441E4485EA040313406B4033449F +:101390004E6A099602EB7363099F9C4ED1F830E0C8 +:1013A0003E44D1F83880F3442E4484EA02051D40BF +:1013B000654035448E6AA6F5244703EB35550A96F9 +:1013C0004F3F274482EA03042C4054403C44CF6AF8 +:1013D0000B9705EBF4340B9E8D4F3744029E174458 +:1013E00083EA050222405A403A448A4F774404EB8C +:1013F000B2221F4485EA040313406B403B444F6B09 +:10140000BC4402EB7363654484EA020C0CEA030CEF +:101410008CEA040C6544DFF854C2C44403EB355530 +:10142000A44482EA03042C4054406444D1F83CC0F4 +:10143000794905EBF4346144114483EA0502224002 +:101440005A400A44754904EBB2223144079E1944BC +:1014500084EA02032B4063400B44714902EBF363BF +:1014600031440B9E0D4482EA03012140514029443E +:101470006C4D03EBF1513544019E254483EA010490 +:1014800014405C402C44684D01EBB4443544069E46 +:10149000154481EA04021A404A402A44634D04EB91 +:1014A000323235440A9E1D4484EA02030B406340F5 +:1014B0002B445F4D02EBF3633544059E0D4482EAF5 +:1014C00003012140514029445A4D03EBF151654439 +:1014D000254483EA010414405C402C44564D01EB42 +:1014E000B4443544099E154481EA04021A404A4036 +:1014F0002A44524D04EB32323544049E1D4484EAA2 +:1015000002030B4063402B444D4D02EBF363454413 +:101510000D4482EA0301214051402944494D03EB27 +:10152000F1513544089E2C4483EA010515405D4085 +:101530002C44454D01EBB4443544039E2A4481EAD2 +:1015400004051D404D402A44404D04EB32323D44D9 +:101550002B4484EA020593440D4065402B443C4DE6 +:1015600002EBF3633544069E294482EA03052540D5 +:1015700055402944374D03EBF1514D442C4483EA47 +:10158000010515405D40254401EBB54581EA0504A0 +:1015900004EA03024A405A44A6F5B82B089E05EB1C +:1015A0003232ABF2BE6B54405B4423442A4C344489 +:1015B00002EB33730B9E0C4485EA0201594021442F +:1015C000264C344403EB7151029E254482EA030405 +:1015D0004C402544224C444401EB3545144483EAF5 +:1015E00001026A40224443E078A46AD7EECEBDC12E +:1015F00056B7C7E8DB702024AF0F7CF52AC68747B3 +:10160000134630A8019546FDD8988069AFF7448B02 +:10161000BED75C892211906B2108B44962251EF661 +:1016200040B340C0515A5E26AAC7B6E95D102FD616 +:101630005314440281E6A1D8C8FBD3E7E6CDE121EB +:10164000D60737C3870DD5F4ED145A4505E9E3A94C +:10165000F8A3EFFCD9026F6781F6718722619D6D57 +:101660000C38E5FD937198FD8A4C2A8D8E4379A63E +:10167000934C344405EB7222059E1C4481EA050319 +:10168000534023448F4C344402EB33730A9E0C4482 +:1016900085EA0201594021448B4C4C4403EB7151C3 +:1016A000254482EA03044C402C44884D354401EB28 +:1016B0003444019E154483EA010262402A44844D69 +:1016C0003D4404EB72221D4481EA040353402B4441 +:1016D000804D354402EB3373049E294484EA0205AD +:1016E0005D4029447C4D354403EB7151079E2544F0 +:1016F00082EA03044C402C44784D354401EB3444D9 +:10170000099E2A4483EA010565401544744A32441F +:1017100004EB7525039E134481EA04026A401A44CF +:10172000704B734405EB32720B4484EA050151405F +:1017300019446D4B634402EB71511C4485EA02036A +:101740004B401C44694B334401EB3444019E1D441F +:1017500082EA010363402B44654D04EB7323354457 +:10176000069E154463EA010262402A44614D03EB80 +:10177000B2624D4462EA040929445F4D89EA0309D3 +:10178000454449442C445D4D02EBB1513544049E1F +:1017900061EA03081D4488EA0208444401EB7444EA +:1017A00064EA02034B402B44554D04EBF32375448C +:1017B00063EA010E15448EEA040E0EEB0502514D4C +:1017C00003EBB262354462EA040E29440A9D8EEAB4 +:1017D000030EA5F580164C4D7144A6F6833602EB38 +:1017E000B151264461EA030454403444029E01EBA3 +:1017F0007444354464EA02061D444E407319089E41 +:10180000424D04EBF323354463EA01061544664078 +:1018100072193F4D03EBB262654462EA0406294443 +:101820003C4D5E403144079E02EBB151354461EAC4 +:1018300003062C44384D56403D443444059E1D4417 +:1018400001EB744464EA02034B402B44334D04EB38 +:10185000F32335440B9E154463EA010262402A4497 +:101860002F4D03EBB2623544039E0D4462EA04013E +:10187000594029442B4D02EBB15135442A4E2544A1 +:1018800061EA030454402C44099D01EB74442E4446 +:1018900064EA02051E4485EA01039D1903681A449F +:1018A0000AEB040303EBF5230260436083681C44E6 +:1018B000C36819448460C1600DB0BDE8F08F00BFFB +:1018C00044EABEA4A9CFDE4B604BBBF670BCBFBEE2 +:1018D000C67E9B28FA27A1EA8530EFD4051D88042F +:1018E00039D0D4D9E599DBE6F87CA21F6556ACC4A3 +:1018F000442229F497FF2A43A72394AB39A093FCF1 +:10190000C3595B6592CC0C8FD15D84854F7EA86FE7 +:10191000E0E62CFE144301A3A111084E827E53F78A +:1019200035F23ABDBBD2D72A91D386EB094B03607F +:1019300003F18833436003F12943A3F59613A3F61B +:101940008B638360A3F18833C3600023C0E9043351 +:10195000704700BF012345672DE9F843144602692B +:1019600005460E46E300C2F3C50800F118079B18B0 +:10197000036122BF43690133436112F4FC7F436971 +:1019800003EB5473436114D0C8F1400907EB08001E +:101990004C4504D22246BDE8F84307F0F5BB403C75 +:1019A0004A464E4407F0F0FB444439462846FFF7C8 +:1019B0006FFCA04606EB0409B8F13F0FA9EB080144 +:1019C0000AD94022384607F0DFFB39462846A8F1FD +:1019D0004008FFF75DFCEFE7A1096FF03F023846D2 +:1019E00002FB014206EB8111D5E7000070B50B69DF +:1019F00001F1180506460C46C3F3C503EA18501C4E +:101A00008022EA54C3F13F02072A1FD8002100F0C8 +:101A100087F929462046FFF73BFC3822002128465B +:101A200000F07EF9236929462046236563696365D2 +:101A3000FFF72EFC21461022304607F0A5FB20467A +:101A400058220021BDE8704000F06AB9C3F13702A6 +:101A50000021E5E72DE9F84F4FF47A7306460D466D +:101A6000002402FB03F7DFF85080DFF8509098F96C +:101A700000305FFA84FA5A1C01D0A34210D159F801 +:101A800024002A4631460368D3F820B03B46D847A5 +:101A9000854205D1074B012083F800A0BDE8F88FEF +:101AA0000134042CE3D14FF4FA7004F0B3FD0020AC +:101AB000F4E700BFE43300201022002014220020AD +:101AC000002307B5024601210DF107008DF807300C +:101AD000FFF7C0FF20B19DF8070003B05DF804FBDD +:101AE0004FF0FF30F9E700000A46042108B5FFF780 +:101AF000B1FF80F00100C0B2404208BD074B0A466A +:101B000030B41978064B53F821400146236820462B +:101B1000DD69044BAC4630BC604700BFE4330020B5 +:101B200014220020A086010070B50A4E00240A4D40 +:101B300005F0EAF9308028683388834208D905F037 +:101B4000DFF92B6804440133B4F5003F2B60F2D376 +:101B500070BD00BFE6330020A033002005F0A2BA1C +:101B600000F1006000F500300068704700F100608F +:101B7000920000F5003005F023BA0000054B1A680A +:101B8000054B1B889B1A834202D9104405F0B8B953 +:101B900000207047A0330020E633002038B504460B +:101BA000074D29B128682044BDE8384005F0C0B988 +:101BB0002868204405F0AAF90028F3D038BD00BFFA +:101BC000A03300200020704700F1FF5000F58F1077 +:101BD000D0F8000870470000064991F8243033B16E +:101BE00000230822086A81F82430FFF7BFBF0120D4 +:101BF000704700BFA4330020014B1868704700BF36 +:101C00000010005C194B01380322084470B51D68B0 +:101C1000174BC5F30B042D0C1E88A6420BD15C6834 +:101C20000A46013C824213460FD214F9016F4EB1AD +:101C300002F8016BF6E7013A03F10803ECD18142A7 +:101C40000B4602D22C2203F8012B0424094A1688E1 +:101C5000AE4204D1984284BF967803F8016B013CF0 +:101C600002F10402F3D1581A70BD00BF0010005CED +:101C700024220020D4920008022803D1024B4FF006 +:101C800080529A61704700BF00100258022803D1A9 +:101C9000024B4FF480529A61704700BF0010025807 +:101CA000022804D1024A536983F480535361704778 +:101CB0000010025870B504464FF47A764CB1412CAE +:101CC000254628BF412506FB05F0641B04F0A2FC55 +:101CD000F4E770BD002310B5934203D0CC5CC4542C +:101CE0000133F9E710BD0000013810B510F9013FCC +:101CF0003BB191F900409C4203D11AB10131013A44 +:101D0000F4E71AB191F90020981A10BD1046FCE7CB +:101D100003460246D01A12F9011B0029FAD1704776 +:101D200002440346934202D003F8011BFAE77047CE +:101D30002DE9F8431F4D14460746884695F82420A0 +:101D400052BBDFF870909CB395F824302BB9202259 +:101D5000FF2148462F62FFF7E3FF95F82400414634 +:101D6000C0F1080205EB8000A24228BF2246D6B28D +:101D70009200FFF7AFFF95F82430A41B17441E44D0 +:101D80009044E4B2F6B2082E85F82460DBD1FFF768 +:101D900023FF0028D7D108E02B6A03EB820383429C +:101DA000CFD0FFF719FF0028CBD10020BDE8F88382 +:101DB0000120FBE7A4330020024B1A78024B1A7073 +:101DC000704700BFE433002010220020F8B5194C02 +:101DD000194803F027FF2146174803F04FFF2468F6 +:101DE0004FF47A70154ED4F89020154DD2F804387F +:101DF000114F43F00203C2F80438FFF75BFF20469F +:101E0000104904F049F8D4F890200424D2F804389A +:101E100023F00203C2F804384FF4E133336055F87D +:101E2000040BB84202D0314603F05AFE013CF6D111 +:101E3000F8BD00BFD49A000818490020CC33002018 +:101E400014220020DC9A00080C4B70B50C4D04469F +:101E50001E780C4B55F826209A420DD00A4B0021D3 +:101E600018221846FFF75CFF0460014655F826006B +:101E7000BDE8704003F034BE70BD00BFE433002005 +:101E80001422002018490020CC330020F8B571B688 +:101E9000002301201A46194602F08AFD04468020DC +:101EA00005F0A0F9002849D00025254A80274FF4E5 +:101EB000D06C3D26136913F0C06F26D1D2F81031D3 +:101EC00013F0C06F21D1236805F100619960236888 +:101ED000D86023685F602368C3F800C021680B687E +:101EE00043F001030B6021680B6823F01E030B60B5 +:101EF00021680B68DB07FCD4237B8035616806FA18 +:101F000003F3B5F5001F0B60D4D1204602F086FD27 +:101F1000B5F5001F11D000240A4E0B4D012005F02D +:101F2000C1F83388A34205D928682044013404F05D +:101F3000FFFFF6E7002005F0B5F861B6F8BD00BF79 +:101F400000200052E6330020A033002030B50A44C0 +:101F5000084D91420DD011F8013B5840082340F341 +:101F60000004013B2C4013F0FF0384EA5000F6D13B +:101F7000EFE730BD2083B8ED0121884238BF084625 +:101F800005F068B908B105F069B9704710B5084C9B +:101F900001220849002001F0B3FE23783BB1064836 +:101FA00003F016FD044803F049FD0023237010BD23 +:101FB000E8330020E4920008C83600201D482DE9CF +:101FC000F041036D2BB901224FF48051503005F0E0 +:101FD000CDFA194E33780BB1FFF7D8FF0324174F12 +:101FE0004FF00008134D15492846C7F8048003F048 +:101FF00017FD284603F050FB48B1013C284603F08A +:102000001DFD14F0FF04EED1204634700FE00C49A2 +:1020100001220C4801F074FE014618B1284603F075 +:10202000D7FCEAE7084800F011F801203070BDE85D +:10203000F08100BFC8360020E83300203C22002099 +:10204000E4920008EC330020E89200080FB400206E +:1020500004B07047006870470346006859687047CD +:102060000B0A017043700B0C090E8370C17070472E +:10207000110A027003714170110C120E8170C2704E +:102080001A0A42711A0C1B0E8271C371704700004C +:10209000C36A0239023B8B4283BF4389006C01FB58 +:1020A0000300002070470000C2F307238A76CB7636 +:1020B0000378032B01BF120C0A75120A4A75704788 +:1020C00000F10B010022D30143EA520310F8012B67 +:1020D00052FA83F38842DAB2F5D110467047000015 +:1020E00010B5417804460020013102464901022A18 +:1020F00016BFA35C032203EBC03302F101021EBF33 +:102100009BB203EB500398B29142F0D810BD00008F +:1021100002684AB1134613F8011B1F290DD93A2949 +:10212000F9D1911C8B4202D04FF0FF3070471278EA +:10213000302AF9D1036000207047014B18787047AE +:102140003836002038B50D46044618B9092000235A +:102150002B6038BD0368002BF8D01A78002AF5D020 +:102160008188DA889142F1D1587804F0EFFB10F0C1 +:102170000100EBD12368EBE738B50D4640F2523150 +:10218000144602F0B9F9FF2807D9012C0BD9030A2C +:10219000022468702B70204638BD30B1002CFAD074 +:1021A00001242870F7E70024F5E70446F3E7000070 +:1021B0002DE9F8430026D0F8008005460C468E76BF +:1021C000836B002B4AD098F80030042B4BD1334658 +:1021D0003546402720E0B7F5187F80F0C480F90627 +:1021E00006F1010608BF0237D05B02372BB900F5B4 +:1021F000205292B2B2F5006F0DD305F11A01C5F16C +:10220000FF0240EA03402144FFF7B6FF002800F038 +:10221000AA80054400200346D8F8102092F8231025 +:10222000B142D8D8002B40F09E80002D00F09B805A +:1022300000232544AB766373D8F81020137903F09C +:102240003701DB0621730BD402F13800FFF704FFDE +:10225000C4E9000193896381D3892381BDE8F883B0 +:1022600000200146F4E7C36C01335ED1EA6B002322 +:102270002E26551E184615F8011F013020290CD0B6 +:10228000052908BFE521092804D10B2B9EBFE718BB +:1022900001337E73E718013379730B28EBD1E11812 +:1022A00000204873A17E00294BD1002B40D06FF055 +:1022B0000C0604F10D000825361B331810F8011B1D +:1022C000002938D02E298BB24AD0A3F14101192917 +:1022D00003D8117B0D4200D020330373EDE7B9F131 +:1022E000000F05D100F520539BB2B3F5006F0BD35F +:1022F00007F11A01C7F1FF0240EA09402144FFF744 +:102300003BFF48B10744002002368146D8F80C3024 +:10231000985B0028E3D13846B9F1000F4FF0000276 +:1023200018BF002023189A76A0E7B1463746EDE79C +:102330003F23A3760123234400219976137B03B91D +:102340006373D37A02F11C0003F03F03237300236D +:10235000FFF780FE20606360D38A6381138B7CE784 +:1023600010250B46B9E73F230125A37660E700005F +:1023700038B50546002435F8020B08B9204638BDAB +:1023800002F0EEF86308C2B203EBC43312FA83F32F +:102390009AB2C0F3072303EB520303EBC2339CB2A0 +:1023A000E9E7000037B5C37804461BB90025284685 +:1023B00003B030BD00F14C01826C012340780191E3 +:1023C00004F0EAFA054680B9A36BE070A06C226BBA +:1023D000C31A9342EAD2A3780199022BE6D10244B0 +:1023E0000123607804F0D8FAE1E70125DFE7000077 +:1023F00038B5836C05460C468B4210D0FFF7D2FFF0 +:1024000060B92246012305F14C01687804F0A0FA76 +:1024100000281CBF4FF0FF340120AC6438BD002001 +:10242000FCE7000038B500230446C3704FF0FF33CB +:102430008364FFF7DDFF00284BD1B4F84A524AF617 +:1024400055239D4207D10B22254904F14C0006F08B +:102450008BFE00283FD094F84C30EB2B03D0183380 +:10246000DBB2012B2ED84AF655239D4206D1082215 +:102470001C4904F19E0006F077FE48B3B4F85730CB +:10248000B3F5007F1ED194F85930DBB15A1E1A42C1 +:1024900018D1B4F85A30ABB194F85C30013B012B41 +:1024A00010D8B4F85D306BB1B4F85F307F2B06D82C +:1024B00004F16C00FFF7CEFDB0F5803F02D3B4F815 +:1024C000623053B94AF6552085420CBF02200320E2 +:1024D00038BD0420FCE70120FAE70020F8E700BF40 +:1024E000149300082093000802392DE9F04701F009 +:1024F00007044FF0010A466C05460AFA04F4174631 +:10250000984606EB1136C1F3C809E4B231462846B5 +:102510000136FFF76DFF18B10120BDE8F08799463D +:1025200005EB090292F84C30234214BF012100212F +:10253000414513D06340013F82F84C3085F803A039 +:10254000EBD0640014F0FF04EAD109F10103012487 +:102550004FF00009B3F5007FE1D1D7E70220DCE7B7 +:1025600001290246F8B50C4640F28C800668F36AF1 +:102570008B4240F287803378013B032B00F282804C +:10258000DFE803F00229384B04EB5405B16B304609 +:1025900001EB5521FFF72CFF10B14FF0FF30F8BDD4 +:1025A0006F1CC5F30805B16B3046354401EB57216C +:1025B00095F84C50FFF71CFF0028EED1C7F3080731 +:1025C000E3073E4496F84C0045EA00204CBF000962 +:1025D000C0F30B00E3E7B16B304601EB1421FFF7CA +:1025E00007FF0028D9D1640004F4FF742644B6F82C +:1025F0004C00D4E7B16B304601EBD411FFF7F8FE85 +:102600000028CAD1A40006F14C0004F4FE74204452 +:10261000FFF720FD20F07040C1E7D0E90430D57904 +:1026200053EA000101D0916801B95DBB9168022DA8 +:10263000A4EB01010DD1013B728940F1FF305B0A2F +:1026400043EAC053B3FBF2F399421BD81CD0601C81 +:10265000A5E7032D02D193698B42F8D8D3699BB9C2 +:10266000B16B304601EBD411FFF7C2FE002894D1C4 +:10267000A0004C3600F4FE703044FFF7EBFC20F075 +:1026800000408CE701208AE76FF0004087E70000F8 +:10269000F8B5066804460D463378042B0CBF4FF09E +:1026A00080524FF400128A4201D80220F8BDCA06B7 +:1026B000FBD182680163D2B9022B13D83389B3EB03 +:1026C000551FF2D9F36BA363A36B6263002BECD0AD +:1026D00003EB55234C36C5F308050020A3633544AE +:1026E000E563E3E7F36BC271002BE7D01A46778905 +:1026F0007F02BD42114604D23046FFF7C9FCA063F9 +:10270000E2E72046FFF72CFF431C024606D00128D3 +:10271000CBD9F36A8342C8D9ED1BEAE70120C5E7AC +:1027200001292DE9F04706460C46174608D9C36A29 +:102730008B4205D90378022B62D003D8012B22D01B +:10274000022552E0033B012BFAD8816B01EBD41137 +:10275000FFF74EFE0546002847D1A40006F14C03C2 +:1027600004F4FE741C443378042B07D0204627F071 +:102770007047FFF76FFC00F0704007433946204672 +:10278000FFF76EFC2FE001EB5108816B01EB582144 +:10279000FFF72EFE054640BB14F0010406F14C097C +:1027A00008F1010AC8F3080808BFFBB230461FBF92 +:1027B00019F8083003F00F023B0103F0F00318BFD3 +:1027C000134309F808300123B16BF37001EB5A2170 +:1027D000FFF70EFE054640B9CAF3080A44B1C7F335 +:1027E000071709F80A700123F3702846BDE8F0873F +:1027F00019F80A30C7F3032723F00F031F43F0E74C +:10280000816B01EB1421FFF7F3FD05460028ECD1A5 +:10281000640006F14C0304F4FF741F551919C7F343 +:1028200007274F70DFE70000F8B504460E4617464D +:10283000E3690BB91846F8BD012BA6EB0305206828 +:1028400014BFAA1C3A46691CFFF76AFF0028F2D1A0 +:10285000E369013BE361EBE701292DE9F843064613 +:102860000C461746056802D80220BDE8F883EB6ADB +:102870008B42F9D97AB9A14621463046A046FFF7E6 +:102880006FFE0446B0B92B78042B02D1002F43D140 +:10289000F7710020E9E72B78042B02D1C379022BD2 +:1028A000E9D04FF0FF3239462846FFF739FF0028BC +:1028B000E1D0DAE70128D7D0421C01D10120D4E7CA +:1028C0002B78042B19D1EA6AAB69023A93421CD3E4 +:1028D00008F10102A2420CD02B78042B08D100236E +:1028E000A2EB090249462846FFF7FEFD0028BCD1AD +:1028F000A146EB6AA342BFD8C5E70022414628465D +:10290000FFF70EFF0028DED0AFE70133AB612B7974 +:1029100043F001032B71DBE7F3798BB9B468BC4258 +:1029200002D10223F371B4E721463046FFF718FEC7 +:10293000012899D9431CC1D001348442EFD0A8E7C3 +:10294000032BA6D1B368BB42A3D8B2691344BB42E0 +:102950009FD3E6E770B5C3790446032B06D181689F +:102960008369CD18A94203D10023E371002070BD13 +:102970004E1C20683246FFF7D3FE0028F7D13146BF +:10298000F0E700002DE9F74305460191FFF70AFD46 +:102990000446002849D105F14C09019928464FF415 +:1029A0000072FFF775FB2146A86407464846FFF70B +:1029B000B7F96C896402B4F5004F28BF4FF40044A6 +:1029C000B4F5007F2FD9204604F04CFC804630B18E +:1029D00022460021640A0026FFF7A2F909E06408F4 +:1029E000EEE72346BA194146687803F0D5FF18B9D7 +:1029F00026446B899E42F4D3404604F043FC688928 +:102A0000801B18BF012003B0BDE8F08301366B893D +:102A10009E42F4D20123BA194946687803F0BCFFFC +:102A20000028F3D0EBE70026F1E70120EBE70000F8 +:102A3000F8B50446FFF7B6FC0546002842D12378D6 +:102A4000032B37D12779012F34D104F14C060146ED +:102A50004FF400723046FFF763F95523412272218B +:102A600084F84A32AA2304F50D7084F84F2084F8C4 +:102A70004B32522384F8301284F84C3084F84D30B5 +:102A8000612384F8311284F84E3084F83332A1691E +:102A900084F83222FFF7E4FA616904F50E70FFF75B +:102AA000DFFA626B3B46314601326078A26403F084 +:102AB00073FF257100226078114603F091FF003802 +:102AC00018BF0120F8BD000000232DE9F0430B6082 +:102AD00085B00F461546FFF71BFB061EC0F2B281FC +:102AE000804B53F82640002C00F0AE813C6005F08E +:102AF000FE0523786BB1607803F028FFC70708D480 +:102B00001DB110F0040500D00A25284605B0BDE827 +:102B1000F0830023F0B22370607003F003FFC1075D +:102B200000F194810DB14207EED400212046FFF759 +:102B300079FC022840F099806E4604F2122304F2D8 +:102B40005221324618461033FFF784FA42F8040B3C +:102B50008B42F7D1002556F8041B00297DD0204672 +:102B6000FFF760FC012879D80128A26C40F0C080F2 +:102B700004F1570304F18C0113F8015B002D7BD1A4 +:102B80008B42F9D1B4F8B430B3F5807F74D194F8A6 +:102B9000B830092B70D104F19400FFF75DFA4FF0C3 +:102BA000FF33171841F10001BB4275EB010363D3FA +:102BB00004F1A000FFF74EFA94F8BA302063012B1D +:102BC000A37059D194F8B99003FA09F91FFA89F35F +:102BD0006381002B50D0444B04F1A800FFF73AFA70 +:102BE0000646984248D8831C626304F1A400E3625D +:102BF000FFF730FA00EB020804F19C00C4F84080B3 +:102C0000FFF728FA10441FFA89F2A06306FB02F3CB +:102C100013EB080345EB05029F4271EB02032BD334 +:102C20002E4604F1AC00FFF715FAE06365B963893D +:102C3000B34221D9E16B2046FFF72AFA81192046D9 +:102C4000FFF7D6FB98B90136631993F84C30812B06 +:102C500014D02035C5F30805E8E703200135042D1D +:102C60007FF479AF042807D101E0042801D10125C0 +:102C70004BE701287FF678AF0D2546E705F11400F4 +:102C800004F14C063044FFF7E5F901280546F3D975 +:102C9000E36A8342F0D96189821E236C02FB01330F +:102CA0006364A16B204601EBD511FFF7A1FB00285F +:102CB000DDD105F07F0006EB8000FFF7CBF9431C68 +:102CC00003D00135A842ECD0D6E70425C4E90500BD +:102CD000064A257000251388E56101339BB21380F5 +:102CE000E38012E73C360020FDFFFF7F40360020E6 +:102CF000B4F85730B3F5007FBED1B4F8626026B99E +:102D000004F17000FFF7A6F9064694F85C302663DC +:102D1000591EA3700129AFD894F859506581002D30 +:102D2000AAD0691E2942A7D1B4F85D8018F00F0F10 +:102D3000A4F80880A0D1B4F85F0018B904F16C00C1 +:102D4000FFF788F9B4F85A10002995D006FB03FE66 +:102D500001EB181CF44460458ED3A0EB0C00A84294 +:102D6000B0FBF5F388D33E48834285D84FF6F57023 +:102D700083426DD903259F1C114402EB0C03032DE4 +:102D8000E7626263A16323644CD1B4F8763053EAFE +:102D900008037FF471AFBB0004F17800FFF75AF924 +:102DA000E06303F2FF13B6EB532FFFF465AF4FF070 +:102DB000FF33032DC4E905334FF08003237187D11E +:102DC000B4F87C30012B83D1511C2046FFF710FB57 +:102DD00000287FF47DAFB4F84A224AF655232071CB +:102DE0009A427FF475AF1F4B04F14C00FFF732F9A4 +:102DF00098427FF46DAF03F1FF5304F50C70FFF7B9 +:102E000029F903F50053203398427FF461AF04F5AC +:102E10000D70FFF71FF9A06104F50E70FFF71AF9A6 +:102E2000606155E7B8F1000F3FF426AF7144022D01 +:102E30004FEA4703E1631EBFD91907F0010303EB13 +:102E40005103AEE70B2560E60C255EE603255CE644 +:102E500040F6F575AB428CBF022501258BE700BF1C +:102E6000F5FFFF0F525261412DE9F84F0746056803 +:102E7000884649B96E69C6B1EB6AB34298BF01266C +:102E8000AB69A3B9002405E0FFF76AFB01280446FB +:102E900003D801242046BDE8F88F421C00F0D28000 +:102EA000EB6A8342F6D84646EAE70126E8E72A7845 +:102EB000EB6A042A40F08380A6F1020A023B4FF03D +:102EC000010B9A4528BF4FF0000AD146696C28468D +:102ED00001EB1931FFF78CFA00283BD109F0070309 +:102EE000EA6AC9F3C8010BFA03F3901EDBB26A1851 +:102EF0004C4609F1010992F84C20814502EA03028F +:102F000033BF5B0000234FF40071DBB228BF99464A +:102F1000B2B90234631E0333BCD8012321462846CC +:102F20001A46FFF7E1FA0228B3D0012800F08A80A0 +:102F3000B8F1000F13D10223FB710028A9D130E0B2 +:102F4000CA450AD0002BD2D10131B1F5007FBDD2E4 +:102F50000123CCE74FF0FF34DCE70024DAE7FB790C +:102F6000022B07D1731CA342E7D0BB68F31ABB61E5 +:102F70000323FB7108F10102FB69A24205D113B1E1 +:102F80000133FB61D9E70223FBE70BB90123FB61A6 +:102F9000224641463846FFF747FC00284FD101231F +:102FA000FB61EA6AAB69023A6C6193429CBF03F130 +:102FB000FF33AB612B7943F001032B716AE7464580 +:102FC00014D1741C3846A34298BF02242146FFF74F +:102FD000C7FA01283FF45DAF431C33D0E0B16B6901 +:102FE000012B03D9EA6A934238BF1E4634460134A6 +:102FF000EB6AA34203D8012E7FF644AF0224214698 +:103000003846FFF7ADFA48B101283FF442AF01302E +:1030100018D0B442EBD135E7002CE7D04FF0FF32A7 +:1030200021462846FFF77CFB48B9B8F1000FB8D01D +:10303000224641462846FFF773FB0028B1D00128FD +:103040007FF427AF4FF0FF3424E700002DE9F84369 +:1030500006680446076B894633782037042B0CBF7B +:103060004FF080534FF40013BB429CBF0023836397 +:10307000836B73B1C7F30808B8F1000F3CD101337B +:10308000416B836339B93389B3EB571F34D80023BD +:10309000A36304200AE07389013B13EA57232BD171 +:1030A000FFF75EFA0128054602D80220BDE8F88342 +:1030B000421C01D10120F9E7F36A834216D8B9F125 +:1030C000000FE4D0616B2046FFF7CEFE0546C8B185 +:1030D0000128EAD0431CEDD001463046FFF752FCF0 +:1030E0000028E7D1E37943F00403E3712946304631 +:1030F0006563FEF7CDFFA0634C360020276346448E +:10310000E663D3E70720D1E7F8B50E460021044671 +:103110000768FFF7BDFA98B90546A16B3846FFF777 +:1031200067F968B93A78E36B042A1B780CD11B065F +:103130000ED5054601212046FFF788FF0028ECD078 +:10314000042808BF072006E0E52B01D0002BF0D1B2 +:103150000135B542EED1F8BDC16C4B1C2DE9F041F3 +:1031600004460568066B1FD1E5274FF00108A16BE7 +:103170002846FFF73DF998B92A78E36B042A09BF7E +:103180001A781F7002F07F021A7085F80380236B93 +:10319000B3420DD200212046FFF758FF0028E6D0A9 +:1031A000042808BF022003E0FFF772FA0028DBD0F2 +:1031B000BDE8F0812DE9F04105460068A96B06697C +:1031C000FFF716F9044620B9EB6B1A78852A03D06D +:1031D00002242046BDE8F081324603F1200153F875 +:1031E000040B8B4242F8040BF9D1777801377F0149 +:1031F000A7F16003B3F5007FEAD800212846FFF766 +:1032000025FF04280446E3D00028E2D1A96B2868F2 +:10321000FFF7EEF804460028DBD1EB6B1A78C02AE2 +:10322000D6D106F1200203F1200153F8040B8B42A2 +:1032300042F8040BF9D196F823300F222C33B3FB5C +:10324000F2F3B7EB431FC3D34FF0400800212846E9 +:10325000FFF7FCFE04280446BAD00028B9D1A96BB8 +:103260002868FFF7C5F804460028B2D1EB6B1A783E +:10327000C12AADD1B8F5187F09D206EB080203F1D7 +:10328000200153F8040B8B4242F8040BF9D108F1EA +:1032900020084745DAD8B8F5187F9AD83046FEF7A7 +:1032A0001FFF7388834294D092E700000B680022CE +:1032B00010B5036004460B6A83604B6AC261C37138 +:1032C00023F0FF03896AC0E90432C164FFF7E0F923 +:1032D00020B92046BDE81040FFF76CBF10BD0000CC +:1032E000F8B50368054601271C692046FEF7F8FE7D +:1032F000A070000A6678E0702846E96CFFF7C8F90C +:1033000020B1022828BF0220C0B2F8BDA96B2868EE +:10331000FFF76EF80028F4D1EB6B04F1200254F8AB +:10332000041B944243F8041BF9D12B68DF70002E74 +:10333000E7D000212846013EFFF788FEE0E70000C5 +:103340002DE9F8434FF0FF08064607680424454678 +:103350004FF6FF79B16B11B9002C73D063E038469A +:10336000FFF746F8044600285DD1F06B0378002B88 +:103370006ED03A78042A11D1852B4DD1336B30466B +:10338000F364FFF717FF044600284CD13B691B7913 +:1033900003F03F03B3712046BDE8F883C27AE52B02 +:1033A00002F03F02B27143D02E2B41D022F0200117 +:1033B00008293DD00F2A40D1590637D503F0BF0563 +:1033C000336B90F80D80F364437B434530D1428BDF +:1033D00072BB03780D21FC6823F04003DFF874E032 +:1033E000013B4B4301211EF801CB30F80CC009B35F +:1033F000FF2B1DD824F813C06146013301320D2A7A +:10340000F1D10278520605D521B1FF2B10D8002248 +:1034100024F81320013DEDB200213046FFF716FEDF +:103420000446002896D00023B363B4E7AB42CBD068 +:10343000FF25F1E7CC45E1D0FAE72DB9FEF740FED4 +:10344000404501D10024A6E74FF0FF33F364A2E723 +:103450000424E8E7BC9300082DE9F04F002187B071 +:103460000446D0F80090FFF713F9804670B999F838 +:103470000030042B33D1D9F80C00FEF779FF074652 +:103480002046FFF75DFF054620B18046404607B065 +:10349000BDE8F08FD9F810309A8CBA42F0D193F889 +:1034A00023B040265D4506D1D9F80C3033F81530ED +:1034B000002BE5D1EAE7F106D9F8103008BF023653 +:1034C000985B01F04DF8D9F80C30824633F81500BE +:1034D00001F046F88245D3D102360135E2E74FF0DC +:1034E000FF0A4FF0FF3B5546C4F84CB0A16B48466D +:1034F000FEF77EFF00285CD1E66B3778002F77D08F +:10350000F27AE52F02F03F03A37103D0120704D52E +:103510000F2B04D0C4F84CB04FE00F2B54D194F8CB +:103520004B3058063FD4790645D5236B07F0BF07CB +:1035300096F80DA0E364737B53453ED1738B002B4B +:103540003BD135780121D9F80C3005F03F050193C6 +:103550000D23013D5D43284B13F8012BB25A71B383 +:10356000FF2D059329D81046049200F0F9FF6B1C3B +:1035700003900293019B33F8150000F0F1FF0399CB +:1035800081421AD1049A029D1146059B1B4A93421F +:10359000E2D133785A0604D519B1019B33F81530BE +:1035A0005BB97D1EEDB200212046FFF74FFD0028DC +:1035B0009CD080466AE7BD42BDD0FF25F3E74FF6B9 +:1035C000FF708242E2D0F8E72DB93046FEF778FD71 +:1035D00050453FF45BAF94F84B30DB079AD40B2295 +:1035E00004F14001304605F0BFFD002892D14DE7BF +:1035F0004FF004084AE700BFBC930008C9930008D5 +:103600002DE9F04F90F84BB099B004461BF0A0059F +:1036100040F068810668F26832F81530002B4AD114 +:103620003378042B40F087800F230E352046B5FBFE +:10363000F3F5A91CFFF768FD8146002877D1236BBD +:103640000135A3EB4515E3795A07E56435D523F039 +:1036500004032046E371FFF77DF950BB4FF0FF32C2 +:10366000616B2046FFF7E0F818BBA3682BB3214637 +:1036700004A8FFF71BFEE0B970894FF40071D4E98C +:103680000423E0FB01233069C4E904233830FEF74A +:10369000EFFC3069D4E904232830FEF7E9FCE37934 +:1036A000326904A843F0010382F82130FFF718FEC5 +:1036B00018B181463BE00135AEE7D6E9035440221C +:1036C00000212046FEF72CFB852301214022237098 +:1036D000C0234FF0C10C04EB010884F82030002314 +:1036E0001E469E46571C04F802C0F0B2023204F88F +:1036F00007E021B135F8131009B10133DBB20F0A2D +:10370000A15408F802700232D706F2D135F81370CE +:103710000136002FE6D184F82330831C28466370DD +:10372000FEF726FE84F82400000A84F825004846A7 +:1037300019B0BDE8F08F04F140070DF1100A1BF03D +:10374000010F97E807008AE8070000F0D3804023C4 +:103750004FF0010884F84B30BC46F368B8F1050F10 +:103760009AE80700ACE803002CF8022B4FEA12425B +:103770008CF8002059D9981E424630F8021F0029C3 +:1037800042D10DF10F0C072102F00F0E91461209E4 +:103790000EF13000392888BF0EF1370001390CF8DE +:1037A000010902D0B9F10F0FEED818AB7E205A18DC +:1037B00002F8580C38460022914206D010F801CB8E +:1037C00002F1010EBCF1200F31D104F13F0C0729A9 +:1037D00002F1010297BF18AB20205818013198BFA1 +:1037E00010F8580C072A0CF80200F0D92046FFF711 +:1037F00033FE8146002878D108F10108B8F1640F42 +:10380000AAD14FF0070992E74FF0100C01F0010E1A +:1038100049080EEB4202D30344BF82F4883282F09F +:103820002102BCF1010CF1D1A7E74246A9E772469B +:10383000C2E7216B2046A1EB4511FEF729FF814627 +:1038400000287FF474AF4FF6FF783846FEF738FC57 +:103850000190A16B3046FEF7CBFD814600287FF436 +:1038600066AFE36BE9B2019A4FF00D0CD6F80CE0AD +:103870005A734FF00F02DFF8E0A0DA724A1E187395 +:103880000CFB02F284469876D87640451AF8019BE4 +:103890000CF1010C18BF3EF8120003EB090B18BF26 +:1038A000013203F809004FEA1029002808BF4046FA +:1038B000BCF10D0F8BF80190E7D1404502D03EF8E6 +:1038C00012200AB941F0400119700123002120465D +:1038D000F370FFF7BBFB814600287FF428AF013D62 +:1038E000B7D11BE04FF0060921E704287FF41FAF92 +:1038F00084F84BB01BF0020F20461BBF0C350D2186 +:103900000125B5FBF1F518BF01352946FFF7FCFB92 +:10391000814600287FF40BAF013D8AD1A16B304670 +:10392000FEF766FD814600287FF401AF01462022A4 +:10393000E06BFEF7F5F9E36B03CF18605960BA78D6 +:1039400039889A72198194F84B30E26B03F01803AE +:1039500013730123F370EAE6BC93000810B5044624 +:103960000A463430FEF776FB886004F13800FEF733 +:1039700073FBC2E9040194F8213003F00203D37110 +:103980000023D36110BD000003284B8B04BF8A8A3B +:1039900043EA0243184670472DE9F04F0B7899B07F +:1039A000044689462F2BD0F800B001D05C2B09D1FA +:1039B0004A461378914601322F2BFAD05C2BF8D06F +:1039C000002301E0DBF81C30A3600023E3619BF8D7 +:1039D0000030042B1ED1A368E3B1DBF82030214670 +:1039E00004A82362DBF824306362DBF82830A3628A +:1039F000FFF75CFC0346002854D1DBF8102002F1ED +:103A00003800FEF727FBC4E9040392F8213003F0E5 +:103A10000203E37199F800301F2B00F235818023F7 +:103A20000021204684F84B3019B0BDE8F04FFEF776 +:103A30002FBE49460B78894601312F2BFAD05C2BDB +:103A4000F8D01F2B8CBF00250425012F2FD1138800 +:103A50002E2B31D1002322F8173004F140029F426F +:103A60008CBF2E21202101330B2B02F8011BF6D134 +:103A700045F02005204684F84B50FFF7EDFC94F804 +:103A80004B30002800F0E78004280BD1990603F0A2 +:103A9000040240F1DC80002A00F0F6808023002040 +:103AA00084F84B3019B0BDE8F08F0425CDE7022F24 +:103AB00002D153882E2BCAD0911E87BB002322F837 +:103AC0001730002F00F0118132F81300194601332E +:103AD0002028F9D009B92E2801D145F00305901E00 +:103AE00030F817302E2B01D0013FF9D14FF02033A1 +:103AF0004FF0000A6364D0462364C4F847300823BB +:103B0000481C32F811600090F6B1202E03D02E2E02 +:103B10000DD1B84210D045F003050099F0E731F817 +:103B20001730202B01D02E2BC8D1013FC5E79A4575 +:103B300005D20099B9423BD10B2B30D101E00B2BC0 +:103B400027D145F003050B2394F84020E52A04BF54 +:103B5000052284F84020082B04BF4FEA88085FFA4A +:103B600088F808F00C030C2B03D008F00303032B98 +:103B700001D145F00205A8073FF57CAF18F0010F11 +:103B800018BF45F0100518F0040F18BF45F00805E0 +:103B900070E70099B94202D045F00305D4D84FEA46 +:103BA00088080B234FF0080A00975FFA88F8B4E7FB +:103BB0007F2E15D9304640F25231CDE9022345F02F +:103BC0000203019300F098FC10F0800F0646DDE937 +:103BD000022316D000F07F0646498E5D019D46B354 +:103BE00031464548CDE9012305F0E8FADDE9012336 +:103BF000F8B9A6F1410189B219291ED848F0020886 +:103C000010E0FF28EAD9591E8A4503D345F0030581 +:103C10009A4682E704EB0A01000A0AF1010A019DB3 +:103C200081F8400004EB0A010AF1010A81F84060C2 +:103C300073E745F003055F26F4E7A6F1610189B259 +:103C400019299EBF203E48F00108B6B2EAE7002AD3 +:103C500008BF052026E75A073FF524AFA379DB0606 +:103C600045D59BF80000042835D1A3682146E279A8 +:103C700023622369DBF8100023F0FF031343636220 +:103C8000E36CA362FFF76AFE23680027DA6819F87D +:103C9000010B00283FF409AF40F25231009200F0CE +:103CA0004BFC054608B31F28009A7FF6FEAE2F286E +:103CB0003FF4BFAE5C283FF4BCAE7F2805D8014678 +:103CC0000E4805F07BFA009A78B9FF2F0DD022F844 +:103CD00017500137DBE7216B0BF14C03C1F30801EF +:103CE0001944FFF751FEA060CEE70620DAE6052072 +:103CF000D8E600BF3C930008359300082C930008D9 +:103D00001FB5CDE9001003A814460391FEF700FA91 +:103D1000002815DB0B4A52F820300BB10021197036 +:103D2000019B0BB10021197042F820302CB1002208 +:103D300001A96846FEF7C8FE0446204604B010BD3F +:103D40000B24FAE73C3600202DE9F04798B0904666 +:103D500005460191002800F0528102F03F0603A9B8 +:103D600001A83246FEF7B0FE002840F04681039BD2 +:103D70004FF48C60049303F075FA0746002800F0B6 +:103D80004081039B00F500720199D86004A81A6174 +:103D9000FFF702FE044620B99DF95B30002BB8BF47 +:103DA000062418F01C0F00F0CD80002C4CD0042C01 +:103DB00040D104A8FFF724FC044600283AD146F07D +:103DC0000806039B1A78042A40F083801869294664 +:103DD0002B60FFF7C3FD039B1E22002118690230F0 +:103DE000FDF79EFF039C00211A2220692630FDF773 +:103DF00097FF236920221A71246903F06DFA0146A6 +:103E0000012208342046FEF72BF9039B04A81B6906 +:103E100083F82120FFF764FA044658B9A96801B372 +:103E200002462846FEF718FDAB68039A0446013B9C +:103E30005361B4B1384603F025FA0CB100232B606E +:103E4000204618B0BDE8F0879DF8163013F0110F2A +:103E500040F0848018F0040F40F0C98018F0080F7B +:103E6000AFD1039A31071399936C48BF46F04006CF +:103E7000E964AB641078042872D1069B9DF8171092 +:103E80002B62089B106923F0FF030B4329466B62EA +:103E9000179BAB62FFF762FDDDF80CA00024002247 +:103EA00005F15008BAF8063021464046C5F800A092 +:103EB000AB80002385F8306085F831406C64C5E93B +:103EC0000E234FF40072FDF72BFFB20653D40024EB +:103ED000B0E703F001FA0146009013980E30FEF7A8 +:103EE000BFF8139800991630FEF7BAF8039C13999F +:103EF0002078FFF749FD202300228046CB72204620 +:103F00001399FEF7D1F8139B002201211A775A77F3 +:103F10009A77DA77039BD970B8F1000FA1D04146A8 +:103F200004A8D3F84890FEF797FC0446002881D1F6 +:103F300049460398FEF75CFA039B044608F1FF30FC +:103F4000586176E7002C7FF475AF9DF81630DC06DB +:103F50004FD418F0020F84D0D80782D5072469E720 +:103F6000FFF712FD0023A86001F11C00FEF772F8B4 +:103F70006B61286190E7D5E9046956EA0903A6D088 +:103F8000BAF80AA0A9684FEA4A2AC5E90E69B245FB +:103F900074EB09031BD300242964002C7FF44AAF7F +:103FA000C6F30803002B92D0039C2046FEF770F85E +:103FB00008B3760A0123414646EAC95682196A6463 +:103FC000607802F0C5FC041E18BF012432E72846C1 +:103FD000FEF7C6FAB6EB0A06014669F100090128A8 +:103FE00003D9431CD3D10124D6E70224D4E7082403 +:103FF00020E704241EE702241CE704461EE70924E8 +:104000001EE711241CE700002DE9F04F994685B00A +:104010000023884603A90446C9F800301646FEF777 +:1040200091F8054680BB94F831506DBB94F8303060 +:1040300013F00103009300F0A68004F1500AD4E9C4 +:104040000432D4E90E011B1A62EB0102B34272F191 +:10405000000238BF1E46BEB1D4E90E10C1F30803FA +:10406000002B40F08280039B5A894B0A013A43EAB5 +:10407000C0531A401BD151EA000309D1A06801289E +:104080000DD8022584F83150284605B0BDE8F08FE0 +:10409000216C20460192FEF763FA019AEFE7431C78 +:1040A00004D10123009D84F83130EDE72064DDF870 +:1040B0000CB0216C5846FDF7EBFF0028E1D0B6F5B7 +:1040C000007F02EB000731D3BBF80A1002EB562049 +:1040D000730A88429BF8010088BF8B1A3A46414612 +:1040E000019302F035FC0028DBD194F93020019BCC +:1040F000002A0BDA606CC01B984207D24FF40072A2 +:10410000514608EB4020FDF7E5FD019B5F02D9F821 +:104110000030F61BB8443B44C9F80030D4E90E32F5 +:10412000DB1942F10002C4E90E3294E7626CBA4234 +:104130001AD094F93030002B0DDA012351469BF848 +:10414000010002F029FC0028ABD194F8303003F0D4 +:104150007F0384F83030039801233A465146407873 +:1041600002F0F6FB00289CD16764A16B4046C1F3C6 +:104170000801C1F500775144B74228BF37463A4697 +:10418000FDF7A8FDC3E707257EE7000070B596B0F0 +:104190000E460022019002A901A8FEF795FC0446F4 +:1041A000E0B94FF48C6003F05DF80546D8B1029B8E +:1041B00000F500720199D86002A81A61FFF7ECFBC4 +:1041C000044640B99DF95330002B0ADB1EB131463D +:1041D00002A8FDF7EDFF284603F054F8204616B07C +:1041E00070BD0624F7E71124F8E7000070B5B8B0F9 +:1041F0000222019003A901A8FEF766FC044608BB51 +:10420000039B4FF48C60109303F02CF805460028B4 +:1042100066D0039B00F500720199D86010A81A615E +:10422000FFF7BAFB044650B99DF88B30980655D479 +:10423000190653D49DF84630DA0706D507242846D8 +:1042400003F020F8204638B070BD039B0493187823 +:10425000042814D104A91869FFF780FB069E9DF875 +:104260004630DB0610D410A8FEF776FF044600287F +:10427000E5D156BB0398FEF7DBFB0446DFE71F9949 +:10428000FFF782FB0646EAE7039BDA69B242D5D024 +:1042900024930021269624A81B78042B01BFDDE976 +:1042A0000823CDE928239DF817308DF89730FEF7C5 +:1042B000EFF904460028C2D124A8FFF741F80446CC +:1042C0000028BBD00428BAD1CDE70246314604A865 +:1042D000FEF7C2FA04460028B1D1CBE70624AEE7C8 +:1042E0001124AFE7F0B5BDB0CDE900106846FDF789 +:1042F0000FFF022203A901A8FEF7E6FB04460028EF +:1043000041D1039B4FF48C60149302F0ABFF054640 +:10431000002800F0EE80039B00F5007214AE0199B6 +:10432000D8601A613046FFF737FB044640BB9DF862 +:104330009B3013F0A00F40F0D880039B009F1A78A9 +:10434000042A68D11B6904AC03F1400C18680833D7 +:1043500053F8041C2246634503C21446F6D150228A +:10436000314628A8FDF7B6FC394628A8FFF714FB0C +:10437000044600284CD12A9A169B9A4206D008245B +:10438000284602F07FFF20463DB0F0BD349A209BC6 +:104390009A42F4D128A8FFF733F904460028EFD158 +:1043A000039B04AF1B6993F801E093F823C09C8C36 +:1043B0003A46083303CAB24243F8080C43F8041CD7 +:1043C0001746F5D1039B28A81B6983F801E0039BDE +:1043D0001A6982F823C01A6982F82440240A82F8F4 +:1043E00025401A691379D9065CBF43F02003137185 +:1043F000FEF776FF04460028C2D13046FEF7ACFE39 +:1044000004460028BCD10398FEF712FB0446B7E728 +:104410000428B5D1BEE7239A04AB02F1200C106842 +:10442000083252F8041C1C46624503C42346F6D1E8 +:104430005022314628A8FDF74DFC394628A8FFF741 +:10444000ABFA044600284CD12A9A169B9A4296D180 +:10445000349A209B9A4292D128A8FFF7D1F80446BB +:1044600000288DD137990DF11D030DF12D0001F1BB +:104470000D0253F8044B834242F8044BF9D11888DB +:10448000012710809B7893709DF81B30039CDA06FF +:1044900058BF43F02003CB72E770CB7ADB06ACD574 +:1044A000169A2A9B9A42A8D02078FFF76DFA014607 +:1044B0002046FDF7EDFD0146C8B12046FDF798FF07 +:1044C000044600287FF45CAF039890F86D302E2BE3 +:1044D00093D12A9A00F16C01FDF7E6FD039BDF7092 +:1044E0008BE704287FF44CAFB6E7062448E70224A4 +:1044F00046E7112447E700007F2810B501D880B2B5 +:1045000010BDB0F5803F13D240F2523399420FD123 +:104510000849002231F8024B93B2844203D103F1DF +:104520008000C0B2ECE70132802AF3D11346F6E7EF +:104530000020E5E77C9600087F280DD940F2523331 +:10454000994208D1FF2806D800F10040034B80387B +:1045500033F8100070470020704700BF7C960008B9 +:10456000B0F5803FF0B522D21F4A83B21F49B0F5A3 +:10457000805F28BF0A46141D34F8042C2146AAB1D6 +:10458000934213D334F8025C2E0AEFB252FA85F547 +:10459000A84222DA082E09D8DFE806F0050A101230 +:1045A0001416181A1C00801A34F810301846F0BD82 +:1045B000981A00F001001B1A9BB2F7E7103BFBE7CB +:1045C000203BF9E7303BF7E71A3BF5E70833F3E721 +:1045D000503BF1E7A3F5E353EEE70434002ECBD1D3 +:1045E00001EB4702C7E700BFCC930008C095000865 +:1045F00008B5074B074A196801F03D0199605368F7 +:104600000BB190689847BDE8084003F09FB800BF21 +:10461000000002404436002008B5084B196889099B +:1046200001F03D018A019A60054AD3680BB1106917 +:104630009847BDE8084003F089B800BF0000024079 +:104640004436002008B5084B1968090C01F03D01FB +:104650000A049A60054A53690BB190699847BDE80E +:10466000084003F073B800BF000002404436002049 +:1046700008B5084B1968890D01F03D018A059A605B +:10468000054AD3690BB1106A9847BDE8084003F0AA +:104690005DB800BF000002404436002008B5074B5B +:1046A000074A596801F03D01D960536A0BB1906A1D +:1046B0009847BDE8084003F049B800BF0000024039 +:1046C0004436002008B5084B5968890901F03D01BE +:1046D0008A01DA60054AD36A0BB1106B9847BDE8CE +:1046E000084003F033B800BF000002404436002009 +:1046F00008B5084B5968090C01F03D010A04DA605D +:10470000054A536B0BB1906B9847BDE8084003F026 +:104710001DB800BF000002404436002008B5084B19 +:104720005968890D01F03D018A05DA60054AD36BAD +:104730000BB1106C9847BDE8084003F007B800BF04 +:10474000000002404436002008B5074B074A1968AC +:1047500001F03D019960536C0BB1906C9847BDE836 +:10476000084002F0F3BF00BF0004024044360020BE +:1047700008B5084B1968890901F03D018A019A6062 +:10478000054AD36C0BB1106D9847BDE8084002F0A4 +:10479000DDBF00BF000402404436002008B5084BCE +:1047A0001968090C01F03D010A049A60054A536D2D +:1047B0000BB1906D9847BDE8084002F0C7BF00BF3D +:1047C000000402404436002008B5084B1968890DE2 +:1047D00001F03D018A059A60054AD36D0BB1106E58 +:1047E0009847BDE8084002F0B1BF00BF0004024096 +:1047F0004436002008B5074B074A596801F03D01CF +:10480000D960536E0BB1906E9847BDE8084002F036 +:104810009DBF00BF000402404436002008B5084B8D +:104820005968890901F03D018A01DA60054AD36EB1 +:104830000BB1106F9847BDE8084002F087BF00BF7A +:10484000000402404436002008B5084B5968090CA2 +:1048500001F03D010A04DA60054A536F0BB1906F15 +:104860009847BDE8084002F071BF00BF0004024055 +:104870004436002008B5084B5968890D01F03D0108 +:104880008A05DA60054AD36F13B1D2F880009847E1 +:10489000BDE8084002F05ABF000402404436002040 +:1048A00000230C4910B51A460B4C0B6054F823003A +:1048B000026001EB430004334260402BF6D1074A0B +:1048C0004FF0FF339360D360C2F80834C2F80C3461 +:1048D00010BD00BF443600207C9700080000024055 +:1048E0000F28F8B510D9102810D0112811D012288F +:1048F00008D10F240720DFF8B4E00126DEF80050CD +:10490000A04208D9002649E00446F4E70F2400201D +:10491000F1E70724FBE706FA00F73D4240D1214CBE +:104920004FEA001C3D4304EB00160EEBC000CEF82E +:104930000050C0E90123FBB24BB11B48836B43F02D +:1049400001038363036E43F001030366036E17F4F0 +:104950007F4F09D01448836B43F002038363036ED7 +:1049600043F002030366036E54F80C00036823F05F +:104970001F030360056815F00105FBD104EB0C0370 +:104980003D2493F80CC05F6804FA0CF43C602124C9 +:104990000560446112B1987B00F0B4FC3046F8BD6C +:1049A0000130ADE77C9700080045025844360020EE +:1049B00010B5302484F31188FFF792FF002383F3AE +:1049C000118810BD10B50446807B00F0B1FC0123B6 +:1049D0001049627B03FA02F20B6823EA0203DAB29F +:1049E0000B604AB90C4A916B21F001019163116E81 +:1049F00021F001011166126E13F47F4F09D1064BAD +:104A00009A6B22F002029A631A6E22F002021A6670 +:104A10001B6E10BD443600200045025808B53023F7 +:104A200083F31188FFF7CEFF002383F3118808BDBD +:104A3000836CC26A8B42506810B506D95A1E4C006E +:104A400002EB4103B3FBF4F3184410BD01F0010382 +:104A50008A0748BF43F002034A0748BF43F00803F0 +:104A60000A0748BF43F00403CA0648BF43F01003D7 +:104A70008A06426B48BF43F02003134343637047E9 +:104A800010B5074C204600F0BFFF064B0022C4E9DA +:104A90001023054BA364054BE363054BE36410BD92 +:104AA000C83600200070005200B4C4041C37002037 +:104AB0001C390020C36A0BB90E4BC3620379012B6A +:104AC0000CD10D4B984209D10C4B5A6B42F48032F9 +:104AD0005A63DA6D42F48032DA65DB6D436C002292 +:104AE0001A65DA621A605A605A624FF0FF329A63AE +:104AF000704700BF7C980008C83600200045025867 +:104B00000379012B16D0436C00221A65DA621A6011 +:104B10005A605A624FF0FF329A63074B984209D1AC +:104B2000064B5A6B22F480325A63DA6D22F48032DB +:104B3000DA65DB6D704700BFC836002000450258BB +:104B400010B5446C0649FFF773FF6060236842F2BA +:104B5000107043F003032360BDE8104001F05ABD1C +:104B6000801A06000129F8B5466C0B4F09D175680B +:104B70000A493D40FFF75CFF054345F480557560E9 +:104B8000F8BD746806493C40FFF752FF044344F403 +:104B900080547460F4E700BF00ECFFFF80F0FA027D +:104BA00040787D01436C00225A601A607047000013 +:104BB000426C0129536823F4404304D0022905D0F4 +:104BC00001B95360704743F48043FAE743F400436C +:104BD000F7E70000436C41F480519A60D9605A6B4A +:104BE0001206FCD580229A637047000010B541F48C +:104BF0008851446CA260E160616B11F04502FBD00A +:104C0000A26311F0040203D0FFF720FF012010BDC2 +:104C1000616910461960FAE710B541F48851446C97 +:104C2000A260E160616B11F04502FBD0A26311F05C +:104C3000050203D0FFF70AFF012010BD616910468D +:104C40001960FAE773B5134604460E46302282F324 +:104C50001188426CD26B32B14FF0FF31403001937A +:104C600001F0E4FC019B606C00220265C263C26239 +:104C7000456B15F4807504D185F31188012002B0CD +:104C800070BD4FF0FF31816382F31188012E06D988 +:104C90000C21204602B0BDE87040FFF7BDBF1046B2 +:104CA000EDE7000073B5446C0E4600250192616B80 +:104CB000A1632565E562FFF7C9FE012E07D9019BB7 +:104CC0002A460C2102B0BDE87040FFF7A5BF02B034 +:104CD00070BD000010B541F49851446CA260E160D1 +:104CE000616B11F04502FBD0A26311F03F0203D0CB +:104CF000FFF7ACFE012010BD216A10461960E16982 +:104D00005960A16999606169D960F4E72DE9F743B9 +:104D100004460191006D01A91746984602F03EFC39 +:104D2000064600284AD0626C2046DDF8049055689B +:104D3000C5F3090501356B00A56CB5FBF3F54FF420 +:104D40007A73B5FBF3F55D43556200F023FE50BB6B +:104D5000636C4FF0FF3201254146C3F8589020465E +:104D60001D659A634FF49572DA6342F207029F62FF +:104D7000DA62E36C0A9AFFF74FFFA0B9E26C104BBE +:104D800011680B407BB929462046FFF75BFF0546BB +:104D900048B92E463A460199206D02F037FC30465C +:104DA00003B0BDE8F0833A460199206D02F02EFC75 +:104DB000E26C01212046FFF775FFF0E70126EEE7E0 +:104DC00008E0FFFD2DE9F7431F46436C01924FF4C5 +:104DD0007A725D6804468846C5F3090501356E00A0 +:104DE000856CB5FBF6F5B5FBF2F555435D6200F059 +:104DF000D1FD20B10125284603B0BDE8F0837E0235 +:104E000001A9206D324602F0C9FB05460028F1D009 +:104E1000636C019AD4F84C909A6501221A654FF0A0 +:104E2000FF329A634FF49572DA639E62236BDB065E +:104E30004B4658BF4FEA4828012F42461BD9122142 +:104E40002046FFF7E9FEC0B9D9F80020104B134007 +:104E50009BB9636C42F2930239462046DA62E26CF7 +:104E6000FFF7F0FE804640B932460199206D454675 +:104E700002F0CCFBBFE71121E2E732460199206D39 +:104E800002F0C4FBE26C39462046FFF70BFFB2E7A5 +:104E900008E0FFFD2DE9F3411F46436C01924FF4FA +:104EA0007A725D6804468846C5F3090501356E00CF +:104EB000856CB5FBF6F5B5FBF2F555435D6200F088 +:104EC00069FD20B10125284602B0BDE8F0817E02CF +:104ED00001A9206D324602F0A7FB05460028F1D05B +:104EE000636C019A9A6501221A654FF0FF329A634A +:104EF0004FF48D72DA639E62236BE66CDB063346F9 +:104F000058BF4FEA4828012F424619D91921204697 +:104F1000FFF782FEB0B932680F4B134093B9636C50 +:104F200042F2910239462046DA62E26CFFF78AFECD +:104F3000064638B901993546206D02F0B1FBC2E74B +:104F40001821E4E70199206D02F0AAFBE26C3946D2 +:104F50002046FFF7A7FEB6E708E0FFFD12F0030FBB +:104F60002DE9F04107460C4615461E4617D00E4463 +:104F7000B44202D10020BDE8F0810123FA6B214642 +:104F80003846FFF71FFF0028F5D128464FF400727E +:104F9000F96B05F500750134FCF79CFEE8E7BDE808 +:104FA000F041FFF70FBF000012F0030F2DE9F041B1 +:104FB00007460C4615461E4617D00E44B44202D191 +:104FC0000020BDE8F08129464FF40072F86B05F52A +:104FD0000075FCF77FFE0123FA6B21463846FFF788 +:104FE00059FF0028EDD10134E8E7BDE8F041FFF7B3 +:104FF00051BF000000207047302310B583F31188A3 +:105000000024436C40302146DC6301F01DFB84F337 +:10501000118810BD026843681143016003B118474D +:1050200070470000024A136843F0C00313607047E2 +:1050300000440040024A136843F0C0031360704705 +:1050400000480040024A136843F0C00313607047F1 +:1050500000780040044B9A6C02439A641A6F104324 +:1050600018671B6F704700BF0045025837B5274CC3 +:10507000274D204600F028FD04F114000094002381 +:105080004FF40072234900F0C3F94FF40072224933 +:1050900004F138000094214B00F03CFA204BC4E9A5 +:1050A0001735204C204600F00FFD04F11400009449 +:1050B00000234FF400721C4900F0AAF94FF400726B +:1050C0001A4904F138000094194B00F023FA194BE7 +:1050D000C4E91735184C204600F0F6FC04F1140022 +:1050E00000234FF400721549009400F091F9144B1D +:1050F0004FF40072134904F13800009400F00AFAEA +:10510000114BC4E9173503B030BD00BF2039002072 +:1051100000E1F505643A00206440002025500008B5 +:10512000004400408C390020643C00206442002090 +:105130003550000800480040F8390020643E002047 +:1051400045500008644400200078004038B5264DE2 +:105150000446037C002918BF0D46012B06D1234BC2 +:10516000984230D14FF40030FFF774FF2A68236E65 +:10517000E16D03EB5203A566B3FBF2F36A6810041A +:1051800042BF23F0070003F0070343EA4003CB606C +:10519000AB6843F040034B60EB6843F001038B6066 +:1051A00042F4967343F001030B604FF0FF330B6240 +:1051B000510505D512F0102211D0B2F1805F10D048 +:1051C00084F8643038BD0A4B984205D0094B9842A8 +:1051D000CCD14FF08040C7E74FF48020C4E77F2355 +:1051E000EEE73F23ECE700BF849800082039002059 +:1051F0008C390020F83900202DE9F047C66D0546AE +:105200003768F469210734621AD014F0080118BF16 +:105210004FF48071E20748BF41F02001A3074FF02F +:10522000300348BF41F04001600748BF41F08001B2 +:1052300083F31188281DFFF7EDFE002383F3118807 +:10524000E2050AD5302383F311884FF48061281DCD +:10525000FFF7E0FE002383F311884FF030094FF091 +:10526000000A14F0200838D13B0616D54FF030095B +:1052700005F1380A200610D589F31188504600F050 +:105280007DF9002836DA0821281DFFF7C3FE27F034 +:1052900080033360002383F31188790614D56206F6 +:1052A00012D5302383F31188D5E913239A4208D10C +:1052B0002B6C33B127F040071021281DFFF7AAFE01 +:1052C0003760002383F31188E30618D5AA6E1369AB +:1052D000ABB15069BDE8F047184789F31188736A8C +:1052E000284695F86410194000F008FC8AF31188EC +:1052F000F469B6E7B06288F31188F469BAE7BDE8EB +:10530000F0870000090100F16043012203F56143C9 +:10531000C9B283F8001300F01F039A4043099B00B1 +:1053200003F1604303F56143C3F880211A607047BD +:1053300000F01F0301229A40430900F160409B00E6 +:1053400000F5614003F1604303F56143C3F8802039 +:10535000C3F88021002380F800337047F8B5154664 +:10536000826804460B46AA4200D28568A169266974 +:10537000761AB5420BD218462A46FCF7ABFCA36955 +:105380002B44A3612846A3685B1BA360F8BD0CD91E +:10539000AF1B18463246FCF79DFC3A46E1683044A4 +:1053A000FCF798FCE3683B44EBE718462A46FCF719 +:1053B00091FCE368E5E7000083689342F7B5044693 +:1053C000154600D28568D4E90460361AB5420BD27E +:1053D0002A46FCF77FFC63692B4463612846A36877 +:1053E0005B1BA36003B0F0BD0DD93246AF1B01912A +:1053F000FCF770FC01993A46E0683144FCF76AFC1E +:10540000E3683B44E9E72A46FCF764FCE368E4E729 +:1054100010B50A440024C361029B8460C16002612C +:105420000362C0E90000C0E9051110BD08B5D0E96C +:105430000532934201D1826882B98268013282606A +:105440005A1C426119700021D0E904329A4224BFEB +:10545000C368436101F012F9002008BD4FF0FF302E +:10546000FBE7000070B5302304460E4683F3118835 +:10547000A568A5B1A368A269013BA360531CA36101 +:1054800015782269934224BFE368A361E3690BB1F5 +:1054900020469847002383F31188284607E03146C9 +:1054A000204601F0DBF80028E2DA85F3118870BDB0 +:1054B0002DE9F74F04460E4617469846D0F81C9043 +:1054C0004FF0300A8AF311884FF0000B154665B192 +:1054D0002A4631462046FFF741FF034660B9414660 +:1054E000204601F0BBF80028F1D0002383F3118897 +:1054F000781B03B0BDE8F08FB9F1000F03D0019025 +:105500002046C847019B8BF31188ED1A1E448AF38D +:105510001188DCE7C160C361009B82600362C0E95F +:1055200005111144C0E9000001617047F8B5044657 +:105530000D461646302383F31188A768A7B1A368E8 +:10554000013BA36063695A1C62611D70D4E9043297 +:105550009A4224BFE3686361E3690BB12046984730 +:10556000002080F3118807E03146204601F076F8EC +:105570000028E2DA87F31188F8BD0000D0E905239E +:1055800010B59A4201D182687AB98268002101324D +:1055900082605A1C82611C7803699A4224BFC368E6 +:1055A000836101F06BF8204610BD4FF0FF30FBE740 +:1055B0002DE9F74F04460E4617469846D0F81C9042 +:1055C0004FF0300A8AF311884FF0000B154665B191 +:1055D0002A4631462046FFF7EFFE034660B94146B2 +:1055E000204601F03BF80028F1D0002383F3118816 +:1055F000781B03B0BDE8F08FB9F1000F03D0019024 +:105600002046C847019B8BF31188ED1A1E448AF38C +:105610001188DCE70379052B05BF836A0020012090 +:105620004B6004BF4FF400730B60704770B55D1E94 +:10563000866A04460D44B54205D9436B43F08003A6 +:105640004363012070BD06250571FFF787FC052324 +:105650002371F7E770B55D1E866A04460D44B542B6 +:1056600005D9436B43F080034363012070BD0725D8 +:105670000571FFF799FC05232371F7E738B5057924 +:105680000446052D05D108230371FFF7B3FC2571EE +:1056900038BD0120FCE700000323F0B5037185B09D +:1056A0000446FFF74DFA002220461146FFF792FA12 +:1056B0004FF4D57203AB08212046FFF7ADFA02463E +:1056C000B8B901232363039BC3F30323012B09D13F +:1056D00003AB37212046FFF79FFA18B9A44B039A72 +:1056E0001340ABB120460125FFF75CFA022323717A +:1056F00037E103AB002237212046FFF78DFA28B9A6 +:105700009B4A039B1A40002A00F0A78002232363D0 +:10571000236B03F00F03022B40F0A9806425954E04 +:1057200042F2107000F076FF03AB324601212046B2 +:10573000FFF75CFA0028D5D1039B002B80F2938001 +:105740005A0003D5236B43F010032363002204F1B6 +:10575000080302212046FFF7BDFA02460028C1D106 +:1057600004F1380303212046FFF756FA0028B9D187 +:1057700004F11805A26B092120462B46FFF7AAFA6F +:105780000028AFD102ABA26B07212046FFF744FAF5 +:1057900006460028A6D1236B03F00F03022B40F02E +:1057A0008F807E227F21284603F02CFA012840F2C8 +:1057B0008780E76B42F2107000F02CFF08234FF453 +:1057C0000072394620460096FFF7A0FA002889D1DA +:1057D000384603F065FA236BA06203F00F03022B37 +:1057E00072D103AB644A06212046FFF715FA002860 +:1057F00071D15F49039B1940B1FA81F149092046F3 +:10580000FFF7B0F902AB4FF4007210212046FFF70A +:1058100003FA054600287FF465AF554E029B3342DC +:105820007FF460AF236B13F00E0F03F00F0273D001 +:10583000022A7FF457AFE36A1978012900F09480B7 +:10584000022900F09380002900F089804B4F204608 +:10585000FFF7AEF903AB3A4676E0114620462263E5 +:10586000FFF7B8F954E7013D7FF45AAF3AE7444DEA +:105870006426444A3E4F012B18BF154603AB002255 +:1058800037212046FFF7C8F900287FF42BAF039B90 +:105890003B427FF427AF03AB2A4629212046FFF77E +:1058A000A5F900287FF41EAF039B002BFFF648AF3D +:1058B000013E3FF417AF42F2107000F0ABFEDDE79F +:1058C000284603F0C1F986E77E227F212846E66B51 +:1058D00003F098F908B9002191E7002340223146EE +:1058E000204600930623FFF711FA0028F3D1B3896D +:1058F0005BBA9B07EFD5244B4022314620460093EC +:105900000623FFF703FA0028E5D1317C01F00F01EF +:105910000F3918BF012172E7E36A1978F9B101293B +:105920007FF4E0AE2046FFF743F903ABA26B3721CB +:105930002046FFF771F900287FF4D4AE039B334271 +:105940007FF4D0AE03AB022206212046FFF764F9B4 +:1059500000287FF4C7AE039B33427FF4C3AE052318 +:105960002371284605B0F0BD084F70E7084F6EE779 +:1059700008E0FFFD0080FFC00001B9030000B7038D +:105980000080FF5000001080F1FFFF800001B7038E +:105990000002B70337B504460C4D01ABA26B0D21D5 +:1059A0002046FFF739F978B9019B2B420BD1C3F39D +:1059B0004323042B08D0053B022B04D84FF47A7004 +:1059C00000F028FEE9E7012003B030BD08E0FFFD4C +:1059D00070B53023054683F3118803790024022B28 +:1059E00003D184F31188204670BD0423037184F32E +:1059F00011880226FFF7CEFF04462846FFF7D2F8AB +:105A00002E71F0E7FFF73CB8044B036001230371EC +:105A100000234363C0E90A33704700BF9C98000825 +:105A200010B53023044683F31188C162FFF742F8B2 +:105A300002230020237180F3118810BD10B530239C +:105A4000044683F31188FFF75BF800230122E36229 +:105A5000227183F3118810BD02684368114301600D +:105A600003B11847704700001430FFF721BD000054 +:105A70004FF0FF331430FFF71BBD00003830FFF745 +:105A800097BD00004FF0FF333830FFF791BD0000A5 +:105A90001430FFF7E7BC00004FF0FF311430FFF780 +:105AA000E1BC00003830FFF741BD00004FF0FF328D +:105AB0003830FFF73BBD0000012914BF6FF0130021 +:105AC00000207047FFF7D2BA044B03600023436005 +:105AD000C0E9023301230374704700BFC098000877 +:105AE00010B53023044683F31188FFF72FFB022300 +:105AF0000020237480F3118810BD000038B5C369FD +:105B000004460D461BB904210844FFF7A5FF2946AA +:105B100004F11400FFF78AFC002806DA201D4FF478 +:105B20000061BDE83840FFF797BF38BD02684368A1 +:105B30001143016003B118477047000013B5406B73 +:105B400000F58054D4F8A4381A681178042914D1C7 +:105B5000017C022911D11979012312898B4013424A +:105B60000BD101A94C3002F07BFFD4F8A4480246C7 +:105B7000019B2179206800F0DFF902B010BD000020 +:105B8000143002F0FDBE00004FF0FF33143002F07D +:105B9000F7BE00004C3002F0CFBF00004FF0FF33E3 +:105BA0004C3002F0C9BF0000143002F0CBBE000040 +:105BB0004FF0FF31143002F0C5BE00004C3002F04F +:105BC0009BBF00004FF0FF324C3002F095BF000049 +:105BD0000020704710B500F58054D4F8A4381A6836 +:105BE0001178042917D1017C022914D15979012394 +:105BF00052898B4013420ED1143002F05DFE0246F2 +:105C000048B1D4F8A4484FF4407361792068BDE8E6 +:105C1000104000F07FB910BD406BFFF7DBBF000004 +:105C2000704700007FB5124B01250426044603602F +:105C30000023057400F1840243602946C0E9023361 +:105C40000C4B0290143001934FF44073009602F015 +:105C50000FFE094B04F69442294604F14C000294CD +:105C6000CDE900634FF4407302F0D6FE04B070BD7E +:105C7000E8980008195C00083D5B00080A683023BA +:105C800083F311880B790B3342F823004B791333DC +:105C900042F823008B7913B10B3342F8230000F54F +:105CA0008053C3F8A41802230374002080F31188E2 +:105CB0007047000038B5037F044613B190F85430A4 +:105CC000ABB90125201D0221FFF730FF04F11400BC +:105CD0006FF00101257700F0DDFC04F14C0084F841 +:105CE00054506FF00101BDE8384000F0D3BC38BD1E +:105CF00010B5012104460430FFF718FF0023237775 +:105D000084F8543010BD000038B504460025143026 +:105D100002F0C6FD04F14C00257702F095FE201D2F +:105D200084F854500121FFF701FF2046BDE83840B8 +:105D3000FFF750BF90F8803003F06003202B06D1AE +:105D400090F881200023212A03D81F2A06D800209A +:105D50007047222AFBD1C0E91D3303E0034A4267A2 +:105D600007228267C3670120704700BF44220020DA +:105D700037B500F58055D5F8A4381A68117804298C +:105D80001AD1017C022917D11979012312898B407C +:105D9000134211D100F14C04204602F015FF58B116 +:105DA00001A9204602F05CFED5F8A4480246019BFA +:105DB0002179206800F0C0F803B030BD01F10B0379 +:105DC000F0B550F8236085B004460D46FEB130238F +:105DD00083F3118804EB8507301D0821FFF7A6FE29 +:105DE000FB6806F14C005B691B681BB1019002F077 +:105DF00045FE019803A902F033FE024648B1039B19 +:105E00002946204600F098F8002383F3118805B056 +:105E1000F0BDFB685A691268002AF5D01B8A013B65 +:105E20001340F1D104F18002EAE70000133138B5E4 +:105E300050F82140ECB1302383F3118804F58053EE +:105E4000D3F8A4281368527903EB8203DB689B69BB +:105E50005D6845B104216018FFF768FE294604F12A +:105E6000140002F033FD2046FFF7B4FE002383F355 +:105E7000118838BD7047000001F062BD0123402247 +:105E8000002110B5044600F8303BFBF749FF002322 +:105E9000C4E9013310BD000010B53023044683F37C +:105EA00011882422416000210C30FBF739FF204685 +:105EB00001F068FD02230020237080F3118810BDDB +:105EC00070B500EB8103054650690E461446DA6052 +:105ED00018B110220021FBF723FFA06918B110228E +:105EE0000021FBF71DFF31462846BDE8704001F058 +:105EF00049BE000083682022002103F0011310B581 +:105F0000044683601030FBF70BFF2046BDE81040CD +:105F100001F0C4BEF0B4012500EB810447898D4037 +:105F2000E4683D43A469458123600023A260636067 +:105F3000F0BC01F0E1BE0000F0B4012500EB8104EB +:105F400007898D40E4683D4364690581236000232F +:105F5000A2606360F0BC01F057BF000070B502237F +:105F600000250446242203702946C0F888500C30CE +:105F700040F8045CFBF7D4FE204684F8705001F032 +:105F800095FD63681B6823B129462046BDE8704033 +:105F9000184770BD0378052B10B504460AD080F869 +:105FA0008C300523037043681B680BB104219847AC +:105FB0000023A36010BD00000178052906D190F8E8 +:105FC0008C20436802701B6803B1184770470000BB +:105FD00070B590F87030044613B1002380F870302B +:105FE00004F18002204601F07DFE63689B68B3B92E +:105FF00094F8803013F0600535D00021204602F07F +:106000006FF90021204602F05FF963681B6813B145 +:10601000062120469847062384F8703070BD20463C +:1060200098470028E4D0B4F88630A26F9A4288BF1F +:10603000A36794F98030A56F002B4FF0300380F2F6 +:106040000381002D00F0F280092284F8702083F390 +:10605000118800212046D4E91D23FFF76DFF00239E +:1060600083F31188DAE794F8812003F07F0343EA91 +:10607000022340F20232934200F0C58021D8B3F5EA +:10608000807F48D00DD8012B3FD0022B00F09380A9 +:10609000002BB2D104F1880262670222A267E36793 +:1060A000C1E7B3F5817F00F09B80B3F5407FA4D1B9 +:1060B00094F88230012BA0D1B4F8883043F0020369 +:1060C00032E0B3F5006F4DD017D8B3F5A06F31D0E3 +:1060D000A3F5C063012B90D86368204694F8822012 +:1060E0005E6894F88310B4F88430B047002884D0F8 +:1060F000436863670368A3671AE0B3F5106F36D08F +:1061000040F6024293427FF478AF5C4B6367022310 +:10611000A3670023C3E794F88230012B7FF46DAFAF +:10612000B4F8883023F00203A4F88830C4E91D5580 +:10613000E56778E7B4F88030B3F5A06F0ED194F836 +:106140008230204684F88A3001F00EFD63681B68B7 +:1061500013B1012120469847032323700023C4E98B +:106160001D339CE704F18B0363670123C3E72378A6 +:10617000042B10D1302383F311882046FFF7BAFE99 +:1061800085F311880321636884F88B5021701B68A4 +:106190000BB12046984794F88230002BDED084F86B +:1061A0008B300423237063681B68002BD6D0022138 +:1061B00020469847D2E794F8843020461D0603F025 +:1061C0000F010AD501F080FD012804D002287FF4D8 +:1061D00014AF2B4B9AE72B4B98E701F067FDF3E7E1 +:1061E00094F88230002B7FF408AF94F8843013F0D9 +:1061F0000F01B3D01A06204602D502F089F8ADE7A8 +:1062000002F07AF8AAE794F88230002B7FF4F5AE1A +:1062100094F8843013F00F01A0D01B06204602D55D +:1062200002F05EF89AE702F04FF897E7142284F83C +:10623000702083F311882B462A4629462046FFF713 +:1062400069FE85F31188E9E65DB1152284F87020B6 +:1062500083F3118800212046D4E91D23FFF75AFE5D +:10626000FDE60B2284F8702083F311882B462A4622 +:1062700029462046FFF760FEE3E700BF18990008B3 +:10628000109900081499000838B590F87030044649 +:10629000002B3ED0063BDAB20F2A34D80F2B32D86F +:1062A000DFE803F037313108223231313131313119 +:1062B00031313737856FB0F886309D4214D2C368CC +:1062C0001B8AB5FBF3F203FB12556DB9302383F340 +:1062D00011882B462A462946FFF72EFE85F31188A2 +:1062E0000A2384F870300EE0142384F870303023D1 +:1062F00083F31188002320461A461946FFF70AFE49 +:10630000002383F3118838BDC36F03B1984700237E +:10631000E7E70021204601F0E3FF0021204601F0DD +:10632000D3FF63681B6813B10621204698470623F4 +:10633000D7E7000010B590F870300446142B29D030 +:1063400017D8062B05D001D81BB110BD093B022B75 +:10635000FBD80021204601F0C3FF0021204601F0B8 +:10636000B3FF63681B6813B10621204698470623D4 +:1063700019E0152BE9D10B2380F87030302383F31B +:10638000118800231A461946FFF7D6FD002383F330 +:106390001188DAE7C3689B695B68002BD5D1C36FAE +:1063A00003B19847002384F87030CEE70023826859 +:1063B00080F8243083691B6899689142FBD25A683F +:1063C00003604260106058607047000000238268DC +:1063D00080F8243083691B6899689142FBD85A6819 +:1063E00003604260106058607047000008B50846BE +:1063F000302383F3118891F82430032B05D0042B2C +:106400000DD02BB983F3118808BD8B6A00221A6066 +:106410004FF0FF338362FFF7C9FF0023F2E7D1E9B2 +:10642000003213605A60F3E7034610B51B689842C8 +:1064300003D09C688A689442F8D25A680B604A601C +:106440001160596010BD0000FFF7B0BF064BD9685E +:1064500081F824001868026853601A600122D8602D +:1064600080F82420F9F7CEBF684600200C4B30B5E9 +:10647000DD684B1C87B004460FD02B46094A68469E +:1064800000F09CF92046FFF7E1FF009B13B168463E +:1064900000F09EF9A86A07B030BDFFF7D7FFF9E713 +:1064A00068460020ED630008044B1A68DB689068BA +:1064B0009B68984294BF00200120704768460020E6 +:1064C000094B10B51C68D868226853601A60012215 +:1064D000DC6084F82420FFF779FF01462046BDE800 +:1064E0001040F9F78FBF00BF68460020044B1A68C0 +:1064F000DB6892689B689A4201D9FFF7E1BF704759 +:106500006846002038B50123084C002523706560DB +:1065100002F0F4FB02F01AFC0549064802F0F0FC18 +:106520000223237085F3118838BD00BF1049002075 +:10653000209900086846002000F080B9034A51689D +:1065400053685B1A9842FBD8704700BF001000E008 +:106550008B604B630023CA6100F128020B630223A6 +:106560000A618B840123886181F8263001F11003D0 +:10657000C26A4A611360C36201F12C030846CB6210 +:1065800070470000D0E90131026841F8183CA1F1E0 +:106590009C033839CB60036941F8243C436941F8D6 +:1065A000203C034B41F8043CC3680248FFF7D0BFCE +:1065B0001D0400086846002008B5FFF7E3FFBDE8AA +:1065C0000840FFF741BF000038B50E4BDC6804F10E +:1065D0002C05A062E06AA8420FD194F826303BB99E +:1065E00094F825309B0702BFD4E9043213605A6047 +:1065F0000F20BDE83840FFF729BF0368E362FFF7CB +:1066000023FFE7E768460020302383F31188FFF774 +:10661000DBBF000008B50146302383F31188082052 +:10662000FFF724FF002383F3118808BD054BDB68C7 +:1066300021B1036098620320FFF718BF4FF0FF30CD +:10664000704700BF6846002003682BB1002202603B +:1066500018469962FFF7F8BE70470000064BDB68EA +:1066600039B1426818605A60136043600420FFF734 +:10667000FDBE4FF0FF307047684600200368984227 +:1066800006D01A680260506018469962FFF7DCBEB7 +:106690007047000038B504460D462068844200D19A +:1066A00038BD036823605C608562FFF7CDFEF4E7C8 +:1066B000036810B59C68A2420CD85C688A600B60C5 +:1066C0004C602160596099688A1A9A604FF0FF33D4 +:1066D000836010BD121B1B68ECE700000A2938BF5D +:1066E0000A2170B504460D460A26601902F000FB27 +:1066F00002F0E8FA041BA54203D8751C04462E4696 +:10670000F3E70A2E04D90120BDE8704002F0C0BCB6 +:1067100070BD0000F8B5144B0D460A2A4FF00A0769 +:10672000D96103F11001826038BF0A224160196902 +:106730001446016048601861A81802F0C9FA02F016 +:10674000C1FA431B0646A34206D37C1C28192746E0 +:10675000354602F0CDFAF2E70A2F04D90120BDE850 +:10676000F84002F095BCF8BD68460020F8B5064632 +:106770000D4602F0A7FA0F4A134653F8107F9F42C6 +:1067800006D12A4601463046BDE8F840FFF7C2BFB1 +:10679000D169BB68441A2C1928BF2C46A34202D9E0 +:1067A0002946FFF79BFF224631460348BDE8F840E3 +:1067B000FFF77EBF6846002078460020C0E903232B +:1067C000002310B45DF8044B4361FFF7CFBF000016 +:1067D00010B5194C236998420DD08168D0E9003278 +:1067E00013605A609A680A449A60002303604FF06D +:1067F000FF33A36110BD0268234643F8102F536096 +:106800000022026022699A4203D1BDE8104002F0E2 +:1068100069BA936881680B44936002F053FA226965 +:10682000E1699268441AA242E4D91144BDE81040DB +:10683000091AFFF753BF00BF684600202DE9F04753 +:10684000DFF8BC8008F110072C4ED8F8105002F089 +:1068500039FAD8F81C40AA68031B9A423ED814445F +:106860004FF00009D5E90032C8F81C4013605A60A7 +:10687000C5F80090D8F81030B34201D102F032FAD6 +:1068800089F31188D5E9033128469847302383F3EB +:1068900011886B69002BD8D002F014FA6A69A0EB5A +:1068A000040982464A450DD2022002F0F1FB002283 +:1068B000D8F81030B34208D151462846BDE8F04719 +:1068C000FFF728BF121A2244F2E712EB0909294602 +:1068D000384638BF4A46FFF7EBFEB5E7D8F8103028 +:1068E000B34208D01444C8F81C00211AA960BDE8BE +:1068F000F047FFF7F3BEBDE8F08700BF7846002001 +:106900006846002038B502F0DDF9054AD2E90845AD +:10691000031B181945F10001C2E9080138BD00BF89 +:106920006846002010B560B9074804790368053C43 +:106930009B6818BF0124984708B144F0040420461E +:1069400010BD0124FBE700BFC8360020FFF7EABFF7 +:106950002DE9F047884617469A460446B0B90D4ED1 +:106960003579052D05D003240DE0013D15F0FF0517 +:106970000ED03268534639463046D2F8149042461B +:10698000C8470028F1D12046BDE8F0870424FAE783 +:106990000124F8E7C83600202DE9F047884617465D +:1069A0009A460446B0B90D4E3579052D05D003241D +:1069B0000DE0013D15F0FF050ED032685346394613 +:1069C0003046D2F818904246C8470028F1D12046F8 +:1069D000BDE8F0870424FAE70124F8E7C836002070 +:1069E00037B50C46154670B951B101290BD107488E +:1069F000694603681B6A984710B9019B04462B60DF +:106A0000204603B030BD0424FAE700BFC83600209A +:106A100000207047FEE70000704700004FF0FF3095 +:106A2000704700004B6843608B688360CB68C3602D +:106A30000B6943614B6903628B6943620B680360B6 +:106A40007047000008B53C4B40F2FF713B48D3F85B +:106A500088200A43C3F88820D3F8882022F4FF62F4 +:106A600022F00702C3F88820D3F88830344B1A6C20 +:106A70000A431A649A6E0A439A66324A9B6E11461A +:106A8000FFF7D0FF00F5806002F11C01FFF7CAFF9D +:106A900000F5806002F13801FFF7C4FF00F5806067 +:106AA00002F15401FFF7BEFF00F5806002F17001B2 +:106AB000FFF7B8FF00F5806002F18C01FFF7B2FF2D +:106AC00000F5806002F1A801FFF7ACFF00F58060DF +:106AD00002F1C401FFF7A6FF00F5806002F1E001BA +:106AE000FFF7A0FF00F5806002F1FC01FFF79AFFBD +:106AF00002F58C7100F58060FFF794FF01F09CFCBB +:106B0000114BD3F8902242F00102C3F89022D3F83F +:106B1000942242F00102C3F894220522C3F898207F +:106B20004FF06052C3F89C20084AC3F8A020BDE88B +:106B3000084000F0F3BC00BF0044025800000258B7 +:106B4000004502583499000800ED00E01F000803DA +:106B500008B501F079FEFFF7D5FC0D4BDA6B42F07A +:106B60004002DA635A6E22F040025A665B6E094BAD +:106B70001A6842F008021A601A6842F004021A60A9 +:106B800000F096FD00F032FBBDE8084000F0B4B81C +:106B90000045025800180248012070470020704745 +:106BA0007047000002290CD0032904D001290748AE +:106BB00018BF00207047032A05D8054800EBC20023 +:106BC0007047044870470020704700BF389B00089A +:106BD00054220020EC9A000870B59AB00546084689 +:106BE000144601A900F0C2F801A8FBF791F8431C74 +:106BF0000022C6B25B001046C5E9003423700323AF +:106C0000023404F8013C01ABD1B202348E4201D807 +:106C10001AB070BD13F8011B013204F8010C04F81E +:106C2000021CF1E708B5302383F311880348FFF70E +:106C30009FF8002383F3118808BD00BF1849002086 +:106C400090F8803003F01F02012A07D190F88120CC +:106C50000B2A03D10023C0E91D3315E003F06003C4 +:106C6000202B08D1B0F884302BB990F88120212A4C +:106C700003D81F2A04D8FFF75DB8222AEBD0FAE721 +:106C8000034A426707228267C3670120704700BF3B +:106C90004B22002007B5052917D8DFE801F01916A7 +:106CA00003191920302383F31188104A0121019020 +:106CB000FFF706F9019802210D4AFFF701F90D4887 +:106CC000FFF722F8002383F3118803B05DF804FB7B +:106CD000302383F311880748FEF7ECFFF2E73023F7 +:106CE00083F311880348FFF703F8EBE78C9A000859 +:106CF000B09A00081849002038B50C4D0C4C2A46B3 +:106D00000C4904F10800FFF767FF05F1CA0204F11E +:106D100010000949FFF760FF05F5CA7204F1180079 +:106D20000649BDE83840FFF757BF00BFF0610020BB +:106D300054220020689A0008729A0008819A00087C +:106D400070B5044608460D46FAF7E2FFC6B2204683 +:106D5000013403780BB9184670BD32462946FAF75C +:106D6000C3FF0028F3D10120F6E700002DE9F0472A +:106D700005460C46FAF7CCFF2B49C6B22846FFF76A +:106D8000DFFF08B10E36F6B228492846FFF7D8FFD4 +:106D900008B11036F6B2632E0BD8DFF88C80DFF81E +:106DA0008C90234FDFF894A02E7846B92670BDE86A +:106DB000F08729462046BDE8F04702F00DBA252E9F +:106DC0002ED1072241462846FAF78EFF70B9194B9B +:106DD000224603F1140153F8040B8B4242F8040BD2 +:106DE000F9D11B78073515341370DDE708224946C1 +:106DF0002846FAF779FF98B9A21C0F4B197802328E +:106E00000909C95D02F8041C13F8011B01F00F0108 +:106E10005345C95D02F8031CF0D118340835C3E7A7 +:106E2000013504F8016BBFE7589B0008819A000800 +:106E3000769B0008609B000800E8F11F0CE8F11F3A +:106E4000BFF34F8F044B1A695107FCD1D3F81021BF +:106E50005207F8D1704700BF0020005208B50D4B13 +:106E60001B78ABB9FFF7ECFF0B4BDA68D10704D501 +:106E70000A4A5A6002F188325A60D3F80C21D207CC +:106E800006D5064AC3F8042102F18832C3F804216A +:106E900008BD00BF4E64002000200052230167455A +:106EA00008B5114B1B78F3B9104B1A69510703D57C +:106EB000DA6842F04002DA60D3F81021520705D5B3 +:106EC000D3F80C2142F04002C3F80C21FFF7B8FFC1 +:106ED000064BDA6842F00102DA60D3F80C2142F086 +:106EE0000102C3F80C2108BD4E64002000200052AE +:106EF0000F289ABF00F58060400400207047000012 +:106F00004FF4003070470000102070470F2808B57C +:106F10000BD8FFF7EDFF00F500330268013204D112 +:106F200004308342F9D1012008BD0020FCE70000B5 +:106F30000F2838B505463FD8FFF782FF1F4CFFF7F3 +:106F40008DFF4FF0FF3307286361C4F814311DD85B +:106F50002361FFF775FF030243F02403E360E36856 +:106F600043F08003E36023695A07FCD42846FFF707 +:106F700067FFFFF7BDFF4FF4003100F0ABFA284682 +:106F8000FFF78EFFBDE83840FFF7C0BFC4F81031EF +:106F9000FFF756FFA0F108031B0243F02403C4F8D7 +:106FA0000C31D4F80C3143F08003C4F80C31D4F820 +:106FB00010315B07FBD4D9E7002038BD0020005218 +:106FC0002DE9F84F05460C46104645EA0203DE0659 +:106FD00002D00020BDE8F88F20F01F00DFF8BCB021 +:106FE000DFF8BCA0FFF73AFF04EB0008444503D1EB +:106FF0000120FFF755FFEDE720222946204602F049 +:10700000B3F810B920352034F0E72B4605F1200203 +:107010001F68791CDDD104339A42F9D105F1784318 +:107020001B481C4EB3F5801F1B4B38BF184603F19D +:10703000F80332BFD946D1461E46FFF701FF07606D +:10704000A5EB040C336804F11C0143F00203336028 +:10705000231FD9F8007017F00507FAD153F8042F51 +:107060008B424CF80320F4D1BFF34F8FFFF7E8FEBB +:107070004FF0FF332022214603602846336823F077 +:107080000203336002F070F80028BBD03846B0E746 +:10709000142100520C2000521420005210200052E3 +:1070A0001021005210B5084C237828B11BB9FFF706 +:1070B000D5FE0123237010BD002BFCD02070BDE84D +:1070C0001040FFF7EDBE00BF4E6400202DE9F04FE9 +:1070D0000D4685B0814658B111F00D0614BF20222F +:1070E000082211F00803019304D0431E034269D023 +:1070F000002435E0002E37D009F11F0121F01F09CF +:107100004FF00108314F05F00403DFF8CCA005EA89 +:10711000080BBBF1000F32D07869C0072FD408F1FB +:1071200001080C37B8F1060FF3D19EB9284D494636 +:10713000A819019201F02CFE0446002839D120360E +:10714000019AA02EF3D1494601F022FE0446002800 +:107150002FD1019A49461F4801F01AFE044660BB30 +:10716000204605B0BDE8F08F0029C9D10146284668 +:10717000029201F00DFE0446D8B9029AC0E713B19D +:1071800078694107CBD5AC0702D578698007C6D5A9 +:10719000019911B178690107C1D549460AEB481038 +:1071A000CDE9022301F0F4FD0446DDE902230028C5 +:1071B000B5D04A460021204601E04A460021FAF7B0 +:1071C000AFFDCDE70246002E96D199E7889B0008D7 +:1071D0009064002050640020706400200021FFF7BC +:1071E00075BF00000121FFF771BF000070B5144D9D +:1071F0000124144E40F2FF3200210120FAF790FDE5 +:1072000006EB441001342A6955F80C1F01F0ACFD5F +:10721000062CF5D137254FF4C0542046FFF7E2FF86 +:10722000014628B122460848BDE8704001F09CBDE7 +:10723000C4EBC404013D4FEAD404EED170BD00BFDD +:10724000889B000870640020506400200421FFF730 +:107250003DBF00004843FFF7C1BF000008B101F087 +:1072600009BE7047B0F5805F10B5044607D8FFF738 +:10727000EDFF28B92046BDE81040FFF7AFBF002062 +:1072800010BD0000FFF7EABF70B5AAB140EA0103E4 +:1072900013F01F030FD1094C0144A5686D0706D5F3 +:1072A0002568A84203D366683544A94204D903334C +:1072B0000C34122BF1D10022104670BD889B0008BF +:1072C00008B501F0EDFE034AD2E90032C01842EBE6 +:1072D000010108BD30650020434BD3E900232DE9AF +:1072E000F34113437CD0FFF7EBFF404A0023002714 +:1072F000F9F7A2F806460D463D4A0023F9F79CF837 +:107300000023144630462946394AF9F795F84FF4D8 +:1073100061613C23ADF80170B4FBF1F5B4FBF3F609 +:1073200001FB154103FB16464624B1FBF3F1314B3B +:10733000F6B28DF8004098423CD84FF0640C4FF400 +:10734000C87EA30704F26C7225D1B2FBFCF30CFBE0 +:10735000132313BBB2FBFEF30EFB1322B2FA82F32C +:107360005B0903F26D18621C8045D2B217D90FB1C8 +:107370008DF800400022204C4FF00C0C17460CFBFF +:107380000343D4B2013213F804C084450CD8A0EBF7 +:107390000C000127F5E70023E3E70123E1E7A0EB79 +:1073A000080014460127CCE70FB18DF80140431CBB +:1073B0008DF802309DF80100431C9DF80000503804 +:1073C000400640EA43509DF8023040EA034040EA5C +:1073D000560040EAC52040EA411002B0BDE8F08105 +:1073E0004FF40410F9E700BF3065002040420F0061 +:1073F0008051010090230B00D09B00080244074BF2 +:10740000D2B210B5904200D110BD441C00B253F866 +:10741000200041F8040BE0B2F4E700BF50400058F0 +:107420000E4B30B51C6F240405D41C6F1C671C6FF9 +:1074300044F400441C670A4C02442368D2B243F46B +:1074400080732360074B904200D130BD441C51F83B +:10745000045B00B243F82050E0B2F4E70044025865 +:10746000004802585040005807B5012201A90020E9 +:10747000FFF7C4FF019803B05DF804FB13B50446A1 +:10748000FFF7F2FFA04205D0012201A900200194DC +:10749000FFF7C6FF02B010BD10B56424013C4FF4E5 +:1074A0007A70FFF7B7F814F0FF04F7D1084B4FF0EC +:1074B000807214249A6103F5805308229A61013C7A +:1074C0004FF47A70FFF7A6F814F0FF04F7D110BD5F +:1074D000000002580144BFF34F8F064B884204D38B +:1074E000BFF34F8FBFF36F8F7047C3F85C0220303C +:1074F000F4E700BF00ED00E00144BFF34F8F064BFF +:10750000884204D3BFF34F8FBFF36F8F7047C3F828 +:1075100070022030F4E700BF00ED00E0114BDA69A3 +:1075200052021ED59A69D00704D50F4A9A6002F11B +:1075300044329A600B4BDA69D107FCD41A6A22F400 +:1075400080021A629A6942F002029A61DA69D207ED +:10755000FCD49A6942F001029A61024AD369DB07BE +:10756000FCD47047002000523B2A190870B505462C +:1075700016460C4601201021FFF76CFE286046736A +:107580003CB1204636B1FFF761FE2B68186000B1B0 +:107590009C6070BDFFF726FEF7E70000F8B50F46C8 +:1075A0001546044648B905F11F010126386821F047 +:1075B0001F01FFF78FFF3046F8BD427B2946386830 +:1075C000FFF762FE06460028EDD13B686360A368C2 +:1075D000AB4210D213B12068FFF740FE637B284610 +:1075E0002BB1FFF733FE206020B9A060E3E7FFF77F +:1075F000F9FDF8E7A560206805F11F01012621F0DB +:107600001F013860FFF766FF2673D4E710B5044604 +:1076100040B10068884205D1606808B1FAF75AFBAA +:107620000023237310BD0000F8B50F46144605462D +:1076300048B904F11F010126386821F01F01FFF746 +:107640005BFF3046F8BD427B21463868FFF71CFEE1 +:1076500006460028EDD1AB68A34210D213B12868CA +:10766000FFF7FCFD6B7B20462BB1FFF7EFFD286099 +:1076700020B9A860E5E7FFF7B5FDF8E7AC60396829 +:1076800019B122462868FAF725FB286804F11F0182 +:10769000012621F01F013860FFF72EFF2E73D0E77F +:1076A00020B103688B4204BF0023037370470000BE +:1076B000034B1A681AB9034AD2F8D0241A607047EB +:1076C000386500200040025808B5FFF7F1FF024B73 +:1076D0001868C0F3806008BD38650020EFF30983A7 +:1076E000054968334A6B22F001024A6383F3098833 +:1076F000002383F31188704700EF00E0302080F30F +:10770000118862B60D4B0E4AD96821F4E061090474 +:10771000090C0A430B49DA60D3F8FC2042F080726E +:10772000C3F8FC20084AC2F8B01F116841F00101FB +:1077300011602022DA7783F82200704700ED00E024 +:107740000003FA0555CEACC5001000E0302310B59B +:1077500083F311880E4B5B6813F4006314D0F1EED1 +:10776000103AEFF309844FF08073683CE361094BF2 +:10777000DB6B236684F30988FEF796FE10B1064B97 +:10778000A36110BD054BFBE783F31188F9E700BF48 +:1077900000ED00E000EF00E02F04000832040008D4 +:1077A00070B5BFF34F8FBFF36F8F1A4A0021C2F835 +:1077B0005012BFF34F8FBFF36F8F536943F4003301 +:1077C0005361BFF34F8FBFF36F8FC2F88410BFF3C5 +:1077D0004F8FD2F8803043F6E074C3F3C900C3F38F +:1077E0004E335B0103EA0406014646EA817501391E +:1077F000C2F86052F9D2203B13F1200FF2D1BFF34F +:107800004F8F536943F480335361BFF34F8FBFF3FE +:107810006F8F70BD00ED00E0FEE70000214B2248B5 +:10782000224A70B5904237D3214BC11EDA1C121A7E +:1078300022F003028B4238BF00220021FAF770FACF +:107840001C4A0023C2F88430BFF34F8FD2F8803037 +:1078500043F6E074C3F3C900C3F34E335B0103EA9C +:107860000406014646EA81750139C2F86C52F9D224 +:10787000203B13F1200FF2D1BFF34F8FBFF36F8F77 +:10788000BFF34F8FBFF36F8F0023C2F85032BFF3A7 +:107890004F8FBFF36F8F70BD53F8041B40F8041B6C +:1078A000C0E700BFD49C0008346700203467002084 +:1078B0003467002000ED00E0054B996B21EA0001E0 +:1078C00099631A6E22EA00021A661B6E704700BFA7 +:1078D0000045025870B5D0E9244300224FF0FF352F +:1078E0009E6804EB42135101D3F80009002805DA21 +:1078F000D3F8000940F08040C3F80009D3F8000B2A +:10790000002805DAD3F8000B40F08040C3F8000BE4 +:10791000013263189642C3F80859C3F8085BE0D2F5 +:107920004FF00113C4F81C3870BD0000890141F00C +:107930002001016103699B06FCD41220FEF7FEBD05 +:1079400010B50A4C2046FEF799FA094BC4F890305E +:10795000084BC4F89430084C2046FEF78FFA074BCA +:10796000C4F89030064BC4F8943010BD3C6500203C +:10797000000008400C9C0008D8650020000004406E +:10798000189C000870B503780546012B58D13F4B71 +:10799000D0F89040984254D13D4B0E2165209A6B0F +:1079A00042F000629A631A6E42F000621A661B6E21 +:1079B000384BD3F8802042F00062C3F88020D3F81F +:1079C000802022F00062C3F88020D3F88030FDF7D9 +:1079D00099FC314BE360314BC4F800380023D5F8F3 +:1079E0009060C4F8003EC02323604FF40413A363E7 +:1079F0003369002BFCDA01230C203361FEF79EFD76 +:107A00003369DB07FCD41220FEF798FD3369002BA5 +:107A1000FCDA00262846A660FFF75CFF6B68C4F816 +:107A20001068DB68C4F81468C4F81C6863BB1C4B9E +:107A3000A3614FF0FF336361A36843F00103A360C8 +:107A400070BD184B9842C9D1114B4FF080609A6BB2 +:107A500042F000729A631A6E42F000721A661B6E50 +:107A60000C4BD3F8802042F00072C3F88020D3F88A +:107A7000802022F00072C3F88020D3F88030FFF716 +:107A80001BFF0E214D20A2E7074BD1E73C650020EC +:107A900000450258004402584014004003002002F0 +:107AA000003C30C0D8650020083C30C0F8B5D0F8A4 +:107AB0009040054600214FF000662046FFF736FF54 +:107AC000D5F8941000234FF001128F684FF0FF306B +:107AD000C4F83438C4F81C2804EB431201339F4225 +:107AE000C2F80069C2F8006BC2F80809C2F8080BB6 +:107AF000F2D20B68D5F89020C5F898306362102355 +:107B00001361166916F01006FBD11220FEF716FD60 +:107B1000D4F8003823F4FE63C4F80038A36943F4B2 +:107B2000402343F01003A3610923C4F81038C4F8BC +:107B300014380B4BEB604FF0C043C4F8103B094BBB +:107B4000C4F8003BC4F81069C4F80039D5F898307F +:107B500003F1100243F48013C5F89820A362F8BD26 +:107B6000E89B000840800010D0F8902090F88A1020 +:107B7000D2F8003823F4FE6343EA0113C2F8003858 +:107B8000704700002DE9F84300EB8103D0F89050D6 +:107B90000C468046DA680FFA81F94801166806F04B +:107BA0000306731E022B05EB41134FF0000194BF37 +:107BB000B604384EC3F8101B4FF0010104F1100356 +:107BC00098BF06F1805601FA03F3916998BF06F554 +:107BD000004600293AD0578A04F158013743490139 +:107BE0006F50D5F81C180B430021C5F81C382B1812 +:107BF0000127C3F81019A7405369611E9BB3138A6C +:107C0000928B9B08012A88BF5343D8F89820981874 +:107C100042EA034301F140022146C8F89800284691 +:107C200005EB82025360FFF781FE08EB8900C36811 +:107C30001B8A43EA845348341E4364012E51D5F80D +:107C40001C381F43C5F81C78BDE8F88305EB4917BD +:107C5000D7F8001B21F40041C7F8001BD5F81C1809 +:107C600021EA0303C0E704F13F030B4A28462146FB +:107C700005EB83035A60FFF759FE05EB4910D0F876 +:107C8000003923F40043C0F80039D5F81C3823EA42 +:107C90000707D7E70080001000040002D0F8942006 +:107CA0001268C0F89820FFF715BE00005831D0F8D0 +:107CB000903049015B5813F4004004D013F4001FC6 +:107CC0000CBF0220012070474831D0F890304901A4 +:107CD0005B5813F4004004D013F4001F0CBF0220C3 +:107CE0000120704700EB8101CB68196A0B681360B3 +:107CF0004B6853607047000000EB810330B5DD68CE +:107D0000AA691368D36019B9402B84BF402313605C +:107D10006B8A1468D0F890201C4402EB4110013C9F +:107D200009B2B4FBF3F46343033323F0030343EAE0 +:107D3000C44343F0C043C0F8103B2B6803F0030377 +:107D4000012B0ED1D2F8083802EB411013F4807FDA +:107D5000D0F8003B14BF43F0805343F00053C0F809 +:107D6000003B02EB4112D2F8003B43F00443C2F85F +:107D7000003B30BD2DE9F041D0F8906005460C463F +:107D800006EB4113D3F8087B3A07C3F8087B08D504 +:107D9000D6F814381B0704D500EB8103DB685B6859 +:107DA0009847FA071FD5D6F81438DB071BD505EB23 +:107DB0008403D968CCB98B69488A5A68B2FBF0F65B +:107DC00000FB16228AB91868DA6890420DD2121A9E +:107DD000C3E90024302383F3118821462846FFF7A6 +:107DE0008BFF84F31188BDE8F081012303FA04F2CC +:107DF0006B8923EA02036B81CB68002BF3D0214609 +:107E00002846BDE8F041184700EB81034A0170B5F0 +:107E1000DD68D0F890306C692668E66056BB1A447D +:107E20004FF40020C2F810092A6802F00302012A68 +:107E30000AB20ED1D3F8080803EB421410F4807F85 +:107E4000D4F8000914BF40F0805040F00050C4F84E +:107E5000000903EB4212D2F8000940F00440C2F8D6 +:107E600000090122D3F8340802FA01F10143C3F8F2 +:107E7000341870BD19B9402E84BF4020206020689E +:107E80001A442E8A8419013CB4FBF6F440EAC4403B +:107E900040F00050C6E700002DE9F843D0F89060AC +:107EA00005460C464F0106EB4113D3F8088918F03C +:107EB000010FC3F808891CD0D6F81038DB0718D595 +:107EC00000EB8103D3F80CC0DCF81430D3F800E0E9 +:107ED000DA68964530D2A2EB0E024FF000091A6024 +:107EE000C3F80490302383F31188FFF78DFF89F3E3 +:107EF000118818F0800F1DD0D6F834380126A6401E +:107F0000334217D005EB84030134D5F89050D3F8F1 +:107F10000CC0E4B22F44DCF8142005EB0434D2F892 +:107F200000E05168714514D3D5F8343823EA0606C9 +:107F3000C5F83468BDE8F883012303FA01F2038928 +:107F400023EA02030381DCF80830002BD1D09847E4 +:107F5000CFE7AEEB0103BCF81000834228BF034615 +:107F6000D7F8180980B2B3EB800FE3D89068A0F17E +:107F7000040959F8048FC4F80080A0EB090898445C +:107F8000B8F1040FF5D818440B4490605360C8E76B +:107F90002DE9F84FD0F8905004466E69AB691E4049 +:107FA00016F480586E6103D0BDE8F84FFDF7D6BFD8 +:107FB000002E12DAD5F8003E9B0705D0D5F8003E1A +:107FC00023F00303C5F8003ED5F80438204623F01B +:107FD0000103C5F80438FDF7EFFF370505D5204646 +:107FE000FFF778FC2046FDF7D5FFB0040CD5D5F897 +:107FF000083813F0060FEB6823F470530CBF43F4FA +:10800000105343F4A053EB6031071BD56368DB6862 +:108010001BB9AB6923F00803AB612378052B0CD1A6 +:10802000D5F8003E9A0705D0D5F8003E23F00303AB +:10803000C5F8003E2046FDF7BFFF6368DB680BB163 +:1080400020469847F30200F1BA80B70226D5D4F84B +:10805000909000274FF0010A09EB4712D2F8003B3D +:1080600003F44023B3F5802F11D1D2F8003B002B4D +:108070000DDA62890AFA07F322EA0303638104EB4B +:108080008703DB68DB6813B1394620469847013720 +:10809000D4F89430FFB29B689F42DDD9F00619D521 +:1080A000D4F89000026AC2F30A1702F00F0302F438 +:1080B000F012B2F5802F00F0CA80B2F5402F09D13E +:1080C00004EB8303002200F58050DB681B6A9742B3 +:1080D00040F0B0803003D5F8185835D5E90303D502 +:1080E00000212046FFF746FEAA0303D501212046C2 +:1080F000FFF740FE6B0303D502212046FFF73AFE4F +:108100002F0303D503212046FFF734FEE80203D5F1 +:1081100004212046FFF72EFEA90203D505212046A3 +:10812000FFF728FE6A0203D506212046FFF722FE4C +:108130002B0203D507212046FFF71CFEEF0103D5D4 +:1081400008212046FFF716FE700340F1A780E907DB +:1081500003D500212046FFF79FFEAA0703D5012182 +:108160002046FFF799FE6B0703D502212046FFF753 +:1081700093FE2F0703D503212046FFF78DFEEE0661 +:1081800003D504212046FFF787FEA80603D5052165 +:108190002046FFF781FE690603D506212046FFF73A +:1081A0007BFE2A0603D507212046FFF775FEEB0567 +:1081B00074D520460821BDE8F84FFFF76DBED4F80E +:1081C00090904FF0000B4FF0010AD4F894305FFA12 +:1081D0008BF79B689F423FF638AF09EB4713D3F804 +:1081E000002902F44022B2F5802F20D1D3F80029D3 +:1081F000002A1CDAD3F8002942F09042C3F8002983 +:10820000D3F80029002AFBDB3946D4F89000FFF7A9 +:108210008DFB22890AFA07F322EA0303238104EB88 +:108220008703DB689B6813B13946204698470BF1FA +:10823000010BCAE7910701D1D0F80080072A02F1AB +:1082400001029CBF03F8018B4FEA18283FE704EBBB +:10825000830300F58050DA68D2F818C0DCF80820F3 +:10826000DCE9001CA1EB0C0C00218F4208D1DB687B +:108270009B699A683A449A605A683A445A6029E776 +:1082800011F0030F01D1D0F800808C4501F10101FC +:1082900084BF02F8018B4FEA1828E6E7BDE8F88FA3 +:1082A00008B50348FFF774FEBDE80840FFF74EBA73 +:1082B0003C65002008B50348FFF76AFEBDE80840AA +:1082C000FFF744BAD8650020D0F8903003EB411195 +:1082D000D1F8003B43F40013C1F8003B70470000A5 +:1082E000D0F8903003EB4111D1F8003943F400137A +:1082F000C1F8003970470000D0F8903003EB41110D +:10830000D1F8003B23F40013C1F8003B7047000094 +:10831000D0F8903003EB4111D1F8003923F4001369 +:10832000C1F8003970470000044BDA6B0243DA638E +:108330005A6E104358665B6E704700BF0045025886 +:1083400008B53C4B4FF0FF31D3F8802062F000427B +:10835000C3F88020D3F8802002F00042C3F88020C8 +:10836000D3F88020D3F88420C3F88410D3F8842075 +:108370000022C3F88420D3F88400D86F40F0FF4077 +:1083800040F4FF0040F4DF4040F07F00D867D86F32 +:1083900020F0FF4020F4FF0020F4DF4020F07F00B9 +:1083A000D867D86FD3F888006FEA40506FEA505012 +:1083B000C3F88800D3F88800C0F30A00C3F8880027 +:1083C000D3F88800D3F89000C3F89010D3F8900049 +:1083D000C3F89020D3F89000D3F89400C3F8941019 +:1083E000D3F89400C3F89420D3F89400D3F89800FD +:1083F000C3F89810D3F89800C3F89820D3F89800E1 +:10840000D3F88C00C3F88C10D3F88C00C3F88C2000 +:10841000D3F88C00D3F89C00C3F89C10D3F89C10C0 +:10842000C3F89C20D3F89C30FCF73AFABDE808402A +:1084300000F0D2B90044025808B50122504BC3F8ED +:108440000821504B5A6D42F002025A65DA6F42F031 +:108450000202DA670422DB6F4B4BDA605A68910440 +:10846000FCD54A4A1A6001229A60494ADA60002221 +:108470001A614FF440429A61434B9A699204FCD5C9 +:108480001A6842F480721A60424B1A6F12F4407FED +:1084900004D04FF480321A6700221A671A6842F03B +:1084A00001021A603B4B1A685007FCD500221A6182 +:1084B0001A6912F03802FBD1012119604FF0804196 +:1084C00059605A67344ADA62344A1A611A6842F4C7 +:1084D00080321A602F4B1A689103FCD51A6842F457 +:1084E00080521A601A689204FCD52D4A2D499A626E +:1084F00000225A63196301F57C01DA6301F5E77123 +:1085000099635A64284A1A64284ADA621A6842F05F +:10851000A8521A601F4B1A6802F02852B2F1285F65 +:10852000F9D148229A614FF48862DA6140221A62D6 +:108530001F4ADA641F4A1A651F4A5A651F4A9A651C +:1085400032231F4A1360136803F00F03022BFAD182 +:10855000104A136943F003031361136903F03803EE +:10856000182BFAD14FF00050FFF7DEFE4FF080409D +:10857000FFF7DAFE4FF00040BDE80840FFF7D4BE39 +:1085800000800051004502580048025800C000F029 +:1085900004000001004402580000FF010088900818 +:1085A0003220600063020901470E0508DD0BBF01A0 +:1085B00020000020000001100910E000000101105F +:1085C000002000524FF0B04208B5D2F8883003F0D6 +:1085D0000103C2F8883023B1044A13680BB1506814 +:1085E0009847BDE80840FFF7B1B800BFB466002067 +:1085F0004FF0B04208B5D2F8883003F00203C2F859 +:10860000883023B1044A93680BB1D0689847BDE81D +:108610000840FFF79BB800BFB46600204FF0B0429F +:1086200008B5D2F8883003F00403C2F8883023B1CB +:10863000044A13690BB150699847BDE80840FFF739 +:1086400085B800BFB46600204FF0B04208B5D2F83C +:10865000883003F00803C2F8883023B1044A9369D4 +:108660000BB1D0699847BDE80840FFF76FB800BF6D +:10867000B46600204FF0B04208B5D2F8883003F05D +:108680001003C2F8883023B1044A136A0BB1506A50 +:108690009847BDE80840FFF759B800BFB46600200E +:1086A0004FF0B04310B5D3F8884004F47872C3F8A3 +:1086B0008820A30604D5124A936A0BB1D06A984762 +:1086C000600604D50E4A136B0BB1506B9847210618 +:1086D00004D50B4A936B0BB1D06B9847E20504D5D8 +:1086E000074A136C0BB1506C9847A30504D5044A94 +:1086F000936C0BB1D06C9847BDE81040FFF726B8DB +:10870000B46600204FF0B04310B5D3F8884004F4AD +:108710007C42C3F88820620504D5164A136D0BB15C +:10872000506D9847230504D5124A936D0BB1D06D57 +:108730009847E00404D50F4A136E0BB1506E98476A +:10874000A10404D50B4A936E0BB1D06E9847620416 +:1087500004D5084A136F0BB1506F9847230404D512 +:10876000044A936F0BB1D06F9847BDE81040FEF7F5 +:10877000EDBF00BFB466002008B50348FCF73CFC21 +:10878000BDE80840FEF7E2BFC836002008B5034840 +:10879000FCF732FDBDE80840FEF7D8BF20390020C5 +:1087A00008B50348FCF728FDBDE80840FEF7CEBF3A +:1087B0008C39002008B50348FCF71EFDBDE80840D1 +:1087C000FEF7C4BFF839002008B500F0B7FCBDE8DB +:1087D0000840FEF7BBBF0000062108B50846FCF7BD +:1087E00091FD06210720FCF78DFD06210820FCF7EE +:1087F00089FD06210920FCF785FD06210A20FCF7EA +:1088000081FD06211720FCF77DFD06212820FCF7BD +:1088100079FD09217A20FCF775FD09213120FCF74B +:1088200071FD07213220FCF76DFD0C212620FCF79D +:1088300069FD0C212720FCF765FD0C215220BDE8C5 +:108840000840FCF75FBD000008B5FFF779FD00F0B8 +:1088500043FCFDF737F9FDF7D5F8FDF70DFBFDF704 +:10886000DFF9FEF79DF9BDE8084000F029BA0000E5 +:1088700030B50433039C0172002104FB0325C16061 +:10888000C0E90653049B0363059BC0E90000C0E9EF +:108890000422C0E90842C0E90A11436330BD000068 +:1088A0000022416AC260C0E90411C0E90A226FF0E7 +:1088B0000101FDF7EFBE0000D0E90432934201D17F +:1088C000C2680AB9181D7047002070470369196013 +:1088D0000021C2680132C260C269134482699342B6 +:1088E000036124BF436A0361FDF7C8BE38B504467F +:1088F0000D46E3683BB162690020131D1268A36254 +:108900001344E36207E0237A33B929462046FDF792 +:10891000A5FE0028EDDA38BD6FF00100FBE700008E +:10892000C368C269013BC3604369134482699342CF +:10893000436124BF436A436100238362036B03B135 +:108940001847704770B53023044683F31188866A50 +:108950003EB9FFF7CBFF054618B186F311882846CC +:1089600070BDA36AE26A13F8015B9342A36202D36B +:108970002046FFF7D5FF002383F31188EFE70000BF +:108980002DE9F84F04460E46174698464FF0300939 +:1089900089F311880025AA46D4F828B0BBF1000F4E +:1089A00009D141462046FFF7A1FF20B18BF3118882 +:1089B0002846BDE8F88FD4E90A12A7EB050B521A36 +:1089C000934528BF9346BBF1400F1BD9334601F1B5 +:1089D000400251F8040B914243F8040BF9D1A36A09 +:1089E000403640354033A362D4E90A239A4202D389 +:1089F0002046FFF795FF8AF31188BD42D8D289F34C +:108A00001188C9E730465A46F9F764F9A36A5E440B +:108A10005D445B44A362E7E710B5029C0433017236 +:108A200003FB0421C460C0E906130023C0E90A3334 +:108A3000039B0363049BC0E90000C0E90422C0E972 +:108A40000842436310BD0000026A6FF00101C2607A +:108A5000426AC0E904220022C0E90A22FDF71ABED8 +:108A6000D0E904239A4201D1C26822B9184650F8CD +:108A7000043B0B60704700231846FAE7C3680021E7 +:108A8000C2690133C36043691344826993424361FD +:108A900024BF436A4361FDF7F1BD000038B50446C9 +:108AA0000D46E3683BB1236900201A1DA262E2690A +:108AB0001344E36207E0237A33B929462046FDF7E1 +:108AC000CDFD0028EDDA38BD6FF00100FBE70000B6 +:108AD00003691960C268013AC260C26913448269BD +:108AE0009342036124BF436A036100238362036BE3 +:108AF00003B118477047000070B530230D46044697 +:108B0000114683F31188866A2EB9FFF7C7FF10B1AB +:108B100086F3118870BDA36A1D70A36AE26A0133EF +:108B20009342A36204D3E16920460439FFF7D0FFE2 +:108B3000002080F31188EDE72DE9F84F04460D463B +:108B4000904699464FF0300A8AF311880026B346C2 +:108B5000A76A4FB949462046FFF7A0FF20B187F327 +:108B600011883046BDE8F88FD4E90A073A1AA8EB15 +:108B70000607974228BF1746402F1BD905F140032F +:108B800055F8042B9D4240F8042BF9D1A36A4036D6 +:108B90004033A362D4E90A239A4204D3E169204610 +:108BA0000439FFF795FF8BF311884645D9D28AF334 +:108BB0001188CDE729463A46F9F78CF8A36A3D4477 +:108BC0003E443B44A362E5E7D0E904239A4217D12F +:108BD000C3689BB1836A8BB1043B9B1A0ED01360B0 +:108BE000C368013BC360C3691A4483699A42026146 +:108BF00024BF436A03610023836201231846704740 +:108C00000023FBE701F01F03F0B502F01F04560933 +:108C10005A1C0123B6EB511F50F8265003FA02F3F9 +:108C20004FEA511703F1FF333DBF50F82720C4F13D +:108C30002000134003EA05003BBF03FA00F225FAC7 +:108C400004F0E0401043F0BD70B57E227F21054660 +:108C5000FFF7D8FF18B1012819D0002070BD3E22BF +:108C600049212846FFF7CEFF2F220446312128460E +:108C7000FFF7C8FF0646013450220236532128462A +:108C8000B440FFF7BFFF093804FA00F0E6E73022EE +:108C900045212846FFF7B6FF01308002DEE70000DD +:108CA00090F8D63090F8D7201B0403EB026390F8BD +:108CB000D42090F8D500134403EB00207047000047 +:108CC00000F018BA014B586A704700BF000C004012 +:108CD000034B002258631A610222DA60704700BF1A +:108CE000000C0040014B0022DA607047000C00408D +:108CF000014B5863704700BF000C0040024B034A11 +:108D00001A60034A5A6070478C660020386700205A +:108D100000000220074B494210B55C68201A084049 +:108D20001968821A8A4203D3A24201D85A6010BD40 +:108D30000020FCE78C66002008B5302383F31188FF +:108D4000FFF7E8FF002383F3118808BD0448054BB3 +:108D500003600023C0E901330C3000F017B900BFF5 +:108D600094660020398D0008CB1D083A23F00703D4 +:108D7000591A521A10B4D2080024C0E90043846082 +:108D80000C301C605A605DF8044B00F0FFB8000026 +:108D90002DE9F74F364FCD1D8846002818BF0746EE +:108DA000082A4FEAD50538BF082207F10C003C1D00 +:108DB0009146019000F02CF9019809F10701C9F1E1 +:108DC000000E2246246864B900F02CF93B68CBB34E +:108DD00008224946E8009847044698B340E90278DB +:108DE00030E004EB010CD4F804A00CEA0E0C0AF1FC +:108DF0000106ACF1080304EBC6069E42E1D9A6EBDE +:108E00000C0CB5EBEC0F4FEAEC0BDAD89C421DD200 +:108E100004F10802AB45A3EB02024FEAE2026260F2 +:108E200009D9691CED4303EBC1025D445560256817 +:108E300043F8315022601C46C3F8048044F8087B94 +:108E400000F0F0F8204603B0BDE8F08FAA45216895 +:108E500002D111602346EEE7013504EBC50344F867 +:108E6000351003F10801761AF6105E601360F1E721 +:108E70009466002073B50446A0F1080550F8080C6C +:108E800054F8043C061D0C3007330190DB0844F80D +:108E9000043C00F0BDF8334601989E421A6801D0A8 +:108EA000AB4228D20AB1954225D244F8082C54F896 +:108EB000042C1D60013254F8081C05EBC206B142B7 +:108EC00006D14E68324444F8042C0A6844F8082C51 +:108ED0005E68711C03EBC1018D4207D154F8042C6C +:108EE000013232445A6054F8082C1A6002B0BDE8CE +:108EF000704000F097B81346CFE70000FEE700008F +:108F000070B51E4B0025044686B058600E460563BA +:108F10008163FEF7F3FB04F12803A5606563C4E9F0 +:108F20000A3304F11003C4E904334FF0FF33C4E9FA +:108F30000044C4E90635FFF7C5FE2B46024604F19E +:108F40003C012046C4E9082380230D4A6567FDF7EC +:108F5000FFFA7368E0600B4A03620123009280F815 +:108F600024306846F26801923269CDE90223064B4B +:108F7000CDE90435FDF720FB06B070BD1049002097 +:108F80002C9C0008249C0008FD8E00080023C0E9EA +:108F9000000083600361704770B51C4B0546846810 +:108FA000DE685CB3B44213D103690133036170BD61 +:108FB000A36094F8243083B1062B15D1A06A214612 +:108FC000D4E9003213605A60FDF72EFAA36A9C6858 +:108FD000B368A2689A42EBD306E0D4E90032204697 +:108FE00013605A60FDF730FA28463146FDF71CFA47 +:108FF000B5620620BDE87040FDF728BA03698660B7 +:1090000001330361336BC3603063D0E768460020EF +:1090100008B5302383F31188FFF7BEFF002383F3E5 +:10902000118808BD194BD96883688B4210B520D1CF +:10903000302383F311880269013A0261B2B90468EE +:10904000C368A0420B631ED04A6B9BB901238A60A0 +:10905000036103681A68026050601A6B8360C26023 +:1090600018631846FDF7F0F9FDF740FA002383F383 +:10907000118810BD1C68A34203D0A468A24238BF67 +:109080002246DB68E1E78260F0E700BF6846002027 +:10909000024A536B18435063704700BF6846002074 +:1090A00038B5EFF311859DB9EFF30584C4F30804D7 +:1090B000302334B183F31188FDF724FC85F3118844 +:1090C00038BD83F31188FDF71DFC84F3118838BD8A +:1090D000BDE83840FDF716BC0023054A19460133A8 +:1090E000102BC2E9001102F10802F8D1704700BF4D +:1090F000B46600200E4B9A6C42F008029A641A6F14 +:1091000042F008021A670B4A1B6FD36B43F0080347 +:10911000D363C722084B9A624FF0FF32DA62002213 +:109120009A615A63DA605A6001225A611A60704784 +:10913000004502580010005C000C0040094A08B5C8 +:109140001169D3680B40D9B29B076FEA0101116125 +:1091500007D5302383F31188FDF7EEF9002383F35D +:10916000118808BD000C004010B50139024490423E +:1091700001D1002005E0037811F8014FA34201D08E +:10918000181B10BD0130F2E7884210B501EB020454 +:1091900002D98442234607D8431EA14208D011F8C1 +:1091A000012B03F8012FF8E7024401468A4200D15F +:1091B00010BD13F8014D02F8014DF7E7C9B203469F +:1091C00010F8012B1AB18A42F9D1184670470029CC +:1091D00018BF0023F9E70000034611F8012B03F83C +:1091E000012B002AF9D1704710B50139034632B17D +:1091F00011F8014F03F8014B013A002CF7D11A4442 +:109200000021934200D110BD03F8011BF9E70000D3 +:109210004D4435002D2D0A002F6172647570696C04 +:109220006F742E6162696E002F6172647570696C73 +:109230006F742D7665726966792E6162696E002F92 +:109240006172647570696C6F742D666C6173682EE1 +:109250006162696E002F6172647570696C6F742D44 +:10926000666C61736865642E6162696E000000005F +:109270000000000000000000ED0E0008890F00084B +:1092800039110008C10F0008810F0008000000001C +:1092900000000000E90E0008950F00087111000899 +:1092A000E50E0008F10E000853544D333248373FA5 +:1092B0003F3F0053544D3332483733782F3732789D +:1092C0000053544D3332483734332F3735332F372B +:1092D0003530000001105A000310590001205800D9 +:1092E000032056002F000000537563636573736697 +:1092F000756C6C79206D6F756E7465642053444392 +:109300006172642028736C6F77646F776E3D25758A +:10931000290A0000EB769045584641542020200051 +:109320004641543332202020000000002A3A3C3EBF +:109330007C223F7F002B2C3B3D5B5D00435545412C +:109340004141414345454549494941414592924F33 +:109350004F4F5555594F554F9C4F9E9F41494F5523 +:10936000A5A5A6A7A8A9AAABACADAEAFB0B1B2B344 +:10937000B4414141B8B9BABBBCBDBEBFC0C1C2C394 +:10938000C4C54141C8C9CACBCCCDCECFD1D145454A +:109390004549494949D9DADBDCDD49DF4FE14F4F27 +:1093A0004F4FE6E8E85555555959EEEFF0F1F2F315 +:1093B000F4F5F6F7F8F9FAFBFCFDFEFF01030507EB +:1093C000090E10121416181C1E00000061001A036A +:1093D000E0001703F8000703FF0001007801000117 +:1093E000300132010601390110014A012E017901D3 +:1093F000060180014D004302810182018201840146 +:10940000840186018701870189018A018B018B0113 +:109410008D018E018F0190019101910193019401C1 +:10942000F60196019701980198013D029B019C016C +:109430009D0120029F01A001A001A201A201A4019F +:10944000A401A601A701A701A901AA01AB01AC01D2 +:10945000AC01AE01AF01AF01B101B201B301B30183 +:10946000B501B501B701B801B801BA01BB01BC0132 +:10947000BC01BE01F701C001C101C201C301C401A9 +:10948000C501C401C701C801C701CA01CB01CA0196 +:10949000CD011001DD0101008E01DE011201F30199 +:1094A0000300F101F401F401F80128012202120184 +:1094B0003A020900652C3B023B023D02662C3F024A +:1094C00040024102410246020A015302400081016A +:1094D0008601550289018A0158028F015A029001C2 +:1094E0005C025D025E025F0293016102620294010E +:1094F0006402650266026702970196016A02622CA5 +:109500006C026D026E029C01700271029D01730279 +:1095100074029F0176027702780279027A027B0256 +:109520007C02642C7E027F02A60181028202A901D4 +:109530008402850286028702AE014402B101B201B3 +:1095400045028D028E028F0290029102B7017B03C9 +:109550000300FD03FE03FF03AC030400860388033E +:1095600089038A03B1031103C2030200A303A30307 +:10957000C4030803CC0303008C038E038F03D803BA +:109580001801F2030A00F903F303F403F503F603E9 +:10959000F703F703F903FA03FA0330042003500436 +:1095A0001007600422018A043601C1040E01CF04B1 +:1095B0000100C004D004440161052604000000003D +:1095C0007D1D0100632C001E9601A01E5A01001F84 +:1095D0000806101F0606201F0806301F0806401F39 +:1095E0000606511F0700591F521F5B1F541F5D1FA6 +:1095F000561F5F1F601F0806701F0E00BA1FBB1F9B +:10960000C81FC91FCA1FCB1FDA1FDB1FF81FF91F96 +:10961000EA1FEB1FFA1FFB1F801F0806901F08069A +:10962000A01F0806B01F0400B81FB91FB21FBC1F3F +:10963000CC1F0100C31FD01F0206E01F0206E51F5A +:109640000100EC1FF31F0100FC1F4E21010032211D +:1096500070211002842101008321D0241A05302CAE +:109660002F04602C0201672C0601752C0201802C4E +:109670006401002D260841FF1A030000C700FC000A +:10968000E900E200E400E000E500E700EA00EB00AA +:10969000E800EF00EE00EC00C400C500C900E600E1 +:1096A000C600F400F600F200FB00F900FF00D6004F +:1096B000DC00F800A300D800D7009201E100ED0023 +:1096C000F300FA00F100D100AA00BA00BF00AE001A +:1096D000AC00BD00BC00A100AB00BB0091259225F1 +:1096E000932502252425C100C200C000A9006325DE +:1096F000512557255D25A200A500102514253425E8 +:109700002C251C2500253C25E300C3005A255425A3 +:1097100069256625602550256C25A400F000D00041 +:10972000CA00CB00C8003101CD00CE00CF00182503 +:109730000C2588258425A600CC008025D300DF00D9 +:10974000D400D200F500D500B500FE00DE00DA003E +:10975000DB00D900FD00DD00AF00B400AD00B100BA +:109760001720BE00B600A700F700B800B000A800A0 +:10977000B700B900B300B200A025A000100002405D +:10978000080002400008024000000B0028000240D0 +:10979000080002400408024006010C00400002409C +:1097A000080002400808024010020D005800024064 +:1097B000080002400C08024016030E007000024030 +:1097C0000C0002401008024000040F008800024014 +:1097D0000C0002401408024006051000A0000240E0 +:1097E0000C0002401808024010061100B8000240A8 +:1097F0000C0002401C08024016072F001004024013 +:1098000008040240200802400008380028040240F2 +:1098100008040240240802400609390040040240BE +:109820000804024028080240100A3A005804024086 +:10983000080402402C080240160B3B007004024052 +:109840000C04024030080240000C3C008804024036 +:109850000C04024034080240060D4400A0040240FB +:109860000C04024038080240100E4500B8040240C3 +:109870000C0402403C080240160F460001000000A4 +:109880000000000000960000000000000000000042 +:1098900000000000000000000000000000000000C8 +:1098A000996B00089D6B000899560008D159000873 +:1098B0002D560008555600087D560008155600081C +:1098C00000000000855A0008715A0008AD5A0008CF +:1098D000995A0008A55A0008915A00087D5A0008B4 +:1098E000695A0008B95A0008000000009D5B000892 +:1098F000895B0008C55B0008B15B0008BD5B000820 +:10990000A95B0008955B0008815B0008D15B00083B +:1099100000000000010000000000000063300000B3 +:109920001C9900080000000000000000E046002034 +:10993000104900200000812A00000000AAAAAAAA5B +:1099400000000024FFFE00000000000000A00A004C +:109950000001000000000000AAAAAAAA000000005E +:10996000FFFF000000000000000000001400AA56E5 +:1099700000000000AAAAAAAA14005554FFFF000084 +:1099800000000000CCCC0C0020681A000000000091 +:10999000AAAA8AAA10541500FFFF0000000C700745 +:1099A000770000004081020100100000AAAAAAAAC4 +:1099B00000410100F7FF00000000007007000000F8 +:1099C0000000000000000000AAAAAAAA00000000EF +:1099D000FFFF000000000000000000000000000089 +:1099E00000000000AAAAAAAA00000000FFFF0000D1 +:1099F0000000000000000000000000000000000067 +:109A0000AAAAAAAA00000000FFFF000000000000B0 +:109A1000000000000000000000000000AAAAAAAA9E +:109A200000000000FFFF0000000000000000000038 +:109A30000000000000000000AAAAAAAA000000007E +:109A4000FFFF000000000000000000000000000018 +:109A500000000000AAAAAAAA00000000FFFF000060 +:109A600000000000000000004375626550696C6FE3 +:109A70007400437562654F72616E67652B2D424CB1 +:109A8000002553455249414C2500000002000000CA +:109A900000000000BD5D00082D5E00084000400091 +:109AA000C0610020D0610020020000000000000022 +:109AB0000300000000000000755E000800000000C8 +:109AC00010000000E0610020000000000100000024 +:109AD000000000003C65002001010200956C0008B8 +:109AE000A56B0008416C0008256C000843000000CD +:109AF000F49A000809024300020100C03209040080 +:109B000000010202010005240010010524010001EA +:109B1000042402020524060001070582030800FF51 +:109B200009040100020A00000007050102400000CC +:109B3000070581024000000012000000409B000861 +:109B40001201100102000040AE2D58100002010267 +:109B5000030100000403090425424F41524425003B +:109B6000437562654F72616E6765506C75732D62E7 +:109B70006473686F740030313233343536373839B6 +:109B8000414243444546000000000020000002001E +:109B90000200000000000030000004000800000087 +:109BA0000000002400000800040000000004000081 +:109BB00000FC0000020000000000043000800000F3 +:109BC0000800000000000038000001000100000053 +:109BD0001F1C1F1E1F1E1F1F1E1F1E1F1F1D1F1E9F +:109BE0001F1E1F1F1E1F1E1F00000000D15F000848 +:109BF0008962000835630008400040007466002058 +:109C000074660020010000008466002080000000CF +:109C100040010000080000000001000000100000EA +:109C20000800000069646C65000000006D61696EE9 +:109C3000002C0438040438080C10141C2024252699 +:109C400000000000000064040100040000000000A7 +:109C5000000C0010283034001068FF7F0100000065 +:109C6000270400000000000000001E0000000000AB +:109C7000FF00000018490020203900208C39002006 +:109C8000F839002000000000A892000883040000BA +:109C9000B392000850040000C192000801000000C7 +:109CA0000000000000960000000008009600000080 +:109CB0000008000004000000549B000800000000A1 +:109CC0000000000000000000000000000000000094 +:049CD0000000000090 :00000001FF diff --git a/Tools/bootloaders/CubeOrange_bl.bin b/Tools/bootloaders/CubeOrange_bl.bin index cd5b57818bff26..d569f834483460 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 f8477f312eaf59..0aed51f9759452 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 aea4d36ed1a818..c3335dd4d6437f 100644 --- a/Tools/bootloaders/CubeOrange_bl.hex +++ b/Tools/bootloaders/CubeOrange_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 :1000000000060020E1020008E3020008E302000805 :10001000E3020008E3020008E3020008E30200082C -:10002000E3020008E3020008E30200089D8A0008DA +:10002000E3020008E3020008E3020008F17600089A :10003000E3020008E3020008E3020008E30200080C :10004000E3020008E3020008E3020008E3020008FC -:10005000E3020008E3020008497F0008757F0008FA -:10006000A17F0008CD7F0008F97F0008E3020008A7 -:10007000E3020008E3020008E3020008E3020008CC -:10008000E3020008E3020008E3020008E3020008BC -:10009000E3020008E3020008E302000825800008EC +:10005000E3020008E3020008FD8500082986000885 +:100060005586000881860008AD860008094600080C +:10007000314600085D46000889460008B54600087C +:10008000DD46000809470008E3020008E302000813 +:10009000E3020008E3020008E3020008D986000832 :1000A000E3020008E3020008E3020008E30200089C :1000B000E3020008E3020008E3020008E30200088C :1000C000E3020008E3020008E3020008E30200087C -:1000D000E3020008E30200081181000825810008FE -:1000E00089800008E3020008E3020008E302000838 -:1000F000E3020008E3020008E3020008E30200084C -:10010000E3020008FD8000084D810008E3020008BA +:1000D000E3020008E3020008C5870008D98700088A +:1000E0003D870008E3020008E3020008E30200087D +:1000F000E3020008E3020008E302000835470008B5 +:10010000E3020008B187000801880008E302000844 :10011000E3020008E3020008E3020008E30200082B -:10012000E3020008E3020008E3020008E30200081B -:10013000E3020008E3020008E3020008E30200080B +:100120006147000889470008B5470008E147000813 +:100130000D480008E3020008E3020008E30200089B :10014000E3020008E3020008E3020008E3020008FB -:10015000E3020008E3020008E3020008E3020008EB +:1001500035480008614800088D480008E30200089F :10016000E3020008E3020008E3020008E3020008DB -:10017000E3020008317C0008E3020008E302000803 -:10018000E3020008E302000839810008E3020008E6 +:10017000E3020008DD820008E3020008E302000851 +:10018000E3020008E3020008ED870008E30200082C :10019000E3020008E3020008E3020008E3020008AB :1001A000E3020008E3020008E3020008E30200089B :1001B000E3020008E3020008E3020008E30200088B :1001C000E3020008E3020008E3020008E30200087B -:1001D000E30200081D7C0008E3020008E3020008B7 +:1001D000E3020008C9820008E3020008E302000805 :1001E000E3020008E3020008E3020008E30200085B :1001F000E3020008E3020008E3020008E30200084B :10020000E3020008E3020008E3020008E30200083A @@ -51,22 +51,22 @@ :100310004F8FBFF36F8F40F20000C0F2F0004EF637 :100320008851CEF200010860BFF34F8FBFF36F8F8B :100330004FF00000E1EE100A4EF63C71CEF20001E3 -:100340000860062080F31488BFF36F8F06F0DCFE90 -:1003500006F0ECF84FF055301F491B4A91423CBF64 +:100340000860062080F31488BFF36F8F07F032FA3D +:1003500006F0A4FB4FF055301F491B4A91423CBFA9 :1003600041F8040BFAE71D49184A91423CBF41F895 :10037000040BFAE71A491B4A1B4B9A423EBF51F83D :10038000040B42F8040BF8E700201849184A914280 -:100390003CBF41F8040BFAE706F0F4FE06F04AF918 +:100390003CBF41F8040BFAE707F04AFA06F002FC0A :1003A000144C154DAC4203DA54F8041B8847F9E7A6 :1003B00000F0C4F9114C124DAC4203DA54F8041B9E -:1003C0008847F9E706F0DCBE000600200022002086 +:1003C0008847F9E707F032BA000600200022002033 :1003D0000000000808ED00E00000002000060020FA -:1003E000B896000800220020D8220020D822002041 -:1003F00020670020E0020008E0020008E002000898 +:1003E000989C00080022002074220020782200201F +:1003F00034670020E0020008E0020008E002000884 :10040000E00200082DE9F04F2DED108AC1F80CD064 :10041000D0F80CD0BDEC108ABDE8F08F002383F338 -:1004200011882846A047002005F072FEFEE705F07F -:10043000B1FD00DFFEE7000053B94AB9002908BF4B +:1004200011882846A047002006F01AF9FEE706F0DA +:1004300073F800DFFEE7000053B94AB9002908BF8E :1004400000281CBF4FF0FF314FF0FF3000F074B9AF :10045000ADF1080C6DE904CE00F006F8DDF804E01B :10046000DDE9022304B070472DE9F047089D0446FA @@ -114,29 +114,29 @@ :100700000646E3E61846F8E64B45A9D2B9EB0208DF :1007100064EB0C0E0138A3E74646EAE7204694E76F :100720004046D1E7D0467BE7023B614432E73046A2 -:1007300009E76444023842E7704700BF38B500F06B -:10074000DDFB06F0EFFB054606F0D4FC0446E0B9FD -:10075000104B9D421BD001339D4241F2883504BFAE -:1007600001240025002006F0E7FB0CB100F07AF828 -:1007700001F03AFB01F0F6F900F028FD08B100F0B5 -:1007800071F8284600F01CF9F9E70025EAE705466C -:10079000E8E700BF010007B008B501F0AFF9A0F12C +:1007300009E76444023842E7704700BF38B501F06A +:10074000FFF901F0AFFB06F0C1FE054606F0C6FF5B +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F0B9FE0CB135 +:1007700000F078F801F036FB00F026FD08B100F03B +:1007800071F8284600F01CF9F9E70025ECE705466A +:10079000EAE700BF010007B008B501F09DF9A0F13C :1007A00020035842584108BD07B541F21203022107 -:1007B00001A8ADF8043001F0BFF903B05DF804FB07 -:1007C00038B5302383F31188174803680BB105F05F -:1007D00083FD0023154A4FF47A71134805F072FD2A +:1007B00001A8ADF8043001F0ADF903B05DF804FB19 +:1007C00038B5302383F31188174803680BB106F05E +:1007D0002BF80023154A4FF47A71134806F01AF8E3 :1007E000002383F31188124C236813B12368013B63 :1007F0002360636813B16368013B63600D4D2B7820 -:1008000033B963687BB9022001F068FA3223636070 -:100810002B78032B07D163682BB9022001F05EFA15 -:100820004FF47A73636038BDD8220020C1070008F6 -:10083000F8230020F0220020084B187003280CD861 -:10084000DFE800F008050208022001F03DBA0220AE -:1008500001F030BA024B00225A607047F0220020AB -:10086000F8230020F8B5504B504A1C461968013156 +:1008000033B963687BB9022001F056FA3223636082 +:100810002B78032B07D163682BB9022001F04CFA27 +:100820004FF47A73636038BD78220020C107000856 +:100830009823002090220020084B187003280CD821 +:10084000DFE800F008050208022001F02BBA0220C0 +:1008500001F01EBA024B00225A607047902200201D +:1008600098230020F8B5504B504A1C4619680131B6 :1008700000F0998004339342F8D162684C4B9A425D :1008800040F291804B4B9B6803F1006303F500330A -:100890009A4280F08880002001F07EF90220FFF764 +:100890009A4280F08880002001F06CF90220FFF776 :1008A000CBFF454B0021D3F8E820C3F8E810D3F87C :1008B0001021C3F81011D3F81021D3F8EC20C3F89D :1008C000EC10D3F81421C3F81411D3F81421D3F881 @@ -156,15 +156,15 @@ :1009A00080F308882047F8BD0000020820000208F4 :1009B000FFFF0108002200200044025800ED00E083 :1009C0002DE9F04F93B0B44B2022FF2100900AA8EC -:1009D0009D6801F0B3F9B14A1378A3B90121B04879 +:1009D0009D6801F0B1F9B14A1378A3B90121B0487B :1009E00011700360302383F3118803680BB105F0A5 -:1009F00073FC0023AB4A4FF47A71A94805F062FCFE +:1009F0001BFF0023AB4A4FF47A71A94805F00AFFA8 :100A0000002383F31188009B13B1A74B009A1A604F :100A1000A64A1378032B03D000231370A24A536015 :100A20004FF0000A009CD3465646D146012001F003 -:100A30004BF924B19C4B1B68002B00F02682002050 -:100A400001F05CF80390039B002BF2DB012001F026 -:100A500031F9039B213B1F2BE8D801A252F823F068 +:100A300039F924B19C4B1B68002B00F02682002062 +:100A400001F04AF80390039B002BF2DB012001F038 +:100A50001FF9039B213B1F2BE8D801A252F823F07A :100A6000E10A0008090B00089D0B00082D0A000888 :100A70002D0A00082D0A00082F0C0008FF0D0008A1 :100A8000190D00087B0D0008A30D0008C90D000812 @@ -175,2253 +175,2341 @@ :100AD0002D0A00082D0A00082D0A00089D0B0008A9 :100AE0000220FFF759FE002840F0F981009B022107 :100AF00005A8BAF1000F08BF1C4641F21233ADF849 -:100B0000143001F019F891E74FF47A7000F0F6FF15 +:100B0000143001F007F891E74FF47A7000F0E4FF39 :100B1000071EEBDB0220FFF73FFE0028E6D0013F77 :100B2000052F00F2DE81DFE807F0030A0D1013360F -:100B30000523042105A8059300F0FEFF17E004211A +:100B30000523042105A8059300F0ECFF17E004212C :100B40005548F9E704215A48F6E704215948F3E7E4 -:100B50004FF01C08404608F1040801F01FF804217A -:100B6000059005A800F0E8FFB8F12C0FF2D10120A4 +:100B50004FF01C08404608F1040801F00DF804218C +:100B6000059005A800F0D6FFB8F12C0FF2D10120B6 :100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F -:100B800001F028F926B10BF00B030B2B08BF002452 +:100B800001F026F926B10BF00B030B2B08BF002454 :100B9000FFF70AFE4AE704214748CDE7002EA5D01B :100BA0000BF00B030B2BA1D10220FFF7F5FD07463D -:100BB00000289BD00120002600F0EEFF0220FFF766 -:100BC0003BFE1FFA86F8404600F0F6FF0446B0B13F +:100BB00000289BD00120002600F0DCFF0220FFF778 +:100BC0003BFE1FFA86F8404600F0E4FF0446B0B151 :100BD000039940460136A1F140025142514100F0D3 -:100BE000FBFF0028EDD1BA46044641F21213022160 -:100BF00005A83E46ADF8143000F09EFF16E72546E6 +:100BE000E9FF0028EDD1BA46044641F21213022172 +:100BF00005A83E46ADF8143000F08CFF16E72546F8 :100C00000120FFF719FE244B9B68AB4207D9284609 -:100C100000F0C4FF013040F067810435F3E70025A0 +:100C100000F0B2FF013040F067810435F3E70025B2 :100C2000224BBA463E461D701F4B5D60A8E7002E62 :100C30003FF45CAF0BF00B030B2B7FF457AF02209C -:100C4000FFF7FAFD322000F059FFB0F10008FFF67F +:100C4000FFF7FAFD322000F047FFB0F10008FFF691 :100C50004DAF18F003077FF449AF0F4A08EB0503C7 :100C6000926893423FF642AFB8F5807F3FF73EAFC0 -:100C7000124BB845019323DD4FF47A7000F03EFF2C +:100C7000124BB845019323DD4FF47A7000F02CFF3E :100C80000390039A002AFFF631AF039A0137019BC4 -:100C900003F8012BEDE700BF00220020F423002021 -:100CA000D8220020C1070008F8230020F0220020ED -:100CB00004220020082200200C220020F422002020 +:100C900003F8012BEDE700BF002200209423002081 +:100CA00078220020C107000898230020902200200D +:100CB00004220020082200200C2200209422002080 :100CC000C820FFF769FD074600283FF40FAF1F2D2E :100CD00011D8C5F120020AAB25F003008449424532 -:100CE000184428BF4246019201F002F8019AFF2100 -:100CF0007F4801F023F84FEAA803C8F387027C4934 -:100D00002846019301F022F8064600283FF46DAF13 +:100CE000184428BF4246019201F000F8019AFF2102 +:100CF0007F4801F021F84FEAA803C8F387027C4936 +:100D00002846019301F020F8064600283FF46DAF15 :100D1000019B05EB830533E70220FFF73DFD00282B -:100D20003FF4E4AE00F076FF00283FF4DFAE00278A +:100D20003FF4E4AE00F064FF00283FF4DFAE00279C :100D3000B846704B9B68BB4218D91F2F11D80A9B2D :100D400001330ED027F0030312AA134453F8203CBA -:100D500005934046042205A9043701F0A5F8804612 -:100D6000E7E7384600F01AFF0590F2E7CDF8148067 -:100D7000042105A800F0E0FE02E70023642104A896 -:100D8000049300F0CFFE00287FF4B0AE0220FFF7FE -:100D900003FD00283FF4AAAE049800F031FF05904F -:100DA000E6E70023642104A8049300F0BBFE0028BA +:100D500005934046042205A9043701F003F98046B3 +:100D6000E7E7384600F008FF0590F2E7CDF8148079 +:100D7000042105A800F0CEFE02E70023642104A8A8 +:100D8000049300F0BDFE00287FF4B0AE0220FFF710 +:100D900003FD00283FF4AAAE049800F01FFF059061 +:100DA000E6E70023642104A8049300F0A9FE0028CC :100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 -:100DC000049800F01FFFEAE70220FFF7E5FC002887 -:100DD0003FF48CAE00F02EFFE1E70220FFF7DCFCD1 -:100DE00000283FF483AE05A9142000F029FF074630 -:100DF0000421049004A800F09FFE3946B9E7322090 -:100E000000F07CFE071EFFF671AEBB077FF46EAEEE +:100DC000049800F00DFFEAE70220FFF7E5FC002899 +:100DD0003FF48CAE00F01CFFE1E70220FFF7DCFCE3 +:100DE00000283FF483AE05A9142000F017FF074642 +:100DF0000421049004A800F08DFE3946B9E73220A2 +:100E000000F06AFE071EFFF671AEBB077FF46EAE00 :100E1000384A07EB0903926893423FF667AE022017 :100E2000FFF7BAFC00283FF461AE27F003074F44F8 -:100E3000B9453FF4A5AE484609F1040900F0AEFEFD -:100E40000421059005A800F077FEF1E74FF47A70D1 -:100E5000FFF7A2FC00283FF449AE00F0DBFE0028BB +:100E3000B9453FF4A5AE484609F1040900F09CFE0F +:100E40000421059005A800F065FEF1E74FF47A70E3 +:100E5000FFF7A2FC00283FF449AE00F0C9FE0028CD :100E600044D00A9B01330BD008220AA9002000F0CD -:100E70006DFF00283AD02022FF210AA800F05EFF73 -:100E8000FFF792FC1C4805F049F913B0BDE8F08F5C +:100E70006BFF00283AD02022FF210AA800F05CFF77 +:100E8000FFF792FC1C4805F0F1FB13B0BDE8F08FB2 :100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 -:100EA0000023642105A8059300F03CFE07460028B6 +:100EA0000023642105A8059300F02AFE07460028C8 :100EB0007FF41CAE0220FFF76FFC804600283FF451 -:100EC00015AEFFF771FC41F2883005F027F905985F -:100ED00000F0C8FF46463C4600F07CFFA6E506460B +:100EC00015AEFFF771FC41F2883005F0CFFB0598B5 +:100ED00000F0C6FF46463C4600F07AFFA6E506460F :100EE0004EE64FF0000901E6BA467EE637467CE65C -:100EF000F422002000220020A0860100704700009C -:100F00007047000070470000704700002DE9F04175 -:100F100000F58037044616463B7C5BB9C06810304C -:100F2000204400F0E5FEE5683544B5F5004FE56086 -:100F300002D816B1BDE8F081DEB905F07F0605F1F3 -:100F400010000021C6F180062044F6B232462E443D -:100F500000F0F4FEA06804F11008324600F10060D1 -:100F6000414600F5003005F0A5FD30B901233B7482 -:100F7000E0E74FF400463546ECE7A26805F11001C2 -:100F8000404632442144A260E268521BE26000F015 -:100F9000AFFE0220BDE8F04100F0A0BE183000F026 -:100FA000E9BC000010B5044607F028FE204610BD3D -:100FB00010B5044607F022FE204610BDC3B280B231 -:100FC000A3F14102052A02D8373800B27047613BCD -:100FD000052B94BF57383038F7E70000F8B50446C2 -:100FE0001546084603220C4900F08CFE014688B9DC -:100FF00008346F1C15F91100FFF7E0FF064617F9DA -:1010000011000131FFF7DAFF102940EA061004F859 -:10101000010BEFD1F8BD00BF748D00082DE9F04F32 -:10102000ADF53F7D0746416801222AA802F030FE57 -:10103000002840F087800646824681461125DFF869 -:101040000C81DFF80CB101AB4FF4805241462AA865 -:1010500002F07EFF002875D1019AB2F5805F71D849 -:10106000002A65D00446019A9442ECD2282D0FD074 -:1010700008DC132D2DD01E2D39D0112D13D00134A5 -:10108000A4B2F0E7322D2DD0372D2FD02D2DF6D153 -:101090003B68121B08EB040138461B692D25984755 -:1010A000BDF80440EBE7121B022A09D9594608EBA8 -:1010B000040000F027FE18B902342825A4B2DEE7A8 -:1010C00018F804303A2B3DD00A2B1CBFA14613253B -:1010D000D5E718F804300A2B34D03A2B04BFA246C7 -:1010E0003225CCE718F80430202BC8D0264618F853 -:1010F00004300A2B1AD1AAEB090208EB090102A855 -:1011000011254F2A28BF4F2207F020FEA21B08EB13 -:10111000060116A84F2A28BF4F2207F017FE3B688A -:1011200016AA02A9DB6838469847A8E71E25A6E755 -:101130003B68384604491B69984701200DF53F7DFF -:10114000BDE8F08F0020F9E7768E0008002400202B -:10115000788D000800F1180110B5044686B00846E5 -:10116000019100F0F1FB2046FFF758FF60B10199B3 -:1011700002A800F049FC102204F1080102A807F0BF -:1011800061FDB0FA80F0400906B010BD70B50446AC -:101190000025EEB2304600F00FFD58B10021304678 -:1011A000013500F019FD08B9002070BD022000F0E3 -:1011B00095FDEEE72046FFF731FF0028F4D004F557 -:1011C0008034207C80F00100EFE70000F0B5C9B06A -:1011D00005F0C0FE00F096FE18B90025284649B07B -:1011E000F0BD69462A4802F075FF00284BD1294C12 -:1011F000204602F09FFF284802F09CFF274802F09B -:1012000099FF2146224803F011F80028E5D170200B -:1012100007F0F6FC064610B1214B446003603368CA -:1012200030469B689847054600282ED01A4F19482B -:10123000394602F0FBFF05460028CED1194807F0D9 -:10124000DFFC044638B1184B4760036000F580337B -:10125000C0E902551D74236820469B6898470546DF -:1012600028B10E490C4802F0E1FF0028B5D13368DF -:1012700030465B6898471CB1236820465B689847F6 -:1012800000F028FEAAE70025FAE70446EFE700BFD2 -:101290007C8D00088C8D0008A38D0008B98D000896 -:1012A000DC8D000814000100F88D00082DE9F04FD6 -:1012B000D44A8DB00B68D0F804A001931A44036897 -:1012C000D14E1A44D1F81C90DFF8B4C3DFF8B4B3A0 -:1012D000D0E90234634003EA0A03634013444A68D6 -:1012E00002920AEB7363029CC84A2244C4682244F7 -:1012F00084688AEA04051D40654015448A680392A3 -:1013000003EB3555039CC24A2244846822448AEA8E -:1013100003042C4084EA0A041444CA6805EBF4343C -:101320000492164483EA0502224056445A4032444D -:101330000E69059604EBB222059FB64E3E441E444C -:1013400085EA040313406B4033444E69069602EB72 -:101350007363069FB04E3E442E4484EA02051D404E -:10136000654035448E69079603EB3555079FAB4EB4 -:101370003E44264482EA03042C4054403444A84EA0 -:101380004E4405EBF434164483EA050222405A40E9 -:1013900032440E6A089604EBB222089FA14E3E44E6 -:1013A0001E4485EA040313406B4033444E6A099699 -:1013B00002EB7363099F9C4ED1F830E03E44D1F8B4 -:1013C0003880F3442E4484EA02051D4065403544CC -:1013D0008E6AA6F5244703EB35550A964F3F2744FE -:1013E00082EA03042C4054403C44CF6A0B9705EB3F -:1013F000F4340B9E8D4F3744029E174483EA050256 -:1014000022405A403A448A4F774404EBB2221F44A8 -:1014100085EA040313406B403B444F6BBC4402EB32 -:101420007363654484EA020C0CEA030C8CEA040C36 -:101430006544DFF854C2C44403EB3555A44482EA42 -:1014400003042C4054406444D1F83CC0794905EB76 -:10145000F4346144114483EA050222405A400A44AC -:10146000754904EBB2223144079E194484EA020311 -:101470002B4063400B44714902EBF36331440B9EF4 -:101480000D4482EA03012140514029446C4D03EB95 -:10149000F1513544019E254483EA010414405C4027 -:1014A0002C44684D01EBB4443544069E154481EA52 -:1014B00004021A404A402A44634D04EB3232354458 -:1014C0000A9E1D4484EA02030B4063402B445F4D97 -:1014D00002EBF3633544059E0D4482EA030121408B -:1014E000514029445A4D03EBF1516544254483EAA8 -:1014F000010414405C402C44564D01EBB444354487 -:10150000099E154481EA04021A404A402A44524D79 -:1015100004EB32323544049E1D4484EA02030B403E -:1015200063402B444D4D02EBF36345440D4482EA86 -:101530000301214051402944494D03EBF151354409 -:10154000089E2C4483EA010515405D402C44454D1E -:1015500001EBB4443544039E2A4481EA04051D404E -:101560004D402A44404D04EB32323D442B4484EA42 -:10157000020593440D4065402B443C4D02EBF36360 -:101580003544069E294482EA0305254055402944F6 -:10159000374D03EBF1514D442C4483EA01051540CE -:1015A0005D40254401EBB54581EA050404EA0302E8 -:1015B0004A405A44A6F5B82B089E05EB3232ABF2EE -:1015C000BE6B54405B4423442A4C344402EB3373D7 -:1015D0000B9E0C4485EA020159402144264C3444B8 -:1015E00003EB7151029E254482EA03044C402544DA -:1015F000224C444401EB3545144483EA01026A401D -:10160000224443E078A46AD7EECEBDC156B7C7E8FE -:10161000DB702024AF0F7CF52AC68747134630A81D -:10162000019546FDD8988069AFF7448BBED75C8999 -:101630002211906B2108B44962251EF640B340C0C8 -:10164000515A5E26AAC7B6E95D102FD6531444023C -:1016500081E6A1D8C8FBD3E7E6CDE121D60737C3A1 -:10166000870DD5F4ED145A4505E9E3A9F8A3EFFC7D -:10167000D9026F6781F6718722619D6D0C38E5FD97 -:10168000937198FD8A4C2A8D8E4379A6934C3444ED -:1016900005EB7222059E1C4481EA05035340234456 -:1016A0008F4C344402EB33730A9E0C4485EA0201EA -:1016B000594021448B4C4C4403EB7151254482EA40 -:1016C00003044C402C44884D354401EB3444019EC6 -:1016D000154483EA010262402A44844D3D4404EBF0 -:1016E00072221D4481EA040353402B44804D35444B -:1016F00002EB3373049E294484EA02055D402944C9 -:101700007C4D354403EB7151079E254482EA030466 -:101710004C402C44784D354401EB3444099E2A4416 -:1017200083EA010565401544744A324404EB75258B -:10173000039E134481EA04026A401A44704B7344C6 -:1017400005EB32720B4484EA0501514019446D4B9C -:10175000634402EB71511C4485EA02034B401C4474 -:10176000694B334401EB3444019E1D4482EA01037A -:1017700063402B44654D04EB73233544069E1544AA -:1017800063EA010262402A44614D03EBB2624D44B8 -:1017900062EA040929445F4D89EA03094544494442 -:1017A0002C445D4D02EBB1513544049E61EA0308BF -:1017B0001D4488EA0208444401EB744464EA0203CD -:1017C0004B402B44554D04EBF323754463EA010E63 -:1017D00015448EEA040E0EEB0502514D03EBB26286 -:1017E000354462EA040E29440A9D8EEA030EA5F5EB -:1017F00080164C4D7144A6F6833602EBB151264457 -:1018000061EA030454403444029E01EB74443544BD -:1018100064EA02061D444E407319089E424D04EBD3 -:10182000F323354463EA01061544664072193F4DBF -:1018300003EBB262654462EA040629443C4D5E4013 -:101840003144079E02EBB151354461EA03062C4452 -:10185000384D56403D443444059E1D4401EB7444CC -:1018600064EA02034B402B44334D04EBF32335442D -:101870000B9E154463EA010262402A442F4D03EB9C -:10188000B2623544039E0D4462EA04015940294482 -:101890002B4D02EBB15135442A4E254461EA030435 -:1018A00054402C44099D01EB74442E4464EA020523 -:1018B0001E4485EA01039D1903681A440AEB0403D8 -:1018C00003EBF5230260436083681C44C36819443A -:1018D0008460C1600DB0BDE8F08F00BF44EABEA4D3 -:1018E000A9CFDE4B604BBBF670BCBFBEC67E9B284B -:1018F000FA27A1EA8530EFD4051D880439D0D4D960 -:10190000E599DBE6F87CA21F6556ACC4442229F4B5 -:1019100097FF2A43A72394AB39A093FCC3595B6577 -:1019200092CC0C8FD15D84854F7EA86FE0E62CFEB3 -:10193000144301A3A111084E827E53F735F23ABD3C -:10194000BBD2D72A91D386EB094B036003F18833CE -:10195000436003F12943A3F59613A3F68B638360D9 -:10196000A3F18833C3600023C0E90433704700BF8C -:10197000012345672DE9F8431446026905460E46E2 -:10198000E300C2F3C50800F118079B18036122BFEA -:1019900043690133436112F4FC7F436903EB5473E1 -:1019A000436114D0C8F1400907EB08004C4504D24C -:1019B0002246BDE8F84307F055B9403C4A464E443C -:1019C00007F050F9444439462846FFF76FFCA0461B -:1019D00006EB0409B8F13F0FA9EB08010AD9402230 -:1019E000384607F03FF939462846A8F14008FFF786 -:1019F0005DFCEFE7A1096FF03F02384602FB0142B0 -:101A000006EB8111D5E7000070B50B6901F11805EF -:101A100006460C46C3F3C503EA18501C8022EA545C -:101A2000C3F13F02072A1FD8002100F087F9294699 -:101A30002046FFF73BFC38220021284600F07EF9C3 -:101A4000236929462046236563696365FFF72EFCF9 -:101A500021461022304607F005F920465822002181 -:101A6000BDE8704000F06AB9C3F137020021E5E734 -:101A70002DE9F84F4FF47A7306460D46002402FB19 -:101A800003F7DFF85080DFF8509098F900305FFAE4 -:101A900084FA5A1C01D0A34210D159F824002A46D6 -:101AA00031460368D3F820B03B46D847854205D17C -:101AB000074B012083F800A0BDE8F88F0134042C07 -:101AC000E3D14FF4FA7004F029FB0020F4E700BFE3 -:101AD00044340020102200201422002070B5044657 -:101AE0004FF47A76412C254628BF412506FB05F0A8 -:101AF00004F014FB641BF5D170BD0000002307B592 -:101B0000024601210DF107008DF80730FFF7B0FF05 -:101B100020B19DF8070003B05DF804FB4FF0FF30E3 -:101B2000F9E700000A46042108B5FFF7A1FF80F09D -:101B30000100C0B2404208BD074B0A4630B41978D4 -:101B4000064B53F82140014623682046DD69044BCB -:101B5000AC4630BC604700BF443400201422002053 -:101B6000A086010070B50A4E00240A4D04F046FF1D -:101B7000308028683388834208D904F03BFF2B6803 -:101B800004440133B4F5003F2B60F2D370BD00BFB5 -:101B9000463400200034002004F0FEBF00F1006055 -:101BA00000F500300068704700F10060920000F519 -:101BB000003004F07FBF0000054B1A68054B1B88FE -:101BC0009B1A834202D9104404F014BF00207047CE -:101BD000003400204634002038B50446074D29B1B2 -:101BE00028682044BDE8384004F01CBF2868204421 -:101BF00004F006FF0028F3D038BD00BF00340020F9 -:101C00000020704700F1FF5000F58F10D0F8000859 -:101C100070470000064991F8243033B100230822B0 -:101C2000086A81F82430FFF7BFBF0120704700BF6A -:101C300004340020014B1868704700BF0010005C9E -:101C4000194B01380322084470B51D68174BC5F3C2 -:101C50000B042D0C1E88A6420BD15C680A46013C81 -:101C6000824213460FD214F9016F4EB102F8016B94 -:101C7000F6E7013A03F10803ECD181420B4602D2A8 -:101C80002C2203F8012B0424094A1688AE4204D101 -:101C9000984284BF967803F8016B013C02F104027C -:101CA000F3D1581A70BD00BF0010005C2422002040 -:101CB000388E0008022803D1024B4FF080529A61FF -:101CC000704700BF00100258022803D1024B4FF4A6 -:101CD00080529A61704700BF00100258022804D158 -:101CE000024A536983F480535361704700100258CD -:101CF000002310B5934203D0CC5CC4540133F9E700 -:101D000010BD0000013810B510F9013F3BB191F949 -:101D100000409C4203D11AB10131013AF4E71AB1F3 -:101D200091F90020981A10BD1046FCE703460246C0 -:101D3000D01A12F9011B0029FAD170470244034658 -:101D4000934202D003F8011BFAE770472DE9F843EC -:101D50001F4D14460746884695F8242052BBDFF8ED -:101D600070909CB395F824302BB92022FF2148466F -:101D70002F62FFF7E3FF95F824004146C0F1080207 -:101D800005EB8000A24228BF2246D6B29200FFF7A0 -:101D9000AFFF95F82430A41B17441E449044E4B2CE -:101DA000F6B2082E85F82460DBD1FFF733FF002858 -:101DB000D7D108E02B6A03EB82038342CFD0FFF731 -:101DC00029FF0028CBD10020BDE8F8830120FBE7E4 -:101DD00004340020024B1A78024B1A70704700BF7F -:101DE0004434002010220020F8B5194C194803F0A3 -:101DF00083FC2146174803F0ABFC24684FF47A704B -:101E0000154ED4F89020154DD2F80438114F43F0F8 -:101E10000203C2F80438FFF761FE2046104903F0C0 -:101E2000A5FDD4F890200424D2F8043823F002034E -:101E3000C2F804384FF4E133336055F8040BB8426C -:101E400002D0314603F0B6FB013CF6D1F8BD00BF2D -:101E500038950008F04800202C340020142200207F -:101E6000409500080C4B70B50C4D04461E780C4B89 -:101E700055F826209A420DD00A4B00211822184608 -:101E8000FFF75CFF0460014655F82600BDE870408E -:101E900003F090BB70BD00BF44340020142200202A -:101EA000F04800202C34002030B50A44084D9142FF -:101EB0000DD011F8013B5840082340F30004013BCA -:101EC0002C4013F0FF0384EA5000F6D1EFE730BD59 -:101ED0002083B8ED10B5084C01220849002001F01C -:101EE000B3FE23783BB1064803F0DCFA044803F064 -:101EF0000FFB0023237010BD48340020488E0008DB -:101F0000A43600201D482DE9F041036D2BB90122B4 -:101F10004FF48051503005F05FF8194E33780BB113 -:101F2000FFF7D8FF0324174F4FF00008134D154952 -:101F30002846C7F8048003F0DDFA284603F016F9B6 -:101F400048B1013C284603F0E3FA14F0FF04EED157 -:101F5000204634700FE00C4901220C4801F074FE59 -:101F6000014618B1284603F09DFAEAE7084800F058 -:101F700011F801203070BDE8F08100BFA4360020C8 -:101F8000483400203C220020488E00084C340020B9 -:101F90004C8E00080FB4002004B0704700687047F2 -:101FA00003460068596870470B0A017043700B0CB8 -:101FB000090E8370C1707047110A0270037141707D -:101FC000110C120E8170C2701A0A42711A0C1B0E8B -:101FD0008271C37170470000C36A0239023B8B42B1 -:101FE00083BF4389006C01FB0300002070470000A1 -:101FF000C2F307238A76CB760378032B01BF120C3A -:102000000A75120A4A75704700F10B010022D301CC -:1020100043EA520310F8012B52FA83F38842DAB2F2 -:10202000F5D110467047000010B5417804460020F5 -:10203000013102464901022A16BFA35C032203EBC9 -:10204000C03302F101021EBF9BB203EB500398B2F2 -:102050009142F0D810BD000002684AB1134613F84F -:10206000011B1F290DD93A29F9D1911C8B4202D0AD -:102070004FF0FF3070471278302AF9D1036000200A -:102080007047014B187870479836002038B50D46D8 -:10209000044618B9092000232B6038BD0368002BC3 -:1020A000F8D01A78002AF5D08188DA889142F1D1E7 -:1020B000587804F0BFF910F00100EBD12368EBE78A -:1020C00038B50D4640F25231144602F0B9F9FF28F6 -:1020D00007D9012C0BD9030A022468702B70204603 -:1020E00038BD30B1002CFAD001242870F7E7002465 -:1020F000F5E70446F3E700002DE9F8430026D0F8A1 -:10210000008005460C468E76836B002B4AD098F8EB -:102110000030042B4BD133463546402720E0B7F53D -:10212000187F80F0C480F90606F1010608BF023767 -:10213000D05B02372BB900F5205292B2B2F5006F96 -:102140000DD305F11A01C5F1FF0240EA0340214415 -:10215000FFF7B6FF002800F0AA80054400200346E0 -:10216000D8F8102092F82310B142D8D8002B40F0B4 -:102170009E80002D00F09B8000232544AB76637386 -:10218000D8F81020137903F03701DB0621730BD444 -:1021900002F13800FFF704FFC4E90001938963816D -:1021A000D3892381BDE8F88300200146F4E7C36C9E -:1021B00001335ED1EA6B00232E26551E184615F812 -:1021C000011F013020290CD0052908BFE52109286D -:1021D00004D10B2B9EBFE71801337E73E718013340 -:1021E00079730B28EBD1E11800204873A17E0029F8 -:1021F0004BD1002B40D06FF00C0604F10D000825E8 -:10220000361B331810F8011B002938D02E298BB249 -:102210004AD0A3F14101192903D8117B0D4200D006 -:1022200020330373EDE7B9F1000F05D100F520531A -:102230009BB2B3F5006F0BD307F11A01C7F1FF0290 -:1022400040EA09402144FFF73BFF48B10744002022 -:1022500002368146D8F80C30985B0028E3D1384626 -:10226000B9F1000F4FF0000218BF002023189A7632 -:10227000A0E7B1463746EDE73F23A3760123234489 -:1022800000219976137B03B96373D37A02F11C00A2 -:1022900003F03F0323730023FFF780FE2060636099 -:1022A000D38A6381138B7CE710250B46B9E73F2364 -:1022B0000125A37660E7000038B50546002435F80F -:1022C000020B08B9204638BD02F0EEF86308C2B22E -:1022D00003EBC43312FA83F39AB2C0F3072303EB80 -:1022E000520303EBC2339CB2E9E7000037B5C37871 -:1022F00004461BB90025284603B030BD00F14C014F -:10230000826C01234078019104F0BAF8054680B947 -:10231000A36BE070A06C226BC31A9342EAD2A3783D -:102320000199022BE6D102440123607804F0A8F859 -:10233000E1E70125DFE7000038B5836C05460C4670 -:102340008B4210D0FFF7D2FF60B92246012305F17E -:102350004C01687804F070F800281CBF4FF0FF347F -:102360000120AC6438BD0020FCE7000038B5002334 -:102370000446C3704FF0FF338364FFF7DDFF00288E -:102380004BD1B4F84A524AF655239D4207D10B224D -:10239000254904F14C0006F055FC00283FD094F884 -:1023A0004C30EB2B03D01833DBB2012B2ED84AF67E -:1023B00055239D4206D108221C4904F19E0006F0D7 -:1023C00041FC48B3B4F85730B3F5007F1ED194F800 -:1023D0005930DBB15A1E1A4218D1B4F85A30ABB199 -:1023E00094F85C30013B012B10D8B4F85D306BB130 -:1023F000B4F85F307F2B06D804F16C00FFF7CEFDF8 -:10240000B0F5803F02D3B4F8623053B94AF6552094 -:1024100085420CBF0220032038BD0420FCE70120C8 -:10242000FAE70020F8E700BF788E0008848E0008E5 -:1024300002392DE9F04701F007044FF0010A466C1C -:1024400005460AFA04F41746984606EB1136C1F31E -:10245000C809E4B2314628460136FFF76DFF18B1CE -:102460000120BDE8F087994605EB090292F84C304F -:10247000234214BF01210021414513D06340013F95 -:1024800082F84C3085F803A0EBD0640014F0FF0410 -:10249000EAD109F1010301244FF00009B3F5007FEF -:1024A000E1D1D7E70220DCE701290246F8B50C4666 -:1024B00040F28C800668F36A8B4240F28780337862 -:1024C000013B032B00F28280DFE803F00229384B46 -:1024D00004EB5405B16B304601EB5521FFF72CFF9F -:1024E00010B14FF0FF30F8BD6F1CC5F30805B16B9C -:1024F0003046354401EB572195F84C50FFF71CFF4F -:102500000028EED1C7F30807E3073E4496F84C00D5 -:1025100045EA00204CBF0009C0F30B00E3E7B16BB4 -:10252000304601EB1421FFF707FF0028D9D16400E2 -:1025300004F4FF742644B6F84C00D4E7B16B30467F -:1025400001EBD411FFF7F8FE0028CAD1A40006F170 -:102550004C0004F4FE742044FFF720FD20F070408E -:10256000C1E7D0E90430D57953EA000101D0916880 -:1025700001B95DBB9168022DA4EB01010DD1013BB6 -:10258000728940F1FF305B0A43EAC053B3FBF2F3B8 -:1025900099421BD81CD0601CA5E7032D02D193697A -:1025A0008B42F8D8D3699BB9B16B304601EBD4119B -:1025B000FFF7C2FE002894D1A0004C3600F4FE7054 -:1025C0003044FFF7EBFC20F000408CE701208AE765 -:1025D0006FF0004087E70000F8B5066804460D4636 -:1025E0003378042B0CBF4FF080524FF400128A4214 -:1025F00001D80220F8BDCA06FBD182680163D2B9B6 -:10260000022B13D83389B3EB551FF2D9F36BA363B5 -:10261000A36B6263002BECD003EB55234C36C5F360 -:1026200008050020A3633544E563E3E7F36BC2715B -:10263000002BE7D01A4677897F02BD42114604D2AB -:102640003046FFF7C9FCA063E2E72046FFF72CFF06 -:10265000431C024606D00128CBD9F36A8342C8D96D -:10266000ED1BEAE70120C5E701292DE9F047064601 -:102670000C46174608D9C36A8B4205D90378022B4A -:1026800062D003D8012B22D0022552E0033B012B5C -:10269000FAD8816B01EBD411FFF74EFE05460028F6 -:1026A00047D1A40006F14C0304F4FE741C443378B3 -:1026B000042B07D0204627F07047FFF76FFC00F08F -:1026C0007040074339462046FFF76EFC2FE001EBD0 -:1026D0005108816B01EB5821FFF72EFE054640BBE8 -:1026E00014F0010406F14C0908F1010AC8F30808C6 -:1026F00008BFFBB230461FBF19F8083003F00F02C5 -:102700003B0103F0F00318BF134309F8083001231D -:10271000B16BF37001EB5A21FFF70EFE054640B98D -:10272000CAF3080A44B1C7F3071709F80A7001236E -:10273000F3702846BDE8F08719F80A30C7F303277D -:1027400023F00F031F43F0E7816B01EB1421FFF728 -:10275000F3FD05460028ECD1640006F14C0304F4B7 -:10276000FF741F551919C7F307274F70DFE70000E3 -:10277000F8B504460E461746E3690BB91846F8BD8E -:10278000012BA6EB0305206814BFAA1C3A46691C5E -:10279000FFF76AFF0028F2D1E369013BE361EBE751 -:1027A00001292DE9F84306460C461746056802D86C -:1027B0000220BDE8F883EB6A8B42F9D97AB9A146C9 -:1027C00021463046A046FFF76FFE0446B0B92B788D -:1027D000042B02D1002F43D1F7710020E9E72B78B9 -:1027E000042B02D1C379022BE9D04FF0FF323946D6 -:1027F0002846FFF739FF0028E1D0DAE70128D7D0D3 -:10280000421C01D10120D4E72B78042B19D1EA6AAC -:10281000AB69023A93421CD308F10102A2420CD0E8 -:102820002B78042B08D10023A2EB09024946284645 -:10283000FFF7FEFD0028BCD1A146EB6AA342BFD83A -:10284000C5E7002241462846FFF70EFF0028DED0EC -:10285000AFE70133AB612B7943F001032B71DBE769 -:10286000F3798BB9B468BC4202D10223F371B4E7A7 -:1028700021463046FFF718FE012899D9431CC1D0E4 -:1028800001348442EFD0A8E7032BA6D1B368BB4242 -:10289000A3D8B2691344BB429FD3E6E770B5C379AE -:1028A0000446032B06D181688369CD18A94203D160 -:1028B0000023E371002070BD4E1C20683246FFF7F4 -:1028C000D3FE0028F7D13146F0E700002DE9F743A9 -:1028D00005460191FFF70AFD0446002849D105F19C -:1028E0004C09019928464FF40072FFF775FB214609 -:1028F000A86407464846FFF721FA6C896402B4F5DC -:10290000004F28BF4FF40044B4F5007F2FD9204674 -:1029100004F022FA804630B122460021640A0026E3 -:10292000FFF70CFA09E06408EEE72346BA194146BE -:10293000687803F0A5FD18B926446B899E42F4D34C -:10294000404604F019FA6889801B18BF012003B0C3 -:10295000BDE8F08301366B899E42F4D20123BA1997 -:102960004946687803F08CFD0028F3D0EBE7002699 -:10297000F1E70120EBE70000F8B50446FFF7B6FCED -:102980000546002842D12378032B37D12779012F20 -:1029900034D104F14C0601464FF400723046FFF783 -:1029A000CDF955234122722184F84A32AA2304F535 -:1029B0000D7084F84F2084F84B32522384F8301283 -:1029C00084F84C3084F84D30612384F8311284F857 -:1029D0004E3084F83332A16984F83222FFF7E4FAEA -:1029E000616904F50E70FFF7DFFA626B3B46314612 -:1029F00001326078A26403F043FD25710022607803 -:102A0000114603F061FD003818BF0120F8BD000039 -:102A100000232DE9F0430B6085B00F461546FFF704 -:102A20001BFB061EC0F2B281804B53F82640002CDF -:102A300000F0AE813C6005F0FE0523786BB1607854 -:102A400003F0F8FCC70708D41DB110F0040500D04E -:102A50000A25284605B0BDE8F0830023F0B22370B4 -:102A6000607003F0D3FCC10700F194810DB14207FF -:102A7000EED400212046FFF779FC022840F099802F -:102A80006E4604F2122304F25221324618461033E5 -:102A9000FFF784FA42F8040B8B42F7D1002556F871 -:102AA000041B00297DD02046FFF760FC012879D85F -:102AB0000128A26C40F0C08004F1570304F18C019E -:102AC00013F8015B002D7BD18B42F9D1B4F8B430FF -:102AD000B3F5807F74D194F8B830092B70D104F12C -:102AE0009400FFF75DFA4FF0FF33171841F1000132 -:102AF000BB4275EB010363D304F1A000FFF74EFA6C -:102B000094F8BA302063012BA37059D194F8B9908E -:102B100003FA09F91FFA89F36381002B50D0444B63 -:102B200004F1A800FFF73AFA0646984248D8831CF9 -:102B3000626304F1A400E362FFF730FA00EB0208DD -:102B400004F19C00C4F84080FFF728FA10441FFAF3 -:102B500089F2A06306FB02F313EB080345EB0502C1 -:102B60009F4271EB02032BD32E4604F1AC00FFF71A -:102B700015FAE06365B96389B34221D9E16B204658 -:102B8000FFF72AFA81192046FFF7D6FB98B90136DC -:102B9000631993F84C30812B14D02035C5F3080508 -:102BA000E8E703200135042D7FF479AF042807D12D -:102BB00001E0042801D101254BE701287FF678AF19 -:102BC0000D2546E705F1140004F14C063044FFF7EB -:102BD000E5F901280546F3D9E36A8342F0D9618912 -:102BE000821E236C02FB01336364A16B204601EB60 -:102BF000D511FFF7A1FB0028DDD105F07F0006EB22 -:102C00008000FFF7CBF9431C03D00135A842ECD07C -:102C1000D6E70425C4E90500064A25700025138877 -:102C2000E56101339BB21380E38012E79C360020FC -:102C3000FDFFFF7FA0360020B4F85730B3F5007FCA -:102C4000BED1B4F8626026B904F17000FFF7A6F9AE -:102C5000064694F85C302663591EA3700129AFD84C -:102C600094F859506581002DAAD0691E2942A7D138 -:102C7000B4F85D8018F00F0FA4F80880A0D1B4F864 -:102C80005F0018B904F16C00FFF788F9B4F85A1026 -:102C9000002995D006FB03FE01EB181CF4446045A7 -:102CA0008ED3A0EB0C00A842B0FBF5F388D33E48CE -:102CB000834285D84FF6F57083426DD903259F1C5A -:102CC000114402EB0C03032DE7626263A1632364EA -:102CD0004CD1B4F8763053EA08037FF471AFBB00EF -:102CE00004F17800FFF75AF9E06303F2FF13B6EB43 -:102CF000532FFFF465AF4FF0FF33032DC4E90533C5 -:102D00004FF08003237187D1B4F87C30012B83D13D -:102D1000511C2046FFF710FB00287FF47DAFB4F86C -:102D20004A224AF6552320719A427FF475AF1F4B11 -:102D300004F14C00FFF732F998427FF46DAF03F1D4 -:102D4000FF5304F50C70FFF729F903F50053203306 -:102D500098427FF461AF04F50D70FFF71FF9A06191 -:102D600004F50E70FFF71AF9606155E7B8F1000F2E -:102D70003FF426AF7144022D4FEA4703E1631EBFC3 -:102D8000D91907F0010303EB5103AEE70B2560E609 -:102D90000C255EE603255CE640F6F575AB428CBF7C -:102DA000022501258BE700BFF5FFFF0F525261415D -:102DB0002DE9F84F07460568884649B96E69C6B1DE -:102DC000EB6AB34298BF0126AB69A3B9002405E0C2 -:102DD000FFF76AFB0128044603D801242046BDE81A -:102DE000F88F421C00F0D280EB6A8342F6D8464648 -:102DF000EAE70126E8E72A78EB6A042A40F08380B4 -:102E0000A6F1020A023B4FF0010B9A4528BF4FF092 -:102E1000000AD146696C284601EB1931FFF78CFA9C -:102E200000283BD109F00703EA6AC9F3C8010BFA8D -:102E300003F3901EDBB26A184C4609F1010992F8BF -:102E40004C20814502EA030233BF5B0000234FF4AC -:102E50000071DBB228BF9946B2B90234631E033356 -:102E6000BCD80123214628461A46FFF7E1FA02287A -:102E7000B3D0012800F08A80B8F1000F13D10223EB -:102E8000FB710028A9D130E0CA450AD0002BD2D16D -:102E90000131B1F5007FBDD20123CCE74FF0FF3403 -:102EA000DCE70024DAE7FB79022B07D1731CA3428D -:102EB000E7D0BB68F31ABB610323FB7108F1010281 -:102EC000FB69A24205D113B10133FB61D9E70223AB -:102ED000FBE70BB90123FB61224641463846FFF769 -:102EE00047FC00284FD10123FB61EA6AAB69023A33 -:102EF0006C6193429CBF03F1FF33AB612B7943F0CC -:102F000001032B716AE7464514D1741C3846A3426D -:102F100098BF02242146FFF7C7FA01283FF45DAFAE -:102F2000431C33D0E0B16B69012B03D9EA6A9342A9 -:102F300038BF1E4634460134EB6AA34203D8012E43 -:102F40007FF644AF022421463846FFF7ADFA48B178 -:102F500001283FF442AF013018D0B442EBD135E73D -:102F6000002CE7D04FF0FF3221462846FFF77CFBCC -:102F700048B9B8F1000FB8D0224641462846FFF7BD -:102F800073FB0028B1D001287FF427AF4FF0FF3446 -:102F900024E700002DE9F84306680446076B8946DC -:102FA00033782037042B0CBF4FF080534FF40013BD -:102FB000BB429CBF00238363836B73B1C7F30808D4 -:102FC000B8F1000F3CD10133416B836339B93389C8 -:102FD000B3EB571F34D80023A36304200AE073899E -:102FE000013B13EA57232BD1FFF75EFA0128054670 -:102FF00002D80220BDE8F883421C01D10120F9E784 -:10300000F36A834216D8B9F1000FE4D0616B204611 -:10301000FFF7CEFE0546C8B10128EAD0431CEDD02B -:1030200001463046FFF752FC0028E7D1E37943F030 -:103030000403E371294630466563FEF7CDFFA063C4 -:103040004C36002027634644E663D3E70720D1E7E8 -:10305000F8B50E46002104460768FFF7BDFA98B997 -:103060000546A16B3846FFF767F968B93A78E36B14 -:10307000042A1B780CD11B060ED5054601212046DB -:10308000FFF788FF0028ECD0042808BF072006E0DF -:10309000E52B01D0002BF0D10135B542EED1F8BDC2 -:1030A000C16C4B1C2DE9F04104460568066B1FD12D -:1030B000E5274FF00108A16B2846FFF73DF998B9C5 -:1030C0002A78E36B042A09BF1A781F7002F07F0286 -:1030D0001A7085F80380236BB3420DD2002120467D -:1030E000FFF758FF0028E6D0042808BF022003E0BD -:1030F000FFF772FA0028DBD0BDE8F0812DE9F0413E -:1031000005460068A96B0669FFF716F9044620B961 -:10311000EB6B1A78852A03D002242046BDE8F081A3 -:10312000324603F1200153F8040B8B4242F8040BA2 -:10313000F9D1777801377F01A7F16003B3F5007FFC -:10314000EAD800212846FFF725FF04280446E3D0EB -:103150000028E2D1A96B2868FFF7EEF804460028A2 -:10316000DBD1EB6B1A78C02AD6D106F1200203F12D -:10317000200153F8040B8B4242F8040BF9D196F866 -:1031800023300F222C33B3FBF2F3B7EB431FC3D32F -:103190004FF0400800212846FFF7FCFE04280446B3 -:1031A000BAD00028B9D1A96B2868FFF7C5F8044642 -:1031B0000028B2D1EB6B1A78C12AADD1B8F5187FCF -:1031C00009D206EB080203F1200153F8040B8B42ED -:1031D00042F8040BF9D108F120084745DAD8B8F5D0 -:1031E000187F9AD83046FEF71FFF7388834294D029 -:1031F00092E700000B68002210B5036004460B6ADA -:1032000083604B6AC261C37123F0FF03896AC0E91E -:103210000432C164FFF7E0F920B92046BDE8104050 -:10322000FFF76CBF10BD0000F8B503680546012725 -:103230001C692046FEF7F8FEA070000A6678E07070 -:103240002846E96CFFF7C8F920B1022828BF022000 -:10325000C0B2F8BDA96B2868FFF76EF80028F4D15A -:10326000EB6B04F1200254F8041B944243F8041B56 -:10327000F9D12B68DF70002EE7D000212846013EEF -:10328000FFF788FEE0E700002DE9F8434FF0FF0864 -:1032900006460768042445464FF6FF79B16B11B91D -:1032A000002C73D063E03846FFF746F80446002848 -:1032B0005DD1F06B0378002B6ED03A78042A11D1DF -:1032C000852B4DD1336B3046F364FFF717FF04466F -:1032D00000284CD13B691B7903F03F03B3712046B2 -:1032E000BDE8F883C27AE52B02F03F02B27143D009 -:1032F0002E2B41D022F0200108293DD00F2A40D1A9 -:10330000590637D503F0BF05336B90F80D80F36491 -:10331000437B434530D1428B72BB03780D21FC685F -:1033200023F04003DFF874E0013B4B4301211EF81A -:1033300001CB30F80CC009B3FF2B1DD824F813C003 -:103340006146013301320D2AF1D10278520605D5CA -:1033500021B1FF2B10D8002224F81320013DEDB23B -:1033600000213046FFF716FE0446002896D00023C1 -:10337000B363B4E7AB42CBD0FF25F1E7CC45E1D056 -:10338000FAE72DB9FEF740FE404501D10024A6E73B -:103390004FF0FF33F364A2E70424E8E7208F00082E -:1033A0002DE9F04F002187B00446D0F80090FFF7D8 -:1033B00013F9804670B999F80030042B33D1D9F84D -:1033C0000C00FEF779FF07462046FFF75DFF054634 -:1033D00020B18046404607B0BDE8F08FD9F81030E4 -:1033E0009A8CBA42F0D193F823B040265D4506D1BD -:1033F000D9F80C3033F81530002BE5D1EAE7F106A7 -:10340000D9F8103008BF0236985B01F04DF8D9F8B2 -:103410000C30824633F8150001F046F88245D3D1CE -:1034200002360135E2E74FF0FF0A4FF0FF3B554609 -:10343000C4F84CB0A16B4846FEF77EFF00285CD173 -:10344000E66B3778002F77D0F27AE52F02F03F0352 -:10345000A37103D0120704D50F2B04D0C4F84CB0CD -:103460004FE00F2B54D194F84B3058063FD47906D7 -:1034700045D5236B07F0BF0796F80DA0E364737B77 -:1034800053453ED1738B002B3BD135780121D9F8C0 -:103490000C3005F03F0501930D23013D5D43284BA2 -:1034A00013F8012BB25A71B3FF2D059329D810469A -:1034B000049200F0F9FF6B1C03900293019B33F818 -:1034C000150000F0F1FF039981421AD1049A029D80 -:1034D0001146059B1B4A9342E2D133785A0604D524 -:1034E00019B1019B33F815305BB97D1EEDB2002197 -:1034F0002046FFF74FFD00289CD080466AE7BD427A -:10350000BDD0FF25F3E74FF6FF708242E2D0F8E727 -:103510002DB93046FEF778FD50453FF45BAF94F887 -:103520004B30DB079AD40B2204F14001304605F002 -:1035300089FB002892D14DE74FF004084AE700BF0D -:10354000208F00082D8F00082DE9F04F90F84BB028 -:1035500099B004461BF0A00540F068810668F26847 -:1035600032F81530002B4AD13378042B40F0878095 -:103570000F230E352046B5FBF3F5A91CFFF768FDB8 -:103580008146002877D1236B0135A3EB4515E379FC -:103590005A07E56435D523F004032046E371FFF7AD -:1035A0007DF950BB4FF0FF32616B2046FFF7E0F82A -:1035B00018BBA3682BB3214604A8FFF71BFEE0B994 -:1035C00070894FF40071D4E90423E0FB01233069D2 -:1035D000C4E904233830FEF7EFFC3069D4E9042352 -:1035E0002830FEF7E9FCE379326904A843F00103CF -:1035F00082F82130FFF718FE18B181463BE0013513 -:10360000AEE7D6E90354402200212046FEF796FBA0 -:103610008523012140222370C0234FF0C10C04EB0D -:10362000010884F8203000231E469E46571C04F8EB -:1036300002C0F0B2023204F807E021B135F81310ED -:1036400009B10133DBB20F0AA15408F8027002324B -:10365000D706F2D135F813700136002FE6D184F881 -:103660002330831C28466370FEF726FE84F824006E -:10367000000A84F82500484619B0BDE8F08F04F12F -:1036800040070DF1100A1BF0010F97E807008AE8C8 -:10369000070000F0D38040234FF0010884F84B303E -:1036A000BC46F368B8F1050F9AE80700ACE80300E0 -:1036B0002CF8022B4FEA12428CF8002059D9981EA0 -:1036C000424630F8021F002942D10DF10F0C0721AC -:1036D00002F00F0E914612090EF13000392888BF12 -:1036E0000EF1370001390CF8010902D0B9F10F0FC2 -:1036F000EED818AB7E205A1802F8580C3846002233 -:10370000914206D010F801CB02F1010EBCF1200F5E -:1037100031D104F13F0C072902F1010297BF18AB28 -:1037200020205818013198BF10F8580C072A0CF8BF -:103730000200F0D92046FFF733FE8146002878D1F9 -:1037400008F10108B8F1640FAAD14FF0070992E718 -:103750004FF0100C01F0010E49080EEB4202D303AA -:1037600044BF82F4883282F02102BCF1010CF1D115 -:10377000A7E74246A9E77246C2E7216B2046A1EBC4 -:103780004511FEF729FF814600287FF474AF4FF6FC -:10379000FF783846FEF738FC0190A16B3046FEF703 -:1037A000CBFD814600287FF466AFE36BE9B2019A56 -:1037B0004FF00D0CD6F80CE05A734FF00F02DFF803 -:1037C000E0A0DA724A1E18730CFB02F28446987667 -:1037D000D87640451AF8019B0CF1010C18BF3EF851 -:1037E000120003EB090B18BF013203F809004FEA7E -:1037F0001029002808BF4046BCF10D0F8BF801903E -:10380000E7D1404502D03EF812200AB941F040010C -:103810001970012300212046F370FFF7BBFB81469E -:1038200000287FF428AF013DB7D11BE04FF0060917 -:1038300021E704287FF41FAF84F84BB01BF0020F80 -:1038400020461BBF0C350D210125B5FBF1F518BF36 -:1038500001352946FFF7FCFB814600287FF40BAFBA -:10386000013D8AD1A16B3046FEF766FD81460028F6 -:103870007FF401AF01462022E06BFEF75FFAE36BB5 -:1038800003CF18605960BA7839889A72198194F810 -:103890004B30E26B03F0180313730123F370EAE675 -:1038A000208F000810B504460A463430FEF776FB38 -:1038B000886004F13800FEF773FBC2E9040194F854 -:1038C000213003F00203D3710023D36110BD000047 -:1038D00003284B8B04BF8A8A43EA02431846704789 -:1038E0002DE9F04F0B7899B0044689462F2BD0F87C -:1038F00000B001D05C2B09D14A46137891460132C1 -:103900002F2BFAD05C2BF8D0002301E0DBF81C3021 -:10391000A3600023E3619BF80030042B1ED1A36851 -:10392000E3B1DBF82030214604A82362DBF8243021 -:103930006362DBF82830A362FFF75CFC03460028D3 -:1039400054D1DBF8102002F13800FEF727FBC4E960 -:10395000040392F8213003F00203E37199F8003078 -:103960001F2B00F2358180230021204684F84B3044 -:1039700019B0BDE8F04FFEF72FBE49460B788946D7 -:1039800001312F2BFAD05C2BF8D01F2B8CBF0025D8 -:103990000425012F2FD113882E2B31D1002322F89B -:1039A000173004F140029F428CBF2E2120210133A9 -:1039B0000B2B02F8011BF6D145F02005204684F8B8 -:1039C0004B50FFF7EDFC94F84B30002800F0E780F7 -:1039D00004280BD1990603F0040240F1DC80002A90 -:1039E00000F0F6808023002084F84B3019B0BDE849 -:1039F000F08F0425CDE7022F02D153882E2BCAD099 -:103A0000911E87BB002322F81730002F00F0118190 -:103A100032F81300194601332028F9D009B92E28AD -:103A200001D145F00305901E30F817302E2B01D040 -:103A3000013FF9D14FF020334FF0000A6364D046C4 -:103A40002364C4F847300823481C32F81160009002 -:103A5000F6B1202E03D02E2E0DD1B84210D045F055 -:103A600003050099F0E731F81730202B01D02E2BF9 -:103A7000C8D1013FC5E79A4505D20099B9423BD16B -:103A80000B2B30D101E00B2B27D145F003050B2385 -:103A900094F84020E52A04BF052284F84020082B32 -:103AA00004BF4FEA88085FFA88F808F00C030C2B73 -:103AB00003D008F00303032B01D145F00205A8074A -:103AC0003FF57CAF18F0010F18BF45F0100518F056 -:103AD000040F18BF45F0080570E70099B94202D0FD -:103AE00045F00305D4D84FEA88080B234FF0080AA5 -:103AF00000975FFA88F8B4E77F2E15D9304640F278 -:103B00005231CDE9022345F00203019300F098FC05 -:103B100010F0800F0646DDE9022316D000F07F0684 -:103B200046498E5D019D46B331464548CDE90123A6 -:103B300005F0F6F8DDE90123F8B9A6F1410189B2F3 -:103B400019291ED848F0020810E0FF28EAD9591EAA -:103B50008A4503D345F003059A4682E704EB0A0140 -:103B6000000A0AF1010A019D81F8400004EB0A01F4 -:103B70000AF1010A81F8406073E745F003055F260A -:103B8000F4E7A6F1610189B219299EBF203E48F0F1 -:103B90000108B6B2EAE7002A08BF052026E75A075F -:103BA0003FF524AFA379DB0645D59BF80000042838 -:103BB00035D1A3682146E27923622369DBF810003E -:103BC00023F0FF0313436362E36CA362FFF76AFE13 -:103BD00023680027DA6819F8010B00283FF409AFC1 -:103BE00040F25231009200F04BFC054608B31F280A -:103BF000009A7FF6FEAE2F283FF4BFAE5C283FF45C -:103C0000BCAE7F2805D801460E4805F089F8009A19 -:103C100078B9FF2F0DD022F817500137DBE7216B61 -:103C20000BF14C03C1F308011944FFF751FEA060EA -:103C3000CEE70620DAE60520D8E600BFA08E000811 -:103C4000998E0008908E00081FB5CDE9001003A8DA -:103C500014460391FEF700FA002815DB0B4A52F8D0 -:103C600020300BB100211970019B0BB1002119709C -:103C700042F820302CB1002201A96846FEF7C8FEA8 -:103C80000446204604B010BD0B24FAE79C36002001 -:103C90002DE9F04798B0904605460191002800F0C4 -:103CA000528102F03F0603A901A83246FEF7B0FE9A -:103CB000002840F04681039B4FF48C60049303F08E -:103CC0004BF80746002800F04081039B00F5007286 -:103CD0000199D86004A81A61FFF702FE044620B9D2 -:103CE0009DF95B30002BB8BF062418F01C0F00F0C4 -:103CF000CD80002C4CD0042C40D104A8FFF724FC2C -:103D0000044600283AD146F00806039B1A78042A94 -:103D100040F08380186929462B60FFF7C3FD039BA1 -:103D20001E22002118690230FEF708F8039C0021CA -:103D30001A2220692630FEF701F8236920221A7121 -:103D4000246903F027F80146012208342046FEF7D3 -:103D50002BF9039B04A81B6983F82120FFF764FA61 -:103D6000044658B9A96801B302462846FEF718FD73 -:103D7000AB68039A0446013B5361B4B1384602F084 -:103D8000FBFF0CB100232B60204618B0BDE8F08784 -:103D90009DF8163013F0110F40F0848018F0040FD6 -:103DA00040F0C98018F0080FAFD1039A310713997A -:103DB000936C48BF46F04006E964AB641078042871 -:103DC00072D1069B9DF817102B62089B106923F097 -:103DD000FF030B4329466B62179BAB62FFF762FD43 -:103DE000DDF80CA00024002205F15008BAF80630D6 -:103DF00021464046C5F800A0AB80002385F830601E -:103E000085F831406C64C5E90E234FF40072FDF76C -:103E100095FFB20653D40024B0E702F0BBFF014681 -:103E2000009013980E30FEF7BFF8139800991630E3 -:103E3000FEF7BAF8039C13992078FFF749FD202379 -:103E400000228046CB7220461399FEF7D1F8139BCF -:103E5000002201211A775A779A77DA77039BD97073 -:103E6000B8F1000FA1D0414604A8D3F84890FEF75E -:103E700097FC0446002881D149460398FEF75CFA76 -:103E8000039B044608F1FF30586176E7002C7FF46D -:103E900075AF9DF81630DC064FD418F0020F84D0B1 -:103EA000D80782D5072469E7FFF712FD0023A86031 -:103EB00001F11C00FEF772F86B61286190E7D5E90B -:103EC000046956EA0903A6D0BAF80AA0A9684FEA1D -:103ED0004A2AC5E90E69B24574EB09031BD30024D5 -:103EE0002964002C7FF44AAFC6F30803002B92D05C -:103EF000039C2046FEF770F808B3760A012341467A -:103F000046EAC95682196A64607802F095FA041E7E -:103F100018BF012432E72846FEF7C6FAB6EB0A06B8 -:103F2000014669F10009012803D9431CD3D10124BA -:103F3000D6E70224D4E7082420E704241EE702245D -:103F40001CE704461EE709241EE711241CE70000B5 -:103F50002DE9F04F994685B00023884603A9044611 -:103F6000C9F800301646FEF791F8054680BB94F874 -:103F700031506DBB94F8303013F00103009300F022 -:103F8000A68004F1500AD4E90432D4E90E011B1AC8 -:103F900062EB0102B34272F1000238BF1E46BEB1AD -:103FA000D4E90E10C1F30803002B40F08280039B7C -:103FB0005A894B0A013A43EAC0531A401BD151EACD -:103FC000000309D1A06801280DD8022584F83150DA -:103FD000284605B0BDE8F08F216C20460192FEF71F -:103FE00063FA019AEFE7431C04D10123009D84F892 -:103FF0003130EDE72064DDF80CB0216C5846FDF758 -:10400000EBFF0028E1D0B6F5007F02EB000731D3CB -:10401000BBF80A1002EB5620730A88429BF8010095 -:1040200088BF8B1A3A464146019302F005FA0028F0 -:10403000DBD194F93020019B002A0BDA606CC01BA5 -:10404000984207D24FF40072514608EB4020FDF72A -:104050004FFE019B5F02D9F80030F61BB8443B4489 -:10406000C9F80030D4E90E32DB1942F10002C4E98C -:104070000E3294E7626CBA421AD094F93030002BB9 -:104080000DDA012351469BF8010002F0F9F90028EE -:10409000ABD194F8303003F07F0384F830300398CC -:1040A00001233A465146407802F0C6F900289CD1D7 -:1040B0006764A16B4046C1F30801C1F50077514424 -:1040C000B74228BF37463A46FDF712FEC3E7072539 -:1040D0007EE7000070B596B00E460022019002A95E -:1040E00001A8FEF795FC0446E0B94FF48C6002F09D -:1040F00033FE0546D8B1029B00F500720199D860E5 -:1041000002A81A61FFF7ECFB044640B99DF9533051 -:10411000002B0ADB1EB1314602A8FDF7EDFF284651 -:1041200002F02AFE204616B070BD0624F7E71124DF -:10413000F8E7000070B5B8B00222019003A901A809 -:10414000FEF766FC044608BB039B4FF48C6010939B -:1041500002F002FE0546002866D0039B00F50072BF -:104160000199D86010A81A61FFF7BAFB044650B94C -:104170009DF88B30980655D4190653D49DF84630D7 -:10418000DA0706D50724284602F0F6FD204638B0A7 -:1041900070BD039B04931878042814D104A91869EE -:1041A000FFF780FB069E9DF84630DB0610D410A872 -:1041B000FEF776FF04460028E5D156BB0398FEF7CC -:1041C000DBFB0446DFE71F99FFF782FB0646EAE7C1 -:1041D000039BDA69B242D5D024930021269624A805 -:1041E0001B78042B01BFDDE90823CDE928239DF8C6 -:1041F00017308DF89730FEF7EFF904460028C2D14A -:1042000024A8FFF741F804460028BBD00428BAD1FF -:10421000CDE70246314604A8FEF7C2FA044600285C -:10422000B1D1CBE70624AEE71124AFE7F0B5BDB0BE -:10423000CDE900106846FDF70FFF022203A901A88F -:10424000FEF7E6FB0446002841D1039B4FF48C6047 -:10425000149302F081FD0546002800F0EE80039BD8 -:1042600000F5007214AE0199D8601A613046FFF76C -:1042700037FB044640BB9DF89B3013F0A00F40F085 -:10428000D880039B009F1A78042A68D11B6904AC6C -:1042900003F1400C1868083353F8041C22466345A8 -:1042A00003C21446F6D15022314628A8FDF720FD5E -:1042B000394628A8FFF714FB044600284CD12A9A57 -:1042C000169B9A4206D00824284602F055FD204647 -:1042D0003DB0F0BD349A209B9A42F4D128A8FFF754 -:1042E00033F904460028EFD1039B04AF1B6993F810 -:1042F00001E093F823C09C8C3A46083303CAB242CB -:1043000043F8080C43F8041C1746F5D1039B28A872 -:104310001B6983F801E0039B1A6982F823C01A69BC -:1043200082F82440240A82F825401A691379D906B4 -:104330005CBF43F020031371FEF776FF04460028AC -:10434000C2D13046FEF7ACFE04460028BCD103982B -:10435000FEF712FB0446B7E70428B5D1BEE7239A5F -:1043600004AB02F1200C1068083252F8041C1C4601 -:10437000624503C42346F6D15022314628A8FDF7F2 -:10438000B7FC394628A8FFF7ABFA044600284CD101 -:104390002A9A169B9A4296D1349A209B9A4292D19D -:1043A00028A8FFF7D1F8044600288DD137990DF1E0 -:1043B0001D030DF12D0001F10D0253F8044B834252 -:1043C00042F8044BF9D11888012710809B7893702C -:1043D0009DF81B30039CDA0658BF43F02003CB72D4 -:1043E000E770CB7ADB06ACD5169A2A9B9A42A8D006 -:1043F0002078FFF76DFA01462046FDF7EDFD0146F6 -:10440000C8B12046FDF798FF044600287FF45CAF52 -:10441000039890F86D302E2B93D12A9A00F16C01FD -:10442000FDF7E6FD039BDF708BE704287FF44CAFBC -:10443000B6E7062448E7022446E7112447E70000D0 -:104440007F2810B501D880B210BDB0F5803F13D2DF -:1044500040F2523399420FD10849002231F8024B01 -:1044600093B2844203D103F18000C0B2ECE7013281 -:10447000802AF3D11346F6E70020E5E7E091000833 -:104480007F280DD940F25233994208D1FF2806D82F -:1044900000F10040034B803833F8100070470020D3 -:1044A000704700BFE0910008B0F5803FF0B522D220 -:1044B0001F4A83B21F49B0F5805F28BF0A46141D0A -:1044C00034F8042C2146AAB1934213D334F8025C89 -:1044D0002E0AEFB252FA85F5A84222DA082E09D840 -:1044E000DFE806F0050A10121416181A1C00801ACC -:1044F00034F810301846F0BD981A00F001001B1A6D -:104500009BB2F7E7103BFBE7203BF9E7303BF7E7CF -:104510001A3BF5E70833F3E7503BF1E7A3F5E35324 -:10452000EEE70434002ECBD101EB4702C7E700BF12 -:10453000308F000824910008084BC26A994228BFB6 -:104540001946836C50688B4210B506D95A1E4C0030 -:1045500002EB4103B3FBF4F3184410BD20BCBE00D2 -:1045600001F001038A0748BF43F002034A0748BF2E -:1045700043F008030A0748BF43F00403CA0648BFD4 -:1045800043F010038A06426B48BF43F020031343F5 -:104590004363704710B5074C204600F09FFF064B61 -:1045A0000022C4E91023054BA364054BE363054BCC -:1045B000E36410BDA43600200070005200B4C404AF -:1045C000F8360020F8380020C36A0BB9104BC362DC -:1045D0000379012B11D10F4B98420ED10E4BD3F81A -:1045E000D42042F48032C3F8D420D3F8FC2042F423 -:1045F0008032C3F8FC20D3F8FC30436C00221A65EB -:10460000DA621A605A605A624FF0FF329A6370475A -:10461000E0920008A4360020004402580379012BE0 -:104620001BD0436C00221A65DA621A605A605A6223 -:104630004FF0FF329A63094B98420ED1084BD3F8E2 -:10464000D42022F48032C3F8D420D3F8FC2022F402 -:104650008032C3F8FC20D3F8FC307047A436002029 -:104660000044025810B5446C0649FFF765FF6060CE -:10467000236842F2107043F003032360BDE810404A -:1046800001F04CBD801A06000129F8B5466C0B4FAD -:1046900009D175680A493D40FFF74EFF054345F4CF -:1046A00080557560F8BD746806493C40FFF744FFCB -:1046B000044344F480547460F4E700BF00ECFFFF4F -:1046C00080F0FA0240787D01436C00225A601A6043 -:1046D00070470000426C0129536823F4404304D022 -:1046E000022905D001B95360704743F48043FAE7CB -:1046F00043F40043F7E70000436C41F480519A60B3 -:10470000D9605A6B1206FCD580229A63704700006C -:1047100010B541F48851446CA260E160616B11F006 -:104720004502FBD0A26311F0040203D0FFF718FF8B -:10473000012010BD616910461960FAE710B541F417 -:104740008851446CA260E160616B11F04502FBD0BE -:10475000A26311F0050203D0FFF702FF012010BD94 -:10476000616910461960FAE773B5134604460E46B0 -:10477000302282F31188426CD26B32B14FF0FF319C -:104780004030019301F0D6FC019B606C0022026571 -:10479000C263C262456B15F4807504D185F311883C -:1047A000012002B070BD4FF0FF31816382F31188A8 -:1047B000012E06D90C21204602B0BDE87040FFF75B -:1047C000BDBF1046EDE7000073B5446C0E460025F2 -:1047D0000192616BA1632565E562FFF7C1FE012EC1 -:1047E00007D9019B2A460C2102B0BDE87040FFF7B3 -:1047F000A5BF02B070BD000010B541F49851446CE3 -:10480000A260E160616B11F04502FBD0A26311F080 -:104810003F0203D0FFF7A4FE012010BD216A10461D -:104820001960E1695960A16999606169D960F4E72B -:104830002DE9F74304460191006D01A917469846FA -:1048400002F0E2FB064600284AD0626C2046DDF802 -:1048500004905568C5F3090501356B00A56CB5FBDF -:10486000F3F54FF47A73B5FBF3F55D43556200F051 -:10487000FBFD50BB636C4FF0FF3201254146C3F88E -:10488000589020461D659A634FF49572DA6342F2A0 -:1048900007029F62DA62E36C0A9AFFF74FFFA0B942 -:1048A000E26C104B11680B407BB929462046FFF79C -:1048B0005BFF054648B92E463A460199206D02F045 -:1048C000CBFB304603B0BDE8F0833A460199206D3A -:1048D00002F0C2FBE26C01212046FFF775FFF0E712 -:1048E0000126EEE708E0FFFD2DE9F7431F46436C84 -:1048F00001924FF47A725D6804468846C5F3090553 -:1049000001356E00856CB5FBF6F5B5FBF2F5554348 -:104910005D6200F0A9FD20B10125284603B0BDE885 -:10492000F0837E0201A9206D324602F06DFB054640 -:104930000028F1D0636C019AD4F84C909A6501225A -:104940001A654FF0FF329A634FF49572DA639E62F4 -:10495000236BDB064B4658BF4FEA4828012F4246DF -:104960001BD912212046FFF7E9FEC0B9D9F8002073 -:10497000104B13409BB9636C42F2930239462046B8 -:10498000DA62E26CFFF7F0FE804640B932460199E8 -:10499000206D454602F060FBBFE71121E2E7324699 -:1049A0000199206D02F058FBE26C39462046FFF772 -:1049B0000BFFB2E708E0FFFD2DE9F3411F46436C12 -:1049C00001924FF47A725D6804468846C5F3090582 -:1049D00001356E00856CB5FBF6F5B5FBF2F5554378 -:1049E0005D6200F041FD20B10125284602B0BDE81E -:1049F000F0817E0201A9206D324602F03BFB0546A4 -:104A00000028F1D0636C019A9A6501221A654FF073 -:104A1000FF329A634FF48D72DA639E62236BE66C09 -:104A2000DB06334658BF4FEA4828012F424619D9C2 -:104A300019212046FFF782FEB0B932680F4B1340B0 -:104A400093B9636C42F2910239462046DA62E26C15 -:104A5000FFF78AFE064638B901993546206D02F007 -:104A600035FBC2E71821E4E70199206D02F02EFB27 -:104A7000E26C39462046FFF7A7FEB6E708E0FFFDE7 -:104A800012F0030F2DE9F04107460C4615461E466D -:104A900017D00E44B44202D10020BDE8F0810123BA -:104AA000FA6B21463846FFF71FFF0028F5D128464C -:104AB0004FF40072F96B05F500750134FDF718F934 -:104AC000E8E7BDE8F041FFF70FBF000012F0030F69 -:104AD0002DE9F04107460C4615461E4617D00E44F8 -:104AE000B44202D10020BDE8F08129464FF40072A3 -:104AF000F86B05F50075FDF7FBF80123FA6B21460D -:104B00003846FFF759FF0028EDD10134E8E7BDE84A -:104B1000F041FFF751BF000000207047302310B56F -:104B200083F311880024436C40302146DC6301F09C -:104B30000FFB84F3118810BD0268436811430160C4 -:104B400003B1184770470000024A136843F0C003DE -:104B50001360704700440040024A136843F0C003EA -:104B60001360704700480040024A136843F0C003D6 -:104B70001360704700780040064BD3F8E8200243EA -:104B8000C3F8E820D3F810211043C3F81001D3F87C -:104B9000103170470044025837B5274C274D204646 -:104BA00000F0FCFC04F11400009400234FF40072A8 -:104BB000234900F097F94FF40072224904F13800BC -:104BC0000094214B00F010FA204BC4E91735204C1B -:104BD000204600F0E3FC04F11400009400234FF49D -:104BE00000721C4900F07EF94FF400721A4904F17A -:104BF00038000094194B00F0F7F9194BC4E9173548 -:104C0000184C204600F0CAFC04F1140000234FF4B5 -:104C100000721549009400F065F9144B4FF40072CE -:104C2000134904F13800009400F0DEF9114BC4E997 -:104C3000173503B030BD00BFFC38002000E1F5059A -:104C4000403A002040400020494B0008004400400A -:104C500068390020403C002040420020594B0008A9 -:104C600000480040D4390020403E0020694B000835 -:104C7000404400200078004038B5264D0446037CAF -:104C8000002918BF0D46012B06D1234B984230D185 -:104C90004FF40030FFF770FF2A68236EE16D03EBDD -:104CA0005203A566B3FBF2F36A68100442BF23F017 -:104CB000070003F0070343EA4003CB60AB6843F00F -:104CC00040034B60EB6843F001038B6042F4967342 -:104CD00043F001030B604FF0FF330B62510505D524 -:104CE00012F0102211D0B2F1805F10D084F864303D -:104CF00038BD0A4B984205D0094B9842CCD14FF0B1 -:104D00008040C7E74FF48020C4E77F23EEE73F23CE -:104D1000ECE700BFE8920008FC380020683900206A -:104D2000D43900202DE9F047C66D05463768F4698F -:104D3000210734621AD014F0080118BF4FF48071B3 -:104D4000E20748BF41F02001A3074FF0300348BFFE -:104D500041F04001600748BF41F0800183F31188B2 -:104D6000281DFFF7E9FE002383F31188E2050AD529 -:104D7000302383F311884FF48061281DFFF7DCFE98 -:104D8000002383F311884FF030094FF0000A14F02C -:104D9000200838D13B0616D54FF0300905F1380A06 -:104DA000200610D589F31188504600F051F90028EB -:104DB00036DA0821281DFFF7BFFE27F08003336095 -:104DC000002383F31188790614D5620612D53023A7 -:104DD00083F31188D5E913239A4208D12B6C33B1A0 -:104DE00027F040071021281DFFF7A6FE376000239B -:104DF00083F31188E30618D5AA6E1369ABB1506925 -:104E0000BDE8F047184789F31188736A284695F87A -:104E10006410194000F0DCFB8AF31188F469B6E7EE -:104E2000B06288F31188F469BAE7BDE8F087000042 -:104E3000F8B51546826804460B46AA4200D285683A -:104E4000A1692669761AB5420BD218462A46FCF7A4 -:104E50004FFFA3692B44A3612846A3685B1BA36093 -:104E6000F8BD0CD9AF1B18463246FCF741FF3A4655 -:104E7000E1683044FCF73CFFE3683B44EBE718464D -:104E80002A46FCF735FFE368E5E7000083689342B4 -:104E9000F7B50446154600D28568D4E90460361A91 -:104EA000B5420BD22A46FCF723FF63692B446361AA -:104EB0002846A3685B1BA36003B0F0BD0DD9324642 -:104EC000AF1B0191FCF714FF01993A46E0683144A9 -:104ED000FCF70EFFE3683B44E9E72A46FCF708FFCE -:104EE000E368E4E710B50A440024C361029B8460D0 -:104EF000C16002610362C0E90000C0E9051110BD94 -:104F000008B5D0E90532934201D1826882B982683E -:104F1000013282605A1C426119700021D0E90432CA -:104F20009A4224BFC368436101F02CF9002008BDF8 -:104F30004FF0FF30FBE7000070B5302304460E460B -:104F400083F31188A568A5B1A368A269013BA3609A -:104F5000531CA36115782269934224BFE368A361BF -:104F6000E3690BB120469847002383F31188284654 -:104F700007E03146204601F0F5F80028E2DA85F333 -:104F8000118870BD2DE9F74F04460E461746984626 -:104F9000D0F81C904FF0300A8AF311884FF0000BC4 -:104FA000154665B12A4631462046FFF741FF0346C4 -:104FB00060B94146204601F0D5F80028F1D0002321 -:104FC00083F31188781B03B0BDE8F08FB9F1000FAF -:104FD00003D001902046C847019B8BF31188ED1A3E -:104FE0001E448AF31188DCE7C160C361009B8260C4 -:104FF0000362C0E905111144C0E900000161704776 -:10500000F8B504460D461646302383F31188A76889 -:10501000A7B1A368013BA36063695A1C62611D705C -:10502000D4E904329A4224BFE3686361E3690BB1B7 -:1050300020469847002080F3118807E0314620463B -:1050400001F090F80028E2DA87F31188F8BD00003B -:10505000D0E9052310B59A4201D182687AB98268F5 -:105060000021013282605A1C82611C7803699A42D5 -:1050700024BFC368836101F085F8204610BD4FF05E -:10508000FF30FBE72DE9F74F04460E4617469846DA -:10509000D0F81C904FF0300A8AF311884FF0000BC3 -:1050A000154665B12A4631462046FFF7EFFE034616 -:1050B00060B94146204601F055F80028F1D00023A0 -:1050C00083F31188781B03B0BDE8F08FB9F1000FAE -:1050D00003D001902046C847019B8BF31188ED1A3D -:1050E0001E448AF31188DCE70379052B05BF836A28 -:1050F000002001204B6004BF4FF400730B60704729 -:1051000070B55D1E866A04460D44B54205D9436BF1 -:1051100043F080034363012070BD06250571FFF74E -:10512000AFFC05232371F7E770B55D1E866A044660 -:105130000D44B54205D9436B43F08003436301201E -:1051400070BD07250571FFF7C1FC05232371F7E743 -:1051500038B505790446052D05D108230371FFF7FD -:10516000DBFC257138BD0120FCE700000323F0B50E -:10517000037185B00446FFF775FA002220461146F8 -:10518000FFF7BAFA4FF4D57203AB08212046FFF7B8 -:10519000D5FA0246B8B901232363039BC3F3032363 -:1051A000012B09D103AB37212046FFF7C7FA18B905 -:1051B000A44B039A1340ABB120460125FFF784FAB4 -:1051C0000223237137E103AB002237212046FFF78A -:1051D000B5FA28B99B4A039B1A40002A00F0A78021 -:1051E00002232363236B03F00F03022B40F0A980FB -:1051F0006425954E42F2107000F090FF03AB3246EA -:1052000001212046FFF784FA0028D5D1039B002B0B -:1052100080F293805A0003D5236B43F0100323637D -:10522000002204F1080302212046FFF7E5FA0246B6 -:105230000028C1D104F1380303212046FFF77EFA8C -:105240000028B9D104F11805A26B092120462B468C -:10525000FFF7D2FA0028AFD102ABA26B072120469C -:10526000FFF76CFA06460028A6D1236B03F00F0364 -:10527000022B40F08F807E227F21284603F09AF98E -:10528000012840F28780E76B42F2107000F046FF81 -:1052900008234FF40072394620460096FFF7C8FAFB -:1052A000002889D1384603F0D3F9236BA06203F0BC -:1052B0000F03022B72D103AB644A06212046FFF78D -:1052C0003DFA002871D15F49039B1940B1FA81F181 -:1052D00049092046FFF7D8F902AB4FF400721021BC -:1052E0002046FFF72BFA054600287FF465AF554EA0 -:1052F000029B33427FF460AF236B13F00E0F03F079 -:105300000F0273D0022A7FF457AFE36A197801299C -:1053100000F09480022900F09380002900F0898039 -:105320004B4F2046FFF7D6F903AB3A4676E01146DD -:1053300020462263FFF7E0F954E7013D7FF45AAFBE -:105340003AE7444D6426444A3E4F012B18BF1546A8 -:1053500003AB002237212046FFF7F0F900287FF445 -:105360002BAF039B3B427FF427AF03AB2A46292197 -:105370002046FFF7CDF900287FF41EAF039B002BDA -:10538000FFF648AF013E3FF417AF42F2107000F055 -:10539000C5FEDDE7284603F02FF986E77E227F2150 -:1053A0002846E66B03F006F908B9002191E70023CF -:1053B00040223146204600930623FFF739FA0028A1 -:1053C000F3D1B3895BBA9B07EFD5244B402231461A -:1053D000204600930623FFF72BFA0028E5D1317C05 -:1053E00001F00F010F3918BF012172E7E36A197844 -:1053F000F9B101297FF4E0AE2046FFF76BF903AB6A -:10540000A26B37212046FFF799F900287FF4D4AE2C -:10541000039B33427FF4D0AE03AB02220621204629 -:10542000FFF78CF900287FF4C7AE039B33427FF46B -:10543000C3AE05232371284605B0F0BD084F70E7C1 -:10544000084F6EE708E0FFFD0080FFC00001B903D0 -:105450000000B7030080FF5000001080F1FFFF80C4 -:105460000001B7030002B70337B504460C4D01AB8A -:10547000A26B0D212046FFF761F978B9019B2B4201 -:105480000BD1C3F34323042B08D0053B022B04D8D4 -:105490004FF47A7000F042FEE9E7012003B030BD1E -:1054A00008E0FFFD70B53023054683F311880379CA -:1054B0000024022B03D184F31188204670BD0423FD -:1054C000037184F311880226FFF7CEFF04462846B5 -:1054D000FFF7FAF82E71F0E7FFF75CB8044B0360B2 -:1054E0000123037100234363C0E90A33704700BFFF -:1054F0000093000810B53023044683F31188C1627D -:10550000FFF762F802230020237180F3118810BD99 -:1055100010B53023044683F31188FFF77FF800238A -:105520000122E362227183F3118810BD026843688F -:105530001143016003B11847704700001430FFF7B2 -:1055400021BD00004FF0FF331430FFF71BBD0000FA -:105550003830FFF797BD00004FF0FF333830FFF7CA -:1055600091BD00001430FFF7E7BC00004FF0FF31A1 -:105570001430FFF7E1BC00003830FFF741BD0000F8 -:105580004FF0FF323830FFF73BBD0000012914BF58 -:105590006FF0130000207047FFF7FEBA044B036062 -:1055A00000234360C0E9023301230374704700BF46 -:1055B0002493000810B53023044683F31188FFF7C5 -:1055C0005BFB02230020237480F3118810BD0000D0 -:1055D00038B5C36904460D461BB904210844FFF7DA -:1055E000A5FF294604F11400FFF78AFC002806DA1B -:1055F000201D4FF40061BDE83840FFF797BF38BD6C -:10560000026843681143016003B118477047000006 -:1056100013B5406B00F58054D4F8A4381A6811789B -:10562000042914D1017C022911D11979012312898D -:105630008B4013420BD101A94C3002F0E9FED4F8A3 -:10564000A4480246019B2179206800F0DFF902B0EE -:1056500010BD0000143002F06BBE00004FF0FF33AD -:10566000143002F065BE00004C3002F03DBF000077 -:105670004FF0FF334C3002F037BF0000143002F01F -:1056800039BE00004FF0FF31143002F033BE00008D -:105690004C3002F009BF00004FF0FF324C3002F0F6 -:1056A00003BF00000020704710B500F58054D4F807 -:1056B000A4381A681178042917D1017C022914D161 -:1056C0005979012352898B4013420ED1143002F0D4 -:1056D000CBFD024648B1D4F8A4484FF44073617939 -:1056E0002068BDE8104000F07FB910BD406BFFF7A7 -:1056F000DBBF0000704700007FB5124B0125042678 -:10570000044603600023057400F1840243602946C7 -:10571000C0E902330C4B0290143001934FF44073F4 -:10572000009602F07DFD094B04F69442294604F1EF -:105730004C000294CDE900634FF4407302F044FE44 -:1057400004B070BD4C930008ED56000811560008D7 -:105750000A68302383F311880B790B3342F8230056 -:105760004B79133342F823008B7913B10B3342F892 -:10577000230000F58053C3F8A4180223037400200B -:1057800080F311887047000038B5037F044613B1D9 -:1057900090F85430ABB90125201D0221FFF730FFEE -:1057A00004F114006FF00101257700F0F7FC04F11B -:1057B0004C0084F854506FF00101BDE8384000F00F -:1057C000EDBC38BD10B5012104460430FFF718FFC9 -:1057D0000023237784F8543010BD000038B5044608 -:1057E0000025143002F034FD04F14C00257702F05E -:1057F00003FE201D84F854500121FFF701FF2046CD -:10580000BDE83840FFF750BF90F8803003F06003E8 -:10581000202B06D190F881200023212A03D81F2AAB -:1058200006D800207047222AFBD1C0E91D3303E0CF -:10583000034A426707228267C3670120704700BF9F -:105840004422002037B500F58055D5F8A4381A68F1 -:10585000117804291AD1017C022917D11979012361 -:1058600012898B40134211D100F14C04204602F002 -:1058700083FE58B101A9204602F0CAFDD5F8A4481C -:105880000246019B2179206800F0C0F803B030BDCA -:1058900001F10B03F0B550F8236085B004460D46C6 -:1058A000FEB1302383F3118804EB8507301D0821F6 -:1058B000FFF7A6FEFB6806F14C005B691B681BB195 -:1058C000019002F0B3FD019803A902F0A1FD024688 -:1058D00048B1039B2946204600F098F8002383F343 -:1058E000118805B0F0BDFB685A691268002AF5D02E -:1058F0001B8A013B1340F1D104F18002EAE700006A -:10590000133138B550F82140ECB1302383F31188BE -:1059100004F58053D3F8A4281368527903EB82036B -:10592000DB689B695D6845B104216018FFF768FE7C -:10593000294604F1140002F0A1FC2046FFF7B4FE52 -:10594000002383F3118838BD7047000001F0B0BC1C -:1059500001234022002110B5044600F8303BFCF73B -:10596000EDF90023C4E9013310BD000010B5302368 -:10597000044683F311882422416000210C30FCF797 -:10598000DDF9204601F0B6FC02230020237080F3ED -:10599000118810BD70B500EB8103054650690E46B5 -:1059A0001446DA6018B110220021FCF7C7F9A0698B -:1059B00018B110220021FCF7C1F931462846BDE894 -:1059C000704001F09DBD000083682022002103F09B -:1059D000011310B5044683601030FCF7AFF9204680 -:1059E000BDE8104001F018BEF0B4012500EB8104C1 -:1059F00047898D40E4683D43A469458123600023C5 -:105A0000A2606360F0BC01F035BE0000F0B4012577 -:105A100000EB810407898D40E4683D43646905819A -:105A200023600023A2606360F0BC01F0ABBE000005 -:105A300070B5022300250446242203702946C0F8CD -:105A400088500C3040F8045CFCF778F9204684F864 -:105A5000705001F0E9FC63681B6823B129462046B9 -:105A6000BDE87040184770BD0378052B10B504469B -:105A70000AD080F88C300523037043681B680BB193 -:105A8000042198470023A36010BD00000178052978 -:105A900006D190F88C20436802701B6803B1184748 -:105AA0007047000070B590F87030044613B10023C1 -:105AB00080F8703004F18002204601F0D1FD636867 -:105AC0009B68B3B994F8803013F0600535D000219D -:105AD000204602F0C3F80021204602F0B3F86368C4 -:105AE0001B6813B1062120469847062384F87030BE -:105AF00070BD204698470028E4D0B4F88630A26FE5 -:105B00009A4288BFA36794F98030A56F002B4FF0AD -:105B1000300380F20381002D00F0F280092284F826 -:105B2000702083F3118800212046D4E91D23FFF75C -:105B30006DFF002383F31188DAE794F8812003F0E6 -:105B40007F0343EA022340F20232934200F0C58011 -:105B500021D8B3F5807F48D00DD8012B3FD0022B40 -:105B600000F09380002BB2D104F188026267022218 -:105B7000A267E367C1E7B3F5817F00F09B80B3F5CF -:105B8000407FA4D194F88230012BA0D1B4F88830A2 -:105B900043F0020332E0B3F5006F4DD017D8B3F5F0 -:105BA000A06F31D0A3F5C063012B90D86368204665 -:105BB00094F882205E6894F88310B4F88430B0477B -:105BC000002884D0436863670368A3671AE0B3F5CD -:105BD000106F36D040F6024293427FF478AF5C4BB0 -:105BE00063670223A3670023C3E794F88230012B85 -:105BF0007FF46DAFB4F8883023F00203A4F8883046 -:105C0000C4E91D55E56778E7B4F88030B3F5A06FB7 -:105C10000ED194F88230204684F88A3001F062FC7C -:105C200063681B6813B10121204698470323237042 -:105C30000023C4E91D339CE704F18B036367012350 -:105C4000C3E72378042B10D1302383F31188204637 -:105C5000FFF7BAFE85F311880321636884F88B503F -:105C600021701B680BB12046984794F88230002BB6 -:105C7000DED084F88B300423237063681B68002B0C -:105C8000D6D0022120469847D2E794F884302046A7 -:105C90001D0603F00F010AD501F0D4FC012804D041 -:105CA00002287FF414AF2B4B9AE72B4B98E701F0B7 -:105CB000BBFCF3E794F88230002B7FF408AF94F834 -:105CC000843013F00F01B3D01A06204602D501F03C -:105CD000DDFFADE701F0CEFFAAE794F88230002B9C -:105CE0007FF4F5AE94F8843013F00F01A0D01B06BA -:105CF000204602D501F0B2FF9AE701F0A3FF97E733 -:105D0000142284F8702083F311882B462A462946F2 -:105D10002046FFF769FE85F31188E9E65DB115229B -:105D200084F8702083F3118800212046D4E91D23D4 -:105D3000FFF75AFEFDE60B2284F8702083F31188EA -:105D40002B462A4629462046FFF760FEE3E700BFC0 -:105D50007C930008749300087893000838B590F895 -:105D600070300446002B3ED0063BDAB20F2A34D8FE -:105D70000F2B32D8DFE803F03731310822323131CE -:105D80003131313131313737856FB0F886309D424E -:105D900014D2C3681B8AB5FBF3F203FB12556DB92D -:105DA000302383F311882B462A462946FFF72EFE1F -:105DB00085F311880A2384F870300EE0142384F8E8 -:105DC0007030302383F31188002320461A46194689 -:105DD000FFF70AFE002383F3118838BDC36F03B1B8 -:105DE00098470023E7E70021204601F037FF002114 -:105DF000204601F027FF63681B6813B10621204687 -:105E000098470623D7E7000010B590F87030044695 -:105E1000142B29D017D8062B05D001D81BB110BDE3 -:105E2000093B022BFBD80021204601F017FF00217F -:105E3000204601F007FF63681B6813B10621204666 -:105E40009847062319E0152BE9D10B2380F8703011 -:105E5000302383F3118800231A461946FFF7D6FD35 -:105E6000002383F31188DAE7C3689B695B68002B22 -:105E7000D5D1C36F03B19847002384F87030CEE7C3 -:105E80000023826880F8243083691B6899689142F6 -:105E9000FBD25A680360426010605860704700008F -:105EA0000023826880F8243083691B6899689142D6 -:105EB000FBD85A6803604260106058607047000069 -:105EC00008B50846302383F3118891F82430032B5A -:105ED00005D0042B0DD02BB983F3118808BD8B6A34 -:105EE00000221A604FF0FF338362FFF7C9FF0023DF -:105EF000F2E7D1E9003213605A60F3E7034610B5C8 -:105F00001B68984203D09C688A689442F8D25A6809 -:105F10000B604A601160596010BD0000FFF7B0BF10 -:105F2000064BD96881F824001868026853601A602B -:105F30000122D86080F82420FAF764BA4046002095 -:105F40000C4B30B5DD684B1C87B004460FD02B4698 -:105F5000094A684600F0B6F92046FFF7E1FF009BCA -:105F600013B1684600F0B8F9A86A07B030BDFFF772 -:105F7000D7FFF9E740460020C15E0008044B1A68CD -:105F8000DB6890689B68984294BF002001207047AE -:105F900040460020094B10B51C68D8682268536041 -:105FA0001A600122DC6084F82420FFF779FF0146A3 -:105FB0002046BDE81040FAF725BA00BF4046002051 -:105FC000044B1A68DB6892689B689A4201D9FFF714 -:105FD000E1BF70474046002038B50123084C00253A -:105FE0002370656002F062FB02F088FB05490648F9 -:105FF00002F05EFC0223237085F3118838BD00BFD8 -:10600000E8480020849300084046002000F09AB938 -:10601000EFF3118020B9EFF30583302282F311886A -:106020007047000010B530B9EFF30584C4F30804DD -:1060300014B180F3118810BDFFF7C2FF84F31188FB -:10604000F9E70000034A516853685B1A9842FBD88D -:10605000704700BF001000E08B604B630023CA61F3 -:1060600000F128020B6302230A618B8401238861FB -:1060700081F8263001F11003C26A4A611360C362DD -:1060800001F12C030846CB6270470000D0E90131D2 -:10609000026841F8183CA1F19C033839CB600369D0 -:1060A00041F8243C436941F8203C034B41F8043C4F -:1060B000C3680248FFF7D0BF1D0400084046002017 -:1060C00008B5FFF7E3FFBDE80840FFF727BF000072 -:1060D00038B50E4BDC6804F12C05A062E06AA842DA -:1060E0000FD194F826303BB994F825309B0702BFB6 -:1060F000D4E9043213605A600F20BDE83840FFF73E -:106100000FBF0368E362FFF709FFE7E7404600209F -:10611000302383F31188FFF7DBBF000008B5014689 -:10612000302383F311880820FFF70AFF002383F34D -:10613000118808BD054BDB6821B10360986203201C -:10614000FFF7FEBE4FF0FF30704700BF4046002013 -:1061500003682BB10022026018469962FFF7DEBE89 -:1061600070470000064BDB6839B1426818605A601E -:10617000136043600420FFF7E3BE4FF0FF30704729 -:10618000404600200368984206D01A6802605060BA -:1061900018469962FFF7C2BE7047000038B5044642 -:1061A0000D462068844200D138BD036823605C60DE -:1061B0008562FFF7B3FEF4E7036810B59C68A2425E -:1061C0000CD85C688A600B604C60216059609968EB -:1061D0008A1A9A604FF0FF33836010BD121B1B6850 -:1061E000ECE700000A2938BF0A2170B504460D46C5 -:1061F0000A26601902F054FA02F03CFA041BA54288 -:1062000003D8751C04462E46F3E70A2E04D9012054 -:10621000BDE8704002F014BC70BD0000F8B5144B2E -:106220000D460A2A4FF00A07D96103F11001826076 -:1062300038BF0A224160196914460160486018613C -:10624000A81802F01DFA02F015FA431B0646A342F5 -:1062500006D37C1C28192746354602F021FAF2E7BE -:106260000A2F04D90120BDE8F84002F0E9BBF8BDCF -:1062700040460020F8B506460D4602F0FBF90F4AED -:10628000134653F8107F9F4206D12A4601463046F6 -:10629000BDE8F840FFF7C2BFD169BB68441A2C19AA -:1062A00028BF2C46A34202D92946FFF79BFF22466E -:1062B00031460348BDE8F840FFF77EBF4046002066 -:1062C00050460020C0E90323002310B45DF8044BBE -:1062D0004361FFF7CFBF000010B5194C2369984206 -:1062E0000DD08168D0E9003213605A609A680A4480 -:1062F0009A60002303604FF0FF33A36110BD026872 -:10630000234643F8102F53600022026022699A420C -:1063100003D1BDE8104002F0BDB9936881680B4419 -:10632000936002F0A7F92269E1699268441AA242D7 -:10633000E4D91144BDE81040091AFFF753BF00BF6C -:10634000404600202DE9F047DFF8BC8008F1100737 -:106350002C4ED8F8105002F08DF9D8F81C40AA68DD -:10636000031B9A423ED814444FF00009D5E900328D -:10637000C8F81C4013605A60C5F80090D8F8103077 -:10638000B34201D102F086F989F31188D5E90331CE -:1063900028469847302383F311886B69002BD8D0A7 -:1063A00002F068F96A69A0EB040982464A450DD2F9 -:1063B000022002F045FB0022D8F81030B34208D189 -:1063C00051462846BDE8F047FFF728BF121A22447D -:1063D000F2E712EB09092946384638BF4A46FFF76B -:1063E000EBFEB5E7D8F81030B34208D01444C8F833 -:1063F0001C00211AA960BDE8F047FFF7F3BEBDE815 -:10640000F08700BF504600204046002010B560B91C -:10641000074804790368053C9B6818BF0124984726 -:1064200008B144F00404204610BD0124FBE700BF7E -:10643000A4360020FFF7EABF2DE9F047884617464B -:106440009A460446B0B90D4E3579052D05D0032482 -:106450000DE0013D15F0FF050ED032685346394678 -:106460003046D2F814904246C8470028F1D1204661 -:10647000BDE8F0870424FAE70124F8E7A4360020F9 -:106480002DE9F047884617469A460446B0B90D4EA6 -:106490003579052D05D003240DE0013D15F0FF05EC -:1064A0000ED03268534639463046D2F818904246EC -:1064B000C8470028F1D12046BDE8F0870424FAE758 -:1064C0000124F8E7A436002037B50C46154670B90C -:1064D00051B101290BD10748694603681B6A9847E7 -:1064E00010B9019B04462B60204603B030BD042444 -:1064F000FAE700BFA436002000207047FEE7000046 -:10650000704700004FF0FF30704700004B68436059 -:106510008B688360CB68C3600B6943614B6903621E -:106520008B6943620B6803607047000008B53C4B01 -:1065300040F2FF713B48D3F888200A43C3F8882013 -:10654000D3F8882022F4FF6222F00702C3F88820E3 -:10655000D3F88820D3F8E0200A43C3F8E020D3F82A -:1065600008210A43C3F808212F4AD3F808311146FD -:10657000FFF7CCFF00F5806002F11C01FFF7C6FFBA -:1065800000F5806002F13801FFF7C0FF00F5806080 -:1065900002F15401FFF7BAFF00F5806002F17001CB -:1065A000FFF7B4FF00F5806002F18C01FFF7AEFF4A -:1065B00000F5806002F1A801FFF7A8FF00F58060F8 -:1065C00002F1C401FFF7A2FF00F5806002F1E001D3 -:1065D000FFF79CFF00F5806002F1FC01FFF796FFDA -:1065E00002F58C7100F58060FFF790FF01F0E2FB8F -:1065F0000E4BD3F8902242F00102C3F89022D3F858 -:10660000942242F00102C3F894220522C3F8982094 -:106610004FF06052C3F89C20054AC3F8A02008BD83 -:1066200000440258000002589893000800ED00E072 -:106630001F00080308B501F0DFFDFFF7CDFC104B8C -:10664000D3F8DC2042F04002C3F8DC20D3F8042168 -:1066500022F04002C3F80421D3F80431094B1A6830 -:1066600042F008021A601A6842F004021A6000F050 -:1066700035FD00F035FBBDE8084000F0B5B800BFBF -:10668000004402580018024801207047002070475B -:106690007047000002290CD0032904D001290748C3 -:1066A00018BF00207047032A05D8054800EBC20038 -:1066B0007047044870470020704700BF9C95000851 -:1066C000542200205095000870B59AB0054608463F -:1066D000144601A900F0C2F801A8FBF727FB431CF0 -:1066E0000022C6B25B001046C5E9003423700323C4 -:1066F000023404F8013C01ABD1B202348E4201D81D -:106700001AB070BD13F8011B013204F8010C04F833 -:10671000021CF1E708B5302383F311880348FFF723 -:1067200091F8002383F3118808BD00BFF0480020D2 -:1067300090F8803003F01F02012A07D190F88120E1 -:106740000B2A03D10023C0E91D3315E003F06003D9 -:10675000202B08D1B0F884302BB990F88120212A61 -:1067600003D81F2A04D8FFF74FB8222AEBD0FAE744 -:10677000034A426707228267C3670120704700BF50 -:106780004B22002007B5052917D8DFE801F01916BC -:1067900003191920302383F31188104A0121019035 -:1067A000FFF7F8F8019802210D4AFFF7F3F80D48BA -:1067B000FFF714F8002383F3118803B05DF804FB9E -:1067C000302383F311880748FEF7DEFFF2E730231A -:1067D00083F311880348FEF7F5FFEBE7F094000818 -:1067E00014950008F048002038B50C4D0C4C2A4692 -:1067F0000C4904F10800FFF767FF05F1CA0204F134 -:1068000010000949FFF760FF05F5CA7204F118008E -:106810000649BDE83840FFF757BF00BFC8610020F8 -:1068200054220020CC940008D9940008E494000875 -:1068300070B5044608460D46FBF778FAC6B2204606 -:10684000013403780BB9184670BD32462946FBF770 -:1068500059FA0028F3D10120F6E700002DE9F84F9E -:1068600005460C46FBF762FA2C49C6B22846FFF7EC -:10687000DFFF08B10336F6B229492846FFF7D8FFF3 -:1068800008B11036F6B2632E0DD8DFF89080DFF82D -:106890009090244FDFF894A0DFF894B02E7846B99A -:1068A0002670BDE8F88F29462046BDE8F84F02F073 -:1068B00045BA252E2ED1072241462846FBF722FA5B -:1068C00070B9DBF8003007350A3444F80A3CDBF8CD -:1068D000043044F8063CBBF8083024F8023CDDE7FD -:1068E000082249462846FBF70DFA98B9A21C0E4B20 -:1068F000197802320909C95D02F8041C13F8011B5A -:1069000001F00F015345C95D02F8031CF0D11834A2 -:106910000835C3E7013504F8016BBFE7BC950008F3 -:10692000E4940008CF95000800E8F11F0CE8F11F7F -:10693000C4950008BFF34F8F044B1A695107FCD16F -:10694000D3F810215207F8D1704700BF0020005241 -:1069500008B50D4B1B78ABB9FFF7ECFF0B4BDA68B2 -:10696000D10704D50A4A5A6002F188325A60D3F836 -:106970000C21D20706D5064AC3F8042102F1883259 -:10698000C3F8042108BD00BF266400200020005287 -:106990002301674508B5114B1B78F3B9104B1A69F1 -:1069A000510703D5DA6842F04002DA60D3F81021CB -:1069B000520705D5D3F80C2142F04002C3F80C2150 -:1069C000FFF7B8FF064BDA6842F00102DA60D3F84D -:1069D0000C2142F00102C3F80C2108BD26640020FE -:1069E000002000520F289ABF00F58060400400206C -:1069F000704700004FF400307047000010207047CF -:106A00000F2808B50BD8FFF7EDFF00F5003302683B -:106A1000013204D104308342F9D1012008BD0020A5 -:106A2000FCE700000F2838B505463FD8FFF782FF86 -:106A30001F4CFFF78DFF4FF0FF3307286361C4F849 -:106A400014311DD82361FFF775FF030243F02403BF -:106A5000E360E36843F08003E36023695A07FCD4F2 -:106A60002846FFF767FFFFF7BDFF4FF4003100F046 -:106A70008FFA2846FFF78EFFBDE83840FFF7C0BF0A -:106A8000C4F81031FFF756FFA0F108031B0243F0D2 -:106A90002403C4F80C31D4F80C3143F08003C4F85B -:106AA0000C31D4F810315B07FBD4D9E7002038BD96 -:106AB000002000522DE9F84F05460C46104645EAE5 -:106AC0000203DE0602D00020BDE8F88F20F01F0090 -:106AD000DFF8BCB0DFF8BCA0FFF73AFF04EB00081A -:106AE000444503D10120FFF755FFEDE72022294659 -:106AF000204602F0A7F810B920352034F0E72B46E5 -:106B000005F120021F68791CDDD104339A42F9D1C6 -:106B100005F178431B481C4EB3F5801F1B4B38BF53 -:106B2000184603F1F80332BFD946D1461E46FFF797 -:106B300001FF0760A5EB040C336804F11C0143F06E -:106B400002033360231FD9F8007017F00507FAD14C -:106B500053F8042F8B424CF80320F4D1BFF34F8F2E -:106B6000FFF7E8FE4FF0FF3320222146036028465E -:106B7000336823F00203336002F064F80028BBD0CE -:106B80003846B0E7142100520C2000521420005265 -:106B9000102000521021005210B5084C237828B163 -:106BA0001BB9FFF7D5FE0123237010BD002BFCD0CD -:106BB0002070BDE81040FFF7EDBE00BF2664002046 -:106BC0002DE9F04F0D4685B0814658B111F00D0604 -:106BD00014BF2022082211F00803019304D0431EA1 -:106BE000034269D0002435E0002E37D009F11F019F -:106BF00021F01F094FF00108314F05F00403DFF8C1 -:106C0000CCA005EA080BBBF1000F32D07869C007B1 -:106C10002FD408F101080C37B8F1060FF3D19EB953 -:106C2000284D4946A819019201F08AFD0446002822 -:106C300039D12036019AA02EF3D1494601F080FDCA -:106C4000044600282FD1019A49461F4801F078FDDB -:106C5000044660BB204605B0BDE8F08F0029C9D1CD -:106C600001462846029201F06BFD0446D8B9029A0B -:106C7000C0E713B178694107CBD5AC0702D5786975 -:106C80008007C6D5019911B178690107C1D5494678 -:106C90000AEB4810CDE9022301F052FD0446DDE97C -:106CA00002230028B5D04A460021204601E04A468A -:106CB0000021FBF743F8CDE70246002E96D199E775 -:106CC000E0950008686400202864002048640020E3 -:106CD0000021FFF775BF00000121FFF771BF000021 -:106CE00070B5144D0124144E40F2FF3200210120F2 -:106CF000FBF724F806EB441001342A6955F80C1F01 -:106D000001F00AFD062CF5D137254FF4C05420467A -:106D1000FFF7E2FF014628B122460848BDE870406F -:106D200001F0FABCC4EBC404013D4FEAD404EED137 -:106D300070BD00BFE0950008486400202864002072 -:106D40000421FFF73DBF00004843FFF7C1BF00002B -:106D500008B101F067BD7047B0F5805F10B504461B -:106D600007D8FFF7EDFF28B92046BDE81040FFF730 -:106D7000AFBF002010BD0000FFF7EABF08B501F06B -:106D800067FE034AD2E90032C01842EB010108BD98 -:106D900008650020434BD3E900232DE9F341134359 -:106DA0007CD0FFF7EBFF404A00230027F9F744FBB4 -:106DB00006460D463D4A0023F9F73EFB00231446E4 -:106DC00030462946394AF9F737FB4FF461613C23D5 -:106DD000ADF80170B4FBF1F5B4FBF3F601FB15411E -:106DE00003FB16464624B1FBF3F1314BF6B28DF8A6 -:106DF000004098423CD84FF0640C4FF4C87EA30783 -:106E000004F26C7225D1B2FBFCF30CFB132313BB11 -:106E1000B2FBFEF30EFB1322B2FA82F35B0903F21C -:106E20006D18621C8045D2B217D90FB18DF80040A1 -:106E30000022204C4FF00C0C17460CFB0343D4B23D -:106E4000013213F804C084450CD8A0EB0C000127D4 -:106E5000F5E70023E3E70123E1E7A0EB0800144690 -:106E60000127CCE70FB18DF80140431C8DF80230AB -:106E70009DF80100431C9DF800005038400640EA90 -:106E800043509DF8023040EA034040EA560040EA91 -:106E9000C52040EA411002B0BDE8F0814FF4041073 -:106EA000F9E700BF0865002040420F008051010053 -:106EB00090230B00289600080244074BD2B210B56D -:106EC000904200D110BD441C00B253F8200041F89C -:106ED000040BE0B2F4E700BF504000580E4B30B551 -:106EE0001C6F240405D41C6F1C671C6F44F4004401 -:106EF0001C670A4C02442368D2B243F480732360B7 -:106F0000074B904200D130BD441C51F8045B00B2E5 -:106F100043F82050E0B2F4E7004402580048025819 -:106F20005040005807B5012201A90020FFF7C4FF17 -:106F3000019803B05DF804FB13B50446FFF7F2FFB8 -:106F4000A04205D0012201A900200194FFF7C6FF4D -:106F500002B010BD10B56424013C4FF47A70FFF705 -:106F6000DDF814F0FF04F7D1084B4FF080721424C1 -:106F70009A6103F5805308229A61013C4FF47A70BC -:106F8000FFF7CCF814F0FF04F7D110BD0000025851 -:106F90000144BFF34F8F064B884204D3BFF34F8F9A -:106FA000BFF36F8F7047C3F85C022030F4E700BF77 -:106FB00000ED00E00144BFF34F8F064B884204D33D -:106FC000BFF34F8FBFF36F8F7047C3F8700220304D -:106FD000F4E700BF00ED00E070B5054616460C462C -:106FE00001201021FFF7B0FE286046733CB1204617 -:106FF00036B1FFF7A5FE2B68186000B19C6070BD2C -:10700000FFF76AFEF7E7000070B50E461546044626 -:1070100000B30B6843608368934210D213B10068D9 -:10702000FFF796FE637B28462BB1FFF789FE2060B1 -:1070300020B9A06070BDFFF74FFEF8E7A56020689B -:1070400005F11F01306021F01F01FFF7A1FF0120B2 -:107050002073EFE70120EDE710B5044640B100686A -:10706000884205D1606808B1FAF742FE0023237315 -:1070700010BD000070B50E461546044620B3836867 -:107080009A4210D913B10068FFF762FE637B28466D -:107090002BB1FFF755FE206020B9A06070BDFFF74F -:1070A0001BFEF8E7A560316819B12A462068FAF797 -:1070B0001FFE206805F11F01306021F01F01FFF75E -:1070C00079FF01202073E9E70120E7E720B1036899 -:1070D0008B4204BF0023037370470000034B1A6800 -:1070E0001AB9034AD2F8D0241A60704710650020FC -:1070F0000040025808B5FFF7F1FF024B1868C0F3D3 -:10710000806008BD1065002070B5BFF34F8FBFF3DE -:107110006F8F1A4A0021C2F85012BFF34F8FBFF38E -:107120006F8F536943F400335361BFF34F8FBFF345 -:107130006F8FC2F88410BFF34F8FD2F8803043F6C0 -:10714000E074C3F3C900C3F34E335B0103EA0406E2 -:10715000014646EA81750139C2F86052F9D2203BF6 -:1071600013F1200FF2D1BFF34F8F536943F48033F3 -:107170005361BFF34F8FBFF36F8F70BD00ED00E021 -:10718000FEE70000214B2248224A70B5904237D3D7 -:10719000214BC11EDA1C121A22F003028B4238BFA7 -:1071A00000220021FAF7CAFD1C4A0023C2F88430ED -:1071B000BFF34F8FD2F8803043F6E074C3F3C900B9 -:1071C000C3F34E335B0103EA0406014646EA8175C8 -:1071D0000139C2F86C52F9D2203B13F1200FF2D1E1 -:1071E000BFF34F8FBFF36F8FBFF34F8FBFF36F8F1F -:1071F0000023C2F85032BFF34F8FBFF36F8F70BDC3 -:1072000053F8041B40F8041BC0E700BF9097000828 -:1072100020670020206700202067002000ED00E0AC -:10722000074BD3F8D81021EA0001C3F8D810D3F8DF -:10723000002122EA0002C3F80021D3F80031704790 -:107240000044025870B5D0E9244300224FF0FF35C6 -:107250009E6804EB42135101D3F80009002805DAB7 -:10726000D3F8000940F08040C3F80009D3F8000BC0 -:10727000002805DAD3F8000B40F08040C3F8000B7B -:10728000013263189642C3F80859C3F8085BE0D28C -:107290004FF00113C4F81C3870BD0000890141F0A3 -:1072A0002001016103699B06FCD41220FEF7CABECF -:1072B00010B50A4C2046FEF74BFB094BC4F8903042 -:1072C000084BC4F89430084C2046FEF741FB074BAE -:1072D000C4F89030064BC4F8943010BD14650020FB -:1072E0000000084064960008B065002000000440DB -:1072F0007096000870B503780546012B5CD1434BAE -:10730000D0F89040984258D1414B0E216520D3F8D7 -:10731000D82042F00062C3F8D820D3F8002142F010 -:107320000062C3F80021D3F80021D3F8802042F096 -:107330000062C3F88020D3F8802022F00062C3F8F6 -:107340008020D3F8803000F041FF324BE360324BB5 -:10735000C4F800380023D5F89060C4F8003EC0237C -:1073600023604FF40413A3633369002BFCDA012379 -:107370000C203361FEF766FE3369DB07FCD4122074 -:10738000FEF760FE3369002BFCDA00262846A66073 -:10739000FFF758FF6B68C4F81068DB68C4F814681E -:1073A000C4F81C6883BB1D4BA3614FF0FF336361BE -:1073B000A36843F00103A36070BD194B9842C9D183 -:1073C000134B4FF08060D3F8D82042F00072C3F81E -:1073D000D820D3F8002142F00072C3F80021D3F87E -:1073E0000021D3F8802042F00072C3F88020D3F847 -:1073F000802022F00072C3F88020D3F88030FFF79D -:107400000FFF0E214D209EE7064BCDE714650020AF -:10741000004402584014004003002002003C30C0E9 -:10742000B0650020083C30C0F8B5D0F89040054663 -:1074300000214FF000662046FFF730FFD5F894108A -:1074400000234FF001128F684FF0FF30C4F834383A -:10745000C4F81C2804EB431201339F42C2F80069B0 -:10746000C2F8006BC2F80809C2F8080BF2D20B6828 -:10747000D5F89020C5F8983063621023136116691F -:1074800016F01006FBD11220FEF7DCFDD4F8003810 -:1074900023F4FE63C4F80038A36943F4402343F0A7 -:1074A0001003A3610923C4F81038C4F814380B4B37 -:1074B000EB604FF0C043C4F8103B094BC4F8003BED -:1074C000C4F81069C4F80039D5F8983003F11002F7 -:1074D00043F48013C5F89820A362F8BD40960008D5 -:1074E00040800010D0F8902090F88A10D2F8003830 -:1074F00023F4FE6343EA0113C2F80038704700002A -:107500002DE9F84300EB8103D0F890500C468046FB -:10751000DA680FFA81F94801166806F00306731E4F -:10752000022B05EB41134FF0000194BFB604384E17 -:10753000C3F8101B4FF0010104F1100398BF06F1CE -:10754000805601FA03F3916998BF06F500460029B9 -:107550003AD0578A04F15801374349016F50D5F8A2 -:107560001C180B430021C5F81C382B180127C3F841 -:107570001019A7405369611E9BB3138A928B9B0815 -:10758000012A88BF5343D8F89820981842EA034349 -:1075900001F140022146C8F89800284605EB820216 -:1075A0005360FFF77BFE08EB8900C3681B8A43EA40 -:1075B000845348341E4364012E51D5F81C381F43B0 -:1075C000C5F81C78BDE8F88305EB4917D7F8001B10 -:1075D00021F40041C7F8001BD5F81C1821EA030369 -:1075E000C0E704F13F030B4A2846214605EB83031D -:1075F0005A60FFF753FE05EB4910D0F8003923F429 -:107600000043C0F80039D5F81C3823EA0707D7E74C -:107610000080001000040002D0F894201268C0F826 -:107620009820FFF70FBE00005831D0F89030490184 -:107630005B5813F4004004D013F4001F0CBF022069 -:10764000012070474831D0F8903049015B5813F45D -:10765000004004D013F4001F0CBF0220012070472B -:1076600000EB8101CB68196A0B6813604B685360AB -:107670007047000000EB810330B5DD68AA6913682C -:10768000D36019B9402B84BF402313606B8A146800 -:10769000D0F890201C4402EB4110013C09B2B4FB2D -:1076A000F3F46343033323F0030343EAC44343F097 -:1076B000C043C0F8103B2B6803F00303012B0ED12D -:1076C000D2F8083802EB411013F4807FD0F8003B69 -:1076D00014BF43F0805343F00053C0F8003B02EB6B -:1076E0004112D2F8003B43F00443C2F8003B30BDE6 -:1076F0002DE9F041D0F8906005460C4606EB4113A9 -:10770000D3F8087B3A07C3F8087B08D5D6F81438B5 -:107710001B0704D500EB8103DB685B689847FA0719 -:107720001FD5D6F81438DB071BD505EB8403D968C1 -:10773000CCB98B69488A5A68B2FBF0F600FB162276 -:107740008AB91868DA6890420DD2121AC3E9002487 -:10775000302383F3118821462846FFF78BFF84F3FB -:107760001188BDE8F081012303FA04F26B8923EA52 -:1077700002036B81CB68002BF3D021462846BDE87D -:10778000F041184700EB81034A0170B5DD68D0F87D -:1077900090306C692668E66056BB1A444FF40020AE -:1077A000C2F810092A6802F00302012A0AB20ED1B7 -:1077B000D3F8080803EB421410F4807FD4F80009D2 -:1077C00014BF40F0805040F00050C4F8000903EBB3 -:1077D0004212D2F8000940F00440C2F80009012228 -:1077E000D3F8340802FA01F10143C3F8341870BD2C -:1077F00019B9402E84BF4020206020681A442E8A88 -:107800008419013CB4FBF6F440EAC44040F0005057 -:10781000C6E700002DE9F843D0F8906005460C4615 -:107820004F0106EB4113D3F8088918F0010FC3F894 -:1078300008891CD0D6F81038DB0718D500EB810377 -:10784000D3F80CC0DCF81430D3F800E0DA689645C1 -:1078500030D2A2EB0E024FF000091A60C3F8049078 -:10786000302383F31188FFF78DFF89F3118818F017 -:10787000800F1DD0D6F834380126A640334217D0E9 -:1078800005EB84030134D5F89050D3F80CC0E4B272 -:107890002F44DCF8142005EB0434D2F800E05168E2 -:1078A000714514D3D5F8343823EA0606C5F8346890 -:1078B000BDE8F883012303FA01F2038923EA0203F6 -:1078C0000381DCF80830002BD1D09847CFE7AEEB2E -:1078D0000103BCF81000834228BF0346D7F81809FB -:1078E00080B2B3EB800FE3D89068A0F1040959F897 -:1078F000048FC4F80080A0EB09089844B8F1040F85 -:10790000F5D818440B4490605360C8E72DE9F84F50 -:10791000D0F8905004466E69AB691E4016F480584A -:107920006E6103D0BDE8F84FFEF782B8002E12DA80 -:10793000D5F8003E9B0705D0D5F8003E23F00303A1 -:10794000C5F8003ED5F80438204623F00103C5F8F9 -:107950000438FEF79BF8370505D52046FFF772FC83 -:107960002046FEF781F8B0040CD5D5F8083813F09E -:10797000060FEB6823F470530CBF43F4105343F429 -:10798000A053EB6031071BD56368DB681BB9AB699B -:1079900023F00803AB612378052B0CD1D5F8003E0A -:1079A0009A0705D0D5F8003E23F00303C5F8003E42 -:1079B0002046FEF76BF86368DB680BB120469847FA -:1079C000F30200F1BA80B70226D5D4F890900027D0 -:1079D0004FF0010A09EB4712D2F8003B03F44023B1 -:1079E000B3F5802F11D1D2F8003B002B0DDA62895C -:1079F0000AFA07F322EA0303638104EB8703DB68D7 -:107A0000DB6813B13946204698470137D4F89430E3 -:107A1000FFB29B689F42DDD9F00619D5D4F89000DB -:107A2000026AC2F30A1702F00F0302F4F012B2F571 -:107A3000802F00F0CA80B2F5402F09D104EB8303F8 -:107A4000002200F58050DB681B6A974240F0B0804E -:107A50003003D5F8185835D5E90303D50021204661 -:107A6000FFF746FEAA0303D501212046FFF740FE9B -:107A70006B0303D502212046FFF73AFE2F0303D5FF -:107A800003212046FFF734FEE80203D504212046F7 -:107A9000FFF72EFEA90203D505212046FFF728FE99 -:107AA0006A0203D506212046FFF722FE2B0203D5EA -:107AB00007212046FFF71CFEEF0103D508212046D1 -:107AC000FFF716FE700340F1A780E90703D50021F8 -:107AD0002046FFF79FFEAA0703D501212046FFF7A6 -:107AE00099FE6B0703D502212046FFF793FE2F076F -:107AF00003D503212046FFF78DFEEE0603D50421B2 -:107B00002046FFF787FEA80603D505212046FFF78C -:107B100081FE690603D506212046FFF77BFE2A0673 -:107B200003D507212046FFF775FEEB0574D52046E7 -:107B30000821BDE8F84FFFF76DBED4F890904FF0E4 -:107B4000000B4FF0010AD4F894305FFA8BF79B6872 -:107B50009F423FF638AF09EB4713D3F8002902F4F0 -:107B60004022B2F5802F20D1D3F80029002A1CDA58 -:107B7000D3F8002942F09042C3F80029D3F8002935 -:107B8000002AFBDB3946D4F89000FFF787FB2289F7 -:107B90000AFA07F322EA0303238104EB8703DB6875 -:107BA0009B6813B13946204698470BF1010BCAE791 -:107BB000910701D1D0F80080072A02F101029CBF91 -:107BC00003F8018B4FEA18283FE704EB830300F525 -:107BD0008050DA68D2F818C0DCF80820DCE9001C14 -:107BE000A1EB0C0C00218F4208D1DB689B699A68DD -:107BF0003A449A605A683A445A6029E711F0030FF0 -:107C000001D1D0F800808C4501F1010184BF02F858 -:107C1000018B4FEA1828E6E7BDE8F88F08B503485E -:107C2000FFF774FEBDE8084000F070BF1465002047 -:107C300008B50348FFF76AFEBDE8084000F066BFDC -:107C4000B0650020D0F8903003EB4111D1F8003B33 -:107C500043F40013C1F8003B70470000D0F89030A7 -:107C600003EB4111D1F8003943F40013C1F8003996 -:107C700070470000D0F8903003EB4111D1F8003B81 -:107C800023F40013C1F8003B70470000D0F8903097 -:107C900003EB4111D1F8003923F40013C1F8003986 -:107CA00070470000064BD3F8DC200243C3F8DC2009 -:107CB000D3F804211043C3F80401D3F8043170470A -:107CC000004402583A4B4FF0FF31D3F8802062F065 -:107CD0000042C3F88020D3F8802002F00042C3F8AD -:107CE0008020D3F88020D3F88420C3F88410D3F800 -:107CF00084200022C3F88420D3F88400D86F40F099 -:107D0000FF4040F4FF0040F4DF4040F07F00D867C0 -:107D1000D86F20F0FF4020F4FF0020F4DF4020F077 -:107D20007F00D867D86FD3F888006FEA40506FEAB9 -:107D30005050C3F88800D3F88800C0F30A00C3F895 -:107D40008800D3F88800D3F89000C3F89010D3F8D7 -:107D50009000C3F89020D3F89000D3F89400C3F8B3 -:107D60009410D3F89400C3F89420D3F89400D3F877 -:107D70009800C3F89810D3F89800C3F89820D3F867 -:107D80009800D3F88C00C3F88C10D3F88C00C3F89B -:107D90008C20D3F88C00D3F89C00C3F89C10D3F847 -:107DA0009C10C3F89C20D3F89C3000F0D7B900BFDA -:107DB0000044025808B50122534BC3F80821534B25 -:107DC000D3F8F42042F00202C3F8F420D3F81C21C7 -:107DD00042F00202C3F81C210222D3F81C314C4BA2 -:107DE000DA605A689104FCD54A4A1A6001229A6006 -:107DF000494ADA6000221A614FF440429A61444BCA -:107E00009A699204FCD51A6842F480721A603F4B5A -:107E10001A6F12F4407F04D04FF480321A670022A8 -:107E20001A671A6842F001021A60384B1A68500744 -:107E3000FCD500221A611A6912F03802FBD1012127 -:107E400019604FF0804159605A67344ADA62344A07 -:107E50001A611A6842F480321A602C4B1A68910336 -:107E6000FCD51A6842F480521A601A689204FCD554 -:107E70002C4A2D499A6200225A63196301F57C014C -:107E8000DA6301F5E77199635A64284A1A64284A4B -:107E9000DA621A6842F0A8521A601C4B1A6802F0A3 -:107EA0002852B2F1285FF9D148229A614FF48862D2 -:107EB000DA6140221A621F4ADA641F4A1A651F4AB1 -:107EC0005A651F4A9A6532231E4A1360136803F0ED -:107ED0000F03022BFAD10D4A136943F00303136118 -:107EE000136903F03803182BFAD14FF00050FFF755 -:107EF000D9FE4FF08040FFF7D5FE4FF00040BDE8BF -:107F00000840FFF7CFBE00BF008000510044025878 -:107F10000048025800C000F0020000010000FF010C -:107F2000008890083220600063020901470E0508AE -:107F3000DD0BBF0120000020000001100910E0004F -:107F400000010110002000524FF0B04208B5D2F8F5 -:107F5000883003F00103C2F8883023B1044A136863 -:107F60000BB150689847BDE8084000F0CFBD00BF96 -:107F7000986600204FF0B04208B5D2F8883003F080 -:107F80000203C2F8883023B1044A93680BB1D06869 -:107F90009847BDE8084000F0B9BD00BF98660020D2 -:107FA0004FF0B04208B5D2F8883003F00403C2F8AD -:107FB000883023B1044A13690BB150699847BDE872 -:107FC000084000F0A3BD00BF986600204FF0B0420B -:107FD00008B5D2F8883003F00803C2F8883023B11E -:107FE000044A93690BB1D0699847BDE8084000F096 -:107FF0008DBD00BF986600204FF0B04208B5D2F8A2 -:10800000883003F01003C2F8883023B1044A136AA1 -:108010000BB1506A9847BDE8084000F077BD00BF3B -:10802000986600204FF0B04310B5D3F8884004F4B0 -:108030007872C3F88820A30604D5124A936A0BB15C -:10804000D06A9847600604D50E4A136B0BB1506B8B -:108050009847210604D50B4A936B0BB1D06B984718 -:10806000E20504D5074A136C0BB1506C9847A30581 -:1080700004D5044A936C0BB1D06C9847BDE810400E -:1080800000F044BD986600204FF0B04310B5D3F81F -:10809000884004F47C42C3F88820620504D5164A5F -:1080A000136D0BB1506D9847230504D5124A936D9B -:1080B0000BB1D06D9847E00404D50F4A136E0BB195 -:1080C000506E9847A10404D50B4A936E0BB1D06E45 -:1080D0009847620404D5084A136F0BB1506F984754 -:1080E000230404D5044A936F0BB1D06F9847BDE8C1 -:1080F000104000F00BBD00BF9866002008B5034893 -:10810000FCF70CFDBDE8084000F000BDA4360020DF -:1081100008B50348FCF706FEBDE8084000F0F6BCD1 -:10812000FC38002008B50348FCF7FCFDBDE808401A -:1081300000F0ECBC6839002008B50348FCF7F2FDFC -:10814000BDE8084000F0E2BCD439002008B500F0DA -:108150003FFDBDE8084000F0D9BC0000062108B58D -:10816000084600F033F80621072000F02FF806211A -:10817000082000F02BF80621092000F027F806213E -:108180000A2000F023F80621172000F01FF806212E -:10819000282000F01BF809217A2000F017F80921A7 -:1081A000312000F013F80721322000F00FF80C21E5 -:1081B000262000F00BF80C21272000F007F80C21F6 -:1081C0005220BDE8084000F001B80000090100F1AC -:1081D0006043012203F56143C9B283F8001300F044 -:1081E0001F039A4043099B0003F1604303F5614379 -:1081F000C3F880211A60704708B5FFF763FD00F0EF -:10820000AFFCFDF7C9F9FDF767F9FDF79FFBFDF737 -:1082100071FAFEF73DFABDE8084000F029BA000007 -:1082200030B50433039C0172002104FB0325C160B7 -:10823000C0E90653049B0363059BC0E90000C0E945 -:108240000422C0E90842C0E90A11436330BD0000BE -:108250000022416AC260C0E90411C0E90A226FF03D -:108260000101FDF79BBF0000D0E90432934201D128 -:10827000C2680AB9181D7047002070470369196069 -:108280000021C2680132C260C2691344826993420C -:10829000036124BF436A0361FDF774BF38B5044628 -:1082A0000D46E3683BB162690020131D1268A362AA -:1082B0001344E36207E0237A33B929462046FDF7E9 -:1082C00051FF0028EDDA38BD6FF00100FBE7000038 -:1082D000C368C269013BC360436913448269934226 -:1082E000436124BF436A436100238362036B03B18C -:1082F0001847704770B53023044683F31188866AA7 -:108300003EB9FFF7CBFF054618B186F31188284622 -:1083100070BDA36AE26A13F8015B9342A36202D3C1 -:108320002046FFF7D5FF002383F31188EFE7000015 -:108330002DE9F84F04460E46174698464FF030098F -:1083400089F311880025AA46D4F828B0BBF1000FA4 -:1083500009D141462046FFF7A1FF20B18BF31188D8 -:108360002846BDE8F88FD4E90A12A7EB050B521A8C -:10837000934528BF9346BBF1400F1BD9334601F10B -:10838000400251F8040B914243F8040BF9D1A36A5F -:10839000403640354033A362D4E90A239A4202D3DF -:1083A0002046FFF795FF8AF31188BD42D8D289F3A2 -:1083B0001188C9E730465A46F9F79AFCA36A5E4429 -:1083C0005D445B44A362E7E710B5029C043301728D -:1083D00003FB0421C460C0E906130023C0E90A338B -:1083E000039B0363049BC0E90000C0E90422C0E9C9 -:1083F0000842436310BD0000026A6FF00101C260D1 -:10840000426AC0E904220022C0E90A22FDF7C6BE82 -:10841000D0E904239A4201D1C26822B9184650F823 -:10842000043B0B60704700231846FAE7C36800213D -:10843000C2690133C3604369134482699342436153 -:1084400024BF436A4361FDF79DBE000038B5044672 -:108450000D46E3683BB1236900201A1DA262E26960 -:108460001344E36207E0237A33B929462046FDF737 -:1084700079FE0028EDDA38BD6FF00100FBE700005F -:1084800003691960C268013AC260C2691344826913 -:108490009342036124BF436A036100238362036B39 -:1084A00003B118477047000070B530230D460446ED -:1084B000114683F31188866A2EB9FFF7C7FF10B102 -:1084C00086F3118870BDA36A1D70A36AE26A013346 -:1084D0009342A36204D3E16920460439FFF7D0FF39 -:1084E000002080F31188EDE72DE9F84F04460D4692 -:1084F000904699464FF0300A8AF311880026B34619 -:10850000A76A4FB949462046FFF7A0FF20B187F37D -:1085100011883046BDE8F88FD4E90A073A1AA8EB6B -:108520000607974228BF1746402F1BD905F1400385 -:1085300055F8042B9D4240F8042BF9D1A36A40362C -:108540004033A362D4E90A239A4204D3E169204666 -:108550000439FFF795FF8BF311884645D9D28AF38A -:108560001188CDE729463A46F9F7C2FBA36A3D4494 -:108570003E443B44A362E5E7D0E904239A4217D185 -:10858000C3689BB1836A8BB1043B9B1A0ED0136006 -:10859000C368013BC360C3691A4483699A4202619C -:1085A00024BF436A03610023836201231846704796 -:1085B0000023FBE701F01F03F0B502F01F0456098A -:1085C0005A1C0123B6EB511F50F8265003FA02F350 -:1085D0004FEA511703F1FF333DBF50F82720C4F194 -:1085E0002000134003EA05003BBF03FA00F225FA1E -:1085F00004F0E0401043F0BD70B57E227F210546B7 -:10860000FFF7D8FF18B1012819D0002070BD3E2215 -:1086100049212846FFF7CEFF2F2204463121284664 -:10862000FFF7C8FF06460134502202365321284680 -:10863000B440FFF7BFFF093804FA00F0E6E7302244 -:1086400045212846FFF7B6FF01308002DEE7000033 -:1086500090F8D63090F8D7201B0403EB026390F813 -:10866000D42090F8D500134403EB0020704700009D -:1086700000F084BA014B586A704700BF000C0040FC -:10868000034B002258631A610222DA60704700BF70 -:10869000000C0040014B0022DA607047000C0040E3 -:1086A000014B5863704700BF000C0040024B034A67 -:1086B0001A60034A5A6070476466002020670020F1 -:1086C00000000220074B494210B55C68201A0840A0 -:1086D0001968821A8A4203D3A24201D85A6010BD97 -:1086E0000020FCE76466002008B5302383F311887E -:1086F000FFF7E8FF002383F3118808BD0448054B0A -:1087000003600023C0E901330C3000F017B900BF4B -:108710006C660020E9860008CB1D083A23F00703A9 -:10872000591A521A10B4D2080024C0E900438460D8 -:108730000C301C605A605DF8044B00F0FFB800007C -:108740002DE9F74F364FCD1D8846002818BF074644 -:10875000082A4FEAD50538BF082207F10C003C1D56 -:108760009146019000F02CF9019809F10701C9F137 -:10877000000E2246246864B900F02CF93B68CBB3A4 -:1087800008224946E8009847044698B340E9027831 -:1087900030E004EB010CD4F804A00CEA0E0C0AF152 -:1087A0000106ACF1080304EBC6069E42E1D9A6EB34 -:1087B0000C0CB5EBEC0F4FEAEC0BDAD89C421DD257 -:1087C00004F10802AB45A3EB02024FEAE202626049 -:1087D00009D9691CED4303EBC1025D44556025686E -:1087E00043F8315022601C46C3F8048044F8087BEB -:1087F00000F0F0F8204603B0BDE8F08FAA452168EC -:1088000002D111602346EEE7013504EBC50344F8BD -:10881000351003F10801761AF6105E601360F1E777 -:108820006C66002073B50446A0F1080550F8080CEA -:1088300054F8043C061D0C3007330190DB0844F863 -:10884000043C00F0BDF8334601989E421A6801D0FE -:10885000AB4228D20AB1954225D244F8082C54F8EC -:10886000042C1D60013254F8081C05EBC206B1420D -:1088700006D14E68324444F8042C0A6844F8082CA7 -:108880005E68711C03EBC1018D4207D154F8042CC2 -:10889000013232445A6054F8082C1A6002B0BDE824 -:1088A000704000F097B81346CFE70000FEE70000E5 -:1088B00070B51E4B0025044686B058600E46056311 -:1088C000816300F0FBF804F12803A5606563C4E947 -:1088D0000A3304F11003C4E904334FF0FF33C4E951 -:1088E0000044C4E90635FFF7C5FE2B46024604F1F5 -:1088F0003C012046C4E9082380230D4A6567FDF743 -:10890000ABFB7368E0600B4A03620123009280F8BE -:1089100024306846F26801923269CDE90223064BA1 -:10892000CDE90435FDF7CCFB06B070BDE84800206A -:10893000849600087C960008AD8800080023C0E9F2 -:10894000000083600361704770B51C4B0546846866 -:10895000DE685CB3B44213D103690133036170BDB7 -:10896000A36094F8243083B1062B15D1A06A214668 -:10897000D4E9003213605A60FDF7C0FAA36A9C681C -:10898000B368A2689A42EBD306E0D4E900322046ED -:1089900013605A60FDF7C2FA28463146FDF7AEFA79 -:1089A000B5620620BDE87040FDF7BABA036986607B -:1089B00001330361336BC3603063D0E7404600206E -:1089C00008B5302383F31188FFF7BEFF002383F33C -:1089D000118808BD194BD96883688B4210B520D126 -:1089E000302383F311880269013A0261B2B9046845 -:1089F000C368A0420B631ED04A6B9BB901238A60F7 -:108A0000036103681A68026050601A6B8360C26079 -:108A100018631846FDF782FAFDF7D2FA002383F3B4 -:108A2000118810BD1C68A34203D0A468A24238BFBD -:108A30002246DB68E1E78260F0E700BF40460020A5 -:108A4000024A536B18435063704700BF40460020F2 -:108A500070B5104E82B0FDF7DBFA0546FFF70AFE4F -:108A6000326803469042336037BF0B4A0A49516867 -:108A7000146836BF0131D1E900415160041928461C -:108A800041F100010191FDF7CDFA2046019902B0B4 -:108A900070BD00BF8C66002090660020EFF3098354 -:108AA000054968334A6B22F001024A6383F309885F -:108AB000002383F31188704700EF00E0302080F33B -:108AC000118862B60D4B0E4AD96821F4E0610904A1 -:108AD000090C0A430B49DA60D3F8FC2042F080729B -:108AE000C3F8FC20084AC2F8B01F116841F0010128 -:108AF00011602022DA7783F82200704700ED00E051 -:108B00000003FA0555CEACC5001000E0302310B5C7 -:108B100083F311880E4B5B6813F4006314D0F1EEFD -:108B2000103AEFF309844FF08073683CE361094B1E -:108B3000DB6B236684F30988FDF720FA10B1064B3E -:108B4000A36110BD054BFBE783F31188F9E700BF74 -:108B500000ED00E000EF00E02F0400083204000800 -:108B60000023054A19460133102BC2E9001102F116 -:108B70000802F8D1704700BF98660020114BD3F867 -:108B8000E82042F00802C3F8E820D3F8102142F0B0 -:108B90000802C3F810210C4AD3F81031D36B43F00C -:108BA0000803D363C722094B9A624FF0FF32DA629F -:108BB00000229A615A63DA605A6001225A611A608F -:108BC000704700BF004402580010005C000C0040D9 -:108BD000094A08B51169D3680B40D9B29B076FEAFF -:108BE0000101116107D5302383F31188FDF70EFAD7 -:108BF000002383F3118808BD000C0040FEF7A8B8DD -:108C0000012838BF012010B504462046FEF760F861 -:108C100030B900F007F808B900F00CF88047F4E725 -:108C200010BD0000024B1868BFF35B8F704700BF98 -:108C30001867002008B5062000F056F80120FDF75F -:108C40005DFC000010B501390244904201D10020C2 -:108C500005E0037811F8014FA34201D0181B10BDA5 -:108C60000130F2E7884210B501EB020402D98442D8 -:108C7000234607D8431EA14208D011F8012B03F860 -:108C8000012FF8E7024401468A4200D110BD13F8D3 -:108C9000014D02F8014DF7E71F2938B504460D468E -:108CA00004D9162303604FF0FF3038BD426C12B177 -:108CB00052F821304BB9204600F030F82A460146E0 -:108CC0002046BDE8384000F017B8012B0AD0591CE7 -:108CD00003D1162303600120E7E7002442F8254072 -:108CE000284698470020E0E7024B01461868FFF746 -:108CF000D3BF00BF7422002038B5074D00230446BF -:108D0000084611462B60FDF7FDFB431C02D12B6882 -:108D100003B1236038BD00BF1C670020FDF7ECBB2A -:108D2000C9B2034610F8012B1AB18A42F9D118468C -:108D30007047002918BF0023F9E70000034611F827 -:108D4000012B03F8012B002AF9D1704710B5013926 -:108D5000034632B111F8014F03F8014B013A002CE0 -:108D6000F7D11A440021934200D110BD03F8011B32 -:108D7000F9E700004D4435002D2D0A002F61726483 -:108D80007570696C6F742E6162696E002F61726418 -:108D90007570696C6F742D7665726966792E616283 -:108DA000696E002F6172647570696C6F742D666CEA -:108DB0006173682E6162696E002F617264757069FB -:108DC0006C6F742D666C61736865642E6162696E88 -:108DD000000000000000000000000000090F000873 -:108DE000A50F000855110008DD0F00089D0F0008B1 -:108DF0000000000000000000050F0008B10F00088F -:108E00008D110008010F00080D0F000853544D3359 -:108E10003248373F3F3F0053544D33324837337861 -:108E20002F3732780053544D3332483734332F378D -:108E300035332F373530000001105A000310590028 -:108E400001205800032056002F0000005375636373 -:108E500065737366756C6C79206D6F756E7465647F -:108E6000205344436172642028736C6F77646F777A -:108E70006E3D2575290A0000EB7690455846415411 -:108E800020202000464154333220202000000000E2 -:108E90002A3A3C3E7C223F7F002B2C3B3D5B5D0011 -:108EA0004355454141414143454545494949414172 -:108EB0004592924F4F4F5555594F554F9C4F9E9F3E -:108EC00041494F55A5A5A6A7A8A9AAABACADAEAF81 -:108ED000B0B1B2B3B4414141B8B9BABBBCBDBEBF79 -:108EE000C0C1C2C3C4C54141C8C9CACBCCCDCECF15 -:108EF000D1D145454549494949D9DADBDCDD49DF6E -:108F00004FE14F4F4F4FE6E8E85555555959EEEFB1 -:108F1000F0F1F2F3F4F5F6F7F8F9FAFBFCFDFEFFD9 -:108F200001030507090E10121416181C1E0000007C -:108F300061001A03E0001703F8000703FF000100B7 -:108F400078010001300132010601390110014A01A6 -:108F50002E017901060180014D0043028101820149 -:108F600082018401840186018701870189018A01C8 -:108F70008B018B018D018E018F0190019101910177 -:108F800093019401F60196019701980198013D0221 -:108F90009B019C019D0120029F01A001A001A20153 -:108FA000A201A401A401A601A701A701A901AA0188 -:108FB000AB01AC01AC01AE01AF01AF01B101B20137 -:108FC000B301B301B501B501B701B801B801BA01E8 -:108FD000BB01BC01BC01BE01F701C001C101C2015E -:108FE000C301C401C501C401C701C801C701CA0149 -:108FF000CB01CA01CD011001DD0101008E01DE01AE -:109000001201F3010300F101F401F401F801280158 -:10901000220212013A020900652C3B023B023D028A -:10902000662C3F0240024102410246020A015302FD -:10903000400081018601550289018A0158028F0191 -:109040005A0290015C025D025E025F0293016102BE -:10905000620294016402650266026702970196014A -:109060006A02622C6C026D026E029C017002710237 -:109070009D01730274029F017602770278027902E1 -:109080007A027B027C02642C7E027F02A6018102AE -:109090008202A9018402850286028702AE0144028F -:1090A000B101B20145028D028E028F02900291023F -:1090B000B7017B030300FD03FE03FF03AC030400C1 -:1090C0008603880389038A03B1031103C2030200E4 -:1090D000A303A303C4030803CC0303008C038E0380 -:1090E0008F03D8031801F2030A00F903F303F40312 -:1090F000F503F603F703F703F903FA03FA03300461 -:10910000200350041007600422018A043601C104C0 -:109110000E01CF040100C004D004440161052604FF -:10912000000000007D1D0100632C001E9601A01EA2 -:109130005A01001F0806101F0606201F0806301FD0 -:109140000806401F0606511F0700591F521F5B1FCC -:10915000541F5D1F561F5F1F601F0806701F0E0003 -:10916000BA1FBB1FC81FC91FCA1FCB1FDA1FDB1FB7 -:10917000F81FF91FEA1FEB1FFA1FFB1F801F0806CD -:10918000901F0806A01F0806B01F0400B81FB91FD3 -:10919000B21FBC1FCC1F0100C31FD01F0206E01F5F -:1091A0000206E51F0100EC1FF31F0100FC1F4E210A -:1091B0000100322170211002842101008321D0247A -:1091C0001A05302C2F04602C0201672C0601752C27 -:1091D0000201802C6401002D260841FF1A030000C3 -:1091E000C700FC00E900E200E400E000E500E70061 -:1091F000EA00EB00E800EF00EE00EC00C400C50060 -:10920000C900E600C600F400F600F200FB00F90019 -:10921000FF00D600DC00F800A300D800D7009201C0 -:10922000E100ED00F300FA00F100D100AA00BA005D -:10923000BF00AE00AC00BD00BC00A100AB00BB0095 -:1092400091259225932502252425C100C200C00046 -:10925000A9006325512557255D25A200A5001025ED -:10926000142534252C251C2500253C25E300C300AE -:109270005A25542569256625602550256C25A400AE -:10928000F000D000CA00CB00C8003101CD00CE00F4 -:10929000CF0018250C2588258425A600CC00802524 -:1092A000D300DF00D400D200F500D500B500FE00E9 -:1092B000DE00DA00DB00D900FD00DD00AF00B40005 -:1092C000AD00B1001720BE00B600A700F700B8003F -:1092D000B000A800B700B900B300B200A025A000FC -:1092E00001000000000000000096000000000000E7 -:1092F000000000000000000000000000000000006E -:1093000000000000896600088D6600086D510008A5 -:10931000A5540008015100082951000851510008C6 -:10932000E9500008000000005955000845550008A4 -:10933000815500086D5500087955000865550008ED -:10934000515500083D5500088D55000800000000EB -:10935000715600085D5600089956000885560008A9 -:10936000915600087D5600086956000855560008B9 -:10937000A5560008000000000100000000000000E9 -:10938000633000008093000800000000000000002F -:10939000B8460020E84800200000812A00000000B4 -:1093A000AAAAAAAA00000024FFFE000000000000F4 -:1093B00000A00A000001000000000000AAAAAAAA5A -:1093C00000000000FFFF000000000000000000009F -:1093D0001400AA5600000000AAAAAAAA1400555414 -:1093E000FFFF000000000000CCCC0C0020681A0039 -:1093F00000000000AAAA8AAA10541500FFFF00006E -:10940000000C70077700000040810201001000008E -:10941000AAAAAAAA00410100F7FF000000000070FC -:10942000070000000000000000000000AAAAAAAA8D -:1094300000000000FFFF000000000000000000002E -:109440000000000000000000AAAAAAAA0000000074 -:10945000FFFF00000000000000000000000000000E -:1094600000000000AAAAAAAA00000000FFFF000056 -:1094700000000000000000000000000000000000EC -:10948000AAAAAAAA00000000FFFF00000000000036 -:10949000000000000000000000000000AAAAAAAA24 -:1094A00000000000FFFF00000000000000000000BE -:1094B0000000000000000000AAAAAAAA0000000004 -:1094C000FFFF000000000000000000004865782F4A -:1094D00050726F6669434E430025424F4152442506 -:1094E0002D424C002553455249414C2500000000B7 -:1094F0000200000000000000915800080159000817 -:109500004000400098610020A86100200200000097 -:10951000000000000300000000000000495900089E -:109520000000000010000000B861002000000000F2 -:10953000010000000000000014650020010102008D -:109540008567000895660008316700081567000800 -:10955000430000005895000809024300020100C0C2 -:109560003209040000010202010005240010010577 -:1095700024010001042402020524060001070582DB -:10958000030800FF09040100020A000000070501AA -:1095900002400000070581024000000012000000A8 -:1095A000A49500081201100102000040AE2D161013 -:1095B00000020102030100000403090425424F4197 -:1095C00052442500437562654F72616E67650030D5 -:1095D0003132333435363738394142434445460019 -:1095E0000000002000000200020000000000003027 -:1095F0000000040008000000000000240000080033 -:10960000040000000004000000FC00000200000054 -:109610000000043000800000080000000000003856 -:1096200000000100010000001F1C1F1E1F1E1F1F45 -:109630001E1F1E1F1F1D1F1E1F1E1F1F1E1F1E1F42 -:1096400000000000A55A00085D5D0008095E0008E2 -:10965000400040004C6600204C66002001000000E5 -:109660005C6600208000000040010000080000004F -:1096700000010000001000000800000069646C6533 -:10968000000000006D61696E002C04380404380885 -:109690000C10141C20242526000000000000640487 -:1096A0000100040000000000000C0010283034000D -:1096B000B86DFF7F010000008C000000000000007A -:1096C00000001E0000000000FF000000F048002025 -:1096D000FC38002068390020D43900200000000048 -:1096E0000C8E000883040000178E00085004000050 -:1096F000258E000801000000000000000096000018 -:1097000000000800960000000008000004000000AF -:10971000B8950008000000000000000000000000F4 -:10972000000000000000000000000000782200207F -:109730000000000000000000000000000000000029 -:109740000000000000000000000000000000000019 -:109750000000000000000000000000000000000009 -:1097600000000000000000000000000000000000F9 -:1097700000000000000000000000000000000000E9 -:1097800000000000000000000000000000000000D9 +:100EF0009422002000220020A086010070470000FC +:100F000070470000704700002DE9F04100F5803780 +:100F1000044616463B7C5BB9C0681030204400F0A4 +:100F2000E5FEE5683544B5F5004FE56002D816B139 +:100F3000BDE8F081DEB905F07F0605F11000002163 +:100F4000C6F180062044F6B232462E4400F0F4FE8C +:100F5000A06804F11008324600F10060414600F537 +:100F6000003006F05FF830B901233B74E0E74FF43E +:100F700000463546ECE7A26805F1100140463244D0 +:100F80002144A260E268521BE26000F0AFFE022042 +:100F9000BDE8F04100F090BE183000F0E9BC000060 +:100FA00010B5044600F0FAFF204610BD10B5044607 +:100FB00000F0F4FF204610BDC3B280B2A3F141029D +:100FC000052A02D8373800B27047613B052B94BF21 +:100FD00057383038F7E70000F8B50446154608469C +:100FE00003220C4900F08CFE014688B908346F1CBE +:100FF00015F91100FFF7E0FF064617F9110001315E +:10100000FFF7DAFF102940EA061004F8010BEFD1D0 +:10101000F8BD00BF549200082DE9F04FADF53F7DBB +:101020000746416801222AA802F09AFE002840F0F3 +:1010300087800646824681461125DFF80C81DFF85D +:101040000CB101AB4FF4805241462AA802F0E8FFF0 +:10105000002875D1019AB2F5805F71D8002A65D059 +:101060000446019A9442ECD2282D0FD008DC132DAF +:101070002DD01E2D39D0112D13D00134A4B2F0E79C +:10108000322D2DD0372D2FD02D2DF6D13B68121BB0 +:1010900008EB040138461B692D259847BDF804402C +:1010A000EBE7121B022A09D9594608EB040000F0AD +:1010B00027FE18B902342825A4B2DEE718F8043058 +:1010C0003A2B3DD00A2B1CBFA1461325D5E718F8B3 +:1010D00004300A2B34D03A2B04BFA2463225CCE789 +:1010E00018F80430202BC8D0264618F804300A2BF4 +:1010F0001AD1AAEB090208EB090102A811254F2A0F +:1011000028BF4F2208F092F8A21B08EB060116A890 +:101110004F2A28BF4F2208F089F83B6816AA02A977 +:10112000DB6838469847A8E71E25A6E73B6838469F +:1011300004491B69984701200DF53F7DBDE8F08FFC +:101140000020F9E756930008A023002058920008D9 +:1011500000F1180110B5044686B00846019100F070 +:10116000F1FB2046FFF758FF60B1019902A800F09B +:1011700049FC102204F1080102A808F017F8B0FA9F +:1011800080F0400906B010BD70B504460025EEB2EF +:10119000304600F0FFFC58B100213046013500F028 +:1011A00009FD08B9002070BD022000F085FDEEE7C2 +:1011B0002046FFF731FF0028F4D004F58034207C6E +:1011C00080F00100EFE70000F0B5C9B006F096F935 +:1011D00000F000FF18B90025284649B0F0BD694667 +:1011E0002A4802F0DFFF00284BD1294C204603F0AB +:1011F00009F8284803F006F8274803F003F82146C9 +:10120000224803F07BF80028E5D1702000F0C0FEF2 +:10121000064610B1214B44600360336830469B683A +:101220009847054600282ED01A4F1948394603F032 +:1012300065F805460028CED1194800F0A9FE0446FD +:1012400038B1184B4760036000F58033C0E90255A0 +:101250001D74236820469B689847054628B10E49AF +:101260000C4803F04BF80028B5D1336830465B6872 +:1012700098471CB1236820465B68984700F092FEAF +:10128000AAE70025FAE70446EFE700BF5C920008F2 +:101290006C9200088392000899920008BC920008A2 +:1012A00014000100D89200082DE9F04FD44A8DB007 +:1012B0000B68D0F804A001931A440368D14E1A4475 +:1012C000D1F81C90DFF8B4C3DFF8B4B3D0E902342E +:1012D000634003EA0A03634013444A6802920AEB3C +:1012E0007363029CC84A2244C468224484688AEA20 +:1012F00004051D40654015448A68039203EB35558B +:10130000039CC24A2244846822448AEA03042C4093 +:1013100084EA0A041444CA6805EBF43404921644BF +:1013200083EA0502224056445A4032440E6905962B +:1013300004EBB222059FB64E3E441E4485EA0403E8 +:1013400013406B4033444E69069602EB7363069F6D +:10135000B04E3E442E4484EA02051D4065403544AB +:101360008E69079603EB3555079FAB4E3E442644E6 +:1013700082EA03042C4054403444A84E4E4405EB0A +:10138000F434164483EA050222405A4032440E6A7D +:10139000089604EBB222089FA14E3E441E4485EA03 +:1013A000040313406B4033444E6A099602EB7363A7 +:1013B000099F9C4ED1F830E03E44D1F83880F34488 +:1013C0002E4484EA02051D40654035448E6AA6F528 +:1013D000244703EB35550A964F3F274482EA03041E +:1013E0002C4054403C44CF6A0B9705EBF4340B9EE1 +:1013F0008D4F3744029E174483EA050222405A402B +:101400003A448A4F774404EBB2221F4485EA04032E +:1014100013406B403B444F6BBC4402EB7363654429 +:1014200084EA020C0CEA030C8CEA040C6544DFF835 +:1014300054C2C44403EB3555A44482EA03042C404F +:1014400054406444D1F83CC0794905EBF43461441C +:10145000114483EA050222405A400A44754904EBCC +:10146000B2223144079E194484EA02032B406340B0 +:101470000B44714902EBF36331440B9E0D4482EA45 +:1014800003012140514029446C4D03EBF151354497 +:10149000019E254483EA010414405C402C44684DBD +:1014A00001EBB4443544069E154481EA04021A4017 +:1014B0004A402A44634D04EB323235440A9E1D44AF +:1014C00084EA02030B4063402B445F4D02EBF3635D +:1014D0003544059E0D4482EA0301214051402944D0 +:1014E0005A4D03EBF1516544254483EA010414404D +:1014F0005C402C44564D01EBB4443544099E1544E0 +:1015000081EA04021A404A402A44524D04EB323226 +:101510003544049E1D4484EA02030B4063402B447F +:101520004D4D02EBF36345440D4482EA0301214033 +:1015300051402944494D03EBF1513544089E2C4458 +:1015400083EA010515405D402C44454D01EBB44450 +:101550003544039E2A4481EA04051D404D402A4437 +:10156000404D04EB32323D442B4484EA020593445F +:101570000D4065402B443C4D02EBF3633544069E21 +:10158000294482EA0305254055402944374D03EBA1 +:10159000F1514D442C4483EA010515405D4025443A +:1015A00001EBB54581EA050404EA03024A405A44C6 +:1015B000A6F5B82B089E05EB3232ABF2BE6B544059 +:1015C0005B4423442A4C344402EB33730B9E0C449B +:1015D00085EA020159402144264C344403EB715101 +:1015E000029E254482EA03044C402544224C444494 +:1015F00001EB3545144483EA01026A40224443E08A +:1016000078A46AD7EECEBDC156B7C7E8DB702024F8 +:10161000AF0F7CF52AC68747134630A8019546FDD3 +:10162000D8988069AFF7448BBED75C892211906B44 +:101630002108B44962251EF640B340C0515A5E26C7 +:10164000AAC7B6E95D102FD65314440281E6A1D88B +:10165000C8FBD3E7E6CDE121D60737C3870DD5F424 +:10166000ED145A4505E9E3A9F8A3EFFCD9026F6729 +:1016700081F6718722619D6D0C38E5FD937198FDAF +:101680008A4C2A8D8E4379A6934C344405EB722202 +:10169000059E1C4481EA0503534023448F4C344487 +:1016A00002EB33730A9E0C4485EA0201594021443F +:1016B0008B4C4C4403EB7151254482EA03044C40AB +:1016C0002C44884D354401EB3444019E154483EA93 +:1016D000010262402A44844D3D4404EB72221D44C1 +:1016E00081EA040353402B44804D354402EB3373AD +:1016F000049E294484EA02055D4029447C4D35441A +:1017000003EB7151079E254482EA03044C402C44AC +:10171000784D354401EB3444099E2A4483EA01059F +:1017200065401544744A324404EB7525039E134406 +:1017300081EA04026A401A44704B734405EB32722A +:101740000B4484EA0501514019446D4B634402EB9C +:1017500071511C4485EA02034B401C44694B3344DD +:1017600001EB3444019E1D4482EA010363402B4493 +:10177000654D04EB73233544069E154463EA01026C +:1017800062402A44614D03EBB2624D4462EA0409AF +:1017900029445F4D89EA0309454449442C445D4D81 +:1017A00002EBB1513544049E61EA03081D4488EA06 +:1017B0000208444401EB744464EA02034B402B44A6 +:1017C000554D04EBF323754463EA010E15448EEA8C +:1017D000040E0EEB0502514D03EBB262354462EA92 +:1017E000040E29440A9D8EEA030EA5F580164C4D81 +:1017F0007144A6F6833602EBB151264461EA030434 +:1018000054403444029E01EB7444354464EA0206B9 +:101810001D444E407319089E424D04EBF32335449A +:1018200063EA01061544664072193F4D03EBB2624C +:10183000654462EA040629443C4D5E403144079EFB +:1018400002EBB151354461EA03062C44384D564051 +:101850003D443444059E1D4401EB744464EA020394 +:101860004B402B44334D04EBF32335440B9E15447E +:1018700063EA010262402A442F4D03EBB262354411 +:10188000039E0D4462EA0401594029442B4D02EBAA +:10189000B15135442A4E254461EA030454402C4496 +:1018A000099D01EB74442E4464EA02051E4485EA56 +:1018B00001039D1903681A440AEB040303EBF523A3 +:1018C0000260436083681C44C36819448460C1603B +:1018D0000DB0BDE8F08F00BF44EABEA4A9CFDE4B37 +:1018E000604BBBF670BCBFBEC67E9B28FA27A1EA40 +:1018F0008530EFD4051D880439D0D4D9E599DBE6CD +:10190000F87CA21F6556ACC4442229F497FF2A43F1 +:10191000A72394AB39A093FCC3595B6592CC0C8F81 +:10192000D15D84854F7EA86FE0E62CFE144301A3B1 +:10193000A111084E827E53F735F23ABDBBD2D72AA9 +:1019400091D386EB094B036003F18833436003F1C5 +:101950002943A3F59613A3F68B638360A3F1883321 +:10196000C3600023C0E90433704700BF012345670B +:101970002DE9F8431446026905460E46E300C2F31A +:10198000C50800F118079B18036122BF43690133A2 +:10199000436112F4FC7F436903EB5473436114D039 +:1019A000C8F1400907EB08004C4504D22246BDE8C7 +:1019B000F84307F00BBC403C4A464E4407F006FC97 +:1019C000444439462846FFF76FFCA04606EB04095D +:1019D000B8F13F0FA9EB08010AD94022384607F0B9 +:1019E000F5FB39462846A8F14008FFF75DFCEFE714 +:1019F000A1096FF03F02384602FB014206EB81115C +:101A0000D5E7000070B50B6901F1180506460C46D4 +:101A1000C3F3C503EA18501C8022EA54C3F13F0205 +:101A2000072A1FD8002100F087F929462046FFF732 +:101A30003BFC38220021284600F07EF92369294624 +:101A40002046236563696365FFF72EFC214610225B +:101A5000304607F0BBFB204658220021BDE870400D +:101A600000F06AB9C3F137020021E5E72DE9F84F2C +:101A70004FF47A7306460D46002402FB03F7DFF8A5 +:101A80005080DFF8509098F900305FFA84FA5A1CC1 +:101A900001D0A34210D159F824002A4631460368E8 +:101AA000D3F820B03B46D847854205D1074B0120EB +:101AB00083F800A0BDE8F88F0134042CE3D14FF483 +:101AC000FA7004F0D3FD0020F4E700BFE4330020F7 +:101AD0001022002014220020002307B50246012115 +:101AE0000DF107008DF80730FFF7C0FF20B19DF81A +:101AF000070003B05DF804FB4FF0FF30F9E700008A +:101B00000A46042108B5FFF7B1FF80F00100C0B21A +:101B1000404208BD074B0A4630B41978064B53F8CB +:101B20002140014623682046DD69044BAC4630BCA9 +:101B3000604700BFE433002014220020A08601008B +:101B400070B50A4E00240A4D05F010FA308028685E +:101B50003388834208D905F005FA2B680444013321 +:101B6000B4F5003F2B60F2D370BD00BFE633002018 +:101B7000A033002005F0C8BA00F1006000F5003085 +:101B80000068704700F10060920000F5003005F039 +:101B900049BA0000054B1A68054B1B889B1A834203 +:101BA00002D9104405F0DEB900207047A0330020B0 +:101BB000E633002038B50446074D29B12868204493 +:101BC000BDE8384005F0E6B92868204405F0D0F9B2 +:101BD0000028F3D038BD00BFA0330020002070479C +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7BFBF0120704700BFA43300207E +:101C1000014B1868704700BF0010005C194B013879 +:101C20000322084470B51D68174BC5F30B042D0C37 +:101C30001E88A6420BD15C680A46013C82421346CC +:101C40000FD214F9016F4EB102F8016BF6E7013AB9 +:101C500003F10803ECD181420B4602D22C2203F897 +:101C6000012B0424094A1688AE4204D1984284BF4D +:101C7000967803F8016B013C02F10402F3D1581A83 +:101C800070BD00BF0010005C2422002018930008E3 +:101C9000022803D1024B4FF080529A61704700BF77 +:101CA00000100258022803D1024B4FF480529A616F +:101CB000704700BF00100258022804D1024A53693D +:101CC00083F48053536170470010025870B5044686 +:101CD0004FF47A764CB1412C254628BF412506FBAE +:101CE00005F0641B04F0C2FCF4E770BD002310B5DE +:101CF000934203D0CC5CC4540133F9E710BD00001B +:101D0000013810B510F9013F3BB191F900409C42F8 +:101D100003D11AB10131013AF4E71AB191F9002067 +:101D2000981A10BD1046FCE703460246D01A12F975 +:101D3000011B0029FAD1704702440346934202D0A6 +:101D400003F8011BFAE770472DE9F8431F4D1446CD +:101D50000746884695F8242052BBDFF870909CB364 +:101D600095F824302BB92022FF2148462F62FFF737 +:101D7000E3FF95F824004146C0F1080205EB80001E +:101D8000A24228BF2246D6B29200FFF7AFFF95F8D5 +:101D90002430A41B17441E449044E4B2F6B2082E2B +:101DA00085F82460DBD1FFF723FF0028D7D108E0B6 +:101DB0002B6A03EB82038342CFD0FFF719FF002881 +:101DC000CBD10020BDE8F8830120FBE7A43300203D +:101DD000024B1A78024B1A70704700BFE4330020A0 +:101DE00010220020F8B5194C194803F047FF21468E +:101DF000174803F06FFF24684FF47A70154ED4F83B +:101E00009020154DD2F80438114F43F00203C2F868 +:101E10000438FFF75BFF2046104904F069F8D4F856 +:101E200090200424D2F8043823F00203C2F80438C6 +:101E30004FF4E133336055F8040BB84202D0314619 +:101E400003F07AFE013CF6D1F8BD00BF189B0008F4 +:101E500018490020CC33002014220020209B0008C9 +:101E60000C4B70B50C4D04461E780C4B55F82620D3 +:101E70009A420DD00A4B002118221846FFF75CFF4A +:101E80000460014655F82600BDE8704003F054BEDA +:101E900070BD00BFE4330020142200201849002048 +:101EA000CC330020F8B571B6002301201A4619463C +:101EB00002F094FD0446802005F0C6F9002849D0C0 +:101EC0000025254A80274FF4D06C3D26136913F076 +:101ED000C06F26D1D2F8103113F0C06F21D1236822 +:101EE00005F1006199602368D86023685F6023680A +:101EF000C3F800C021680B6843F001030B60216840 +:101F00000B6823F01E030B6021680B68DB07FCD411 +:101F1000237B8035616806FA03F3B5F5001F0B607B +:101F2000D4D1204602F09AFDB5F5001F11D000244F +:101F30000A4E0B4D012005F0E7F83388A34205D97E +:101F400028682044013405F025F8F6E7002005F064 +:101F5000DBF861B6F8BD00BF00200052E633002078 +:101F6000A033002030B50A44084D91420DD011F83D +:101F7000013B5840082340F30004013B2C4013F080 +:101F8000FF0384EA5000F6D1EFE730BD2083B8EDBF +:101F90000121884238BF084605F08EB908B105F026 +:101FA0008FB9704710B5084C01220849002001F094 +:101FB000B3FE23783BB1064803F036FD044803F036 +:101FC00069FD0023237010BDE8330020289300082A +:101FD000C83600201D482DE9F041036D2BB90122C0 +:101FE0004FF48051503005F0CBFA194E33780BB1D5 +:101FF000FFF7D8FF0324174F4FF00008134D154982 +:102000002846C7F8048003F037FD284603F070FB2C +:1020100048B1013C284603F03DFD14F0FF04EED129 +:10202000204634700FE00C4901220C4801F074FE88 +:10203000014618B1284603F0F7FCEAE7084800F02B +:1020400011F801203070BDE8F08100BFC8360020D3 +:10205000E83300203C22002028930008EC330020C5 +:102060002C9300080FB4002004B07047006870473C +:1020700003460068596870470B0A017043700B0CE7 +:10208000090E8370C1707047110A027003714170AC +:10209000110C120E8170C2701A0A42711A0C1B0EBA +:1020A0008271C37170470000C36A0239023B8B42E0 +:1020B00083BF4389006C01FB0300002070470000D0 +:1020C000C2F307238A76CB760378032B01BF120C69 +:1020D0000A75120A4A75704700F10B010022D301FC +:1020E00043EA520310F8012B52FA83F38842DAB222 +:1020F000F5D110467047000010B541780446002025 +:10210000013102464901022A16BFA35C032203EBF8 +:10211000C03302F101021EBF9BB203EB500398B221 +:102120009142F0D810BD000002684AB1134613F87E +:10213000011B1F290DD93A29F9D1911C8B4202D0DC +:102140004FF0FF3070471278302AF9D10360002039 +:102150007047014B187870473836002038B50D4667 +:10216000044618B9092000232B6038BD0368002BF2 +:10217000F8D01A78002AF5D08188DA889142F1D116 +:10218000587804F00FFC10F00100EBD12368EBE766 +:1021900038B50D4640F25231144602F0B9F9FF2825 +:1021A00007D9012C0BD9030A022468702B70204632 +:1021B00038BD30B1002CFAD001242870F7E7002494 +:1021C000F5E70446F3E700002DE9F8430026D0F8D0 +:1021D000008005460C468E76836B002B4AD098F81B +:1021E0000030042B4BD133463546402720E0B7F56D +:1021F000187F80F0C480F90606F1010608BF023797 +:10220000D05B02372BB900F5205292B2B2F5006FC5 +:102210000DD305F11A01C5F1FF0240EA0340214444 +:10222000FFF7B6FF002800F0AA800544002003460F +:10223000D8F8102092F82310B142D8D8002B40F0E3 +:102240009E80002D00F09B8000232544AB766373B5 +:10225000D8F81020137903F03701DB0621730BD473 +:1022600002F13800FFF704FFC4E90001938963819C +:10227000D3892381BDE8F88300200146F4E7C36CCD +:1022800001335ED1EA6B00232E26551E184615F841 +:10229000011F013020290CD0052908BFE52109289C +:1022A00004D10B2B9EBFE71801337E73E71801336F +:1022B00079730B28EBD1E11800204873A17E002927 +:1022C0004BD1002B40D06FF00C0604F10D00082517 +:1022D000361B331810F8011B002938D02E298BB279 +:1022E0004AD0A3F14101192903D8117B0D4200D036 +:1022F00020330373EDE7B9F1000F05D100F520534A +:102300009BB2B3F5006F0BD307F11A01C7F1FF02BF +:1023100040EA09402144FFF73BFF48B10744002051 +:1023200002368146D8F80C30985B0028E3D1384655 +:10233000B9F1000F4FF0000218BF002023189A7661 +:10234000A0E7B1463746EDE73F23A37601232344B8 +:1023500000219976137B03B96373D37A02F11C00D1 +:1023600003F03F0323730023FFF780FE20606360C8 +:10237000D38A6381138B7CE710250B46B9E73F2393 +:102380000125A37660E7000038B50546002435F83E +:10239000020B08B9204638BD02F0EEF86308C2B25D +:1023A00003EBC43312FA83F39AB2C0F3072303EBAF +:1023B000520303EBC2339CB2E9E7000037B5C378A0 +:1023C00004461BB90025284603B030BD00F14C017E +:1023D000826C01234078019104F00AFB054680B924 +:1023E000A36BE070A06C226BC31A9342EAD2A3786D +:1023F0000199022BE6D102440123607804F0F8FA37 +:10240000E1E70125DFE7000038B5836C05460C469F +:102410008B4210D0FFF7D2FF60B92246012305F1AD +:102420004C01687804F0C0FA00281CBF4FF0FF345C +:102430000120AC6438BD0020FCE7000038B5002363 +:102440000446C3704FF0FF338364FFF7DDFF0028BD +:102450004BD1B4F84A524AF655239D4207D10B227C +:10246000254904F14C0006F0A1FE00283FD094F865 +:102470004C30EB2B03D01833DBB2012B2ED84AF6AD +:1024800055239D4206D108221C4904F19E0006F006 +:102490008DFE48B3B4F85730B3F5007F1ED194F8E1 +:1024A0005930DBB15A1E1A4218D1B4F85A30ABB1C8 +:1024B00094F85C30013B012B10D8B4F85D306BB15F +:1024C000B4F85F307F2B06D804F16C00FFF7CEFD27 +:1024D000B0F5803F02D3B4F8623053B94AF65520C4 +:1024E00085420CBF0220032038BD0420FCE70120F8 +:1024F000FAE70020F8E700BF58930008649300084B +:1025000002392DE9F04701F007044FF0010A466C4B +:1025100005460AFA04F41746984606EB1136C1F34D +:10252000C809E4B2314628460136FFF76DFF18B1FD +:102530000120BDE8F087994605EB090292F84C307E +:10254000234214BF01210021414513D06340013FC4 +:1025500082F84C3085F803A0EBD0640014F0FF043F +:10256000EAD109F1010301244FF00009B3F5007F1E +:10257000E1D1D7E70220DCE701290246F8B50C4695 +:1025800040F28C800668F36A8B4240F28780337891 +:10259000013B032B00F28280DFE803F00229384B75 +:1025A00004EB5405B16B304601EB5521FFF72CFFCE +:1025B00010B14FF0FF30F8BD6F1CC5F30805B16BCB +:1025C0003046354401EB572195F84C50FFF71CFF7E +:1025D0000028EED1C7F30807E3073E4496F84C0005 +:1025E00045EA00204CBF0009C0F30B00E3E7B16BE4 +:1025F000304601EB1421FFF707FF0028D9D1640012 +:1026000004F4FF742644B6F84C00D4E7B16B3046AE +:1026100001EBD411FFF7F8FE0028CAD1A40006F19F +:102620004C0004F4FE742044FFF720FD20F07040BD +:10263000C1E7D0E90430D57953EA000101D09168AF +:1026400001B95DBB9168022DA4EB01010DD1013BE5 +:10265000728940F1FF305B0A43EAC053B3FBF2F3E7 +:1026600099421BD81CD0601CA5E7032D02D19369A9 +:102670008B42F8D8D3699BB9B16B304601EBD411CA +:10268000FFF7C2FE002894D1A0004C3600F4FE7083 +:102690003044FFF7EBFC20F000408CE701208AE794 +:1026A0006FF0004087E70000F8B5066804460D4665 +:1026B0003378042B0CBF4FF080524FF400128A4243 +:1026C00001D80220F8BDCA06FBD182680163D2B9E5 +:1026D000022B13D83389B3EB551FF2D9F36BA363E5 +:1026E000A36B6263002BECD003EB55234C36C5F390 +:1026F00008050020A3633544E563E3E7F36BC2718B +:10270000002BE7D01A4677897F02BD42114604D2DA +:102710003046FFF7C9FCA063E2E72046FFF72CFF35 +:10272000431C024606D00128CBD9F36A8342C8D99C +:10273000ED1BEAE70120C5E701292DE9F047064630 +:102740000C46174608D9C36A8B4205D90378022B79 +:1027500062D003D8012B22D0022552E0033B012B8B +:10276000FAD8816B01EBD411FFF74EFE0546002825 +:1027700047D1A40006F14C0304F4FE741C443378E2 +:10278000042B07D0204627F07047FFF76FFC00F0BE +:102790007040074339462046FFF76EFC2FE001EBFF +:1027A0005108816B01EB5821FFF72EFE054640BB17 +:1027B00014F0010406F14C0908F1010AC8F30808F5 +:1027C00008BFFBB230461FBF19F8083003F00F02F4 +:1027D0003B0103F0F00318BF134309F8083001234D +:1027E000B16BF37001EB5A21FFF70EFE054640B9BD +:1027F000CAF3080A44B1C7F3071709F80A7001239E +:10280000F3702846BDE8F08719F80A30C7F30327AC +:1028100023F00F031F43F0E7816B01EB1421FFF757 +:10282000F3FD05460028ECD1640006F14C0304F4E6 +:10283000FF741F551919C7F307274F70DFE7000012 +:10284000F8B504460E461746E3690BB91846F8BDBD +:10285000012BA6EB0305206814BFAA1C3A46691C8D +:10286000FFF76AFF0028F2D1E369013BE361EBE780 +:1028700001292DE9F84306460C461746056802D89B +:102880000220BDE8F883EB6A8B42F9D97AB9A146F8 +:1028900021463046A046FFF76FFE0446B0B92B78BC +:1028A000042B02D1002F43D1F7710020E9E72B78E8 +:1028B000042B02D1C379022BE9D04FF0FF32394605 +:1028C0002846FFF739FF0028E1D0DAE70128D7D002 +:1028D000421C01D10120D4E72B78042B19D1EA6ADC +:1028E000AB69023A93421CD308F10102A2420CD018 +:1028F0002B78042B08D10023A2EB09024946284675 +:10290000FFF7FEFD0028BCD1A146EB6AA342BFD869 +:10291000C5E7002241462846FFF70EFF0028DED01B +:10292000AFE70133AB612B7943F001032B71DBE798 +:10293000F3798BB9B468BC4202D10223F371B4E7D6 +:1029400021463046FFF718FE012899D9431CC1D013 +:1029500001348442EFD0A8E7032BA6D1B368BB4271 +:10296000A3D8B2691344BB429FD3E6E770B5C379DD +:102970000446032B06D181688369CD18A94203D18F +:102980000023E371002070BD4E1C20683246FFF723 +:10299000D3FE0028F7D13146F0E700002DE9F743D8 +:1029A00005460191FFF70AFD0446002849D105F1CB +:1029B0004C09019928464FF40072FFF775FB214638 +:1029C000A86407464846FFF7B7F96C896402B4F576 +:1029D000004F28BF4FF40044B4F5007F2FD92046A4 +:1029E00004F072FC804630B122460021640A0026C1 +:1029F000FFF7A2F909E06408EEE72346BA19414659 +:102A0000687803F0F5FF18B926446B899E42F4D329 +:102A1000404604F069FC6889801B18BF012003B0A0 +:102A2000BDE8F08301366B899E42F4D20123BA19C6 +:102A30004946687803F0DCFF0028F3D0EBE7002676 +:102A4000F1E70120EBE70000F8B50446FFF7B6FC1C +:102A50000546002842D12378032B37D12779012F4F +:102A600034D104F14C0601464FF400723046FFF7B2 +:102A700063F955234122722184F84A32AA2304F5CE +:102A80000D7084F84F2084F84B32522384F83012B2 +:102A900084F84C3084F84D30612384F8311284F886 +:102AA0004E3084F83332A16984F83222FFF7E4FA19 +:102AB000616904F50E70FFF7DFFA626B3B46314641 +:102AC00001326078A26403F093FF257100226078E0 +:102AD000114603F0B1FF003818BF0120F8BD000017 +:102AE00000232DE9F0430B6085B00F461546FFF734 +:102AF0001BFB061EC0F2B281804B53F82640002C0F +:102B000000F0AE813C6005F0FE0523786BB1607883 +:102B100003F048FFC70708D41DB110F0040500D02A +:102B20000A25284605B0BDE8F0830023F0B22370E3 +:102B3000607003F023FFC10700F194810DB14207DB +:102B4000EED400212046FFF779FC022840F099805E +:102B50006E4604F2122304F2522132461846103314 +:102B6000FFF784FA42F8040B8B42F7D1002556F8A0 +:102B7000041B00297DD02046FFF760FC012879D88E +:102B80000128A26C40F0C08004F1570304F18C01CD +:102B900013F8015B002D7BD18B42F9D1B4F8B4302E +:102BA000B3F5807F74D194F8B830092B70D104F15B +:102BB0009400FFF75DFA4FF0FF33171841F1000161 +:102BC000BB4275EB010363D304F1A000FFF74EFA9B +:102BD00094F8BA302063012BA37059D194F8B990BE +:102BE00003FA09F91FFA89F36381002B50D0444B93 +:102BF00004F1A800FFF73AFA0646984248D8831C29 +:102C0000626304F1A400E362FFF730FA00EB02080C +:102C100004F19C00C4F84080FFF728FA10441FFA22 +:102C200089F2A06306FB02F313EB080345EB0502F0 +:102C30009F4271EB02032BD32E4604F1AC00FFF749 +:102C400015FAE06365B96389B34221D9E16B204687 +:102C5000FFF72AFA81192046FFF7D6FB98B901360B +:102C6000631993F84C30812B14D02035C5F3080537 +:102C7000E8E703200135042D7FF479AF042807D15C +:102C800001E0042801D101254BE701287FF678AF48 +:102C90000D2546E705F1140004F14C063044FFF71A +:102CA000E5F901280546F3D9E36A8342F0D9618941 +:102CB000821E236C02FB01336364A16B204601EB8F +:102CC000D511FFF7A1FB0028DDD105F07F0006EB51 +:102CD0008000FFF7CBF9431C03D00135A842ECD0AC +:102CE000D6E70425C4E90500064A257000251388A7 +:102CF000E56101339BB21380E38012E73C3600208C +:102D0000FDFFFF7F40360020B4F85730B3F5007F59 +:102D1000BED1B4F8626026B904F17000FFF7A6F9DD +:102D2000064694F85C302663591EA3700129AFD87B +:102D300094F859506581002DAAD0691E2942A7D167 +:102D4000B4F85D8018F00F0FA4F80880A0D1B4F893 +:102D50005F0018B904F16C00FFF788F9B4F85A1055 +:102D6000002995D006FB03FE01EB181CF4446045D6 +:102D70008ED3A0EB0C00A842B0FBF5F388D33E48FD +:102D8000834285D84FF6F57083426DD903259F1C89 +:102D9000114402EB0C03032DE7626263A163236419 +:102DA0004CD1B4F8763053EA08037FF471AFBB001E +:102DB00004F17800FFF75AF9E06303F2FF13B6EB72 +:102DC000532FFFF465AF4FF0FF33032DC4E90533F4 +:102DD0004FF08003237187D1B4F87C30012B83D16D +:102DE000511C2046FFF710FB00287FF47DAFB4F89C +:102DF0004A224AF6552320719A427FF475AF1F4B41 +:102E000004F14C00FFF732F998427FF46DAF03F103 +:102E1000FF5304F50C70FFF729F903F50053203335 +:102E200098427FF461AF04F50D70FFF71FF9A061C0 +:102E300004F50E70FFF71AF9606155E7B8F1000F5D +:102E40003FF426AF7144022D4FEA4703E1631EBFF2 +:102E5000D91907F0010303EB5103AEE70B2560E638 +:102E60000C255EE603255CE640F6F575AB428CBFAB +:102E7000022501258BE700BFF5FFFF0F525261418C +:102E80002DE9F84F07460568884649B96E69C6B10D +:102E9000EB6AB34298BF0126AB69A3B9002405E0F1 +:102EA000FFF76AFB0128044603D801242046BDE849 +:102EB000F88F421C00F0D280EB6A8342F6D8464677 +:102EC000EAE70126E8E72A78EB6A042A40F08380E3 +:102ED000A6F1020A023B4FF0010B9A4528BF4FF0C2 +:102EE000000AD146696C284601EB1931FFF78CFACC +:102EF00000283BD109F00703EA6AC9F3C8010BFABD +:102F000003F3901EDBB26A184C4609F1010992F8EE +:102F10004C20814502EA030233BF5B0000234FF4DB +:102F20000071DBB228BF9946B2B90234631E033385 +:102F3000BCD80123214628461A46FFF7E1FA0228A9 +:102F4000B3D0012800F08A80B8F1000F13D102231A +:102F5000FB710028A9D130E0CA450AD0002BD2D19C +:102F60000131B1F5007FBDD20123CCE74FF0FF3432 +:102F7000DCE70024DAE7FB79022B07D1731CA342BC +:102F8000E7D0BB68F31ABB610323FB7108F10102B0 +:102F9000FB69A24205D113B10133FB61D9E70223DA +:102FA000FBE70BB90123FB61224641463846FFF798 +:102FB00047FC00284FD10123FB61EA6AAB69023A62 +:102FC0006C6193429CBF03F1FF33AB612B7943F0FB +:102FD00001032B716AE7464514D1741C3846A3429D +:102FE00098BF02242146FFF7C7FA01283FF45DAFDE +:102FF000431C33D0E0B16B69012B03D9EA6A9342D9 +:1030000038BF1E4634460134EB6AA34203D8012E72 +:103010007FF644AF022421463846FFF7ADFA48B1A7 +:1030200001283FF442AF013018D0B442EBD135E76C +:10303000002CE7D04FF0FF3221462846FFF77CFBFB +:1030400048B9B8F1000FB8D0224641462846FFF7EC +:1030500073FB0028B1D001287FF427AF4FF0FF3475 +:1030600024E700002DE9F84306680446076B89460B +:1030700033782037042B0CBF4FF080534FF40013EC +:10308000BB429CBF00238363836B73B1C7F3080803 +:10309000B8F1000F3CD10133416B836339B93389F7 +:1030A000B3EB571F34D80023A36304200AE07389CD +:1030B000013B13EA57232BD1FFF75EFA012805469F +:1030C00002D80220BDE8F883421C01D10120F9E7B3 +:1030D000F36A834216D8B9F1000FE4D0616B204641 +:1030E000FFF7CEFE0546C8B10128EAD0431CEDD05B +:1030F00001463046FFF752FC0028E7D1E37943F060 +:103100000403E371294630466563FEF7CDFFA063F3 +:103110004C36002027634644E663D3E70720D1E717 +:10312000F8B50E46002104460768FFF7BDFA98B9C6 +:103130000546A16B3846FFF767F968B93A78E36B43 +:10314000042A1B780CD11B060ED50546012120460A +:10315000FFF788FF0028ECD0042808BF072006E00E +:10316000E52B01D0002BF0D10135B542EED1F8BDF1 +:10317000C16C4B1C2DE9F04104460568066B1FD15C +:10318000E5274FF00108A16B2846FFF73DF998B9F4 +:103190002A78E36B042A09BF1A781F7002F07F02B5 +:1031A0001A7085F80380236BB3420DD200212046AC +:1031B000FFF758FF0028E6D0042808BF022003E0EC +:1031C000FFF772FA0028DBD0BDE8F0812DE9F0416D +:1031D00005460068A96B0669FFF716F9044620B991 +:1031E000EB6B1A78852A03D002242046BDE8F081D3 +:1031F000324603F1200153F8040B8B4242F8040BD2 +:10320000F9D1777801377F01A7F16003B3F5007F2B +:10321000EAD800212846FFF725FF04280446E3D01A +:103220000028E2D1A96B2868FFF7EEF804460028D1 +:10323000DBD1EB6B1A78C02AD6D106F1200203F15C +:10324000200153F8040B8B4242F8040BF9D196F895 +:1032500023300F222C33B3FBF2F3B7EB431FC3D35E +:103260004FF0400800212846FFF7FCFE04280446E2 +:10327000BAD00028B9D1A96B2868FFF7C5F8044671 +:103280000028B2D1EB6B1A78C12AADD1B8F5187FFE +:1032900009D206EB080203F1200153F8040B8B421C +:1032A00042F8040BF9D108F120084745DAD8B8F5FF +:1032B000187F9AD83046FEF71FFF7388834294D058 +:1032C00092E700000B68002210B5036004460B6A09 +:1032D00083604B6AC261C37123F0FF03896AC0E94E +:1032E0000432C164FFF7E0F920B92046BDE8104080 +:1032F000FFF76CBF10BD0000F8B503680546012755 +:103300001C692046FEF7F8FEA070000A6678E0709F +:103310002846E96CFFF7C8F920B1022828BF02202F +:10332000C0B2F8BDA96B2868FFF76EF80028F4D189 +:10333000EB6B04F1200254F8041B944243F8041B85 +:10334000F9D12B68DF70002EE7D000212846013E1E +:10335000FFF788FEE0E700002DE9F8434FF0FF0893 +:1033600006460768042445464FF6FF79B16B11B94C +:10337000002C73D063E03846FFF746F80446002877 +:103380005DD1F06B0378002B6ED03A78042A11D10E +:10339000852B4DD1336B3046F364FFF717FF04469E +:1033A00000284CD13B691B7903F03F03B3712046E1 +:1033B000BDE8F883C27AE52B02F03F02B27143D038 +:1033C0002E2B41D022F0200108293DD00F2A40D1D8 +:1033D000590637D503F0BF05336B90F80D80F364C1 +:1033E000437B434530D1428B72BB03780D21FC688F +:1033F00023F04003DFF874E0013B4B4301211EF84A +:1034000001CB30F80CC009B3FF2B1DD824F813C032 +:103410006146013301320D2AF1D10278520605D5F9 +:1034200021B1FF2B10D8002224F81320013DEDB26A +:1034300000213046FFF716FE0446002896D00023F0 +:10344000B363B4E7AB42CBD0FF25F1E7CC45E1D085 +:10345000FAE72DB9FEF740FE404501D10024A6E76A +:103460004FF0FF33F364A2E70424E8E70094000878 +:103470002DE9F04F002187B00446D0F80090FFF707 +:1034800013F9804670B999F80030042B33D1D9F87C +:103490000C00FEF779FF07462046FFF75DFF054663 +:1034A00020B18046404607B0BDE8F08FD9F8103013 +:1034B0009A8CBA42F0D193F823B040265D4506D1EC +:1034C000D9F80C3033F81530002BE5D1EAE7F106D6 +:1034D000D9F8103008BF0236985B01F04DF8D9F8E2 +:1034E0000C30824633F8150001F046F88245D3D1FE +:1034F00002360135E2E74FF0FF0A4FF0FF3B554639 +:10350000C4F84CB0A16B4846FEF77EFF00285CD1A2 +:10351000E66B3778002F77D0F27AE52F02F03F0381 +:10352000A37103D0120704D50F2B04D0C4F84CB0FC +:103530004FE00F2B54D194F84B3058063FD4790606 +:1035400045D5236B07F0BF0796F80DA0E364737BA6 +:1035500053453ED1738B002B3BD135780121D9F8EF +:103560000C3005F03F0501930D23013D5D43284BD1 +:1035700013F8012BB25A71B3FF2D059329D81046C9 +:10358000049200F0F9FF6B1C03900293019B33F847 +:10359000150000F0F1FF039981421AD1049A029DAF +:1035A0001146059B1B4A9342E2D133785A0604D553 +:1035B00019B1019B33F815305BB97D1EEDB20021C6 +:1035C0002046FFF74FFD00289CD080466AE7BD42A9 +:1035D000BDD0FF25F3E74FF6FF708242E2D0F8E757 +:1035E0002DB93046FEF778FD50453FF45BAF94F8B7 +:1035F0004B30DB079AD40B2204F14001304605F032 +:10360000D5FD002892D14DE74FF004084AE700BFEE +:10361000009400080D9400082DE9F04F90F84BB08D +:1036200099B004461BF0A00540F068810668F26876 +:1036300032F81530002B4AD13378042B40F08780C4 +:103640000F230E352046B5FBF3F5A91CFFF768FDE7 +:103650008146002877D1236B0135A3EB4515E3792B +:103660005A07E56435D523F004032046E371FFF7DC +:103670007DF950BB4FF0FF32616B2046FFF7E0F859 +:1036800018BBA3682BB3214604A8FFF71BFEE0B9C3 +:1036900070894FF40071D4E90423E0FB0123306901 +:1036A000C4E904233830FEF7EFFC3069D4E9042381 +:1036B0002830FEF7E9FCE379326904A843F00103FE +:1036C00082F82130FFF718FE18B181463BE0013542 +:1036D000AEE7D6E90354402200212046FEF72CFB3A +:1036E0008523012140222370C0234FF0C10C04EB3D +:1036F000010884F8203000231E469E46571C04F81B +:1037000002C0F0B2023204F807E021B135F813101C +:1037100009B10133DBB20F0AA15408F8027002327A +:10372000D706F2D135F813700136002FE6D184F8B0 +:103730002330831C28466370FEF726FE84F824009D +:10374000000A84F82500484619B0BDE8F08F04F15E +:1037500040070DF1100A1BF0010F97E807008AE8F7 +:10376000070000F0D38040234FF0010884F84B306D +:10377000BC46F368B8F1050F9AE80700ACE803000F +:103780002CF8022B4FEA12428CF8002059D9981ECF +:10379000424630F8021F002942D10DF10F0C0721DB +:1037A00002F00F0E914612090EF13000392888BF41 +:1037B0000EF1370001390CF8010902D0B9F10F0FF1 +:1037C000EED818AB7E205A1802F8580C3846002262 +:1037D000914206D010F801CB02F1010EBCF1200F8E +:1037E00031D104F13F0C072902F1010297BF18AB58 +:1037F00020205818013198BF10F8580C072A0CF8EF +:103800000200F0D92046FFF733FE8146002878D128 +:1038100008F10108B8F1640FAAD14FF0070992E747 +:103820004FF0100C01F0010E49080EEB4202D303D9 +:1038300044BF82F4883282F02102BCF1010CF1D144 +:10384000A7E74246A9E77246C2E7216B2046A1EBF3 +:103850004511FEF729FF814600287FF474AF4FF62B +:10386000FF783846FEF738FC0190A16B3046FEF732 +:10387000CBFD814600287FF466AFE36BE9B2019A85 +:103880004FF00D0CD6F80CE05A734FF00F02DFF832 +:10389000E0A0DA724A1E18730CFB02F28446987696 +:1038A000D87640451AF8019B0CF1010C18BF3EF880 +:1038B000120003EB090B18BF013203F809004FEAAD +:1038C0001029002808BF4046BCF10D0F8BF801906D +:1038D000E7D1404502D03EF812200AB941F040013C +:1038E0001970012300212046F370FFF7BBFB8146CE +:1038F00000287FF428AF013DB7D11BE04FF0060947 +:1039000021E704287FF41FAF84F84BB01BF0020FAF +:1039100020461BBF0C350D210125B5FBF1F518BF65 +:1039200001352946FFF7FCFB814600287FF40BAFE9 +:10393000013D8AD1A16B3046FEF766FD8146002825 +:103940007FF401AF01462022E06BFEF7F5F9E36B4F +:1039500003CF18605960BA7839889A72198194F83F +:103960004B30E26B03F0180313730123F370EAE6A4 +:103970000094000810B504460A463430FEF776FB82 +:10398000886004F13800FEF773FBC2E9040194F883 +:10399000213003F00203D3710023D36110BD000076 +:1039A00003284B8B04BF8A8A43EA024318467047B8 +:1039B0002DE9F04F0B7899B0044689462F2BD0F8AB +:1039C00000B001D05C2B09D14A46137891460132F0 +:1039D0002F2BFAD05C2BF8D0002301E0DBF81C3051 +:1039E000A3600023E3619BF80030042B1ED1A36881 +:1039F000E3B1DBF82030214604A82362DBF8243051 +:103A00006362DBF82830A362FFF75CFC0346002802 +:103A100054D1DBF8102002F13800FEF727FBC4E98F +:103A2000040392F8213003F00203E37199F80030A7 +:103A30001F2B00F2358180230021204684F84B3073 +:103A400019B0BDE8F04FFEF72FBE49460B78894606 +:103A500001312F2BFAD05C2BF8D01F2B8CBF002507 +:103A60000425012F2FD113882E2B31D1002322F8CA +:103A7000173004F140029F428CBF2E2120210133D8 +:103A80000B2B02F8011BF6D145F02005204684F8E7 +:103A90004B50FFF7EDFC94F84B30002800F0E78026 +:103AA00004280BD1990603F0040240F1DC80002ABF +:103AB00000F0F6808023002084F84B3019B0BDE878 +:103AC000F08F0425CDE7022F02D153882E2BCAD0C8 +:103AD000911E87BB002322F81730002F00F01181C0 +:103AE00032F81300194601332028F9D009B92E28DD +:103AF00001D145F00305901E30F817302E2B01D070 +:103B0000013FF9D14FF020334FF0000A6364D046F3 +:103B10002364C4F847300823481C32F81160009031 +:103B2000F6B1202E03D02E2E0DD1B84210D045F084 +:103B300003050099F0E731F81730202B01D02E2B28 +:103B4000C8D1013FC5E79A4505D20099B9423BD19A +:103B50000B2B30D101E00B2B27D145F003050B23B4 +:103B600094F84020E52A04BF052284F84020082B61 +:103B700004BF4FEA88085FFA88F808F00C030C2BA2 +:103B800003D008F00303032B01D145F00205A80779 +:103B90003FF57CAF18F0010F18BF45F0100518F085 +:103BA000040F18BF45F0080570E70099B94202D02C +:103BB00045F00305D4D84FEA88080B234FF0080AD4 +:103BC00000975FFA88F8B4E77F2E15D9304640F2A7 +:103BD0005231CDE9022345F00203019300F098FC35 +:103BE00010F0800F0646DDE9022316D000F07F06B4 +:103BF00046498E5D019D46B331464548CDE90123D6 +:103C000005F0FEFADDE90123F8B9A6F1410189B218 +:103C100019291ED848F0020810E0FF28EAD9591ED9 +:103C20008A4503D345F003059A4682E704EB0A016F +:103C3000000A0AF1010A019D81F8400004EB0A0123 +:103C40000AF1010A81F8406073E745F003055F2639 +:103C5000F4E7A6F1610189B219299EBF203E48F020 +:103C60000108B6B2EAE7002A08BF052026E75A078E +:103C70003FF524AFA379DB0645D59BF80000042867 +:103C800035D1A3682146E27923622369DBF810006D +:103C900023F0FF0313436362E36CA362FFF76AFE42 +:103CA00023680027DA6819F8010B00283FF409AFF0 +:103CB00040F25231009200F04BFC054608B31F2839 +:103CC000009A7FF6FEAE2F283FF4BFAE5C283FF48B +:103CD000BCAE7F2805D801460E4805F091FA009A3F +:103CE00078B9FF2F0DD022F817500137DBE7216B91 +:103CF0000BF14C03C1F308011944FFF751FEA0601A +:103D0000CEE70620DAE60520D8E600BF809300085B +:103D100079930008709300081FB5CDE9001003A83F +:103D200014460391FEF700FA002815DB0B4A52F8FF +:103D300020300BB100211970019B0BB100211970CB +:103D400042F820302CB1002201A96846FEF7C8FED7 +:103D50000446204604B010BD0B24FAE73C36002090 +:103D60002DE9F04798B0904605460191002800F0F3 +:103D7000528102F03F0603A901A83246FEF7B0FEC9 +:103D8000002840F04681039B4FF48C60049303F0BD +:103D90009BFA0746002800F04081039B00F5007263 +:103DA0000199D86004A81A61FFF702FE044620B901 +:103DB0009DF95B30002BB8BF062418F01C0F00F0F3 +:103DC000CD80002C4CD0042C40D104A8FFF724FC5B +:103DD000044600283AD146F00806039B1A78042AC4 +:103DE00040F08380186929462B60FFF7C3FD039BD1 +:103DF0001E22002118690230FDF79EFF039C00215E +:103E00001A2220692630FDF797FF236920221A71B4 +:103E1000246903F093FA0146012208342046FEF794 +:103E20002BF9039B04A81B6983F82120FFF764FA90 +:103E3000044658B9A96801B302462846FEF718FDA2 +:103E4000AB68039A0446013B5361B4B1384603F0B2 +:103E50004BFA0CB100232B60204618B0BDE8F08768 +:103E60009DF8163013F0110F40F0848018F0040F05 +:103E700040F0C98018F0080FAFD1039A31071399A9 +:103E8000936C48BF46F04006E964AB6410780428A0 +:103E900072D1069B9DF817102B62089B106923F0C6 +:103EA000FF030B4329466B62179BAB62FFF762FD72 +:103EB000DDF80CA00024002205F15008BAF8063005 +:103EC00021464046C5F800A0AB80002385F830604D +:103ED00085F831406C64C5E90E234FF40072FDF79C +:103EE0002BFFB20653D40024B0E703F027FA0146B3 +:103EF000009013980E30FEF7BFF813980099163013 +:103F0000FEF7BAF8039C13992078FFF749FD2023A8 +:103F100000228046CB7220461399FEF7D1F8139BFE +:103F2000002201211A775A779A77DA77039BD970A2 +:103F3000B8F1000FA1D0414604A8D3F84890FEF78D +:103F400097FC0446002881D149460398FEF75CFAA5 +:103F5000039B044608F1FF30586176E7002C7FF49C +:103F600075AF9DF81630DC064FD418F0020F84D0E0 +:103F7000D80782D5072469E7FFF712FD0023A86060 +:103F800001F11C00FEF772F86B61286190E7D5E93A +:103F9000046956EA0903A6D0BAF80AA0A9684FEA4C +:103FA0004A2AC5E90E69B24574EB09031BD3002404 +:103FB0002964002C7FF44AAFC6F30803002B92D08B +:103FC000039C2046FEF770F808B3760A01234146A9 +:103FD00046EAC95682196A64607802F0E5FC041E5C +:103FE00018BF012432E72846FEF7C6FAB6EB0A06E8 +:103FF000014669F10009012803D9431CD3D10124EA +:10400000D6E70224D4E7082420E704241EE702248C +:104010001CE704461EE709241EE711241CE70000E4 +:104020002DE9F04F994685B00023884603A9044640 +:10403000C9F800301646FEF791F8054680BB94F8A3 +:1040400031506DBB94F8303013F00103009300F051 +:10405000A68004F1500AD4E90432D4E90E011B1AF7 +:1040600062EB0102B34272F1000238BF1E46BEB1DC +:10407000D4E90E10C1F30803002B40F08280039BAB +:104080005A894B0A013A43EAC0531A401BD151EAFC +:10409000000309D1A06801280DD8022584F8315009 +:1040A000284605B0BDE8F08F216C20460192FEF74E +:1040B00063FA019AEFE7431C04D10123009D84F8C1 +:1040C0003130EDE72064DDF80CB0216C5846FDF787 +:1040D000EBFF0028E1D0B6F5007F02EB000731D3FB +:1040E000BBF80A1002EB5620730A88429BF80100C5 +:1040F00088BF8B1A3A464146019302F055FC0028CE +:10410000DBD194F93020019B002A0BDA606CC01BD4 +:10411000984207D24FF40072514608EB4020FDF759 +:10412000E5FD019B5F02D9F80030F61BB8443B4423 +:10413000C9F80030D4E90E32DB1942F10002C4E9BB +:104140000E3294E7626CBA421AD094F93030002BE8 +:104150000DDA012351469BF8010002F049FC0028CA +:10416000ABD194F8303003F07F0384F830300398FB +:1041700001233A465146407802F016FC00289CD1B3 +:104180006764A16B4046C1F30801C1F50077514453 +:10419000B74228BF37463A46FDF7A8FDC3E70725D3 +:1041A0007EE7000070B596B00E460022019002A98D +:1041B00001A8FEF795FC0446E0B94FF48C6003F0CB +:1041C00083F80546D8B1029B00F500720199D860CA +:1041D00002A81A61FFF7ECFB044640B99DF9533081 +:1041E000002B0ADB1EB1314602A8FDF7EDFF284681 +:1041F00003F07AF8204616B070BD0624F7E71124C4 +:10420000F8E7000070B5B8B00222019003A901A838 +:10421000FEF766FC044608BB039B4FF48C601093CA +:1042200003F052F80546002866D0039B00F50072A3 +:104230000199D86010A81A61FFF7BAFB044650B97B +:104240009DF88B30980655D4190653D49DF8463006 +:10425000DA0706D50724284603F046F8204638B08A +:1042600070BD039B04931878042814D104A918691D +:10427000FFF780FB069E9DF84630DB0610D410A8A1 +:10428000FEF776FF04460028E5D156BB0398FEF7FB +:10429000DBFB0446DFE71F99FFF782FB0646EAE7F0 +:1042A000039BDA69B242D5D024930021269624A834 +:1042B0001B78042B01BFDDE90823CDE928239DF8F5 +:1042C00017308DF89730FEF7EFF904460028C2D179 +:1042D00024A8FFF741F804460028BBD00428BAD12F +:1042E000CDE70246314604A8FEF7C2FA044600288C +:1042F000B1D1CBE70624AEE71124AFE7F0B5BDB0EE +:10430000CDE900106846FDF70FFF022203A901A8BE +:10431000FEF7E6FB0446002841D1039B4FF48C6076 +:10432000149302F0D1FF0546002800F0EE80039BB5 +:1043300000F5007214AE0199D8601A613046FFF79B +:1043400037FB044640BB9DF89B3013F0A00F40F0B4 +:10435000D880039B009F1A78042A68D11B6904AC9B +:1043600003F1400C1868083353F8041C22466345D7 +:1043700003C21446F6D15022314628A8FDF7B6FCF8 +:10438000394628A8FFF714FB044600284CD12A9A86 +:10439000169B9A4206D00824284602F0A5FF204624 +:1043A0003DB0F0BD349A209B9A42F4D128A8FFF783 +:1043B00033F904460028EFD1039B04AF1B6993F83F +:1043C00001E093F823C09C8C3A46083303CAB242FA +:1043D00043F8080C43F8041C1746F5D1039B28A8A2 +:1043E0001B6983F801E0039B1A6982F823C01A69EC +:1043F00082F82440240A82F825401A691379D906E4 +:104400005CBF43F020031371FEF776FF04460028DB +:10441000C2D13046FEF7ACFE04460028BCD103985A +:10442000FEF712FB0446B7E70428B5D1BEE7239A8E +:1044300004AB02F1200C1068083252F8041C1C4630 +:10444000624503C42346F6D15022314628A8FDF721 +:104450004DFC394628A8FFF7ABFA044600284CD19A +:104460002A9A169B9A4296D1349A209B9A4292D1CC +:1044700028A8FFF7D1F8044600288DD137990DF10F +:104480001D030DF12D0001F10D0253F8044B834281 +:1044900042F8044BF9D11888012710809B7893705B +:1044A0009DF81B30039CDA0658BF43F02003CB7203 +:1044B000E770CB7ADB06ACD5169A2A9B9A42A8D035 +:1044C0002078FFF76DFA01462046FDF7EDFD014625 +:1044D000C8B12046FDF798FF044600287FF45CAF82 +:1044E000039890F86D302E2B93D12A9A00F16C012D +:1044F000FDF7E6FD039BDF708BE704287FF44CAFEC +:10450000B6E7062448E7022446E7112447E70000FF +:104510007F2810B501D880B210BDB0F5803F13D20E +:1045200040F2523399420FD10849002231F8024B30 +:1045300093B2844203D103F18000C0B2ECE70132B0 +:10454000802AF3D11346F6E70020E5E7C09600087D +:104550007F280DD940F25233994208D1FF2806D85E +:1045600000F10040034B803833F810007047002002 +:10457000704700BFC0960008B0F5803FF0B522D26A +:104580001F4A83B21F49B0F5805F28BF0A46141D39 +:1045900034F8042C2146AAB1934213D334F8025CB8 +:1045A0002E0AEFB252FA85F5A84222DA082E09D86F +:1045B000DFE806F0050A10121416181A1C00801AFB +:1045C00034F810301846F0BD981A00F001001B1A9C +:1045D0009BB2F7E7103BFBE7203BF9E7303BF7E7FF +:1045E0001A3BF5E70833F3E7503BF1E7A3F5E35354 +:1045F000EEE70434002ECBD101EB4702C7E700BF42 +:10460000109400080496000808B5074B074A19687B +:1046100001F03D01996053680BB190689847BDE87F +:10462000084003F09DB800BF00000240443600205F +:1046300008B5084B1968890901F03D018A019A60A3 +:10464000054AD3680BB110699847BDE8084003F0EC +:1046500087B800BF000002404436002008B5084B70 +:104660001968090C01F03D010A049A60054A536972 +:104670000BB190699847BDE8084003F071B800BFDE +:10468000000002404436002008B5084B1968890D27 +:1046900001F03D018A059A60054AD3690BB1106AA1 +:1046A0009847BDE8084003F05BB800BF0000024037 +:1046B0004436002008B5074B074A596801F03D0110 +:1046C000D960536A0BB1906A9847BDE8084003F07F +:1046D00047B800BF000002404436002008B5084B30 +:1046E0005968890901F03D018A01DA60054AD36AF7 +:1046F0000BB1106B9847BDE8084003F031B800BF1C +:10470000000002404436002008B5084B5968090CE7 +:1047100001F03D010A04DA60054A536B0BB1906B5E +:104720009847BDE8084003F01BB800BF00000240F6 +:104730004436002008B5084B5968890D01F03D0149 +:104740008A05DA60054AD36B0BB1106C9847BDE857 +:10475000084003F005B800BF0000024044360020C6 +:1047600008B5074B074A196801F03D019960536C81 +:104770000BB1906C9847BDE8084002F0F1BF00BF54 +:10478000000402404436002008B5084B1968890926 +:1047900001F03D018A019A60054AD36C0BB1106D9E +:1047A0009847BDE8084002F0DBBF00BF00040240AC +:1047B0004436002008B5084B1968090C01F03D018A +:1047C0000A049A60054A536D0BB1906D9847BDE895 +:1047D000084002F0C5BF00BF00040240443600207C +:1047E00008B5084B1968890D01F03D018A059A60EA +:1047F000054AD36D0BB1106E9847BDE8084002F032 +:10480000AFBF00BF000402404436002008B5074B8C +:10481000074A596801F03D01D960536E0BB1906EA3 +:104820009847BDE8084002F09BBF00BF000402406B +:104830004436002008B5084B5968890901F03D014C +:104840008A01DA60054AD36E0BB1106F9847BDE854 +:10485000084002F085BF00BF00040240443600203B +:1048600008B5084B5968090C01F03D010A04DA60EB +:10487000054A536F0BB1906F9847BDE8084002F0AE +:104880006FBF00BF000402404436002008B5084B4B +:104890005968890D01F03D018A05DA60054AD36F38 +:1048A00013B1D2F880009847BDE8084002F058BF25 +:1048B000000402404436002000230C4910B51A467B +:1048C0000B4C0B6054F82300026001EB43000433EF +:1048D0004260402BF6D1074A4FF0FF339360D3601C +:1048E000C2F80834C2F80C3410BD00BF44360020B2 +:1048F000C0970008000002400F28F8B510D9102812 +:1049000010D0112811D0122808D10F240720DFF869 +:10491000C8E00126DEF80050A04208D9002653E086 +:104920000446F4E70F240020F1E70724FBE706FA2A +:1049300000F73D424AD1264C4FEA001C3D4304EBB0 +:1049400000160EEBC000CEF80050C0E90123FBB208 +:1049500073B12048D0F8D83043F00103C0F8D83004 +:10496000D0F8003143F00103C0F80031D0F8003135 +:1049700017F47F4F0ED01748D0F8D83043F0020319 +:10498000C0F8D830D0F8003143F00203C0F800314D +:10499000D0F8003154F80C00036823F01F030360C3 +:1049A000056815F00105FBD104EB0C033D2493F8D9 +:1049B0000CC05F6804FA0CF43C602124056044617B +:1049C00012B1987B00F0CAFC3046F8BD0130A3E775 +:1049D000C0970008004402584436002010B5302427 +:1049E00084F31188FFF788FF002383F3118810BD3B +:1049F00010B50446807B00F0C7FC01231549627B9B +:104A000003FA02F20B6823EA0203DAB20B6072B90E +:104A1000114AD2F8D81021F00101C2F8D810D2F80A +:104A2000001121F00101C2F80011D2F8002113F4A5 +:104A30007F4F0ED1084BD3F8D82022F00202C3F8E2 +:104A4000D820D3F8002122F00202C3F80021D3F8C5 +:104A5000003110BD443600200044025808B5302310 +:104A600083F31188FFF7C4FF002383F3118808BD87 +:104A7000836CC26A8B42506810B506D95A1E4C002E +:104A800002EB4103B3FBF4F3184410BD01F0010342 +:104A90008A0748BF43F002034A0748BF43F00803B0 +:104AA0000A0748BF43F00403CA0648BF43F0100397 +:104AB0008A06426B48BF43F02003134343637047A9 +:104AC00010B5074C204600F0CBFF064B0022C4E98E +:104AD0001023054BA364054BE363054BE36410BD52 +:104AE000C83600200070005200B4C4041C370020F7 +:104AF0001C390020C36A0BB9104BC3620379012B28 +:104B000011D10F4B98420ED10E4BD3F8D42042F462 +:104B10008032C3F8D420D3F8FC2042F48032C3F8AA +:104B2000FC20D3F8FC30436C00221A65DA621A606C +:104B30005A605A624FF0FF329A637047C09800087B +:104B4000C8360020004402580379012B1BD0436C67 +:104B500000221A65DA621A605A605A624FF0FF3218 +:104B60009A63094B98420ED1084BD3F8D42022F413 +:104B70008032C3F8D420D3F8FC2022F48032C3F86A +:104B8000FC20D3F8FC307047C8360020004402589F +:104B900010B5446C0649FFF76BFF6060236842F272 +:104BA000107043F003032360BDE8104001F05EBDC8 +:104BB000801A06000129F8B5466C0B4F09D17568BB +:104BC0000A493D40FFF754FF054345F480557560A1 +:104BD000F8BD746806493C40FFF74AFF044344F4BB +:104BE00080547460F4E700BF00ECFFFF80F0FA022D +:104BF00040787D01436C00225A601A6070470000C3 +:104C0000426C0129536823F4404304D0022905D0A3 +:104C100001B95360704743F48043FAE743F400431B +:104C2000F7E70000436C41F480519A60D9605A6BF9 +:104C30001206FCD580229A637047000010B541F43B +:104C40008851446CA260E160616B11F04502FBD0B9 +:104C5000A26311F0040203D0FFF718FF012010BD7A +:104C6000616910461960FAE710B541F48851446C47 +:104C7000A260E160616B11F04502FBD0A26311F00C +:104C8000050203D0FFF702FF012010BD6169104645 +:104C90001960FAE773B5134604460E46302282F3D4 +:104CA0001188426CD26B32B14FF0FF31403001932A +:104CB00001F0E8FC019B606C00220265C263C262E5 +:104CC000456B15F4807504D185F31188012002B07D +:104CD00070BD4FF0FF31816382F31188012E06D938 +:104CE0000C21204602B0BDE87040FFF7BDBF104662 +:104CF000EDE7000073B5446C0E4600250192616B30 +:104D0000A1632565E562FFF7C1FE012E07D9019B6E +:104D10002A460C2102B0BDE87040FFF7A5BF02B0E3 +:104D200070BD000010B541F49851446CA260E16080 +:104D3000616B11F04502FBD0A26311F03F0203D07A +:104D4000FFF7A4FE012010BD216A10461960E16939 +:104D50005960A16999606169D960F4E72DE9F74369 +:104D600004460191006D01A91746984602F020FC07 +:104D7000064600284AD0626C2046DDF8049055684B +:104D8000C5F3090501356B00A56CB5FBF3F54FF4D0 +:104D90007A73B5FBF3F55D43556200F027FE50BB17 +:104DA000636C4FF0FF3201254146C3F8589020460E +:104DB0001D659A634FF49572DA6342F207029F62AF +:104DC000DA62E36C0A9AFFF74FFFA0B9E26C104B6E +:104DD00011680B407BB929462046FFF75BFF05466B +:104DE00048B92E463A460199206D02F019FC30462A +:104DF00003B0BDE8F0833A460199206D02F010FC43 +:104E0000E26C01212046FFF775FFF0E70126EEE78F +:104E100008E0FFFD2DE9F7431F46436C01924FF474 +:104E20007A725D6804468846C5F3090501356E004F +:104E3000856CB5FBF6F5B5FBF2F555435D6200F008 +:104E4000D5FD20B10125284603B0BDE8F0837E02E0 +:104E500001A9206D324602F0ABFB05460028F1D0D7 +:104E6000636C019AD4F84C909A6501221A654FF050 +:104E7000FF329A634FF49572DA639E62236BDB060E +:104E80004B4658BF4FEA4828012F42461BD91221F2 +:104E90002046FFF7E9FEC0B9D9F80020104B1340B7 +:104EA0009BB9636C42F2930239462046DA62E26CA7 +:104EB000FFF7F0FE804640B932460199206D454625 +:104EC00002F0AEFBBFE71121E2E732460199206D07 +:104ED00002F0A6FBE26C39462046FFF70BFFB2E773 +:104EE00008E0FFFD2DE9F3411F46436C01924FF4AA +:104EF0007A725D6804468846C5F3090501356E007F +:104F0000856CB5FBF6F5B5FBF2F555435D6200F037 +:104F10006DFD20B10125284602B0BDE8F0817E027A +:104F200001A9206D324602F089FB05460028F1D028 +:104F3000636C019A9A6501221A654FF0FF329A63F9 +:104F40004FF48D72DA639E62236BE66CDB063346A8 +:104F500058BF4FEA4828012F424619D91921204647 +:104F6000FFF782FEB0B932680F4B134093B9636C00 +:104F700042F2910239462046DA62E26CFFF78AFE7D +:104F8000064638B901993546206D02F093FBC2E719 +:104F90001821E4E70199206D02F08CFBE26C3946A0 +:104FA0002046FFF7A7FEB6E708E0FFFD12F0030F6B +:104FB0002DE9F04107460C4615461E4617D00E4413 +:104FC000B44202D10020BDE8F0810123FA6B2146F2 +:104FD0003846FFF71FFF0028F5D128464FF400722E +:104FE000F96B05F500750134FCF780FEE8E7BDE8D4 +:104FF000F041FFF70FBF000012F0030F2DE9F04161 +:1050000007460C4615461E4617D00E44B44202D140 +:105010000020BDE8F08129464FF40072F86B05F5D9 +:105020000075FCF763FE0123FA6B21463846FFF753 +:1050300059FF0028EDD10134E8E7BDE8F041FFF762 +:1050400051BF000000207047302310B583F3118852 +:105050000024436C40302146DC6301F021FB84F3E3 +:10506000118810BD026843681143016003B11847FD +:1050700070470000024A136843F0C0031360704792 +:1050800000440040024A136843F0C00313607047B5 +:1050900000480040024A136843F0C00313607047A1 +:1050A00000780040064BD3F8E8200243C3F8E8201C +:1050B000D3F810211043C3F81001D3F81031704712 +:1050C0000044025837B5274C274D204600F028FDF4 +:1050D00004F11400009400234FF40072234900F0FF +:1050E000C3F94FF40072224904F138000094214BB7 +:1050F00000F03CFA204BC4E91735204C204600F064 +:105100000FFD04F11400009400234FF400721C49B9 +:1051100000F0AAF94FF400721A4904F13800009423 +:10512000194B00F023FA194BC4E91735184C2046E7 +:1051300000F0F6FC04F1140000234FF4007215494E +:10514000009400F091F9144B4FF40072134904F1EC +:105150003800009400F00AFA114BC4E9173503B087 +:1051600030BD00BF2039002000E1F505643A002081 +:105170006440002075500008004400408C39002035 +:10518000643C002064420020855000080048004034 +:10519000F8390020643E0020955000086444002047 +:1051A0000078004038B5264D0446037C002918BF1E +:1051B0000D46012B06D1234B984230D14FF40030DD +:1051C000FFF770FF2A68236EE16D03EB5203A566BB +:1051D000B3FBF2F36A68100442BF23F0070003F048 +:1051E000070343EA4003CB60AB6843F040034B60E6 +:1051F000EB6843F001038B6042F4967343F00103C4 +:105200000B604FF0FF330B62510505D512F01022F1 +:1052100011D0B2F1805F10D084F8643038BD0A4BF1 +:10522000984205D0094B9842CCD14FF08040C7E757 +:105230004FF48020C4E77F23EEE73F23ECE700BF75 +:10524000C8980008203900208C390020F839002047 +:105250002DE9F047C66D05463768F46921073462C9 +:105260001AD014F0080118BF4FF48071E20748BF4C +:1052700041F02001A3074FF0300348BF41F0400147 +:10528000600748BF41F0800183F31188281DFFF7B4 +:10529000E9FE002383F31188E2050AD5302383F366 +:1052A00011884FF48061281DFFF7DCFE002383F393 +:1052B00011884FF030094FF0000A14F0200838D15F +:1052C0003B0616D54FF0300905F1380A200610D5F7 +:1052D00089F31188504600F07DF9002836DA08215C +:1052E000281DFFF7BFFE27F080033360002383F300 +:1052F0001188790614D5620612D5302383F31188FC +:10530000D5E913239A4208D12B6C33B127F040071B +:105310001021281DFFF7A6FE3760002383F31188B4 +:10532000E30618D5AA6E1369ABB15069BDE8F04722 +:10533000184789F31188736A284695F86410194054 +:1053400000F008FC8AF31188F469B6E7B06288F3CC +:105350001188F469BAE7BDE8F0870000090100F19F +:105360006043012203F56143C9B283F8001300F0E2 +:105370001F039A4043099B0003F1604303F5614317 +:10538000C3F880211A60704700F01F0301229A4081 +:10539000430900F160409B0000F5614003F1604368 +:1053A00003F56143C3F88020C3F88021002380F80F +:1053B00000337047F8B51546826804460B46AA428A +:1053C00000D28568A1692669761AB5420BD21846C3 +:1053D0002A46FCF78BFCA3692B44A3612846A368EB +:1053E0005B1BA360F8BD0CD9AF1B18463246FCF717 +:1053F0007DFC3A46E1683044FCF778FCE3683B44C6 +:10540000EBE718462A46FCF771FCE368E5E7000085 +:1054100083689342F7B50446154600D28568D4E9FF +:105420000460361AB5420BD22A46FCF75FFC63696A +:105430002B4463612846A3685B1BA36003B0F0BDE7 +:105440000DD93246AF1B0191FCF750FC01993A4649 +:10545000E0683144FCF74AFCE3683B44E9E72A464C +:10546000FCF744FCE368E4E710B50A440024C36198 +:10547000029B8460C16002610362C0E90000C0E970 +:10548000051110BD08B5D0E90532934201D18268FB +:1054900082B98268013282605A1C4261197000210F +:1054A000D0E904329A4224BFC368436101F012F983 +:1054B000002008BD4FF0FF30FBE7000070B530233F +:1054C00004460E4683F31188A568A5B1A368A269B6 +:1054D000013BA360531CA36115782269934224BF4A +:1054E000E368A361E3690BB120469847002383F387 +:1054F0001188284607E03146204601F0DBF80028F5 +:10550000E2DA85F3118870BD2DE9F74F04460E46A7 +:1055100017469846D0F81C904FF0300A8AF311884D +:105520004FF0000B154665B12A4631462046FFF77D +:1055300041FF034660B94146204601F0BBF8002810 +:10554000F1D0002383F31188781B03B0BDE8F08FFE +:10555000B9F1000F03D001902046C847019B8BF39F +:105560001188ED1A1E448AF31188DCE7C160C3611B +:10557000009B82600362C0E905111144C0E900008C +:1055800001617047F8B504460D461646302383F393 +:105590001188A768A7B1A368013BA36063695A1C7F +:1055A00062611D70D4E904329A4224BFE3686361EA +:1055B000E3690BB120469847002080F3118807E08B +:1055C0003146204601F076F80028E2DA87F31188A8 +:1055D000F8BD0000D0E9052310B59A4201D18268D8 +:1055E0007AB982680021013282605A1C82611C787B +:1055F00003699A4224BFC368836101F06BF82046B7 +:1056000010BD4FF0FF30FBE72DE9F74F04460E4683 +:1056100017469846D0F81C904FF0300A8AF311884C +:105620004FF0000B154665B12A4631462046FFF77C +:10563000EFFE034660B94146204601F03BF80028E2 +:10564000F1D0002383F31188781B03B0BDE8F08FFD +:10565000B9F1000F03D001902046C847019B8BF39E +:105660001188ED1A1E448AF31188DCE70379052BB3 +:1056700005BF836A002001204B6004BF4FF4007314 +:105680000B60704770B55D1E866A04460D44B542D6 +:1056900005D9436B43F080034363012070BD0625A9 +:1056A0000571FFF783FC05232371F7E770B55D1ED5 +:1056B000866A04460D44B54205D9436B43F0800326 +:1056C0004363012070BD07250571FFF795FC052395 +:1056D0002371F7E738B505790446052D05D1082370 +:1056E0000371FFF7AFFC257138BD0120FCE7000016 +:1056F0000323F0B5037185B00446FFF749FA002291 +:1057000020461146FFF78EFA4FF4D57203AB0821FD +:105710002046FFF7A9FA0246B8B901232363039B89 +:10572000C3F30323012B09D103AB37212046FFF735 +:105730009BFA18B9A44B039A1340ABB1204601253C +:10574000FFF758FA0223237137E103AB0022372118 +:105750002046FFF789FA28B99B4A039B1A40002A82 +:1057600000F0A78002232363236B03F00F03022BB7 +:1057700040F0A9806425954E42F2107000F076FF4B +:1057800003AB324601212046FFF758FA0028D5D155 +:10579000039B002B80F293805A0003D5236B43F0C8 +:1057A00010032363002204F1080302212046FFF7BF +:1057B000B9FA02460028C1D104F13803032120467A +:1057C000FFF752FA0028B9D104F11805A26B09219C +:1057D00020462B46FFF7A6FA0028AFD102ABA26BFA +:1057E00007212046FFF740FA06460028A6D1236B82 +:1057F00003F00F03022B40F08F807E227F2128468A +:1058000003F01CFA012840F28780E76B42F2107027 +:1058100000F02CFF08234FF4007239462046009612 +:10582000FFF79CFA002889D1384603F055FA236B1C +:10583000A06203F00F03022B72D103AB644A06216E +:105840002046FFF711FA002871D15F49039B1940E8 +:10585000B1FA81F149092046FFF7ACF902AB4FF4E8 +:10586000007210212046FFF7FFF9054600287FF45B +:1058700065AF554E029B33427FF460AF236B13F04C +:105880000E0F03F00F0273D0022A7FF457AFE36AC2 +:105890001978012900F09480022900F093800029F2 +:1058A00000F089804B4F2046FFF7AAF903AB3A4638 +:1058B00076E0114620462263FFF7B4F954E7013D34 +:1058C0007FF45AAF3AE7444D6426444A3E4F012BD9 +:1058D00018BF154603AB002237212046FFF7C4F955 +:1058E00000287FF42BAF039B3B427FF427AF03AB31 +:1058F0002A4629212046FFF7A1F900287FF41EAF90 +:10590000039B002BFFF648AF013E3FF417AF42F276 +:10591000107000F0ABFEDDE7284603F0B1F986E732 +:105920007E227F212846E66B03F088F908B9002122 +:1059300091E7002340223146204600930623FFF7DB +:105940000DFA0028F3D1B3895BBA9B07EFD5244B3E +:1059500040223146204600930623FFF7FFF9002836 +:10596000E5D1317C01F00F010F3918BF012172E739 +:10597000E36A1978F9B101297FF4E0AE2046FFF718 +:105980003FF903ABA26B37212046FFF76DF90028E2 +:105990007FF4D4AE039B33427FF4D0AE03AB02223C +:1059A00006212046FFF760F900287FF4C7AE039B6D +:1059B00033427FF4C3AE05232371284605B0F0BD02 +:1059C000084F70E7084F6EE708E0FFFD0080FFC05A +:1059D0000001B9030000B7030080FF5000001080F1 +:1059E000F1FFFF800001B7030002B70337B504469B +:1059F0000C4D01ABA26B0D212046FFF735F978B9AC +:105A0000019B2B420BD1C3F34323042B08D0053B4E +:105A1000022B04D84FF47A7000F028FEE9E7012049 +:105A200003B030BD08E0FFFD70B53023054683F3B9 +:105A3000118803790024022B03D184F311882046B6 +:105A400070BD0423037184F311880226FFF7CEFF93 +:105A500004462846FFF7CEF82E71F0E7FFF730B87E +:105A6000044B03600123037100234363C0E90A333D +:105A7000704700BFE098000810B53023044683F358 +:105A80001188C162FFF736F802230020237180F3EA +:105A9000118810BD10B53023044683F31188FFF739 +:105AA00053F800230122E362227183F3118810BDB1 +:105AB000026843681143016003B118477047000052 +:105AC0001430FFF721BD00004FF0FF331430FFF713 +:105AD0001BBD00003830FFF797BD00004FF0FF33CB +:105AE0003830FFF791BD00001430FFF7E7BC00002D +:105AF0004FF0FF311430FFF7E1BC00003830FFF702 +:105B000041BD00004FF0FF323830FFF73BBD0000D1 +:105B1000012914BF6FF0130000207047FFF7D2BABD +:105B2000044B036000234360C0E902330123037484 +:105B3000704700BF0499000810B53023044683F372 +:105B40001188FFF72FFB02230020237480F31188B4 +:105B500010BD000038B5C36904460D461BB90421C9 +:105B60000844FFF7A5FF294604F11400FFF78AFC5B +:105B7000002806DA201D4FF40061BDE83840FFF729 +:105B800097BF38BD026843681143016003B11847ED +:105B90007047000013B5406B00F58054D4F8A4386A +:105BA0001A681178042914D1017C022911D11979BC +:105BB000012312898B4013420BD101A94C3002F012 +:105BC0006BFFD4F8A4480246019B2179206800F0BD +:105BD000DFF902B010BD0000143002F0EDBE00008D +:105BE0004FF0FF33143002F0E7BE00004C3002F0FB +:105BF000BFBF00004FF0FF334C3002F0B9BF0000D0 +:105C0000143002F0BBBE00004FF0FF31143002F040 +:105C1000B5BE00004C3002F08BBF00004FF0FF32E9 +:105C20004C3002F085BF00000020704710B500F531 +:105C30008054D4F8A4381A681178042917D1017C4B +:105C4000022914D15979012352898B4013420ED174 +:105C5000143002F04DFE024648B1D4F8A4484FF487 +:105C6000407361792068BDE8104000F07FB910BD35 +:105C7000406BFFF7DBBF0000704700007FB5124BA1 +:105C800001250426044603600023057400F1840204 +:105C900043602946C0E902330C4B02901430019353 +:105CA0004FF44073009602F0FFFD094B04F6944256 +:105CB000294604F14C000294CDE900634FF440738F +:105CC00002F0C6FE04B070BD2C990008715C00089B +:105CD000955B00080A68302383F311880B790B3336 +:105CE00042F823004B79133342F823008B7913B128 +:105CF0000B3342F8230000F58053C3F8A4180223A5 +:105D00000374002080F311887047000038B5037FCA +:105D1000044613B190F85430ABB90125201D02217F +:105D2000FFF730FF04F114006FF00101257700F058 +:105D3000DDFC04F14C0084F854506FF00101BDE823 +:105D4000384000F0D3BC38BD10B501210446043002 +:105D5000FFF718FF0023237784F8543010BD0000AC +:105D600038B504460025143002F0B6FD04F14C00AD +:105D7000257702F085FE201D84F854500121FFF79D +:105D800001FF2046BDE83840FFF750BF90F8803053 +:105D900003F06003202B06D190F881200023212AF4 +:105DA00003D81F2A06D800207047222AFBD1C0E959 +:105DB0001D3303E0034A426707228267C36701205D +:105DC000704700BF4422002037B500F58055D5F854 +:105DD000A4381A68117804291AD1017C022917D134 +:105DE0001979012312898B40134211D100F14C041F +:105DF000204602F005FF58B101A9204602F04CFEF2 +:105E0000D5F8A4480246019B2179206800F0C0F82B +:105E100003B030BD01F10B03F0B550F8236085B03D +:105E200004460D46FEB1302383F3118804EB850749 +:105E3000301D0821FFF7A6FEFB6806F14C005B69E8 +:105E40001B681BB1019002F035FE019803A902F016 +:105E500023FE024648B1039B2946204600F098F8ED +:105E6000002383F3118805B0F0BDFB685A691268FE +:105E7000002AF5D01B8A013B1340F1D104F18002C6 +:105E8000EAE70000133138B550F82140ECB1302377 +:105E900083F3118804F58053D3F8A428136852794A +:105EA00003EB8203DB689B695D6845B104216018E0 +:105EB000FFF768FE294604F1140002F023FD204696 +:105EC000FFF7B4FE002383F3118838BD704700004C +:105ED00001F044BD01234022002110B5044600F822 +:105EE000303BFBF729FF0023C4E9013310BD00005C +:105EF00010B53023044683F3118824224160002129 +:105F00000C30FBF719FF204601F04AFD0223002068 +:105F1000237080F3118810BD70B500EB8103054636 +:105F200050690E461446DA6018B110220021FBF7C2 +:105F300003FFA06918B110220021FBF7FDFE3146D6 +:105F40002846BDE8704001F031BE00008368202281 +:105F5000002103F0011310B5044683601030FBF7F5 +:105F6000EBFE2046BDE8104001F0ACBEF0B40125C8 +:105F700000EB810447898D40E4683D43A469458175 +:105F800023600023A2606360F0BC01F0C9BE000082 +:105F9000F0B4012500EB810407898D40E4683D439E +:105FA0006469058123600023A2606360F0BC01F096 +:105FB0003FBF000070B50223002504462422037071 +:105FC0002946C0F888500C3040F8045CFBF7B4FE5A +:105FD000204684F8705001F07DFD63681B6823B192 +:105FE00029462046BDE87040184770BD0378052B50 +:105FF00010B504460AD080F88C300523037043683E +:106000001B680BB1042198470023A36010BD00005A +:106010000178052906D190F88C20436802701B682E +:1060200003B118477047000070B590F8703004460F +:1060300013B1002380F8703004F18002204601F093 +:1060400065FE63689B68B3B994F8803013F060050F +:1060500035D00021204602F057F90021204602F0F9 +:1060600047F963681B6813B1062120469847062349 +:1060700084F8703070BD204698470028E4D0B4F80A +:106080008630A26F9A4288BFA36794F98030A56FCB +:10609000002B4FF0300380F20381002D00F0F280DE +:1060A000092284F8702083F3118800212046D4E966 +:1060B0001D23FFF76DFF002383F31188DAE794F8BF +:1060C000812003F07F0343EA022340F2023293422D +:1060D00000F0C58021D8B3F5807F48D00DD8012BC2 +:1060E0003FD0022B00F09380002BB2D104F1880244 +:1060F00062670222A267E367C1E7B3F5817F00F020 +:106100009B80B3F5407FA4D194F88230012BA0D1BD +:10611000B4F8883043F0020332E0B3F5006F4DD09D +:1061200017D8B3F5A06F31D0A3F5C063012B90D879 +:106130006368204694F882205E6894F88310B4F86F +:106140008430B047002884D0436863670368A3673E +:106150001AE0B3F5106F36D040F6024293427FF456 +:1061600078AF5C4B63670223A3670023C3E794F80F +:106170008230012B7FF46DAFB4F8883023F0020336 +:10618000A4F88830C4E91D55E56778E7B4F8803095 +:10619000B3F5A06F0ED194F88230204684F88A308F +:1061A00001F0F6FC63681B6813B101212046984793 +:1061B000032323700023C4E91D339CE704F18B0300 +:1061C00063670123C3E72378042B10D1302383F3C3 +:1061D00011882046FFF7BAFE85F311880321636812 +:1061E00084F88B5021701B680BB12046984794F8B7 +:1061F0008230002BDED084F88B3004232370636858 +:106200001B68002BD6D0022120469847D2E794F88D +:10621000843020461D0603F00F010AD501F068FD09 +:10622000012804D002287FF414AF2B4B9AE72B4BA4 +:1062300098E701F04FFDF3E794F88230002B7FF4EC +:1062400008AF94F8843013F00F01B3D01A0620463B +:1062500002D502F071F8ADE702F062F8AAE794F80F +:106260008230002B7FF4F5AE94F8843013F00F01E8 +:10627000A0D01B06204602D502F046F89AE702F0AD +:1062800037F897E7142284F8702083F311882B469F +:106290002A4629462046FFF769FE85F31188E9E67C +:1062A0005DB1152284F8702083F311880021204607 +:1062B000D4E91D23FFF75AFEFDE60B2284F8702077 +:1062C00083F311882B462A4629462046FFF760FEB5 +:1062D000E3E700BF5C99000854990008589900084A +:1062E00038B590F870300446002B3ED0063BDAB249 +:1062F0000F2A34D80F2B32D8DFE803F037313108BA +:10630000223231313131313131313737856FB0F8A7 +:1063100086309D4214D2C3681B8AB5FBF3F203FB9F +:1063200012556DB9302383F311882B462A4629462E +:10633000FFF72EFE85F311880A2384F870300EE0F3 +:10634000142384F87030302383F31188002320460F +:106350001A461946FFF70AFE002383F3118838BD59 +:10636000C36F03B198470023E7E70021204601F0FF +:10637000CBFF0021204601F0BBFF63681B6813B10F +:106380000621204698470623D7E7000010B590F86D +:1063900070300446142B29D017D8062B05D001D80D +:1063A0001BB110BD093B022BFBD80021204601F098 +:1063B000ABFF0021204601F09BFF63681B6813B10F +:1063C000062120469847062319E0152BE9D10B2317 +:1063D00080F87030302383F3118800231A46194661 +:1063E000FFF7D6FD002383F31188DAE7C3689B69C2 +:1063F0005B68002BD5D1C36F03B19847002384F8A5 +:106400007030CEE70023826880F8243083691B68EF +:1064100099689142FBD25A680360426010605860EC +:10642000704700000023826880F8243083691B686D +:1064300099689142FBD85A680360426010605860C6 +:106440007047000008B50846302383F3118891F89F +:106450002430032B05D0042B0DD02BB983F31188E6 +:1064600008BD8B6A00221A604FF0FF338362FFF78A +:10647000C9FF0023F2E7D1E9003213605A60F3E765 +:10648000034610B51B68984203D09C688A68944202 +:10649000F8D25A680B604A601160596010BD000064 +:1064A000FFF7B0BF064BD96881F82400186802686E +:1064B00053601A600122D86080F82420F9F7A2BF47 +:1064C000684600200C4B30B5DD684B1C87B0044695 +:1064D0000FD02B46094A684600F09CF92046FFF78A +:1064E000E1FF009B13B1684600F09EF9A86A07B06F +:1064F00030BDFFF7D7FFF9E7684600204564000884 +:10650000044B1A68DB6890689B68984294BF00202F +:106510000120704768460020094B10B51C68D868F8 +:10652000226853601A600122DC6084F82420FFF79F +:1065300079FF01462046BDE81040F9F763BF00BF70 +:1065400068460020044B1A68DB6892689B689A4290 +:1065500001D9FFF7E1BF70476846002038B5012335 +:10656000084C00252370656002F0E4FB02F00AFC91 +:106570000549064802F0E0FC0223237085F31188E8 +:1065800038BD00BF1049002064990008684600200B +:1065900000F080B9034A516853685B1A9842FBD8EF +:1065A000704700BF001000E08B604B630023CA619E +:1065B00000F128020B6302230A618B8401238861A6 +:1065C00081F8263001F11003C26A4A611360C36288 +:1065D00001F12C030846CB6270470000D0E901317D +:1065E000026841F8183CA1F19C033839CB6003697B +:1065F00041F8243C436941F8203C034B41F8043CFA +:10660000C3680248FFF7D0BF1D0400086846002099 +:1066100008B5FFF7E3FFBDE80840FFF741BF000002 +:1066200038B50E4BDC6804F12C05A062E06AA84284 +:106630000FD194F826303BB994F825309B0702BF60 +:10664000D4E9043213605A600F20BDE83840FFF7E8 +:1066500029BF0368E362FFF723FFE7E768460020EE +:10666000302383F31188FFF7DBBF000008B5014634 +:10667000302383F311880820FFF724FF002383F3DE +:10668000118808BD054BDB6821B1036098620320C7 +:10669000FFF718BF4FF0FF30704700BF684600207B +:1066A00003682BB10022026018469962FFF7F8BE1A +:1066B00070470000064BDB6839B1426818605A60C9 +:1066C000136043600420FFF7FDBE4FF0FF307047BA +:1066D000684600200368984206D01A68026050603D +:1066E00018469962FFF7DCBE7047000038B50446D3 +:1066F0000D462068844200D138BD036823605C6089 +:106700008562FFF7CDFEF4E7036810B59C68A242EE +:106710000CD85C688A600B604C6021605960996895 +:106720008A1A9A604FF0FF33836010BD121B1B68FA +:10673000ECE700000A2938BF0A2170B504460D466F +:106740000A26601902F0F0FA02F0D8FA041BA542FA +:1067500003D8751C04462E46F3E70A2E04D90120FF +:10676000BDE8704002F0B0BC70BD0000F8B5144B3D +:106770000D460A2A4FF00A07D96103F11001826021 +:1067800038BF0A22416019691446016048601861E7 +:10679000A81802F0B9FA02F0B1FA431B0646A34268 +:1067A00006D37C1C28192746354602F0BDFAF2E7CD +:1067B0000A2F04D90120BDE8F84002F085BCF8BDDD +:1067C00068460020F8B506460D4602F097FA0F4AD3 +:1067D000134653F8107F9F4206D12A4601463046A1 +:1067E000BDE8F840FFF7C2BFD169BB68441A2C1955 +:1067F00028BF2C46A34202D92946FFF79BFF224619 +:1068000031460348BDE8F840FFF77EBF68460020E8 +:1068100078460020C0E90323002310B45DF8044B40 +:106820004361FFF7CFBF000010B5194C23699842B0 +:106830000DD08168D0E9003213605A609A680A442A +:106840009A60002303604FF0FF33A36110BD02681C +:10685000234643F8102F53600022026022699A42B7 +:1068600003D1BDE8104002F059BA936881680B4427 +:10687000936002F043FA2269E1699268441AA242E5 +:10688000E4D91144BDE81040091AFFF753BF00BF17 +:10689000684600202DE9F047DFF8BC8008F11007BA +:1068A0002C4ED8F8105002F029FAD8F81C40AA68EB +:1068B000031B9A423ED814444FF00009D5E9003238 +:1068C000C8F81C4013605A60C5F80090D8F8103022 +:1068D000B34201D102F022FA89F31188D5E90331DC +:1068E00028469847302383F311886B69002BD8D052 +:1068F00002F004FA6A69A0EB040982464A450DD207 +:10690000022002F0E1FB0022D8F81030B34208D197 +:1069100051462846BDE8F047FFF728BF121A224427 +:10692000F2E712EB09092946384638BF4A46FFF715 +:10693000EBFEB5E7D8F81030B34208D01444C8F8DD +:106940001C00211AA960BDE8F047FFF7F3BEBDE8BF +:10695000F08700BF784600206846002038B502F076 +:10696000CDF9054AD2E90845031B181945F1000184 +:10697000C2E9080138BD00BF6846002010B560B903 +:10698000074804790368053C9B6818BF01249847B1 +:1069900008B144F00404204610BD0124FBE700BF09 +:1069A000C8360020FFF7EABF2DE9F04788461746B2 +:1069B0009A460446B0B90D4E3579052D05D003240D +:1069C0000DE0013D15F0FF050ED032685346394603 +:1069D0003046D2F814904246C8470028F1D12046EC +:1069E000BDE8F0870424FAE70124F8E7C836002060 +:1069F0002DE9F047884617469A460446B0B90D4E31 +:106A00003579052D05D003240DE0013D15F0FF0576 +:106A10000ED03268534639463046D2F81890424676 +:106A2000C8470028F1D12046BDE8F0870424FAE7E2 +:106A30000124F8E7C836002037B50C46154670B972 +:106A400051B101290BD10748694603681B6A984771 +:106A500010B9019B04462B60204603B030BD0424CE +:106A6000FAE700BFC836002000207047FEE70000AC +:106A7000704700004FF0FF30704700004B684360E4 +:106A80008B688360CB68C3600B6943614B690362A9 +:106A90008B6943620B6803607047000008B53C4B8C +:106AA00040F2FF713B48D3F888200A43C3F888209E +:106AB000D3F8882022F4FF6222F00702C3F888206E +:106AC000D3F88820D3F8E0200A43C3F8E020D3F8B5 +:106AD00008210A43C3F808212F4AD3F80831114688 +:106AE000FFF7CCFF00F5806002F11C01FFF7C6FF45 +:106AF00000F5806002F13801FFF7C0FF00F580600B +:106B000002F15401FFF7BAFF00F5806002F1700155 +:106B1000FFF7B4FF00F5806002F18C01FFF7AEFFD4 +:106B200000F5806002F1A801FFF7A8FF00F5806082 +:106B300002F1C401FFF7A2FF00F5806002F1E0015D +:106B4000FFF79CFF00F5806002F1FC01FFF796FF64 +:106B500002F58C7100F58060FFF790FF01F084FC76 +:106B60000E4BD3F8902242F00102C3F89022D3F8E2 +:106B7000942242F00102C3F894220522C3F898201F +:106B80004FF06052C3F89C20054AC3F8A02008BD0E +:106B900000440258000002587899000800ED00E017 +:106BA0001F00080308B501F06BFEFFF7D7FC104B80 +:106BB000D3F8DC2042F04002C3F8DC20D3F80421F3 +:106BC00022F04002C3F80421D3F80431094B1A68BB +:106BD00042F008021A601A6842F004021A6000F0DB +:106BE00071FD00F035FBBDE8084000F0B5B800BF0E +:106BF00000440258001802480120704700207047E6 +:106C00007047000002290CD0032904D0012907484D +:106C100018BF00207047032A05D8054800EBC200C2 +:106C20007047044870470020704700BF7C9B0008F5 +:106C300054220020309B000870B59AB005460846E3 +:106C4000144601A900F0C2F801A8FBF76DF8431C37 +:106C50000022C6B25B001046C5E90034237003234E +:106C6000023404F8013C01ABD1B202348E4201D8A7 +:106C70001AB070BD13F8011B013204F8010C04F8BE +:106C8000021CF1E708B5302383F311880348FFF7AE +:106C90009BF8002383F3118808BD00BF184900202A +:106CA00090F8803003F01F02012A07D190F881206C +:106CB0000B2A03D10023C0E91D3315E003F0600364 +:106CC000202B08D1B0F884302BB990F88120212AEC +:106CD00003D81F2A04D8FFF759B8222AEBD0FAE7C5 +:106CE000034A426707228267C3670120704700BFDB +:106CF0004B22002007B5052917D8DFE801F0191647 +:106D000003191920302383F31188104A01210190BF +:106D1000FFF702F9019802210D4AFFF7FDF80D482F +:106D2000FFF71EF8002383F3118803B05DF804FB1E +:106D3000302383F311880748FEF7E8FFF2E730239A +:106D400083F311880348FEF7FFFFEBE7D09A0008B2 +:106D5000F49A00081849002038B50C4D0C4C2A460E +:106D60000C4904F10800FFF767FF05F1CA0204F1BE +:106D700010000949FFF760FF05F5CA7204F1180019 +:106D80000649BDE83840FFF757BF00BFF06100205B +:106D900054220020AC9A0008B99A0008C49A00084E +:106DA00070B5044608460D46FAF7BEFFC6B2204647 +:106DB000013403780BB9184670BD32462946FAF7FC +:106DC0009FFF0028F3D10120F6E700002DE9F84FDE +:106DD00005460C46FAF7A8FF2C49C6B22846FFF72D +:106DE000DFFF08B10336F6B229492846FFF7D8FF7E +:106DF00008B11036F6B2632E0DD8DFF89080DFF8B8 +:106E00009090244FDFF894A0DFF894B02E7846B924 +:106E10002670BDE8F88F29462046BDE8F84F02F0FD +:106E2000FDB9252E2ED1072241462846FAF768FFE4 +:106E300070B9DBF8003007350A3444F80A3CDBF857 +:106E4000043044F8063CBBF8083024F8023CDDE787 +:106E5000082249462846FAF753FF98B9A21C0E4B60 +:106E6000197802320909C95D02F8041C13F8011BE4 +:106E700001F00F015345C95D02F8031CF0D118342D +:106E80000835C3E7013504F8016BBFE79C9B000898 +:106E9000C49A0008AF9B000800E8F11F0CE8F11F3E +:106EA000A49B0008BFF34F8F044B1A695107FCD114 +:106EB000D3F810215207F8D1704700BF00200052CC +:106EC00008B50D4B1B78ABB9FFF7ECFF0B4BDA683D +:106ED000D10704D50A4A5A6002F188325A60D3F8C1 +:106EE0000C21D20706D5064AC3F8042102F18832E4 +:106EF000C3F8042108BD00BF4E64002000200052EA +:106F00002301674508B5114B1B78F3B9104B1A697B +:106F1000510703D5DA6842F04002DA60D3F8102155 +:106F2000520705D5D3F80C2142F04002C3F80C21DA +:106F3000FFF7B8FF064BDA6842F00102DA60D3F8D7 +:106F40000C2142F00102C3F80C2108BD4E64002060 +:106F5000002000520F289ABF00F5806040040020F6 +:106F6000704700004FF40030704700001020704759 +:106F70000F2808B50BD8FFF7EDFF00F500330268C6 +:106F8000013204D104308342F9D1012008BD002030 +:106F9000FCE700000F2838B505463FD8FFF782FF11 +:106FA0001F4CFFF78DFF4FF0FF3307286361C4F8D4 +:106FB00014311DD82361FFF775FF030243F024034A +:106FC000E360E36843F08003E36023695A07FCD47D +:106FD0002846FFF767FFFFF7BDFF4FF4003100F0D1 +:106FE000ABFA2846FFF78EFFBDE83840FFF7C0BF79 +:106FF000C4F81031FFF756FFA0F108031B0243F05D +:107000002403C4F80C31D4F80C3143F08003C4F8E5 +:107010000C31D4F810315B07FBD4D9E7002038BD20 +:10702000002000522DE9F84F05460C46104645EA6F +:107030000203DE0602D00020BDE8F88F20F01F001A +:10704000DFF8BCB0DFF8BCA0FFF73AFF04EB0008A4 +:10705000444503D10120FFF755FFEDE720222946E3 +:10706000204602F0A3F810B920352034F0E72B4673 +:1070700005F120021F68791CDDD104339A42F9D151 +:1070800005F178431B481C4EB3F5801F1B4B38BFDE +:10709000184603F1F80332BFD946D1461E46FFF722 +:1070A00001FF0760A5EB040C336804F11C0143F0F9 +:1070B00002033360231FD9F8007017F00507FAD1D7 +:1070C00053F8042F8B424CF80320F4D1BFF34F8FB9 +:1070D000FFF7E8FE4FF0FF332022214603602846E9 +:1070E000336823F00203336002F060F80028BBD05D +:1070F0003846B0E7142100520C20005214200052F0 +:10710000102000521021005210B5084C237828B1ED +:107110001BB9FFF7D5FE0123237010BD002BFCD057 +:107120002070BDE81040FFF7EDBE00BF4E640020A8 +:107130002DE9F04F0D4685B0814658B111F00D068E +:1071400014BF2022082211F00803019304D0431E2B +:10715000034269D0002435E0002E37D009F11F0129 +:1071600021F01F094FF00108314F05F00403DFF84B +:10717000CCA005EA080BBBF1000F32D07869C0073C +:107180002FD408F101080C37B8F1060FF3D19EB9DE +:10719000284D4946A819019201F016FE0446002820 +:1071A00039D12036019AA02EF3D1494601F00CFEC8 +:1071B000044600282FD1019A49461F4801F004FED9 +:1071C000044660BB204605B0BDE8F08F0029C9D158 +:1071D00001462846029201F0F7FD0446D8B9029A0A +:1071E000C0E713B178694107CBD5AC0702D5786900 +:1071F0008007C6D5019911B178690107C1D5494603 +:107200000AEB4810CDE9022301F0DEFD0446DDE97A +:1072100002230028B5D04A460021204601E04A4614 +:107220000021FAF789FDCDE70246002E96D199E7B5 +:10723000C09B00089064002050640020706400200F +:107240000021FFF775BF00000121FFF771BF0000AB +:1072500070B5144D0124144E40F2FF32002101207C +:10726000FAF76AFD06EB441001342A6955F80C1F41 +:1072700001F096FD062CF5D137254FF4C054204679 +:10728000FFF7E2FF014628B122460848BDE87040FA +:1072900001F086BDC4EBC404013D4FEAD404EED135 +:1072A00070BD00BFC09B00087064002050640020C7 +:1072B0000421FFF73DBF00004843FFF7C1BF0000B6 +:1072C00008B101F0F3BD7047B0F5805F10B504461A +:1072D00007D8FFF7EDFF28B92046BDE81040FFF7BB +:1072E000AFBF002010BD0000FFF7EABF70B5AAB124 +:1072F00040EA010313F01F030FD1094C0144A568B4 +:107300006D0706D52568A84203D366683544A942AF +:1073100004D903330C34122BF1D10022104670BD76 +:10732000C09B000808B501F0D7FE034AD2E900323D +:10733000C01842EB010108BD30650020434BD3E982 +:1073400000232DE9F34113437CD0FFF7EBFF404AC4 +:1073500000230027F9F770F806460D463D4A002342 +:10736000F9F76AF80023144630462946394AF9F7F6 +:1073700063F84FF461613C23ADF80170B4FBF1F5A3 +:10738000B4FBF3F601FB154103FB16464624B1FBA3 +:10739000F3F1314BF6B28DF8004098423CD84FF0F3 +:1073A000640C4FF4C87EA30704F26C7225D1B2FBC3 +:1073B000FCF30CFB132313BBB2FBFEF30EFB1322F7 +:1073C000B2FA82F35B0903F26D18621C8045D2B2F7 +:1073D00017D90FB18DF800400022204C4FF00C0C53 +:1073E00017460CFB0343D4B2013213F804C08445A2 +:1073F0000CD8A0EB0C000127F5E70023E3E70123FD +:10740000E1E7A0EB080014460127CCE70FB18DF8A7 +:107410000140431C8DF802309DF80100431C9DF88B +:1074200000005038400640EA43509DF8023040EAE0 +:10743000034040EA560040EAC52040EA411002B04D +:10744000BDE8F0814FF40410F9E700BF306500207B +:1074500040420F008051010090230B00089C00085F +:107460000244074BD2B210B5904200D110BD441C6B +:1074700000B253F8200041F8040BE0B2F4E700BF7B +:10748000504000580E4B30B51C6F240405D41C6FBF +:107490001C671C6F44F400441C670A4C02442368B8 +:1074A000D2B243F480732360074B904200D130BDC9 +:1074B000441C51F8045B00B243F82050E0B2F4E7FA +:1074C00000440258004802585040005807B50122B5 +:1074D00001A90020FFF7C4FF019803B05DF804FB89 +:1074E00013B50446FFF7F2FFA04205D0012201A91F +:1074F00000200194FFF7C6FF02B010BD10B5642450 +:10750000013C4FF47A70FFF7B1F814F0FF04F7D1A3 +:10751000084B4FF0807214249A6103F580530822BF +:107520009A61013C4FF47A70FFF7A0F814F0FF0461 +:10753000F7D110BD000002580144BFF34F8F064B36 +:10754000884204D3BFF34F8FBFF36F8F7047C3F8E8 +:107550005C022030F4E700BF00ED00E00144BFF31F +:107560004F8F064B884204D3BFF34F8FBFF36F8F0B +:107570007047C3F870022030F4E700BF00ED00E070 +:1075800070B5054616460C4601201021FFF794FE03 +:10759000286046733CB1204636B1FFF789FE2B6860 +:1075A000186000B19C6070BDFFF74EFEF7E7000069 +:1075B000F8B50F461546044648B905F11F010126E6 +:1075C000386821F01F01FFF7B7FF3046F8BD427B56 +:1075D00029463868FFF78AFE06460028EDD13B6849 +:1075E0006360A368AB4210D213B12068FFF768FE56 +:1075F000637B28462BB1FFF75BFE206020B9A060BB +:10760000E3E7FFF721FEF8E7A560206805F11F0119 +:10761000012621F01F013860FFF78EFF2673D4E7A3 +:1076200010B5044640B10068884205D1606808B1D1 +:10763000FAF75CFB0023237310BD0000F8B50F467A +:107640001446054648B904F11F010126386821F0A7 +:107650001F01FFF783FF3046F8BD427B21463868A3 +:10766000FFF744FE06460028EDD1AB68A34210D2D6 +:1076700013B12868FFF724FE6B7B20462BB1FFF780 +:1076800017FE286020B9A860E5E7FFF7DDFDF8E701 +:10769000AC60396819B122462868FAF727FB2868D8 +:1076A00004F11F01012621F01F013860FFF756FF8A +:1076B0002E73D0E720B103688B4204BF002303730D +:1076C00070470000034B1A681AB9034AD2F8D02455 +:1076D0001A607047386500200040025808B5FFF76F +:1076E000F1FF024B1868C0F3806008BD38650020C8 +:1076F000EFF30983054968334A6B22F001024A63BC +:1077000083F30988002383F31188704700EF00E0BA +:10771000302080F3118862B60D4B0E4AD96821F4EF +:10772000E0610904090C0A430B49DA60D3F8FC2034 +:1077300042F08072C3F8FC20084AC2F8B01F1168FA +:1077400041F0010111602022DA7783F822007047AE +:1077500000ED00E00003FA0555CEACC5001000E0D6 +:10776000302310B583F311880E4B5B6813F400636C +:1077700014D0F1EE103AEFF309844FF08073683CB7 +:10778000E361094BDB6B236684F30988FEF7B8FEDF +:1077900010B1064BA36110BD054BFBE783F31188C5 +:1077A000F9E700BF00ED00E000EF00E02F04000863 +:1077B0003204000870B5BFF34F8FBFF36F8F1A4AC2 +:1077C0000021C2F85012BFF34F8FBFF36F8F536980 +:1077D00043F400335361BFF34F8FBFF36F8FC2F891 +:1077E0008410BFF34F8FD2F8803043F6E074C3F3B8 +:1077F000C900C3F34E335B0103EA0406014646EABF +:1078000081750139C2F86052F9D2203B13F1200F83 +:10781000F2D1BFF34F8F536943F480335361BFF309 +:107820004F8FBFF36F8F70BD00ED00E0FEE70000EB +:10783000214B2248224A70B5904237D3214BC11EBA +:10784000DA1C121A22F003028B4238BF00220021F8 +:10785000FAF772FA1C4A0023C2F88430BFF34F8F44 +:10786000D2F8803043F6E074C3F3C900C3F34E335B +:107870005B0103EA0406014646EA81750139C2F854 +:107880006C52F9D2203B13F1200FF2D1BFF34F8F8E +:10789000BFF36F8FBFF34F8FBFF36F8F0023C2F81B +:1078A0005032BFF34F8FBFF36F8F70BD53F8041B7F +:1078B00040F8041BC0E700BF0C9D0008346700209F +:1078C000346700203467002000ED00E0074BD3F858 +:1078D000D81021EA0001C3F8D810D3F8002122EA19 +:1078E0000002C3F80021D3F8003170470044025869 +:1078F00070B5D0E9244300224FF0FF359E6804EBB9 +:1079000042135101D3F80009002805DAD3F8000921 +:1079100040F08040C3F80009D3F8000B002805DAD6 +:10792000D3F8000B40F08040C3F8000B013263181D +:107930009642C3F80859C3F8085BE0D24FF0011330 +:10794000C4F81C3870BD0000890141F020010161BC +:1079500003699B06FCD41220FEF71CBE10B50A4C2E +:107960002046FEF7B7FA094BC4F89030084BC4F82C +:107970009430084C2046FEF7ADFA074BC4F890301F +:10798000064BC4F8943010BD3C6500200000084050 +:10799000449C0008D865002000000440509C00086A +:1079A00070B503780546012B5CD1434BD0F890406D +:1079B000984258D1414B0E216520D3F8D82042F08F +:1079C0000062C3F8D820D3F8002142F00062C3F867 +:1079D0000021D3F80021D3F8802042F00062C3F8E0 +:1079E0008020D3F8802022F00062C3F88020D3F8F2 +:1079F0008030FDF7B3FC324BE360324BC4F8003803 +:107A00000023D5F89060C4F8003EC02323604FF4F3 +:107A10000413A3633369002BFCDA01230C203361C8 +:107A2000FEF7B8FD3369DB07FCD41220FEF7B2FD88 +:107A30003369002BFCDA00262846A660FFF758FFC2 +:107A40006B68C4F81068DB68C4F81468C4F81C6874 +:107A500083BB1D4BA3614FF0FF336361A36843F009 +:107A60000103A36070BD194B9842C9D1134B4FF06D +:107A70008060D3F8D82042F00072C3F8D820D3F841 +:107A8000002142F00072C3F80021D3F80021D3F89E +:107A9000802042F00072C3F88020D3F8802022F0CA +:107AA0000072C3F88020D3F88030FFF70FFF0E215B +:107AB0004D209EE7064BCDE73C6500200044025870 +:107AC0004014004003002002003C30C0D865002074 +:107AD000083C30C0F8B5D0F89040054600214FF082 +:107AE00000662046FFF730FFD5F8941000234FF0D2 +:107AF00001128F684FF0FF30C4F83438C4F81C28E6 +:107B000004EB431201339F42C2F80069C2F8006BD4 +:107B1000C2F80809C2F8080BF2D20B68D5F8902019 +:107B2000C5F89830636210231361166916F01006C9 +:107B3000FBD11220FEF72EFDD4F8003823F4FE63AB +:107B4000C4F80038A36943F4402343F01003A36151 +:107B50000923C4F81038C4F814380B4BEB604FF00D +:107B6000C043C4F8103B094BC4F8003BC4F810698B +:107B7000C4F80039D5F8983003F1100243F48013AB +:107B8000C5F89820A362F8BD209C00084080001032 +:107B9000D0F8902090F88A10D2F8003823F4FE63D1 +:107BA00043EA0113C2F80038704700002DE9F8439A +:107BB00000EB8103D0F890500C468046DA680FFA4B +:107BC00081F94801166806F00306731E022B05EBC7 +:107BD00041134FF0000194BFB604384EC3F8101B98 +:107BE0004FF0010104F1100398BF06F1805601FA2D +:107BF00003F3916998BF06F5004600293AD0578AE9 +:107C000004F15801374349016F50D5F81C180B4354 +:107C10000021C5F81C382B180127C3F81019A740FC +:107C20005369611E9BB3138A928B9B08012A88BFFC +:107C30005343D8F89820981842EA034301F14002D0 +:107C40002146C8F89800284605EB82025360FFF7EA +:107C50007BFE08EB8900C3681B8A43EA84534834DF +:107C60001E4364012E51D5F81C381F43C5F81C78FB +:107C7000BDE8F88305EB4917D7F8001B21F4004154 +:107C8000C7F8001BD5F81C1821EA0303C0E704F16C +:107C90003F030B4A2846214605EB83035A60FFF752 +:107CA00053FE05EB4910D0F8003923F40043C0F827 +:107CB0000039D5F81C3823EA0707D7E70080001001 +:107CC00000040002D0F894201268C0F89820FFF752 +:107CD0000FBE00005831D0F8903049015B5813F4C2 +:107CE000004004D013F4001F0CBF02200120704795 +:107CF0004831D0F8903049015B5813F4004004D06B +:107D000013F4001F0CBF02200120704700EB81011B +:107D1000CB68196A0B6813604B68536070470000AA +:107D200000EB810330B5DD68AA691368D36019B927 +:107D3000402B84BF402313606B8A1468D0F89020D6 +:107D40001C4402EB4110013C09B2B4FBF3F4634361 +:107D5000033323F0030343EAC44343F0C043C0F8B2 +:107D6000103B2B6803F00303012B0ED1D2F8083827 +:107D700002EB411013F4807FD0F8003B14BF43F0B6 +:107D8000805343F00053C0F8003B02EB4112D2F89D +:107D9000003B43F00443C2F8003B30BD2DE9F04105 +:107DA000D0F8906005460C4606EB4113D3F8087BEB +:107DB0003A07C3F8087B08D5D6F814381B0704D552 +:107DC00000EB8103DB685B689847FA071FD5D6F89C +:107DD0001438DB071BD505EB8403D968CCB98B6954 +:107DE000488A5A68B2FBF0F600FB16228AB9186876 +:107DF000DA6890420DD2121AC3E90024302383F3CB +:107E0000118821462846FFF78BFF84F31188BDE8CF +:107E1000F081012303FA04F26B8923EA02036B81E8 +:107E2000CB68002BF3D021462846BDE8F041184727 +:107E300000EB81034A0170B5DD68D0F890306C69C1 +:107E40002668E66056BB1A444FF40020C2F81009B9 +:107E50002A6802F00302012A0AB20ED1D3F80808F8 +:107E600003EB421410F4807FD4F8000914BF40F0F3 +:107E7000805040F00050C4F8000903EB4212D2F8E1 +:107E8000000940F00440C2F800090122D3F8340888 +:107E900002FA01F10143C3F8341870BD19B9402E3C +:107EA00084BF4020206020681A442E8A8419013C37 +:107EB000B4FBF6F440EAC44040F00050C6E70000CE +:107EC0002DE9F843D0F8906005460C464F0106EBCB +:107ED0004113D3F8088918F0010FC3F808891CD0A2 +:107EE000D6F81038DB0718D500EB8103D3F80CC0A7 +:107EF000DCF81430D3F800E0DA68964530D2A2EB13 +:107F00000E024FF000091A60C3F80490302383F387 +:107F10001188FFF78DFF89F3118818F0800F1DD0AD +:107F2000D6F834380126A640334217D005EB840337 +:107F30000134D5F89050D3F80CC0E4B22F44DCF8EB +:107F4000142005EB0434D2F800E05168714514D3D5 +:107F5000D5F8343823EA0606C5F83468BDE8F88356 +:107F6000012303FA01F2038923EA02030381DCF807 +:107F70000830002BD1D09847CFE7AEEB0103BCF817 +:107F80001000834228BF0346D7F8180980B2B3EB2C +:107F9000800FE3D89068A0F1040959F8048FC4F861 +:107FA0000080A0EB09089844B8F1040FF5D81844F4 +:107FB0000B4490605360C8E72DE9F84FD0F890501B +:107FC00004466E69AB691E4016F480586E6103D09A +:107FD000BDE8F84FFDF7EEBF002E12DAD5F8003EEF +:107FE0009B0705D0D5F8003E23F00303C5F8003EFB +:107FF000D5F80438204623F00103C5F80438FEF70D +:1080000007F8370505D52046FFF772FC2046FDF737 +:10801000EDFFB0040CD5D5F8083813F0060FEB6867 +:1080200023F470530CBF43F4105343F4A053EB609C +:1080300031071BD56368DB681BB9AB6923F0080304 +:10804000AB612378052B0CD1D5F8003E9A0705D0FB +:10805000D5F8003E23F00303C5F8003E2046FDF7A7 +:10806000D7FF6368DB680BB120469847F30200F145 +:10807000BA80B70226D5D4F8909000274FF0010AB5 +:1080800009EB4712D2F8003B03F44023B3F5802FED +:1080900011D1D2F8003B002B0DDA62890AFA07F3FE +:1080A00022EA0303638104EB8703DB68DB6813B117 +:1080B0003946204698470137D4F89430FFB29B6880 +:1080C0009F42DDD9F00619D5D4F89000026AC2F3B8 +:1080D0000A1702F00F0302F4F012B2F5802F00F03D +:1080E000CA80B2F5402F09D104EB8303002200F5CA +:1080F0008050DB681B6A974240F0B0803003D5F8AF +:10810000185835D5E90303D500212046FFF746FE70 +:10811000AA0303D501212046FFF740FE6B0303D5D8 +:1081200002212046FFF73AFE2F0303D50321204604 +:10813000FFF734FEE80203D504212046FFF72EFEA8 +:10814000A90203D505212046FFF728FE6A0203D5C0 +:1081500006212046FFF722FE2B0203D507212046E9 +:10816000FFF71CFEEF0103D508212046FFF716FE9E +:10817000700340F1A780E90703D500212046FFF7EF +:108180009FFEAA0703D501212046FFF799FE6B0742 +:1081900003D502212046FFF793FE2F0703D50321C5 +:1081A0002046FFF78DFEEE0603D504212046FFF79B +:1081B00087FEA80603D505212046FFF781FE690644 +:1081C00003D506212046FFF77BFE2A0603D50721AB +:1081D0002046FFF775FEEB0574D520460821BDE863 +:1081E000F84FFFF76DBED4F890904FF0000B4FF0B2 +:1081F000010AD4F894305FFA8BF79B689F423FF6F0 +:1082000038AF09EB4713D3F8002902F44022B2F546 +:10821000802F20D1D3F80029002A1CDAD3F80029B6 +:1082200042F09042C3F80029D3F80029002AFBDB72 +:108230003946D4F89000FFF787FB22890AFA07F342 +:1082400022EA0303238104EB8703DB689B6813B1F5 +:108250003946204698470BF1010BCAE7910701D137 +:10826000D0F80080072A02F101029CBF03F8018BBD +:108270004FEA18283FE704EB830300F58050DA68E3 +:10828000D2F818C0DCF80820DCE9001CA1EB0C0CCB +:1082900000218F4208D1DB689B699A683A449A6052 +:1082A0005A683A445A6029E711F0030F01D1D0F817 +:1082B00000808C4501F1010184BF02F8018B4FEA77 +:1082C0001828E6E7BDE8F88F08B50348FFF774FE05 +:1082D000BDE80840FFF744BA3C65002008B50348F4 +:1082E000FFF76AFEBDE80840FFF73ABAD8650020FC +:1082F000D0F8903003EB4111D1F8003B43F4001368 +:10830000C1F8003B70470000D0F8903003EB4111FA +:10831000D1F8003943F40013C1F800397047000068 +:10832000D0F8903003EB4111D1F8003B23F4001357 +:10833000C1F8003B70470000D0F8903003EB4111CA +:10834000D1F8003923F40013C1F800397047000058 +:10835000064BD3F8DC200243C3F8DC20D3F8042119 +:108360001043C3F80401D3F80431704700440258A5 +:1083700008B53C4B4FF0FF31D3F8802062F000424B +:10838000C3F88020D3F8802002F00042C3F8802098 +:10839000D3F88020D3F88420C3F88410D3F8842045 +:1083A0000022C3F88420D3F88400D86F40F0FF4047 +:1083B00040F4FF0040F4DF4040F07F00D867D86F02 +:1083C00020F0FF4020F4FF0020F4DF4020F07F0089 +:1083D000D867D86FD3F888006FEA40506FEA5050E2 +:1083E000C3F88800D3F88800C0F30A00C3F88800F7 +:1083F000D3F88800D3F89000C3F89010D3F8900019 +:10840000C3F89020D3F89000D3F89400C3F89410E8 +:10841000D3F89400C3F89420D3F89400D3F89800CC +:10842000C3F89810D3F89800C3F89820D3F89800B0 +:10843000D3F88C00C3F88C10D3F88C00C3F88C20D0 +:10844000D3F88C00D3F89C00C3F89C10D3F89C1090 +:10845000C3F89C20D3F89C30FCF72EFABDE8084006 +:1084600000F0D6B90044025808B50122534BC3F8B6 +:108470000821534BD3F8F42042F00202C3F8F42051 +:10848000D3F81C2142F00202C3F81C210222D3F8C7 +:108490001C314C4BDA605A689104FCD54A4A1A6088 +:1084A00001229A60494ADA6000221A614FF4404280 +:1084B0009A61444B9A699204FCD51A6842F480721E +:1084C0001A603F4B1A6F12F4407F04D04FF4803291 +:1084D0001A6700221A671A6842F001021A60384BC4 +:1084E0001A685007FCD500221A611A6912F0380286 +:1084F000FBD1012119604FF0804159605A67344A1D +:10850000DA62344A1A611A6842F480321A602C4BDB +:108510001A689103FCD51A6842F480521A601A68EE +:108520009204FCD52C4A2D499A6200225A631963A1 +:1085300001F57C01DA6301F5E77199635A64284A11 +:108540001A64284ADA621A6842F0A8521A601C4B70 +:108550001A6802F02852B2F1285FF9D148229A61D4 +:108560004FF48862DA6140221A621F4ADA641F4AB5 +:108570001A651F4A5A651F4A9A6532231E4A1360BC +:10858000136803F00F03022BFAD10D4A136943F06D +:1085900003031361136903F03803182BFAD14FF06A +:1085A0000050FFF7D5FE4FF08040FFF7D1FE4FF0AF +:1085B0000040BDE80840FFF7CBBE00BF008000517F +:1085C000004402580048025800C000F002000001B8 +:1085D0000000FF010088900832206000630209015A +:1085E000470E0508DD0BBF01200000200000011030 +:1085F0000910E00000010110002000524FF0B042CD +:1086000008B5D2F8883003F00103C2F8883023B1EE +:10861000044A13680BB150689847BDE80840FFF75B +:108620009FB800BFB46600204FF0B04208B5D2F842 +:10863000883003F00203C2F8883023B1044A9368FB +:108640000BB1D0689847BDE80840FFF789B800BF74 +:10865000B46600204FF0B04208B5D2F8883003F07D +:108660000403C2F8883023B1044A13690BB150697E +:108670009847BDE80840FFF773B800BFB466002014 +:108680004FF0B04208B5D2F8883003F00803C2F8C2 +:10869000883023B1044A93690BB1D0699847BDE88B +:1086A0000840FFF75DB800BFB46600204FF0B0424D +:1086B00008B5D2F8883003F01003C2F8883023B12F +:1086C000044A136A0BB1506A9847BDE80840FFF7A7 +:1086D00047B800BFB46600204FF0B04310B5D3F8E0 +:1086E000884004F47872C3F88820A30604D5124A9F +:1086F000936A0BB1D06A9847600604D50E4A136B93 +:108700000BB1506B9847210604D50B4A936B0BB104 +:10871000D06B9847E20504D5074A136C0BB1506C37 +:108720009847A30504D5044A936C0BB1D06C9847C5 +:10873000BDE81040FFF714B8B46600204FF0B04316 +:1087400010B5D3F8884004F47C42C3F88820620551 +:1087500004D5164A136D0BB1506D9847230504D507 +:10876000124A936D0BB1D06D9847E00404D50F4ABF +:10877000136E0BB1506E9847A10404D50B4A936E4B +:108780000BB1D06E9847620404D5084A136F0BB141 +:10879000506F9847230404D5044A936F0BB1D06FF0 +:1087A0009847BDE81040FEF7DBBF00BFB46600206D +:1087B00008B50348FCF748FCBDE80840FEF7D0BF09 +:1087C000C836002008B50348FCF742FDBDE8084064 +:1087D000FEF7C6BF2039002008B50348FCF738FD76 +:1087E000BDE80840FEF7BCBF8C39002008B503483F +:1087F000FCF72EFDBDE80840FEF7B2BFF8390020B7 +:1088000008B500F0BDFCBDE80840FEF7A9BF0000B8 +:10881000062108B50846FCF7A1FD06210720FCF754 +:108820009DFD06210820FCF799FD06210920FCF793 +:1088300095FD06210A20FCF791FD06211720FCF783 +:108840008DFD06212820FCF789FD09217A20FCF7FF +:1088500085FD09213120FCF781FD07213220FCF73D +:108860007DFD0C212620FCF779FD0C212720FCF74B +:1088700075FD0C215220BDE80840FCF76FBD0000DB +:1088800008B5FFF775FD00F043FCFDF747F9FDF76C +:10889000E5F8FDF71DFBFDF7EFF9FEF7B1F9BDE8CF +:1088A000084000F029BA000030B50433039C01727F +:1088B000002104FB0325C160C0E90653049B036348 +:1088C000059BC0E90000C0E90422C0E90842C0E9F4 +:1088D0000A11436330BD00000022416AC260C0E952 +:1088E0000411C0E90A226FF00101FDF7FFBE00008C +:1088F000D0E90432934201D1C2680AB9181D704709 +:1089000000207047036919600021C2680132C2600B +:10891000C269134482699342036124BF436A0361BD +:10892000FDF7D8BE38B504460D46E3683BB1626931 +:108930000020131D1268A3621344E36207E0237A48 +:1089400033B929462046FDF7B5FE0028EDDA38BDDB +:108950006FF00100FBE70000C368C269013BC36020 +:108960004369134482699342436124BF436A43616C +:1089700000238362036B03B11847704770B530233F +:10898000044683F31188866A3EB9FFF7CBFF05469C +:1089900018B186F31188284670BDA36AE26A13F8FD +:1089A000015B9342A36202D32046FFF7D5FF002369 +:1089B00083F31188EFE700002DE9F84F04460E46D7 +:1089C000174698464FF0300989F311880025AA46CA +:1089D000D4F828B0BBF1000F09D141462046FFF77B +:1089E000A1FF20B18BF311882846BDE8F88FD4E9A8 +:1089F0000A12A7EB050B521A934528BF9346BBF109 +:108A0000400F1BD9334601F1400251F8040B91424B +:108A100043F8040BF9D1A36A403640354033A362D2 +:108A2000D4E90A239A4202D32046FFF795FF8AF33E +:108A30001188BD42D8D289F31188C9E730465A4619 +:108A4000F9F754F9A36A5E445D445B44A362E7E727 +:108A500010B5029C0433017203FB0421C460C0E919 +:108A600006130023C0E90A33039B0363049BC0E998 +:108A70000000C0E90422C0E90842436310BD0000C1 +:108A8000026A6FF00101C260426AC0E9042200225A +:108A9000C0E90A22FDF72ABED0E904239A4201D197 +:108AA000C26822B9184650F8043B0B607047002397 +:108AB0001846FAE7C3680021C2690133C3604369FD +:108AC000134482699342436124BF436A4361FDF7C3 +:108AD00001BE000038B504460D46E3683BB123698A +:108AE00000201A1DA262E2691344E36207E0237AC0 +:108AF00033B929462046FDF7DDFD0028EDDA38BD03 +:108B00006FF00100FBE7000003691960C268013AD9 +:108B1000C260C269134482699342036124BF436AFD +:108B2000036100238362036B03B1184770470000A1 +:108B300070B530230D460446114683F31188866ACA +:108B40002EB9FFF7C7FF10B186F3118870BDA36A75 +:108B50001D70A36AE26A01339342A36204D3E16900 +:108B600020460439FFF7D0FF002080F31188EDE79D +:108B70002DE9F84F04460D46904699464FF0300ACD +:108B80008AF311880026B346A76A4FB949462046A2 +:108B9000FFF7A0FF20B187F311883046BDE8F88FBA +:108BA000D4E90A073A1AA8EB0607974228BF1746E6 +:108BB000402F1BD905F1400355F8042B9D4240F886 +:108BC000042BF9D1A36A40364033A362D4E90A23C7 +:108BD0009A4204D3E16920460439FFF795FF8BF3ED +:108BE00011884645D9D28AF31188CDE729463A46FD +:108BF000F9F77CF8A36A3D443E443B44A362E5E7B1 +:108C0000D0E904239A4217D1C3689BB1836A8BB120 +:108C1000043B9B1A0ED01360C368013BC360C36959 +:108C20001A4483699A42026124BF436A03610023A4 +:108C300083620123184670470023FBE701F01F03FE +:108C4000F0B502F01F0456095A1C0123B6EB511F60 +:108C500050F8265003FA02F34FEA511703F1FF339D +:108C60003DBF50F82720C4F12000134003EA05005F +:108C70003BBF03FA00F225FA04F0E0401043F0BDD8 +:108C800070B57E227F210546FFF7D8FF18B1012875 +:108C900019D0002070BD3E2249212846FFF7CEFFA3 +:108CA0002F22044631212846FFF7C8FF064601342B +:108CB0005022023653212846B440FFF7BFFF09383F +:108CC00004FA00F0E6E7302245212846FFF7B6FF18 +:108CD00001308002DEE7000090F8D63090F8D7200F +:108CE0001B0403EB026390F8D42090F8D5001344E2 +:108CF00003EB00207047000000F018BA014B586ADF +:108D0000704700BF000C0040034B002258631A61FB +:108D10000222DA60704700BF000C0040014B0022C5 +:108D2000DA607047000C0040014B5863704700BF89 +:108D3000000C0040024B034A1A60034A5A60704715 +:108D40008C6600203867002000000220074B494253 +:108D500010B55C68201A08401968821A8A4203D349 +:108D6000A24201D85A6010BD0020FCE78C660020AA +:108D700008B5302383F31188FFF7E8FF002383F35E +:108D8000118808BD0448054B03600023C0E9013386 +:108D90000C3000F017B900BF94660020718D0008F8 +:108DA000CB1D083A23F00703591A521A10B4D208FF +:108DB0000024C0E9004384600C301C605A605DF8F8 +:108DC000044B00F0FFB800002DE9F74F364FCD1DE2 +:108DD0008846002818BF0746082A4FEAD50538BF3D +:108DE000082207F10C003C1D9146019000F02CF97F +:108DF000019809F10701C9F1000E2246246864B9FF +:108E000000F02CF93B68CBB308224946E8009847AC +:108E1000044698B340E9027830E004EB010CD4F842 +:108E200004A00CEA0E0C0AF10106ACF1080304EBF5 +:108E3000C6069E42E1D9A6EB0C0CB5EBEC0F4FEA4F +:108E4000EC0BDAD89C421DD204F10802AB45A3EB2F +:108E500002024FEAE202626009D9691CED4303EBAA +:108E6000C1025D445560256843F8315022601C46BC +:108E7000C3F8048044F8087B00F0F0F8204603B003 +:108E8000BDE8F08FAA45216802D111602346EEE7C4 +:108E9000013504EBC50344F8351003F10801761AD7 +:108EA000F6105E601360F1E79466002073B5044627 +:108EB000A0F1080550F8080C54F8043C061D0C30CD +:108EC00007330190DB0844F8043C00F0BDF833465A +:108ED00001989E421A6801D0AB4228D20AB195424D +:108EE00025D244F8082C54F8042C1D60013254F8A3 +:108EF000081C05EBC206B14206D14E68324444F864 +:108F0000042C0A6844F8082C5E68711C03EBC1014C +:108F10008D4207D154F8042C013232445A6054F87F +:108F2000082C1A6002B0BDE8704000F097B81346F4 +:108F3000CFE70000FEE7000070B51E4B0025044699 +:108F400086B058600E4605638163FEF7E1FB04F1CD +:108F50002803A5606563C4E90A3304F11003C4E97A +:108F600004334FF0FF33C4E90044C4E90635FFF78A +:108F7000C5FE2B46024604F13C012046C4E9082305 +:108F800080230D4A6567FDF70FFB7368E0600B4AAD +:108F900003620123009280F824306846F26801924F +:108FA0003269CDE90223064BCDE90435FDF730FBEC +:108FB00006B070BD10490020649C00085C9C00084D +:108FC000358F00080023C0E900008360036170470B +:108FD00070B51C4B05468468DE685CB3B44213D19F +:108FE00003690133036170BDA36094F8243083B139 +:108FF000062B15D1A06A2146D4E9003213605A60CD +:10900000FDF73EFAA36A9C68B368A2689A42EBD364 +:1090100006E0D4E90032204613605A60FDF740FABA +:1090200028463146FDF72CFAB5620620BDE87040AF +:10903000FDF738BA0369866001330361336BC3609F +:109040003063D0E76846002008B5302383F31188E9 +:10905000FFF7BEFF002383F3118808BD194BD968C1 +:1090600083688B4210B520D1302383F311880269C5 +:10907000013A0261B2B90468C368A0420B631ED012 +:109080004A6B9BB901238A60036103681A68026016 +:1090900050601A6B8360C26018631846FDF700FACF +:1090A000FDF750FA002383F3118810BD1C68A3421A +:1090B00003D0A468A24238BF2246DB68E1E78260A1 +:1090C000F0E700BF68460020024A536B1843506324 +:1090D000704700BF6846002038B5EFF311859DB991 +:1090E000EFF30584C4F30804302334B183F311880B +:1090F000FDF734FC85F3118838BD83F31188FDF743 +:109100002DFC84F3118838BDBDE83840FDF726BC3E +:109110000023054A19460133102BC2E9001102F160 +:109120000802F8D1704700BFB4660020114BD3F895 +:10913000E82042F00802C3F8E820D3F8102142F0FA +:109140000802C3F810210C4AD3F81031D36B43F056 +:109150000803D363C722094B9A624FF0FF32DA62E9 +:1091600000229A615A63DA605A6001225A611A60D9 +:10917000704700BF004402580010005C000C004023 +:10918000094A08B51169D3680B40D9B29B076FEA49 +:109190000101116107D5302383F31188FDF7F8F938 +:1091A000002383F3118808BD000C004010B501397D +:1091B0000244904201D1002005E0037811F8014FEC +:1091C000A34201D0181B10BD0130F2E7884210B550 +:1091D00001EB020402D98442234607D8431EA14270 +:1091E00008D011F8012B03F8012FF8E702440146DB +:1091F0008A4200D110BD13F8014D02F8014DF7E786 +:10920000C9B2034610F8012B1AB18A42F9D11846A7 +:109210007047002918BF0023F9E70000034611F842 +:10922000012B03F8012B002AF9D1704710B5013941 +:10923000034632B111F8014F03F8014B013A002CFB +:10924000F7D11A440021934200D110BD03F8011B4D +:10925000F9E700004D4435002D2D0A002F6172649E +:109260007570696C6F742E6162696E002F61726433 +:109270007570696C6F742D7665726966792E61629E +:10928000696E002F6172647570696C6F742D666C05 +:109290006173682E6162696E002F61726475706916 +:1092A0006C6F742D666C61736865642E6162696EA3 +:1092B000000000000000000000000000050F000892 +:1092C000A10F000851110008D90F0008990F0008DC +:1092D0000000000000000000010F0008AD0F0008B2 +:1092E00089110008FD0E0008090F000853544D3382 +:1092F0003248373F3F3F0053544D3332483733787D +:109300002F3732780053544D3332483734332F37A8 +:1093100035332F373530000001105A000310590043 +:1093200001205800032056002F000000537563638E +:1093300065737366756C6C79206D6F756E7465649A +:10934000205344436172642028736C6F77646F7795 +:109350006E3D2575290A0000EB769045584641542C +:1093600020202000464154333220202000000000FD +:109370002A3A3C3E7C223F7F002B2C3B3D5B5D002C +:10938000435545414141414345454549494941418D +:109390004592924F4F4F5555594F554F9C4F9E9F59 +:1093A00041494F55A5A5A6A7A8A9AAABACADAEAF9C +:1093B000B0B1B2B3B4414141B8B9BABBBCBDBEBF94 +:1093C000C0C1C2C3C4C54141C8C9CACBCCCDCECF30 +:1093D000D1D145454549494949D9DADBDCDD49DF89 +:1093E0004FE14F4F4F4FE6E8E85555555959EEEFCD +:1093F000F0F1F2F3F4F5F6F7F8F9FAFBFCFDFEFFF5 +:1094000001030507090E10121416181C1E00000097 +:1094100061001A03E0001703F8000703FF000100D2 +:1094200078010001300132010601390110014A01C1 +:109430002E017901060180014D0043028101820164 +:1094400082018401840186018701870189018A01E3 +:109450008B018B018D018E018F0190019101910192 +:1094600093019401F60196019701980198013D023C +:109470009B019C019D0120029F01A001A001A2016E +:10948000A201A401A401A601A701A701A901AA01A3 +:10949000AB01AC01AC01AE01AF01AF01B101B20152 +:1094A000B301B301B501B501B701B801B801BA0103 +:1094B000BB01BC01BC01BE01F701C001C101C20179 +:1094C000C301C401C501C401C701C801C701CA0164 +:1094D000CB01CA01CD011001DD0101008E01DE01C9 +:1094E0001201F3010300F101F401F401F801280174 +:1094F000220212013A020900652C3B023B023D02A6 +:10950000662C3F0240024102410246020A01530218 +:10951000400081018601550289018A0158028F01AC +:109520005A0290015C025D025E025F0293016102D9 +:109530006202940164026502660267029701960165 +:109540006A02622C6C026D026E029C017002710252 +:109550009D01730274029F017602770278027902FC +:109560007A027B027C02642C7E027F02A6018102C9 +:109570008202A9018402850286028702AE014402AA +:10958000B101B20145028D028E028F02900291025A +:10959000B7017B030300FD03FE03FF03AC030400DC +:1095A0008603880389038A03B1031103C2030200FF +:1095B000A303A303C4030803CC0303008C038E039B +:1095C0008F03D8031801F2030A00F903F303F4032D +:1095D000F503F603F703F703F903FA03FA0330047C +:1095E000200350041007600422018A043601C104DC +:1095F0000E01CF040100C004D0044401610526041B +:10960000000000007D1D0100632C001E9601A01EBD +:109610005A01001F0806101F0606201F0806301FEB +:109620000806401F0606511F0700591F521F5B1FE7 +:10963000541F5D1F561F5F1F601F0806701F0E001E +:10964000BA1FBB1FC81FC91FCA1FCB1FDA1FDB1FD2 +:10965000F81FF91FEA1FEB1FFA1FFB1F801F0806E8 +:10966000901F0806A01F0806B01F0400B81FB91FEE +:10967000B21FBC1FCC1F0100C31FD01F0206E01F7A +:109680000206E51F0100EC1FF31F0100FC1F4E2125 +:109690000100322170211002842101008321D02495 +:1096A0001A05302C2F04602C0201672C0601752C42 +:1096B0000201802C6401002D260841FF1A030000DE +:1096C000C700FC00E900E200E400E000E500E7007C +:1096D000EA00EB00E800EF00EE00EC00C400C5007B +:1096E000C900E600C600F400F600F200FB00F90035 +:1096F000FF00D600DC00F800A300D800D7009201DC +:10970000E100ED00F300FA00F100D100AA00BA0078 +:10971000BF00AE00AC00BD00BC00A100AB00BB00B0 +:1097200091259225932502252425C100C200C00061 +:10973000A9006325512557255D25A200A500102508 +:10974000142534252C251C2500253C25E300C300C9 +:109750005A25542569256625602550256C25A400C9 +:10976000F000D000CA00CB00C8003101CD00CE000F +:10977000CF0018250C2588258425A600CC0080253F +:10978000D300DF00D400D200F500D500B500FE0004 +:10979000DE00DA00DB00D900FD00DD00AF00B40020 +:1097A000AD00B1001720BE00B600A700F700B8005A +:1097B000B000A800B700B900B300B200A025A00017 +:1097C00010000240080002400008024000000B00A8 +:1097D00028000240080002400408024006010C0074 +:1097E00040000240080002400808024010020D003C +:1097F00058000240080002400C08024016030E0008 +:10980000700002400C0002401008024000040F00EB +:10981000880002400C0002401408024006051000B7 +:10982000A00002400C00024018080240100611007F +:10983000B80002400C0002401C08024016072F002E +:1098400010040240080402402008024000083800CA +:109850002804024008040240240802400609390096 +:10986000400402400804024028080240100A3A005E +:1098700058040240080402402C080240160B3B002A +:10988000700402400C04024030080240000C3C000E +:10989000880402400C04024034080240060D4400D3 +:1098A000A00402400C04024038080240100E45009B +:1098B000B80402400C0402403C080240160F460067 +:1098C0000100000000000000009600000000000001 +:1098D0000000000000000000000000000000000088 +:1098E00000000000F96B0008FD6B0008F15600084D +:1098F000295A000885560008AD560008D5560008BC +:109900006D56000800000000DD5A0008C95A000822 +:10991000055B0008F15A0008FD5A0008E95A0008E2 +:10992000D55A0008C15A0008115B00080000000069 +:10993000F55B0008E15B00081D5C0008095C00089D +:10994000155C0008015C0008ED5B0008D95B0008AD +:10995000295C000800000000010000000000000079 +:109960006330000060990008000000000000000063 +:10997000E0460020104900200000812A000000007D +:10998000AAAAAAAA00000024FFFE0000000000000E +:1099900000A00A000001000000000000AAAAAAAA74 +:1099A00000000000FFFF00000000000000000000B9 +:1099B0001400AA5600000000AAAAAAAA140055542E +:1099C000FFFF000000000000CCCC0C0020681A0053 +:1099D00000000000AAAA8AAA10541500FFFF000088 +:1099E000000C7007770000004081020100100000A9 +:1099F000AAAAAAAA00410100F7FF00000000007017 +:109A0000070000000000000000000000AAAAAAAAA7 +:109A100000000000FFFF0000000000000000000048 +:109A20000000000000000000AAAAAAAA000000008E +:109A3000FFFF000000000000000000000000000028 +:109A400000000000AAAAAAAA00000000FFFF000070 +:109A50000000000000000000000000000000000006 +:109A6000AAAAAAAA00000000FFFF00000000000050 +:109A7000000000000000000000000000AAAAAAAA3E +:109A800000000000FFFF00000000000000000000D8 +:109A90000000000000000000AAAAAAAA000000001E +:109AA000FFFF000000000000000000004865782F64 +:109AB00050726F6669434E430025424F4152442520 +:109AC0002D424C002553455249414C2500000000D1 +:109AD0000200000000000000155E0008855E00081E +:109AE00040004000C0610020D06100200200000062 +:109AF000000000000300000000000000CD5E000830 +:109B00000000000010000000E061002000000000E4 +:109B100001000000000000003C650020010102007F +:109B2000F56C0008056C0008A16C0008856C000845 +:109B300043000000389B000809024300020100C0F6 +:109B40003209040000010202010005240010010591 +:109B500024010001042402020524060001070582F5 +:109B6000030800FF09040100020A000000070501C4 +:109B700002400000070581024000000012000000C2 +:109B8000849B00081201100102000040AE2D161047 +:109B900000020102030100000403090425424F41B1 +:109BA00052442500437562654F72616E67650030EF +:109BB0003132333435363738394142434445460033 +:109BC0000000002000000200020000000000003041 +:109BD000000004000800000000000024000008004D +:109BE000040000000004000000FC0000020000006F +:109BF0000000043000800000080000000000003871 +:109C000000000100010000001F1C1F1E1F1E1F1F5F +:109C10001E1F1E1F1F1D1F1E1F1E1F1F1E1F1E1F5C +:109C20000000000029600008E16200088D63000860 +:109C300040004000746600207466002001000000AF +:109C40008466002080000000400100000800000041 +:109C500000010000001000000800000069646C654D +:109C6000000000006D61696E002C0438040438089F +:109C70000C10141C202425260000000000006404A1 +:109C80000100040000000000000C00102830340027 +:109C9000D867FF7F010000008C000000000000007A +:109CA00000001E0000000000FF0000001849002016 +:109CB000203900208C390020F839002000000000F5 +:109CC000EC92000883040000F792000850040000A2 +:109CD000059300080100000000000000009600004D +:109CE00000000800960000000008000004000000CA +:109CF000989B000800000000000000000000000029 +:0C9D000000000000000000000000000057 :00000001FF diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.bin b/Tools/bootloaders/CubePilot-CANMod_bl.bin deleted file mode 100755 index 164019d4b6aa9d..00000000000000 Binary files a/Tools/bootloaders/CubePilot-CANMod_bl.bin and /dev/null differ diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.hex b/Tools/bootloaders/CubePilot-CANMod_bl.hex deleted file mode 100644 index 79443030873fff..00000000000000 --- a/Tools/bootloaders/CubePilot-CANMod_bl.hex +++ /dev/null @@ -1,2053 +0,0 @@ -:020000040800F2 -:1000000000070020F1020008FD320008B5320008A8 -:10001000DD320008B5320008D5320008F3020008CE -:10002000F3020008F3020008F3020008E1420008AE -:10003000F3020008F3020008F3020008F3020008CC -:10004000F3020008F3020008F3020008F3020008BC -:10005000F3020008F3020008E17600080D770008BB -:10006000397700086577000891770008A5430008F4 -:10007000CD430008F9430008254400085144000816 -:1000800079440008A5440008F302000895320008EE -:10009000F3020008A5320008F3020008BD7700084B -:1000A000F3020008F3020008F3020008F30200085C -:1000B000F3020008F3020008F3020008F30200084C -:1000C000F3020008F3020008F3020008F30200083C -:1000D000F3020008F3020008F3020008F30200082C -:1000E00021780008F3020008F3020008F302000878 -:1000F000F3020008F3020008F3020008D1440008EC -:10010000F3020008F3020008A9780008F3020008CF -:10011000F3020008F3020008F3020008F3020008EB -:10012000FD44000825450008514500087D450008AC -:10013000A9450008F3020008F3020008F3020008D2 -:10014000F3020008F3020008F3020008F3020008BB -:10015000D1450008FD45000829460008F3020008C3 -:10016000F3020008F3020008F3020008F30200089B -:10017000F30200088D6D0008F3020008F302000886 -:10018000F3020008F302000895780008F302000863 -:10019000F3020008F3020008F3020008F30200086B -:1001A000F3020008F3020008F3020008F30200085B -:1001B000F3020008F3020008F3020008F30200084B -:1001C000F3020008F3020008F3020008F30200083B -:1001D000F3020008796D0008F3020008F30200083A -:1001E000F3020008F3020008F3020008F30200081B -:1001F000F3020008F3020008F3020008F30200080B -:10020000F3020008F3020008F3020008F3020008FA -:10021000F3020008F3020008F3020008F3020008EA -:10022000F3020008F3020008F3020008F3020008DA -:10023000F3020008F3020008F3020008F3020008CA -:10024000F3020008F3020008F3020008F3020008BA -:10025000F3020008F3020008F3020008F3020008AA -:10026000F3020008F3020008F3020008F30200089A -:10027000F3020008F3020008F3020008F30200088A -:10028000F3020008F3020008F3020008F30200087A -:10029000F3020008F3020008F3020008F30200086A -:1002A000F3020008F3020008F3020008F30200085A -:1002B000F3020008F3020008F3020008F30200084A -:1002C000F3020008F3020008F3020008F30200083A -:1002D000F3020008F3020008F3020008F30200082A -:1002E000D51600080000000000000000000000001B -:1002F00002E000F000F8FEE772B6374880F30888A5 -:10030000364880F3098836483649086040F20000D4 -:10031000CCF200004EF63471CEF200010860BFF35B -:100320004F8FBFF36F8F40F20000C0F2F0004EF627 -:100330008851CEF200010860BFF34F8FBFF36F8F7B -:100340004FF00000E1EE100A4EF63C71CEF20001D3 -:100350000860062080F31488BFF36F8F05F08CFFD0 -:1003600006F090FF4FF055301F491B4A91423CBFA9 -:1003700041F8040BFAE71D49184A91423CBF41F885 -:10038000040BFAE71A491B4A1B4B9A423EBF51F82D -:10039000040B42F8040BF8E700201849184A914270 -:1003A0003CBF41F8040BFAE705F0A4FF06F0ECFFB0 -:1003B000144C154DAC4203DA54F8041B8847F9E796 -:1003C00000F042F8114C124DAC4203DA54F8041B11 -:1003D0008847F9E705F08CBF0007002000230020C4 -:1003E0000000000808ED00E00001002000070020E8 -:1003F000607F000800230020D0230020D0230020AD -:1004000000740020E0020008E4020008E402000892 -:10041000E40200082DE9F04F2DED108AC1F80CD050 -:10042000D0F80CD0BDEC108ABDE8F08F002383F328 -:1004300011882846A047002005F004FAFEE705F0E1 -:1004400083F900DFFEE70000F8B501F0BFF901F025 -:1004500061FB05F095FE074605F004FF0546A8BBC5 -:100460001F4B9F4232D001339F4232D027F0FF0210 -:100470001C4B9A4230D12E4642F21074F8B200F072 -:1004800079FF00F07DFF08B10024264601F08AFDC7 -:1004900020B10024032000F079F8264635B1124B34 -:1004A0009F4203D0002405F0D5FE2646002005F02B -:1004B00071FE0EB100F080F801F0CAFA00F094FF6E -:1004C000204600F02BF900F077F8F9E72E460024DB -:1004D000D7E704460126D4E7064641F28834D0E740 -:1004E000010007B0000008B0263A09B008B501F0D5 -:1004F00039F9A0F120035842584108BD07B541F22F -:100500001203022101A8ADF8043001F049F903B04B -:100510005DF804FB38B5302383F31188174803686E -:100520000BB105F05BFA0023154A4FF47A711348BA -:1005300005F04AFA002383F31188124C236813B1A3 -:100540002368013B2360636813B16368013B636008 -:100550000D4D2B7833B963687BB9022001F0EAF9BD -:10056000322363602B78032B07D163682BB90220F9 -:1005700001F0E0F94FF47A73636038BDD0230020B6 -:1005800015050008F0240020E8230020084B18700F -:1005900003280CD8DFE800F008050208022001F06B -:1005A000C7B9022001F0C2B9024B00225A6070475D -:1005B000E8230020F0240020F8B501F0F3FC30B16E -:1005C0004D4B03221A7000224C4B5A60F8BD4C4B25 -:1005D0004C4A1C4619680131F8D004339342F9D1D2 -:1005E0006268494B9A42F1D9484B9B6803F100631A -:1005F00003F580239A42E9D205F000FE05F012FED1 -:10060000002001F009F90220FFF7C0FF404B002154 -:100610009A6C99641A6F19671A6FDA6CD9645A6FF9 -:1006200059675A6F1A6D19659A6F99679B6F394BA5 -:10063000D3F8802042F00062C3F88020D3F88020F5 -:1006400022F00062C3F88020D3F88020D3F8802005 -:1006500042F00072C3F88020D3F8802022F00072AC -:10066000C3F88020D3F8803072B64FF0E023C3F88F -:10067000084DD4E90004BFF34F8FBFF36F8F264AB4 -:10068000C2F88410BFF34F8F536923F48033536152 -:10069000BFF34F8FD2F8803043F6E076C3F3C9053D -:1006A000C3F34E335B0103EA060C29464CEA81771B -:1006B0000139C2F87472F9D2203B13F1200FF2D144 -:1006C000BFF34F8FBFF36F8FBFF34F8FBFF36F8FAA -:1006D000536923F4003353610023C2F85032BFF34F -:1006E0004F8FBFF36F8F302383F31188854680F3DC -:1006F000088820476AE700BFE8230020F024002094 -:100700000000040820000408FFFF03080023002065 -:10071000004502580044025800ED00E02DE9F04F7A -:1007200093B0B74B2022FF2100900AA89D6801F0EA -:1007300039F9B44A1378A3B90121B34811700360A1 -:10074000302383F3118803680BB105F047F90023C8 -:10075000AE4A4FF47A71AC4805F036F9002383F3C2 -:100760001188009B13B1AA4B009A1A60A94A13780A -:10077000032B03D000231370A54A53604FF0000AE7 -:10078000009CD3465646D146012001F0D1F824B151 -:100790009F4B1B68002B00F02C82002000F0E2FF32 -:1007A0000390039B002B01DA00F066FE039B002BF5 -:1007B000EDDB012001F0BAF8039B213B1F2BE3D8AE -:1007C00001A252F823F000BF490800087108000890 -:1007D000050900088907000889070008890700083B -:1007E00097090008670B0008810A0008E30A00085F -:1007F0000B0B0008310B000889070008430B0008A9 -:1008000089070008B50B0008E908000889070008F7 -:10081000F90B000855080008E908000889070008D6 -:10082000E30A00088907000889070008890700080B -:100830008907000889070008890700088907000858 -:1008400089070008050900080220FFF74FFE00286D -:1008500040F0F981009B022105A8BAF1000F08BF02 -:100860001C4641F21233ADF8143000F099FF8BE7CB -:100870004FF47A7000F076FF071EEBDB0220FFF7E3 -:1008800035FE0028E6D0013F052F00F2DE81DFE8CB -:1008900007F0030A0D1013360523042105A805935C -:1008A00000F07EFF17E004215548F9E704215A487B -:1008B000F6E704215948F3E74FF01C08404608F1D9 -:1008C000040800F0ABFF0421059005A800F068FFC4 -:1008D000B8F12C0FF2D101204FF0000900FA07F710 -:1008E00047EA0B0B5FFA8BFB01F0A8F826B10BF07F -:1008F0000B030B2B08BF0024FFF700FE44E7042185 -:100900004748CDE7002EA5D00BF00B030B2BA1D150 -:100910000220FFF7EBFD074600289BD001200026B0 -:1009200000F07AFF0220FFF731FE1FFA86F84046FA -:1009300000F082FF0446B0B1039940460136A1F1B0 -:1009400040025142514100F08FFF0028EDD1BA46DC -:10095000044641F21213022105A83E46ADF81430B8 -:1009600000F01EFF10E725460120FFF70FFE244B85 -:100970009B68AB4207D9284600F050FF013040F099 -:1009800067810435F3E70025224BBA463E461D70C9 -:100990001F4B5D60A8E7002E3FF45CAF0BF00B032C -:1009A0000B2B7FF457AF0220FFF7F0FD322000F051 -:1009B000D9FEB0F10008FFF64DAF18F003077FF441 -:1009C00049AF0F4A08EB0503926893423FF642AFE6 -:1009D000B8F5807F3FF73EAF124BB845019323DD5A -:1009E0004FF47A7000F0BEFE0390039A002AFFF6DF -:1009F00031AF039A0137019B03F8012BEDE700BFEC -:100A000000230020EC240020D0230020150500083E -:100A1000F0240020E82300200423002008230020E5 -:100A20000C230020EC230020C820FFF75FFD0746C1 -:100A300000283FF40FAF1F2D11D8C5F120020AABDB -:100A400025F0030084494245184428BF42460192DC -:100A500000F082FF019AFF217F4800F0A3FF4FEAD8 -:100A6000A803C8F387027C492846019300F0A2FF3F -:100A7000064600283FF46DAF019B05EB830533E785 -:100A80000220FFF733FD00283FF4E4AE00F0FEFE45 -:100A900000283FF4DFAE0027B846704B9B68BB428E -:100AA00018D91F2F11D80A9B01330ED027F003034A -:100AB00012AA134453F8203C05934046042205A98A -:100AC000043701F059FA8046E7E7384600F0A6FE01 -:100AD0000590F2E7CDF81480042105A800F060FE2F -:100AE00002E70023642104A8049300F04FFE0028CD -:100AF0007FF4B0AE0220FFF7F9FC00283FF4AAAE65 -:100B0000049800F0B9FE0590E6E70023642104A8EC -:100B1000049300F03BFE00287FF49CAE0220FFF718 -:100B2000E5FC00283FF496AE049800F0A7FEEAE743 -:100B30000220FFF7DBFC00283FF48CAE00F0B6FE8D -:100B4000E1E70220FFF7D2FC00283FF483AE05A9BD -:100B5000142000F0B1FE07460421049004A800F020 -:100B60001FFE3946B9E7322000F0FCFD071EFFF6F4 -:100B700071AEBB077FF46EAE384A07EB090392688B -:100B800093423FF667AE0220FFF7B0FC00283FF427 -:100B900061AE27F003074F44B9453FF4A5AE484680 -:100BA00009F1040900F03AFE0421059005A800F0BF -:100BB000F7FDF1E74FF47A70FFF798FC00283FF457 -:100BC00049AE00F063FE002844D00A9B01330BD0ED -:100BD00008220AA9002000F0EDFE00283AD02022C9 -:100BE000FF210AA800F0DEFEFFF788FC1C4804F095 -:100BF0002FFE13B0BDE8F08F002E3FF42BAE0BF0AC -:100C00000B030B2B7FF426AE0023642105A805936C -:100C100000F0BCFD074600287FF41CAE0220FFF761 -:100C200065FC804600283FF415AEFFF767FC41F2F3 -:100C3000883004F00DFE059800F04AFF46463C4619 -:100C400000F0FCFEA0E506464EE64FF0000901E686 -:100C5000BA467EE637467CE6EC23002000230020DF -:100C6000A0860100094A49F26900136899B21B0C79 -:100C700000FB013344F250611360054B186882B2E7 -:100C8000000C01FB0200186080B2704714230020A2 -:100C9000102300200021102210B5044600F082FE2F -:100CA000034B03CB206061601868A06010BD00BFDB -:100CB00000E8F11F2DE9F041ADF5507D0D46002112 -:100CC00040F275126EAC074610A80F9100F06AFE54 -:100CD0004FF4C4720021204600F064FE0DF13C0880 -:100CE00002F014FB4FF47A72264BB0FBF2F018605E -:100CF00093E80700022384E807000DF5ED702382D6 -:100D0000FFF7C8FF43F204731F4907A8238406F0C6 -:100D10006FFE1E230DF2EB220DF1340C84F83231FC -:100D200007AB1E46083203CE664542F8080C42F86F -:100D3000041C3346F5D13068414610602046B38824 -:100D40009380012200F03CFF002380B2E97E0393F0 -:100D5000AB7E029305F1190301930123009307A3CE -:100D6000D3E90023CDE90480384602F08DFE0DF56D -:100D7000507DBDE8F08100BFAFF300809E6AC421C2 -:100D8000818A46EEF8240020007A00082DE9F0411F -:100D90002C4CDAB080460D46237A5BBB27A9284647 -:100DA00001F01CF80746002842D19DF89D60C82E2E -:100DB0003ED801464FF4A662204600F0F3FD4FF402 -:100DC000807332460DF19E01C4F8F8314FF4007380 -:100DD00004F109002644C4F80C334FF44073C4F8FE -:100DE000203400F0B9FD9DF89C30777223720BB966 -:100DF000EB7E237206AC8122002127A800F0D2FDF1 -:100E00000122214627A801F025F8002380B2E97EBF -:100E10000393AB7E029305F1190301932823CDE9D7 -:100E200004400093404605A3D3E9002302F02CFEC2 -:100E30005AB0BDE8F08100BFAFF300802641727266 -:100E4000DF25D7B7004A0020F0B5254E4FF48A754C -:100E5000F1B0002405FB006596F8D830D822214671 -:100E600085F8DC303AA885F8E84006AF00F09AFD36 -:100E700006F1090000F08EFDD5F8E430C2B206F1AB -:100E800009018DF8F0000DF1F100CDE93A3400F0E0 -:100E900063FD394601223AA801F008F8082380B220 -:100EA000317ACDE9047001270E48CDE9023706F109 -:100EB000D80301933023009307A3D3E9002302F062 -:100EC000E3FDA04206DD02F021FAC5F8E000384655 -:100ED00071B0F0BD2046FBE778F6339F93CACD8D05 -:100EE000004A0020103500202DE9F0411D4D86B04C -:100EF0001D4E1E4F284602F0F3FD034658B3002452 -:100F0000DFF86C80ADF814400294CDE90344027B15 -:100F10008DF8142003AA9968406803C21B6843F047 -:100F20000043029302F0F4F982190094384641F12B -:100F3000000302A901F030FAA04205DD284602F0C4 -:100F4000D3FD88F80040D5E798F80030072B05D886 -:100F5000013388F8003006B0BDE8F081014802F0A6 -:100F6000C3FDF8E71035002040420F004035002057 -:100F7000354F002070B50D4614461E4602F0E0FCC9 -:100F800050B9022E10D1012C0ED112A3D3E90023A7 -:100F90000120C5E9002307E0282C10D005D8012C3A -:100FA00009D0052C0FD0002070BD302CFBD10BA335 -:100FB000D3E90023ECE70BA3D3E90023E8E70BA375 -:100FC000D3E90023E4E70BA3D3E90023E0E700BF64 -:100FD000AFF30080401DA12026812A0B78F6339FB5 -:100FE00093CACD8D9E6AC421818A46EE26417272D3 -:100FF000DF25D7B7F017304A39059E5638B5054674 -:101000000E4C0021013500F02FFCA4F82C55B4F84B -:101010002C0500F011FC78B1B4F82C0500F01CFC94 -:10102000014648B9B4F82C0500F01EFCB4F82C3584 -:101030000133A4F82C35EAE738BD00BF004A002090 -:101040000A4B0B4A10B51A6003F5805393F84820F9 -:101050003AB95C6C2CB1204601F022F8204606F02B -:101060007DFC0448BDE8104001F01AB8403500206E -:10107000B07A0008704500202DE9F04F8FB005468A -:101080000C4600AF02F05CFC002849D1237E022B05 -:101090001BD1E38A012B18D102F038F90646FFF77D -:1010A000E1FD03464FF4C87006F51676DFF8C082FE -:1010B000B3FBF0F202FB103316FA83F3C8F80030EA -:1010C000E37E33B9A34B00221A703C37BD46BDE81E -:1010D000F08F07F12401204600F03EFE0028F4D1F5 -:1010E00007F11400FFF7D6FD97F8264007F1140129 -:1010F00007F12700224606F049FC0028E2D10F2C18 -:1011000008D8944B1C70D8F80030A3F51673C8F8B3 -:101110000030DAE797F82410284602F009FCD4E7FB -:10112000E38A282B2BD010D8012B23D0052BCCD130 -:10113000BFF34F8F8849894BCA6802F4E0621343BA -:10114000CB60BFF34F8F00BFFDE7302BBDD1844E86 -:10115000E17E327A9142B8D1607E3146002291F828 -:10116000DC50854200F0A580013201F58A71042A25 -:10117000F5D1AAE721462846FFF79CFDA5E72146C1 -:101180002846FFF703FEA0E7B2F8EC507B6005F1BC -:1011900003094FEA99094FEA8902D11DC908A8EB52 -:1011A000C10300219D46EB46584600F0FBFB04F1CD -:1011B000EE012A465846314400F0CEFB7B6813B955 -:1011C000012000F029FB96F8D20000F035FB044620 -:1011D00030B9307200F05AFB204600F01DFBB1E040 -:1011E000D6F8D4203AB996F8D200B6F82C25824227 -:1011F00001D8FFF703FFD6F8D4202A44944208D23E -:1012000096F8D200B6F82C250130824201D8FFF7BB -:10121000F5FE5FFA89F25946706800F0CBFB08B919 -:10122000C54679E0726896F8D2002A447260D6F812 -:10123000D42005EB0209C6F8D49000F0FDFA8145F0 -:1012400009D396F8D220D6F8D4000132001B86F8D4 -:10125000D220C6F8D400FF2D0FD80024347200F03D -:1012600015FB204600F0D8FA00F09CFE3D4B18819B -:1012700008B9FFF7A1F9C54627E7BB6896F8D9007A -:101280000AFB0362FB68D2F8E41082F8E83001F54B -:101290008061C2F8E030C2F8E410FFF7D5FDFFF737 -:1012A00023FE96F8D920013202F0030286F8D920F5 -:1012B000B6E74FF48A7A20460AFB02F505F1EA0107 -:1012C000314400F01FFEF86000287FF4FEAE0122DA -:1012D000354485F8E82002F019F8D5F8E020D6ED7D -:1012E000007A801A40F6B832B8EE677ADFED1E6AEF -:1012F000192838BF1920904228BF104607EE900ADF -:10130000F8EEE77A67EEA67ADFED186AE7EE267A5E -:10131000FCEEE77AC6ED007A96F8D930BB60BA6881 -:1013200073680AFB02F4321992F8E81059B1D2F846 -:10133000E410E8468B423FF427AF002182F8E81022 -:10134000C2F8E010C5467368064A9B0A0133138150 -:10135000BBE600BF0935002000ED00E00400FA05FF -:10136000004A0020F8240020CDCCCC3D6666663FC4 -:101370000C350020014B1870704700BF0425002079 -:1013800038B54FF00054144B22689A4221D1627D47 -:101390000025124B12481A70C922237D09301149C9 -:1013A00000F8013C4FF48073C0F8DB50C0F8EF3117 -:1013B0004FF40073C0F803334FF44073C0F8173490 -:1013C00000F0CAFAE0222946204600F0EBFA01209C -:1013D00038BD0020FCE700BF9AAD44C504250020BD -:1013E000004A00201600002037B500F0DBFD194D43 -:1013F00002230022184928816B710123174801F04C -:1014000047FB002316494FF480520193154B1648B1 -:101410000093164B02F064FA154B197811B112487B -:1014200002F086FA01F072FF0446FFF71BFC4FF44E -:10143000C873B0FBF3F202FB130304F5167010FA45 -:1014400083F00C4B186004F00DFF08B10F232B81C3 -:1014500003B030BDF824002040420F00403500208A -:1014600008250020750F00081035002079100008AD -:10147000042500200C3500202DE9F04F8C4C2DED7B -:10148000028B85A7D7E9006795B00FF21429D9E937 -:1014900000899FED858BFFF727FD0DAD0023DFF859 -:1014A00024B20C93ADF83C300D936B6000234FF0E9 -:1014B000010A0DF1250209A958468DF825308DF84D -:1014C00024A08DED008B01F089FE9DF824200023DF -:1014D000002A40F0AE80204602F032FA054600288D -:1014E00047D1DFF8E4B101F011FFDBF8003098429A -:1014F0003FD301F00BFF0790FFF7B4FB4FF4C87325 -:10150000079AB0FBF3F101FB130302F5167010FA12 -:1015100083F0CBF8000010A8DFF8B0B19BF8001002 -:10152000002914BF2B46534607918DF83030FFF742 -:10153000B1FB079910AB0DF13100C1F11002194454 -:10154000D2B2062A28BF0622079200F005FA079AAF -:101550000CAB2046039301321823D2B20293554BB1 -:1015600004923246CDE900A33B4602F02FFA8BF8F5 -:10157000005001F0CBFE504A504D1368C31AB3F52A -:101580007A7F32D3106001F0C3FE02460B4620463C -:1015900002F0B4FA204602F0D3F930B32B7A0DF101 -:1015A000400BDFF82CA1002B14BF032302238AF881 -:1015B000053001F0ABFE4FF47A7301225946B0FBBF -:1015C000F3F0CAF80000504600F09EFB182380B2EA -:1015D000424602933A4B019340F25513CDE903B0D2 -:1015E000009320464B4602F0F1F92B7AABB101F0A3 -:1015F0008DFE4FF0000A83464FF48A7295F8D900A9 -:10160000504400F0030002FB005393F8E81071B35C -:101610000AF1010ABAF1040FF0D1C82004F018F958 -:101620002B7A002B7FF435AF15B0BDEC028BBDE8F3 -:10163000F08F1946102210A800F0B4F90DF126031E -:101640000AAA0CA9584601F0B3F811AB95E80300BB -:1016500083E803009DF83C3010A920468DF84C30FB -:101660000C9B1093DDE90A2302F01CFC1EE7D3F863 -:10167000E01049B12B68ABEB0101FA2B38BFFA231C -:101680000533B1EB430FC3D3FFF7DEFB4FF48A7290 -:101690000028BDD1C1E700BF401DA12026812A0B33 -:1016A000F1C6A7C1D068080F0000000000000000CC -:1016B0001035002008350020304F0020004A00205F -:1016C000344F0020403500200C3500200935002023 -:1016D000F824002008B5054801F012F9044A05492C -:1016E0000020BDE8084006F033B900BF40350020B7 -:1016F0008C4F0020411000082DE9F84F4FF47A7309 -:1017000006460D46002402FB03F7DFF85080DFF8A1 -:10171000509098F900305FFA84FA5A1C01D0A34225 -:1017200012D159F824002A4631460368D3F820B074 -:101730003B46D847854207D1074B012083F800A0DC -:10174000BDE8F88F0124E4E7002CFBD04FF4FA70D9 -:1017500004F07EF80020F3E77C4F002018230020DF -:101760001C230020002307B5024601210DF10700CC -:101770008DF80730FFF7C0FF20B19DF8070003B0D8 -:101780005DF804FB4FF0FF30F9E700000A46042142 -:1017900008B5FFF7B1FF80F00100C0B2404208BDBC -:1017A000074B0A4630B41978064B53F821400146DE -:1017B00023682046DD69044BAC4630BC604700BF5F -:1017C0007C4F00201C230020A086010070B5104C27 -:1017D0000025104E04F066FB208030682388834289 -:1017E0000CD800252088013804F058FB23880544D4 -:1017F000013BB5F5802F2380F4D370BD04F04EFB80 -:10180000336805440133B5F5802F3360E5D3E8E74D -:101810007E4F0020384F002004F012BC00F1006021 -:1018200000F580200068704700F10060920000F52C -:10183000802004F093BB0000054B1A68054B1B8801 -:101840009B1A834202D9104404F028BB0020704741 -:10185000384F00207E4F0020024B1B68184404F0D4 -:1018600023BB00BF384F0020024B1B68184404F014 -:101870002DBB00BF384F00200020704700F1FF5003 -:1018800000F58F10D0F8000870470000064991F865 -:10189000243033B100230822086A81F82430FFF78E -:1018A000C3BF0120704700BF3C4F0020014B1868A8 -:1018B000704700BF0010005C194B01380322084438 -:1018C00070B51D68174BC5F30B042D0C1E88A6427E -:1018D0000BD15C680A46013C824213460FD214F9D0 -:1018E000016F4EB102F8016BF6E7013A03F108030C -:1018F000ECD181420B4602D22C2203F8012B0424A6 -:10190000094A1688AE4204D1984284BF967803F8FB -:10191000016B013C02F10402F3D1581A70BD00BF03 -:101920000010005C242300204C7A0008704700005F -:10193000704700007047000070B504464FF47A7697 -:101940004CB1412C254628BF412506FB05F0641B00 -:1019500003F07EFFF4E770BD002310B5934203D07F -:10196000CC5CC4540133F9E710BD0000013810B558 -:1019700010F9013F3BB191F900409C4203D11AB1EB -:101980000131013AF4E71AB191F90020981A10BD1B -:101990001046FCE703460246D01A12F9011B002943 -:1019A000FAD1704702440346934202D003F8011B68 -:1019B000FAE770472DE9F8431F4D1446074688465D -:1019C00095F8242052BBDFF870909CB395F8243032 -:1019D0002BB92022FF2148462F62FFF7E3FF95F83D -:1019E00024004146C0F1080205EB8000A24228BF56 -:1019F0002246D6B29200FFF7AFFF95F82430A41B21 -:101A000017441E449044E4B2F6B2082E85F82460D0 -:101A1000DBD1FFF73BFF0028D7D108E02B6A03EBAF -:101A200082038342CFD0FFF731FF0028CBD10020C3 -:101A3000BDE8F8830120FBE73C4F0020024B1A78F9 -:101A4000024B1A70704700BF7C4F00201823002003 -:101A500038B51A4C1A4D204603F03EFA2946204666 -:101A600003F066FA2D684FF47A70D5F89020D2F81A -:101A7000043843F00203C2F80438FFF75DFF114950 -:101A8000284603F063FBD5F890200F4DD2F80438B8 -:101A9000286823F002030D49A042C2F804384FF42D -:101AA000E1330B6001D003F075F96868A04204D0FF -:101AB0000649BDE8384003F06DB938BDF056002046 -:101AC000FC7C0008047D00081C230020644F0020DB -:101AD0000C4B70B50C4D04461E780C4B55F8262067 -:101AE0009A420DD00A4B002118221846FFF75AFFE0 -:101AF0000460014655F82600BDE8704003F04AB97D -:101B000070BD00BF7C4F00201C230020F056002039 -:101B1000644F0020F0B5A1B071B60023012000246D -:101B200080261A46194602F01DFE4FF4D067214A5E -:101B30003D25136923BBD2F810310BBB036804F1B8 -:101B4000006199600368C3F80CD003685E600368A5 -:101B50001F6001680B6843F001030B6001680B68AC -:101B600023F01E030B6001680B68DB07FCD4037BCA -:101B70008034416805FA03F3B4F5001F0B60D8D137 -:101B800002F026FEB4F5001F11D000240A4E0B4DC2 -:101B9000012004F055FA3388A34205D9286820446F -:101BA000013404F093F9F6E7002004F049FA61B635 -:101BB00021B0F0BD002000527E4F0020384F0020A1 -:101BC0002DE9F0470D46044600219046284640F294 -:101BD0007912FFF7E7FE234620220021284604F170 -:101BE000220702F001F9231D022220212846C026E7 -:101BF00002F0FAF8631D03222221284602F0F4F8CD -:101C0000A31D03222521284602F0EEF804F1080363 -:101C100010222821284602F0E7F804F110030822D8 -:101C20003821284602F0E0F804F11103082240218F -:101C3000284602F0D9F804F1120308224821284668 -:101C400002F0D2F804F1140320225021284602F0B9 -:101C5000CBF804F1180340227021284602F0C4F8A2 -:101C600004F120030822B021284602F0BDF804F157 -:101C700021030822B821284602F0B6F8314608367A -:101C80003B4608222846013702F0AEF8B6F5A07FA1 -:101C9000F4D1002704F1330A04F13203082231465B -:101CA000284602F0A1F894F832304FEAC7099F4263 -:101CB00009F5A47615D3B8F1000F08D1314609F221 -:101CC0004F1604F599730722284602F08DF827462F -:101CD0003B1B94F8322193420CD3F01DC008BDE8A1 -:101CE000F0870AEB0703082231462846013702F045 -:101CF0007BF8D8E707F23313314608222846083626 -:101D0000013702F071F8E3E713B5044608460021F5 -:101D10002022234601900160C0F8031002F064F80D -:101D2000231D01980222202102F05EF8631D019814 -:101D30000322222102F058F8A31D01980322252135 -:101D400002F052F8019804F108031022282102F051 -:101D50004BF8072002B010BD0023F7B50E46047FF4 -:101D6000072200911946054601F002FF731C01226B -:101D7000072100932846002301F0FAFEC4B9B31CE2 -:101D8000052208212846009323460D2401F0F0FE89 -:101D90003746BB1BB278934211D307342B7FA88AF6 -:101DA000E408BBB9844294BF0020012003B0F0BD19 -:101DB000AB8A0824DB00083BDB08B370E8E7FB1CB8 -:101DC000214608222846009300230834013701F0F9 -:101DD000CFFEDEE7201A18BF0120E7E70023F7B5A2 -:101DE0000E46047F082200911946054601F0C0FE08 -:101DF000731CC4B9082200932346102411462846B8 -:101E000001F0B6FE01235F1C7278013B934211D3AF -:101E100007342B7FA88AE408BBB9844294BF002012 -:101E2000012003B0F0BDAB8A0824DB00083BDB08CF -:101E30007370E7E7F3192146082228460093002330 -:101E400001F096FE08343B46DDE7201A18BF01205A -:101E5000E7E70000F8B50E4605461446002181224A -:101E60003046FFF79FFD2B4608220021304601F047 -:101E7000BBFF7CB90F246B1C07220821304601F000 -:101E8000B3FF01235F1C6A78013B934204D3E01D3A -:101E9000C008F8BD0824F4E7EB19214608223046B3 -:101EA00001F0A2FF08343B46ECE70000F8B50E460F -:101EB000054614460021CE223046FFF773FD2B461F -:101EC00028220021304601F08FFF7CB9302405F133 -:101ED000080308222821304601F086FF2F467B1B8D -:101EE0002A7A934204D3E01DC008F8BD2824F5E700 -:101EF00007F109032146082230460834013701F072 -:101F000073FFECE7F7B5047F0E4600910123102222 -:101F10000021054601F02CFEC4B9B31C0922102192 -:101F2000284600932346192401F022FE3746728882 -:101F3000BB1B9A4211D807342B7FA88AE408BBB98F -:101F4000844294BF0020012003B0F0BDAB8A10246E -:101F5000DB00103BDB087380E8E73B1D21460822CD -:101F60002846009300230834013701F001FEDEE724 -:101F7000201A18BF0120E7E730B50A44084D914206 -:101F80000DD011F8013B5840082340F30004013BF9 -:101F90002C4013F0FF0384EA5000F6D1EFE730BD88 -:101FA0002083B8EDF7B5384A6B46106851686A4629 -:101FB00003C308233549364805F0F8FC04460028D9 -:101FC00033D10A25334A6B46106851686A4603C309 -:101FD000082331492E4805F0E9FC0446002849D081 -:101FE0000369B3F5E01F45D8B0F8661040F23742F8 -:101FF00091423FD1294A024402F15C018B4239D31C -:102000005C3B234900209E1AFFF7B6FF04F16401F0 -:10201000074632460020FFF7AFFFA3689F4229D151 -:10202000E368984208BF002524E00369B3F5E01F88 -:1020300027D8418B40F23742914220D1174A0244BF -:1020400002F110018B4218D3103B114900209D1A58 -:10205000FFF792FF04F1180106462A460020FFF719 -:102060008BFFA3689E4202D1E368984201D00D2500 -:10207000A8E70025284603B0F0BD1025A2E70C25EF -:10208000A0E70B259EE700BF5C7A0008DCFF1B0081 -:1020900000000408657A000890FF1B000800FCF7A8 -:1020A00010B5037C044613B9006805F067FC2046B0 -:1020B00010BD00000023BFF35B8FC360BFF35B8FD5 -:1020C000BFF35B8F8360BFF35B8F7047BFF35B8FA2 -:1020D0000068BFF35B8F704770B505460C30FFF7A3 -:1020E000F5FF044605F108063046FFF7EFFFA04272 -:1020F00006D96D683046FFF7E9FF2544281A70BD00 -:102100003046FFF7E3FF201AF9E7000070B50546F7 -:102110004068A0B105F10C0605F10800FFF7D6FFF5 -:1021200004463046FFF7D2FF844204F1FF343046C4 -:1021300094BF6D680025FFF7C9FF2C44201A70BDBD -:1021400038B50C460546FFF7C7FFA04210D305F18E -:102150000800FFF7BBFF04446868BFF35B8FB4FB64 -:10216000F0F100FB11440120AC60BFF35B8F38BD80 -:102170000020FCE72DE9F041144607460D46FFF725 -:10218000C5FF844228BF0446D4B1B84658F80C6B4A -:102190004046FFF79BFF3044286040467E68FFF7CB -:1021A00095FF331A9C4203D801206C60BDE8F08192 -:1021B000A41B6B603B682044AB60E8600220F5E73D -:1021C0002046F3E738B50C460546FFF79FFFA042CF -:1021D00010D305F10C00FFF779FF04446868BFF3E2 -:1021E0005B8FB4FBF0F100FB11440120EC60BFF306 -:1021F0005B8F38BD0020FCE72DE9FF41884669462A -:1022000007466C46FFF7B6FF002506B204EBC6068C -:10221000B4420AD0626808EB050120680834FFF771 -:102220009BFB54F8043C1D44F2E729463846FFF76F -:10223000C9FF284604B0BDE8F0810000F8B50546A6 -:102240000C300F46FFF742FF05F108060446304602 -:10225000FFF73CFFA042304688BF6C68FFF736FFAF -:10226000201A386020B12C683046FFF72FFF204439 -:10227000F8BD000073B5144606460D46FFF72CFF67 -:102280008442019028BF0446DCB101A93046FFF723 -:10229000D5FF019B33B93268C5E90233C5E9002493 -:1022A00001200CE09C42286038BF019401988442D0 -:1022B0006860F5D93368241A0220AB60EC6002B084 -:1022C00070BD2046FBE700002DE9FF410F4669463F -:1022D0006C46FFF7CFFF00B2002604EBC005AC420E -:1022E00009D0D4F80480B81954F8081B4246464473 -:1022F000FFF732FBF3E7304604B0BDE8F0810000A1 -:1023000038B50546FFF7E0FF044601462846FFF7CB -:1023100017FF204638BD00007047000010B4134678 -:10232000026814680022A4465DF8044B6047000070 -:1023300000F5805090F859047047000000F5805077 -:1023400090F852047047000000F5805090F958044E -:10235000704700004E207047302383F3118800F54A -:102360008052D2F89C34D2F898041844D2F89434AD -:102370001844D2F87C341844D2F88C341844D2F87B -:1023800088341844002383F31188704700F5805087 -:10239000C0F85414012070472DE9F04F0C4600F5A9 -:1023A000805185B01F4691F8523405469046BDF8DD -:1023B00038909BB1D1F878340133C1F87834236870 -:1023C000980006D4237B082B0BD9627B0AB10F2B14 -:1023D00007D9D1F87C340133C1F87C344FF0FF3099 -:1023E00010E0302383F31188EB6AD3F8C42012F491 -:1023F000001B0AD0D1F8803400200133C1F88034AA -:1024000080F3118805B0BDE8F08F20684822D3F82A -:10241000C4300028C3F3044A6B6AB4BF40F0804064 -:10242000800412FB0A334FEA4A16186022685200F1 -:102430004FEA0A6244BF40F000501860207B42EA35 -:1024400000425A60607B10B342F440125A60D1F8E7 -:10245000B0240132C1F8B024AA1902F58352117BCD -:1024600041F020011173207B039300F0ABFF033098 -:10247000039B80105FFA8BF20BF1010B82420DDAA5 -:1024800004EB820103EB820249689160F2E7AA192A -:1024900002F58352117B60F34511E3E70122EB6AF9 -:1024A00005EB4A1102FA0AF201F58251C3F8D02075 -:1024B000AB19183104F10C0203F58253C3E9048708 -:1024C000234653F8040B934241F8040BF9D11B88BF -:1024D0002E440B8041F2680346F803A006F58056AF -:1024E00009F0030396F86C2043F0100322F01F025A -:1024F000134386F86C30002383F3118842463B4631 -:1025000021462846CDF8009000F022FF012079E70F -:102510002DE9F04700F58056044696F85254002DF8 -:1025200040F00381037C032B40F0948028462B4627 -:102530002F465FFA80FC944510DA01EBCC0E51F87F -:102540003CC0BCF1000F04DBDEF804C0BCF1000F9E -:1025500002DB01370130ECE70133FBE7302080F389 -:102560001188E06AF3B9D0F8803043F00203C0F874 -:1025700080304E23E06A002F6FD1D0F8803043F0D6 -:102580000103C0F880306A4B6A4A1B6803F180532C -:1025900003F52C539B009342A36240F2B08066483F -:1025A00000F0AEFE4D2B42D8DFF884814FEA034E97 -:1025B000DFF88891D8F800C04EEA8C0EC0F884E0AD -:1025C0000CF1805000F52C508000606103EB0C0092 -:1025D000D4F82CC0C3F14E03C8F80000DCF880002A -:1025E00040F03000CCF880004FF0000CD4F814809C -:1025F000E6465FFA8CF08242BCDD01EBC00A51F87E -:102600003000002810DBDAF804A0BAF1000F0BDA72 -:1026100009EA00400AF07F0A40EA0A0040F0084058 -:1026200048F82E000EF1010E0CF1010CE1E7836970 -:1026300023F00103836100F069FE0646E36A9B69AB -:10264000D90704D500F062FE831BFA2BF6D90023CC -:1026500083F311882846BDE8F087B7EB530F3DD2CE -:10266000DFF8CCE04FEA074CDEF800304CEA830C90 -:10267000C0F888C003F1805003EB4703002700F542 -:102680002C50CEF80030BC468000A061E06AD0F843 -:10269000803043F00C03C0F88030D4F818E0FBB26F -:1026A0009A427FF770AF51F8330001EBC30800285E -:1026B000D8F8043001DB002B0EDB20F0604023F063 -:1026C000604340F0005043F000434EF83C000EEBF6 -:1026D000CC000CF1010C43600137E0E7836923F083 -:1026E0000103836100F012FE0646E36A9B69DA0784 -:1026F000ADD500F00BFE831BFA2BF6D9A7E7E26AF3 -:10270000936923F00103936100F000FE0746E36A3A -:102710009B69DB0705D500F0F9FDC31BFA2BF6D941 -:1027200095E7012586F8525491E7002592E700BF0E -:10273000884F0020FCB50040707A00080000FF07B9 -:1027400013B500F580540191606CFFF7DFFC1F2882 -:102750000AD920220199606CFFF74EFDA0F12003F9 -:102760005842584102B010BD0020FBE708B53023A5 -:1027700083F3118800F58050406CFFF79BFC002329 -:1027800083F3118808BD000000220260828142604C -:10279000826070470022002310B5C0E900230023A7 -:1027A00004460C3020F8043CFFF7EEFF204610BD35 -:1027B0002DE9F0479A4688B007468846914630236F -:1027C00083F3118807F580546846FFF7E3FF606CD8 -:1027D000FFF782FC1F282ED920226946606CFFF784 -:1027E0008FFD202827D194F8523423B303AD4446FB -:1027F00005AB2E46083403CE9E4244F8080C44F83C -:10280000041C3546F5D130682060B388A380DDE92B -:102810000023C9E90023BDF80830AAF800300023DE -:1028200083F3118853464A464146384608B0BDE80E -:10283000F04700F07BBD002080F3118808B0BDE8B0 -:10284000F08700002DE9F84F0023064600F581547B -:10285000054688461034C0E90133264B46F8303B24 -:10286000374638462037FFF795FFA742F9D105F5DF -:1028700080544FF4805305F5A3594FF0000A2663A6 -:102880000026676405F5835709F110094FF0000B26 -:102890001037E663C4E90D36012384F8403084F82C -:1028A0004830A7F11800203747E910ABFFF76CFF5D -:1028B00047F8286C4F45F4D184F85884A4F85A643A -:1028C000A4F85C64A4F85E6484F86064A4F86264AC -:1028D000A4F86464A4F8666484F86864B8F1000F2E -:1028E00002D0054800F00CFD044B2846EB62BDE821 -:1028F000F88F00BFB07A0008947A000800A000406A -:10290000044B10B5197804464A1C1A70FFF79AFF59 -:10291000204610BD854F00202DE9F04300295AD0F4 -:102920002E4E2F48B6FBF1F481428CBF0A201120B5 -:10293000431EB4FBF0F700FB1740DDB220B1022BC1 -:102940001846F5D8002032E07B1EB3F5806F2ED2FA -:10295000C5EBC5084FF47A7308F103044FEAE40E9F -:10296000C4F3C7040EF10109281B0EFB033E5FFAF6 -:1029700080FC59FA80F0BEFBF0F0B0F5617F18DC06 -:1029800083B2601C5CFA80F07843B6FBF0F08142C1 -:10299000D8D1611E0F29D5D80CF1FF310729D1D824 -:1029A0000120138057801071547182F806C0BDE871 -:1029B000F08308F1FF34E010C4F3C70400F1010E06 -:1029C0002D1B00FB03335FFA85FC5EFA85F5B3FB34 -:1029D000F5F39BB2D5E70846E9E700BF00B4C404AD -:1029E0003F420F0030B50D4B05200D4D1C786C4358 -:1029F0008C420ED159780120518099785171D97843 -:102A00009171197911715B7903EB83035B0013807A -:102A100030BD013803F10603E8D1F9E7F07A000888 -:102A200040420F0038B540F27772C36A154CC3F8C4 -:102A3000BC200722C36AC3F8C8202268C16A930079 -:102A400043F4C023C1F8A03002F1805302F16C01BD -:102A5000C56A03F52C53EA3289009B00226041F0DD -:102A6000E061094AC361C5F8C01003F5D87103F5E8 -:102A70006A7341629342836202D9044800F040FCC9 -:102A800038BD00BF884F0020FCB50040707A0008B8 -:102A90002DE9F04F00F580551F4689B0044695F8A2 -:102AA000583489469046012B04D90026304609B097 -:102AB000BDE8F08FA04A52F8231009B942F823006C -:102AC0009E48C4F80C9001782774C9B9302383F369 -:102AD00011889B4BD3F8EC2042F48072C3F8EC20B1 -:102AE000D3F8942042F48072C3F89420D3F8942051 -:102AF00022F48072C3F894200123037081F31188BB -:102B000095F851647EB9302383F311880321132093 -:102B100001F074FF0321152001F070FF012385F8F7 -:102B2000513486F31188302383F31188E26A936964 -:102B300023F01003936100F0E9FB8246E36A9E698B -:102B400016F0080609D000F0E1FBA0EB0A03FA2B0F -:102B5000F4D9002686F31188A8E79A6942F00102A9 -:102B60009A6100F0D3FB8246E36A9A69D00706D4E3 -:102B700000F0CCFBA0EB0A03FA2BF5D9E9E79A6940 -:102B80004FF0000A42F002029A61E36AC3F854A0CF -:102B90008AF3118804F5825B686CFFF78BFA0BF1FE -:102BA000100B202200216846FEF7FCFE02A8FFF76A -:102BB000EBFD6A460BEB06030DF1180ECDF818A0DD -:102BC00094460833BCE80300F44543F8080C43F886 -:102BD000041C6246F4D1DCF8000020361860B6F51B -:102BE000806F9CF804201A71DBD1002304F5A252F7 -:102BF000494620461A3285F8503485F85334FFF799 -:102C00008BFE064690B9E26A936923F00103936153 -:102C100000F07CFB0546E36A9B69D9077FF545AF69 -:102C200000F074FB431BFA2BF5D93EE795F85E34B0 -:102C3000C5F86C94591E95F85F34E26A013B1B029B -:102C400043EA416395F8601401390B43B5F85C140D -:102C5000013943EA0143D361B8F1000F36D004F5DE -:102C6000A352414620460232FFF7BCFE90B9E26A09 -:102C7000936923F00103936100F048FB0546E36A82 -:102C80009B69DA077FF511AF00F040FB431BFA2B7D -:102C9000F5D90AE795F86724C5F87084511E95F8B0 -:102CA0006824E36A013A120142EA012295F86614A7 -:102CB00001390A43B5F86414013942EA014242F489 -:102CC0000002DA604FF42062E36A9A64E36A4FF02C -:102CD00000082046C3F8BC80FFF7A4FE85F859849D -:102CE0006FF04042E36A1A65164AE36A5A654FF08C -:102CF0000222E36A9A654FF0FF32E36AC3F8E020EC -:102D00000322E36A9742DA653FF4D0AEE26A936940 -:102D100023F00103936100F0F9FA0746E36A9B6927 -:102D2000DB0705D500F0F2FAC31BFA2BF6D9BCE697 -:102D3000012385F85234B9E6804F0020844F0020EB -:102D400000440258550200022DE9F04F054689B0B3 -:102D500090469946002741F2680A00F58056EB6AD2 -:102D6000D3F8D830FB40D80751D505EB47124FEACE -:102D7000471B52441379190749D4D6F884340133D8 -:102D8000C6F8843405F5A553C3E9008913799A067A -:102D900005EB0B0248BFD6F8B434524444BF0133AC -:102DA000C6F8B434137943F008031371DB0723D555 -:102DB00096F8533403B305F582546846FFF7EAFCEE -:102DC00003AB18345C4404F1080C2068083454F850 -:102DD000041C1A46644503C21346F6D120686946AE -:102DE00010602846A2889A800123ADF808302B682D -:102DF000CDE90089DB6B9847D6F8A834D6F854049F -:102E00000133C6F8A83410B103681B69984701372D -:102E1000202FA4D109B0BDE8F08F00002DE9F04FBC -:102E20000F468DB0044600F073FA82468946002FA3 -:102E30005BD1E36AD3F8A02012F4FE0F03D1002087 -:102E40000DB0BDE8F08FD3F8A420920141BF04F586 -:102E50008051D1F898240132C1F89824D3F8A420E5 -:102E60005606ECD0D3F8A450E669C5F305254823EF -:102E7000E8464FF0000B03FB05664046FFF784FC75 -:102E8000326851004ABF22F06043C2F38A4343F0E4 -:102E90000043920048BF43F080430093736813F4EB -:102EA00000131BBF012304F580528DF80D308DF8FF -:102EB0000D301EBFD2F8B8340133C2F8B834F388ED -:102EC00003F00F038DF80C309DF80C0000F07AFA37 -:102ED0005FFA8BF3984225D9F2180CA90BF1010B7C -:102EE000127A0B4403F82C2CEEE7012FA7D1E36AEA -:102EF000D3F8B02012F4FE0FA1D0D3F8B42095017E -:102F000041BF04F58051D1F898240132C1F89824CA -:102F1000D3F8B420500692D0D3F8B450266AC5F343 -:102F20000525A4E7EFB9E36AC3F8A85004A807ADE4 -:102F3000FFF730FC98E80F0007C52B8000232046E0 -:102F400004A9ADF81830236804F58054DB6BCDE993 -:102F500004A9984758B1D4F890340133C4F8903498 -:102F60006EE7012FE2D1E36AC3F8B850DEE7D4F888 -:102F7000943401200133C4F8943461E72DE9F04121 -:102F800005460F4600F58054012639462846FFF7CE -:102F900045FF10B184F85364F7E7D4F8A834D4F8A7 -:102FA00054040133C4F8A83420B10368BDE8F041EB -:102FB0001B691847BDE8F081C36AF0B51A6C12F4BA -:102FC0007F0F2BD01B6C00F5805441F268054FF049 -:102FD000010CC4F8AC340023471900EB43125E0126 -:102FE0002A44117911F0020F15D0490713D4B959A9 -:102FF000C66A0CFA01F1D6F8CCE011EA0E0F0AD03D -:10300000C6F8D410117941F004011171D4F88C2460 -:103010000132C4F88C240133202BDED1F0BD000036 -:1030200010B5264C264B22680AB340B31A6D9205A0 -:103030000FD54FF400721A6500F06AF950EA0102E8 -:103040000B4602D0013861F1000302462068FFF709 -:103050007BFE1B4A136D9B012AD523684FF000713C -:1030600003F580531165012283F8592420E00122E1 -:103070001A6510221A654FF480521A6510BD196D39 -:10308000C80702D4196D490705D5052110461965F1 -:103090000021FFF773FF0A4B1A6DD00602D41A6D98 -:1030A000510605D5502201211A652068FFF766FFF9 -:1030B0002068BDE81040FFF77FBF00BF804F0020B1 -:1030C00000A0004008B5302383F31188FFF774FF98 -:1030D000002383F3118808BDC36AD3F8C00010F041 -:1030E0007C5005D0D3F8C40080F40010C0F34050E9 -:1030F0007047000008B5302383F3118800F5805035 -:10310000406CFEF7E9FF002383F3118843090CBFED -:103110000120002008BD000000F5805393F85924D9 -:1031200062B1C16A8A6922F001028A61D3F89C24E3 -:103130000132C3F89C24002283F859247047000010 -:103140002DE9F743302181F3118800F582510025E4 -:1031500041F2680E4FF00108103100F5805C00EB81 -:1031600045147444267977071CD4F6061AD58E695F -:10317000D0F82C9008FA06F6D9F8CC703E4211D05F -:103180004F6801970F689742019F9F410AD2C9F883 -:10319000D460267946F004062671DCF888440134B0 -:1031A000CCF8884401352031202DD8D1002383F379 -:1031B000118803B0BDE8F083F8B51E4600230F4622 -:1031C000054613701446FFF795FF80F00100387034 -:1031D0001EB12846FFF780FF2070F8BD2DE9F04FA3 -:1031E00085B099460D468046164691F800B0DDE957 -:1031F0000EA302931378019300F08AF82B7804460B -:103200000F4613B93378002B41D022463B46404647 -:10321000FFF796FFFFF756FFFFF77EFF4B4632465C -:103220002946FFF7C9FF2B7833B1BBF1000F03D05C -:10323000012005B0BDE8F08F337813B1019B002B5E -:10324000F6D108F5805303935445029B77EB0303B3 -:103250001DD2039BD3F85404C8B10368AAEB040140 -:103260001B6898474B46324629464046FFF7A4FF65 -:103270002B7813B1BBF1000FDAD1337813B1019B76 -:10328000002BD5D100F044F804460F46DCE70020BF -:10329000CFE7000008B50020FFF7C2FEBDE80840F8 -:1032A00001F056B808B50120FFF7BAFEBDE80840A6 -:1032B00001F04EB800B59BB0EFF309816822684673 -:1032C000FEF74AFBEFF30583014B9B6BFEE700BF64 -:1032D00000ED00E008B5FFF7EDFF000000B59BB082 -:1032E000EFF3098168226846FEF736FBEFF30583AA -:1032F000014B5B6BFEE700BF00ED00E0FEE7000066 -:103300000FB408B5029802F049FAFEE702F0DABEFF -:1033100002F0BCBE13B56C46031D84E8060094E8B9 -:10332000030083E80500012002B010BD73B5856875 -:10333000019155B11B885B0707D4D0E900369B6B20 -:103340009847019AC1B23046A847012002B070BD2B -:10335000F0B5866889B005460C465EB1BDF83830D8 -:103360005B070AD4D0E900379B6B98472246C1B26D -:103370003846B047012009B0F0BD0022002301F11A -:103380000806CDE9002300230A46ADF8083003AB58 -:103390001068083252F8041C1C46B24203C423468B -:1033A000F6D1106820609288A280FFF7B1FF042355 -:1033B000ADF808302B68CDE90001DB6B6946284683 -:1033C0009847D7E7082817D909280CD00A280CD025 -:1033D0000B280CD00C280CD00D280CD00E2814BFB4 -:1033E0004020302070470C20704710207047142078 -:1033F0007047182070472020704700002DE9F041E9 -:10340000456A15B94162BDE8F0814B68AC4623F0CE -:103410006047C3F38A464FEAD37EC3F3807816EA47 -:10342000230638BF3E462B465A68BEEBD27F22F0B9 -:1034300060440AD0002A18DAA40CB44217D19D4285 -:103440000FD10D60DEE71346EEE7A74207D102F089 -:103450008044C2F3807242450BD054B1EFE708D2EA -:10346000EDE7CCF800100B60CDE7B44201D0B442D8 -:10347000E5D81A689C46002AE5D11960C3E7000028 -:103480002DE9F047089D01F0070400EBD1004FF44F -:103490007F494FEAD508224405F00705944201D13F -:1034A000BDE8F08704F0070705F0070A111B08EBD9 -:1034B000D50E57453E4613F80EC038BF5646C6F1E6 -:1034C00008068E4228BF0E46E108415C344435446C -:1034D000B94029FA06F721FA0AF1FFB28CEA010194 -:1034E00047FA0AF739408CEA010C03F80EC0D5E719 -:1034F00080EA0120082341F2210201B2013B400091 -:10350000002980B2B8BF504013F0FF03F5D17047D7 -:1035100038B50C468D18A54200D138BD14F8011BF2 -:10352000FFF7E6FFF7E7000042684AB113688189B8 -:103530004360438901339BB29942438138BF838101 -:103540001046704770B588B0044620220D46684684 -:103550000021FEF727FA20460495FFF7E5FF024613 -:1035600060B16B46054608AE1C46083503CCB44234 -:1035700045F8080C45F8041C2346F5D1104608B060 -:1035800070BD0000082817D909280CD00A280CD0D3 -:103590000B280CD00C280CD00D280CD00E2814BFF2 -:1035A0004020302070470C207047102070471420B6 -:1035B000704718207047202070470000082817D94E -:1035C0000C280CD910280CD914280CD918280CD97F -:1035D00020280CD930288CBF0F200E2070470920DE -:1035E00070470A2070470B2070470C2070470D2051 -:1035F000704700002DE9F843078C0446072F1ED9B9 -:1036000000254FF6FF73D0E90298C5F12006A5F119 -:10361000200029FA05F1083508FA06F628FA00F024 -:10362000314301431846C9B2FFF762FF402D0346FC -:10363000EBD13A46E169BDE8F843FFF769BF4FF6C1 -:10364000FF70BDE8F883000010B54B6823B9CA8A43 -:1036500063F30902CA8210BD04691A681C60036121 -:10366000C38A013BC3824A60EFE700002DE9F84FAF -:103670001D46CB8A0F468146C3F3090192460529B0 -:103680000B4630D00020AAB207F11A049EB21FFAEE -:1036900080F8042E0FD8904503F1010306D30A44A5 -:1036A000FB8A62F309030120FB821AE01AF800602A -:1036B0000130E654EAE79045F1D2A1F1050B1C2355 -:1036C0007C68BBFBF3F203FB12BB1FFA8BF6002CEA -:1036D00045D14846FFF728FF044638B978606FF0B7 -:1036E0000200BDE8F88F4FF00008E6E7002606600C -:1036F0007860ADB24FF0000B454510D90AEB0803D6 -:10370000221D13F8011B08F101089155B1B21FFAEF -:1037100088F81B292BD0454506F10106F1D8FB8A14 -:10372000C3F30902154465F30903BCE701321C46E3 -:1037300092B22368002BF9D16B1F0B441C21B3FB01 -:10374000F1F301339BB29A42D3D2BBF1000FD0D137 -:103750004846FFF7E9FE20B9C4F800B0BFE70122F0 -:10376000E7E7C0F800B05E4620600446C1E7454583 -:10377000D5D94846FFF7D8FE08B92060AFE7C0F8B2 -:1037800000B0002620600446B6E700002DE9F04FA7 -:103790001C46074688462DED028B83B05B6901927B -:1037A000002B00F09A80238C2BB1E269002A00F0F4 -:1037B0009480072B35D807F10C00FFF7B5FE0546BE -:1037C00038B96FF00205284603B0BDEC028BBDE8A6 -:1037D000F08F14220021FEF7E5F8228CE16905F153 -:1037E0000800FEF7B9F8208C48F00041013080B2A3 -:1037F000FFF7E4FEFFF7C6FE013880B220840130F7 -:10380000287438466369228C1B782A4403F01F030E -:1038100063F03F03137269602946FFF7EFFD01254E -:10382000D1E74FF0000900F10C034FF0800A4E463B -:103830004D4608EE103A18EE100AFFF775FE834663 -:103840000028BED014220021FEF7ACF8002E3AD199 -:10385000019B0222ABF808300BF1080E1FFA82FC24 -:10386000218C0CF10100BCF1060F80B201D88E4210 -:103870002BD3FFF7A3FE8E4208BF4FF0400AFFF79D -:1038800081FE62690138013512781BFA80F101303E -:1038900002F01F022DB242EA491289F001094AEAF8 -:1038A000020A48F0004281F808A059468BF810003F -:1038B0003846CBF804204FF0000AFFF79FFD238C19 -:1038C000B342B8D17FE70022C6E7E169895D0136DE -:1038D0000EF80210B6B20132C0E76FF0010572E7D0 -:1038E000F8B515460E463022002104461F46FEF765 -:1038F00059F8069BB5F5001FA760636004F110003E -:10390000079B34BF6A094FF6FF72E661A36200238A -:1039100097B29A4206D800230360A782E3822383EA -:10392000E360F8BD0660013330462036F1E7000061 -:1039300003781BB94BB2002BC8BF01707047000061 -:1039400000787047F8B50C46C969074611B9238C51 -:10395000002B37D1257E1F2D34D8387828BB228CF8 -:10396000072A2CD8268A36F003032BD14FF6FF7096 -:10397000FFF7CEFD20F0010031024FF6FF72400448 -:1039800041EA0561400C41EA402523462946384674 -:10399000FFF7FCFE002807DD626913780133DBB214 -:1039A0001F2B88BF00231370F8BD218A2D0645EA1E -:1039B000012505432046FFF71DFE0246E5E76FF0AF -:1039C0000300F1E76FF00100EEE7000070B58AB088 -:1039D000044616460021282268461D46FDF7E2FFF0 -:1039E000BDF8383069462046ADF810300F9B05937E -:1039F0009DF840308DF81830119B0793BDF8483082 -:103A0000CDE90265ADF82030FFF79CFF0AB070BD2C -:103A10002DE9F041D36905460C4616460BB9138CC7 -:103A20005BBB377E1F2F28D895F80080B8F1000FB8 -:103A300026D03046FFF7DEFD3378210202462846C5 -:103A400041EAC331338A41EA080141EA076141EAA8 -:103A50000341334641F08001FFF798FE00280ADD5C -:103A60003378012B07D1726913780133DBB21F2B36 -:103A700088BF00231370BDE8F0816FF00100FAE702 -:103A80006FF00300F7E70000F0B58BB004460D4679 -:103A900017460021282268461E46FDF783FF9DF841 -:103AA0004C30294620465A1E534253416A468DF8EF -:103AB00000309DF84030ADF81030119B05939DF813 -:103AC00048308DF81830149B0793BDF85430CDE979 -:103AD0000276ADF82030FFF79BFF0BB0F0BD000081 -:103AE000406A00B104307047436A1A684262026952 -:103AF0001A600361C38A013BC38270472DE9F0411C -:103B0000D0F8208014461D46184E4146002709B9BA -:103B1000BDE8F081D1E90223A21A65EB03039642C6 -:103B200077EB03031ED2036A8B420DD1FFF78CFDA6 -:103B3000036A1B68036203690B60C38A0161013B6E -:103B4000016AC3828846E2E7FFF77EFD0B68C8F88A -:103B5000003003690B60C38A0161013BC382D8F85E -:103B60000010D4E788460968D1E700BF80841E00B2 -:103B70002DE9F04F8BB00D4614469B46DDF8509072 -:103B80008046002800F01881B9F1000F00F0148180 -:103B9000531E3F2B00F21081012A03D1BBF1000F0D -:103BA00040F00A810023CDE90833B8F81430B5EBB2 -:103BB000C30F4FEAC30703D300200BB0BDE8F08F5B -:103BC0002B199F42D8F80C3036BF7F1B2746FFB217 -:103BD0001BB9D8F81030002B7AD0272D4DD8C5F15D -:103BE000280600232946B742009308ABD8F80800FE -:103BF0002CBFF6B23E46A7EB060A354432465FFAC2 -:103C00008AFAFFF73DFCB8F81430282103F100537D -:103C1000053BDB000493D8F80C300393039B13B1EE -:103C2000BAF1000F2CD1D8F8100040B1BAF1000F52 -:103C300005D008AB5246691A0096FFF721FC38B24E -:103C4000002FB9D066070AD00AAB624203EBD40159 -:103C500002F0070211F8083C134101F8083C082C57 -:103C60003DD9102C40F2B580202C40F2B780BBF13A -:103C7000000F00F09C80082335E0BA460026C2E71A -:103C8000049BE02B28BFE02306930B44AB42059333 -:103C900015D95A1B0398691A0096924508AB00F192 -:103CA000040034BF5246D2B20792FFF7E9FB079AED -:103CB0001644AAEB020A1544F6B25FFA8AFA049B8C -:103CC000069A05999B1A0493039B1B680393A5E727 -:103CD00000933A4608AB2946D8F80800ADE7BBF197 -:103CE000000F13D00123B4EBC30F6BD0082C12D8F4 -:103CF0009DF82030621E23FA02F2D50706D54FF058 -:103D0000FF3202FA04F423438DF820309DF820306E -:103D100089F8003051E7102C12D8BDF82030621E0F -:103D200023FA02F2D10706D54FF0FF3202FA04F46B -:103D30002343ADF82030BDF82030A9F800303CE72F -:103D4000202C0FD80899631E21FA03F3DA0705D552 -:103D50004FF0FF3202FA04F40C430894089BC9F8B0 -:103D600000302AE7402C2AD0611EC4F12102A4F1C0 -:103D70002103DDE9086526FA01F105FA02F225FAC8 -:103D800003F311431943CB0711D50122A4F12003FA -:103D9000C4F1200102FA03F322FA01F1A2400B431D -:103DA000524263EB430332432B43CDE90823DDE961 -:103DB0000823C9E9002300E76FF00100FDE66FF07A -:103DC0000800FAE6082CA1D9102CB4D9202CEED882 -:103DD000C4E7BBF1000FAED0022384E7BBF1000FB4 -:103DE000BCD004237FE70000012A30B5144638BF59 -:103DF000012485B00025402C28BF4024012ACDE9AC -:103E0000025518D81B788DF8083063070AD004AB28 -:103E1000624203EBD40502F0070215F8083C934018 -:103E200005F8083C034600912246002102A8FFF74E -:103E300027FB05B030BD082AE4D9102A03D81B8817 -:103E4000ADF80830E1E7202A95BF1B68D3E90023CD -:103E50000293CDE90223D8E710B5CB681BB98B607C -:103E60000B618B8210BD04691A681C600361C38AF0 -:103E7000013BC382CA60F0E703064CBFC0F3C03009 -:103E80000220704708B50246FFF7F6FF022806D168 -:103E90005306C2F30F2001D100F0030008BDC2F3A6 -:103EA0000740FBE72DE9F04F93B004460D46CDE9FE -:103EB00003230A681046FFF7DFFF0228824614BF7B -:103EC000C2F306260026002A80F2F38112F0C049D0 -:103ED00040F0EF81097B002900F0EB81022803D03C -:103EE0002378B34240F0E881C2F3046310462944CA -:103EF000069302F07F030593FFF7C4FF059B0022A2 -:103F000083464FEA8348002348EA0A4848EA46685D -:103F1000CE78CDE90823F30948EA0008029368D077 -:103F2000059B024608A92046009353466768B84798 -:103F3000002800F0C481276A4FB9414604F10C0003 -:103F4000FFF700FB074690B96FF0020055E03B69B0 -:103F500098450DD03F68002FF9D1414604F10C007F -:103F6000FFF7F0FA07460028EED0236A3B6027628D -:103F700097F817C006F01F08CCF3840CACEB0800D0 -:103F8000A8EB0C031FFA80FE0028B8BF0EF120003A -:103F90001FFA83FEB8BF00B2002B0793B8BF0EF123 -:103FA0002003D7E90221BCBF1BB2079352EA0103E9 -:103FB00038D0039B4FF0000CDFF820E39A1A049BE3 -:103FC00063EB010196457CEB01032BD36B7B97F8E8 -:103FD0001AE0734519D1029B002B78D0012821DC0F -:103FE0007868F8B9DFF8F0C2944570EB010316D396 -:103FF00037E0276A27B96FF00C0013B0BDE8F08FE7 -:104000003B699845B4D03F68F4E7B34890427CEBF5 -:10401000010301D30020F0E7029B002BFAD0079B9D -:104020000F2B17DCFA7DB3003946204602F003025D -:1040300003F07C031343FB75FFF706FB6B7BBB763A -:10404000029B3BB9FB7DC3F38402013262F386031A -:10405000FB75D0E76A7BBB7E9A42DBD1029B002BCB -:1040600035D0B309022B32D0039B142200210DA8B6 -:10407000BB60049BFB60FDF795FC039B0AA92046EF -:104080000A93049BADF83EB00B932B1D8DF840A016 -:104090000C932B7B8DF84180013BDBB2ADF83C30BB -:1040A000069B8DF84230059B8DF8433094F82C30F8 -:1040B00083F001038DF84430A3689847FB7DC3F378 -:1040C0008403013303F01F039B02FB82A2E7FB7D05 -:1040D000C6F34012B2EBD31F40F0F480C3F3840365 -:1040E000434540F0F280029AB6092B7B002A4DD05E -:1040F000F2075DD4032B40F2EB80039BAE1D3946E3 -:1041000004F10C00BB603246049BFB602B7B033B3D -:10411000DBB2FFF7ABFA00280CDA39462046FFF78E -:1041200093FAFB7DC3F38403013303F01F039B0267 -:10413000FB8209E7AB88DDE908843B834FF6FF7318 -:10414000C9F12000A9F1200228FA09F109F10809B2 -:1041500004FA00F024FA02F2014318461143C9B2EE -:10416000FFF7C6F9B9F1400F0346E9D1B8823146ED -:104170002A7B033AD2B2FFF7CBF9FB7DB882DA4350 -:10418000C2F3C01262F3C713FB7543E786B92E1D55 -:10419000013B394604F10C00DBB23246FFF766FA08 -:1041A0000028BADB2A7B3146B88A013AD2B2E2E76C -:1041B000F98A013BC1F30901DAB204295BD8281D51 -:1041C000002307F11B069A4208D910F801CB0133EE -:1041D00006F801C00131DBB20529F4D103999342FD -:1041E0000A9138BF043304992CBF002355FA83F396 -:1041F0000B9107F11B010C9179680E930D91291D0C -:10420000FB8AADF83EB0C3F309038DF840A08DF8EA -:1042100041801A44069B8DF84230059BADF83C2046 -:104220008DF8433094F82C3083F001038DF844303E -:104230000023B88A7B602A7B013AFFF769F93B8B40 -:10424000B882834203D1A3680AA920469847204632 -:104250000AA9FFF701FEFB7DBA8AC3F38403013389 -:1042600003F01F039B02FB823B8B9A420CBF002092 -:104270006FF01000C1E67B68002BAFD0052001E095 -:104280001C3033461E68002EFAD1091A2E1D081D57 -:10429000184401EB090C5FFA89F3BCF11B0F9DD8A0 -:1042A0009A429BD916F8013B09F1010900F8013B3C -:1042B000EFE76FF00900A0E66FF00A009DE66FF0EF -:1042C0000B009AE66FF00D0097E66FF00E0094E693 -:1042D0006FF00F0091E600BF40420F0080841E0087 -:1042E000EFF30983054968334A6B22F001024A6300 -:1042F00083F30988002383F31188704700EF00E0FF -:10430000302080F3118862B60D4B0E4AD96821F433 -:10431000E0610904090C0A430B49DA60D3F8FC2078 -:1043200042F08072C3F8FC20084AC2F8B01F11683E -:1043300041F0010111602022DA7783F822007047F2 -:1043400000ED00E00003FA0555CEACC5001000E01A -:10435000302310B583F311880E4B5B6813F40063B0 -:1043600014D0F1EE103AEFF309844FF08073683CFB -:10437000E361094BDB6B236684F3098801F0D8F90C -:1043800010B1064BA36110BD054BFBE783F3118809 -:10439000F9E700BF00ED00E000EF00E03F04000897 -:1043A0004204000808B5074B074A196801F03D01AF -:1043B000996053680BB190689847BDE80840FFF7D3 -:1043C000C7BF00BF00000240904F002008B5084B57 -:1043D0001968890901F03D018A019A60054AD3688C -:1043E0000BB110699847BDE80840FFF7B1BF00BFA7 -:1043F00000000240904F002008B5084B1968090CD6 -:1044000001F03D010A049A60054A53690BB19069B5 -:104410009847BDE80840FFF79BBF00BF000002407F -:10442000904F002008B5084B1968890D01F03D0137 -:104430008A059A60054AD3690BB1106A9847BDE8AE -:104440000840FFF785BF00BF00000240904F0020EA -:1044500008B5074B074A596801F03D01D960536A16 -:104460000BB1906A9847BDE80840FFF771BF00BFE5 -:1044700000000240904F002008B5084B5968890998 -:1044800001F03D018A01DA60054AD36A0BB1106B75 -:104490009847BDE80840FFF75BBF00BF000002403F -:1044A000904F002008B5084B5968090C01F03D01F8 -:1044B0000A04DA60054A536B0BB1906B9847BDE86C -:1044C0000840FFF745BF00BF00000240904F0020AA -:1044D00008B5084B5968890D01F03D018A05DA607D -:1044E000054AD36B0BB1106C9847BDE80840FFF745 -:1044F0002FBF00BF00000240904F002008B5074BBF -:10450000074A196801F03D019960536C0BB1906C3A -:104510009847BDE80840FFF71BBF00BF00040240FA -:10452000904F002008B5084B1968890901F03D013A -:104530008A019A60054AD36C0BB1106D9847BDE8AB -:104540000840FFF705BF00BF00040240904F002065 -:1045500008B5084B1968090C01F03D010A049A607E -:10456000054A536D0BB1906D9847BDE80840FFF7C1 -:10457000EFBE00BF00040240904F002008B5084B7A -:104580001968890D01F03D018A059A60054AD36DCD -:104590000BB1106E9847BDE80840FFF7D9BE00BFC9 -:1045A00000040240904F002008B5074B074A5968A5 -:1045B00001F03D01D960536E0BB1906E9847BDE894 -:1045C0000840FFF7C5BE00BF00040240904F002026 -:1045D00008B5084B5968890901F03D018A01DA6084 -:1045E000054AD36E0BB1106F9847BDE80840FFF73E -:1045F000AFBE00BF00040240904F002008B5084B3A -:104600005968090C01F03D010A04DA60054A536F4C -:104610000BB1906F9847BDE80840FFF799BE00BF07 -:1046200000040240904F002008B5084B5968890DDE -:1046300001F03D018A05DA60054AD36F13B1D2F863 -:1046400080009847BDE80840FFF782BE00040240A2 -:10465000904F002000230C4910B51A460B4C0B60FC -:1046600054F82300026001EB430004334260402B06 -:10467000F6D1074A4FF0FF339360D360C2F8083495 -:10468000C2F80C3410BD00BF904F0020107B000812 -:10469000000002400F28F8B510D9102810D01128BA -:1046A00011D0122808D10F240720DFF8B4E001262A -:1046B000DEF80050A04208D9002649E00446F4E79D -:1046C0000F240020F1E70724FBE706FA00F73D423C -:1046D00040D1214C4FEA001C3D4304EB00160EEB89 -:1046E000C000CEF80050C0E90123FBB24BB11B481B -:1046F000836B43F001038363036E43F0010303669E -:10470000036E17F47F4F09D01448836B43F0020304 -:104710008363036E43F002030366036E54F80C00D8 -:10472000036823F01F030360056815F00105FBD142 -:1047300004EB0C033D2493F80CC05F6804FA0CF4FE -:104740003C6021240560446112B1987B00F056F969 -:104750003046F8BD0130ADE7107B00080045025837 -:10476000904F002010B5302484F31188FFF792FF9A -:10477000002383F3118810BD10B50446807B00F040 -:1047800053F901231049627B03FA02F20B6823EA12 -:104790000203DAB20B604AB90C4A916B21F00101B5 -:1047A0009163116E21F001011166126E13F47F4FB7 -:1047B00009D1064B9A6B22F002029A631A6E22F01C -:1047C00002021A661B6E10BD904F00200045025871 -:1047D00008B5302383F31188FFF7CEFF002383F35E -:1047E000118808BD026843681143016003B118478E -:1047F00070470000024A136843F0C003136070471B -:104800000078004013B50E4C204600F0B7FA04F1D2 -:10481000140000234FF400720A49009400F074F968 -:10482000094B4FF40072094904F13800009400F07C -:10483000EDF9074A074BC4E9172302B010BD00BFCA -:104840001450002080500020F547000880520020BE -:104850000078004000E1F505037C30B5214C0029CB -:1048600018BF0C46012B0CD11F4B984209D11F4B8E -:104870009A6C42F080429A641A6F42F080421A6742 -:104880001B6F2268036EC16D03EB52038466B3FB9A -:10489000F2F36268150442BF23F0070503F0070333 -:1048A00043EA4503CB60A36843F040034B60E368F1 -:1048B00043F001038B6042F4967343F001030B60F5 -:1048C0004FF0FF330B62510505D512F0102205D0D1 -:1048D000B2F1805F04D080F8643030BD7F23FAE706 -:1048E0003F23F8E7107C00081450002000450258D0 -:1048F0002DE9F047C66D05463768F4692107346233 -:104900001AD014F0080118BF4FF48071E20748BFB5 -:1049100041F02001A3074FF0300348BF41F04001B0 -:10492000600748BF41F0800183F31188281DFFF71D -:1049300059FF002383F31188E2050AD5302383F35E -:1049400011884FF48061281DFFF74CFF002383F38B -:1049500011884FF030094FF0000A14F0200838D1C8 -:104960003B0616D54FF0300905F1380A200610D560 -:1049700089F31188504600F07DF9002836DA0821C5 -:10498000281DFFF72FFF27F080033360002383F3F8 -:104990001188790614D5620612D5302383F3118865 -:1049A000D5E913239A4208D12B6C33B127F0400785 -:1049B0001021281DFFF716FF3760002383F31188AD -:1049C000E30618D5AA6E1369ABB15069BDE8F0478C -:1049D000184789F31188736A284695F864101940BE -:1049E00000F0E6F98AF31188F469B6E7B06288F35B -:1049F0001188F469BAE7BDE8F0870000090100F109 -:104A00006043012203F56143C9B283F8001300F04B -:104A10001F039A4043099B0003F1604303F5614380 -:104A2000C3F880211A60704700F01F0301229A40EA -:104A3000430900F160409B0000F5614003F16043D1 -:104A400003F56143C3F88020C3F88021002380F878 -:104A500000337047F8B51546826804460B46AA42F3 -:104A600000D28568A1692669761AB5420BD218462C -:104A70002A46FCF771FFA3692B44A3612846A3686B -:104A80005B1BA360F8BD0CD9AF1B18463246FCF780 -:104A900063FF3A46E1683044FCF75EFFE3683B445D -:104AA000EBE718462A46FCF757FFE368E5E7000006 -:104AB00083689342F7B50446154600D28568D4E969 -:104AC0000460361AB5420BD22A46FCF745FF6369EB -:104AD0002B4463612846A3685B1BA36003B0F0BD51 -:104AE0000DD93246AF1B0191FCF736FF01993A46CA -:104AF000E0683144FCF730FFE3683B44E9E72A46CD -:104B0000FCF72AFFE368E4E710B50A440024C36118 -:104B1000029B8460C16002610362C0E90000C0E9D9 -:104B2000051110BD08B5D0E90532934201D1826864 -:104B300082B98268013282605A1C42611970002178 -:104B4000D0E904329A4224BFC368436100F09CFE5E -:104B5000002008BD4FF0FF30FBE7000070B53023A8 -:104B600004460E4683F31188A568A5B1A368A2691F -:104B7000013BA360531CA36115782269934224BFB3 -:104B8000E368A361E3690BB120469847002383F3F0 -:104B90001188284607E03146204600F065FE0028CF -:104BA000E2DA85F3118870BD2DE9F74F04460E4611 -:104BB00017469846D0F81C904FF0300A8AF31188B7 -:104BC0004FF0000B154665B12A4631462046FFF7E7 -:104BD00041FF034660B94146204600F045FE0028EB -:104BE000F1D0002383F31188781B03B0BDE8F08F68 -:104BF000B9F1000F03D001902046C847019B8BF309 -:104C00001188ED1A1E448AF31188DCE7C160C36184 -:104C1000009B82600362C0E905111144C0E90000F5 -:104C200001617047F8B504460D461646302383F3FC -:104C30001188A768A7B1A368013BA36063695A1CE8 -:104C400062611D70D4E904329A4224BFE368636153 -:104C5000E3690BB120469847002080F3118807E0F4 -:104C60003146204600F000FE0028E2DA87F3118882 -:104C7000F8BD0000D0E9052310B59A4201D1826841 -:104C80007AB982680021013282605A1C82611C78E4 -:104C900003699A4224BFC368836100F0F5FD204692 -:104CA00010BD4FF0FF30FBE72DE9F74F04460E46ED -:104CB00017469846D0F81C904FF0300A8AF31188B6 -:104CC0004FF0000B154665B12A4631462046FFF7E6 -:104CD000EFFE034660B94146204600F0C5FD0028BE -:104CE000F1D0002383F31188781B03B0BDE8F08F67 -:104CF000B9F1000F03D001902046C847019B8BF308 -:104D00001188ED1A1E448AF31188DCE702684368B3 -:104D10001143016003B11847704700001430FFF7DA -:104D200043BF00004FF0FF331430FFF73DBF0000DA -:104D30003830FFF7B9BF00004FF0FF333830FFF7CE -:104D4000B3BF00001430FFF709BF00004FF0FF3180 -:104D50001430FFF703BF00003830FFF763BF0000D7 -:104D60004FF0FF323830FFF75DBF0000012914BF5C -:104D70006FF0130000207047FFF744BD044B036041 -:104D800000234360C0E9023301230374704700BF6E -:104D9000287C000810B53023044683F31188FFF700 -:104DA0005BFD02230020237480F3118810BD0000F6 -:104DB00038B5C36904460D461BB904210844FFF702 -:104DC000A5FF294604F11400FFF7ACFE002806DA1F -:104DD000201D4FF40061BDE83840FFF797BF38BD94 -:104DE000026843681143016003B11847704700002F -:104DF00013B5406B00F58054D4F8A4381A681178C4 -:104E0000042914D1017C022911D1197901231289B5 -:104E10008B4013420BD101A94C3002F0E9F8D4F8D1 -:104E2000A4480246019B2179206800F0DFF902B016 -:104E300010BD0000143002F06BB800004FF0FF33DB -:104E4000143002F065B800004C3002F03DB90000AB -:104E50004FF0FF334C3002F037B90000143002F04D -:104E600039B800004FF0FF31143002F033B80000C1 -:104E70004C3002F009B900004FF0FF324C3002F024 -:104E800003B900000020704710B500F58054D4F835 -:104E9000A4381A681178042917D1017C022914D189 -:104EA0005979012352898B4013420ED1143001F0FD -:104EB000CBFF024648B1D4F8A4484FF4407361795F -:104EC0002068BDE8104000F07FB910BD406BFFF7CF -:104ED000DBBF0000704700007FB5124B01250426A0 -:104EE000044603600023057400F1840243602946F0 -:104EF000C0E902330C4B0290143001934FF440731D -:104F0000009601F07DFF094B04F69442294604F116 -:104F10004C000294CDE900634FF4407302F044F872 -:104F200004B070BD507C0008CD4E0008F14D000863 -:104F30000A68302383F311880B790B3342F823007E -:104F40004B79133342F823008B7913B10B3342F8BA -:104F5000230000F58053C3F8A41802230374002033 -:104F600080F311887047000038B5037F044613B101 -:104F700090F85430ABB90125201D0221FFF730FF16 -:104F800004F114006FF00101257700F089FC04F1B1 -:104F90004C0084F854506FF00101BDE8384000F037 -:104FA0007FBC38BD10B5012104460430FFF718FF5F -:104FB0000023237784F8543010BD000038B5044630 -:104FC0000025143001F034FF04F14C00257702F085 -:104FD00003F8201D84F854500121FFF701FF2046FB -:104FE000BDE83840FFF750BF90F8803003F0600311 -:104FF000202B06D190F881200023212A03D81F2AD4 -:1050000006D800207047222AFBD1C0E91D3303E0F7 -:10501000034A426707228267C3670120704700BFC7 -:105020003C23002037B500F58055D5F8A4381A6820 -:10503000117804291AD1017C022917D11979012389 -:1050400012898B40134211D100F14C04204602F02A -:1050500083F858B101A9204601F0CAFFD5F8A44849 -:105060000246019B2179206800F0C0F803B030BDF2 -:1050700001F10B03F0B550F8236085B004460D46EE -:10508000FEB1302383F3118804EB8507301D08211E -:10509000FFF7A6FEFB6806F14C005B691B681BB1BD -:1050A000019001F0B3FF019803A901F0A1FF0246AE -:1050B00048B1039B2946204600F098F8002383F36B -:1050C000118805B0F0BDFB685A691268002AF5D056 -:1050D0001B8A013B1340F1D104F18002EAE7000092 -:1050E000133138B550F82140ECB1302383F31188E7 -:1050F00004F58053D3F8A4281368527903EB820394 -:10510000DB689B695D6845B104216018FFF768FEA4 -:10511000294604F1140001F0A1FE2046FFF7B4FE79 -:10512000002383F3118838BD7047000001F074B983 -:1051300001234022002110B5044600F8303BFCF763 -:1051400031FC0023C4E9013310BD000010B5302349 -:10515000044683F311882422416000210C30FCF7BF -:1051600021FC204601F07AF902230020237080F30D -:10517000118810BD70B500EB8103054650690E46DD -:105180001446DA6018B110220021FCF70BFCA0696C -:1051900018B110220021FCF705FC31462846BDE875 -:1051A000704001F05BBA000083682022002103F008 -:1051B000011310B5044683601030FCF7F3FB204662 -:1051C000BDE8104001F0D6BAF0B4012500EB81042F -:1051D00047898D40E4683D43A469458123600023ED -:1051E000A2606360F0BC01F0F3BA0000F0B40125E6 -:1051F00000EB810407898D40E4683D4364690581C3 -:1052000023600023A2606360F0BC01F069BB000072 -:1052100070B5022300250446242203702946C0F8F5 -:1052200088500C3040F8045CFCF7BCFB204684F846 -:10523000705001F0A7F963681B6823B12946204626 -:10524000BDE87040184770BD0378052B10B50446C3 -:105250000AD080F88C300523037043681B680BB1BB -:10526000042198470023A36010BD000001780529A0 -:1052700006D190F88C20436802701B6803B1184770 -:105280007047000070B590F87030044613B10023E9 -:1052900080F8703004F18002204601F08FFA6368D4 -:1052A0009B68B3B994F8803013F0600535D00021C5 -:1052B000204601F081FD0021204601F071FD636868 -:1052C0001B6813B1062120469847062384F87030E6 -:1052D00070BD204698470028E4D0B4F88630A26F0D -:1052E0009A4288BFA36794F98030A56F002B4FF0D6 -:1052F000300380F20381002D00F0F280092284F84F -:10530000702083F3118800212046D4E91D23FFF784 -:105310006DFF002383F31188DAE794F8812003F00E -:105320007F0343EA022340F20232934200F0C58039 -:1053300021D8B3F5807F48D00DD8012B3FD0022B68 -:1053400000F09380002BB2D104F188026267022240 -:10535000A267E367C1E7B3F5817F00F09B80B3F5F7 -:10536000407FA4D194F88230012BA0D1B4F88830CA -:1053700043F0020332E0B3F5006F4DD017D8B3F518 -:10538000A06F31D0A3F5C063012B90D8636820468D -:1053900094F882205E6894F88310B4F88430B047A3 -:1053A000002884D0436863670368A3671AE0B3F5F5 -:1053B000106F36D040F6024293427FF478AF5C4BD8 -:1053C00063670223A3670023C3E794F88230012BAD -:1053D0007FF46DAFB4F8883023F00203A4F888306E -:1053E000C4E91D55E56778E7B4F88030B3F5A06FE0 -:1053F0000ED194F88230204684F88A3001F020F9EA -:1054000063681B6813B1012120469847032323706A -:105410000023C4E91D339CE704F18B036367012378 -:10542000C3E72378042B10D1302383F3118820465F -:10543000FFF7BAFE85F311880321636884F88B5067 -:1054400021701B680BB12046984794F88230002BDE -:10545000DED084F88B300423237063681B68002B34 -:10546000D6D0022120469847D2E794F884302046CF -:105470001D0603F00F010AD501F092F9012804D0AE -:1054800002287FF414AF2B4B9AE72B4B98E701F0DF -:1054900079F9F3E794F88230002B7FF408AF94F8A1 -:1054A000843013F00F01B3D01A06204602D501F064 -:1054B0009BFCADE701F08CFCAAE794F88230002B4E -:1054C0007FF4F5AE94F8843013F00F01A0D01B06E2 -:1054D000204602D501F070FC9AE701F061FC97E7E5 -:1054E000142284F8702083F311882B462A4629461B -:1054F0002046FFF769FE85F31188E9E65DB11522C4 -:1055000084F8702083F3118800212046D4E91D23FC -:10551000FFF75AFEFDE60B2284F8702083F3118812 -:105520002B462A4629462046FFF760FEE3E700BFE8 -:10553000807C0008787C00087C7C000838B590F8F6 -:1055400070300446002B3ED0063BDAB20F2A34D826 -:105550000F2B32D8DFE803F03731310822323131F6 -:105560003131313131313737856FB0F886309D4276 -:1055700014D2C3681B8AB5FBF3F203FB12556DB955 -:10558000302383F311882B462A462946FFF72EFE47 -:1055900085F311880A2384F870300EE0142384F810 -:1055A0007030302383F31188002320461A461946B1 -:1055B000FFF70AFE002383F3118838BDC36F03B1E0 -:1055C00098470023E7E70021204601F0F5FB002182 -:1055D000204601F0E5FB63681B6813B106212046F5 -:1055E00098470623D7E7000010B590F870300446BE -:1055F000142B29D017D8062B05D001D81BB110BD0C -:10560000093B022BFBD80021204601F0D5FB0021ED -:10561000204601F0C5FB63681B6813B106212046D4 -:105620009847062319E0152BE9D10B2380F8703039 -:10563000302383F3118800231A461946FFF7D6FD5D -:10564000002383F31188DAE7C3689B695B68002B4A -:10565000D5D1C36F03B19847002384F87030CEE7EB -:1056600000238268037503691B6899689142FBD225 -:105670005A68036042601060586070470023826877 -:10568000037503691B6899689142FBD85A680360E7 -:10569000426010605860704708B50846302383F3B5 -:1056A00011880B7D032B05D0042B0DD02BB983F370 -:1056B000118808BD8B6900221A604FF0FF338361A7 -:1056C000FFF7CEFF0023F2E7D1E9003213605A6002 -:1056D000F3E70000FFF7C4BF054BD96808751868E9 -:1056E000026853601A600122D8600275FAF792BE10 -:1056F000805400200C4B30B5DD684B1C87B004464D -:105700000FD02B46094A684600F05EF92046FFF7A5 -:10571000E3FF009B13B1684600F060F9A86907B089 -:1057200030BDFFF7D9FFF9E78054002099560008F3 -:10573000044B1A68DB6890689B68984294BF00200D -:105740000120704780540020084B10B51C68D868B1 -:10575000226853601A600122DC602275FFF78EFF19 -:1057600001462046BDE81040FAF754BE80540020A0 -:1057700038B5074C012300250649074823706560AA -:1057800001F028FD0223237085F3118838BD00BF86 -:10579000E8560020887C00088054002008B572B6C6 -:1057A000044B186500F060FC00F026FD024B03225C -:1057B0001A70FEE780540020E856002000F044B93B -:1057C000034A516853685B1A9842FBD8704700BF80 -:1057D000001000E08B600223086108468B8270474E -:1057E0008368A3F1840243F8142C026943F8442C23 -:1057F000426943F8402C094A43F8242CC268A3F1BB -:10580000200043F8182C022203F80C2C002203F885 -:105810000B2C034A43F8102C704700BF2D040008DE -:105820008054002008B5FFF7DBFFBDE80840FFF714 -:1058300051BF0000024BDB6898610F20FFF74CBF9F -:1058400080540020302383F31188FFF7F3BF00005A -:1058500008B50146302383F311880820FFF74AFF7B -:10586000002383F3118808BD064BDB6839B1426819 -:1058700018605A60136043600420FFF73BBF4FF08D -:10588000FF307047805400200368984206D01A68A1 -:105890000260506018469961FFF71CBF7047000016 -:1058A00038B504460D462068844200D138BD0368EF -:1058B00023605C608561FFF70DFFF4E7036810B5B6 -:1058C0009C68A2420CD85C688A600B604C602160C6 -:1058D000596099688A1A9A604FF0FF33836010BD4F -:1058E000121B1B68ECE700000A2938BF0A2170B5BB -:1058F00004460D460A26601901F064FC01F04CFCD8 -:10590000041BA54203D8751C04462E46F3E70A2E55 -:1059100004D90120BDE8704001F09CBC70BD0000BE -:10592000F8B5144B0D460A2A4FF00A07D96103F166 -:105930001001826038BF0A22416019691446016073 -:1059400048601861A81801F02DFC01F025FC431BEC -:105950000646A34206D37C1C28192746354601F08B -:1059600031FCF2E70A2F04D90120BDE8F84001F02C -:1059700071BCF8BD80540020F8B506460D4601F014 -:105980000BFC0F4A134653F8107F9F4206D12A465C -:1059900001463046BDE8F840FFF7C2BFD169BB6899 -:1059A000441A2C1928BF2C46A34202D92946FFF7D6 -:1059B0009BFF224631460348BDE8F840FFF77EBF13 -:1059C0008054002090540020C0E90323002310B429 -:1059D0005DF8044B4361FFF7CFBF000010B5194CD1 -:1059E000236998420DD08168D0E9003213605A6073 -:1059F0009A680A449A60002303604FF0FF33A36162 -:105A000010BD0268234643F8102F53600022026045 -:105A100022699A4203D1BDE8104001F0CDBB9368E2 -:105A200081680B44936001F0B7FB2269E1699268D9 -:105A3000441AA242E4D91144BDE81040091AFFF704 -:105A400053BF00BF805400202DE9F047DFF8BC8031 -:105A500008F110072C4ED8F8105001F09DFBD8F833 -:105A60001C40AA68031B9A423ED814444FF0000918 -:105A7000D5E90032C8F81C4013605A60C5F80090A0 -:105A8000D8F81030B34201D101F096FB89F31188A8 -:105A9000D5E9033128469847302383F311886B6991 -:105AA000002BD8D001F078FB6A69A0EB040982468C -:105AB0004A450DD2022001F0CDFB0022D8F810306B -:105AC000B34208D151462846BDE8F047FFF728BF4A -:105AD000121A2244F2E712EB09092946384638BF68 -:105AE0004A46FFF7EBFEB5E7D8F81030B34208D0CE -:105AF0001444C8F81C00211AA960BDE8F047FFF75C -:105B0000F3BEBDE8F08700BF905400208054002011 -:105B100038B501F041FB054AD2E90845031B1819C5 -:105B200045F10001C2E9080138BD00BF80540020E2 -:105B300000207047FEE70000704700004FF0FF3084 -:105B40007047000002290CD0032904D0012907481E -:105B500018BF00207047032A05D8054800EBC20093 -:105B60007047044870470020704700BF607D000800 -:105B70004C230020147D000870B59AB005460846F5 -:105B8000144601A900F0C2F801A8FBF703FF431C6B -:105B90000022C6B25B001046C5E90034237003231F -:105BA000023404F8013C01ABD1B202348E4201D878 -:105BB0001AB070BD13F8011B013204F8010C04F88F -:105BC000021CF1E708B5302383F311880348FFF77F -:105BD00029FA002383F3118808BD00BFF056002086 -:105BE00090F8803003F01F02012A07D190F881203D -:105BF0000B2A03D10023C0E91D3315E003F0600335 -:105C0000202B08D1B0F884302BB990F88120212ABC -:105C100003D81F2A04D8FFF7E7B9222AEBD0FAE706 -:105C2000034A426707228267C3670120704700BFAB -:105C30004323002007B5052917D8DFE801F019161E -:105C400003191920302383F31188104A0121019090 -:105C5000FFF790FA019802210D4AFFF78BFA0D48E1 -:105C6000FFF7ACF9002383F3118803B05DF804FB60 -:105C7000302383F311880748FFF776F9F2E73023E2 -:105C800083F311880348FFF78DF9EBE7B47C000834 -:105C9000D87C0008F056002038B50C4D0C4C2A4634 -:105CA0000C4904F10800FFF767FF05F1CA0204F18F -:105CB00010000949FFF760FF05F5CA7204F11800EA -:105CC0000649BDE83840FFF757BF00BFC86F002046 -:105CD0004C230020947C00089E7C0008A97C0008CE -:105CE00070B5044608460D46FBF754FEC6B2204682 -:105CF000013403780BB9184670BD32462946FBF7CC -:105D000035FE0028F3D10120F6E700002DE9F04729 -:105D100005460C46FBF73EFE2A49C6B22846FFF769 -:105D2000DFFF08B10936F6B227492846FFF7D8FF4A -:105D300008B11036F6B2632E0BD8DFF88880DFF892 -:105D40008890224FDFF890A02E7846B92670BDE8E3 -:105D5000F08729462046BDE8F04701F049BE252ED0 -:105D60002CD1072241462846FBF700FE60B9184BAC -:105D7000224603F1100153F8040B8B4242F8040B46 -:105D8000F9D107351034DFE7082249462846FBF7EA -:105D9000EDFD98B9A21C0F4B197802320909C95DB3 -:105DA00002F8041C13F8011B01F00F015345C95DF3 -:105DB00002F8031CF0D118340835C5E7013504F8A2 -:105DC000016BC1E7807D0008A97C0008887D000880 -:105DD0000E7A000800E8F11F0CE8F11FBFF34F8FA7 -:105DE000044B1A695107FCD1D3F810215207F8D19E -:105DF000704700BF0020005208B50D4B1B78ABB9AF -:105E0000FFF7ECFF0B4BDA68D10704D50A4A5A605A -:105E100002F188325A60D3F80C21D20706D5064A1F -:105E2000C3F8042102F18832C3F8042108BD00BF81 -:105E300026720020002000522301674508B5114B4F -:105E40001B78F3B9104B1A69510703D5DA6842F091 -:105E50004002DA60D3F81021520705D5D3F80C219F -:105E600042F04002C3F80C21FFF7B8FF064BDA6896 -:105E700042F00102DA60D3F80C2142F00102C3F8CB -:105E80000C2108BD26720020002000520F289ABF66 -:105E900000F5806040040020704700004FF400309F -:105EA00070470000102070470F2808B50BD8FFF787 -:105EB000EDFF00F500330268013204D10430834263 -:105EC000F9D1012008BD0020FCE700000F2838B5FB -:105ED00005463FD8FFF782FF1F4CFFF78DFF4FF0BD -:105EE000FF3307286361C4F814311DD82361FFF71D -:105EF00075FF030243F02403E360E36843F080038B -:105F0000E36023695A07FCD42846FFF767FFFFF7D1 -:105F1000BDFF4FF4003100F04BF92846FFF78EFF2C -:105F2000BDE83840FFF7C0BFC4F81031FFF756FF97 -:105F3000A0F108031B0243F02403C4F80C31D4F889 -:105F40000C3143F08003C4F80C31D4F810315B07F6 -:105F5000FBD4D9E7002038BD002000522DE9F84FCE -:105F600005460C46104645EA0203DE0602D0002034 -:105F7000BDE8F88F20F01F00DFF8BCB0DFF8BCA050 -:105F8000FFF73AFF04EB0008444503D10120FFF777 -:105F900055FFEDE720222946204601F0F7FC10B915 -:105FA00020352034F0E72B4605F120021F68791CCC -:105FB000DDD104339A42F9D105F178431B481C4ED8 -:105FC000B3F5801F1B4B38BF184603F1F80332BFEF -:105FD000D946D1461E46FFF701FF0760A5EB040C2A -:105FE000336804F11C0143F002033360231FD9F826 -:105FF000007017F00507FAD153F8042F8B424CF8C4 -:106000000320F4D1BFF34F8FFFF7E8FE4FF0FF33CB -:106010002022214603602846336823F002033360C0 -:1060200001F0B4FC0028BBD03846B0E71421005280 -:106030000C20005214200052102000521021005257 -:1060400010B5084C237828B11BB9FFF7D5FE012302 -:10605000237010BD002BFCD02070BDE81040FFF76E -:10606000EDBE00BF2672002038B5054D0024033474 -:10607000696855F80C0B00F0ADF8122CF7D138BD5B -:106080009C7D0008084601F079BC000038B5EFF3AC -:1060900011859DB9EFF30584C4F30804302334B1AE -:1060A00083F31188FFF734FD85F3118838BD83F33E -:1060B0001188FFF72DFD84F3118838BDBDE8384005 -:1060C000FFF726BD10B5FFF7E1FF104CC008104ADE -:1060D000002340EA4170C908A0FB04ECA0FB020EBB -:1060E0001CEB0000A1FB044CA1FB02125B41001958 -:1060F00043EB0C0011EB0E0142F10002411842F19A -:106100000000090941EA007010BD00BFCFF753E35A -:10611000A59BC4200244074BD2B210B5904200D1D7 -:1061200010BD441C00B253F8200041F8040BE0B24B -:10613000F4E700BF504000580E4B30B51C6F2404EC -:1061400005D41C6F1C671C6F44F400441C670A4C88 -:1061500002442368D2B243F480732360074B904219 -:1061600000D130BD441C51F8045B00B243F820500C -:10617000E0B2F4E70044025800480258504000588A -:1061800007B5012201A90020FFF7C4FF019803B061 -:106190005DF804FB13B50446FFF7F2FFA04205D0FB -:1061A000012201A900200194FFF7C6FF02B010BD33 -:1061B0000144BFF34F8F064B884204D3BFF34F8F88 -:1061C000BFF36F8F7047C3F85C022030F4E700BF65 -:1061D00000ED00E00144BFF34F8F064B884204D32B -:1061E000BFF34F8FBFF36F8F7047C3F8700220303B -:1061F000F4E700BF00ED00E070470000074B45F2F8 -:1062000055521A6002225A6040F6FF729A604CF6AC -:10621000CC421A600122024B1A70704700480058A5 -:106220002C720020034B1B781BB1034B4AF6AA22A9 -:106230001A6070472C72002000480058034B1A68FF -:106240001AB9034AD2F8D0241A6070472872002085 -:1062500000400258024B4FF48032C3F8D0247047FC -:106260000040025808B5FFF7E9FF024B1868C0F379 -:10627000806008BD2872002070B5BFF34F8FBFF358 -:106280006F8F1A4A0021C2F85012BFF34F8FBFF32D -:106290006F8F536943F400335361BFF34F8FBFF3E4 -:1062A0006F8FC2F88410BFF34F8FD2F8803043F65F -:1062B000E074C3F3C900C3F34E335B0103EA040681 -:1062C000014646EA81750139C2F86052F9D2203B95 -:1062D00013F1200FF2D1BFF34F8F536943F4803392 -:1062E0005361BFF34F8FBFF36F8F70BD00ED00E0C0 -:1062F000FEE70000214B2248224A70B5904237D376 -:10630000214BC11EDA1C121A22F003028B4238BF45 -:1063100000220021FBF746FB1C4A0023C2F8843010 -:10632000BFF34F8FD2F8803043F6E074C3F3C90057 -:10633000C3F34E335B0103EA0406014646EA817566 -:106340000139C2F86C52F9D2203B13F1200FF2D17F -:10635000BFF34F8FBFF36F8FBFF34F8FBFF36F8FBD -:106360000023C2F85032BFF34F8FBFF36F8F70BD61 -:1063700053F8041B40F8041BC0E700BF308000083E -:1063800000740020007400200074002000ED00E084 -:10639000054B996B21EA000199631A6E22EA00020B -:1063A0001A661B6E704700BF0045025870B5D0E9F1 -:1063B000244300224FF0FF359E6804EB4213510145 -:1063C000D3F80009002805DAD3F8000940F080402E -:1063D000C3F80009D3F8000B002805DAD3F8000B46 -:1063E00040F08040C3F8000B013263189642C3F8B6 -:1063F0000859C3F8085BE0D24FF00113C4F81C3809 -:1064000070BD0000890141F02001016103699B0614 -:10641000FCD41220FFF7D4B910B50A4C2046FEF781 -:1064200087FE094BC4F89030084BC4F89430084CF0 -:106430002046FEF77DFE074BC4F89030064BC4F8AB -:10644000943010BD3072002000000840087E000823 -:10645000CC72002000000440147E000870B5037860 -:106460000546012B58D13F4BD0F89040984254D16B -:106470003D4B0E2165209A6B42F000629A631A6EC2 -:1064800042F000621A661B6E384BD3F8802042F04F -:106490000062C3F88020D3F8802022F00062C3F8A5 -:1064A0008020D3F88030FEF7A9FA314BE360314BFE -:1064B000C4F800380023D5F89060C4F8003EC0232B -:1064C00023604FF40413A3633369002BFCDA012328 -:1064D0000C203361FFF774F93369DB07FCD4122019 -:1064E000FFF76EF93369002BFCDA00262846A66018 -:1064F000FFF75CFF6B68C4F81068DB68C4F81468C9 -:10650000C4F81C6863BB1C4BA3614FF0FF3363618D -:10651000A36843F00103A36070BD184B9842C9D132 -:10652000114B4FF080609A6B42F000729A631A6EC2 -:1065300042F000721A661B6E0C4BD3F8802042F0BA -:106540000072C3F88020D3F8802022F00072C3F8D4 -:106550008020D3F88030FFF71BFF0E214D20A2E7EB -:10656000074BD1E730720020004502580044025822 -:106570004014004003002002003C30C0CC720020D8 -:10658000083C30C0F8B5D0F89040054600214FF0E7 -:1065900000662046FFF736FFD5F8941000234FF031 -:1065A00001128F684FF0FF30C4F83438C4F81C284B -:1065B00004EB431201339F42C2F80069C2F8006B3A -:1065C000C2F80809C2F8080BF2D20B68D5F890207F -:1065D000C5F89830636210231361166916F010062F -:1065E000FBD11220FFF7ECF8D4F8003823F4FE6357 -:1065F000C4F80038A36943F4402343F01003A361B7 -:106600000923C4F81038C4F814380B4BEB604FF072 -:10661000C043C4F8103B094BC4F8003BC4F81069F0 -:10662000C4F80039D5F8983003F1100243F4801310 -:10663000C5F89820A362F8BDE47D000840800010F2 -:10664000D0F8902090F88A10D2F8003823F4FE6336 -:1066500043EA0113C2F80038704700002DE9F843FF -:1066600000EB8103D0F890500C468046DA680FFAB0 -:1066700081F94801166806F00306731E022B05EB2C -:1066800041134FF0000194BFB604384EC3F8101BFD -:106690004FF0010104F1100398BF06F1805601FA92 -:1066A00003F3916998BF06F5004600293AD0578A4E -:1066B00004F15801374349016F50D5F81C180B43BA -:1066C0000021C5F81C382B180127C3F81019A74062 -:1066D0005369611E9BB3138A928B9B08012A88BF62 -:1066E0005343D8F89820981842EA034301F1400236 -:1066F0002146C8F89800284605EB82025360FFF750 -:1067000081FE08EB8900C3681B8A43EA845348343E -:106710001E4364012E51D5F81C381F43C5F81C7860 -:10672000BDE8F88305EB4917D7F8001B21F40041B9 -:10673000C7F8001BD5F81C1821EA0303C0E704F1D1 -:106740003F030B4A2846214605EB83035A60FFF7B7 -:1067500059FE05EB4910D0F8003923F40043C0F886 -:106760000039D5F81C3823EA0707D7E70080001066 -:1067700000040002D0F894201268C0F89820FFF7B7 -:1067800015BE00005831D0F8903049015B5813F421 -:10679000004004D013F4001F0CBF022001207047FA -:1067A0004831D0F8903049015B5813F4004004D0D0 -:1067B00013F4001F0CBF02200120704700EB810181 -:1067C000CB68196A0B6813604B6853607047000010 -:1067D00000EB810330B5DD68AA691368D36019B98D -:1067E000402B84BF402313606B8A1468D0F890203C -:1067F0001C4402EB4110013C09B2B4FBF3F46343C7 -:10680000033323F0030343EAC44343F0C043C0F817 -:10681000103B2B6803F00303012B0ED1D2F808388C -:1068200002EB411013F4807FD0F8003B14BF43F01B -:10683000805343F00053C0F8003B02EB4112D2F802 -:10684000003B43F00443C2F8003B30BD2DE9F0416A -:10685000D0F8906005460C4606EB4113D3F8087B50 -:106860003A07C3F8087B08D5D6F814381B0704D5B7 -:1068700000EB8103DB685B689847FA071FD5D6F801 -:106880001438DB071BD505EB8403D968CCB98B69B9 -:10689000488A5A68B2FBF0F600FB16228AB91868DB -:1068A000DA6890420DD2121AC3E90024302383F330 -:1068B000118821462846FFF78BFF84F31188BDE835 -:1068C000F081012303FA04F26B8923EA02036B814E -:1068D000CB68002BF3D021462846BDE8F04118478D -:1068E00000EB81034A0170B5DD68D0F890306C6927 -:1068F0002668E66056BB1A444FF40020C2F810091F -:106900002A6802F00302012A0AB20ED1D3F808085D -:1069100003EB421410F4807FD4F8000914BF40F058 -:10692000805040F00050C4F8000903EB4212D2F846 -:10693000000940F00440C2F800090122D3F83408ED -:1069400002FA01F10143C3F8341870BD19B9402EA1 -:1069500084BF4020206020681A442E8A8419013C9C -:10696000B4FBF6F440EAC44040F00050C6E7000033 -:106970002DE9F843D0F8906005460C464F0106EB30 -:106980004113D3F8088918F0010FC3F808891CD007 -:10699000D6F81038DB0718D500EB8103D3F80CC00C -:1069A000DCF81430D3F800E0DA68964530D2A2EB78 -:1069B0000E024FF000091A60C3F80490302383F3ED -:1069C0001188FFF78DFF89F3118818F0800F1DD013 -:1069D000D6F834380126A640334217D005EB84039D -:1069E0000134D5F89050D3F80CC0E4B22F44DCF851 -:1069F000142005EB0434D2F800E05168714514D33B -:106A0000D5F8343823EA0606C5F83468BDE8F883BB -:106A1000012303FA01F2038923EA02030381DCF86C -:106A20000830002BD1D09847CFE7AEEB0103BCF87C -:106A30001000834228BF0346D7F8180980B2B3EB91 -:106A4000800FE3D89068A0F1040959F8048FC4F8C6 -:106A50000080A0EB09089844B8F1040FF5D8184459 -:106A60000B4490605360C8E72DE9F84FD0F8905080 -:106A700004466E69AB691E4016F480586E6103D0FF -:106A8000BDE8F84FFEF7C4BB002E12DAD5F8003E81 -:106A90009B0705D0D5F8003E23F00303C5F8003E60 -:106AA000D5F80438204623F00103C5F80438FEF772 -:106AB000DDFB370505D52046FFF778FC2046FEF7BD -:106AC000C3FBB0040CD5D5F8083813F0060FEB68FB -:106AD00023F470530CBF43F4105343F4A053EB6002 -:106AE00031071BD56368DB681BB9AB6923F008036A -:106AF000AB612378052B0CD1D5F8003E9A0705D061 -:106B0000D5F8003E23F00303C5F8003E2046FEF70B -:106B1000ADFB6368DB680BB120469847F30200F1D8 -:106B2000BA80B70226D5D4F8909000274FF0010A1A -:106B300009EB4712D2F8003B03F44023B3F5802F52 -:106B400011D1D2F8003B002B0DDA62890AFA07F363 -:106B500022EA0303638104EB8703DB68DB6813B17C -:106B60003946204698470137D4F89430FFB29B68E5 -:106B70009F42DDD9F00619D5D4F89000026AC2F31D -:106B80000A1702F00F0302F4F012B2F5802F00F0A2 -:106B9000CA80B2F5402F09D104EB8303002200F52F -:106BA0008050DB681B6A974240F0B0803003D5F814 -:106BB000185835D5E90303D500212046FFF746FED6 -:106BC000AA0303D501212046FFF740FE6B0303D53E -:106BD00002212046FFF73AFE2F0303D5032120466A -:106BE000FFF734FEE80203D504212046FFF72EFE0E -:106BF000A90203D505212046FFF728FE6A0203D526 -:106C000006212046FFF722FE2B0203D5072120464E -:106C1000FFF71CFEEF0103D508212046FFF716FE03 -:106C2000700340F1A780E90703D500212046FFF754 -:106C30009FFEAA0703D501212046FFF799FE6B07A7 -:106C400003D502212046FFF793FE2F0703D503212A -:106C50002046FFF78DFEEE0603D504212046FFF700 -:106C600087FEA80603D505212046FFF781FE6906A9 -:106C700003D506212046FFF77BFE2A0603D5072110 -:106C80002046FFF775FEEB0574D520460821BDE8C8 -:106C9000F84FFFF76DBED4F890904FF0000B4FF017 -:106CA000010AD4F894305FFA8BF79B689F423FF655 -:106CB00038AF09EB4713D3F8002902F44022B2F5AC -:106CC000802F20D1D3F80029002A1CDAD3F800291C -:106CD00042F09042C3F80029D3F80029002AFBDBD8 -:106CE0003946D4F89000FFF78DFB22890AFA07F3A2 -:106CF00022EA0303238104EB8703DB689B6813B15B -:106D00003946204698470BF1010BCAE7910701D19C -:106D1000D0F80080072A02F101029CBF03F8018B22 -:106D20004FEA18283FE704EB830300F58050DA6848 -:106D3000D2F818C0DCF80820DCE9001CA1EB0C0C30 -:106D400000218F4208D1DB689B699A683A449A60B7 -:106D50005A683A445A6029E711F0030F01D1D0F87C -:106D600000808C4501F1010184BF02F8018B4FEADC -:106D70001828E6E7BDE8F88F08B50348FFF774FE6A -:106D8000BDE80840FDF7E4BA3072002008B50348BA -:106D9000FFF76AFEBDE80840FDF7DABACC720020C2 -:106DA000D0F8903003EB4111D1F8003B43F40013CD -:106DB000C1F8003B70470000D0F8903003EB411160 -:106DC000D1F8003943F40013C1F8003970470000CE -:106DD000D0F8903003EB4111D1F8003B23F40013BD -:106DE000C1F8003B70470000D0F8903003EB411130 -:106DF000D1F8003923F40013C1F8003970470000BE -:106E000030B50433039C0172002104FB0325C160EB -:106E1000C0E90653049B0363059BC0E90000C0E979 -:106E20000422C0E90842C0E90A11436330BD0000F2 -:106E30000022416AC260C0E90411C0E90A226FF071 -:106E40000101FEF72DBD0000D0E90432934201D1CB -:106E5000C2680AB9181D704700207047036919609D -:106E60000021C2680132C260C26913448269934240 -:106E7000036124BF436A0361FEF706BD38B50446CB -:106E80000D46E3683BB162690020131D1268A362DE -:106E90001344E36207E0237A33B929462046FEF71C -:106EA000E3FC0028EDDA38BD6FF00100FBE70000DD -:106EB000C368C269013BC36043691344826993425A -:106EC000436124BF436A436100238362036B03B1C0 -:106ED0001847704770B53023044683F31188866ADB -:106EE0003EB9FFF7CBFF054618B186F31188284657 -:106EF00070BDA36AE26A13F8015B9342A36202D3F6 -:106F00002046FFF7D5FF002383F31188EFE7000049 -:106F10002DE9F84F04460E46174698464FF03009C3 -:106F200089F311880025AA46D4F828B0BBF1000FD8 -:106F300009D141462046FFF7A1FF20B18BF311880C -:106F40002846BDE8F88FD4E90A12A7EB050B521AC0 -:106F5000934528BF9346BBF1400F1BD9334601F13F -:106F6000400251F8040B914243F8040BF9D1A36A93 -:106F7000403640354033A362D4E90A239A4202D313 -:106F80002046FFF795FF8AF31188BD42D8D289F3D6 -:106F90001188C9E730465A46FAF7DEFCA36A5E4418 -:106FA0005D445B44A362E7E710B5029C04330172C1 -:106FB00003FB0421C460C0E906130023C0E90A33BF -:106FC000039B0363049BC0E90000C0E90422C0E9FD -:106FD0000842436310BD0000026A6FF00101C26005 -:106FE000426AC0E904220022C0E90A22FEF758BC26 -:106FF000D0E904239A4201D1C26822B9184650F858 -:10700000043B0B60704700231846FAE7C368002171 -:10701000C2690133C3604369134482699342436187 -:1070200024BF436A4361FEF72FBC000038B5044615 -:107030000D46E3683BB1236900201A1DA262E26994 -:107040001344E36207E0237A33B929462046FEF76A -:107050000BFC0028EDDA38BD6FF00100FBE7000003 -:1070600003691960C268013AC260C2691344826947 -:107070009342036124BF436A036100238362036B6D -:1070800003B118477047000070B530230D46044621 -:10709000114683F31188866A2EB9FFF7C7FF10B136 -:1070A00086F3118870BDA36A1D70A36AE26A01337A -:1070B0009342A36204D3E16920460439FFF7D0FF6D -:1070C000002080F31188EDE72DE9F84F04460D46C6 -:1070D000904699464FF0300A8AF311880026B3464D -:1070E000A76A4FB949462046FFF7A0FF20B187F3B2 -:1070F00011883046BDE8F88FD4E90A073A1AA8EBA0 -:107100000607974228BF1746402F1BD905F14003B9 -:1071100055F8042B9D4240F8042BF9D1A36A403660 -:107120004033A362D4E90A239A4204D3E16920469A -:107130000439FFF795FF8BF311884645D9D28AF3BE -:107140001188CDE729463A46FAF706FCA36A3D4482 -:107150003E443B44A362E5E7D0E904239A4217D1B9 -:10716000C3689BB1836A8BB1043B9B1A0ED013603A -:10717000C368013BC360C3691A4483699A420261D0 -:1071800024BF436A036100238362012318467047CA -:107190000023FBE700F01CB9014B586A704700BFA1 -:1071A000000C0040034B002258631A610222DA608F -:1071B000704700BF000C0040014B0022DA607047AE -:1071C000000C0040014B5863704700BF000C0040AA -:1071D000FEE7000070B51B4B0025044686B05860E2 -:1071E0000E4685620163FDF78BF804F11003A5607C -:1071F000E562C4E904334FF0FF33C4E90044C4E955 -:107200000635FFF7C9FF2B46024604F1340120463C -:10721000C4E9082380230C4A2565FEF7DBFA012325 -:107220000A4AE06000920375684672680192B2688B -:10723000CDE90223064BCDE90435FEF7F3FA06B09B -:1072400070BD00BFE8560020207E0008257E0008A3 -:10725000D1710008024AD36A1843D062704700BF58 -:10726000805400204B6843608B688360CB68C360A8 -:107270000B6943614B6903628B6943620B6803606E -:107280007047000008B53A4B40F2FF713948D3F817 -:1072900088200A43C3F88820D3F8882022F4FF62AC -:1072A00022F00702C3F88820D3F88830324B1A6CDA -:1072B0000A431A649A6E0A439A66304A9B6E1146D4 -:1072C000FFF7D0FF00F5806002F11C01FFF7CAFF55 -:1072D00000F5806002F13801FFF7C4FF00F580601F -:1072E00002F15401FFF7BEFF00F5806002F170016A -:1072F000FFF7B8FF00F5806002F18C01FFF7B2FFE5 -:1073000000F5806002F1A801FFF7ACFF00F5806096 -:1073100002F1C401FFF7A6FF00F5806002F1E00171 -:10732000FFF7A0FF00F5806002F1FC01FFF79AFF74 -:1073300002F58C7100F58060FFF794FF00F00AF908 -:107340000F4BD3F8902242F00102C3F89022D3F8F9 -:10735000942242F00102C3F894220522C3F8982037 -:107360004FF06052C3F89C20064AC3F8A02008BD25 -:107370000044025800000258004502582C7E0008C4 -:1073800000ED00E01F00080308B500F0C1FAFEF7A9 -:10739000EFF90C4BDA6B42F04002DA635A6E22F0DE -:1073A00040025A665B6E084B1A6842F008021A6087 -:1073B0001A6842F004021A60FEF740FFBDE8084078 -:1073C000FEF76ABC004502580018024870470000EA -:1073D0000E4B9A6C42F008029A641A6F42F008024F -:1073E0001A670B4A1B6FD36B43F00803D363C722A2 -:1073F000084B9A624FF0FF32DA6200229A615A63B8 -:10740000DA605A6001225A611A60704700450258DA -:107410000010005C000C0040094A08B51169D368EF -:107420000B40D9B29B076FEA0101116107D53023E8 -:1074300083F31188FEF7C2F9002383F3118808BD96 -:10744000000C0040044BDA6B0243DA635A6E1043BF -:1074500058665B6E704700BF0045025808B53C4B4C -:107460004FF0FF31D3F8802062F00042C3F8802053 -:10747000D3F8802002F00042C3F88020D3F88020A7 -:10748000D3F88420C3F88410D3F884200022C3F8F2 -:107490008420D3F88400D86F40F0FF4040F4FF0010 -:1074A00040F4DF4040F07F00D867D86F20F0FF4005 -:1074B00020F4FF0020F4DF4020F07F00D867D86F71 -:1074C000D3F888006FEA40506FEA5050C3F8880044 -:1074D000D3F88800C0F30A00C3F88800D3F8880006 -:1074E000D3F89000C3F89010D3F89000C3F8902020 -:1074F000D3F89000D3F89400C3F89410D3F8940014 -:10750000C3F89420D3F89400D3F89800C3F89810E7 -:10751000D3F89800C3F89820D3F89800D3F88C00DB -:10752000C3F88C10D3F88C00C3F88C20D3F88C00EF -:10753000D3F89C00C3F89C10D3F89C10C3F89C208F -:10754000D3F89C30FDF786F8BDE8084000F0B4B9E8 -:107550000044025808B50122504BC3F80821504B93 -:107560005A6D42F002025A65DA6F42F00202DA679F -:107570000422DB6F4B4BDA605A689104FCD54A4A0F -:107580001A6001229A60494ADA6000221A614FF4B7 -:1075900040429A61434B9A699204FCD51A6842F4BE -:1075A00080721A60424B1A6F12F4407F04D04FF47D -:1075B00080321A6700221A671A6842F001021A60C4 -:1075C0003B4B1A685007FCD500221A611A6912F069 -:1075D0003802FBD1012119604FF0804159605A6790 -:1075E000344ADA62344A1A611A6842F480321A6004 -:1075F0002F4B1A689103FCD51A6842F480521A6026 -:107600001A689204FCD52D4A2D499A6200225A63C9 -:10761000196301F57C01DA6301F5E77199635A6436 -:10762000284A1A64284ADA621A6842F0A8521A6094 -:107630001F4B1A6802F02852B2F1285FF9D1482294 -:107640009A614FF48862DA6140221A621F4ADA6452 -:107650001F4A1A651F4A5A651F4A9A6532231F4AF4 -:107660001360136803F00F03022BFAD1104A136959 -:1076700043F003031361136903F03803182BFAD1A5 -:107680004FF00050FFF7DEFE4FF08040FFF7DAFECC -:107690004FF00040BDE80840FFF7D4BE0080005125 -:1076A000004502580048025800C000F004000001E4 -:1076B000004402580000FF0100889008322060005A -:1076C00063020901470E0508DD0BBF012000002001 -:1076D000000001100910E00000010110002000521C -:1076E0004FF0B04208B5D2F8883003F00103C2F879 -:1076F000883023B1044A13680BB150689847BDE83D -:107700000840FCF725BE00BF807300204FF0B04258 -:1077100008B5D2F8883003F00203C2F8883023B1EC -:10772000044A93680BB1D0689847BDE80840FCF75D -:107730000FBE00BF807300204FF0B04208B5D2F8F2 -:10774000883003F00403C2F8883023B1044A136977 -:107750000BB150699847BDE80840FCF7F9BD00BF80 -:10776000807300204FF0B04208B5D2F8883003F0A3 -:107770000803C2F8883023B1044A93690BB1D06979 -:107780009847BDE80840FCF7E3BD00BF80730020C8 -:107790004FF0B04208B5D2F8883003F01003C2F8B9 -:1077A000883023B1044A136A0BB1506A9847BDE888 -:1077B0000840FCF7CDBD00BF807300204FF0B04300 -:1077C00010B5D3F8884004F47872C3F88820A30673 -:1077D00004D5124A936A0BB1D06A9847600604D563 -:1077E0000E4A136B0BB1506B9847210604D50B4A18 -:1077F000936B0BB1D06B9847E20504D5074A136C25 -:107800000BB1506C9847A30504D5044A936C0BB197 -:10781000D06C9847BDE81040FCF79ABD80730020FB -:107820004FF0B04310B5D3F8884004F47C42C3F85D -:107830008820620504D5164A136D0BB1506D984728 -:10784000230504D5124A936D0BB1D06D9847E0041F -:1078500004D50F4A136E0BB1506E9847A10404D59E -:107860000B4A936E0BB1D06E9847620404D5084A58 -:10787000136F0BB1506F9847230404D5044A936FDC -:107880000BB1D06F9847BDE81040FCF761BD00BF59 -:107890008073002008B50348FDF72AF8BDE80840CA -:1078A000FCF756BD1450002008B5FFF7B5FDBDE844 -:1078B0000840FCF74DBD0000062108B50846FDF75D -:1078C0009DF806210720FDF799F806210820FDF70D -:1078D00095F806210920FDF791F806210A20FDF709 -:1078E0008DF806211720FDF789F806212820FDF7DD -:1078F00085F809217A20FDF781F807213220FDF76C -:107900007DF80C215220BDE80840FDF777B8000053 -:1079100008B5FFF7A3FD00F00DF8FDF72DFAFDF710 -:1079200005FCFDF7D7FAFFF751FDBDE80840FFF76A -:1079300031BC00000023054A19460133102BC2E96F -:10794000001102F10802F8D1704700BF80730020D7 -:107950000B460146184600F003B8000000F00EB8D0 -:1079600010B5054C13462CB10A4601460220AFF370 -:10797000008010BD2046FCE700000000024B0146DD -:107980001868FEF77FBB00BF6C23002010B50139DB -:107990000244904201D1002005E0037811F8014F24 -:1079A000A34201D0181B10BD0130F2E72DE9F041D0 -:1079B000A3B1C91A17780144044603F1FF3C8C4275 -:1079C000204601D9002009E00578BD4204F10104F8 -:1079D000F5D10CEB0405D618A54201D1BDE8F08124 -:1079E00015F8018D16F801EDF045F5D0E7E7000038 -:1079F000034611F8012B03F8012B002AF9D1704737 -:107A00006F72672E6172647570696C6F742E437546 -:107A1000626550696C6F742D43414E4D6F64000078 -:107A200053544D333248373F3F3F0053544D333268 -:107A3000483733782F3732780053544D3332483734 -:107A400034332F3735332F373530000001105A00CB -:107A500003105900012058000320560040A2E4F111 -:107A6000646891060041A3E5F26569920700000091 -:107A700043414E464449666163653A204D657373E0 -:107A80006167652052414D204F766572666C6F7755 -:107A9000210000004261642043414E4966616365F4 -:107AA00020696E6465782E00000000000000000070 -:107AB000912A00081D230008DD3100088D230008ED -:107AC00099230008B1270008112500085523000854 -:107AD0005923000831230008192300086D270008E6 -:107AE0003D230008153300084923000841270008FA -:107AF00001040E05054B02020E05054B04010E059F -:107B0000054B05010B04044B080106030346000066 -:107B100010000240080002400008024000000B0074 -:107B200028000240080002400408024006010C0040 -:107B300040000240080002400808024010020D0008 -:107B400058000240080002400C08024016030E00D4 -:107B5000700002400C0002401008024000040F00B8 -:107B6000880002400C000240140802400605100084 -:107B7000A00002400C00024018080240100611004C -:107B8000B80002400C0002401C08024016072F00FB -:107B90001004024008040240200802400008380097 -:107BA0002804024008040240240802400609390063 -:107BB000400402400804024028080240100A3A002B -:107BC00058040240080402402C080240160B3B00F7 -:107BD000700402400C04024030080240000C3C00DB -:107BE000880402400C04024034080240060D4400A0 -:107BF000A00402400C04024038080240100E450068 -:107C0000B80402400C0402403C080240160F460033 -:107C100000960000000000000000000000000000CE -:107C2000000000000000000000000000394D0008C6 -:107C3000254D0008614D00084D4D0008594D0008C4 -:107C4000454D0008314D00081D4D00086D4D0008E0 -:107C500000000000514E00083D4E0008794E00081B -:107C6000654E0008714E00085D4E0008494E000840 -:107C7000354E0008854E000800000000010000009D -:107C80000000000063300000847C0008D85400200D -:107C9000E85600204172647550696C6F740025428B -:107CA0004F415244252D424C002553455249414CE9 -:107CB00025000000020000000000000071500008D4 -:107CC000E150000840004000986F0020A86F00209D -:107CD000020000000000000003000000000000009F -:107CE000295100080000000010000000B86F0020BB -:107CF00000000000010000000000000030720020C1 -:107D000001010200355C0008455B0008E15B0008EA -:107D1000C55B0008430000001C7D00080902430009 -:107D2000020100C032090400000102020100052422 -:107D300000100105240100010424020205240600AC -:107D400001070582030800FF09040100020A000080 -:107D50000007050102400000070581024000000005 -:107D600012000000687D00081201100102000040AE -:107D70000912415700020102030100000403090433 -:107D800025424F41524425003031323334353637A5 -:107D900038394142434445460000000000010020BC -:107DA00000FF01000200000000000030000004009D -:107DB000080000000000002400000800040000008B -:107DC0000004000000FC000002000000000004307D -:107DD00000800000080000000000003800000100E2 -:107DE0000100000000000000855200083D55000819 -:107DF000E9550008400040006873002068730020C7 -:107E000001000000787300208000000040010000A5 -:107E10000800000000010000001000000800000041 -:107E20006D61696E0069646C650000000000802A65 -:107E300000000000AAAAAAAA00000024FFFF000078 -:107E40000000000000A00A00000000000000000088 -:107E5000AAAAAAAA00000000FFFF0000000000007C -:107E6000000000000000000000000000AAAAAAAA6A -:107E700000000000FFFF0000000000000000000004 -:107E80000A00000000000000AAAAAAAA0000000040 -:107E9000FFFF0000990000000000000000800200C9 -:107EA00000000000AAAAAAAA00400100FFFF0000EB -:107EB000000000700700000000000000000000004B -:107EC000AAAAAAAA00000000FFFF0000000000000C -:107ED000000000000500000000000000A5AAAAAAFA -:107EE00000000000FCFF0000000000000000000097 -:107EF0000000000000000000AAAAAAAA00000000DA -:107F0000FFFF000000000000000000000000000073 -:107F100000000000AAAAAAAA00000000FFFF0000BB -:107F20000000000000000000000000000000000051 -:107F3000AAAAAAAA00000000FFFF0000000000009B -:107F4000000000000000000000000000AAAAAAAA89 -:107F500000000000FFFF0000000000000000000023 -:107F600037040000000000000000180000000000BE -:107F7000FE2A0100D2040000FF000000F05600209D -:107F80001450002000000000207A00088304000044 -:107F90002B7A000850040000397A0008009600008F -:107FA0000000080096000000000800000400000027 -:107FB0007C7D0008000000000000000000000000C0 -:107FC00000000000000000000000000070230020FE -:107FD00000000000000000000000000000000000A1 -:107FE0000000000000000000000000000000000091 -:107FF0000000000000000000000000000000000081 -:108000000000000000000000000000000000000070 -:108010000000000000000000000000000000000060 -:108020000000000000000000000000000000000050 -:00000001FF diff --git a/Tools/bootloaders/CubePilot-PPPGW_bl.bin b/Tools/bootloaders/CubePilot-PPPGW_bl.bin deleted file mode 100755 index 517887441d56d2..00000000000000 Binary files a/Tools/bootloaders/CubePilot-PPPGW_bl.bin and /dev/null differ diff --git a/Tools/bootloaders/CubePurple_bl.bin b/Tools/bootloaders/CubePurple_bl.bin index 10a70fa49000fd..ef7c5653123065 100755 Binary files a/Tools/bootloaders/CubePurple_bl.bin and b/Tools/bootloaders/CubePurple_bl.bin differ diff --git a/Tools/bootloaders/CubePurple_bl.hex b/Tools/bootloaders/CubePurple_bl.hex index 1c010870823330..3c36448102e62c 100644 --- a/Tools/bootloaders/CubePurple_bl.hex +++ b/Tools/bootloaders/CubePurple_bl.hex @@ -1,1019 +1,1009 @@ :020000040800F2 -:1000000000040020E10100081D0F0008210F000876 -:10001000750F0008210F0008490F0008E3010008D0 -:10002000E3010008E3010008E30100080D280008CF +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E301000801360008CD :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E301000875390008A139000830 -:10006000CD390008F9390008253A0008E3010008F5 +:10005000E3010008E3010008B1380008D9380008BE +:10006000013900082939000851390008E301000866 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008513A000809 +:10009000E3010008E3010008E301000879390008E2 :1000A000E3010008E3010008E3010008E3010008A0 :1000B000E3010008E3010008E3010008E301000890 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E30100082511000839110008B8 -:1000E000B93A0008E3010008E3010008E301000851 +:1000D000E3010008E30100084D3A0008E3010008CD +:1000E000DD390008E3010008E3010008E30100082E :1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E301000885370008E301000867 +:10010000E3010008E3010008613A0008E301000888 :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008F92E0008BC +:10014000E3010008E3010008E3010008A92D00080D :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E30100084D110008E301000845 +:10018000E3010008E3010008E3010008E3010008BF :10019000E3010008E3010008E3010008E3010008AF :1001A000E3010008E3010008E3010008E30100089F :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F019FB03F02BFA4FF055301F4956 -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE702F0B3 -:1002A000F7FA03F061FA144C144DAC4203DA54F837 -:1002B000041B8847F9E700F03FF8114C114DAC42A0 -:1002C00003DA54F8041B8847F9E702F0DFBA0000AC -:1002D000000400200024002000000008000000208E -:1002E00000040020603F0008002400202824002093 -:1002F00028240020903D0020E0010008E0010008D3 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F0ECFE4B -:1003300001F09CFE00DFFEE770B5204C092300258C -:1003400023706FF03F061F236570A570E57025715F -:100350006571A571E57125726672A372E57200F090 -:10036000FFFC20B10F2325726672A372E57202F0C2 -:100370001FFA044602F044FA0546D8B9104B9C42D5 -:100380001AD001339C4218BF054641F2883404BF9D -:1003900001250024002002F015FA0DB100F0B6F896 -:1003A00000F062FD00F01AFC204600F00DF900F0AC -:1003B000ADF8F9E70024EDE70446EBE72824002038 -:1003C000010007B008B500F087FBA0F120035842F8 -:1003D000584108BD07B5054B02211B88ADF8043014 -:1003E00001A800F0E5FB03B05DF804FBA03B0008AA -:1003F000064991F8243033B100230822086A81F8B5 -:10040000243000F00DBC0120704700BF48240020BC -:100410002DE9F84F234C94F82430054688461746BA -:100420008BBB2E46DFF87C90002F38D094F824A0A8 -:10043000BAF1000F05D12022FF214846266200F0C4 -:1004400001FDCAF10805BD4228BF3D465FFA85FBA4 -:10045000AD0041462A4604EB8A0000F0C9FC94F83E -:100460002430A7EB0B079B445FFA8BFBBBF1080F13 -:100470002E44A844FFB284F824B0D5D1FFF7B8FFCA -:100480000028D1D108E0266A06EB8306B042C9D025 -:10049000FFF7AEFF0028C4D10020BDE8F88F01208F -:1004A000BDE8F88F4824002010B5202383F311887D -:1004B0001248C3680BB101F0ADFE0023104A0F488B -:1004C0004FF47A7101F06AFE002383F311880D4C1A -:1004D000236813B12368013B2360636813B1636829 -:1004E000013B6360084B1B7833B9636823B9022072 -:1004F00000F074FC3223636010BD00BF3424002080 -:10050000A9040008782500207024002010B5254B90 -:10051000254953F8042F013200D110BD8B42F8D188 -:10052000224C234B22689A423AD9224B9B6803F112 -:10053000006303F580439A4232D2002000F068FB4A -:100540001D4B0220187000F03FFC1C4B1A6C00225F -:100550001A64196E1A66196E596C5A64596E5A6685 -:100560005A6E5A6942F080025A615A6922F080023A -:100570005A615A691A6942F000521A611A6922F0E6 -:1005800000521A611B6972B60D4A0E4B13601B684C -:100590002268202181F311889D4683F30888104743 -:1005A00010BD00BFFC3F00081C40000804400008CC -:1005B000FF3F00082824002070240020003802405B -:1005C00008ED00E0004000082DE9F04F99B0B34C71 -:1005D00001902022FF2110A8A66800F033FCB04A49 -:1005E0001378A346A3B9AF480121C360117020233B -:1005F00083F31188C3680BB101F00CFE0023AA4AF3 -:10060000A8484FF47A7101F0C9FD002383F31188E3 -:10061000019B13B1A54B019A1A60A54AA349019FFA -:100620000292002313704B6099461C461D46984663 -:10063000012000F0C9FB002F00F012829B4B1B68C9 -:10064000002B40F00D8219B0BDE8F08F0220FFF7BB -:10065000B9FE002840F0FB81019BB9F1000F08BFF3 -:100660001F46944B1B88ADF82C3002210BA800F0DC -:100670009FFADDE74FF47A7000F02EFA031E039321 -:10068000EADB0220FFF79EFE82460028E4D0039BAF -:10069000581E042800F2DD81DFE800F0030E11147B -:1006A000170018A8052340F8343D042100F080FA13 -:1006B00054464FF0000856E004217848F6E704213C -:1006C0007D48F3E704217D48F0E71C24204600F034 -:1006D000A1FA04340B9004210BA800F069FA2C2C29 -:1006E000F4D1E5E7002DB7D0002CB5D00220FFF7FC -:1006F00069FE0546002800F0AF8101206C4C00F037 -:1007000087FA0220207000F05FFB4FF000095FFACB -:1007100089FA504600F08CFA074658B1504600F06E -:1007200097FA09F101090028F1D12C46A9460027C2 -:10073000634B97E701230220237000F03BFB3E460A -:10074000DBF808309E4206D2304600F063FA0130F2 -:10075000EBD10436F4E7029B00261E70534BA946EA -:100760005E602C46374600F075FB15B1002C18BFB3 -:100770000027FFF72FFE5BE7002D3FF46DAF002C45 -:100780003FF46AAF029B0220187000F01DFB32207C -:1007900000F0A2F9B0F1000AC0F25E811AF0030580 -:1007A00040F05A81DBF8082006EB0A03934200F27E -:1007B0005381BAF5807F00F24F8155450DDA4FF431 -:1007C0007A7000F089F90490049B002BC0F24481F8 -:1007D0003C4A049BAB540135EFE7C820FFF7F2FD1C -:1007E0000546002800F038811F2E11D8C6F12004DC -:1007F000544528BF544610AB26F003002246314929 -:10080000184400F0F5FA2246FF212E4800F01AFBAA -:100810004FEAAA0A5FFA8AF22A493046FFF7F8FD42 -:100820000446002800F01A8106EB8A0605469AE77E -:100830000220FFF7C7FD00283FF40EAFFFF7D8FDF9 -:1008400000283FF409AF4FF0000A5346DBF80820B8 -:1008500092451CD2BAF11F0F12D8109A01320FD054 -:100860002AF0030218A90A4452F8202C0B921846C9 -:1008700004220BA900F092FB0AF1040A0346E5E703 -:100880005046039300F0C6F9039B0B90EFE718A8BE -:10089000042140F84C3D00F08BF964E72824002047 -:1008A0007425002034240020A904000878250020A5 -:1008B00070240020A23B00082C24002030240020BB -:1008C000A43B00087424002018A8002340F8343DFD -:1008D000642100F039F900287FF4BEAE0220FFF752 -:1008E00071FD00283FF4B8AE0B9800F0C3F918ABC7 -:1008F00043F8480D04211846CDE718A8002340F816 -:10090000343D642100F020F900287FF4A5AE0220D8 -:10091000FFF758FD00283FF49FAE0B9800F0B8F9A0 -:1009200018AB43F8440DE5E70220FFF74BFD002824 -:100930003FF492AE00F0B2F918AB43F8400DD9E79E -:100940000220FFF73FFD00283FF486AE0BA91420DC -:1009500000F0AAF9824618A8042140F83CAD00F046 -:1009600027F951460BA896E7322000F0B5F8B0F110 -:10097000000AFFF671AE1AF0030F7FF46DAEDBF8DC -:1009800008200AEB080393423FF666AE0220FFF709 -:1009900019FD00283FF460AE2AF0030AC244D04596 -:1009A0003FF4E1AE404600F035F904210A900AA870 -:1009B00000F0FEF808F10408F1E74FF47A70FFF751 -:1009C00001FD00283FF448AEFFF712FD00283FF478 -:1009D000AFAE109B01330CD0082210A90020FFF706 -:1009E00017FD00283FF4A4AE2022FF2110A800F03C -:1009F00029FAFFF7EFFC374801F08CFB23E6002DC6 -:100A00003FF42AAE002C3FF427AE18A8002340F88C -:100A1000343D642100F098F8824600287FF41CAE33 -:100A20000220FFF7CFFC00283FF416AE0390FFF73B -:100A3000D1FC41F2883001F06DFB0B9800F04EFACA -:100A400000F008FA039B57461C461D46F0E5054694 -:100A500089E64FF00008FFE52546FDE52C4667E6F0 -:100A6000002000F039F80490049B002BFFF6E3AD62 -:100A7000012000F09FF9049B213B122B3FF6D8ADDB -:100A800001A252F823F000BF4D06000875060008C9 -:100A9000E5060008310600083106000831060008A6 -:100AA000790700086909000831080008C90800082A -:100AB000FB08000829090008310600084109000860 -:100AC00031060008BB090008670700083106000866 -:100AD000FF090008A08601002DE9F34702AE0024BB -:100AE0004FF47A7506F8014D144FDFF858804543EE -:100AF00097F900305A1C5FFA84F901D0A34212D151 -:100B000058F8240003680122D3F820A031462B4670 -:100B1000D047012807D10A4B9DF8070083F80090C1 -:100B200002B0BDE8F0870134042CE1D14FF4FA7033 -:100B300001F0F0FA4FF0FF30F2E700BF0024002090 -:100B400098250020F83B00082DE9F0474FF47A750E -:100B5000144FDFF8588006464D43002497F90030C3 -:100B60005A1C5FFA84F901D0A34210D158F824002E -:100B700003680422D3F820A031462B46D04704282E -:100B800005D1094B83F800900020BDE8F0870134BF -:100B9000042CE3D14FF4FA7001F0BCFA4FF0FF30AF -:100BA000BDE8F0870024002098250020F83B0008CD -:100BB00030B4074B1A78074B53F822402368DD699D -:100BC000054B0A46AC460146204630BC604700BF94 -:100BD00098250020F83B0008A086010070B501F0C0 -:100BE000E3FC094C094E20700025306823788342CD -:100BF00008D901F0D3FC336805440133B5F5804FC3 -:100C00003360F2D370BD00BF9925002080250020FD -:100C100001F080BD00F1006000F580400068704781 -:100C200000F10060920000F5804001F00BBD000073 -:100C3000054B1A68054B1B789B1A834202D9104456 -:100C400001F0ACBC002070478025002099250020D1 -:100C500038B5074D04462868204401F0A7FC28B9A0 -:100C600028682044BDE8384001F0B8BC38BD00BF5A -:100C70008025002010F0030308D1B0F5007F05D8CF -:100C800000F10050A0F50840006870470020704750 -:100C9000014BC058704700BF107AFF1F014B186806 -:100CA000704700BF002004E070B52A4B1C68C4F3F5 -:100CB0000B03240C63B140F21342934231D040F253 -:100CC000194293422FD040F2214293422DD1032367 -:100CD000214A0C2505FB03235D6893F9082042F2A5 -:100CE00001039C4224D0B4F5805F23D041F201037C -:100CF0009C4221D041F203039C421FD041F20703E2 -:100D00009C4208BF3122441E0C44013D0B46A342C5 -:100D10001ED215F9016F581C96B1034600F8016CFC -:100D2000F5E70123D4E70223D2E73F220B4DD6E7B4 -:100D30003322E3E74122E1E75A22E4E75922E2E7DE -:100D40002C2584421D7001D9981C5A70401A70BD20 -:100D50001846FBE7002004E0C83B0008A83B000859 -:100D6000124B5A8842F201018A4293B214D0B3F571 -:100D7000805F13D041F20102934211D041F203028D -:100D800093420FD041F2070293420DD10423084A47 -:100D900002EB8303D87870470023F8E70123F6E7D6 -:100DA0000223F4E70323F2E700207047002004E069 -:100DB000B43B0008022802BF024B4FF480529A61F4 -:100DC000704700BF00100240022802BF024B4FF0E4 -:100DD00080529A61704700BF00100240022801BF94 -:100DE000024A536983F480535361704700100240F4 -:100DF00010B50023934203D0CC5CC4540133F9E70F -:100E000010BD000030B5441E14F9010F0B4660B14F -:100E100093F90050854201F1010106D11AB993F905 -:100E20000020801A30BD013AEEE7002AF7D11046C3 -:100E300030BD000002460346981A13F9011B002931 -:100E4000FAD1704702440346934202D003F8011BD3 -:100E5000FAE77047024B1A78024B1A70704700BFCE -:100E60009825002000240020F8B5164C1648174D90 -:100E7000174E154F00F096FC2146134800F0BEFCBB -:100E800024681448626D936B23F40023936301F08C -:100E900041F92046104900F0BDFD626D936B43F4AB -:100EA000002393634FF4E1332B60002456F82400B1 -:100EB000B84202D0294600F0D3FB0134042CF5D10E -:100EC000F8BD00BFE03C00089433002084250020DA -:100ED000F83B000840420F000C3D000838B50B4BB2 -:100EE0001A780B4B53F822400A4B9C4205460CD013 -:100EF000094B002118461422FFF7A4FF05600146A4 -:100F00002046BDE8384000F0ABBB38BD9825002036 -:100F1000F83B00089433002084250020FEE7000001 -:100F200000B59BB0EFF3098168226846FFF760FFC8 -:100F3000EFF30583034B9A6B9A6A9A6A9A6A9A6AE4 -:100F40009B6AFEE700ED00E000B59BB0EFF309817E -:100F500068226846FFF74CFFEFF30583044B9A6B5A -:100F60009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFC4 -:100F700000ED00E000B59BB0EFF309816822684600 -:100F8000FFF736FFEFF30583034B5A6B9A6A9A6AB1 -:100F90009A6A9A6A9B6AFEE700ED00E030B5084D58 -:100FA0000A4491420BD011F8013B09245840013CFE -:100FB000F7D040F300032B4083EA5000F7E730BD41 -:100FC0002083B8ED002304491A465A50C818083344 -:100FD000802B4260F9D170479C250020026843684D -:100FE0001143016003B1184770470000024AD368FB -:100FF00043F0C003D360704700440040024AD36806 -:1010000043F0C003D360704700480040024AD368F1 -:1010100043F0C003D3607047007800402DE9F041F1 -:10102000D0F85C64F7683368DA0505469CB20DD5E4 -:10103000202383F311884FF400710430FFF7CEFFB3 -:101040006FF480733360002383F31188202383F3CC -:10105000118805F1040814F02F0333D183F31188AC -:10106000380615D5210613D5202383F3118805F101 -:10107000380000F053FA002846DA0821281DFFF74F -:10108000ADFF4FF67F733B40F360002383F311887D -:101090007A060ED563060CD5202383F31188EA6CFB -:1010A0002B6D9A4202D12B6C002B2FD1002383F39E -:1010B0001188D5F86424D368002B31D01069BDE8BD -:1010C000F0411847230713D014F0080F0CBF00217C -:1010D0008021E00748BF41F02001A20748BF41F04E -:1010E0004001630748BF41F480714046FFF776FF37 -:1010F000A406736805D595F860142846194000F0D9 -:10110000BDFA3468A4B2A6E77060BEE727F04007D6 -:101110003F041021281D3F0CFFF760FFF760C5E773 -:10112000BDE8F08108B50348FFF778FFBDE8084047 -:1011300001F07CBB1C26002008B50348FFF76EFFBA -:10114000BDE8084001F072BB842A002008B50348BE -:10115000FFF764FFBDE8084001F068BBEC2E0020FB -:1011600010B50E4C0E4A2046002100F057FA0D4BE8 -:10117000C4F85C340C4C0D4A2046002100F04EFAB5 -:101180000B4BC4F85C340B4C0B4A0021204600F09A -:1011900045FA0A4BC4F85C3410BD00BF1C26002081 -:1011A000ED0F000800440040842A0020FD0F0008D5 -:1011B00000480040EC2E00200D1000080078004090 -:1011C00038B5394D037C002918BF0D46012B044664 -:1011D000C0F8645410D1354B984242D1344B1A6C4C -:1011E00042F400321A641A6E42F400321A661B6E20 -:1011F0000B21262000F06AF82E4BD4F85C249A428A -:101200002B6802D02C498A424BD12C4901EB530167 -:10121000B1FBF3F3A988080442BF23F0070003F0F1 -:10122000070343EA40039360EB8843F040039BB21B -:1012300013612B8943F001039BB2536141F40453C2 -:1012400043F02C03D36001F4A05100231360B1F5E7 -:10125000806F136853680CBF7F23FF2384F86034CA -:1012600038BD174B98420CD1114B1A6C42F48022B6 -:101270001A641A6E42F480221A661B6E0B21272014 -:10128000B8E7104B9842B7D1094B1A6C42F0804234 -:101290001A641A6E42F080421A661B6E0B215220AD -:1012A000A8E70949B2E700BF283C00081C26002037 -:1012B00000380240001001400014014000BD01054B -:1012C000842A0020EC2E002080DE800200F16043A2 -:1012D00000F01F02400903F5614309018000C9B213 -:1012E00000F1604083F8001300F561400123934052 -:1012F000C0F8803103607047F8B51546826806690A -:10130000AA420B46816938BF8568761AB542044601 -:1013100007D218462A46FFF76BFDA3692B44A36149 -:101320000DE011D932461846FFF762FDAF1B3A4671 -:10133000E1683044FFF75CFDE2683A44A261A368CB -:101340005B1BA3602846F8BD18462A46FFF750FDF0 -:10135000E368E4E783682DE9F041044693421546CB -:10136000266938BF85684069361AB5420F4606D2ED -:101370002A46FFF73DFD63692B4463610DE012D9F6 -:101380003246A5EB0608FFF733FD4246B919E0687F -:10139000FFF72EFDE26842446261A3685B1BA36015 -:1013A0002846BDE8F0812A46FFF722FDE368E4E71E -:1013B00010B50A440024C361029B00604060846051 -:1013C000C160816141610261036210BD08B582693B -:1013D0004369934201D1826882B982680132826096 -:1013E0005A1C42611970426903699A4201D3C36869 -:1013F0004361002100F0AAFE002008BD4FF0FF303D -:1014000008BD000070B5202304460E4683F3118802 -:10141000A568A5B1A368A269013BA360531CA361A1 -:1014200015782269934224BFE368A361E3690BB195 -:1014300020469847002383F31188284670BD314623 -:10144000204600F073FE0028E2DA85F3118870BDB3 -:101450002DE9F74F05460F4690469A46D0F81C9066 -:10146000202686F311884FF0000B144664B1224603 -:1014700039462846FFF740FF034668B951462846DB -:1014800000F054FE0028F1D0002383F31188A8EB6C -:10149000040003B0BDE8F08FB9F1000F03D0019054 -:1014A0002846C847019B8BF31188E41A1F4486F332 -:1014B0001188DBE7C16081614161C3611144009B18 -:1014C000006040608260016103627047F8B50446C5 -:1014D0000E461746202383F31188A568A5B1A3689B -:1014E000013BA36063695A1C62611E7023696269D3 -:1014F0009A4224BFE3686361E3690BB120469847D1 -:10150000002080F31188F8BD3946204600F00EFE19 -:101510000028E2DA85F31188F8BD0000836942698A -:101520009A4210B501D182687AB98268013282602C -:101530005A1C82611C7803699A4201D3C368836193 -:10154000002100F003FE204610BD4FF0FF3010BD1B -:101550002DE9F74F05460F4690469A46D0F81C9065 -:10156000202686F311884FF0000B144664B1224602 -:1015700039462846FFF7EEFE034668B9514628462D -:1015800000F0D4FD0028F1D0002383F31188A8EBEC -:10159000040003B0BDE8F08FB9F1000F03D0019053 -:1015A0002846C847019B8BF31188E41A1F4486F331 -:1015B0001188DBE7026843681143016003B11847F3 -:1015C000704700001430FFF743BF00004FF0FF33B7 -:1015D0001430FFF73DBF00003830FFF7B9BF0000FF -:1015E0004FF0FF333830FFF7B3BF00001430FFF780 -:1015F00009BF00004FF0FF311430FFF703BF0000B8 -:101600003830FFF763BF00004FF0FF323830FFF78C -:101610005DBF000000207047FFF7A2BD37B50F4B3C -:101620000360002343608360C360012304460374A6 -:10163000154600900B464FF4007200F15C01143027 -:10164000FFF7B6FE00942B464FF4007204F51771B5 -:1016500004F13800FFF72EFF03B030BD3C3C00081A -:1016600010B52023044683F31188FFF7A9FD022358 -:101670002374002383F3118810BD000038B5C369BB -:1016800004460D461BB904210844FFF793FF294681 -:1016900004F11400FFF79AFE002806DA201D4FF42B -:1016A0008061BDE83840FFF785BF38BD02684368F8 -:1016B0001143016003B118477047000013B5446B34 -:1016C000D4F894341A681178042915D1217C0229A0 -:1016D00012D11979128901238B4013420CD101A92F -:1016E00004F14C0001F058FED4F89444019B217998 -:1016F0000246206800F0DAF902B010BD143001F0A3 -:10170000DBBD00004FF0FF33143001F0D5BD000009 -:101710004C3001F0ADBE00004FF0FF334C3001F013 -:10172000A7BE0000143001F0A9BD00004FF0FF314A -:10173000143001F0A3BD00004C3001F079BE000070 -:101740004FF0FF324C3001F073BE0000D0F894240B -:1017500038B5136819780429054601D0012038BD31 -:10176000017C0229FAD112795C8901209040044061 -:10177000F4D105F1140001F03BFD02460028EDD044 -:10178000D5F894544FF480732868697900F07CF997 -:10179000204638BD406BFFF7D9BF000000207047DE -:1017A000704700007FB5124B0360002343608360E5 -:1017B000C360012502260F4B057404460290019375 -:1017C00000F18402294600964FF48073143001F032 -:1017D000EBFC094B0193029400964FF4807304F5DF -:1017E0002372294604F14C0001F0B2FD04B070BD33 -:1017F000643C000895170008BD1600080B682022FD -:1018000082F311880A7903EB820290614A790932E6 -:1018100043F822008A7912B103EB82039861022314 -:101820000374C0F89414002383F3118870470000F8 -:1018300038B5037F044613B190F85430ABB9201D7E -:1018400001250221FFF732FF04F1140025776FF024 -:10185000010100F087FC84F8545004F14C006FF053 -:101860000101BDE8384000F07DBC38BD10B5012154 -:1018700004460430FFF71AFF0023237784F854301E -:1018800010BD000038B504460025143001F0A4FC5A -:1018900004F14C00257701F073FD201D84F85450AD -:1018A0000121FFF703FF2046BDE83840FFF74EBF98 -:1018B00090F8443003F06003202B19D190F84520B4 -:1018C000212A0AD0222A4FF000030ED0202A0FD15D -:1018D000084A82630722C26304E0064B836307233E -:1018E000C36300230364012070478363C363F9E784 -:1018F0000020704701240020D0F8943437B51A68CE -:101900001178042904461AD1017C022917D11979CA -:10191000128901238B40134211D100F14C05284656 -:1019200001F0EEFD58B101A9284601F035FDD4F8CB -:101930009444019B21790246206800F0B7F803B077 -:1019400030BD000000EB8103F7B59C6905460E46EB -:10195000F4B1202383F3118805EB8607201D0821AD -:10196000FFF7A4FEFB685B691B684C3413B120468B -:1019700001F020FD01A9204601F00EFD024648B10C -:10198000019B3146284600F091F8002383F311882B -:1019900003B0F0BDFB685A691268002AF5D01B8AB3 -:1019A000013B1340F1D105F14402EAE7093138B5B2 -:1019B00050F82140DCB1202383F31188D4F894241B -:1019C0001368527903EB8203DB689B695D6845B15C -:1019D00004216018FFF76AFE294604F1140001F0A3 -:1019E00011FC2046FFF7B2FE002383F3118838BDB7 -:1019F0007047000000F0D2BF012303700023436052 -:101A0000C36183620362C3624362036303814381F0 -:101A10007047000038B50446202383F31188002561 -:101A20004160C56005614561856100F0C7FF022323 -:101A3000237085F3118838BD70B500EB810305462E -:101A40005069DA600E46144618B110220021FFF7E3 -:101A5000F9F9A06918B110220021FFF7F3F9314616 -:101A60002846BDE8704001F073B80000028902F01A -:101A700001020281428902F00102428100220261D8 -:101A80004261826101F0F8B8F0B400EB810447894B -:101A9000E4680125A4698D403D434581236000230E -:101AA000A2606360F0BC01F013B90000F0B400EB79 -:101AB00081040789E468012564698D403D430581FF -:101AC00023600023A2606360F0BC01F08DB90000C8 -:101AD00070B50223002504460370A0F84C5080F82E -:101AE0004E5080F84F5005814581C56005614561C4 -:101AF000856180F8345000F0C7FF63681B6823B12C -:101B000029462046BDE87040184770BD43680278FA -:101B10001B6880F85020052202700BB10421184781 -:101B200070470000436890F850201B6802700BB1AA -:101B3000052118477047000090F8343070B504460E -:101B400013B1002380F8343004F14402204601F040 -:101B5000B5F863689B6863BB94F8445015F0600661 -:101B600015D194F8453005F07F0545EA032540F28C -:101B700002339D4200F00E815BD8022D00F0DC8024 -:101B80003FD8002D00F08780012D00F0CF8000218C -:101B9000204601F0EBFA0021204601F0DDFA6368EF -:101BA0001B6813B1062120469847062384F8343079 -:101BB00070BD204698470028CED094F84B2094F86A -:101BC0004A3043EA0223E26B934238BFE36394F95D -:101BD0004430E56B002B4FF0200380F2FD80002D98 -:101BE00000F0EC80092284F8342083F3118800216E -:101BF000E36BA26B2046FFF759FF002383F31188A4 -:101C000070BDB5F5817F00F0B180B5F5407F49D05A -:101C1000B5F5807FBBD194F84630012BB7D1B4F82D -:101C20004C3023F00203A4F84C30A663E66326642C -:101C3000C3E740F201639D421ED8B5F5C06F3BD2A9 -:101C4000B5F5A06FA3D1B4F84430B3F5A06F0ED1B1 -:101C500094F8463084F84E30204600F06DFF6368FB -:101C60001B6813B1012120469847032323700023EA -:101C7000A363E3632364A0E7B5F5106F32D040F6A9 -:101C800002439D4252D0B5F5006F80D104F14F035D -:101C9000A363012324E004F14C03A3630223E36361 -:101CA00025648AE794F84630012B7FF470AFB4F8CE -:101CB0004C3043F00203B6E794F84920616894F889 -:101CC00048304D6894F8471043EA0223204694F8C0 -:101CD0004620A84700283FF45AAF4368A36303682F -:101CE000E363A4E72378042B10D1202383F3118826 -:101CF0002046FFF7BBFE86F31188636884F84F60C7 -:101D00001B68032121700BB12046984794F8463098 -:101D1000002BACD084F84F300423237063681B6819 -:101D2000002BA4D0022120469847A0E7374BA3639D -:101D30000223E36300239DE794F8481011F0800F1D -:101D4000204601F00F010ED000F0AAFF012806D0B6 -:101D500002287FF41CAF2E4BA363E06367E72D4B93 -:101D6000A363E56363E700F08DFFEFE794F8463087 -:101D7000002B7FF40CAF94F8483013F00F013FF4C0 -:101D800076AF1A06204602D501F004FA6FE701F09B -:101D9000F7F96CE794F84630002B7FF4F8AE94F82E -:101DA000483013F00F013FF462AF1B06204602D506 -:101DB00001F0DCF95BE701F0CFF958E7142284F871 -:101DC000342083F311882B462A4629462046FFF704 -:101DD0005BFE85F3118870BD5DB1152284F8342057 -:101DE00083F311880021E36BA26B2046FFF74CFEC2 -:101DF00003E70B2284F8342083F311882B462A460C -:101E000029462046FFF752FEE3E700BF943C000856 -:101E10008C3C0008903C000838B590F834300446FB -:101E2000152B29D8DFE803F03E28282828283E284B -:101E3000280B293928282828282828283E3E90F8C9 -:101E40004B1090F84A20C36B42EA01229A4214D9FF -:101E5000C268128AB3FBF2F502FB15356DB9202377 -:101E600083F311882B462A462946FFF71FFE85F388 -:101E700011880A2384F8343038BD142384F83430B0 -:101E8000202383F3118800231A4619462046FFF7C2 -:101E9000FBFD002383F3118838BD036C03B1984721 -:101EA0000023E7E7002101F061F90021204601F05D -:101EB00053F963681B6813B106212046984706232F -:101EC000D8E7000090F83420152A38B5044622D807 -:101ED0000123934040F6416213421DD113F4801553 -:101EE0000FD19B0217D50B2380F83430202383F3C6 -:101EF00011882B462A462946FFF7D8FD85F311881D -:101F000038BDC3689B695B682BB9036C03B1984704 -:101F1000002384F8343038BD002101F027F9002176 -:101F2000204601F019F963681B6813B106212046A9 -:101F300098470623EDE70000024B00221B605B6020 -:101F40009A60704754330020002303748268054B65 -:101F50001B6899689142FBD25A6803604260106026 -:101F6000586070475433002008B5202383F311884C -:101F7000037C032B05D0042B0DD02BB983F31188E0 -:101F800008BD436900221A604FF0FF334361FFF739 -:101F9000DBFF0023F2E790E80C001A600268536050 -:101FA000F2E70000002303748268054B1B68996800 -:101FB0009142FBD85A6803604260106058607047D5 -:101FC00054330020054B19690874186802681A60B8 -:101FD0005360186101230374FEF796B9543300204F -:101FE00030B54B1C87B005460A4C10D023690A4A0D -:101FF00001A800F0D3F82846FFF7E4FF049B13B1D3 -:1020000001A800F007F92369586907B030BDFFF750 -:10201000D9FFF8E754330020691F000838B50C4D8C -:1020200041612B6981689A689142044603D8BDE8F2 -:102030003840FFF789BF1846FFF786FF01232C6160 -:10204000014623742046BDE83840FEF75DB900BF65 -:1020500054330020044B1A681B6990689B689842AF -:1020600094BF0020012070475433002010B5084C65 -:10207000236820691A6822605460012223611A745F -:10208000FFF790FF01462069BDE81040FEF73CB91C -:10209000543300208260022202740022427470478E -:1020A0008368A3F17C0243F80C2C026943F83C2CB2 -:1020B000426943F8382C074A43F81C2CC26843F89D -:1020C000102C022203F8082C002203F8072CA3F19D -:1020D000180070472103000810B5202383F31188EE -:1020E000FFF7DEFF00210446FFF798FF002383F38C -:1020F0001188204610BD0000024B1B6958610F205B -:10210000FFF760BF54330020202383F31188FFF7CB -:10211000F3BF000008B50146202383F3118808208F -:10212000FFF75EFF002383F3118808BD49B1064B1A -:1021300042681B6918605A60136043600420FFF70F -:102140004FBF4FF0FF307047543300200368984270 -:1021500006D01A680260506059611846FFF7F4BE55 -:102160007047000038B504460D462068844200D10F -:1021700038BD036823605C604561FFF7E5FEF4E766 -:10218000054B03F114025A619A614FF0FF32DA6194 -:1021900000221A62704700BF54330020F8B5036173 -:1021A0001A4BC2605C6A1A4B1A46022952F8145F35 -:1021B00038BF0221954206461F460AD158619861F0 -:1021C0001C620560456081600819BDE8F84001F0B7 -:1021D000B9B9186AAB68241A0C1902D3E41A2D682D -:1021E00004E09C4202D2204401F0BCF9AB689C425E -:1021F000F4D86B68736035601E606E60B460A96867 -:102200004FF0FF33091BA960FB61F8BD000C0040D3 -:102210005433002010B41A4C234653F8141F814243 -:1022200010D0416802680A60026851609A424FF01B -:102230000001C16003D0936881680B4493605DF82E -:10224000044B70470A68626100209A425360C8607C -:1022500003D15DF8044B01F07FB9936888680344AB -:102260009360084A206A526A121A9342E7D9991A6F -:10227000012998BF931C18445DF8044B01F072B912 -:1022800054330020000C004000207047FEE700009F -:10229000704700004FF0FF3070470000022906D061 -:1022A000032906D00129064818BF002070470548B9 -:1022B0007047032A9ABF044800EBC2000020704711 -:1022C000683D00081C3D00080824002070B59AB045 -:1022D00001AD064608462946144600F095F8284602 -:1022E000FEF7A8FDC0B2431C5B0086E8180023700F -:1022F00003236370002302341946DAB2904204F1DA -:10230000020401D81AB070BDEA5C04F8022C04F88B -:10231000011C0133F1E7000008B5202383F3118885 -:102320000348FFF7E9FA002383F3118808BD00BFD3 -:102330009433002010B50446052916D8DFE801F0D3 -:1023400016150316161D202383F311880E4A01214A -:10235000FFF772FB20460D4A0221FFF76DFB0C4888 -:10236000FFF790FA002383F3118810BD202383F335 -:1023700011880748FFF75CFAF4E7202383F31188FC -:102380000348FFF773FAEDE7983C0008BC3C0008EF -:102390009433002038B50C4D0C4C0D492A4604F1FD -:1023A0000800FFF793FF05F1CA0204F11000094984 -:1023B000FFF78CFF05F5CA7204F118000649BDE865 -:1023C0003840FFF783BF00BF5C380020082400209E -:1023D000E83C0008F53C0008033D000870B50446E1 -:1023E00008460D46FEF726FDC6B2204601340378A6 -:1023F0000BB9184670BD32462946FEF703FD00288A -:10240000F3D1012070BD00002DE9F84F05460C46C0 -:10241000FEF710FD2B49C6B22846FFF7DFFF08B1D3 -:102420000336F6B228492846FFF7D8FF08B1103620 -:10243000F6B2632E0DD8DFF88C80DFF88C90234F36 -:10244000DFF890A0DFF890B02E7846B92670BDE88E -:10245000F88F29462046BDE8F84F01F099BB252E9C -:102460002CD1072241462846FEF7CCFC58B9DBF8B0 -:1024700000302360DBF804306360BBF80830238150 -:1024800007350A34E0E7082249462846FEF7BAFC39 -:10249000A0B90F4BA21C13F8011F09095345C95DD0 -:1024A00002F8021C197801F00F0102F10202C95D65 -:1024B00002F8031CEFD118340835C5E72670013542 -:1024C0000134C1E7883D0008033D00089B3D00083A -:1024D0000F7AFF1F1B7AFF1F903D0008BFF34F8F3D -:1024E000024AD368DB03FCD4704700BF003C0240C3 -:1024F00008B5094B1B7873B9FFF7F0FF074B1A6952 -:10250000002ABFBF064A5A6002F188325A601A6830 -:1025100022F480621A6008BDBA3A0020003C0240F2 -:102520002301674508B50B4B1B7893B9FFF7D6FF1E -:10253000094B1A6942F000421A611A6842F480524B -:102540001A601A6822F480521A601A6842F4806293 -:102550001A6008BDBA3A0020003C0240172870B546 -:1025600013D80B4A0B4C137863B90B4E4FF0006134 -:1025700044F8231056F823500133182B2944F7D17F -:102580000123137054F8200070BD002070BD00BFFF -:102590001C3B0020BC3A0020AC3D0008014B53F826 -:1025A00020007047AC3D000818207047172810B570 -:1025B000044601D9002010BDFFF7D0FF064B53F8A9 -:1025C00024301844C21A0BB9012010BD1268013220 -:1025D000F0D1043BF6E700BFAC3D0008172810B56A -:1025E000044629D8FFF77AFFFFF782FF1349F32348 -:1025F000CB600C23B0FBF3F203FB1200D30143EAE0 -:10260000C003DBB243F4007343F002030B610B69B8 -:1026100043F480330B61FFF761FF2046FFF79EFF15 -:10262000074B53F8241000F0DDF8FFF77BFF20463E -:10263000BDE81040FFF7BABF002010BD003C0240CB -:10264000AC3D00082DE9F84312F00103154640D1D6 -:102650008218B2F1026F3CD22C4B1B6813F00103BD -:1026600037D02B4CFFF744FFF323E360FFF736FF2F -:1026700040F20127032D01D9830713D0244C0F46C4 -:10268000401A40F20118EB1B0B44012B00EB07062C -:10269000236924D823F001032361FFF743FF0120BE -:1026A000BDE8F883236923F44073236123693B4326 -:1026B000236151F8046B0660BFF34F8FFFF70EFFE5 -:1026C00003689E4208D0236923F001032361FFF7CA -:1026D00029FF0020BDE8F883043D0430CAE723F455 -:1026E00040732361236943EA08032361B94637F83D -:1026F000023B3380BFF34F8FFFF7F0FE3688B9F807 -:102700000030B6B2B342BED0DDE700BF00380240B1 -:10271000003C0240084908B50B7828B153B9FFF7CF -:10272000E7FE01230B7008BD23B1BDE80840087027 -:10273000FFF7F8BE08BD00BFBA3A002010B502444A -:10274000064B0439D2B2904200D110BD441C00B2F5 -:1027500053F8200041F8040FE0B2F4E7502800409D -:10276000104B30B51C6F240407D41C6F44F4007464 -:102770001C671C6F44F400441C670B4C236843F433 -:10278000807323600244094B0439D2B2904200D1D5 -:1027900030BD441C00B251F8045F43F82050E0B251 -:1027A000F4E700BF003802400070004050280040AD -:1027B00007B5012201A90020FFF7C0FF019803B06F -:1027C0005DF804FB13B50446FFF7F2FFA04206D004 -:1027D00002A9012241F8044D0020FFF7C1FF02B019 -:1027E00010BD000070470000034B1B689B0042BFF8 -:1027F000024B01221A707047743802401D3B0020C2 -:10280000014B1878704700BF1D3B0020064A5368F3 -:1028100023F001035360EFF30983683383F30988DE -:10282000002383F31188704730EF00E010B52023B8 -:1028300083F31188104B5B6813F4006318D0F1EE3A -:10284000103AEFF309844FF0807344F84C3C0B4B83 -:10285000DB6844F8083CA4F1680383F30988FFF7B8 -:10286000F9FB18B1064B44F8503C10BD054BFAE794 -:1028700083F3118810BD00BF00ED00E030EF00E0F1 -:10288000310300083403000870470000FEE7000031 -:10289000084A094B09498B4204D3094A0021934253 -:1028A00005D3704752F8040F43F8040BF3E743F8DD -:1028B000041BF4E7843F0008903D0020903D002079 -:1028C000903D0020836D30B500229D68446D114617 -:1028D0004FF0FF3004EB421301329542C3F8001968 -:1028E000C3F81019C3F80809C3F8001BC3F8101B7C -:1028F000C3F8080BEED24FF00113C4F81C3830BDFA -:10290000890141F02001016103699B06FCD412207A -:1029100000F0B4BE204B03EB80022DE9F047D2F863 -:102920000CE05D6DDEF81420461CD2F800C005EB0B -:10293000063605EB4018516861450BD3D5F83428AD -:10294000012303FA00F022EA0000C5F83408184613 -:10295000BDE8F087BEF81040ACEB0103A34228BFEE -:102960002346D8F81849A4B2B3EB840F10D8946862 -:102970001F46A4F1040959F804AFC6F800A0042FBB -:1029800001D9043FF7E71C440B4494605360D2E73D -:102990000020BDE8F08700BF203B002010B5054CAB -:1029A0002046FFF729F84FF0A0436365024BA3656B -:1029B00010BD00BF203B0020303E00080378012BF3 -:1029C00070B5054650D12A4B446D98421BD1294B16 -:1029D0005A6B42F080025A635A6D42F080025A6587 -:1029E0005A6D5A6942F080025A615A6922F0800297 -:1029F0005A610E2143205B69FEF768FC1E4BE360C1 -:102A00001E4BC4F800380023C4F8003EC0232360E6 -:102A10006E6D4FF45023A3633369002BFCDA01235E -:102A200033610C2000F02AFE3369DB07FCD412204E -:102A300000F024FE3369002BFCDA0026A66028464D -:102A4000FFF740FF6B68C4F81068DB68C4F81468CF -:102A5000C4F81C684BB90A4BA3614FF0FF336361A4 -:102A6000A36843F00103A36070BD064BF4E700BF09 -:102A7000203B0020003802404014004003002002A8 -:102A8000003C30C0083C30C0F8B5446D054600211C -:102A90002046FFF735FFA96D00234FF001128F6824 -:102AA000C4F834384FF00066C4F81C284FF0FF30EB -:102AB00004EB431201339F42C2F80069C2F8006B75 -:102AC000C2F80809C2F8080BF2D20B686A6DEB6510 -:102AD000636210231361166916F01006FBD11220F1 -:102AE00000F0CCFDD4F8003823F4FE63C4F80038BD -:102AF000A36943F4402343F01003A3610923C4F8FE -:102B00001038C4F814380A4BEB604FF0C043C4F8D7 -:102B1000103B084BC4F8003BC4F81069C4F80039F6 -:102B2000EB6D03F1100243F48013EA65A362F8BD74 -:102B30000C3E000840800010426D90F84E10D2F814 -:102B4000003823F4FE6343EA0113C2F800387047EB -:102B50002DE9F0410EB200EB86080D46D8F80C10B6 -:102B60000F6807F00303022B50D0032B50D03D4ACF -:102B70003D4F012B18BF1746446D4FEA451E04EB2D -:102B80000E030022C3F8102B8A6905F1100C002AED -:102B900040D04A8A05F158035B013A43E2500123D1 -:102BA000D4F81C2803FA0CF31343A6444A69C4F86A -:102BB0001C380023CEF8103905F13F03002A39D024 -:102BC0000A8A898B9208012988BF4A43C16D04EBA8 -:102BD0008303561841EA0242C66529465A602046D8 -:102BE000FFF78EFED8F80C301B8A43EA85531F434B -:102BF00005F148035B01E7500123D4F81C2803FAD0 -:102C000005F51543C4F81C58BDE8F081174FB3E72C -:102C1000174FB1E704EB4613D3F8002B22F4004220 -:102C2000C3F8002BD4F81C28012303FA0CF322EA82 -:102C30000303BAE704EB83030E4A5A6004EB46161B -:102C400029462046FFF75CFED6F8003923F40043FE -:102C5000C6F80039D4F81C38012202FA05F523EA37 -:102C60000505CFE7008000100080041000800810E8 -:102C700000800C1000040002826D1268C265FFF72C -:102C800021BE00005831436D49015B5813F40040E8 -:102C900004D013F4001F14BF01200220704700006D -:102CA0004831436D49015B5813F4004004D013F4DC -:102CB000001F14BF012002207047000000EB8101BB -:102CC000CB68196A0B6813604B685360704700004B -:102CD00000EB810330B5DD68AA691368D36019B9C8 -:102CE000402B84BF402313606B8A1468426D1C44E0 -:102CF000013CB4FBF3F46343033323F0030302EB1F -:102D0000411043EAC44343F0C043C0F8103B2B6872 -:102D100003F00303012B09B20ED1D2F8083802EBFD -:102D2000411013F4807FD0F8003B14BF43F0805370 -:102D300043F00053C0F8003B02EB4112D2F8003BD5 -:102D400043F00443C2F8003B30BD00002DE9F041E0 -:102D5000244D6E6D06EB40130446D3F8087BC3F890 -:102D6000087B38070AD5D6F81438190706D505EBBD -:102D700084032146DB6828465B689847FA072FD50D -:102D8000D6F81438DB072BD505EB8403D968CCB90A -:102D90008B69488A5E68B6FBF0F200FB12628AB962 -:102DA0001868DA6890420DD2121A83E814002023C2 -:102DB00083F311880B482146FFF78AFF84F31188BB -:102DC000BDE8F081012303FA04F26B8923EA0203D0 -:102DD0006B81CB6823B121460248BDE8F04118471A -:102DE000BDE8F081203B002000EB810370B5DD6879 -:102DF000436D6C692668E6604A0156BB1A444FF47D -:102E00000020C2F810092A6802F00302012A0AB25F -:102E10000ED1D3F8080803EB421410F4807FD4F8E5 -:102E2000000914BF40F0805040F00050C4F8000981 -:102E300003EB4212D2F8000940F00440C2F8000946 -:102E4000D3F83408012202FA01F10143C3F834181F -:102E500070BD19B9402E84BF4020206020682E8AA2 -:102E6000841940F00050013C1A44B4FBF6F440EAE7 -:102E7000C440C6E7F8B504461E48456D05EB44134B -:102E8000D3F80869C3F80869F10717D5D5F81038E1 -:102E9000DA0713D500EB8403D9684B691F68DA6839 -:102EA000974218D2D21B00271A605F60202383F359 -:102EB00011882146FFF798FF87F31188330617D54D -:102EC000D5F834280123A340134211D02046BDE891 -:102ED000F840FFF71FBD012303FA04F2038923EA38 -:102EE000020303818B68002BE8D021469847E5E771 -:102EF000F8BD00BF203B002096482DE9F84F456DF6 -:102F00006E69AB691E4016F4805F6E61044605D0A1 -:102F1000FEF7DEFDBDE8F84FFFF788BC002E12DAA1 -:102F2000D5F8003E8B489B071EBFD5F8003E23F026 -:102F30000303C5F8003ED5F8043823F00103C5F8B3 -:102F40000438FEF7EFFD370502D58248FEF7DEFDB7 -:102F5000B0040CD5D5F8083813F0060FEB6823F44D -:102F600070530CBF43F4105343F4A053EB6031078C -:102F700004D56368DB680BB176489847F2025AD4EF -:102F8000B3020CD5D4F85480DFF8C8A100274FF065 -:102F90000109A36D9B68F9B28B4280F08780F70628 -:102FA00019D5616D0A6AC2F30A1702F00F0302F421 -:102FB000F012B2F5802F00F0A180B2F5402F0AD1B7 -:102FC00004EB830301F58051DB68186A00231A467D -:102FD0009F4240F087803003D5F8184813D5E103AD -:102FE00002D50020FFF7B2FEA20302D50120FFF7B1 -:102FF000ADFE630302D50220FFF7A8FE270302D52A -:103000000320FFF7A3FE750384D5E00702D5002057 -:10301000FFF730FFA10702D50120FFF72BFF620762 -:1030200002D50220FFF726FF23077FF573AF0320A9 -:10303000FFF720FF6EE7D4F85480DFF818A10027CF -:103040004FF00109A36D9B685FFA87FB5B4597D33F -:1030500008EB4B13D3F8002902F44022B2F5802F7D -:1030600022D1D3F80029002A1EDAD3F8002942F031 -:103070009042C3F80029D3F80029002AFBDB594607 -:10308000606DFFF73DFC228909FA0BF322EA030386 -:10309000238104EB8B03DB689B6813B159465046D0 -:1030A00098475846FFF736FC0137CBE708EB41124B -:1030B000D2F8003B03F44023B3F5802F10D1D2F8AF -:1030C000003B002B0CDA628909FA01F322EA0303C0 -:1030D000638104EB8103DB68DB680BB150469847E2 -:1030E000013756E79C0708BF0A68072B98BF027094 -:1030F00003F101039CBF120A013069E7023304EBBC -:10310000830201F58051526890690268D0F808C0C6 -:103110004068A2EB000E0022104697420AD104EB51 -:10312000830463689B699A683A449A605A681744B2 -:103130005F6050E712F0030F08BF0868964588BF2C -:103140008CF8000002F1010284BF000A0CF1010CAE -:10315000E3E700BF203B0020436D03EB4111D1F8B2 -:10316000003B43F40013C1F8003B7047436D03EB91 -:103170004111D1F8003943F40013C1F80039704708 -:10318000436D03EB4111D1F8003B23F40013C1F868 -:10319000003B7047436D03EB4111D1F8003923F434 -:1031A0000013C1F80039704730B5039C0172043335 -:1031B00004FB0325C361049B03630021059B00609E -:1031C0004060C16042610261856104624262816265 -:1031D000C162436330BD00000022416A4161016168 -:1031E000C2608262C2626FF00101FEF7BBBF0000E5 -:1031F00003694269934203D1C2680AB10020704753 -:10320000181D704703691960C2680132C260C26943 -:10321000134482690361934224BF436A036100211E -:10322000FEF794BF38B504460D46E3683BB16269CA -:10323000131D1268A3621344E362002038BD237A91 -:1032400033B929462046FEF771FF0028EDDA38BD74 -:103250006FF00100FBE70000C368C269013BC36077 -:103260004369134482694361934224BF436A4361C3 -:1032700000238362036B03B11847704770B52023A6 -:10328000044683F31188866A3EB9FFF7CBFF0546F3 -:1032900018B186F31188284670BDA36AE26A13F854 -:1032A000015BA362934202D32046FFF7D5FF0023C0 -:1032B00083F31188EFE700002DE9F84F04460E462E -:1032C00090469946202787F311880025AA46D4F80E -:1032D00028B0BBF1000F09D149462046FFF7A2FFF5 -:1032E00020B18BF311882846BDE8F88FA16AE36A04 -:1032F000A8EB050B5B1A9B4528BF9B46BBF1400F13 -:103300001BD9334601F1400251F8040B43F8040B7A -:103310009142F9D1A36A40334036A3624035A26A94 -:10332000E36A9A4202D32046FFF796FF8AF3118898 -:103330004545D8D287F31188C9E730465A46FDF78C -:1033400057FDA36A5B445E44A3625D44E7E7000067 -:1033500010B5029C0172043303FB0421C3610023F6 -:103360008362C362039B0363049B00604060C4608C -:1033700042610261816104624262436310BD0000E8 -:10338000026AC260426A4261026100228262C262D3 -:103390006FF00101FEF7E6BE436902699A4203D16C -:1033A000C2680AB100207047184650F8043B0B6011 -:1033B00070470000C368C2690133C36043691344A6 -:1033C00082694361934224BF436A43610021FEF74F -:1033D000BDBE000038B504460D46E3683BB1236925 -:1033E0001A1DA262E2691344E362002038BD237A09 -:1033F00033B929462046FEF799FE0028EDDA38BD9C -:103400006FF00100FBE7000003691960C268013A30 -:10341000C260C269134482690361934224BF436A54 -:10342000036100238362036B03B1184770470000F8 -:1034300070B5202304460E4683F31188856A35B99A -:103440001146FFF7C7FF10B185F3118870BDA36A5D -:103450001E70A36AE26A01339342A36204D3E16956 -:1034600020460439FFF7D0FF002080F3118870BD9B -:103470002DE9F84F04460D4691469A464FF0200834 -:1034800088F311880026B346A76A4FB951462046F3 -:10349000FFF7A0FF20B187F311883046BDE8F88F11 -:1034A000A06AE76AA9EB06033F1A9F4228BF1F469E -:1034B000402F1BD905F1400355F8042B40F8042B8D -:1034C0009D42F9D1A36A4033A3624036A26AE36AFF -:1034D0009A4204D3E16920460439FFF795FF8BF344 -:1034E00011884E45D9D288F31188CDE729463A464E -:1034F000FDF77EFCA36A3B443D44A3623E44E5E7FE -:10350000026943699A4203D1C3681BB918467047E0 -:103510000023FBE7836A002BF8D0043B9B1AF5D00D -:103520001360C368013BC360C3691A4483690261C5 -:103530009A4224BF436A0361002383620123E5E7C3 -:1035400000F034B9034B002258631A610222DA609A -:10355000704700BF000C0040014B0022DA6070474A -:10356000000C0040014B5863704700BF000C004046 -:10357000FEE7000010B5174CFEF7DEFCFEF700FE7C -:10358000802215492046FEF785FD012344F8180CDA -:103590000374124B124AD96821F4E0610904090C42 -:1035A0000A431049DA60CA6842F08072CA600E4964 -:1035B0000A6842F001020A601022DA77202283F8BA -:1035C0002220002383F3118862B60848BDE810402A -:1035D000FEF782BD7C3300203C3E000800ED00E099 -:1035E0000003FA05F0ED00E0001000E0443E0008A2 -:1035F0002DE9F84F1F4CDFF88090656904F114073E -:103600004FF00008D9F82430266AAA689E1B96421B -:103610001DD34FF0200AAA68236AD5F80CB01344D2 -:1036200023622B68BB425F60A6EB02066361C5F8AC -:103630000C8001D1FFF790FF88F311882869D847E3 -:103640008AF311886569AB689E42E4D2DAE7626961 -:10365000BA420CD0916823628E1B9660A86802283B -:103660002CBF1818981CBDE8F84FFFF77BBFBDE8CA -:10367000F88F00BF54330020000C0040034B596802 -:103680005A68521A9042FBD8704700BF001000E001 -:103690004B6843608B688360CB68C3600B69436190 -:1036A0004B6903628B6943620B68036070470000DB -:1036B00008B5224B22481A6940F2FF110A431A61E9 -:1036C0001A6922F4FF7222F001021A611A691A6B58 -:1036D0000A431A631A6D0A431A651A4A1B6D11468A -:1036E000FFF7D6FF184802F11C01FFF7D1FF17487A -:1036F00002F13801FFF7CCFF154802F15401FFF742 -:10370000C7FF144802F17001FFF7C2FF124802F12F -:103710008C01FFF7BDFF114802F1A801FFF7B8FFC8 -:103720000F4802F1C401FFF7B3FF0E4802F1E001B8 -:10373000FFF7AEFFBDE8084000F0A4B80038024033 -:1037400000000240643E00080004024000080240FD -:10375000000C024000100240001402400018024019 -:10376000001C02400020024008B500F0FFF9FFF7FE -:1037700001FFFFF739F8BDE80840FEF70BBE000077 -:1037800070470000084B1A69920710B508D500244D -:103790001C61202383F31188FFF72AFF84F311882B -:1037A000BDE81040FFF742B8000C0040104B1A6C07 -:1037B00042F008021A641A6E42F008021A660D4AB4 -:1037C0001B6E936843F0080393600B4B53229A627D -:1037D0004FF0FF32DA6200229A615A63DA605A606F -:1037E00001225A6108211A603220FDF76FBD00BF27 -:1037F00000380240002004E0000C00401F4B1A6912 -:103800006FEAC2526FEAD2521A611A69C2F3080211 -:103810001A614FF0FF301A695A69586100215A69DC -:1038200059615A691A6A62F080521A621A6A02F081 -:1038300080521A621A6A5A6A58625A6A59625A6AF5 -:103840001A6C42F080521A641A6E42F080521A6664 -:103850001A6E0B4A106840F480701060186F00F404 -:103860004070B0F5007F1EBF4FF4803018671967B5 -:10387000536823F40073536000F058B900380240D5 -:1038800000700040324B4FF080521A64314A4FF4BE -:10389000404111601A6842F001021A601A689207EA -:1038A000FCD59A6822F003029A60294B19469A685F -:1038B00012F00C02FBD1186800F0F90018609A6051 -:1038C0001A6842F480321A600B689B03FCD54B6F78 -:1038D00043F001034B671E4B5A6F9007FCD51E4AFD -:1038E0005A601A6842F080721A601A4A5368590482 -:1038F000FCD5174B1A689201FCD5184A9A6003222E -:10390000C3F88C20164B1A68164B9A42164B1BD1E3 -:10391000164A1168164A914216D140F205121A60F1 -:103920000B4B9A6842F002029A609A6802F00C020D -:10393000082AFAD15A6C42F480425A645A6E42F410 -:1039400080425A665B6E704740F20572E7E700BF3F -:103950000038024000700040185440070094883836 -:10396000002004E011640020003C024000ED00E073 -:1039700041C20F41084A08B5536911680B4003F072 -:103980000103536123B1054A13680BB1506898478E -:10399000BDE80840FEF74ABF003C01409C250020DE -:1039A000084A08B5536911680B4003F002035361DC -:1039B00023B1054A93680BB1D0689847BDE8084029 -:1039C000FEF734BF003C01409C250020084A08B5A2 -:1039D000536911680B4003F00403536123B1054A96 -:1039E00013690BB150699847BDE80840FEF71EBF48 -:1039F000003C01409C250020084A08B55369116825 -:103A00000B4003F00803536123B1054A93690BB1DE -:103A1000D0699847BDE80840FEF708BF003C014068 -:103A20009C250020084A08B5536911680B4003F033 -:103A30001003536123B1054A136A0BB1506A9847CA -:103A4000BDE80840FEF7F2BE003C01409C25002086 -:103A5000174B10B55C691A68144004F478725A6107 -:103A6000A30604D5134A936A0BB1D06A984760063F -:103A700004D5104A136B0BB1506B9847210604D53F -:103A80000C4A936B0BB1D06B9847E20504D5094AF9 -:103A9000136C0BB1506C9847A30504D5054A936C81 -:103AA0000BB1D06C9847BDE81040FEF7BFBE00BF19 -:103AB000003C01409C2500201A4B10B55C691A6837 -:103AC000144004F47C425A61620504D5164A136D11 -:103AD0000BB1506D9847230504D5134A936D0BB174 -:103AE000D06D9847E00404D50F4A136E0BB1506EA9 -:103AF0009847A10404D50C4A936E0BB1D06E984739 -:103B0000620404D5084A136F0BB1506F9847230421 -:103B100004D5054A936F0BB1D06F9847BDE81040AC -:103B2000FEF784BE003C01409C250020062108B51C -:103B30000846FDF7CBFB06210720FDF7C7FB062152 -:103B40000820FDF7C3FB06210920FDF7BFFB062176 -:103B50000A20FDF7BBFB06211720FDF7B7FB062166 -:103B60002820BDE80840FDF7B1BB000008B5FFF70D -:103B700045FEFDF727FAFDF74FFDFDF73BFFFDF78B -:103B80000FFEFFF7FDFDBDE80840FFF7D9BC0000C0 -:103B9000034611F8012B03F8012B002AF9D17047D5 -:103BA000121012131211000053544D3332463F3F8E -:103BB0003F000000012033000010410101105A01B4 -:103BC000031059010710310100000000A83B000854 -:103BD0003F00000013040000083C00083F00000004 -:103BE00019040000123C00083F00000021040000FE -:103BF0001C3C00083F000000943300201C260020DD -:103C0000842A0020EC2E002053544D3332463430A9 -:103C1000780053544D3332463432780053544D3388 -:103C20003246343436585800009600000000000038 -:103C30000000000000000000000000000000000084 -:103C4000E1150008CD15000809160008F515000853 -:103C500001160008ED150008D9150008C515000863 -:103C600015160008000000001917000805170008C5 -:103C7000411700082D1700083917000825170008FC -:103C800011170008FD1600089D170008000000002D -:103C90000100000000000000020000000000000021 -:103CA00045190008AD190008400040002C380020DC -:103CB0003C3800200200000000000000030000006B -:103CC00000000000F11900080000000010000000D2 -:103CD0004C3800200000000001000000000000003F -:103CE000203B0020010102004865782F50726F666A -:103CF00069434E430043756265507572706C652D63 -:103D0000424C002553455249414C250035230008BB -:103D10009D220008B1180008192300084300000084 -:103D2000243D000809024300020100C032090400DA -:103D30000001020201000524001001052401000118 -:103D4000042402020524060001070582030800FF7F -:103D500009040100020A00000007050102400000FA -:103D6000070581024000000012000000703D0008BD -:103D70001201100102000040AE2D051000020102E8 -:103D8000030100000403090425424F415244250069 -:103D900043756265507572706C6500303132333432 -:103DA000353637383941424344454600004000002B -:103DB0000040000000400000004000000000010042 -:103DC00000000200000002000000020000000200EB -:103DD000000002000000020000000200004000009D -:103DE0000040000000400000004000000000010012 -:103DF00000000200000002000000020000000200BB -:103E000000000200000002000000020000000000AC -:103E1000391B0008191E0008C51E0008400040009C -:103E2000803B0020803B002001000000903B0020F0 -:103E30008000000040010000030000006D61696E19 -:103E4000000000005C3E0008983B0020903D0020F0 -:103E500001000000713500080000000069646C6515 -:103E6000000000000500802A00020000AAAAAAAAF9 -:103E70000A000000FCFF00000000000000A00A0093 -:103E80000004050000000000AAAAAAAA00080A006F -:103E9000DFFC0000000000000000000014000054DF -:103EA00000000000AAAAAAAA14000054FFFF000004 -:103EB000000000000000000080699A01000000007E -:103EC000AAAA8AAA40555501FFFF0000007070079A -:103ED000777000000081020100000000AAAAAAAACF -:103EE00000410100FFFF000000000080080000000A -:103EF0000000000000000000AAAAAAAA000000001A -:103F0000FFFF0000000000000000000000000000B3 -:103F100000000000AAAAAAAA00000000FFFF0000FB -:103F20000000000000000000000000000000000091 -:103F30000A00000000000000030000000000000074 -:103F40000000000000000000000000000000000071 -:103F50000000000000000000000000000000000061 -:103F6000FF0096000000000804000000843D0008E7 -:103F70000000000000000000000000000000000041 -:083F8000000000000000000039 +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F074FA01 +:1002500003F074F94FF055301F491B4A91423CBFDF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F052FA03F0A2F96E +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F03ABA000600200022002031 +:1002D0000000000808ED00E00000002000060020FB +:1002E000A03E0008002200204C22002050220020C6 +:1002F00020310020E0010008E0010008E0010008D2 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F098FDFEE701F063 +:1003300027FD00DFFEE7000038B500F0DFFB02F02C +:10034000CFF940B1164B6FF03F01002259720F21D7 +:100350001A729972DA7202F0A9F9054602F0E2F90E +:100360000446C8B90F4B9D4218D001339D4218BFB7 +:10037000044641F2883504BF01240025002002F024 +:100380009FF90CB100F076F800F018FD284600F057 +:10039000C1F800F06FF8F9E70025EFE70546EDE753 +:1003A00000220020010007B008B500F073FBA0F1A7 +:1003B00020035842584108BD07B541F212030221FB +:1003C00001A8ADF8043000F083FB03B05DF804FB36 +:1003D00038B5302383F31188174803680BB101F057 +:1003E00009FE164A144800234FF47A7101F0F8FD13 +:1003F000002383F31188124C236813B12368013B57 +:100400002360636813B16368013B63600D4D2B7813 +:1004100033B963687BB9022000F03AFC3223636091 +:100420002B78032B07D163682BB9022000F030FC36 +:100430004FF47A73636038BD50220020D103000866 +:100440007023002068220020084B187003280CD865 +:10045000DFE800F008050208022000F00FBC0220CF +:1004600000F002BC024B00225A6070476822002054 +:1004700070230020234B244A10B51C461968013113 +:100480003FD004339342F9D16268A24239D31F4B63 +:100490009B6803F1006303F580439A4231D2002048 +:1004A00000F046FB0220FFF7CFFF194B1A6C002229 +:1004B0001A64196E1A66196E596C5A64596E5A6626 +:1004C0005A6E5A6942F080025A615A6922F08002DB +:1004D0005A615A691A6942F000521A611A6922F087 +:1004E00000521A611B6972B64FF0E0233021C3F845 +:1004F000084DD4E9003281F311889D4683F30888C2 +:10050000104710BD004000082040000800220020D5 +:10051000003802402DE9F04F93B0AA4B0090202202 +:10052000FF210AA89D6800F0F3FBA74A1378A3B93E +:10053000A648012103601170302383F311880368FA +:100540000BB101F057FDA24AA04800234FF47A7185 +:1005500001F046FD002383F31188009B13B19D4BEE +:10056000009A1A609C4A009C1378032B1EBF00233C +:100570001370984A4FF0000A18BF5360D34656468E +:10058000D146012000F07AFB24B1924B1B68002B6E +:1005900000F01182002000F07DFA0390039B002BF5 +:1005A000F2DB012000F060FB039B213B162BE8D817 +:1005B00001A252F823F000BF150600083D0600080E +:1005C000D10600088305000883050008830500089C +:1005D0005B0700082B09000845080008A708000869 +:1005E000CF080008F508000883050008070900087F +:1005F0008305000879090008B5060008830500088E +:10060000BD09000821060008B5060008830500089A +:10061000A70800080220FFF7C7FE002840F0F58178 +:10062000009B0221BAF1000F08BF1C4605A841F249 +:100630001233ADF8143000F04BFAA2E74FF47A70A1 +:1006400000F028FA071EEBDB0220FFF7ADFE0028C2 +:10065000E6D0013F052F00F2DA81DFE807F0030A58 +:100660000D10133605230593042105A800F030FA78 +:1006700017E054480421F9E758480421F6E75848A0 +:100680000421F3E74FF01C08404600F053FA08F14C +:1006900004080590042105A800F01AFAB8F12C0FFF +:1006A000F2D1012000FA07F747EA0B0B5FFA8BFB48 +:1006B0004FF0000900F078FB26B10BF00B030B2B79 +:1006C00008BF0024FFF778FE5BE746480421CDE72A +:1006D000002EA5D00BF00B030B2BA1D10220FFF7AE +:1006E00063FE074600289BD0012000F021FA02207B +:1006F000FFF7AAFE00261FFA86F8404600F028FA07 +:10070000044690B10021404600F032FA013600283C +:10071000F1D1BA46044641F21213022105A8ADF800 +:1007200014303E4600F0D4F92BE70120FFF78CFE91 +:100730002546244B9B68AB4207D9284600F0FAF9BE +:10074000013040F067810435F3E7234B00251D702D +:10075000204BBA465D603E46ACE7002E3FF460AFEA +:100760000BF00B030B2B7FF45BAF0220FFF76CFE4B +:10077000322000F08FF9B0F10008FFF651AF18F009 +:1007800003077FF44DAF0F4A926808EB05039342CD +:100790003FF646AFB8F5807F3FF742AF124B01936B +:1007A000B84523DD4FF47A7000F074F90390039A92 +:1007B000002AFFF635AF019B039A03F8012B01379E +:1007C000EDE700BF002200206C2300205022002013 +:1007D000D10300087023002068220020042200209A +:1007E000082200200C2200206C220020C820FFF7E5 +:1007F000DBFD074600283FF413AF1F2D11D8C5F1CC +:10080000200242450AAB25F0030028BF4246834937 +:100810000192184400F056FA019A8048FF2100F036 +:1008200077FA4FEAA8037D490193C8F38702284667 +:1008300000F076FA064600283FF46DAF019B05EB09 +:10084000830537E70220FFF7AFFD00283FF4E8AE4D +:1008500000F0BAF900283FF4E3AE0027B846704B29 +:100860009B68BB4218D91F2F11D80A9B01330ED0A9 +:1008700027F0030312AA134453F8203C0593404683 +:10088000042205A900F0F6FA04378046E7E7384667 +:1008900000F050F90590F2E7CDF81480042105A886 +:1008A00000F016F906E70023642104A8049300F081 +:1008B00005F900287FF4B4AE0220FFF775FD00288B +:1008C0003FF4AEAE049800F067F90590E6E7002328 +:1008D000642104A8049300F0F1F800287FF4A0AE8E +:1008E0000220FFF761FD00283FF49AAE049800F063 +:1008F00063F9EAE70220FFF757FD00283FF490AEC6 +:1009000000F072F9E1E70220FFF74EFD00283FF406 +:1009100087AE05A9142000F06DF904210746049064 +:1009200004A800F0D5F83946B9E7322000F0B2F853 +:10093000071EFFF675AEBB077FF472AE384A9268A9 +:1009400007EB090393423FF66BAE0220FFF72CFD45 +:1009500000283FF465AE27F003074F44B9453FF444 +:10096000A9AE484600F0E6F80421059005A800F07D +:10097000AFF809F10409F1E74FF47A70FFF714FDBD +:1009800000283FF44DAE00F01FF9002844D00A9B28 +:1009900001330BD008220AA9002000F0C1F9002879 +:1009A0003AD02022FF210AA800F0B2F9FFF704FD97 +:1009B0001C4801F059FA13B0BDE8F08F002E3FF447 +:1009C0002FAE0BF00B030B2B7FF42AAE0023642118 +:1009D00005A8059300F072F8074600287FF420AEC2 +:1009E0000220FFF7E1FC804600283FF419AEFFF734 +:1009F000E3FC41F2883001F037FA059800F018FA6C +:100A0000464600F0D1F93C46BBE5064652E64FF0BB +:100A1000000905E6BA467EE637467CE66C220020F1 +:100A200000220020A08601002DE9F84F4FF47A73D0 +:100A3000DFF85880DFF8589006460D4602FB03F7B2 +:100A4000002498F900305A1C5FFA84FA01D0A342BE +:100A500012D159F8240003682A46D3F820B0314651 +:100A60003B46D847854207D1074B012083F800A0B9 +:100A7000BDE8F88F0124E4E7002CFBD04FF4FA70B6 +:100A800001F0F2F90020F3E7B82300201022002043 +:100A90001422002007B50023024601210DF10700B2 +:100AA0008DF80730FFF7C0FF20B19DF8070003B0B5 +:100AB0005DF804FB4FF0FF30F9E700000A4608B587 +:100AC0000421FFF7B1FF80F00100C0B2404208BD31 +:100AD00030B4074B0A461978064B53F82140236877 +:100AE000DD69054B0146AC46204630BC604700BF7F +:100AF000B823002014220020A086010070B501F068 +:100B0000D3FC094E094D3080002428683388834285 +:100B100008D901F0C3FC2B6804440133B4F5804FBD +:100B20002B60F2D370BD00BFBA23002078230020D1 +:100B300001F070BD00F1006000F580400068704772 +:100B400000F10060920000F5804001F0FBBC000065 +:100B5000054B1A68054B1B889B1A834202D9104427 +:100B600001F09CBC0020704778230020BA230020AD +:100B700038B5084D044629B128682044BDE83840FE +:100B800001F0ACBC2868204401F090FC0028F3D0B0 +:100B900038BD00BF7823002010F003030AD1B0F560 +:100BA000047F05D200F10050A0F51040D0F80038C5 +:100BB000184670470023FBE700F10050A0F51040F5 +:100BC000D0F8100A70470000064991F8243033B17C +:100BD0000023086A81F824300822FFF7B1BF012002 +:100BE000704700BF7C230020014B1868704700BF8E +:100BF000002004E070B5194B1D68194B0138C5F38E +:100C00000B0408442D0C04221E88A6420BD15C68FC +:100C10000A46013C824213460FD214F9016F4EB1CD +:100C200002F8016BF6E7013A03F10803ECD18142C7 +:100C30000B4602D22C2203F8012B0A4A05241688FF +:100C4000AE4204D1984284BF967803F8016B013C10 +:100C500002F10402F3D1581A70BD00BF002004E075 +:100C6000503B00083C3B0008022802BF024B4FF4F7 +:100C700080529A61704700BF00100240022802BFF4 +:100C8000024B4FF080529A61704700BF0010024043 +:100C9000022801BF024A536983F4805353617047AD +:100CA0000010024070B504464FF47A764CB1412CE6 +:100CB000254628BF412506FB05F001F0D5F8641B49 +:100CC000F4E770BD10B50023934203D0CC5CC4544C +:100CD0000133F9E710BD000010B5013810F9013FEC +:100CE0003BB191F900409C4203D11AB10131013A64 +:100CF000F4E71AB191F90020981A10BD1046FCE7EC +:100D000003460246D01A12F9011B0029FAD1704796 +:100D100002440346934202D003F8011BFAE77047EE +:100D20002DE9F8431F4D144695F8242007468846C0 +:100D300052BBDFF870909CB395F824302BB9202279 +:100D4000FF2148462F62FFF7E3FF95F82400C0F12A +:100D50000802A24228BF2246D6B24146920005EBC5 +:100D60008000FFF7AFFF95F82430A41B1E44F6B2B5 +:100D7000082E17449044E4B285F82460DBD1FFF7D5 +:100D800023FF0028D7D108E02B6A03EB82038342BC +:100D9000CFD0FFF719FF0028CBD10020BDE8F883A2 +:100DA0000120FBE77C230020024B1A78024B1A70CB +:100DB000704700BFB82300201022002038B5174C20 +:100DC000174D204600F0B6FB2946204600F0DEFB1A +:100DD0002D686A6D936B23F4002393634FF47A704C +:100DE000FFF760FF0F49284600F0D6FC6A6D0E4DF4 +:100DF000936B28680D4943F400239363A0424FF49A +:100E0000E1330B6001D000F0F5FA6868A04204D02D +:100E1000BDE83840054900F0EDBA38BD98280020FB +:100E20005C3C0008643C000814220020A42300203D +:100E300070B50C4B0C4D1E780C4B55F826209A4281 +:100E400004460DD00A4B002114221846FFF760FF1C +:100E50000460014655F82600BDE8704000F0CABAAB +:100E600070BD00BFB8230020142200209828002065 +:100E7000A423002030B5094D0A4491420DD011F849 +:100E8000013B5840082340F30004013B2C4013F081 +:100E9000FF0384EA5000F6D1EFE730BD2083B8EDC0 +:100EA000026843681143016003B1184770470000AE +:100EB000024AD36843F0C003D36070470044004047 +:100EC00010B5054C054A0021204600F071FA044A8D +:100ED000044BC4E9972310BDBC230020B10E0008C9 +:100EE0000044004080DE8002234A037C002918BFB2 +:100EF0000A46012B30B5C0F868220CD11F4B98422E +:100F000009D11F4B196C41F400311964196E41F479 +:100F1000003119661B6EB2F904501468D0F86032C3 +:100F2000D0F85C12002D03EB5403B3FBF4F3BEBF07 +:100F300023F0070503F0070343EA450394888B6019 +:100F4000D38843F040030B61138943F001034B61E5 +:100F500044F4045343F02C03CB6004F4A054002366 +:100F60000B60B4F5806F0B684B680CBF7F23FF23C9 +:100F700080F8643230BD00BF703B0008BC23002005 +:100F8000003802402DE9F041D0F85C62F768336820 +:100F9000DA0504469DB20DD5302383F311884FF452 +:100FA00080610430FFF77CFF6FF4807333600023AF +:100FB00083F31188302383F3118804F1040815F0BA +:100FC0002F033AD183F31188380615D5290613D596 +:100FD000302383F3118804F1380000F065F900280C +:100FE0004EDA0821201DFFF75BFF4FF67F733B4071 +:100FF000F360002383F311887A0616D56B0614D5A7 +:10100000302383F31188D4E913239A420AD1236C45 +:1010100043B127F040073F041021201D3F0CFFF78C +:101020003FFFF760002383F31188D4F86822D36868 +:1010300043B3BDE8F041106918472B0714D015F0F1 +:10104000080F0CBF00214FF48071E80748BF41F042 +:101050002001AA0748BF41F040016B0748BF41F09B +:1010600080014046FFF71CFFAD06736805D594F874 +:1010700064122046194000F0CBF93568ADB29EE706 +:101080007060B6E7BDE8F081F8B51546826806697C +:10109000AA420B46816938BF8568761AB542044674 +:1010A0000BD218462A46FFF70DFEA3692B44A36115 +:1010B000A3685B1BA3602846F8BD0CD918463246CE +:1010C000FFF700FEAF1BE1683A463044FFF7FAFD38 +:1010D000E3683B44EBE718462A46FFF7F3FDE36875 +:1010E000E5E7000083689342F7B51546044638BF2C +:1010F0008568D0E90460361AB5420BD22A46FFF75C +:10110000E1FD63692B446361A36828465B1BA36010 +:1011100003B0F0BD0DD932460191FFF7D3FD01991F +:10112000E068AF1B3A463144FFF7CCFDE3683B442F +:10113000E9E72A46FFF7C6FDE368E4E710B50A448D +:101140000024C361029B8460C0E90000C0E905116E +:10115000C1600261036210BD08B5D0E90532934257 +:1011600001D1826882B98268013282605A1C426170 +:101170001970D0E904329A4224BFC3684361002148 +:1011800000F08EFE002008BD4FF0FF30FBE70000AE +:1011900070B5302304460E4683F31188A568A5B1C7 +:1011A000A368A269013BA360531CA361157822695F +:1011B000934224BFE368A361E3690BB120469847DB +:1011C000002383F31188284607E03146204600F0CB +:1011D00057FE0028E2DA85F3118870BD2DE9F74F3C +:1011E00004460E4617469846D0F81C904FF0300A39 +:1011F0008AF311884FF0000B154665B12A46314637 +:101200002046FFF741FF034660B94146204600F003 +:1012100037FE0028F1D0002383F31188781B03B038 +:10122000BDE8F08FB9F1000F03D001902046C84708 +:10123000019B8BF31188ED1A1E448AF31188DCE7B9 +:10124000C0E90511C160C3611144009B8260C0E91F +:101250000000016103627047F8B504460D4616466A +:10126000302383F31188A768A7B1A368013BA3606B +:1012700063695A1C62611D70D4E904329A4224BF2A +:10128000E3686361E3690BB120469847002080F36F +:10129000118807E03146204600F0F2FD0028E2DA2E +:1012A00087F31188F8BD0000D0E905239A4210B5F4 +:1012B00001D182687AB98268013282605A1C8261E7 +:1012C0001C7803699A4224BFC3688361002100F03F +:1012D000E7FD204610BD4FF0FF30FBE72DE9F74F4B +:1012E00004460E4617469846D0F81C904FF0300A38 +:1012F0008AF311884FF0000B154665B12A46314636 +:101300002046FFF7EFFE034660B94146204600F055 +:10131000B7FD0028F1D0002383F31188781B03B0B8 +:10132000BDE8F08FB9F1000F03D001902046C84707 +:10133000019B8BF31188ED1A1E448AF31188DCE7B8 +:10134000026843681143016003B118477047000009 +:101350001430FFF743BF00004FF0FF331430FFF7A6 +:101360003DBF00003830FFF7B9BF00004FF0FF333A +:101370003830FFF7B3BF00001430FFF709BF00009B +:101380004FF0FF311430FFF703BF00003830FFF794 +:1013900063BF00004FF0FF323830FFF75DBF000041 +:1013A000012914BF6FF0130000207047FFF788BDBC +:1013B00037B515460E4A026000224260C0E902229B +:1013C0000122044602740B46009000F15C014FF4C8 +:1013D00080721430FFF7B2FE00942B464FF48072F7 +:1013E00004F5AE7104F13800FFF72AFF03B030BDF9 +:1013F000843B000810B53023044683F31188FFF7BF +:1014000073FD02232374002080F3118810BD0000B7 +:1014100038B5C36904460D461BB904210844FFF7DB +:101420008FFF294604F11400FFF796FE002806DA24 +:10143000201D4FF40061BDE83840FFF781BF38BD83 +:10144000026843681143016003B118477047000008 +:1014500013B5446BD4F894341A681178042915D163 +:10146000217C022912D11979128901238B40134260 +:101470000CD101A904F14C0001F016FFD4F89444FA +:10148000019B21790246206800F0D0F902B010BD1E +:10149000143001F099BE00004FF0FF33143001F01A +:1014A00093BE00004C3001F06BBF00004FF0FF33E3 +:1014B0004C3001F065BF0000143001F067BE000041 +:1014C0004FF0FF31143001F061BE00004C3001F0EC +:1014D00037BF00004FF0FF324C3001F031BF000049 +:1014E0000020704710B5D0F894341A681178042998 +:1014F000044617D1017C022914D15979528901235C +:101500008B4013420ED1143001F0FAFD024648B16F +:10151000D4F894444FF4807361792068BDE810409A +:1015200000F072B910BD0000406BFFF7DBBF000098 +:10153000704700007FB5124B036000234360C0E991 +:101540000233012502260F4B0574044602900193D5 +:1015500000F18402294600964FF48073143001F0A4 +:10156000ABFD094B0294CDE9006304F523724FF4FF +:101570008073294604F14C0001F072FE04B070BD86 +:10158000AC3B000829150008511400080B683022F4 +:1015900082F311880A7903EB820290614A79093259 +:1015A00043F822008A7912B103EB82039861022387 +:1015B000C0F894140374002080F311887047000071 +:1015C00038B5037F044613B190F85430ABB9201DF1 +:1015D00001250221FFF734FF04F1140025776FF095 +:1015E000010100F069FC84F8545004F14C006FF0E4 +:1015F0000101BDE8384000F05FBC38BD10B50121E5 +:1016000004460430FFF71CFF0023237784F854308E +:1016100010BD000038B504460025143001F064FD0B +:1016200004F14C00257701F033FE201D84F854505E +:101630000121FFF705FF2046BDE83840FFF752BF04 +:1016400090F8443003F06003202B07D190F8452038 +:10165000212A4FF0000303D81F2A06D80020704724 +:10166000222AFBD1C0E90E3303E0034A826307223A +:10167000C2630364012070471C22002037B5D0F8F4 +:1016800094341A681178042904461AD1017C02297D +:1016900017D11979128901238B40134211D100F11E +:1016A0004C05284601F0B4FE58B101A9284601F0C6 +:1016B000FBFDD4F89444019B21790246206800F098 +:1016C000B5F803B030BD0000F0B500EB810385B084 +:1016D0009E6904460D46FEB1302383F3118804EB66 +:1016E0008507301D0821FFF7ABFEFB685B691B68AF +:1016F00006F14C001BB1019001F0E4FD019803A933 +:1017000001F0D2FD024648B1039B2946204600F075 +:101710008DF8002383F3118805B0F0BDFB685A698A +:101720001268002AF5D01B8A013B1340F1D104F165 +:101730004402EAE7093138B550F82140DCB13023E2 +:1017400083F31188D4F894241368527903EB82034D +:10175000DB689B695D6845B104216018FFF770FE86 +:10176000294604F1140001F0D5FC2046FFF7BAFE2B +:10177000002383F3118838BD7047000001F034B8AE +:10178000012303700023C0E90133C3618362036254 +:10179000C36243620363704738B50446302383F362 +:1017A00011880025C0E90355C0E90555416001F0E5 +:1017B0002BF80223237085F31188284638BD0000DA +:1017C00070B500EB810305465069DA600E46144699 +:1017D00018B110220021FFF79BFAA06918B110225E +:1017E0000021FFF795FA31462846BDE8704001F028 +:1017F000D5B80000826802F0011282600022C0E9C0 +:101800000422826101F056B9F0B400EB81044789EB +:10181000E4680125A4698D403D4345812360002390 +:10182000A2606360F0BC01F071B90000F0B400EB9D +:1018300081040789E468012564698D403D43058181 +:1018400023600023A2606360F0BC01F0EBB90000EC +:1018500070B50223002504460370C0E90255C0E9B3 +:101860000455C564856180F8345001F033F863682D +:101870001B6823B129462046BDE87040184770BD5B +:101880000378052B10B504460AD080F850300523A4 +:10189000037043681B680BB1042198470023A360C1 +:1018A00010BD00000178052906D190F8502043684A +:1018B00002701B6803B118477047000070B590F8BC +:1018C0003430044613B1002380F8343004F144026C +:1018D000204601F011F963689B68B3B994F844306D +:1018E00013F0600535D00021204601F0B1FB002146 +:1018F000204601F0A3FB63681B6813B10621204654 +:101900009847062384F8343070BD20469847002855 +:10191000E4D0B4F84A30E26B9A4288BFE36394F9AA +:101920004430E56B002B4FF0300380F20381002D33 +:1019300000F0F280092284F8342083F3118800211A +:10194000D4E90E232046FFF771FF002383F31188AB +:10195000DAE794F8452003F07F0343EA022340F2DC +:101960000232934200F0C58021D8B3F5807F48D081 +:101970000DD8012B3FD0022B00F09380002BB2D169 +:1019800004F14C02A2630222E2632364C1E7B3F5CF +:10199000817F00F09B80B3F5407FA4D194F846305E +:1019A000012BA0D1B4F84C3043F0020332E0B3F580 +:1019B000006F4DD017D8B3F5A06F31D0A3F5C06339 +:1019C000012B90D8636894F846205E6894F847101D +:1019D000B4F848302046B047002884D04368A36359 +:1019E0000368E3631AE0B3F5106F36D040F60242A5 +:1019F00093427FF478AF5C4BA3630223E36300233D +:101A0000C3E794F84630012B7FF46DAFB4F84C3047 +:101A100023F00203C4E90E55A4F84C30256478E79E +:101A2000B4F84430B3F5A06F0ED194F8463084F882 +:101A30004E30204600F0A6FF63681B6813B10121F9 +:101A400020469847032323700023C4E90E339CE704 +:101A500004F14F03A3630123C3E72378042B10D1C0 +:101A6000302383F311882046FFF7C4FE85F31188E5 +:101A70000321636884F84F5021701B680BB1204626 +:101A8000984794F84630002BDED084F84F3004237A +:101A9000237063681B68002BD6D00221204698472C +:101AA000D2E794F848301D0603F00F0120460AD50E +:101AB00001F014F8012804D002287FF414AF2B4B56 +:101AC0009AE72B4B98E700F0FBFFF3E794F84630DA +:101AD000002B7FF408AF94F8483013F00F01B3D017 +:101AE0001A06204602D501F0C7FAADE701F0BAFAAE +:101AF000AAE794F84630002B7FF4F5AE94F848300E +:101B000013F00F01A0D01B06204602D501F0A0FA69 +:101B10009AE701F093FA97E7142284F8342083F3CC +:101B200011882B462A4629462046FFF76DFE85F38D +:101B30001188E9E65DB1152284F8342083F3118819 +:101B40000021D4E90E232046FFF75EFEFDE60B22BE +:101B500084F8342083F311882B462A4629462046F0 +:101B6000FFF764FEE3E700BFDC3B0008D43B00085E +:101B7000D83B000838B590F834300446002B3ED0EE +:101B8000063BDAB20F2A34D80F2B32D8DFE803F045 +:101B9000373131082232313131313131313137375A +:101BA000C56BB0F84A309D4214D2C3681B8AB5FB9E +:101BB000F3F203FB12556DB9302383F311882B46E2 +:101BC0002A462946FFF732FE85F311880A2384F856 +:101BD00034300EE0142384F83430302383F311883A +:101BE00000231A4619462046FFF70EFE002383F312 +:101BF000118838BD036C03B198470023E7E7002143 +:101C0000204601F025FA0021204601F017FA63680A +:101C10001B6813B10621204698470623D7E700002A +:101C200010B590F83430142B044629D017D8062B61 +:101C300005D001D81BB110BD093B022BFBD80021F8 +:101C4000204601F005FA0021204601F0F7F963680B +:101C50001B6813B1062120469847062319E0152B6F +:101C6000E9D10B2380F83430302383F3118800232B +:101C70001A461946FFF7DAFD002383F31188DAE7E5 +:101C8000C3689B695B68002BD5D1036C03B198478F +:101C9000002384F83430CEE700230375826803699B +:101CA0001B6899689142FBD25A68036042601060D9 +:101CB0005860704700230375826803691B68996840 +:101CC0009142FBD85A6803604260106058607047C8 +:101CD00008B50846302383F311880B7D032B05D00C +:101CE000042B0DD02BB983F3118808BD8B6900221A +:101CF0001A604FF0FF338361FFF7CEFF0023F2E756 +:101D0000D1E9003213605A60F3E70000FFF7C4BF67 +:101D1000054BD9680875186802681A60536001227B +:101D20000275D860FEF7EEBA2826002030B50C4BBD +:101D3000DD684B1C87B004460FD02B46094A684625 +:101D400000F04EF92046FFF7E3FF009B13B1684611 +:101D500000F050F9A86907B030BDFFF7D9FFF9E7E7 +:101D600028260020D11C0008044B1A68DB68906804 +:101D70009B68984294BF00200120704728260020CD +:101D8000084B10B51C68D86822681A60536001229D +:101D90002275DC60FFF78EFF01462046BDE810404B +:101DA000FEF7B0BA2826002038B5074C0749084886 +:101DB000012300252370656001F068FB0223237076 +:101DC00085F3118838BD00BF90280020E43B00084F +:101DD0002826002000F044B9034A516853685B1A72 +:101DE0009842FBD8704700BF001000E08B600223D0 +:101DF00008618B82084670478368A3F1840243F828 +:101E0000142C026943F8442C426943F8402C094AD7 +:101E100043F8242CC26843F8182C022203F80C2C37 +:101E2000002203F80B2C044A43F8102CA3F12000E5 +:101E3000704700BF1D0300082826002008B5FFF7E3 +:101E4000DBFFBDE80840FFF761BF0000024BDB6825 +:101E500098610F20FFF75CBF28260020302383F312 +:101E60001188FFF7F3BF000008B50146302383F364 +:101E700011880820FFF75AFF002383F3118808BD5B +:101E8000064BDB6839B1426818605A6013604360E2 +:101E90000420FFF74BBF4FF0FF307047282600208B +:101EA0000368984206D01A6802605060996118462B +:101EB000FFF72CBF7047000038B504460D46206878 +:101EC000844200D138BD036823605C608561FFF700 +:101ED0001DFFF4E710B503689C68A2420CD85C684B +:101EE0008A600B604C602160596099688A1A9A6018 +:101EF0004FF0FF33836010BD1B68121BECE700003E +:101F00000A2938BF0A2170B504460D460A26601911 +:101F100001F0B4FA01F09CFA041BA54203D8751C29 +:101F20002E460446F3E70A2E04D9BDE8704001208E +:101F300001F0ECBA70BD0000F8B5144B0D46D96144 +:101F400003F1100141600A2A1969826038BF0A2230 +:101F5000016048601861A818144601F07FFA0A274A +:101F600001F076FA431BA342064606D37C1C2819CF +:101F700001F084FA27463546F2E70A2F04D9BDE876 +:101F8000F840012001F0C2BAF8BD00BF28260020A9 +:101F9000F8B506460D4601F05BFA0F4A134653F8B2 +:101FA000107F9F4206D12A4601463046BDE8F840E0 +:101FB000FFF7C2BFD169BB68441A2C1928BF2C4651 +:101FC000A34202D92946FFF79BFF22463146034828 +:101FD000BDE8F840FFF77EBF282600203826002005 +:101FE00010B4C0E9032300235DF8044B4361FFF7FD +:101FF000CFBF000010B5194C236998420DD0D0E92D +:102000000032816813605A609A680A449A6000231B +:1020100003604FF0FF33A36110BD2346026843F80D +:10202000102F53600022026022699A4203D1BDE85A +:10203000104001F01DBA936881680B44936001F071 +:1020400007FA2269E1699268441AA242E4D911446C +:10205000BDE81040091AFFF753BF00BF2826002033 +:102060002DE9F047DFF8BC8008F110072C4ED8F8B6 +:10207000105001F0EDF9D8F81C40AA68031B9A42F1 +:102080003ED81444D5E900324FF00009C8F81C408E +:1020900013605A60C5F80090D8F81030B34201D1EF +:1020A00001F0E6F989F31188D5E90331284698470C +:1020B000302383F311886B69002BD8D001F0C8F965 +:1020C0006A69A0EB04094A4582460DD2022001F05C +:1020D0001DFA0022D8F81030B34208D151462846E4 +:1020E000BDE8F047FFF728BF121A2244F2E712EBCF +:1020F000090938BF4A4629463846FFF7EBFEB5E7DF +:10210000D8F81030B34208D01444211AC8F81C0083 +:10211000A960BDE8F047FFF7F3BEBDE8F08700BF58 +:10212000382600202826002000207047FEE7000007 +:10213000704700004FF0FF307047000002290CD0BC +:10214000032904D00129074818BF00207047032A3B +:1021500005D8054800EBC2007047044870470020CE +:10216000704700BFC03C00082C220020743C0008CF +:1021700070B59AB00546084601A9144600F0C2F8A9 +:1021800001A8FEF7BDFD431C5B00C5E90034002239 +:10219000237003236370C6B201AB02341046D1B280 +:1021A0008E4204F1020401D81AB070BD13F8011B6D +:1021B00004F8021C04F8010C0132F0E708B53023E2 +:1021C00083F311880348FFF759FA002383F311883A +:1021D00008BD00BF9828002090F8443003F01F028B +:1021E000012A07D190F845200B2A03D10023C0E92A +:1021F0000E3315E003F06003202B08D1B0F848300F +:102200002BB990F84520212A03D81F2A04D8FFF7BC +:1022100017BA222AEBD0FAE7034A82630722C26385 +:1022200003640120704700BF2322002007B5052961 +:1022300017D8DFE801F0191603191920302383F3AA +:102240001188104A01900121FFF7BAFA01980E4A4D +:102250000221FFF7B5FA0D48FFF7DCF9002383F3FD +:10226000118803B05DF804FB302383F3118807481D +:10227000FFF7A6F9F2E7302383F311880348FFF74D +:10228000BDF9EBE7143C0008383C00089828002012 +:1022900038B50C4D0C4C0D492A4604F10800FFF7E7 +:1022A00067FF05F1CA0204F110000949FFF760FF5A +:1022B00005F5CA7204F118000649BDE83840FFF779 +:1022C00057BF00BF602D00202C220020F03B0008EB +:1022D000FD3B0008083C000870B5044608460D4662 +:1022E000FEF70EFDC6B22046013403780BB918463E +:1022F00070BD32462946FEF7EFFC0028F3D10120DD +:10230000F6E700002DE9F84F05460C46FEF7F8FC0D +:102310002B49C6B22846FFF7DFFF08B10336F6B2F5 +:1023200028492846FFF7D8FF08B11036F6B2632EC9 +:102330000DD8DFF88C80DFF88C90234FDFF890A069 +:10234000DFF890B02E7846B92670BDE8F88F2946A0 +:102350002046BDE8F84F01F0D3BB252E2BD1072234 +:1023600041462846FEF7B8FC58B9DBF80030236038 +:10237000DBF804306360BBF80830238107350A348A +:10238000E0E7082249462846FEF7A6FC98B90F4B1D +:10239000A21C197809090232C95D02F8041C13F85D +:1023A000011B01F00F015345C95D02F8031CF0D178 +:1023B00018340835C6E704F8016B0135C2E700BFE1 +:1023C000E03C0008083C0008F33C0008107AFF1FBE +:1023D0001C7AFF1FE83C0008BFF34F8F024AD36806 +:1023E000DB03FCD4704700BF003C024008B5094B3A +:1023F0001B7873B9FFF7F0FF074B1A69002ABFBFBC +:10240000064A5A6002F188325A601A6822F48062E1 +:102410001A6008BDBE2F0020003C02402301674522 +:1024200008B50B4B1B7893B9FFF7D6FF094B1A6918 +:1024300042F000421A611A6842F480521A601A6827 +:1024400022F480521A601A6842F480621A6008BD51 +:10245000BE2F0020003C02401728F0B516D80C4CC7 +:102460000C4923787BB90C4D0E4618234FF00062BF +:1024700055F8047B46F8042B013B13F0FF033A4464 +:10248000F6D10123237051F82000F0BD0020FCE7B5 +:1024900020300020C02F0020043D0008014B53F8DD +:1024A00020007047043D000818207047172810B519 +:1024B000044601D9002010BDFFF7CEFF064B53F8AC +:1024C00024301844C21A0BB90120F4E71268013213 +:1024D000F0D1043BF6E700BF043D0008172838B5EB +:1024E000044628D81549FFF777FFFFF77FFFF3234E +:1024F000CB600C23B0FBF3F203FB1205D30143EADC +:10250000C503DBB243F4007343F002030B610B69B4 +:1025100043F480330B61FFF75FFFFFF79DFF084B2C +:1025200053F8241000F0DAF8FFF77AFF2046BDE8F0 +:102530003840FFF7BBBF002038BD00BF003C024061 +:10254000043D0008F8B512F00103144642D1821888 +:10255000B2F1026F57D82D4B1B6813F0010352D014 +:102560002B4DFFF743FFF323EB60FFF735FF40F2FE +:102570000127032C15D824F001046618244C401AB6 +:1025800040F20117B142236900EB010524D123F089 +:1025900001032361FFF744FF0120F8BD043C043030 +:1025A000E7E78307E7D12B6923F440732B612B699D +:1025B0003B432B6151F8046B0660BFF34F8FFFF76D +:1025C0000BFF03689E42E9D02B6923F001032B61C6 +:1025D000FFF726FF0020E0E723F44073236123691F +:1025E0003B4323610B882B80BFF34F8FFFF7F4FE33 +:1025F0002D8831F8023BADB2AB42C3D0236923F042 +:1026000001032361E4E71846C7E700BF0038024032 +:10261000003C0240084908B50B7828B11BB9FFF708 +:10262000E5FE01230B7008BD002BFCD0BDE808407F +:102630000870FFF7F5BE00BFBE2F002010B50244A2 +:10264000064BD2B2904200D110BD441C00B253F8E8 +:10265000200041F8040BE0B2F4E700BF502800402E +:102660000F4B30B51C6F240407D41C6F44F4007466 +:102670001C671C6F44F400441C670A4C236843F435 +:10268000807323600244084BD2B2904200D130BD27 +:10269000441C00B251F8045B43F82050E0B2F4E768 +:1026A00000380240007000405028004007B5012269 +:1026B00001A90020FFF7C2FF019803B05DF804FBF9 +:1026C00013B50446FFF7F2FFA04205D0012201A98D +:1026D00000200194FFF7C4FF02B010BD7047000056 +:1026E000094B5A88B2F5805F10460BD022F00203E6 +:1026F00041F20102934205D041F20703C31A584246 +:102700005841704701207047002004E0034B1A68CD +:102710001AB9034AD2F874281A607047243000208E +:102720000030024008B5FFF7F1FF024B1868C0F314 +:10273000407008BD2430002070470000FEE7000014 +:102740000A4B0B480B4A90420BD30B4BDA1C121A64 +:10275000C11E22F003028B4238BF00220021FEF787 +:10276000D7BA53F8041B40F8041BECE7EC3E000812 +:1027700020310020203100202031002070B5D0E928 +:1027800015439E6800224FF0FF3504EB42135101C0 +:10279000D3F800090028BEBFD3F8000940F08040FC +:1027A000C3F80009D3F8000B0028BEBFD3F8000B14 +:1027B00040F08040C3F8000B013263189642C3F822 +:1027C0000859C3F8085BE0D24FF00113C4F81C3875 +:1027D00070BD0000890141F02001016103699B0681 +:1027E000FCD41220FFF7F8BA10B5054C2046FEF7CE +:1027F000C7FF4FF0A0436365024BA36510BD00BF48 +:1028000028300020883D000870B50378012B05466C +:1028100050D12A4B446D98421BD1294B5A6B42F040 +:1028200080025A635A6D42F080025A655A6D5A69A5 +:1028300042F080025A615A6922F080025A610E21E8 +:1028400043205B6900F022FC1E4BE3601E4BC4F882 +:1028500000380023C4F8003EC02323606E6D4FF49F +:102860005023A3633369002BFCDA012333610C206E +:10287000FFF7B2FA3369DB07FCD41220FFF7ACFA9A +:102880003369002BFCDA0026A6602846FFF776FFA6 +:102890006B68C4F81068DB68C4F81468C4F81C6876 +:1028A0004BB90A4BA3614FF0FF336361A36843F058 +:1028B0000103A36070BD064BF4E700BF2830002081 +:1028C000003802404014004003002002003C30C0A9 +:1028D000083C30C0F8B5446D054600212046FFF79E +:1028E00079FFA96D00234FF001128F68C4F83438C6 +:1028F0004FF00066C4F81C284FF0FF3004EB431281 +:1029000001339F42C2F80069C2F8006BC2F808099F +:10291000C2F8080BF2D20B686A6DEB656362102394 +:102920001361166916F01006FBD11220FFF754FA56 +:10293000D4F8003823F4FE63C4F80038A36943F4E4 +:10294000402343F01003A3610923C4F81038C4F8EE +:1029500014380A4BEB604FF0C043C4F8103B084BEF +:10296000C4F8003BC4F81069C4F80039EB6D03F1FA +:10297000100243F48013EA65A362F8BD643D0008C9 +:1029800040800010426D90F84E10D2F8003823F4C9 +:10299000FE6343EA0113C2F8003870472DE9F8439B +:1029A00000EB8103456DDA68166806F00306731EB6 +:1029B000022B05EB41130C4680460FFA81F94FEAD2 +:1029C00041104FF00001C3F8101B4FF0010104F15A +:1029D000100398BFB60401FA03F391698EBF334E1A +:1029E00006F1805606F5004600293AD0578A04F1D0 +:1029F0005801490137436F50D5F81C180B43C5F8EF +:102A00001C382B180021C3F8101953690127611EC7 +:102A1000A7409BB3138A928B9B08012A88BF53431C +:102A2000D8F85C20981842EA034301F1400205EB14 +:102A30008202C8F85C00214653602846FFF7CAFEB0 +:102A400008EB8900C3681B8A43EA84534834640155 +:102A50001E432E51D5F81C381F43C5F81C78BDE81D +:102A6000F88305EB4917D7F8001B21F40041C7F89C +:102A7000001BD5F81C1821EA0303C0E704F13F034B +:102A800005EB83030A4A5A6028462146FFF7A2FE57 +:102A900005EB4910D0F8003923F40043C0F80039A1 +:102AA000D5F81C3823EA0707D7E700BF00800010DD +:102AB00000040002826D1268C265FFF75FBE00006D +:102AC0005831436D49015B5813F4004004D013F4AE +:102AD000001F0CBF02200120704700004831436DE9 +:102AE00049015B5813F4004004D013F4001F0CBFDD +:102AF000022001207047000000EB8101CB68196AB9 +:102B00000B6813604B6853607047000000EB810353 +:102B100030B5DD68AA691368D36019B9402B84BF4A +:102B2000402313606B8A1468426D1C44013CB4FB63 +:102B3000F3F46343033323F0030302EB411043EA4E +:102B4000C44343F0C043C0F8103B2B6803F00303B9 +:102B5000012B09B20ED1D2F8083802EB411013F460 +:102B6000807FD0F8003B14BF43F0805343F0005304 +:102B7000C0F8003B02EB4112D2F8003B43F00443A3 +:102B8000C2F8003B30BD00002DE9F041244D6E6DD0 +:102B900006EB40130446D3F8087BC3F8087B3807DC +:102BA0000AD5D6F81438190706D505EB8403214653 +:102BB000DB6828465B689847FA071FD5D6F81438B3 +:102BC000DB071BD505EB8403D968CCB98B69488A30 +:102BD0005A68B2FBF0F600FB16228AB91868DA6868 +:102BE00090420DD2121AC3E90024302383F31188D6 +:102BF0000B482146FFF78AFF84F31188BDE8F08176 +:102C0000012303FA04F26B8923EA02036B81CB6888 +:102C1000002BF3D021460248BDE8F041184700BF21 +:102C20002830002000EB810370B5DD68436D6C69CE +:102C30002668E6604A0156BB1A444FF40020C2F8E9 +:102C400010092A6802F00302012A0AB20ED1D3F851 +:102C5000080803EB421410F4807FD4F8000914BF75 +:102C600040F0805040F00050C4F8000903EB4212DD +:102C7000D2F8000940F00440C2F80009D3F8340843 +:102C8000012202FA01F10143C3F8341870BD19B9E9 +:102C9000402E84BF4020206020682E8A8419013C89 +:102CA000B4FBF6F440EAC44040F000501A44C6E7D2 +:102CB0002DE9F8433B4D6E6D06EB40130446D3F807 +:102CC0000889C3F8088918F0010F4FEA40171AD095 +:102CD000D6F81038DB0716D505EB8003D9684B69A9 +:102CE0001868DA68904230D2121A4FF000091A6060 +:102CF000C3F80490302383F3118821462846FFF758 +:102D000091FF89F3118818F0800F1CD0D6F8343861 +:102D10000126A640334216D005EB84036D6DD3F82F +:102D20000CC0DCF814200134E4B2D2F800E005EB6A +:102D300004342F445168714515D3D5F8343823EA4B +:102D40000606C5F83468BDE8F883012303FA04F2E7 +:102D50002B8923EA02032B818B68002BD3D02146D9 +:102D600028469847CFE7BCF81000AEEB010383423A +:102D700028BF0346D7F8180980B2B3EB800FE2D81A +:102D80009068A0F1040959F8048FC4F80080A0EB02 +:102D900009089844B8F1040FF5D818440B44906022 +:102DA0005360C7E7283000202DE9F74FA24C656D2E +:102DB0006E69AB691E4016F480586E6107D02046DC +:102DC000FEF746FD03B0BDE8F04F00F04DBC002E0D +:102DD00012DAD5F8003E98489B071EBFD5F8003E92 +:102DE00023F00303C5F8003ED5F8043823F00103AF +:102DF000C5F80438FEF756FD370505D58E48FFF7B0 +:102E0000BDFC8D48FEF73CFDB0040CD5D5F8083864 +:102E100013F0060FEB6823F470530CBF43F4105308 +:102E200043F4A053EB6031071BD56368DB681BB923 +:102E3000AB6923F00803AB612378052B0CD1D5F8DF +:102E4000003E7D489A071EBFD5F8003E23F00303DD +:102E5000C5F8003EFEF726FD6368DB680BB17648D7 +:102E60009847F30274D4B70227D5D4F85490DFF80A +:102E7000C8B100274FF0010A09EB4712D2F8003B16 +:102E800003F44023B3F5802F11D1D2F8003B002B7F +:102E90000DDA62890AFA07F322EA0303638104EB7D +:102EA0008703DB68DB6813B1394658469847A36D42 +:102EB00001379B68FFB29F42DED9F00617D5676DD8 +:102EC0003A6AC2F30A1002F00F0302F4F012B2F5EC +:102ED000802F00F08580B2F5402F08D104EB8303EA +:102EE0000022DB681B6A07F5805790426AD13003E5 +:102EF000D5F8184813D5E10302D50020FFF744FEAA +:102F0000A20302D50120FFF73FFE630302D5022092 +:102F1000FFF73AFE270302D50320FFF735FE7503BE +:102F20007FF550AFE00702D50020FFF7C1FEA107F3 +:102F300002D50120FFF7BCFE620702D50220FFF791 +:102F4000B7FE23077FF53EAF0320FFF7B1FE39E759 +:102F5000636DDFF8E4A0019300274FF00109A36D32 +:102F60009B685FFA87FB9B453FF67DAF019B03EBB8 +:102F70004B13D3F8001901F44021B1F5802F1FD174 +:102F8000D3F8001900291BDAD3F8001941F0904159 +:102F9000C3F80019D3F800190029FBDB5946606D0E +:102FA000FFF718FC218909FA0BF321EA03032381B7 +:102FB00004EB8B03DB689B6813B159465046984776 +:102FC0000137CCE7910708BFD7F80080072A98BFE0 +:102FD00003F8018B02F1010298BF4FEA182884E739 +:102FE000023304EB830207F580575268D2F818C009 +:102FF000DCF80820DCE9001CA1EB0C0C0021884265 +:103000000AD104EB830463689B699A6802449A605E +:103010005A6802445A606AE711F0030F08BFD7F8F4 +:1030200000808C4588BF02F8018B01F1010188BF47 +:103030004FEA1828E3E700BF28300020436D03EB78 +:103040004111D1F8003B43F40013C1F8003B704735 +:10305000436D03EB4111D1F8003943F40013C1F87B +:1030600000397047436D03EB4111D1F8003B23F465 +:103070000013C1F8003B7047436D03EB4111D1F8D9 +:10308000003923F40013C1F80039704700F16043A0 +:1030900003F561430901C9B283F80013012200F06E +:1030A0001F039A4043099B0003F1604303F561430A +:1030B000C3F880211A60704730B5039C0172043355 +:1030C00004FB0325C0E90653049B03630021059B11 +:1030D000C160C0E90000C0E90422C0E90842C0E9BB +:1030E0000A11436330BD0000416A0022C0E90411A7 +:1030F000C0E90A22C2606FF00101FEF7DDBE0000E8 +:10310000D0E90432934201D1C2680AB9181D704750 +:103110000020704703691960C2680132C260C26949 +:10312000134482690361934224BF436A036100210F +:10313000FEF7B6BE38B504460D46E3683BB162699A +:10314000131D1268A3621344E362002007E0237A90 +:1031500033B929462046FEF793FE0028EDDA38BD44 +:103160006FF00100FBE70000C368C269013BC36068 +:103170004369134482694361934224BF436A4361B4 +:1031800000238362036B03B11847704770B5302387 +:10319000044683F31188866A3EB9FFF7CBFF0546E4 +:1031A00018B186F31188284670BDA36AE26A13F845 +:1031B000015BA362934202D32046FFF7D5FF0023B1 +:1031C00083F31188EFE700002DE9F84F04460E461F +:1031D000174698464FF0300989F311880025AA4612 +:1031E000D4F828B0BBF1000F09D141462046FFF7C3 +:1031F000A1FF20B18BF311882846BDE8F88FD4E9F0 +:103200000A12A7EB050B521A934528BF9346BBF150 +:10321000400F1BD9334601F1400251F8040B43F82B +:10322000040B9142F9D1A36A40334036A362403582 +:10323000D4E90A239A4202D32046FFF795FF8AF386 +:103240001188BD42D8D289F31188C9E730465A4661 +:10325000FDF738FDA36A5B445E44A3625D44E7E783 +:1032600010B5029C0172043303FB0421C0E906136C +:103270000023C0E90A33039B0363049BC460C0E9D5 +:103280000000C0E90422C0E90842436310BD000009 +:10329000026AC260426AC0E904220022C0E90A222E +:1032A0006FF00101FEF708BED0E904239A4201D174 +:1032B000C26822B9184650F8043B0B6070470023DF +:1032C0001846FAE7C368C2690133C360436913440F +:1032D00082694361934224BF436A43610021FEF740 +:1032E000DFBD000038B504460D46E3683BB12369F5 +:1032F0001A1DA262E2691344E362002007E0237A08 +:1033000033B929462046FEF7BBFD0028EDDA38BD6B +:103310006FF00100FBE7000003691960C268013A21 +:10332000C260C269134482690361934224BF436A45 +:10333000036100238362036B03B1184770470000E9 +:1033400070B530230D460446114683F31188866A12 +:103350002EB9FFF7C7FF10B186F3118870BDA36ABD +:103360001D70A36AE26A01339342A36204D3E16948 +:1033700020460439FFF7D0FF002080F31188EDE7E5 +:103380002DE9F84F04460D46904699464FF0300A15 +:103390008AF311880026B346A76A4FB949462046EA +:1033A000FFF7A0FF20B187F311883046BDE8F88F02 +:1033B000D4E90A073A1AA8EB0607974228BF17462E +:1033C000402F1BD905F1400355F8042B40F8042B7E +:1033D0009D42F9D1A36A4033A3624036D4E90A235F +:1033E0009A4204D3E16920460439FFF795FF8BF335 +:1033F00011884645D9D28AF31188CDE729463A4645 +:10340000FDF760FCA36A3B443D44A3623E44E5E70C +:10341000D0E904239A4217D1C3689BB1836A8BB168 +:10342000043B9B1A0ED01360C368013BC360C369A1 +:103430001A44836902619A4224BF436A03610023EC +:1034400083620123184670470023FBE700F036B97A +:10345000014B586A704700BF000C0040034B00222C +:1034600058631A610222DA60704700BF000C004006 +:10347000014B0022DA607047000C0040014B58639A +:10348000704700BF000C0040FEE7000070B51B4B0A +:1034900001630025044686B0586085620E4600F040 +:1034A000BFF804F11003C4E904334FF0FF33C4E95B +:1034B0000635C4E90044A560E562FFF7C9FF2B4665 +:1034C0000246C4E9082304F134010D4A256580232E +:1034D0002046FEF78BFC0123E0600A4A0375009248 +:1034E00072680192B268CDE90223074B6846CDE9C4 +:1034F0000435FEF7A3FC06B070BD00BF9028002085 +:10350000943D0008993D000889340008024AD36AB6 +:103510001843D062704700BF282600204B684360E4 +:103520008B688360CB68C3600B6943614B6903623E +:103530008B6943620B6803607047000008B5264B37 +:1035400026481A6940F2FF110A431A611A6922F4E7 +:10355000FF7222F001021A611A691A6B0A431A6398 +:103560001A6D0A431A651E4A1B6D1146FFF7D6FFF6 +:1035700002F11C0100F58060FFF7D0FF02F1380175 +:1035800000F58060FFF7CAFF02F1540100F580608A +:10359000FFF7C4FF02F1700100F58060FFF7BEFF86 +:1035A00002F18C0100F58060FFF7B8FF02F1A8017D +:1035B00000F58060FFF7B2FF02F1C40100F5806002 +:1035C000FFF7ACFF02F1E00100F58060FFF7A6FF16 +:1035D000BDE8084000F0F0B80038024000000240AA +:1035E000A03D000808B500F06BFAFEF7DDFBFFF721 +:1035F0008DF8BDE80840FEF74BBE000070470000A4 +:10360000EFF3098305494A6B22F001024A636833EC +:1036100083F30988002383F31188704700EF00E0EB +:10362000302080F3118862B60C4B0D4AD96821F422 +:10363000E0610904090C0A43DA60D3F8FC20094967 +:1036400042F08072C3F8FC200A6842F001020A606E +:103650002022DA7783F82200704700BF00ED00E0F7 +:103660000003FA05001000E010B5302383F3118841 +:103670000E4B5B6813F4006314D0F1EE103AEFF3D5 +:103680000984683C4FF08073E361094BDB6B236670 +:1036900084F30988FEF768FB10B1064BA36110BDE7 +:1036A000054BFBE783F31188F9E700BF00ED00E06D +:1036B00000EF00E02F030008320300080E4B1A6CE5 +:1036C00042F008021A641A6E42F008021A660B4AA7 +:1036D0001B6E936843F008039360094B53229A6270 +:1036E0004FF0FF32DA6200229A615A63DA605A6060 +:1036F00001225A611A60704700380240002004E03D +:10370000000C0040094A08B51169D3680B40D9B2D2 +:10371000C9439B07116107D5302383F31188FEF756 +:1037200059FB002383F3118808BD00BF000C004043 +:103730001F4B1A696FEAC2526FEAD2521A611A69B4 +:10374000C2F308021A614FF0FF301A695A695861D2 +:1037500000215A6959615A691A6A62F080521A62E4 +:103760001A6A02F080521A621A6A5A6A58625A6ACF +:1037700059625A6A1A6C42F080521A641A6E42F008 +:1037800080521A661A6E0B4A106840F480701060FE +:10379000186F00F44070B0F5007F1EBF4FF480300A +:1037A00018671967536823F40073536000F060B919 +:1037B0000038024000700040344B4FF080521A64D1 +:1037C000334A4FF4404111601A6842F001021A6016 +:1037D0001A689107FCD59A6822F003029A602B4B75 +:1037E0009A6812F00C02FBD1196801F0F901196016 +:1037F0009A601A6842F480321A601A689203FCD503 +:103800005A6F42F001025A67204B5A6F9007FCD55D +:10381000204A5A601A6842F080721A601C4A536843 +:103820005904FCD5194B1A689201FCD51A4A9A60C2 +:103830000322C3F88C20194B1A68194B9A42194B72 +:1038400021D1194A1168194A91421CD140F205123E +:103850001A60144A136803F00F03052BFAD10B4BBF +:103860009A6842F002029A609A6802F00C02082AF2 +:10387000FAD15A6C42F480425A645A6E42F4804241 +:103880005A665B6E704740F20572E1E7003802400D +:10389000007000401854400700948838002004E06D +:1038A00011640020003C024000ED00E041C20F41E5 +:1038B000074A08B5536903F00103536123B1054A70 +:1038C00013680BB150689847BDE80840FFF7CCBEBD +:1038D000003C0140A0300020074A08B5536903F0BE +:1038E0000203536123B1054A93680BB1D06898472E +:1038F000BDE80840FFF7B8BE003C0140A030002002 +:10390000074A08B5536903F00403536123B1054A1C +:1039100013690BB150699847BDE80840FFF7A4BE92 +:10392000003C0140A0300020074A08B5536903F06D +:103930000803536123B1054A93690BB1D0699847D5 +:10394000BDE80840FFF790BE003C0140A0300020D9 +:10395000074A08B5536903F01003536123B1054AC0 +:10396000136A0BB1506A9847BDE80840FFF77CBE68 +:10397000003C0140A0300020164B10B55C6904F4F7 +:1039800078725A61A30604D5134A936A0BB1D06AC0 +:103990009847600604D5104A136B0BB1506B9847DB +:1039A000210604D50C4A936B0BB1D06B9847E20506 +:1039B00004D5094A136C0BB1506C9847A30504D584 +:1039C000054A936C0BB1D06C9847BDE81040FFF7E7 +:1039D0004BBE00BF003C0140A0300020194B10B589 +:1039E0005C6904F47C425A61620504D5164A136D81 +:1039F0000BB1506D9847230504D5134A936D0BB155 +:103A0000D06D9847E00404D50F4A136E0BB1506E89 +:103A10009847A10404D50C4A936E0BB1D06E984719 +:103A2000620404D5084A136F0BB1506F9847230402 +:103A300004D5054A936F0BB1D06F9847BDE810408D +:103A4000FFF712BE003C0140A030002008B503483B +:103A5000FDF798FABDE80840FFF706BEBC2300203A +:103A600008B5FFF74FFEBDE80840FFF7FDBD0000B9 +:103A7000062108B50846FFF709FB06210720FFF7D6 +:103A800005FB06210820FFF701FB06210920FFF7AF +:103A9000FDFA06210A20FFF7F9FA06211720FFF7A1 +:103AA000F5FA06212820FFF7F1FA07213220FFF767 +:103AB000EDFABDE808400C212620FFF7E7BA000028 +:103AC00008B5FFF735FE00F00DF8FDF76FFCFDF7C8 +:103AD00055FEFDF72DFDFFF791FDBDE80840FFF70E +:103AE000B5BC00000023054A19460133102BC2E97A +:103AF000001102F10802F8D1704700BFA030002089 +:103B0000034611F8012B03F8012B002AF9D1704765 +:103B100053544D3332463F3F3F0053544D333246AA +:103B20003430780053544D33324634327800535495 +:103B30004D333246343436585800000001203300EB +:103B40000010410001105A00031059000710310005 +:103B500000000000103B0008130400001A3B00089E +:103B600019040000243B0008210400002E3B00083B +:103B700000960000000000000000000000000000AF +:103B800000000000000000006D1300085913000839 +:103B900095130008811300088D130008791300089D +:103BA0006513000851130008A1130008000000006D +:103BB000AD14000899140008D5140008C1140008B9 +:103BC000CD140008B9140008A514000891140008C9 +:103BD000E1140008000000000100000000000000E7 +:103BE00063300000E03B0008802600209028002081 +:103BF0004865782F50726F6669434E430025424FE7 +:103C0000415244252D424C002553455249414C25F3 +:103C1000000000000200000000000000C9160008BB +:103C20003517000840004000302D0020402D0020B6 +:103C3000020000000000000003000000000000007F +:103C4000791700080000000010000000502D00202F +:103C500000000000010000000000000028300020EB +:103C6000010102002D2200083D210008D921000891 +:103C7000BD210008430000007C3C0008090243000D +:103C8000020100C032090400000102020100052403 +:103C9000001001052401000104240202052406008D +:103CA00001070582030800FF09040100020A000061 +:103CB00000070501024000000705810240000000E6 +:103CC00012000000C83C0008120110010200004070 +:103CD000AE2D0510000201020301000004030904D7 +:103CE00025424F41524425004375626550757270FC +:103CF0006C65003031323334353637383941424320 +:103D00004445460000400000004000000040000024 +:103D1000004000000000010000000200000002005E +:103D2000000002000000020000000200000002008B +:103D300000000200004000000040000000400000C1 +:103D4000004000000000010000000200000002002E +:103D5000000002000000020000000200000002005B +:103D60000000020000000000BD180008751B0008DC +:103D7000211C0008400040008830002088300020CE +:103D80000100000098300020800000004001000089 +:103D9000030000006D61696E0069646C65000000DD +:103DA0000500802A00020000AAAAAAAA0A0000248C +:103DB000FCFF00000000000000A00A000004050055 +:103DC00000000000AAAAAAAA00080A00DFFC00005E +:103DD000000000000000000014000054000000007B +:103DE000AAAAAAAA14000054FFFF000000000000C5 +:103DF000000000008069100000000000AAAA8AAA42 +:103E000040561000FFFF0000007070070000000027 +:103E10000001000100000000AAAAAAAA00010000F7 +:103E2000FFFF000000000000000000000000000094 +:103E300000000000AAAAAAAA00000000FFFF0000DC +:103E40000000000000000000000000000000000072 +:103E5000AAAAAAAA00000000FFFF000000000000BC +:103E60000000000000000000000000000A00000048 +:103E7000000000000300000000000000000000003F +:103E80000000000000000000000000000000000032 +:103E90000000000000000000000000000000000022 +:103EA000090000000000000000C01F00000000002A +:103EB000FF00000098280020BC230020009600008E +:103EC0000000080096000000000800000400000048 +:103ED000DC3C0008000000000000000000000000C2 +:0C3EE000000000000000000000000000D6 :00000001FF diff --git a/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin b/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin index 60d444d05398d0..0ed4d44f8ca0bf 100755 Binary files a/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin and b/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin differ diff --git a/Tools/bootloaders/CubeRedPrimary_bl.bin b/Tools/bootloaders/CubeRedPrimary_bl.bin index 8070aaf1ad3780..f36ac6e09d40e1 100755 Binary files a/Tools/bootloaders/CubeRedPrimary_bl.bin and b/Tools/bootloaders/CubeRedPrimary_bl.bin differ diff --git a/Tools/bootloaders/CubeRedPrimary_bl.hex b/Tools/bootloaders/CubeRedPrimary_bl.hex index 5f48f1dbe44db9..af096624e2add1 100644 --- a/Tools/bootloaders/CubeRedPrimary_bl.hex +++ b/Tools/bootloaders/CubeRedPrimary_bl.hex @@ -1,1780 +1,1861 @@ :020000040800F2 -:1000000000060020F50500088D24000841240008A2 -:10001000692400084124000861240008F70500084D -:10002000F7050008F7050008F70500084D6000080F -:10003000F7050008F7050008F7050008F7050008B0 -:10004000F7050008F7050008F7050008F7050008A0 -:10005000F7050008F7050008216400084D64000852 -:1000600079640008A5640008D1640008F705000859 -:10007000F7050008F7050008F7050008F705000870 -:10008000F7050008F7050008F7050008F705000860 -:10009000F7050008F7050008F7050008FD640008EB -:1000A000F7050008F7050008F7050008F705000840 -:1000B000F7050008F7050008F7050008F705000830 -:1000C000F7050008F7050008F7050008F705000820 -:1000D000F7050008F7050008E9650008F7050008BE -:1000E00061650008F7050008F7050008F705000836 -:1000F000F7050008F7050008F7050008F7050008F0 -:10010000F7050008F7050008FD650008F705000879 -:10011000F7050008F7050008F7050008F7050008CF -:10012000F7050008F7050008F7050008F7050008BF -:10013000F7050008F7050008F7050008F7050008AF -:10014000F7050008F7050008F7050008F70500089F -:10015000F7050008F7050008F7050008F70500088F -:10016000F7050008F7050008F7050008F70500087F -:10017000F705000801580008F7050008F705000812 -:10018000F7050008F7050008F7050008F70500085F -:10019000F7050008F7050008F7050008F70500084F -:1001A000F7050008F7050008F7050008F70500083F -:1001B000D5650008F7050008F7050008F7050008F1 -:1001C000F7050008F7050008F7050008F70500081F -:1001D000F7050008ED570008F7050008F7050008C7 -:1001E000F7050008F7050008F7050008F7050008FF -:1001F000F7050008F7050008F7050008F7050008EF -:10020000F7050008F7050008F7050008F7050008DE -:10021000F7050008F7050008F7050008F7050008CE -:10022000F7050008F70500086D4C0008F705000801 -:10023000F7050008F7050008F7050008F7050008AE -:10024000F7050008F7050008F7050008F70500089E -:10025000F7050008F7050008F7050008F70500088E -:10026000F7050008F7050008F7050008F70500087E -:10027000F7050008F7050008F7050008F70500086E -:10028000F7050008F7050008F7050008F70500085E -:10029000F7050008F7050008F7050008F70500084E -:1002A000F7050008F7050008F7050008F70500083E -:1002B000F7050008F7050008F7050008F70500082E -:1002C000F7050008F7050008F7050008F70500081E -:1002D000F7050008F7050008F7050008F70500080E -:1002E000D9070008092100081924000800000000AF -:1002F00053B94AB9002908BF00281CBF4FF0FF318D -:100300004FF0FF3000F074B9ADF1080C6DE904CE88 -:1003100000F006F8DDF804E0DDE9022304B07047E0 -:100320002DE9F047089D04468E46002B4DD18A42A8 -:10033000944669D9B2FA82F252B101FA02F3C2F1DB -:10034000200120FA01F10CFA02FC41EA030E94406C -:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D -:1003600016E341EA034306FB07F199420AD91CEB65 -:10037000030306F1FF3080F01F81994240F21C8197 -:10038000023E63445B1AA4B2B3FBF8F008FB1033DF -:1003900044EA034400FB07F7A7420AD91CEB040414 -:1003A00000F1FF3380F00A81A74240F207816444E4 -:1003B000023840EA0640E41B00261DB1D440002369 -:1003C000C5E900433146BDE8F0878B4209D9002DCD -:1003D00000F0EF800026C5E9000130463146BDE857 -:1003E000F087B3FA83F6002E4AD18B4202D38242C1 -:1003F00000F2F980841A61EB030301209E46002D70 -:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 -:10041000002A40F09280A1EB0C014FEA1C471FFA22 -:100420008CFE0126200CB1FBF7F307FB131140EA09 -:1004300001410EFB03F0884208D91CEB010103F1D6 -:10044000FF3802D2884200F2CB804346091AA4B298 -:10045000B1FBF7F007FB101144EA01440EFB00FE6C -:10046000A64508D91CEB040400F1FF3102D2A645D1 -:1004700000F2BB800846A4EB0E0440EA03409CE770 -:10048000C6F12007B34022FA07FC4CEA030C20FA1D -:1004900007F401FA06F31C43F9404FEA1C4900FA3D -:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA -:1004B00040EA014108FB0EF0884202FA06F20BD92D -:1004C0001CEB010108F1FF3A80F08880884240F27D -:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 -:1004E00009FB101144EA014100FB0EFE8E4508D9BC -:1004F0001CEB010100F1FF346CD28E456AD9023841 -:10050000614440EA0840A0FB0294A1EB0E01A14225 -:10051000C846A64656D353D05DB1B3EB080261EB93 -:100520000E0101FA07F722FA06F3F1401F43C5E96D -:10053000007100263146BDE8F087C2F12003D840A3 -:100540000CFA02FC21FA03F3914001434FEA1C47E5 -:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 -:10056000064300FB0EF69E4204FA02F408D91CEB87 -:10057000030300F1FF382FD29E422DD90238634485 -:100580009B1B89B2B3FBF7F607FB163341EA034125 -:1005900006FB0EF38B4208D91CEB010106F1FF3874 -:1005A00016D28B4214D9023E6144C91A46EA00466B -:1005B00038E72E46284605E70646E3E61846F8E6FD -:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 -:1005D0004646EAE7204694E74046D1E7D0467BE727 -:1005E000023B614432E7304609E76444023842E79F -:1005F000704700BF02E000F000F8FEE772B637482F -:1006000080F30888364880F3098836483649086000 -:1006100040F20000CCF200004EF63471CEF2000140 -:100620000860BFF34F8FBFF36F8F40F20000C0F23E -:10063000F0004EF68851CEF200010860BFF34F8FF4 -:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 -:10065000CEF200010860062080F31488BFF36F8F8C -:1006600004F06CFA05F05CFC4FF055301F491B4A52 -:1006700091423CBF41F8040BFAE71D49184A9142E8 -:100680003CBF41F8040BFAE71A491B4A1B4B9A423C -:100690003EBF51F8040B42F8040BF8E7002018495C -:1006A000184A91423CBF41F8040BFAE704F084FA7F -:1006B00005F0A6FC144C154DAC4203DA54F8041BAB -:1006C0008847F9E700F050F8114C124DAC4203DABC -:1006D00054F8041B8847F9E704F06CBA00060020C0 -:1006E000002200200000000808ED00E000000020CB -:1006F00000060020506E000800220020C8220020C2 -:10070000C8220020B04A0020E0020008EC020008E5 -:10071000EC020008EC0200082DE9F04F2DED108AE4 -:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 -:10073000002383F311882846A047002003F096FB8E -:10074000FEE703F0AFFA00DFFEE70000054B10B54F -:1007500004460360806810B103685B6898472046D0 -:1007600010BD00BF5069000870B500F027FD04F00F -:100770000BF9054604F0D8F90446B8B9144B9D426C -:1007800016D001339D4241F2883512BF0446002540 -:100790000124104E002004F001F9304601F0D6FA91 -:1007A00040B944F6206003F067FBF6E70025F0E768 -:1007B0000546EEE70CB100F091F800F0F1FE00F014 -:1007C00069FD284600F028F900F088F8F9E700BF35 -:1007D000010007B0C82200200448054B054A036009 -:1007E00000230549836005F063BF00BFC8220020D5 -:1007F00050690008002500204D07000808B500F0EA -:1008000015FDA0F120035842584108BD07B5042149 -:1008100001900DEB010000F027FD03B05DF804FB33 -:1008200007B541F21203022101A8ADF8043000F02F -:100830001BFD03B05DF804FB38B5302383F311884A -:10084000174803680BB103F0F5FB0023154A4FF47A -:100850007A71134803F0E4FB002383F31188124CF0 -:10086000236813B12368013B2360636813B1636895 -:10087000013B63600D4D2B7833B963687BB902206F -:1008800000F0CEFD322363602B78032B07D1636821 -:100890002BB9022000F0C4FD4FF47A73636038BDB9 -:1008A00058230020390800087824002070230020F5 -:1008B000084B187003280CD8DFE800F00805020880 -:1008C000022000F0A5BD022000F098BD024B0022DE -:1008D0005A6070477023002078240020F7B54648FE -:1008E00001A901F0B3FB002800F08480434B444A87 -:1008F0001C46196801317AD004339342F9D16268F9 -:10090000404B9A4273D9404B9B6803F1006303F557 -:1009100000339A426BD2002000F0E2FC0220FFF785 -:10092000C7FF3A4B00219A6C99641A6F19671A6FC6 -:10093000DA6CD9645A6F59675A6F1A6D19659A6FD4 -:1009400099679B6F324BD3F8802042F00072C3F856 -:100950008020D3F8802022F00072C3F88020D3F8E2 -:10096000803072B64FF0E023C3F8084DD4E900049C -:10097000BFF34F8FBFF36F8F264AC2F88410BFF3C7 -:100980004F8F536923F480335361BFF34F8FD2F8F5 -:10099000803043F6E076C3F3C905C3F34E335B0101 -:1009A00003EA060C29464CEA81770139C2F87472D1 -:1009B000F9D2203B13F1200FF2D1BFF34F8FBFF3D9 -:1009C0006F8FBFF34F8FBFF36F8F536923F40033E3 -:1009D00053610023C2F85032BFF34F8FBFF36F8FC4 -:1009E000302383F31188854680F308882047024826 -:1009F00000F074FE03B0F0BDC82200200000020821 -:100A000020000208FFFF01080022002000450258D4 -:100A10000044025800ED00E02DE9F04FB04B9DB0CE -:100A20002022FF21079014A89E68DB68069300F03F -:100A300061FDAC4A1378A3B90121AB481170036082 -:100A4000302383F3118803680BB103F0F3FA00231A -:100A5000A64A4FF47A71A44803F0E2FA002383F324 -:100A60001188079B13B1A24B079A1A60A14A137809 -:100A7000032B03D0002313709D4A53600023079D6E -:100A80001F469B46CDE90433012000F0C1FC25B18F -:100A9000974B1B68002B00F05783002000F0C6FB2B -:100AA0000C900C9B002BF2DB012000F0A7FC0C9BB0 -:100AB000213B1F2BE8D801A252F823F03D0B000880 -:100AC000650B0008FB0B0008890A0008890A00086A -:100AD000890A0008A90E0008C3100008650F000865 -:100AE00041100008671000088D100008890A0008EE -:100AF0009F100008890A00080B110008DD0B000890 -:100B0000890A00084F1100088F0C0008C70D000863 -:100B1000890A0008B90F0008890A0008890A000834 -:100B2000890A0008890A0008890A0008890A000859 -:100B3000890A0008890A0008FB0B00080220FFF759 -:100B40005DFE002840F02B83079B0221059A0FA829 -:100B5000002A08BF1D4641F21233ADF83C3000F0C8 -:100B600083FB91E74FF47A7000F060FB041EEBDB2F -:100B70000220FFF743FE0028E6D0013C052C00F2DE -:100B80001083DFE804F0030A0D1013370523042156 -:100B90000FA80F9300F068FB17E004215048F9E715 -:100BA00004215548F6E704215448F3E74FF01C08A8 -:100BB000404608F1040800F095FB04210F900FA8AF -:100BC00000F052FBB8F12C0FF2D10120049B4FF042 -:100BD000000B00FA04F41C43E3B2049300F0D6FCCB -:100BE0002FB1049B03F00B030B2B08BF0025FFF76D -:100BF00017FE49E704214248CCE7002FA4D0049B0C -:100C000003F00B030B2B9FD10220FFF7F7FD0446E7 -:100C1000002899D00120002700F062FB0220FFF796 -:100C200047FE5FFA87F8404600F06AFB0546B0B120 -:100C30000C9940460137A1F140025142514100F068 -:100C40006FFB0028EDD10546059441F212130221F5 -:100C50000FA82746ADF83C3000F006FB14E72E46FF -:100C60000120FFF725FE1E4B9B68B34207D9304693 -:100C700000F038FB013040F097820436F3E700269D -:100C80001C4B274605941E70194B5E60A6E7002F8B -:100C90003FF45AAF049B03F00B030B2B7FF454AFCC -:100CA00064210DA800F0D6FA804600287FF44CAFEE -:100CB0000220FFF7A3FD044600283FF445AFDFF80C -:100CC00048908DF82F80D9F82420D9F8203053434C -:100CD0000D9A93421AD20B4800F0ACFB34E700BFE8 -:100CE0000022002074240020582300203908000826 -:100CF00078240020702300200422002008220020F5 -:100D00000C220020F4670008C8220020BE48474695 -:100D1000C24600F08FFBFFF783FD01210DF12F008C -:100D200000F0A2FA0D9B534541D900230EAA394683 -:100D30004846CDE90E330FAB00F0D4FC002884D038 -:100D400001F0ACFB0E9B00EB030801210DF12F001D -:100D500000F08AFA01F0A2FB404520D9484600F095 -:100D6000FBFE80B964210D9BA848013701FB0AF105 -:100D7000B1FBF3F18DF82F10C9B200F05BFBD9F88D -:100D800020309A44CEE701F089FB0F9B1844404580 -:100D90003FF65BAF01F082FB0E9B00EB03080E9B5E -:100DA0004FF47A70A3FB000303F066F8CDE76423E9 -:100DB00001210DF12F0027468DF82F3000F054FA55 -:100DC000002306930AE7002F3FF4BEAE049B03F016 -:100DD0000B030B2B7FF4B8AE0220FFF769FD322026 -:100DE00000F024FA041EFFF6AFAE069BA046E318FF -:100DF0000893874B089ADB689A423FF6A5AEB4F594 -:100E0000807F3FF7A1AEDFF80CA24FF000094C4500 -:100E10000EDD4FF47A7000F009FA0C900C9B002B59 -:100E2000FFF692AE0C9B09F101090AF8013BEEE7CF -:100E3000C820FFF7E3FC044600283FF485AE0027F6 -:100E4000DFF8D491CDE90E77B8F1000F02D1274633 -:100E5000089BB6E70FAB6F4A0699484602930EAB64 -:100E60003A44394401930DAB0093434601F056F8E0 -:100E700000283FF4EAAE01F013FB0D9B8A4609906F -:100E80001F44A8EB030801F00BFB099A0E9B9B186B -:100E90004AF10002834272EB0103F4D2484600F0AB -:100EA0005BFE0028EFD1CFE7002F3FF44DAE049B4F -:100EB00003F00B030B2B7FF447AE0220FFF7F8FC87 -:100EC000322000F0B3F9B0F10008FFF63DAE18F0A3 -:100ED00003047FF439AE4E4A08EB0603926893424E -:100EE0003FF632AEB8F5807F3FF72EAEDFF82491A3 -:100EF000A0450DDD4FF47A7000F098F90C900C9B32 -:100F0000002BFFF621AE0C9B013409F8013BEFE703 -:100F1000C820FFF773FC044600283FF415AE1F2ECF -:100F200011D8C6F1200214AB26F00300394942451E -:100F3000184428BF4246089200F0AAFA089AFF21F6 -:100F4000344800F0D7FAC8F38702324930464FEAF6 -:100F5000A80900F0D7FA074600283FF476AE06EB62 -:100F600089063BE60220FFF749FC00283FF4ECAD80 -:100F700000F0F4F900283FF4E7AD0024A046244B2C -:100F80009B68A34258D91F2C11D8149B01330ED053 -:100F900024F003031CAA134453F8203C0F9340464B -:100FA00004220FA9043401F0B7F88046E7E7204691 -:100FB00000F098F90F90F2E764210EA800F04AF9CA -:100FC000044600287FF4C0AD0220FFF717FC00287C -:100FD0003FF4BAAD0E9BA046DFF83CA003F0030936 -:100FE0000E99A1EB0901A14218D9214604230FAAA9 -:100FF000504600F0DFFF404604220FA901F08CF8B4 -:1010000004348046ECE700BF196800083168000826 -:101010000022002074230020C8220020B9F1000F14 -:101020000AD04B460FAA624800F0C4FF40464A4629 -:101030000FA901F071F880464046FFF7E7FBCDE5C8 -:10104000002364210FA80F9300F004F900287FF417 -:101050007BAD0220FFF7D2FB00283FF475AD0F985F -:1010600000F072F9E9E7002364210FA80F9300F064 -:10107000F1F800287FF468AD0220FFF7BFFB0028DD -:101080003FF462AD0F9800F061F9D6E70220FFF758 -:10109000B5FB00283FF458AD00F070F9CDE7022011 -:1010A000FFF7ACFB00283FF44FAD0FA9142000F070 -:1010B0006BF90890FFF7AAFB08990FA800F0D4F885 -:1010C0008CE5322000F0B2F8041EFFF63DADA30718 -:1010D0007FF43AAD374A04EB0B03926893423FF634 -:1010E00033AD0220FFF78AFB00283FF42DAD24F03A -:1010F00003045C44A3453FF471AD58460BF1040B67 -:1011000000F0F0F8FFF782FBF4E74FF47A70FFF796 -:1011100075FB00283FF418AD00F020F9002845D0F9 -:10112000149B01330BD0082214A9002000F0EAF927 -:1011300000283BD02022FF2114A800F0DBF9FFF7A4 -:101140006FFB1D4802F098FE1DB0BDE8F08F002F28 -:101150003FF4FAAC049B03F00B030B2B7FF4F4ACCD -:10116000002364210FA80F9300F074F804460028B0 -:101170007FF4EAAC0220FFF741FB804600283FF4F1 -:10118000E3ACFFF74DFB41F2883002F075FE0F989B -:1011900000F048FA4746254600F0F8F974E407469F -:1011A0001CE54FF0000BCFE405944EE53C464CE5C2 -:1011B000C822002000220020A08601007047000005 -:1011C0002DE9F84F4FF47A7306460D46002402FBD2 -:1011D00003F7DFF85080DFF8509098F900305FFA9D -:1011E00084FA5A1C01D0A34212D159F824002A468D -:1011F00031460368D3F820B03B46D847854207D133 -:10120000074B012083F800A0BDE8F88F0124E4E734 -:10121000002CFBD04FF4FA7002F02EFE0020F3E712 -:10122000C42400201022002014220020002307B52F -:10123000024601210DF107008DF80730FFF7C0FFCE -:1012400020B19DF8070003B05DF804FB4FF0FF30BC -:10125000F9E700000A46042108B5FFF7B1FF80F066 -:101260000100C0B2404208BD074B0A4630B41978AD -:10127000064B53F82140014623682046DD69044BA4 -:10128000AC4630BC604700BFC424002014220020BC -:10129000A086010070B5104C0025104E03F020F917 -:1012A00020803068238883420CD8002520880138AC -:1012B00003F012F923880544013BB5F5802F238004 -:1012C000F4D370BD03F008F9336805440133B5F574 -:1012D000003F3360E5D3E8E7C624002080240020E7 -:1012E00003F0DCB900F1006000F5003000687047E1 -:1012F00000F10060920000F5003003F053B90000E7 -:10130000054B1A68054B1B889B1A834202D910446F -:1013100003F0E2B80020704780240020C62400209B -:1013200038B50446074D29B128682044BDE8384047 -:1013300003F0EAB82868204403F0D4F80028F3D07A -:1013400038BD00BF802400200020704700F1FF500E -:1013500000F58F10D0F8000870470000064991F89A -:10136000243033B100230822086A81F82430FFF7C3 -:10137000BFBF0120704700BF84240020014B1868C4 -:10138000704700BF0010005C194B0138032208446D -:1013900070B51D68174BC5F30B042D0C1E88A642B3 -:1013A0000BD15C680A46013C824213460FD214F905 -:1013B000016F4EB102F8016BF6E7013A03F1080341 -:1013C000ECD181420B4602D22C2203F8012B0424DB -:1013D000094A1688AE4204D1984284BF967803F831 -:1013E000016B013C02F10402F3D1581A70BD00BF39 -:1013F0000010005C1C2200206C680008022803D149 -:10140000024B4FF400129A61704700BF0018025857 -:10141000022802D1014B20229A617047001802581D -:10142000022804D1024A536983F0200353617047B4 -:10143000001802580FB4124B30B51A78B5B042B943 -:101440000122104910481A704FF461430B6001F0FB -:10145000B1FE39AB0C4C389AC82102A8019300F0B8 -:10146000EDFF2368C8280246DD6902A9074B28BFA3 -:10147000C8222046A84735B0BDE8304004B07047C8 -:10148000C8240020CC24002024250020A0860100B0 -:10149000002310B5934203D0CC5CC4540133F9E768 -:1014A00010BD0000013810B510F9013F3BB191F9B2 -:1014B00000409C4203D11AB10131013AF4E71AB15C -:1014C00091F90020981A10BD1046FCE70138013947 -:1014D00010F9013F11F9012F0BB19342F8D0981A7E -:1014E0007047000003460246D01A12F9011B00297A -:1014F000FAD1704702440346934202D003F8011B1D -:10150000FAE770472DE9F8431F4D14460746884611 -:1015100095F8242052BBDFF870909CB395F82430E6 -:101520002BB92022FF2148462F62FFF7E3FF95F8F1 -:1015300024004146C0F1080205EB8000A24228BF0A -:101540002246D6B29200FFF7A3FF95F82430A41BE1 -:1015500017441E449044E4B2F6B2082E85F8246085 -:10156000DBD1FFF7FBFE0028D7D108E02B6A03EBA5 -:1015700082038342CFD0FFF7F1FE0028CBD10020B9 -:10158000BDE8F8830120FBE784240020024B1A7891 -:10159000024B1A70704700BFC424002010220020A4 -:1015A00038B51A4C1A4D204601F0A6FE29462046B1 -:1015B00001F0CEFE2D681748D5F89020D2F80438F7 -:1015C00043F00203C2F8043802F056FC12492846E0 -:1015D00001F0CCFFD5F89020104DD2F804382868DF -:1015E00023F002030E49A042C2F804384FF4E1335D -:1015F0000B6001D001F0DEFD6868A04204D008490C -:10160000BDE8384001F0D6BD38BD00BF002C002039 -:10161000946B000840420F009C6B000814220020CD -:10162000AC2400200C4B70B50C4D04461E780C4BBE -:1016300055F826209A420DD00A4B00211822184650 -:10164000FFF758FF0460014655F82600BDE87040DA -:1016500001F0B0BD70BD00BFC424002014220020E2 -:10166000002C0020AC24002080697047C0697047BE -:10167000006A7047406A7047806A7047F0B5ADF203 -:10168000044D0E46054600214FF47F7201A80091DB -:10169000FFF730FF2C6A744301362B6A7343A34271 -:1016A00016D92B686A46214628465F684FF4806346 -:1016B000B84770B16A464FF4806312F8011BFF29E6 -:1016C0000AD1013B9BB2002BF7D104F58064E4E71B -:1016D00001200DF2044DF0BD0020FAE78068036898 -:1016E000DB69184730B5456A85B004468D420FD393 -:1016F0000568CDE90023026A03ABAD6A5143A847F0 -:1017000020B1206A039BC31A5842584105B030BD2E -:101710000020FBE7F0B5C56987B004468D4212D3BF -:101720000C9F866905687143CDE9013705AB0093CD -:101730006D69036AA84720B1A069059BC31A584286 -:10174000584107B0F0BD0020FBE70000F0B566236C -:1017500089B0002405464FF480768068079403A979 -:10176000CDE90336CDE9054403685B699847A8686D -:1017700022462146036800941F692346B847A8689B -:101780009923079403A9CDE90336CDE905440368FD -:101790005B699847A86822462146036800941D6942 -:1017A0002346A84709B0F0BD254B2DE9F04F1B7823 -:1017B0009FB0002504468DF828304FF09F0E8068BA -:1017C0004FF00123ADF8295005A90995CDE905E3AE -:1017D000CDE9075503685B699847A068032229464D -:1017E000036800922A461E690AABB04730B394F8EA -:1017F0008C200C21134B01FB02339DF828101A7921 -:1018000091421BD19DF829205B799A4216D1A0689C -:101810004FF05A0C0C4B082605A90996CDE905C3D3 -:10182000CDE9075503685B699847A0682A462946B1 -:10183000036800961F690AABB84738B900204BE12E -:10184000DC67000824690008002500010422B34970 -:101850000AA804F067FF05460028EFD1BDF82C3038 -:101860006FF48277A3813B44012BE7D8079605A943 -:10187000CDE90A00A06803685B699847A0682A461A -:101880002946036800961E690AABB0470028D5D0E8 -:10189000DDE90A361A0202F4706242EA1662FF2A91 -:1018A000CCD11B0E26F07F4650222946142B2661F0 -:1018B0000AA828BF1423A373FFF71CFEA06807968D -:1018C00005A903685B699847A068A37B294602685D -:1018D0009B0000930AAB16692A46B0470028ADD09A -:1018E0000B990029AADBC9086FF07E43149D4FF0C5 -:1018F000010E994228BF1946C5F303130EFA03F2ED -:1019000021FA03F303916161A261E361002B95D099 -:101910002646A44600274FF002081EAAC7F3460336 -:1019200002EB830353F834AC07F001031B01DA1D0B -:101930000EFA03F908FA02F2A2EB090202EA0A021D -:10194000DA401AD003F108090F330EFA02F2216AC5 -:1019500008FA03F30EFA09FBCCF830208A42A3EB15 -:101960000B0B0BEA0A0A2AFA09F98CF82C90A36AE5 -:1019700088BF2262934288BFA26201370CF1100C2B -:10198000042FCAD1236A4FF0020C039A4FF0010EC4 -:10199000139F9A4224BFB2FBF3F1616207F00F017B -:1019A00038BF01234FF0090201F1010138BF636222 -:1019B0004900336B33B3531C0EFA02F8A2F1050948 -:1019C0000CFA03F30EFA09FAA3EB080302F1FF384D -:1019D0000CFA08F83B40A8EB0A08D34008EA0708CD -:1019E00028FA09F87BD0012B7BD0022B7BD0032B6C -:1019F00008BF4FF47A735FFA88F808FB0333736308 -:101A00004B43B36307321036252AD2D115F0C04FAD -:101A1000C5F3417369D0012B69D0022B0CBF4FF481 -:101A20007A634FF47A43C5F3046202FB0333E3663F -:101A30004B432367199B9E075CD0062384F87430C0 -:101A400015F4005F05F00F03C5F3042514BF402211 -:101A50000822013305FB02255B00A5675D430A9B55 -:101A60009F02E5677FF5EAAE0C9BC3F30722C3F341 -:101A7000421103F01F0384F8802084F8881084F852 -:101A80008130002A3FF4DAAE189BC3F3025213F4FC -:101A9000401F84F883207FF4D1AEDE0602D5042AED -:101AA0007FF4CCAE03F40072002A14BF012200229E -:101AB00084F8872004D0DD0324D5002384F88930FE -:101AC000179B1A0722D5002384F88630702384F8E8 -:101AD0008530012384F88D301FB0BDE8F08F0123DD -:101AE00089E7102387E7802385E710239BE74FF4DE -:101AF000807398E7590701D550239FE713F0780FBB -:101B00009ED09BE69903DBD50123D7E75B07E0D5A1 -:101B1000012384F886300523D9E700BF7C680008DC -:101B200030B58BB000240546806803924FF0012247 -:101B3000059105A9CDE90624CDE90844026852695A -:101B40009047A8680121039B02680091214615690E -:101B50002246A8470BB030BD13B50446A068036801 -:101B6000DB6C98470028F9D10DF1070294F8851035 -:101B70002046FFF7D5FF94F886309DF807001BB18B -:101B800000F0010002B010BDC043C0F3C010F9E77F -:101B900030B54FF001238BB00024054680688DF8E6 -:101BA0000F20059105A9CDE90634CDE90844036865 -:101BB0005B699847A86801220DF10F010368009442 -:101BC0001D692346A8470BB030BD0000F7B5174686 -:101BD0000DF1070206461D46FFF7A2FF68B19DF80A -:101BE000074039469DF82020304624EA05042A4063 -:101BF00022438DF80720FFF7CBFF03B0F0BD0000B4 -:101C000030B54FF4807389B0002405468068039195 -:101C100003A9CDE90434CDE9064403685B6998471C -:101C2000A86822462146036800941D692346A847F8 -:101C300009B030BD10B5044623682046DB6A9847DA -:101C40000028F9D110BD000010B590F8743004469A -:101C50005BB1FFF7EFFF012394F87410204684F87E -:101C60008E30BDE81040FFF7CBBF012010BD000053 -:101C700010B590F87430044653B1FFF7DBFF012331 -:101C80002046042184F88E30BDE81040FFF7B8BF2D -:101C9000012010BDF0B590F883308BB00446042BC2 -:101CA00050D100270DF10E0205218DF80E708DF830 -:101CB0000F70FFF735FF00282FD00DF10F023521EF -:101CC0002046FFF72DFF40B320461F4EFFF7BCFF15 -:101CD0002046FFF7AFFF05AD0FCE0FC5336805A94E -:101CE0009DF80E202B609DF80F30A06843F0020392 -:101CF0008DF810208DF80F308DF8113003685B6976 -:101D00009847A068022204A9036800971D693B4612 -:101D1000A84720B92046FFF7ABFF002010E020467F -:101D2000FFF7A6FF0DF10F0235212046FFF7F8FE61 -:101D30000028F2D09DF80F309B07EED50123636099 -:101D40000BB0F0BD0120FBE7E06700082DE9F3418F -:101D5000002304468068A36010B103685B6898475D -:101D60000025264E264F0C2301A839465FFA85F838 -:101D70006B439A5900F072FA019BA0680022A3609D -:101D8000019210B103685B689847019810B103682D -:101D90005B689847A368E3B141F2883084F88C808F -:101DA00002F06AF82046FFF7D1FC1E2002F064F82A -:101DB0002046FFF7F9FC054688B994F88C300C22D0 -:101DC00010485343F158FFF735FB284602B0BDE8F1 -:101DD000F0810135032DC6D10B4800F059FB204698 -:101DE000FFF758FF0C2294F88C3005465343F15806 -:101DF00008B90648E7E70648E5E700BF2469000898 -:101E0000E424002084680008FA680008AE6800082E -:101E1000D86800082DE9F041044688B00F46164600 -:101E2000FFF712FF2046FFF705FF0025C722A06835 -:101E30004FF48073079503A9CDE90323CDE9055538 -:101E400003685B699847A0682A462946036800959D -:101E5000D3F810802B46C047054630B92046FFF71F -:101E600007FF284608B0BDE8F081E36E3B60236FB2 -:101E70003360F3E72DE9F041002588B01F460446A2 -:101E80000E460E9B00F1400CA8463D60016B81B1EF -:101E9000A9420ED391420CD8B6FBF1FE01FB1E61A4 -:101EA00039B9416B90F82C800F9D1960816B2960C6 -:101EB000154610306045E9D16DB3AB1962699342A4 -:101EC00029D82046FFF7C0FE2046FFF7B3FE4FF4A7 -:101ED0001453A06803A9CDF80C80CDE90436002680 -:101EE000CDE9066603685B699847A06832463146CB -:101EF00003680096D3F810803346C0470646204654 -:101F00002EB9FFF7B5FE304608B0BDE8F081FFF707 -:101F1000AFFE3D60F7E70026F5E700002DE9F04150 -:101F20008669054688B00F46B3429046B1FBF6FC81 -:101F300006FB1C1C28BF3346A6EB0C0C00269C4558 -:101F4000644628BF1C46FFF77FFE2846FFF772FE57 -:101F50000222A86803A9164B0597CDE90323CDE912 -:101F6000066603685B699847A8682246414603688D -:101F700000961F693346B847064628462EB9FFF734 -:101F800077FE304608B0BDE8F081FFF771FE0E9B8A -:101F90001C60AB6FAA696343B3FBF2F30F9A136043 -:101FA000EA6F109B5443AA69B4FBF2F41C60E8E7A3 -:101FB000002500012DE9F04FCE18436989B0044691 -:101FC0009E420F46914639D83D464FF40458DFF8FB -:101FD00078A0FFF72FFEAE4234D994F88030A6EBFC -:101FE000050B94F8882003A903930023BBF5806FA9 -:101FF000A0680693636828BF4FF4806B0595012B9A -:1020000014BF43465346012A049394F8813008BF15 -:1020100003F1FF33079303685B699847A068A9EB56 -:1020200007030268CDF800B02B44D2F810B00022AC -:102030001146D84718B105F58065CCE7002009B0F6 -:10204000BDE8F08F0120FAE700ED0003F0B504468B -:1020500089B00E46FFF7EEFD94F887502DB194F845 -:1020600089302BB1012B24D00025284609B0F0BDC2 -:1020700094F880300393F02306934FF404530493B1 -:102080006368012B04BF1D4B04930023059394F850 -:102090008130A06803A9079303685B699847A0682B -:1020A000314603689B6998470546642001F0E4FEC9 -:1020B000DBE720460027FFF7C7FD2046FFF7BAFD04 -:1020C00008238122852120460097FFF77FFD0546E2 -:1020D00018B92046FFF7CCFDC7E794F88030069783 -:1020E0000393074B04936368012B04BF054B0493D0 -:1020F0000023059394F88130013BCAE700ED00030B -:102100000021001000ED0013014B024A1A607047D5 -:10211000E42400204C6A000830B50A44084D91427E -:102120000DD011F8013B5840082340F30004013B57 -:102130002C4013F0FF0384EA5000F6D1EFE730BDE6 -:102140002083B8ED70470000704700000020704702 -:102150000020704713B56C4600F1140384E80600B4 -:1021600094E8030083E8050002B010BD002070472A -:1021700013B56C4600F10C0384E8060094E80300F4 -:1021800083E8050002B010BD0023C0E903337047A7 -:1021900082B002AB03E9060002B07047704700004E -:1021A00000207047704700000020704700207047F3 -:1021B0000120704782B0002002A901E90C0002B0A2 -:1021C000704700000020704700207047036B1A79A9 -:1021D000034B53F832309B699868C0F34010704746 -:1021E000E46900080B6883634B6843638B68C363CF -:1021F000CB6803640B6943647047000038B5036B18 -:102200000446154D1B7955F8330001F0AFFCD4E9B5 -:102210000B231B7955F8331002F1300349689942BA -:1022200018D000231363E26A5363D4E90B12537C82 -:10223000581E137C92681B0443EA002313438B63EC -:10224000D4E90B131B79303155F83300BDE8384021 -:1022500001F020BC38BD00BFE4690008F8B51D4F8F -:1022600005460E4611463868FFF730F978BB7468AA -:102270003B7924B394F82C209A420BD02468F8E7D9 -:102280000122B52100F00EF9736823603B79746078 -:1022900084F82C30482004F015FA68B1002202714D -:1022A000C0E90322C0E90522027A42F00702027265 -:1022B000094AC0E90B47026028602846F8BD402063 -:1022C00004F000FA04460028DAD12C60F5E7002378 -:1022D0002B60F2E7EC240020F4690008044B10B5F1 -:1022E00004460360406A08B104F0EAF9204610BDD4 -:1022F0009869000810B50446FFF7F0FF204604F087 -:10230000DDF9204610BD000008B519B1FFF776FFD2 -:10231000012008BD036B1A79024B53F8320001F01B -:1023200029FCF5E7E46900082DE9FF41DDF8288084 -:102330000546174603911FFA88F60293FFF75EFFE2 -:1023400002ABBAB203A9E86A009600F0BFF80446EF -:1023500038B900212846FFF7D7FF204604B0BDE872 -:10236000F081AFB92B6B05F134011A79134B53F897 -:102370003200B8F1000F19D101F09AFB80F001048E -:10238000E4B23346E86ADDE9022100F0C5F8E0E78F -:10239000029B83B92B6B3A46084805F134011C793E -:1023A000039B50F8340001F099FBE7E7029B42469B -:1023B00001F0AAFBE2E70024E3E700BFE4690008BC -:1023C00013B504460191FFF719FF019A236B04F13D -:1023D00034011879054B53F8300001F0ABFB0021B4 -:1023E0002046FFF791FF012002B010BDE46900080C -:1023F00010B50446FFF702FF236B1A79054B53F81B -:10240000320001F0A5FB00212046FFF77DFF0120EF -:1024100010BD00BFE4690008054B064A1A6000229F -:102420001A719A60044ADA6040F21F121A827047E9 -:10243000EC2400201B69000800E1F50500F07EBADD -:1024400000B59BB0EFF3098168226846FFF720F8DA -:10245000EFF30583014B9B6BFEE700BF00ED00E04F -:1024600008B5FFF7EDFF000000B59BB0EFF3098161 -:1024700068226846FFF70CF8EFF30583014B5B6BAE -:10248000FEE700BF00ED00E0FEE70000FEE7000011 -:102490000FB408B5029801F07BFCFEE702F014BA15 -:1024A00002F0ECB938B5084B044615460175436097 -:1024B0000A21243002F0A6FA04F128002A460A2153 -:1024C00002F0A0FA204638BD606A0008F8B51E4642 -:1024D0001B6805460C4617461BB9236863B90124DF -:1024E00008E0BDF818203146806A02F0A3FA0028FF -:1024F000F3D100242046F8BD21463A46686A02F02E -:10250000CFFA04460028EAD13368002BF1D0A86A3C -:1025100002F0FAFAEEE7000038B50D46114604461F -:102520001A4611B1806A02F0ADFA2DB12946606AEF -:10253000BDE8384002F0E0BA38BD00000368002171 -:102540001B68184703790BB10022027118467047C7 -:1025500003685B681847000003791BB90123037106 -:1025600018467047002070477047000010B50446B9 -:1025700004F0A4F8204610BDF0B500F10B0423468A -:102580000D46B1FBF2F102FB115707F13006392E6F -:10259000C8BF07F13706954203F8016DF0D2421E1D -:1025A000E11A13F8015B9C4202F8015FF9D108447B -:1025B000F0BD00002DE9F04F804687B015464FF082 -:1025C00000090C4614F8013B002B3BD0252B08D00A -:1025D000D8F800201946404609F10109D268904711 -:1025E00049E14B782D2B06BF8C1C0123002301935E -:1025F00023782B2B06BF01340127002794F800A075 -:10260000BAF1300F0CBF01344FF0200A23782A2B87 -:102610001CD16178023455F804BB2E2943D12178AE -:1026200081B12A2921D0661C0020A1F13002344654 -:10263000D2B2092A1DD80A2316F8011B03FB002079 -:102640000029F2D1484607B0BDE8F08F4FF0000BEB -:1026500014F8011B0029F5D0A1F13002D2B2092AE9 -:10266000DBD80A2303FB0B2BF2E76178023455F821 -:10267000040B01F0DF024C2A17D121780029E1D0A8 -:10268000782904F101041FD8622900F20081582939 -:102690001AD84E2900F23081442900F0918049294E -:1026A00000F08E8010E00020E3E7A1F141027829DC -:1026B000D2B209D862290BD8582905D84E293BD85F -:1026C000442978D0492976D02E468DF80C1056E052 -:1026D000A1F16306152EF7D80FF2040C5CF826F072 -:1026E00071270008B7270008C9260008C926000876 -:1026F000C9260008C9260008B7270008C92600080F -:10270000C9260008C9260008C9260008C9260008ED -:102710004728000835290008C9260008C9260008EE -:1027200087270008C926000831290008C9260008A3 -:10273000C926000835290008A1F14F02092AC3D88B -:1027400001A050F822F000BF4728000835290008F2 -:10275000C9260008C9260008C9260008C92600089D -:1027600031290008C9260008C926000835290008B3 -:102770002E464FF0200A56F8042B8DF80C2003AD9E -:102780000DF10D002BE02E4647F6FF726A4B56F80E -:10279000045B002808BF1046002D08BF1D462A46CE -:1027A0002F18104612F8011B11B1B91A0029F8DAD6 -:1027B0004FF0200A13E02E46192A56F8041B02D8BF -:1027C0002E4656F8041B002936DA2D2249428DF890 -:1027D0000C200DF10D000A2203ADFFF7CDFE471BC3 -:1027E0000199ABEB070323EAE372002945D1002BE3 -:1027F000C2F1000B1EDD29782D2901D02B290DD126 -:10280000BAF1300F0AD1D8F800304046019209F1F0 -:102810000109DB68013F98470135019AD8F800307B -:10282000514640460192DB6898471BF1010B019A23 -:10283000F4D191443B4615E01FB12B228DF80C20BA -:10284000C7E703A8C7E708222E4603A856F8041BCB -:10285000C2E7D8F80020404615F8011BD268019362 -:102860009047019B013BF4D5002FA8BFB9445D46BA -:102870002DB9D94435462146A3E69346DAE7D8F880 -:10288000003051464046013DDB689847F0E7A1F132 -:102890006302152A3FF618AF01A353F822F000BFD8 -:1028A00071270008C1270008C9260008C9260008AA -:1028B000C9260008C9260008C1270008C926000843 -:1028C000C9260008C9260008C9260008C92600082C -:1028D0004728000835290008C9260008C92600082D -:1028E00087270008C926000831290008C9260008E2 -:1028F000C926000835290008A1F14F02092A3FF630 -:10290000E3AE01A353F822F0472800083529000858 -:10291000C9260008C9260008C9260008C9260008DB -:1029200031290008C9260008C926000835290008F1 -:102930000A2289E7102287E7786A0008F0B5054681 -:1029400087B016461F460C4689B14A1E0023294609 -:1029500001A800F05FF83A46314601A8FFF72AFEC9 -:10296000049BA3423CBF0022EA5407B0F0BD0A46D4 -:10297000ECE70000D0E902239A421FBF4268D1541D -:10298000C36801331ABFC36000206FF001007047B5 -:10299000D0E903239A421FBF4268D25C013303612E -:1029A00014BF10466FF001007047000003692BB19F -:1029B000013B426803610020D15470476FF0010071 -:1029C0007047000038B504460846D4E903315B1A65 -:1029D000934228BF13461D4663682A461944FEF7F2 -:1029E00057FD236928462B44236138BD38B504467A -:1029F000D0E902301B1A934228BF13461D46636874 -:102A00002A461844FEF744FDE36828462B44E36059 -:102A100038BD000010B5C0E90223034C0023C0E913 -:102A20000041036110BD00BF806A00088A0710B52D -:102A300004461DD50378042B1AD143681B682BB1BB -:102A40000522027098472378052B01D102232370B9 -:102A5000302383F31188002104F1080001F026FAE5 -:102A6000002383F31188E069BDE8104002F0BCB98F -:102A7000CB0704D50248BDE8104001F089B910BD6C -:102A8000986A000810B5044C204600F0FBFF034A8A -:102A90000023C4E9062310BD042500200050005285 -:102AA00010B503780446012B12D10E4B98420FD17A -:102AB00002460D49102002F069F90C4BE0615A6B97 -:102AC00042F480425A63DA6D42F48042DA65DB6D8B -:102AD0006268A36992685A60054A1A601B22DA602C -:102AE00010BD00BF042500202D2A00080045025813 -:102AF0001500020182691B2310B5D360D1E90030B3 -:102B000013F44C4406D19B011461D06103F440439B -:102B1000536110BD0024184313F4406F1461CC6856 -:102B2000D4615061F5D08B689361F2E730B5846968 -:102B30001B25C069E5600068836104F12003C3615F -:102B400002234261013A03614223C3601623836278 -:102B5000CB682261E361D1E90023134312F4406F93 -:102B6000636101D08B68A361C36843F00103C36054 -:102B700030BD000030B5D0E90640006804F1200502 -:102B80008561C36108234261013A036146230D69EF -:102B9000C36016238362CB682261E361D1E900231D -:102BA000134312F4406F43EA854343F0806363614B -:102BB00001D08B68A361C36843F00103C36030BDDB -:102BC0008069036823F0040310B5CC680360002318 -:102BD0000361C4618361D1E900430969234343EA86 -:102BE000814343F04063436112B14FF010431360DF -:102BF00010BD000083691A6842F002021A601A6868 -:102C00009207FCD41A6842F004021A607047000070 -:102C10008269936810B5D3609B0704461DD503787D -:102C2000032B1AD143681B682BB105220270984709 -:102C30002378052B01D102232370302383F31188DD -:102C4000002104F1080001F031F9002383F3118819 -:102C5000E069BDE8104002F0C7B810BD02684368E3 -:102C60001143016003B1184770470000024A13681E -:102C700043F0C003136070470044004013B50E4C8E -:102C8000204600F08BFA04F1140000234FF4007288 -:102C90000A49009400F048F9094B4FF400720949C1 -:102CA00004F13800009400F0C1F9074A074BC4E969 -:102CB000172302B010BD00BF24250020902500205E -:102CC0006D2C0008902700200044004000E1F5052D -:102CD000037C30B5214C002918BF0C46012B0CD1C8 -:102CE0001F4B984209D11F4B9A6C42F400329A64F0 -:102CF0001A6F42F400321A671B6F2268036EC16DAF -:102D000003EB52038466B3FBF2F36268150442BF1F -:102D100023F0070503F0070343EA4503CB60A368EC -:102D200043F040034B60E36843F001038B6042F4DF -:102D3000967343F001030B604FF0FF330B625105B4 -:102D400005D512F0102205D0B2F1805F04D080F8D2 -:102D5000643030BD7F23FAE73F23F8E7A86A000814 -:102D600024250020004502582DE9F047C66D054690 -:102D70003768F469210734621AD014F0080118BFCB -:102D80004FF48071E20748BF41F02001A3074FF0E4 -:102D9000300348BF41F04001600748BF41F0800167 -:102DA00083F31188281DFFF759FF002383F311884F -:102DB000E2050AD5302383F311884FF48061281D82 -:102DC000FFF74CFF002383F311884FF030094FF0D9 -:102DD000000A14F0200838D13B0616D54FF0300910 -:102DE00005F1380A200610D589F31188504600F005 -:102DF00051F9002836DA0821281DFFF72FFF27F0A8 -:102E000080033360002383F31188790614D56206AA -:102E100012D5302383F31188D5E913239A4208D1C0 -:102E20002B6C33B127F040071021281DFFF716FF48 -:102E30003760002383F31188E30618D5AA6E13695F -:102E4000ABB15069BDE8F047184789F31188736A40 -:102E5000284695F86410194000F0BAF98AF31188F1 -:102E6000F469B6E7B06288F31188F469BAE7BDE89F -:102E7000F0870000F8B51546826804460B46AA4262 -:102E800000D28568A1692669761AB5420BD2184628 -:102E90002A46FEF7FDFAA3692B44A3612846A368DE -:102EA0005B1BA360F8BD0CD9AF1B18463246FEF77A -:102EB000EFFA3A46E1683044FEF7EAFAE3683B4449 -:102EC000EBE718462A46FEF7E3FAE368E5E7000079 -:102ED00083689342F7B50446154600D28568D4E965 -:102EE0000460361AB5420BD22A46FEF7D1FA63695E -:102EF0002B4463612846A3685B1BA36003B0F0BD4D -:102F00000DD93246AF1B0191FEF7C2FA01993A463C -:102F1000E0683144FEF7BCFAE3683B44E9E72A463F -:102F2000FEF7B6FAE368E4E710B50A440024C3618B -:102F3000029B8460C16002610362C0E90000C0E9D5 -:102F4000051110BD08B5D0E90532934201D1826860 -:102F500082B98268013282605A1C42611970002174 -:102F6000D0E904329A4224BFC368436100F0B8FF3D -:102F7000002008BD4FF0FF30FBE7000070B53023A4 -:102F800004460E4683F31188A568A5B1A368A2691B -:102F9000013BA360531CA36115782269934224BFAF -:102FA000E368A361E3690BB120469847002383F3EC -:102FB0001188284607E03146204600F081FF0028AE -:102FC000E2DA85F3118870BD2DE9F74F04460E460D -:102FD00017469846D0F81C904FF0300A8AF31188B3 -:102FE0004FF0000B154665B12A4631462046FFF7E3 -:102FF00041FF034660B94146204600F061FF0028CA -:10300000F1D0002383F31188781B03B0BDE8F08F63 -:10301000B9F1000F03D001902046C847019B8BF304 -:103020001188ED1A1E448AF31188DCE7C160C36180 -:10303000009B82600362C0E905111144C0E90000F1 -:1030400001617047F8B504460D461646302383F3F8 -:103050001188A768A7B1A368013BA36063695A1CE4 -:1030600062611D70D4E904329A4224BFE36863614F -:10307000E3690BB120469847002080F3118807E0F0 -:103080003146204600F01CFF0028E2DA87F3118861 -:10309000F8BD0000D0E9052310B59A4201D182683D -:1030A0007AB982680021013282605A1C82611C78E0 -:1030B00003699A4224BFC368836100F011FF204670 -:1030C00010BD4FF0FF30FBE72DE9F74F04460E46E9 -:1030D00017469846D0F81C904FF0300A8AF31188B2 -:1030E0004FF0000B154665B12A4631462046FFF7E2 -:1030F000EFFE034660B94146204600F0E1FE00289D -:10310000F1D0002383F31188781B03B0BDE8F08F62 -:10311000B9F1000F03D001902046C847019B8BF303 -:103120001188ED1A1E448AF31188DCE702684368AF -:103130001143016003B11847704700001430FFF7D6 -:1031400043BF00004FF0FF331430FFF73DBF0000D6 -:103150003830FFF7B9BF00004FF0FF333830FFF7CA -:10316000B3BF00001430FFF709BF00004FF0FF317C -:103170001430FFF703BF00003830FFF763BF0000D3 -:103180004FF0FF323830FFF75DBF0000012914BF58 -:103190006FF0130000207047FFF770BD044B036011 -:1031A00000234360C0E9023301230374704700BF6A -:1031B000C06A000810B53023044683F31188FFF776 -:1031C00087FD02230020237480F3118810BD0000C6 -:1031D00038B5C36904460D461BB904210844FFF7FE -:1031E000A5FF294604F11400FFF7ACFE002806DA1B -:1031F000201D4FF40061BDE83840FFF797BF38BD90 -:10320000026843681143016003B11847704700002A -:1032100013B5406B00F58054D4F8A4381A681178BF -:10322000042914D1017C022911D1197901231289B1 -:103230008B4013420BD101A94C3002F029FCD4F889 -:10324000A4480246019B2179206800F0DFF902B012 -:1032500010BD0000143002F0ABBB00004FF0FF3394 -:10326000143002F0A5BB00004C3002F07DBC000021 -:103270004FF0FF334C3002F077BC0000143002F006 -:1032800079BB00004FF0FF31143002F073BB000037 -:103290004C3002F049BC00004FF0FF324C3002F0DD -:1032A00043BC00000020704710B500F58054D4F8EE -:1032B000A4381A681178042917D1017C022914D185 -:1032C0005979012352898B4013420ED1143002F0F8 -:1032D0000BFB024648B1D4F8A4484FF4407361791F -:1032E0002068BDE8104000F07FB910BD406BFFF7CB -:1032F000DBBF0000704700007FB5124B012504269C -:10330000044603600023057400F1840243602946EB -:10331000C0E902330C4B0290143001934FF4407318 -:10332000009602F0BDFA094B04F69442294604F1D6 -:103330004C000294CDE900634FF4407302F084FB2B -:1033400004B070BDE86A0008ED32000811320008D0 -:103350000A68302383F311880B790B3342F823007A -:103360004B79133342F823008B7913B10B3342F8B6 -:10337000230000F58053C3F8A4180223037400202F -:1033800080F311887047000038B5037F044613B1FD -:1033900090F85430ABB90125201D0221FFF730FF12 -:1033A00004F114006FF00101257700F0A5FD04F190 -:1033B0004C0084F854506FF00101BDE8384000F033 -:1033C0009BBD38BD10B5012104460430FFF718FF3E -:1033D0000023237784F8543010BD000038B504462C -:1033E0000025143002F074FA04F14C00257702F045 -:1033F00043FB201D84F854500121FFF701FF2046B4 -:10340000BDE83840FFF750BF90F8803003F060030C -:10341000202B06D190F881200023212A03D81F2ACF -:1034200006D800207047222AFBD1C0E91D3303E0F3 -:10343000034A426707228267C3670120704700BFC3 -:103440003422002037B500F58055D5F8A4381A6825 -:10345000117804291AD1017C022917D11979012385 -:1034600012898B40134211D100F14C04204602F026 -:10347000C3FB58B101A9204602F00AFBD5F8A448C5 -:103480000246019B2179206800F0C0F803B030BDEE -:1034900001F10B03F0B550F8236085B004460D46EA -:1034A000FEB1302383F3118804EB8507301D08211A -:1034B000FFF7A6FEFB6806F14C005B691B681BB1B9 -:1034C000019002F0F3FA019803A902F0E1FA024632 -:1034D00048B1039B2946204600F098F8002383F367 -:1034E000118805B0F0BDFB685A691268002AF5D052 -:1034F0001B8A013B1340F1D104F18002EAE700008E -:10350000133138B550F82140ECB1302383F31188E2 -:1035100004F58053D3F8A4281368527903EB82038F -:10352000DB689B695D6845B104216018FFF768FEA0 -:10353000294604F1140002F0E1F92046FFF7B4FE39 -:10354000002383F3118838BD7047000001F09EBC52 -:1035500001234022002110B5044600F8303BFDF75E -:10356000C9FF0023C4E9013310BD000010B53023AA -:10357000044683F311882422416000210C30FDF7BA -:10358000B9FF204601F0A4FC02230020237080F341 -:10359000118810BD70B500EB8103054650690E46D9 -:1035A0001446DA6018B110220021FDF7A3FFA069CC -:1035B00018B110220021FDF79DFF31462846BDE8D5 -:1035C000704001F085BD000083682022002103F0D7 -:1035D000011310B5044683601030FDF78BFF2046C1 -:1035E000BDE8104001F000BEF0B4012500EB8104FD -:1035F00047898D40E4683D43A469458123600023E9 -:10360000A2606360F0BC01F01DBE0000F0B40125B3 -:1036100000EB810407898D40E4683D4364690581BE -:1036200023600023A2606360F0BC01F093BE000041 -:1036300070B5022300250446242203702946C0F8F1 -:1036400088500C3040F8045CFDF754FF204684F8A5 -:10365000705001F0D1FC63681B6823B129462046F5 -:10366000BDE87040184770BD0378052B10B50446BF -:103670000AD080F88C300523037043681B680BB1B7 -:10368000042198470023A36010BD0000017805299C -:1036900006D190F88C20436802701B6803B118476C -:1036A0007047000070B590F87030044613B10023E5 -:1036B00080F8703004F18002204601F0B9FD6368A3 -:1036C0009B68B3B994F8803013F0600535D00021C1 -:1036D000204602F0ABF80021204602F09BF8636818 -:1036E0001B6813B1062120469847062384F87030E2 -:1036F00070BD204698470028E4D0B4F88630A26F09 -:103700009A4288BFA36794F98030A56F002B4FF0D1 -:10371000300380F20381002D00F0F280092284F84A -:10372000702083F3118800212046D4E91D23FFF780 -:103730006DFF002383F31188DAE794F8812003F00A -:103740007F0343EA022340F20232934200F0C58035 -:1037500021D8B3F5807F48D00DD8012B3FD0022B64 -:1037600000F09380002BB2D104F18802626702223C -:10377000A267E367C1E7B3F5817F00F09B80B3F5F3 -:10378000407FA4D194F88230012BA0D1B4F88830C6 -:1037900043F0020332E0B3F5006F4DD017D8B3F514 -:1037A000A06F31D0A3F5C063012B90D86368204689 -:1037B00094F882205E6894F88310B4F88430B0479F -:1037C000002884D0436863670368A3671AE0B3F5F1 -:1037D000106F36D040F6024293427FF478AF5C4BD4 -:1037E00063670223A3670023C3E794F88230012BA9 -:1037F0007FF46DAFB4F8883023F00203A4F888306A -:10380000C4E91D55E56778E7B4F88030B3F5A06FDB -:103810000ED194F88230204684F88A3001F04AFCB8 -:1038200063681B6813B10121204698470323237066 -:103830000023C4E91D339CE704F18B036367012374 -:10384000C3E72378042B10D1302383F3118820465B -:10385000FFF7BAFE85F311880321636884F88B5063 -:1038600021701B680BB12046984794F88230002BDA -:10387000DED084F88B300423237063681B68002B30 -:10388000D6D0022120469847D2E794F884302046CB -:103890001D0603F00F010AD501F0BCFC012804D07D -:1038A00002287FF414AF2B4B9AE72B4B98E701F0DB -:1038B000A3FCF3E794F88230002B7FF408AF94F870 -:1038C000843013F00F01B3D01A06204602D501F060 -:1038D000C5FFADE701F0B6FFAAE794F88230002BF0 -:1038E0007FF4F5AE94F8843013F00F01A0D01B06DE -:1038F000204602D501F09AFF9AE701F08BFF97E787 -:10390000142284F8702083F311882B462A46294616 -:103910002046FFF769FE85F31188E9E65DB11522BF -:1039200084F8702083F3118800212046D4E91D23F8 -:10393000FFF75AFEFDE60B2284F8702083F311880E -:103940002B462A4629462046FFF760FEE3E700BFE4 -:10395000186B0008106B0008146B000838B590F85D -:1039600070300446002B3ED0063BDAB20F2A34D822 -:103970000F2B32D8DFE803F03731310822323131F2 -:103980003131313131313737856FB0F886309D4272 -:1039900014D2C3681B8AB5FBF3F203FB12556DB951 -:1039A000302383F311882B462A462946FFF72EFE43 -:1039B00085F311880A2384F870300EE0142384F80C -:1039C0007030302383F31188002320461A461946AD -:1039D000FFF70AFE002383F3118838BDC36F03B1DC -:1039E00098470023E7E70021204601F01FFF002150 -:1039F000204601F00FFF63681B6813B106212046C3 -:103A000098470623D7E7000010B590F870300446B9 -:103A1000142B29D017D8062B05D001D81BB110BD07 -:103A2000093B022BFBD80021204601F0FFFE0021BC -:103A3000204601F0EFFE63681B6813B106212046A3 -:103A40009847062319E0152BE9D10B2380F8703035 -:103A5000302383F3118800231A461946FFF7D6FD59 -:103A6000002383F31188DAE7C3689B695B68002B46 -:103A7000D5D1C36F03B19847002384F87030CEE7E7 -:103A8000FFF700B8012100230170C0E901330C30B9 -:103A900000F028B910B53023044683F31188416043 -:103AA000FEF7FEFF02230020237080F3118810BD73 -:103AB00010B53023044683F31188032304F8083B30 -:103AC000FFF718F84FF0FF31204600F0E1F900232E -:103AD00083F31188C01A18BF012010BD38B5044601 -:103AE000302585F31188032504F8085BFFF71EF8DD -:103AF0004FF0FF31204600F0CBF9002383F311880B -:103B0000C01A18BF012038BD38B50446302585F3EA -:103B10001188042504F8085BFFF72CF84FF0FF31FB -:103B2000204600F0B5F9002383F31188C01A18BFAE -:103B3000012038BD10B53023044683F31188FFF708 -:103B40003FF806232370002383F3118810BD000083 -:103B500010B53023044683F31188FFF74BF8022396 -:103B60002370002383F3118810BD00000C3000F097 -:103B7000D5B800000C3000F0DBB8000000238268EC -:103B8000037503691B6899689142FBD25A68036008 -:103B900042601060586070470023826803750369B3 -:103BA0001B6899689142FBD85A68036042601060B4 -:103BB0005860704708B50846302383F311880A7DA2 -:103BC0000023052A06D8DFE802F00B050503120ED4 -:103BD000826913604FF0FF338361FFF7CFFF00234B -:103BE00083F3118808BD8269936801339360D0E93B -:103BF000003213605A60EDE7FFF7C0BF054BD9688C -:103C000008751868026853601A600122D86002754E -:103C1000FCF782BD902900200C4B30B5DD684B1CB1 -:103C200087B004460FD02B46094A684600F0F8F9E1 -:103C30002046FFF7E3FF009B13B1684600F0FAF956 -:103C4000A86907B030BDFFF7D9FFF9E79029002038 -:103C5000B53B000838B50C4D04468161EB688168BE -:103C60009A68914203D8BDE83840FFF787BF1846ED -:103C7000FFF792FF01230146EC6020462375BDE863 -:103C80003840FCF749BD00BF90290020044B1A685A -:103C9000DB6890689B68984294BF002001207047C1 -:103CA00090290020084B10B51C68D8682268536022 -:103CB0001A600122DC602275FFF76EFF0146204684 -:103CC000BDE81040FCF728BD90290020044B1A687D -:103CD000DB6892689B689A4201D9FFF7E3BF70479F -:103CE00090290020C0E90000816070478368013B93 -:103CF000002B10B583600CDA074BDC684368A061C9 -:103D0000206063601C6044600520FFF777FFA069B6 -:103D100010BD0020FCE700BF9029002008B530232B -:103D200083F31188FFF7E2FF002383F3118808BDB6 -:103D300008B5302383F3118883680133002B836037 -:103D400007DC036800211A68026050601846FFF71C -:103D500081FF002383F3118808BD000038B50123DB -:103D6000084C00252370656001F082FF01F0A8FF78 -:103D70000549064802F07CF80223237085F3118878 -:103D800038BD00BFF82B0020206B000890290020D0 -:103D900008B572B6044B186500F062FD00F030FE05 -:103DA000024B03221A70FEE790290020F82B002016 -:103DB00000F076B9EFF3118020B9EFF305833022DC -:103DC00082F311887047000010B530B9EFF3058415 -:103DD000C4F3080414B180F3118810BDFFF776FF17 -:103DE00084F31188F9E70000034A516853685B1AAD -:103DF0009842FBD8704700BF001000E08B600223A0 -:103E0000086108468B8270478368A3F1840243F8F7 -:103E1000142C026943F8442C426943F8402C094AA7 -:103E200043F8242CC268A3F1200043F8182C022286 -:103E300003F80C2C002203F80B2C034A43F8102C37 -:103E4000704700BF310700089029002008B5FFF730 -:103E5000DBFFBDE80840FFF7CFBE0000024BDB6888 -:103E600098610F20FFF7CABE90290020302383F30A -:103E70001188FFF7F3BF000008B50146302383F334 -:103E800011880820FFF7C8FE002383F3118808BDBE -:103E9000054BDB6821B1036098610320FFF7BCBECE -:103EA0004FF0FF30704700BF9029002003682BB10E -:103EB0000022026018469961FFF79EBE704700001D -:103EC000064BDB6839B1426818605A601360436082 -:103ED0000420FFF7A1BE4FF0FF307047902900206B -:103EE0000368984206D01A680260506018469961CB -:103EF000FFF782BE7047000038B504460D462068C3 -:103F0000844200D138BD036823605C608561FFF79F -:103F100073FEF4E7036810B59C68A2420CD85C6895 -:103F20008A600B604C602160596099688A1A9A60B7 -:103F30004FF0FF33836010BD121B1B68ECE70000DD -:103F40000A2938BF0A2170B504460D460A266019B1 -:103F500001F088FE01F070FE041BA54203D8751C19 -:103F600004462E46F3E70A2E04D90120BDE870402E -:103F700001F0BEBF70BD0000F8B5144B0D460A2A13 -:103F80004FF00A07D96103F11001826038BF0A229D -:103F9000416019691446016048601861A81801F071 -:103FA00051FE01F049FE431B0646A34206D37C1C8A -:103FB00028192746354601F055FEF2E70A2F04D9A5 -:103FC0000120BDE8F84001F093BFF8BD9029002022 -:103FD000F8B506460D4601F02FFE0F4A134653F87A -:103FE000107F9F4206D12A4601463046BDE8F84080 -:103FF000FFF7C2BFD169BB68441A2C1928BF2C46F1 -:10400000A34202D92946FFF79BFF224631460348C7 -:10401000BDE8F840FFF77EBF90290020A0290020CE -:10402000C0E90323002310B45DF8044B4361FFF79C -:10403000CFBF000010B5194C236998420DD081689C -:10404000D0E9003213605A609A680A449A600023EB -:1040500003604FF0FF33A36110BD0268234643F8AD -:10406000102F53600022026022699A4203D1BDE8FA -:10407000104001F0F1BD936881680B44936001F03A -:10408000DBFD2269E1699268441AA242E4D9114435 -:10409000BDE81040091AFFF753BF00BF9029002068 -:1040A0002DE9F047DFF8BC8008F110072C4ED8F856 -:1040B000105001F0C1FDD8F81C40AA68031B9A42B9 -:1040C0003ED814444FF00009D5E90032C8F81C402E -:1040D00013605A60C5F80090D8F81030B34201D18F -:1040E00001F0BAFD89F31188D5E9033128469847D4 -:1040F000302383F311886B69002BD8D001F09CFD2D -:104100006A69A0EB040982464A450DD2022001F0FB -:10411000EFFE0022D8F81030B34208D151462846AD -:10412000BDE8F047FFF728BF121A2244F2E712EB6E -:1041300009092946384638BF4A46FFF7EBFEB5E77E -:10414000D8F81030B34208D01444C8F81C00211A23 -:10415000A960BDE8F047FFF7F3BEBDE8F08700BFF8 -:10416000A02900209029002000207047FEE70000D1 -:10417000704700004FF0FF307047000002290CD05C -:10418000032904D00129074818BF00207047032ADB -:1041900005D8054800EBC20070470448704700206E -:1041A000704700BFF86B000844220020AC6B000889 -:1041B00070B59AB005460846144601A900F0C2F849 -:1041C00001A8FDF78FF9431C0022C6B25B00104620 -:1041D000C5E9003423700323023404F8013C01AB29 -:1041E000D1B202348E4201D81AB070BD13F8011B4F -:1041F000013204F8010C04F8021CF1E708B5302381 -:1042000083F311880348FFF71DF9002383F3118816 -:1042100008BD00BF002C002090F8803003F01F0282 -:10422000012A07D190F881200B2A03D10023C0E98D -:104230001D3315E003F06003202B08D1B0F8843063 -:104240002BB990F88120212A03D81F2A04D8FFF720 -:10425000DBB8222AEBD0FAE7034A426707228267DB -:10426000C3670120704700BF3B22002007B5052926 -:1042700017D8DFE801F0191603191920302383F34A -:104280001188104A01210190FFF784F90198022159 -:104290000D4AFFF77FF90D48FFF7A0F8002383F3DD -:1042A000118803B05DF804FB302383F311880748BD -:1042B000FFF76AF8F2E7302383F311880348FFF72A -:1042C00081F8EBE74C6B0008706B0008002C0020B5 -:1042D00038B50C4D0C4C2A460C4904F10800FFF788 -:1042E00067FF05F1CA0204F110000949FFF760FFFA -:1042F00005F5CA7204F118000649BDE83840FFF719 -:1043000057BF00BFD8440020442200202C6B000877 -:10431000366B0008416B000870B5044608460D4630 -:10432000FDF7E0F8C6B22046013403780BB9184611 -:1043300070BD32462946FDF7B5F80028F3D10120BB -:10434000F6E700002DE9F04705460C46FDF7CAF8F0 -:104350002B49C6B22846FFF7DFFF08B10736F6B291 -:1043600028492846FFF7D8FF08B11036F6B2632E69 -:104370000BD8DFF88C80DFF88C90234FDFF894A007 -:104380002E7846B92670BDE8F08729462046BDE85C -:10439000F04702F01BBA252E2ED1072241462846AF -:1043A000FDF780F870B9194B224603F10C0153F860 -:1043B000040B8B4242F8040BF9D11B8807350E34ED -:1043C0001380DDE7082249462846FDF76BF898B9C7 -:1043D000A21C0F4B197802320909C95D02F8041CAE -:1043E00013F8011B01F00F015345C95D02F8031CCE -:1043F000F0D118340835C3E7013504F8016BBFE785 -:10440000186C0008416B00082F6C0008206C000835 -:1044100000E8F11F0CE8F11FBFF34F8F044B1A693E -:104420005107FCD1D3F810215207F8D1704700BFD3 -:104430000020005208B50D4B1B78ABB9FFF7ECFF1D -:104440000B4BDA68D10704D50A4A5A6002F1883268 -:104450005A60D3F80C21D20706D5064AC3F80421C6 -:1044600002F18832C3F8042108BD00BF364700209E -:10447000002000522301674508B5114B1B78F3B9A2 -:10448000104B1A69510703D5DA6842F04002DA602E -:10449000D3F81021520705D5D3F80C2142F0400281 -:1044A000C3F80C21FFF7B8FF064BDA6842F00102AF -:1044B000DA60D3F80C2142F00102C3F80C2108BDE8 -:1044C00036470020002000520F289ABF00F5806078 -:1044D00040040020704700004FF400307047000097 -:1044E000102070470F2808B50BD8FFF7EDFF00F537 -:1044F00000330268013204D104308342F9D1012033 -:1045000008BD0020FCE700000F2870B5054645D81F -:10451000FFF750FC224CFFF77FFF0646FFF78AFFAC -:104520004FF0FF33072D6361C4F8143120D82361A5 -:10453000FFF772FF2B0243F02403E360E36843F0CC -:104540008003E36023695A07FCD42846FFF764FF21 -:104550004FF40031FFF7B8FF00F02EFA3046FFF7B6 -:104560008BFFFFF731FC2846BDE87040FFF7BABF6C -:10457000C4F81031FFF750FFA5F108031B0243F008 -:104580002403C4F80C31D4F80C3143F08003C4F890 -:104590000C31D4F810315B07FBD4D6E7002070BD96 -:1045A000002000522DE9F84F40EA020305460C4670 -:1045B0001746D80602D00020BDE8F88F27F01F0765 -:1045C000DFF8D4B0FFF736FF2744BC4203D1012007 -:1045D000FFF752FFF0E720222946204602F0A2F81A -:1045E00010B920352034F0E72B4605F120021E6873 -:1045F000711CE0D104339A42F9D1FFF7DBFB05F1DE -:104600007843234AB3F5801F224B28BF9A4603F113 -:10461000040338BF9046A2F1080228BF9846A3F1D0 -:1046200008033ABF9146DA469946FFF7F5FEC8F807 -:104630000060A5EB040CD9F8002004F11C0142F045 -:104640000202C9F80020221FDAF8006016F0050601 -:10465000FAD152F8043F8A424CF80230F4D1BFF349 -:104660004F8FFFF7D9FE4FF0FF32C8F80020D9F87E -:10467000002022F00202C9F80020FFF7A5FB20224B -:104680002146284602F04EF80028AAD030469FE77F -:1046900014200052102100521020005210B5084C76 -:1046A000237828B11BB9FFF7C5FE0123237010BD85 -:1046B000002BFCD02070BDE81040FFF7DDBE00BF2E -:1046C000364700202DE9F04F0D4685B0814658B1A0 -:1046D00011F00D0614BF2022082211F008030193E7 -:1046E00004D0431E03426AD0002435E0002E37D0A8 -:1046F00009F11F0121F01F094FF00108324F05F0A9 -:104700000403DFF8D0A005EA080BBBF1000F32D09C -:104710007869C0072FD408F101080C37B8F1060FEB -:10472000F3D19EB9294D4946A819019201F0EAFA40 -:10473000044600283AD11836019A782EF3D149461A -:1047400001F0E0FA0446002830D1019A4946204899 -:1047500001F0D8FA044668BB204605B0BDE8F08FEA -:104760000029C9D101462846029201F0CBFA04463D -:10477000E0B9029AC0E713B178694107CBD5AC071D -:1047800002D578698007C6D5019911B1786901070A -:10479000C1D51820494600FB08A0CDE9022301F04D -:1047A000B1FA0446DDE902230028B4D04A460021CC -:1047B000204601E04A460021FCF79CFECCE7024679 -:1047C000002E95D198E700BF406C00086847002094 -:1047D00038470020504700200021FFF773BF00003A -:1047E0000121FFF76FBF0000F8B5144D0124182711 -:1047F000134E40F2FF3200210120FCF77BFE07FB45 -:10480000046001342A6955F80C1F01F067FA062C80 -:10481000F5D137254FF4C0542046FFF7E1FF01469C -:1048200028B122460748BDE8F84001F057BAC4EB6A -:10483000C404013D4FEAD404EED1F8BD406C000839 -:1048400050470020384700200421FFF73BBF0000FD -:104850004843FFF7C1BF000008B101F0C5BA704777 -:1048600038B5054D00240334696855F80C0B00F089 -:10487000B5F8122CF7D138BD406C000870B5104E59 -:1048800082B0FFF797FA054601F0D6F93268034681 -:104890009042336037BF0B4A0A495168146836BFEB -:1048A0000131D1E9004151600419284641F100016C -:1048B0000191FFF789FA2046019902B070BD00BF4F -:1048C000E0470020E847002070B5124E82B0FFF7A5 -:1048D00071FA054601F0B0F9326803469042336040 -:1048E00037BF0D4A0C495168146836BF0131D1E910 -:1048F000004151600419284641F100010191FFF780 -:1049000063FA4FF47A72002320460199FBF7F0FC1A -:1049100002B070BDE0470020E84700200244074B8A -:10492000D2B210B5904200D110BD441C00B253F871 -:10493000200041F8040BE0B2F4E700BF50400058FB -:104940000E4B30B51C6F240405D41C6F1C671C6F04 -:1049500044F400441C670A4C02442368D2B243F476 -:1049600080732360074B904200D130BD441C51F846 -:10497000045B00B243F82050E0B2F4E70044025870 -:10498000004802585040005807B5012201A90020F4 -:10499000FFF7C4FF019803B05DF804FB13B50446AC -:1049A000FFF7F2FFA04205D0012201A900200194E7 -:1049B000FFF7C6FF02B010BD0144BFF34F8F064B97 -:1049C000884204D3BFF34F8FBFF36F8F7047C3F894 -:1049D0005C022030F4E700BF00ED00E00144BFF3CB -:1049E0004F8F064B884204D3BFF34F8FBFF36F8FB7 -:1049F0007047C3F870022030F4E700BF00ED00E01C -:104A00007047000070B5054616460C46012010217F -:104A1000FFF71EFF286046733CB1204636B1FFF712 -:104A200013FF2B68186000B19C6070BDFFF7D8FEC3 -:104A3000F7E7000070B50E461546044600B30B6854 -:104A400043608368934210D213B10068FFF704FFFC -:104A5000637B28462BB1FFF7F7FE206020B9A060EA -:104A600070BDFFF7BDFEF8E7A560206805F11F01E6 -:104A7000306021F01F01FFF79FFF01202073EFE757 -:104A80000120EDE710B5044640B10068884205D129 -:104A9000606808B1FCF7FCFC0023237310BD000024 -:104AA00070B50E461546044620B383689A4210D965 -:104AB00013B10068FFF7D0FE637B28462BB1FFF7E8 -:104AC000C3FE206020B9A06070BDFFF789FEF8E743 -:104AD000A560316819B12A462068FCF7D9FC206826 -:104AE00005F11F01306021F01F01FFF777FF012062 -:104AF0002073E9E70120E7E720B103688B4204BF98 -:104B0000002303737047000008B10023037370474C -:104B1000034B1A681AB9034AD2F8D0241A607047B6 -:104B2000F04700200040025808B5FFF7F1FF024BA4 -:104B30001868C0F3806008BDF047002070B5BFF36F -:104B40004F8FBFF36F8F1A4A0021C2F85012BFF384 -:104B50004F8FBFF36F8F536943F400335361BFF33B -:104B60004F8FBFF36F8FC2F88410BFF34F8FD2F80F -:104B7000803043F6E074C3F3C900C3F34E335B01E6 -:104B800003EA0406014646EA81750139C2F860521B -:104B9000F9D2203B13F1200FF2D1BFF34F8F5369AD -:104BA00043F480335361BFF34F8FBFF36F8F70BDFA -:104BB00000ED00E0FEE70000214B2248224A70B5DC -:104BC000904237D3214BC11EDA1C121A22F0030285 -:104BD0008B4238BF00220021FCF78CFC1C4A0023CA -:104BE000C2F88430BFF34F8FD2F8803043F6E074C0 -:104BF000C3F3C900C3F34E335B0103EA0406014665 -:104C000046EA81750139C2F86C52F9D2203B13F1A2 -:104C1000200FF2D1BFF34F8FBFF36F8FBFF34F8FD2 -:104C2000BFF36F8F0023C2F85032BFF34F8FBFF333 -:104C30006F8F70BD53F8041B40F8041BC0E700BF22 -:104C4000186F0008B04A0020B04A0020B04A002087 -:104C500000ED00E003681A6899685A6043681BB168 -:104C600042EA014180681847704700004FF0A443B2 -:104C700010B51C68E00702D52848FFF7EBFFA10735 -:104C800002D52748FFF7E6FF620702D52548FFF760 -:104C9000E1FF230702D52448FFF7DCFFE00602D539 -:104CA0002248FFF7D7FFA10602D52148FFF7D2FF20 -:104CB000620602D51F48FFF7CDFF230602D51E4826 -:104CC000FFF7C8FFE00502D51C48FFF7C3FFA105A9 -:104CD00002D51B48FFF7BEFF620502D51948FFF752 -:104CE000B9FF230502D51848FFF7B4FFE00402D549 -:104CF0001648FFF7AFFFA10402D51548FFF7AAFF3A -:104D0000620402D51348FFF7A5FF230402D5124819 -:104D1000FFF7A0FFBDE8104001F0D0B9F847002030 -:104D200004480020104800201C480020284800208B -:104D300034480020404800204C48002058480020BB -:104D400064480020704800207C48002088480020EB -:104D500094480020A0480020AC48002030B5094B02 -:104D60000021094C10200725196054F8042B013844 -:104D7000C3E90121D16003F10C0311615560F4D145 -:104D800030BD00BFF4470020886C00080F28F0B544 -:104D90000AD9102806D10F230020114C01272568BD -:104DA000984203D9002018E00346F6E707FA00F618 -:104DB000354213D10C23354343432560181D23444A -:104DC000C3E90212074B20445A6B42F001025A63B6 -:104DD000DA6D42F00102DA65DB6DF0BD0130DFE72C -:104DE000F4470020004502580368D968DA68C9070B -:104DF00022F03F02DA6002D51A689207FCD507223A -:104E00005A607047054B996B21EA000199631A6E4D -:104E100022EA00021A661B6E704700BF0045025866 -:104E200070B5D0E9244300224FF0FF359E6804EBB3 -:104E300042135101D3F80009002805DAD3F800091C -:104E400040F08040C3F80009D3F8000B002805DAD1 -:104E5000D3F8000B40F08040C3F8000B0132631818 -:104E60009642C3F80859C3F8085BE0D24FF001132B -:104E7000C4F81C3870BD0000890141F020010161B7 -:104E800003699B06FCD41220FEF7AEBF10B50A4C96 -:104E90002046FEF75DFB094BC4F89030084BC4F880 -:104EA0009430084C2046FEF753FB074BC4F8903073 -:104EB000064BC4F8943010BDB848002000000840EC -:104EC000EC6C00085449002000000440F86C000815 -:104ED00070B503780546012B58D13F4BD0F8904070 -:104EE000984254D13D4B0E2165209A6B42F00062EE -:104EF0009A631A6E42F000621A661B6E384BD3F842 -:104F0000802042F00062C3F88020D3F8802022F095 -:104F10000062C3F88020D3F8803000F0ABFC314B46 -:104F2000E360314BC4F800380023D5F89060C4F832 -:104F3000003EC02323604FF40413A3633369002BA6 -:104F4000FCDA01230C203361FEF74EFF3369DB07E7 -:104F5000FCD41220FEF748FF3369002BFCDA002650 -:104F60002846A660FFF75CFF6B68C4F81068DB6832 -:104F7000C4F81468C4F81C6863BB1C4BA3614FF0F1 -:104F8000FF336361A36843F00103A36070BD184B56 -:104F90009842C9D1114B4FF080609A6B42F0007279 -:104FA0009A631A6E42F000721A661B6E0C4BD3F8AD -:104FB000802042F00072C3F88020D3F8802022F0D5 -:104FC0000072C3F88020D3F88030FFF71BFF0E215A -:104FD0004D20A2E7074BD1E7B84800200045025812 -:104FE000004402584014004003002002003C30C03E -:104FF00054490020083C30C0F8B5D0F89040054630 -:1050000000214FF000662046FFF736FFD5F89410D8 -:1050100000234FF001128F684FF0FF30C4F834388E -:10502000C4F81C2804EB431201339F42C2F8006904 -:10503000C2F8006BC2F80809C2F8080BF2D20B687C -:10504000D5F89020C5F89830636210231361166973 -:1050500016F01006FBD11220FEF7C6FED4F8003879 -:1050600023F4FE63C4F80038A36943F4402343F0FB -:105070001003A3610923C4F81038C4F814380B4B8B -:10508000EB604FF0C043C4F8103B094BC4F8003B41 -:10509000C4F81069C4F80039D5F8983003F110024B -:1050A00043F48013C5F89820A362F8BDC86C0008CB -:1050B00040800010D0F8902090F88A10D2F8003884 -:1050C00023F4FE6343EA0113C2F80038704700007E -:1050D0002DE9F84300EB8103D0F890500C46804650 -:1050E000DA680FFA81F94801166806F00306731EA4 -:1050F000022B05EB41134FF0000194BFB604384E6C -:10510000C3F8101B4FF0010104F1100398BF06F122 -:10511000805601FA03F3916998BF06F5004600290D -:105120003AD0578A04F15801374349016F50D5F8F6 -:105130001C180B430021C5F81C382B180127C3F895 -:105140001019A7405369611E9BB3138A928B9B0869 -:10515000012A88BF5343D8F89820981842EA03439D -:1051600001F140022146C8F89800284605EB82026A -:105170005360FFF781FE08EB8900C3681B8A43EA8E -:10518000845348341E4364012E51D5F81C381F4304 -:10519000C5F81C78BDE8F88305EB4917D7F8001B64 -:1051A00021F40041C7F8001BD5F81C1821EA0303BD -:1051B000C0E704F13F030B4A2846214605EB830371 -:1051C0005A60FFF759FE05EB4910D0F8003923F477 -:1051D0000043C0F80039D5F81C3823EA0707D7E7A1 -:1051E0000080001000040002D0F894201268C0F87B -:1051F0009820FFF715BE00005831D0F890304901D3 -:105200005B5813F4004004D013F4001F0CBF0220BD -:10521000012070474831D0F8903049015B5813F4B1 -:10522000004004D013F4001F0CBF0220012070477F -:1052300000EB8101CB68196A0B6813604B685360FF -:105240007047000000EB810330B5DD68AA69136880 -:10525000D36019B9402B84BF402313606B8A146854 -:10526000D0F890201C4402EB4110013C09B2B4FB81 -:10527000F3F46343033323F0030343EAC44343F0EB -:10528000C043C0F8103B2B6803F00303012B0ED181 -:10529000D2F8083802EB411013F4807FD0F8003BBD -:1052A00014BF43F0805343F00053C0F8003B02EBBF -:1052B0004112D2F8003B43F00443C2F8003B30BD3A -:1052C0002DE9F041D0F8906005460C4606EB4113FD -:1052D000D3F8087B3A07C3F8087B08D5D6F814380A -:1052E0001B0704D500EB8103DB685B689847FA076E -:1052F0001FD5D6F81438DB071BD505EB8403D96816 -:10530000CCB98B69488A5A68B2FBF0F600FB1622CA -:105310008AB91868DA6890420DD2121AC3E90024DB -:10532000302383F3118821462846FFF78BFF84F34F -:105330001188BDE8F081012303FA04F26B8923EAA6 -:1053400002036B81CB68002BF3D021462846BDE8D1 -:10535000F041184700EB81034A0170B5DD68D0F8D1 -:1053600090306C692668E66056BB1A444FF4002002 -:10537000C2F810092A6802F00302012A0AB20ED10B -:10538000D3F8080803EB421410F4807FD4F8000926 -:1053900014BF40F0805040F00050C4F8000903EB07 -:1053A0004212D2F8000940F00440C2F8000901227C -:1053B000D3F8340802FA01F10143C3F8341870BD80 -:1053C00019B9402E84BF4020206020681A442E8ADC -:1053D0008419013CB4FBF6F440EAC44040F00050AC -:1053E000C6E700002DE9F843D0F8906005460C466A -:1053F0004F0106EB4113D3F8088918F0010FC3F8E9 -:1054000008891CD0D6F81038DB0718D500EB8103CB -:10541000D3F80CC0DCF81430D3F800E0DA68964515 -:1054200030D2A2EB0E024FF000091A60C3F80490CC -:10543000302383F31188FFF78DFF89F3118818F06B -:10544000800F1DD0D6F834380126A640334217D03D -:1054500005EB84030134D5F89050D3F80CC0E4B2C6 -:105460002F44DCF8142005EB0434D2F800E0516836 -:10547000714514D3D5F8343823EA0606C5F83468E4 -:10548000BDE8F883012303FA01F2038923EA02034A -:105490000381DCF80830002BD1D09847CFE7AEEB82 -:1054A0000103BCF81000834228BF0346D7F818094F -:1054B00080B2B3EB800FE3D89068A0F1040959F8EB -:1054C000048FC4F80080A0EB09089844B8F1040FD9 -:1054D000F5D818440B4490605360C8E72DE9F84FA5 -:1054E000D0F8905004466E69AB691E4016F480589F -:1054F0006E6103D0BDE8F84FFEF79AB8002E12DABD -:10550000D5F8003E9B0705D0D5F8003E23F00303F5 -:10551000C5F8003ED5F80438204623F00103C5F84D -:105520000438FEF7B3F8370505D52046FFF778FCB9 -:105530002046FEF799F8B0040CD5D5F8083813F0DA -:10554000060FEB6823F470530CBF43F4105343F47D -:10555000A053EB6031071BD56368DB681BB9AB69EF -:1055600023F00803AB612378052B0CD1D5F8003E5E -:105570009A0705D0D5F8003E23F00303C5F8003E96 -:105580002046FEF783F86368DB680BB12046984736 -:10559000F30200F1BA80B70226D5D4F89090002724 -:1055A0004FF0010A09EB4712D2F8003B03F4402305 -:1055B000B3F5802F11D1D2F8003B002B0DDA6289B0 -:1055C0000AFA07F322EA0303638104EB8703DB682B -:1055D000DB6813B13946204698470137D4F8943038 -:1055E000FFB29B689F42DDD9F00619D5D4F8900030 -:1055F000026AC2F30A1702F00F0302F4F012B2F5C6 -:10560000802F00F0CA80B2F5402F09D104EB83034C -:10561000002200F58050DB681B6A974240F0B080A2 -:105620003003D5F8185835D5E90303D500212046B5 -:10563000FFF746FEAA0303D501212046FFF740FEEF -:105640006B0303D502212046FFF73AFE2F0303D553 -:1056500003212046FFF734FEE80203D5042120464B -:10566000FFF72EFEA90203D505212046FFF728FEED -:105670006A0203D506212046FFF722FE2B0203D53E -:1056800007212046FFF71CFEEF0103D50821204625 -:10569000FFF716FE700340F1A780E90703D500214C -:1056A0002046FFF79FFEAA0703D501212046FFF7FA -:1056B00099FE6B0703D502212046FFF793FE2F07C3 -:1056C00003D503212046FFF78DFEEE0603D5042106 -:1056D0002046FFF787FEA80603D505212046FFF7E1 -:1056E00081FE690603D506212046FFF77BFE2A06C8 -:1056F00003D507212046FFF775FEEB0574D520463C -:105700000821BDE8F84FFFF76DBED4F890904FF038 -:10571000000B4FF0010AD4F894305FFA8BF79B68C6 -:105720009F423FF638AF09EB4713D3F8002902F444 -:105730004022B2F5802F20D1D3F80029002A1CDAAC -:10574000D3F8002942F09042C3F80029D3F8002989 -:10575000002AFBDB3946D4F89000FFF78DFB228945 -:105760000AFA07F322EA0303238104EB8703DB68C9 -:105770009B6813B13946204698470BF1010BCAE7E5 -:10578000910701D1D0F80080072A02F101029CBFE5 -:1057900003F8018B4FEA18283FE704EB830300F579 -:1057A0008050DA68D2F818C0DCF80820DCE9001C68 -:1057B000A1EB0C0C00218F4208D1DB689B699A6831 -:1057C0003A449A605A683A445A6029E711F0030F44 -:1057D00001D1D0F800808C4501F1010184BF02F8AD -:1057E000018B4FEA1828E6E7BDE8F88F08B50348B3 -:1057F000FFF774FEBDE8084000F060BCB848002028 -:1058000008B50348FFF76AFEBDE8084000F056BC43 -:1058100054490020D0F8903003EB4111D1F8003BFF -:1058200043F40013C1F8003B70470000D0F89030FB -:1058300003EB4111D1F8003943F40013C1F80039EA -:1058400070470000D0F8903003EB4111D1F8003BD5 -:1058500023F40013C1F8003B70470000D0F89030EB -:1058600003EB4111D1F8003923F40013C1F80039DA -:1058700070470000090100F16043012203F5614314 -:10588000C9B283F8001300F01F039A4043099B003C -:1058900003F1604303F56143C3F880211A60704748 -:1058A00030B50433039C0172002104FB0325C16061 -:1058B000C0E90653049B0363059BC0E90000C0E9EF -:1058C0000422C0E90842C0E90A11436330BD000068 -:1058D0000022416AC260C0E90411C0E90A226FF0E7 -:1058E0000101FEF709BB0000D0E90432934201D167 -:1058F000C2680AB9181D7047002070470369196013 -:105900000021C2680132C260C269134482699342B5 -:10591000036124BF436A0361FEF7E2BA38B5044667 -:105920000D46E3683BB162690020131D1268A36253 -:105930001344E36207E0237A33B929462046FEF791 -:10594000BFFA0028EDDA38BD6FF00100FBE7000078 -:10595000C368C269013BC3604369134482699342CF -:10596000436124BF436A436100238362036B03B135 -:105970001847704770B53023044683F31188866A50 -:105980003EB9FFF7CBFF054618B186F311882846CC -:1059900070BDA36AE26A13F8015B9342A36202D36B -:1059A0002046FFF7D5FF002383F31188EFE70000BF -:1059B0002DE9F84F04460E46174698464FF0300939 -:1059C00089F311880025AA46D4F828B0BBF1000F4E -:1059D00009D141462046FFF7A1FF20B18BF3118882 -:1059E0002846BDE8F88FD4E90A12A7EB050B521A36 -:1059F000934528BF9346BBF1400F1BD9334601F1B5 -:105A0000400251F8040B914243F8040BF9D1A36A08 -:105A1000403640354033A362D4E90A239A4202D388 -:105A20002046FFF795FF8AF31188BD42D8D289F34B -:105A30001188C9E730465A46FBF72AFDA36A5E443F -:105A40005D445B44A362E7E710B5029C0433017236 -:105A500003FB0421C460C0E906130023C0E90A3334 -:105A6000039B0363049BC0E90000C0E90422C0E972 -:105A70000842436310BD0000026A6FF00101C2607A -:105A8000426AC0E904220022C0E90A22FEF734BAC1 -:105A9000D0E904239A4201D1C26822B9184650F8CD -:105AA000043B0B60704700231846FAE7C3680021E7 -:105AB000C2690133C36043691344826993424361FD -:105AC00024BF436A4361FEF70BBA000038B50446B1 -:105AD0000D46E3683BB1236900201A1DA262E2690A -:105AE0001344E36207E0237A33B929462046FEF7E0 -:105AF000E7F90028EDDA38BD6FF00100FBE70000A0 -:105B000003691960C268013AC260C26913448269BC -:105B10009342036124BF436A036100238362036BE2 -:105B200003B118477047000070B530230D46044696 -:105B3000114683F31188866A2EB9FFF7C7FF10B1AB -:105B400086F3118870BDA36A1D70A36AE26A0133EF -:105B50009342A36204D3E16920460439FFF7D0FFE2 -:105B6000002080F31188EDE72DE9F84F04460D463B -:105B7000904699464FF0300A8AF311880026B346C2 -:105B8000A76A4FB949462046FFF7A0FF20B187F327 -:105B900011883046BDE8F88FD4E90A073A1AA8EB15 -:105BA0000607974228BF1746402F1BD905F140032F -:105BB00055F8042B9D4240F8042BF9D1A36A4036D6 -:105BC0004033A362D4E90A239A4204D3E169204610 -:105BD0000439FFF795FF8BF311884645D9D28AF334 -:105BE0001188CDE729463A46FBF752FCA36A3D44AB -:105BF0003E443B44A362E5E7D0E904239A4217D12F -:105C0000C3689BB1836A8BB1043B9B1A0ED01360AF -:105C1000C368013BC360C3691A4483699A42026145 -:105C200024BF436A0361002383620123184670473F -:105C30000023FBE700F06CBA014B586A704700BFC5 -:105C4000000C0040034B002258631A610222DA6004 -:105C5000704700BF000C0040014B0022DA60704723 -:105C6000000C0040014B5863704700BF000C00401F -:105C7000024B034A1A60034A5A607047084A0020E0 -:105C8000B04A002000000220074B494210B55C6872 -:105C9000201A08401968821A8A4203D3A24201D806 -:105CA0005A6010BD0020FCE7084A002008B53023E8 -:105CB00083F31188FFF7E8FF002383F3118808BD01 -:105CC00004480121044B03600023C0E901330C3078 -:105CD000FEF708B8104A0020AD5C0008CB1D083A5A -:105CE00023F00703591A521A012110B4D2080024D4 -:105CF000C0E9004384600C301C605A605DF8044BBE -:105D0000FDF7F0BF2DE9F84F364ECD1D0F460028A8 -:105D100018BF0646082A4FEAD50538BF082206F103 -:105D20000C08341D91464046FDF7F8FF09F10701C4 -:105D3000C9F1000E224624686CB94046FDF7F8FF11 -:105D40003368CBB308224946E8009847044698B325 -:105D500040E9026730E004EB010CD4F804A00CEA3F -:105D60000E0C0AF10100ACF1080304EBC0009842EC -:105D7000E0D9A0EB0C0CB5EBEC0F4FEAEC0BD9D84B -:105D80009C421CD204F10802AB45A3EB02024FEA8D -:105D9000E202626009D9691CED43206803EBC1028D -:105DA0005D44556043F8310022601C465F60404608 -:105DB00044F8086BFDF7BCFF2046BDE8F88FAA4504 -:105DC000216802D111602346EFE7013504EBC503DA -:105DD00044F8351003F10801401AC01058601360F0 -:105DE000F1E700BF104A0020F8B550F8043C044623 -:105DF00050F8085CA0F1080607332F1D0C35DB08AE -:105E000040F8043C2846FDF789FF3B469F421A684C -:105E100001D0B34228D20AB1964225D244F8082CC8 -:105E200054F8042C1E60013254F8081C06EBC20022 -:105E3000814206D14868024444F8042C0A6844F8B8 -:105E4000082C5868411C03EBC1018E4207D154F85D -:105E5000042C013202445A6054F8082C1A60284677 -:105E6000BDE8F840FDF764BF1346CFE7FEE700004A -:105E700070B51B4B0025044686B058600E468562FF -:105E8000016300F0F3F804F11003A560E562C4E9D2 -:105E900004334FF0FF33C4E90044C4E90635FFF78B -:105EA000CBFE2B46024604F134012046C4E9082308 -:105EB00080230C4A2565FDF7A1FF01230A4AE06013 -:105EC00000920375684672680192B268CDE90223B8 -:105ED000064BCDE90435FDF7B9FF06B070BD00BF34 -:105EE000F82B0020046D0008096D00086D5E0008A5 -:105EF000024AD36A1843D062704700BF902900203D -:105F00004B6843608B688360CB68C3600B694361F7 -:105F10004B6903628B6943620B6803607047000042 -:105F200008B5324B40F2FF70196C014319649A6E48 -:105F300002432F489A662F4A9B6E1146FFF7E0FFF7 -:105F400000F5806002F11C01FFF7DAFF00F58060C8 -:105F500002F13801FFF7D4FF00F5806002F154012F -:105F6000FFF7CEFF00F5806002F17001FFF7C8FF78 -:105F700000F5806002F18C01FFF7C2FF00F5806040 -:105F800002F1A801FFF7BCFF00F5806002F1C40137 -:105F9000FFF7B6FF00F5806002F1E001FFF7B0FF08 -:105FA00000F5806002F1FC01FFF7AAFF02F58C7199 -:105FB00000F58060FFF7A4FF00F06CF90E4BD3F8FA -:105FC000902242F00102C3F89022D3F8942242F0CA -:105FD0000102C3F894220522C3F898204FF06052C2 -:105FE000C3F89C20054AC3F8A02008BD004502580C -:105FF00000000258106D000800ED00E01F000803CB -:1060000008B500F033FBFDF7A9FE0D4BDA6B42F04B -:106010004002DA635A6E22F040025A665B6E094B08 -:106020001A6842F008021A601A6842F004021A6004 -:10603000FEF76EFDFEF7D8FBBDE80840FEF748B955 -:10604000004502580018024870470000EFF309832A -:10605000054968334A6B22F001024A6383F30988D9 -:10606000002383F31188704700EF00E0302080F3B5 -:10607000118862B60D4B0E4AD96821F4E06109041B -:10608000090C0A430B49DA60D3F8FC2042F0807215 -:10609000C3F8FC20084AC2F8B01F116841F00101A2 -:1060A00011602022DA7783F82200704700ED00E0CB -:1060B0000003FA0555CEACC5001000E0302310B542 -:1060C00083F311880E4B5B6813F4006314D0F1EE78 -:1060D000103AEFF309844FF08073683CE361094B99 -:1060E000DB6B236684F30988FDF7D0FD10B1064B06 -:1060F000A36110BD054BFBE783F31188F9E700BFEF -:1061000000ED00E000EF00E043070008460700084C -:106110000E4B9A6C42F008029A641A6F42F0080221 -:106120001A670B4A1B6FD36B43F00803D363C72274 -:10613000084B9A624FF0FF32DA6200229A615A638A -:10614000DA605A6001225A611A60704700450258AD -:106150000010005C000C0040094A08B51169D368C2 -:106160000B40D9B29B076FEA0101116107D53023BB -:1061700083F31188FDF71CFE002383F3118808BD0B -:10618000000C0040044BDA6B0243DA635A6E104392 -:1061900058665B6E704700BF0045025808B53C4B1F -:1061A0004FF0FF31D3F8802062F00042C3F8802026 -:1061B000D3F8802002F00042C3F88020D3F880207A -:1061C000D3F88420C3F88410D3F884200022C3F8C5 -:1061D0008420D3F88400D86F40F0FF4040F4FF00E3 -:1061E00040F4DF4040F07F00D867D86F20F0FF40D8 -:1061F00020F4FF0020F4DF4020F07F00D867D86F44 -:10620000D3F888006FEA40506FEA5050C3F8880016 -:10621000D3F88800C0F30A00C3F88800D3F88800D8 -:10622000D3F89000C3F89010D3F89000C3F89020F2 -:10623000D3F89000D3F89400C3F89410D3F89400E6 -:10624000C3F89420D3F89400D3F89800C3F89810BA -:10625000D3F89800C3F89820D3F89800D3F88C00AE -:10626000C3F88C10D3F88C00C3F88C20D3F88C00C2 -:10627000D3F89C00C3F89C10D3F89C10C3F89C2062 -:10628000D3F89C30FEF76AFDBDE8084000F0BEB9C7 -:106290000044025808B50122504BC3F80821504B66 -:1062A0005A6D42F002025A65DA6F42F00202DA6772 -:1062B0000422DB6F4B4BDA605A689104FCD54A4AE2 -:1062C0001A6001229A60494ADA6000221A614FF48A -:1062D00040429A61434B9A699204FCD51A6842F491 -:1062E00080721A60424B1A6F12F4407F04D04FF450 -:1062F00080321A6700221A671A6842F001021A6097 -:106300003B4B1A685007FCD500221A611A6912F03B -:106310003802FBD1012119604FF0804159605A6762 -:10632000344ADA62344A1A611A6842F480321A60D6 -:106330002F4B1A689103FCD51A6842F480521A60F8 -:106340001A689204FCD52D4A2D499A6200225A639C -:10635000196301F57C01DA6301F5E77199635A6409 -:10636000284A1A64284ADA621A6842F0A8521A6067 -:106370001F4B1A6802F02852B2F1285FF9D1482267 -:106380009A614FF48862DA6140221A621F4ADA6425 -:106390001F4A1A651F4A5A651F4A9A6532231F4AC7 -:1063A0001360136803F00F03022BFAD1104A13692C -:1063B00043F003031361136903F03803182BFAD178 -:1063C0004FF00050FFF7DEFE4FF08040FFF7DAFE9F -:1063D0004FF00040BDE80840FFF7D4BE00800051F8 -:1063E000004502580048025800C000F004000001B7 -:1063F000004402580000FF0100889008322060002D -:1064000063020901470E0508DD0BBF0120000020D3 -:10641000000001100910E0000001011000200052EE -:106420004FF0B04208B5D2F8883003F00103C2F84B -:10643000883023B1044A13680BB150689847BDE80F -:106440000840FFF73BBE00BF284A00204FF0B04293 -:1064500008B5D2F8883003F00203C2F8883023B1BF -:10646000044A93680BB1D0689847BDE80840FFF72D -:1064700025BE00BF284A00204FF0B04208B5D2F830 -:10648000883003F00403C2F8883023B1044A13694A -:106490000BB150699847BDE80840FFF70FBE00BF39 -:1064A000284A00204FF0B04208B5D2F8883003F0F7 -:1064B0000803C2F8883023B1044A93690BB1D0694C -:1064C0009847BDE80840FFF7F9BD00BF284A002003 -:1064D0004FF0B04208B5D2F8883003F01003C2F88C -:1064E000883023B1044A136A0BB1506A9847BDE85B -:1064F0000840FFF7E3BD00BF284A00204FF0B0433B -:1065000010B5D3F8884004F47872C3F88820A30645 -:1065100004D5124A936A0BB1D06A9847600604D535 -:106520000E4A136B0BB1506B9847210604D50B4AEA -:10653000936B0BB1D06B9847E20504D5074A136CF7 -:106540000BB1506C9847A30504D5044A936C0BB16A -:10655000D06C9847BDE81040FFF7B0BD284A002036 -:106560004FF0B04310B5D3F8884004F47C42C3F830 -:106570008820620504D5164A136D0BB1506D9847FB -:10658000230504D5124A936D0BB1D06D9847E004F2 -:1065900004D50F4A136E0BB1506E9847A10404D571 -:1065A0000B4A936E0BB1D06E9847620404D5084A2B -:1065B000136F0BB1506F9847230404D5044A936FAF -:1065C0000BB1D06F9847BDE81040FFF777BD00BF13 -:1065D000284A002008B50348FCF71AFBBDE808402C -:1065E000FFF76CBD0425002008B50348FCF7BCFB91 -:1065F000BDE80840FFF762BD2425002008B5FFF77D -:10660000ABFDBDE80840FFF759BD0000062108B505 -:106610000846FFF72FF906210720FFF72BF906217F -:106620000820FFF727F906210920FFF723F90621A3 -:106630000A20FFF71FF906211720FFF71BF9062193 -:106640002820FFF717F909217A20FFF713F90A210B -:106650005C20FFF70FF907213220FFF70BF90C211F -:106660002620BDE80840FFF705B9000008B5FFF790 -:1066700095FD00F00FF8FCF78FFDFCF767FFFCF7C6 -:1066800039FEFDF7FDF9FFF7DFFCBDE80840FFF735 -:10669000D1BA00000023054A19460133102BC2E984 -:1066A000001102F10802F8D1704700BF284A00200B -:1066B0000B460146184600F027B80000FEF7CCB89C -:1066C000FFF7FCBF012838BF012010B50446204663 -:1066D000FEF782F830B900F007F808B900F00CF8BE -:1066E0008047F4E710BD0000024B1868BFF35B8FD2 -:1066F000704700BFA84A002008B5062000F04AF8FD -:106700000120FDF733FD000010B5054C13462CB1F8 -:106710000A4601460220AFF3008010BD2046FCE788 -:106720000000000010B501390244904201D1002060 -:1067300005E0037811F8014FA34201D0181B10BDEA -:106740000130F2E71F2938B504460D4604D9162357 -:1067500003604FF0FF3038BD426C12B152F8213067 -:106760004BB9204600F030F82A4601462046BDE8E5 -:10677000384000F017B8012B0AD0591C03D116235A -:1067800003600120E7E7002442F8254028469847A7 -:106790000020E0E7024B01461868FFF7D3BF00BFB7 -:1067A0006422002038B5074D0023044608461146F0 -:1067B0002B60FDF7DFFC431C02D12B6803B1236083 -:1067C00038BD00BFAC4A0020FDF7CEBC034611F82F -:1067D000012B03F8012B002AF9D1704700000000BB -:1067E00001000000000100010000000000000000A6 -:1067F0000000000052657175657374656420746FE4 -:10680000206572617365206D6F7265207468616EBA -:106810002077652063616E0A0045726173652043CD -:106820006F6D6D616E642052656365697665640A9B -:106830000050435420444F4E453A2025640A00003E -:1068400053544D333248373F3F3F0053544D33325A -:10685000483733782F3732780053544D3332483726 -:1068600034332F3735332F373530000001105A00BD -:10687000031059000120580003205600534644508D -:10688000000000004A454445433A204661696C6572 -:106890006420746F2064657465637420666C617332 -:1068A00068206465766963653A2025730A004A4565 -:1068B0004445433A204661696C656420746F2063E7 -:1068C0006F6E66696720666C6173682064657669BF -:1068D00063653A2025730A004A454445433A2044FB -:1068E0006574656374656420466C617368204465F3 -:1068F000766963653A2025730A0045787420466CF2 -:10690000617368204E6F7420466F756E64210000BD -:106910006D74323571007732357100773235712DF3 -:10692000647472001069000820BA000000000000C2 -:1069300016690008EF400000000000001B69000815 -:10694000EF700000000000000000000000000000E8 -:106950004D1D0008B51F0008691600086D160008D7 -:10696000151700081D1F000871160008751600088D -:10697000151E0008E5160008751E0008591B0008C2 -:106980007D160008791600084D200008DD16000865 -:1069900000000000000000000000000000000000F7 -:1069A000452100088924000889240008492100089D -:1069B0004D210008512100085521000889240008B4 -:1069C00089240008892400086D210008712100082D -:1069D00089210008912100089D210008A1210008BB -:1069E000A52100080425002001000000000000008F -:1069F00000000000DD220008F52200084521000803 -:106A0000B121000829230008E5210008C12300085E -:106A1000F123000855210008C9210008B52100080C -:106A2000C52100086D210008712100088921000896 -:106A3000912100089D210008A1210008A52100083E -:106A4000CD21000800000000000000005D220008C9 -:106A5000A9210008AD21000800000000000000008E -:106A600051250008592500083D2500084525000846 -:106A7000692500086D250008286E756C6C290000DA -:106A800000000000ED290008C5290008752900084C -:106A900091290008AD2900084D444D4120666169E7 -:106AA0006C75726500000000009600000000000098 -:106AB00000000000000000000000000000000000D6 -:106AC00000000000593100084531000881310008FC -:106AD0006D31000879310008653100085131000836 -:106AE0003D3100088D3100080000000071320008BF -:106AF0005D320008993200088532000891320008A2 -:106B00007D3200086932000855320008A5320008BD -:106B100000000000010000000000000063300000E1 -:106B20001C6B0008E8290020F82B002043756265E3 -:106B300050696C6F7400437562655265642D424CF8 -:106B4000002553455249414C250000000200000039 -:106B500000000000913400080135000840004000AA -:106B6000A8440020B84400200200000000000000FB -:106B7000030000000000000049350008000000008C -:106B800010000000C84400200000000001000000C8 -:106B900000000000B8480020010102006D4200081A -:106BA0007D41000819420008FD4100084300000033 -:106BB000B46B000809024300020100C0320904005E -:106BC000000102020100052400100105240100015A -:106BD000042402020524060001070582030800FFC1 -:106BE00009040100020A000000070501024000003C -:106BF000070581024000000012000000006C000840 -:106C00001201100102000040AE2D591000020102D5 -:106C1000030100000403090425424F4152442500AA -:106C2000437562655265645072696D6172790030B6 -:106C300031323334353637383941424344454600E2 -:106C400000000020000002000200000000010030EF -:106C50000000000008000000000000240000080000 -:106C6000040000000004000000FC0000020000001E -:106C70000000043000800000080000000000003820 -:106C8000000001000100000040000052800000529E -:106C9000C000005200010052400100528001005229 -:106CA000C001005200020052400200528002005215 -:106CB000C002005200030052400300528003005201 -:106CC000C00300520004005200000000A536000876 -:106CD0005D390008093A000840004000F0490020F2 -:106CE000F049002001000000004A00208000000060 -:106CF000400100000800000000010000001000003A -:106D0000080000006D61696E0069646C6500000038 -:106D10000000802A00000000AAAAAAAA00000024FD -:106D2000FFFF00000000000000A00A00200020007B -:106D300000000000AAAAAAAA00000000FFFF0000AD -:106D40000009000000090000000000000000000031 -:106D5000AAAAAAAA00000000FFFF0000000000008D -:106D6000000000000028800A00000000AAAAAAAAC9 -:106D700000140000FFFF0000000070070090990061 -:106D80002000000000000000AAAAAAAA000000003B -:106D9000FFFF0000000900000000000010000000DC -:106DA00000000000AAAAAAAA00000000FBFF000041 -:106DB00000000000000000000104000000000000CE -:106DC000AAAAAAAA00000000FEFF0000000000001E -:106DD000000000000000000000000000AAAAAAAA0B -:106DE00000000000FFFF00000000000000000000A5 -:106DF0000000000000000000AAAAAAAA00000000EB -:106E0000FFFF000000000000000000000000000084 -:106E100000000000AAAAAAAA00000000FFFF0000CC -:106E20000000000000000000000000000000000062 -:106E3000AAAAAAAA00000000FFFF000000000000AC -:106E400000000000DC94FF7F010000000000000053 -:106E50002D0400000000000000001A0000000002E5 -:106E6000FF000000002C002024250020000000006E -:106E700040680008830400004B68000850040000CC -:106E80005968000800960000000008009600000005 -:106E90000008000004000000146C0008000000005E -:106EA00000000000000000000000000000000000E2 -:106EB0000000000068220020000000000000000028 -:106EC00000000000000000000000000000000000C2 -:106ED00000000000000000000000000000000000B2 -:106EE00000000000000000000000000000000000A2 -:106EF0000000000000000000000000000000000092 -:106F00000000000000000000000000000000000081 -:086F1000000000000000000079 +:1000000000070020F102000849230008FD22000833 +:1000100025230008FD2200081D230008F302000824 +:10002000F3020008F3020008F3020008ED4F000895 +:10003000F3020008F3020008F3020008F3020008CC +:10004000F3020008F3020008F3020008F3020008BC +:10005000F3020008F3020008B1680008DD68000838 +:10006000096900083569000861690008012900086C +:10007000292900085529000881290008AD29000810 +:10008000D5290008012A0008F3020008F30200083D +:10009000F3020008F3020008F30200088D6900086B +:1000A000F3020008F3020008F3020008F30200085C +:1000B000F3020008F3020008F3020008F30200084C +:1000C000F3020008F3020008F3020008F30200083C +:1000D000F3020008F3020008796A0008F30200083E +:1000E000F1690008F3020008F3020008F3020008B7 +:1000F000F3020008F3020008F30200082D2A0008AA +:10010000F3020008F3020008A16A0008F3020008E5 +:10011000F3020008F3020008F3020008F3020008EB +:10012000592A0008812A0008AD2A0008D92A0008A7 +:10013000052B0008F3020008F3020008F302000890 +:10014000F3020008F3020008F3020008F3020008BB +:100150002D2B0008592B0008852B0008F3020008FE +:10016000F3020008F3020008F3020008F30200089B +:10017000F3020008755D0008F3020008F3020008AE +:10018000F3020008F30200088D6A0008F302000879 +:10019000F3020008F3020008F3020008F30200086B +:1001A000F3020008F3020008F3020008F30200085B +:1001B000656A0008F3020008F3020008F302000871 +:1001C000F3020008F3020008F3020008F30200083B +:1001D000F3020008615D0008F3020008F302000862 +:1001E000F3020008F3020008F3020008F30200081B +:1001F000F3020008F3020008F3020008F30200080B +:10020000F3020008F3020008F3020008F3020008FA +:10021000F3020008F3020008F3020008F3020008EA +:10022000F3020008F3020008E1510008F30200089D +:10023000F3020008F3020008F3020008F3020008CA +:10024000F3020008F3020008F3020008F3020008BA +:10025000F3020008F3020008F3020008F3020008AA +:10026000F3020008F3020008F3020008F30200089A +:10027000F3020008F3020008F3020008F30200088A +:10028000F3020008F3020008F3020008F30200087A +:10029000F3020008F3020008F3020008F30200086A +:1002A000F3020008F3020008F3020008F30200085A +:1002B000F3020008F3020008F3020008F30200084A +:1002C000F3020008F3020008F3020008F30200083A +:1002D000F3020008F3020008F3020008F30200082A +:1002E000D5040008C51F0008D52200080000000042 +:1002F00002E000F000F8FEE772B6374880F30888A5 +:10030000364880F3098836483649086040F20000D4 +:10031000CCF200004EF63471CEF200010860BFF35B +:100320004F8FBFF36F8F40F20000C0F2F0004EF627 +:100330008851CEF200010860BFF34F8FBFF36F8F7B +:100340004FF00000E1EE100A4EF63C71CEF20001D3 +:100350000860062080F31488BFF36F8F04F0A8FEB6 +:1003600006F082F84FF055301F491B4A91423CBFBE +:1003700041F8040BFAE71D49184A91423CBF41F885 +:10038000040BFAE71A491B4A1B4B9A423EBF51F82D +:10039000040B42F8040BF8E700201849184A914270 +:1003A0003CBF41F8040BFAE704F0C0FE06F0D0F8B9 +:1003B000144C154DAC4203DA54F8041B8847F9E796 +:1003C00000F050F8114C124DAC4203DA54F8041B03 +:1003D0008847F9E704F0A8BE0007002000230020AA +:1003E0000000000808ED00E00001002000070020E8 +:1003F000B8730008002300206C2300207023002025 +:1004000028690020E0020008EC020008EC02000865 +:10041000EC0200082DE9F04F2DED108AC1F80CD048 +:10042000D0F80CD0BDEC108ABDE8F08F002383F328 +:1004300011882846A047002003F0E0FEFEE703F005 +:100440001FFE00DFFEE70000054B10B50446036009 +:10045000806810B103685B689847204610BD00BFF4 +:10046000286D000870B500F0A5FD00F0FBFF04F05A +:100470009BFC054604F0B0FD0446B8B9134B9D4201 +:1004800016D001339D4241F2883512BF0446002543 +:1004900001240F4E002004F091FC304601F0B4FB23 +:1004A00040B944F6206003F0AFFEF6E70025F0E720 +:1004B0000546EEE70CB100F08FF800F011FF28467A +:1004C00000F038F900F088F8F9E700BF010007B044 +:1004D000702300200448054B054A036000230549AA +:1004E000836006F03BBB00BF70230020286D00082E +:1004F000C42500204904000808B500F027FDA0F13C +:1005000020035842584108BD07B5042101900DEB66 +:10051000010000F039FD03B05DF804FB07B541F2BE +:100520001203022101A8ADF8043000F02DFD03B044 +:100530005DF804FB38B5302383F31188174803684E +:100540000BB103F03FFF0023154A4FF47A711348B3 +:1005500003F02EFF002383F31188124C236813B19C +:100560002368013B2360636813B16368013B6360E8 +:100570000D4D2B7833B963687BB9022000F0E0FDA4 +:10058000322363602B78032B07D163682BB90220D9 +:1005900000F0D6FD4FF47A73636038BD002400206C +:1005A000350500082025002018240020084B18706D +:1005B00003280CD8DFE800F008050208022000F04C +:1005C000B7BD022000F0AABD024B00225A6070475E +:1005D0001824002020250020F7B54E4801A901F07D +:1005E00093FC002800F094804B4B4C4A1C46196841 +:1005F000013100F08A8004339342F8D16268484B9D +:100600009A4240F28280474B9B6803F1006303F5F6 +:1006100000339A4279D2002000F0F2FC0220FFF76A +:10062000C5FF414B00219A6C99641A6F19671A6FC4 +:10063000DA6CD9645A6F59675A6F1A6D19659A6FD7 +:1006400099679B6F394BD3F8802042F00062C3F862 +:100650008020D3F8802022F00062C3F88020D3F8F5 +:100660008020D3F8802042F00072C3F88020D3F8B5 +:10067000802022F00072C3F88020D3F8803072B658 +:100680004FF0E023C3F8084DD4E90004BFF34F8FC7 +:10069000BFF36F8F264AC2F88410BFF34F8F5369A0 +:1006A00023F480335361BFF34F8FD2F8803043F689 +:1006B000E076C3F3C905C3F34E335B0103EA060CCE +:1006C00029464CEA81770139C2F87472F9D2203B8D +:1006D00013F1200FF2D1BFF34F8FBFF36F8FBFF332 +:1006E0004F8FBFF36F8F536923F40033536100239F +:1006F000C2F85032BFF34F8FBFF36F8F302383F3B5 +:100700001188854680F308882047024800F044FF9E +:1007100003B0F0BD70230020000002082000020892 +:10072000FFFF010800230020004502580044025842 +:1007300000ED00E02DE9F04FB24B9DB02022FF21EB +:10074000079014A89E68DB68069300F073FDAE4A1C +:100750001378A3B90121AD4811700360302383F3EE +:10076000118803680BB103F02DFE0023A84A4FF453 +:100770007A71A64803F01CFE002383F31188079BBF +:1007800013B1A44B079A1A60A34A1378032B03D022 +:10079000002313709F4A53600023079D1F469B460A +:1007A000CDE90433012000F0C3FC00F0E9FD2DB1D8 +:1007B000984B1B6813B9002800F05883002000F004 +:1007C000C5FB0C900C9B002BEFDB012000F0A6FC7E +:1007D0000C9B213B1F2BE5D801A252F823F000BF50 +:1007E00061080008890800081F090008A50700081B +:1007F000A5070008A5070008CD0B0008E70D0008B5 +:10080000890C0008650D00088B0D0008B10D00086B +:10081000A5070008C30D0008A50700082F0E000853 +:1008200001090008A5070008730E0008B3090008B5 +:10083000EB0A0008A5070008DD0C0008A507000862 +:10084000A5070008A5070008A5070008A5070008D8 +:10085000A5070008A5070008A50700081F0900084C +:100860000220FFF749FE002840F02B83079B02215E +:10087000059A0FA8002A08BF1D4641F21233ADF8B1 +:100880003C3000F081FB8DE74FF47A7000F05EFBA6 +:10089000041EEBDB0220FFF72FFE0028E6D0013C10 +:1008A000052C00F21083DFE804F0030A0D10133763 +:1008B000052304210FA80F9300F066FB17E0042125 +:1008C0005048F9E704215548F6E704215448F3E776 +:1008D0004FF01C08404608F1040800F093FB042187 +:1008E0000F900FA800F050FBB8F12C0FF2D10120AF +:1008F000049B4FF0000B00FA04F41C43E3B2049392 +:1009000000F0E4FC2FB1049B03F00B030B2B08BF9A +:100910000025FFF703FE45E704214248CCE7002FFE +:10092000A4D0049B03F00B030B2B9FD10220FFF7F5 +:10093000E3FD0446002899D00120002700F060FB69 +:100940000220FFF733FE1FFA87F8404600F068FBED +:100950000546B0B10C9940460137A1F14002514221 +:10096000514100F06DFB0028EDD10546059441F2A0 +:10097000121302210FA82746ADF83C3000F004FB0B +:1009800010E72E460120FFF711FE1E4B9B68B34275 +:1009900007D9304600F036FB013040F0978204362C +:1009A000F3E700261C4B274605941E70194B5E602A +:1009B000A6E7002F3FF45AAF049B03F00B030B2B69 +:1009C0007FF454AF64210DA800F0D4FA80460028CB +:1009D0007FF44CAF0220FFF78FFD044600283FF460 +:1009E00045AFDFF848908DF82F80D9F82420D9F84A +:1009F000203053430D9A93421AD20B4800F0AAFBC1 +:100A000034E700BF002300201C2500200024002024 +:100A1000350500082025002018240020042300208C +:100A2000082300200C230020CC6B0008702300203A +:100A3000BE484746C24600F08DFBFFF76FFD01211F +:100A40000DF12F0000F0A0FA0D9B534541D9002372 +:100A50000EAA39464846CDE90E330FAB00F0A0FD93 +:100A6000002884D001F078FC0E9B00EB03080121E4 +:100A70000DF12F0000F088FA01F06EFC404520D9FE +:100A8000484600F0C7FF80B964210D9BA848013794 +:100A900001FB0AF1B1FBF3F18DF82F10C9B200F0A0 +:100AA00059FBD9F820309A44CEE701F055FC0F9B52 +:100AB000184440453FF65BAF01F04EFC0E9B00EB47 +:100AC00003080E9B4FF47A70A3FB000303F09CFB1A +:100AD000CDE7642301210DF12F0027468DF82F303B +:100AE00000F052FA002306930AE7002F3FF4BEAE4F +:100AF000049B03F00B030B2B7FF4B8AE0220FFF72F +:100B000055FD322000F022FA041EFFF6AFAE069B20 +:100B1000A046E3180893874B089ADB689A423FF691 +:100B2000A5AEB4F5807F3FF7A1AEDFF80CA24FF081 +:100B300000094C450EDD4FF47A7000F007FA0C9076 +:100B40000C9B002BFFF692AE0C9B09F101090AF8F1 +:100B5000013BEEE7C820FFF7CFFC044600283FF436 +:100B600085AE0027DFF8D491CDE90E77B8F1000FFC +:100B700002D12746089BB6E70FAB6F4A0699484655 +:100B800002930EAB3A44394401930DAB00934346B4 +:100B900001F022F900283FF4EAAE01F0DFFB0D9BE3 +:100BA0008A4609901F44A8EB030801F0D7FB099A75 +:100BB0000E9B9B184AF10002834272EB0103F4D2B0 +:100BC000484600F027FF0028EFD1CFE7002F3FF481 +:100BD0004DAE049B03F00B030B2B7FF447AE0220BA +:100BE000FFF7E4FC322000F0B1F9B0F10008FFF6A5 +:100BF0003DAE18F003047FF439AE4E4A08EB06030D +:100C0000926893423FF632AEB8F5807F3FF72EAE42 +:100C1000DFF82491A0450DDD4FF47A7000F096F9CD +:100C20000C900C9B002BFFF621AE0C9B013409F8B5 +:100C3000013BEFE7C820FFF75FFC044600283FF4C4 +:100C400015AE1F2E11D8C6F1200214AB26F00300FA +:100C500039494245184428BF4246089200F0B8FA84 +:100C6000089AFF21344800F0E5FAC8F387023249B8 +:100C700030464FEAA80900F0E5FA074600283FF49D +:100C800076AE06EB89063BE60220FFF735FC00282E +:100C90003FF4ECAD00F0F2F900283FF4E7AD00249A +:100CA000A046244B9B68A34258D91F2C11D8149BF3 +:100CB00001330ED024F003031CAA134453F8203C44 +:100CC0000F93404604220FA9043401F083F98046B3 +:100CD000E7E7204600F096F90F90F2E764210EA8AE +:100CE00000F048F9044600287FF4C0AD0220FFF769 +:100CF00003FC00283FF4BAAD0E9BA046DFF83CA0F1 +:100D000003F003090E99A1EB0901A14218D921466C +:100D100004230FAA504601F0ABF8404604220FA965 +:100D200001F058F904348046ECE700BFF16B00088D +:100D3000096C0008002300201C24002070230020E0 +:100D4000B9F1000F0AD04B460FAA624801F090F8A3 +:100D500040464A460FA901F03DF980464046FFF75C +:100D6000D3FBCDE5002364210FA80F9300F002F917 +:100D700000287FF47BAD0220FFF7BEFB00283FF484 +:100D800075AD0F9800F070F9E9E7002364210FA812 +:100D90000F9300F0EFF800287FF468AD0220FFF712 +:100DA000ABFB00283FF462AD0F9800F05FF9D6E787 +:100DB0000220FFF7A1FB00283FF458AD00F06EF9C8 +:100DC000CDE70220FFF798FB00283FF44FAD0FA9B5 +:100DD000142000F069F90890FFF796FB08990FA816 +:100DE00000F0D2F88CE5322000F0B0F8041EFFF6D7 +:100DF0003DADA3077FF43AAD374A04EB0B0392688D +:100E000093423FF633AD0220FFF776FB00283FF414 +:100E10002DAD24F003045C44A3453FF471AD584666 +:100E20000BF1040B00F0EEF8FFF76EFBF4E74FF464 +:100E30007A70FFF761FB00283FF418AD00F01EF94F +:100E4000002845D0149B01330BD0082214A90020A0 +:100E500000F0F8F900283BD02022FF2114A800F070 +:100E6000E9F9FFF75BFB1D4803F0CEF91DB0BDE8C3 +:100E7000F08F002F3FF4FAAC049B03F00B030B2B15 +:100E80007FF4F4AC002364210FA80F9300F072F8F4 +:100E9000044600287FF4EAAC0220FFF72DFB8046D1 +:100EA00000283FF4E3ACFFF739FB41F2883003F050 +:100EB000ABF90F9800F0B0FA4746254600F006FA65 +:100EC00070E407461CE54FF0000BCFE405944EE5B7 +:100ED0003C464CE57023002000230020A086010042 +:100EE0002DE9F84F4FF47A7306460D46002402FBB5 +:100EF00003F7DFF85080DFF8509098F900305FFA80 +:100F000084FA5A1C01D0A34212D159F824002A466F +:100F100031460368D3F820B03B46D847854207D115 +:100F2000074B012083F800A0BDE8F88F0124E4E717 +:100F3000002CFBD04FF4FA7003F066F90020F3E7C1 +:100F4000882500201023002014230020002307B54B +:100F5000024601210DF107008DF80730FFF7C0FFB1 +:100F600020B19DF8070003B05DF804FB4FF0FF309F +:100F7000F9E700000A46042108B5FFF7B1FF80F049 +:100F80000100C0B2404208BD074B0A4630B4197890 +:100F9000064B53F82140014623682046DD69044B87 +:100FA000AC4630BC604700BF8825002014230020D9 +:100FB000A086010070B5104C0025104E03F0A0FC77 +:100FC00020803068238883420CD80025208801388F +:100FD00003F092FC23880544013BB5F5802F238064 +:100FE000F4D370BD03F088FC336805440133B5F5D4 +:100FF000003F3360E5D3E8E78A2500204025002044 +:1010000003F04CBD00F1006000F50030006870474F +:1010100000F10060920000F5003003F0CDBC00004C +:10102000054B1A68054B1B889B1A834202D9104452 +:1010300003F062BC00207047402500208A25002074 +:1010400038B50446074D29B128682044BDE838402A +:1010500003F06ABC2868204403F054FC0028F3D055 +:1010600038BD00BF402500200020704700F1FF5030 +:1010700000F58F10D0F8000870470000064991F87D +:10108000243033B100230822086A81F82430FFF7A6 +:10109000BFBF0120704700BF48250020014B1868E2 +:1010A000704700BF0010005C194B01380322084450 +:1010B00070B51D68174BC5F30B042D0C1E88A64296 +:1010C0000BD15C680A46013C824213460FD214F9E8 +:1010D000016F4EB102F8016BF6E7013A03F1080324 +:1010E000ECD181420B4602D22C2203F8012B0424BE +:1010F000094A1688AE4204D1984284BF967803F814 +:10110000016B013C02F10402F3D1581A70BD00BF1B +:101110000010005C1C230020446C0008022803D14E +:10112000024B4FF400129A61704700BF001802583A +:10113000022802D1014B20229A6170470018025800 +:10114000022804D1024A536983F020035361704797 +:10115000001802580FB4124B30B51A78B5B042B926 +:101160000122104910481A704FF461430B6002F0DD +:101170000FFA39AB0C4C389AC82102A8019301F040 +:10118000BBF82368C8280246DD6902A9074B28BFBF +:10119000C8222046A84735B0BDE8304004B07047AB +:1011A0008C250020902500206C260020A0860100C0 +:1011B00070B504464FF47A764CB1412C254628BFD1 +:1011C000412506FB05F0641B03F01EF8F4E770BD33 +:1011D000002310B5934203D0CC5CC4540133F9E72B +:1011E00010BD0000013810B510F9013F3BB191F975 +:1011F00000409C4203D11AB10131013AF4E71AB11F +:1012000091F90020981A10BD1046FCE70138013909 +:1012100010F9013F11F9012F0BB19342F8D0981A40 +:101220007047000003460246D01A12F9011B00293C +:10123000FAD1704702440346934202D003F8011BDF +:10124000FAE770472DE9F8431F4D144607468846D4 +:1012500095F8242052BBDFF870909CB395F82430A9 +:101260002BB92022FF2148462F62FFF7E3FF95F8B4 +:1012700024004146C0F1080205EB8000A24228BFCD +:101280002246D6B29200FFF7A3FF95F82430A41BA4 +:1012900017441E449044E4B2F6B2082E85F8246048 +:1012A000DBD1FFF7EBFE0028D7D108E02B6A03EB78 +:1012B00082038342CFD0FFF7E1FE0028CBD100208C +:1012C000BDE8F8830120FBE748250020024B1A788F +:1012D000024B1A70704700BF8825002010230020A1 +:1012E00070B5204D204E2846204C02F0F3F93146CF +:1012F000284602F01BFA204602F0ECF91C49204671 +:1013000002F014FA36684FF47A70D6F89020D2F8CA +:10131000043843F00203C2F80438FFF749FF1549C7 +:10132000304602F011FBD6F89020134ED2F8043864 +:10133000306823F002031149A842C2F804384FF480 +:10134000E1330B6003D0A04201D002F021F97068B4 +:10135000A84206D0A04204D00849BDE8704002F07F +:1013600017B970BDB8310020B4700008604A002081 +:10137000BC700008C47000081423002070250020F1 +:101380002049214BF0B50A68ADF5017D9A4206D09F +:101390000B604FF400431D488B6002F0F9F81C4CC1 +:1013A0004FF4007269461B4E236820461D6A0023D5 +:1013B000A847021E154D0ADD2B6869462846DF69DD +:1013C0000023B84700F0C8FF00F57A7030602B6842 +:1013D0004FF4007269460D481D6A0023A847021E9B +:1013E00005DD236869460A48DC690023A04700F050 +:1013F000B3FF336898422CBF002001200DF5017D1A +:10140000F0BD00BF2825002080841E00D8260020C3 +:10141000604A0020442500200D4B0E4A70B50E4D49 +:1014200004461E7855F82630934210D00B4A93425A +:101430000DD00B4B002118221846FFF7FBFE04606D +:10144000014655F82600BDE8704002F0A1B870BD15 +:1014500088250020B831002014230020604A002095 +:1014600070250020F8B571B6002301201A461946F0 +:1014700001F026FC0446802003F0B2FB002849D08E +:101480000025254A80274FF4D06C3D26136913F0C0 +:10149000C06F26D1D2F8103113F0C06F21D123686C +:1014A00005F1006199602368D86023685F60236854 +:1014B000C3F800C021680B6843F001030B6021688A +:1014C0000B6823F01E030B6021680B68DB07FCD45C +:1014D000237B8035616806FA03F3B5F5001F0B60C6 +:1014E000D4D1204601F022FCB5F5001F11D0002414 +:1014F0000A4E0B4D012003F0D1FA3388A34205D9DF +:1015000028682044013403F00FFAF6E7002003F0C6 +:10151000C5FA61B6F8BD00BF002000528A25002040 +:101520004025002080697047C0697047006A704795 +:10153000406A7047806A7047F0B5ADF2044D0E46C0 +:10154000054600214FF47F7201A80091FFF772FE5B +:101550002C6A744301362B6A7343A34216D92B6855 +:101560006A46214628465F684FF48063B84770B1E9 +:101570006A464FF4806312F8011BFF290AD1013B30 +:101580009BB2002BF7D104F58064E4E701200DF253 +:10159000044DF0BD0020FAE780680368DB69184756 +:1015A00030B5456A85B004468D420FD30568CDE954 +:1015B0000023026A03ABAD6A5143A84720B1206AF9 +:1015C000039BC31A5842584105B030BD0020FBE7C9 +:1015D000F0B5C56987B004468D4212D30C9F866969 +:1015E00005687143CDE9013705AB00936D69036A66 +:1015F000A84720B1A069059BC31A5842584107B0BB +:10160000F0BD0020FBE70000F0B5662389B00024A0 +:1016100005464FF480768068079403A9CDE9033628 +:10162000CDE9054403685B699847A86822462146CE +:10163000036800941F692346B847A8689923079454 +:1016400003A9CDE90336CDE9054403685B699847F2 +:10165000A86822462146036800941D692346A847CE +:1016600009B0F0BD254B2DE9F04F1B789FB0002548 +:1016700004468DF828304FF09F0E80684FF001230C +:10168000ADF8295005A90995CDE905E3CDE9075540 +:1016900003685B699847A0680322294603680092A3 +:1016A0002A461E690AABB04730B394F88C200C214F +:1016B000134B01FB02339DF828101A7991421BD17C +:1016C0009DF829205B799A4216D1A0684FF05A0CF8 +:1016D0000C4B082605A90996CDE905C3CDE90755A8 +:1016E00003685B699847A0682A4629460368009604 +:1016F0001F690AABB84738B900204BE1B46B00084A +:10170000FC6C0008002500010422B3490AA805F07A +:1017100039FA05460028EFD1BDF82C306FF48277F6 +:10172000A3813B44012BE7D8079605A9CDE90A0020 +:10173000A06803685B699847A0682A462946036841 +:1017400000961E690AABB0470028D5D0DDE90A36FD +:101750001A0202F4706242EA1662FF2ACCD11B0E12 +:1017600026F07F4650222946142B26610AA828BF5E +:101770001423A373FFF75EFDA068079605A903680D +:101780005B699847A068A37B294602689B00009389 +:101790000AAB16692A46B0470028ADD00B9900293C +:1017A000AADBC9086FF07E43149D4FF0010E9942E9 +:1017B00028BF1946C5F303130EFA03F221FA03F307 +:1017C00003916161A261E361002B95D02646A44696 +:1017D00000274FF002081EAAC7F3460302EB83035B +:1017E00053F834AC07F001031B01DA1D0EFA03F9BC +:1017F00008FA02F2A2EB090202EA0A02DA401AD05F +:1018000003F108090F330EFA02F2216A08FA03F312 +:101810000EFA09FBCCF830208A42A3EB0B0B0BEA43 +:101820000A0A2AFA09F98CF82C90A36A88BF226266 +:10183000934288BFA26201370CF1100C042FCAD169 +:10184000236A4FF0020C039A4FF0010E139F9A4245 +:1018500024BFB2FBF3F1616207F00F0138BF01232F +:101860004FF0090201F1010138BF63624900336B97 +:1018700033B3531C0EFA02F8A2F105090CFA03F374 +:101880000EFA09FAA3EB080302F1FF380CFA08F884 +:101890003B40A8EB0A08D34008EA070828FA09F8F1 +:1018A0007BD0012B7BD0022B7BD0032B08BF4FF4C6 +:1018B0007A735FFA88F808FB033373634B43B363AF +:1018C00007321036252AD2D115F0C04FC5F3417327 +:1018D00069D0012B69D0022B0CBF4FF47A634FF40F +:1018E0007A43C5F3046202FB0333E3664B43236789 +:1018F000199B9E075CD0062384F8743015F4005FB2 +:1019000005F00F03C5F3042514BF4022082201335C +:1019100005FB02255B00A5675D430A9B9F02E56707 +:101920007FF5EAAE0C9BC3F30722C3F3421103F029 +:101930001F0384F8802084F8881084F88130002AFE +:101940003FF4DAAE189BC3F3025213F4401F84F83D +:1019500083207FF4D1AEDE0602D5042A7FF4CCAE1C +:1019600003F40072002A14BF0122002284F88720A9 +:1019700004D0DD0324D5002384F88930179B1A078F +:1019800022D5002384F88630702384F88530012323 +:1019900084F88D301FB0BDE8F08F012389E7102354 +:1019A00087E7802385E710239BE74FF4807398E750 +:1019B000590701D550239FE713F0780F9ED09BE67F +:1019C0009903DBD50123D7E75B07E0D5012384F832 +:1019D00086300523D9E700BF546C000830B58BB0C2 +:1019E00000240546806803924FF00122059105A965 +:1019F000CDE90624CDE90844026852699047A868F9 +:101A00000121039B02680091214615692246A847DF +:101A10000BB030BD13B50446A0680368DB6C984773 +:101A20000028F9D10DF1070294F885102046FFF740 +:101A3000D5FF94F886309DF807001BB100F0010037 +:101A400002B010BDC043C0F3C010F9E730B54FF08D +:101A500001238BB00024054680688DF80F20059186 +:101A600005A9CDE90634CDE9084403685B699847C8 +:101A7000A86801220DF10F01036800941D69234637 +:101A8000A8470BB030BD0000F7B517460DF10702AF +:101A900006461D46FFF7A2FF68B19DF8074039468C +:101AA0009DF82020304624EA05042A4022438DF880 +:101AB0000720FFF7CBFF03B0F0BD000030B54FF4B7 +:101AC000807389B0002405468068039103A9CDE99D +:101AD0000434CDE9064403685B699847A868224648 +:101AE0002146036800941D692346A84709B030BD0C +:101AF00010B5044623682046DB6A98470028F9D1D0 +:101B000010BD000010B590F8743004465BB1FFF7CB +:101B1000EFFF012394F87410204684F88E30BDE85E +:101B20001040FFF7CBBF012010BD000010B590F8AA +:101B30007430044653B1FFF7DBFF01232046042134 +:101B400084F88E30BDE81040FFF7B8BF012010BD0B +:101B5000F0B590F883308BB00446042B50D10027A9 +:101B60000DF10E0205218DF80E708DF80F70FFF744 +:101B700035FF00282FD00DF10F0235212046FFF749 +:101B80002DFF40B320461F4EFFF7BCFF2046FFF756 +:101B9000AFFF05AD0FCE0FC5336805A99DF80E2028 +:101BA0002B609DF80F30A06843F002038DF81020E1 +:101BB0008DF80F308DF8113003685B699847A06885 +:101BC000022204A9036800971D693B46A84720B973 +:101BD0002046FFF7ABFF002010E02046FFF7A6FFEE +:101BE0000DF10F0235212046FFF7F8FE0028F2D054 +:101BF0009DF80F309B07EED5012363600BB0F0BD5D +:101C00000120FBE7B86B00082DE9F34100230446EF +:101C10008068A36010B103685B6898470025264E72 +:101C2000264F0C2301A839465FFA85F86B439A5971 +:101C300000F072FA019BA0680022A360019210B12B +:101C400003685B689847019810B103685B68984720 +:101C5000A368E3B141F2883084F88C8002F0D4FAB2 +:101C60002046FFF7D1FC1E2002F0CEFA2046FFF7F7 +:101C7000F9FC054688B994F88C300C22104853437F +:101C8000F158FFF767FA284602B0BDE8F081013548 +:101C9000032DC6D10B4800F059FB2046FFF758FF33 +:101CA0000C2294F88C3005465343F15808B9064885 +:101CB000E7E70648E5E700BFFC6C0008A825002020 +:101CC0005C6C0008D26C0008866C0008B06C0008E0 +:101CD0002DE9F041044688B00F461646FFF712FF83 +:101CE0002046FFF705FF0025C722A0684FF4807348 +:101CF000079503A9CDE90323CDE9055503685B6981 +:101D00009847A0682A46294603680095D3F81080B2 +:101D10002B46C047054630B92046FFF707FF284647 +:101D200008B0BDE8F081E36E3B60236F3360F3E7FA +:101D30002DE9F041002588B01F4604460E460E9B53 +:101D400000F1400CA8463D60016B81B1A9420ED361 +:101D500091420CD8B6FBF1FE01FB1E6139B9416B13 +:101D600090F82C800F9D1960816B2960154610300A +:101D70006045E9D16DB3AB196269934229D8204619 +:101D8000FFF7C0FE2046FFF7B3FE4FF41453A068E0 +:101D900003A9CDF80C80CDE904360026CDE906660E +:101DA00003685B699847A06832463146036800962D +:101DB000D3F810803346C047064620462EB9FFF7B9 +:101DC000B5FE304608B0BDE8F081FFF7AFFE3D60DC +:101DD000F7E70026F5E700002DE9F04186690546A2 +:101DE00088B00F46B3429046B1FBF6FC06FB1C1CC4 +:101DF00028BF3346A6EB0C0C00269C45644628BF42 +:101E00001C46FFF77FFE2846FFF772FE0222A868F5 +:101E100003A9164B0597CDE90323CDE906660368B0 +:101E20005B699847A86822464146036800961F6987 +:101E30003346B847064628462EB9FFF777FE3046A8 +:101E400008B0BDE8F081FFF771FE0E9B1C60AB6F20 +:101E5000AA696343B3FBF2F30F9A1360EA6F109B16 +:101E60005443AA69B4FBF2F41C60E8E700250001C2 +:101E70002DE9F04FCE18436989B004469E420F46C3 +:101E8000914639D83D464FF40458DFF878A0FFF763 +:101E90002FFEAE4234D994F88030A6EB050B94F8AF +:101EA000882003A903930023BBF5806FA0680693E5 +:101EB000636828BF4FF4806B0595012B14BF434620 +:101EC0005346012A049394F8813008BF03F1FF338D +:101ED000079303685B699847A068A9EB070302684A +:101EE000CDF800B02B44D2F810B000221146D847EC +:101EF00018B105F58065CCE7002009B0BDE8F08F8A +:101F00000120FAE700ED0003F0B5044689B00E4663 +:101F1000FFF7EEFD94F887502DB194F889302BB17E +:101F2000012B24D00025284609B0F0BD94F880305C +:101F30000393F02306934FF4045304936368012B37 +:101F400004BF1D4B04930023059394F88130A068CF +:101F500003A9079303685B699847A0683146036843 +:101F60009B6998470546642002F04EF9DBE720465E +:101F70000027FFF7C7FD2046FFF7BAFD082381229F +:101F8000852120460097FFF77FFD054618B92046BA +:101F9000FFF7CCFDC7E794F8803006970393074B13 +:101FA00004936368012B04BF054B0493002305933E +:101FB00094F88130013BCAE700ED000300210010D6 +:101FC00000ED0013014B024A1A607047A82500205B +:101FD000246E000830B50A44084D91420DD011F826 +:101FE000013B5840082340F30004013B2C4013F010 +:101FF000FF0384EA5000F6D1EFE730BD2083B8ED4F +:1020000070470000704700000020704700207047B4 +:1020100013B56C4600F1140384E8060094E803004D +:1020200083E8050002B010BD0020704713B56C4670 +:1020300000F10C0384E8060094E8030083E805003F +:1020400002B010BD0023C0E90333704782B002AB79 +:1020500003E9060002B07047704700000020704797 +:102060007047000000207047002070470120704733 +:1020700082B0002002A901E90C0002B07047000004 +:102080000020704700207047036B1A79034B53F808 +:1020900032309B699868C0F340107047BC6D0008EF +:1020A0000B6883634B6843638B68C363CB680364CB +:1020B0000B6943647047000038B5036B0446154D47 +:1020C0001B7955F8330001F03FFFD4E90B231B794E +:1020D00055F8331002F130034968994218D00023B3 +:1020E0001363E26A5363D4E90B12537C581E137CCA +:1020F00092681B0443EA002313438B63D4E90B1358 +:102100001B79303155F83300BDE8384001F0B0BEDE +:1021100038BD00BFBC6D0008F8B51D4F05460E4622 +:1021200011463868FFF772F878BB74683B7924B3BE +:1021300094F82C209A420BD02468F8E70122B521AC +:1021400000F01AF9736823603B79746084F82C30CE +:10215000482000F005F968B100220271C0E90322AD +:10216000C0E90522027A42F007020272094AC0E978 +:102170000B47026028602846F8BD402000F0F0F8C8 +:1021800004460028DAD12C60F5E700232B60F2E743 +:10219000B0250020CC6D0008044B10B50446036048 +:1021A000406A08B100F0E6F8204610BD706D0008E6 +:1021B00010B50446FFF7F0FF204600F0D7F82046A0 +:1021C00010BD000008B519B1FFF776FF012008BD6A +:1021D000036B1A79024B53F8320001F0B9FEF5E7B0 +:1021E000BC6D00082DE9FF41DDF828800546174643 +:1021F00003911FFA88F60293FFF75EFF02ABBAB2B3 +:1022000003A9E86A009600F0CBF8044638B900212B +:102210002846FFF7D7FF204604B0BDE8F081AFB9EC +:102220002B6B05F134011A79134B53F83200B8F1D6 +:10223000000F19D101F02AFE80F00104E4B2334608 +:10224000E86ADDE9022100F0D1F8E0E7029B83B9FA +:102250002B6B3A46084805F134011C79039B50F872 +:10226000340001F029FEE7E7029B424601F03AFE06 +:10227000E2E70024E3E700BFBC6D000813B50446A5 +:102280000191FFF719FF019A236B04F134011879CA +:10229000054B53F8300001F03BFE00212046FFF7CC +:1022A00091FF012002B010BDBC6D000810B50446BE +:1022B000FFF702FF236B1A79054B53F8320001F048 +:1022C00035FE00212046FFF77DFF012010BD00BF35 +:1022D000BC6D0008054B064A1A6000221A719A600C +:1022E000044ADA6040F21F121A827047B0250020BB +:1022F000F36C000800E1F50500F08ABA00B59BB068 +:10230000EFF3098168226846FEF762FFEFF3058369 +:10231000014B9B6BFEE700BF00ED00E008B5FFF747 +:10232000EDFF000000B59BB0EFF30981682268461D +:10233000FEF74EFFEFF30583014B5B6BFEE700BF3B +:1023400000ED00E0FEE70000FEE700000FB408B576 +:10235000029801F0FFFEFEE702F0C8BC02F0AABC42 +:102360000121884238BF084602F072BC08B102F071 +:1023700073BC7047FFF7FABF38B5084B04461546E3 +:10238000017543600A21243002F074FD04F1280035 +:102390002A460A2102F06EFD204638BD386E00083C +:1023A000F8B51E461B6805460C4617461BB9236840 +:1023B00063B9012408E0BDF818203146806A02F0B4 +:1023C00071FD0028F3D100242046F8BD21463A468D +:1023D000686A02F0ADFD04460028EAD13368002B9C +:1023E000F1D0A86A02F0E8FDEEE7000038B50D462E +:1023F000114604461A4611B1806A02F08BFD2DB1D8 +:102400002946606ABDE8384002F0CEBD38BD000004 +:10241000036800211B68184703790BB10022027181 +:102420001846704703685B681847000003791BB9BA +:102430000123037118467047002070477047000061 +:1024400010B50446FFF792FF204610BDF0B500F12D +:102450000B0423460D46B1FBF2F102FB115707F1C5 +:102460003006392EC8BF07F13706954203F8016DD3 +:10247000F0D2421EE11A13F8015B9C4202F8015FA0 +:10248000F9D10844F0BD00002DE9F04F804687B037 +:1024900015464FF000090C4614F8013B002B3BD0C9 +:1024A000252B08D0D8F800201946404609F101092B +:1024B000D268904749E14B782D2B06BF8C1C012335 +:1024C0000023019323782B2B06BF0134012700271B +:1024D00094F800A0BAF1300F0CBF01344FF0200A7D +:1024E00023782A2B1CD16178023455F804BB2E299D +:1024F00043D1217881B12A2921D0661C0020A1F185 +:1025000030023446D2B2092A1DD80A2316F8011B1C +:1025100003FB00200029F2D1484607B0BDE8F08F48 +:102520004FF0000B14F8011B0029F5D0A1F1300287 +:10253000D2B2092ADBD80A2303FB0B2BF2E761781E +:10254000023455F8040B01F0DF024C2A17D1217830 +:102550000029E1D0782904F101041FD8622900F292 +:10256000008158291AD84E2900F23081442900F000 +:102570009180492900F08E8010E00020E3E7A1F16E +:1025800041027829D2B209D862290BD8582905D836 +:102590004E293BD8442978D0492976D02E468DF84B +:1025A0000C1056E0A1F16306152EF7D80FF2040CBB +:1025B0005CF826F0452600088B2600089D250008BB +:1025C0009D2500089D2500089D2500088B260008F4 +:1025D0009D2500089D2500089D2500089D250008D3 +:1025E0009D2500081B270008092800089D250008D4 +:1025F0009D2500085B2600089D2500080528000889 +:102600009D2500089D25000809280008A1F14F021A +:10261000092AC3D801A050F822F000BF1B270008E8 +:10262000092800089D2500089D2500089D25000813 +:102630009D250008052800089D2500089D25000807 +:10264000092800082E464FF0200A56F8042B8DF872 +:102650000C2003AD0DF10D002BE02E4647F6FF7266 +:102660006A4B56F8045B002808BF1046002D08BFCF +:102670001D462A462F18104612F8011B11B1B91A2F +:102680000029F8DA4FF0200A13E02E46192A56F8EE +:10269000041B02D82E4656F8041B002936DA2D22D8 +:1026A00049428DF80C200DF10D000A2203ADFFF711 +:1026B000CDFE471B0199ABEB070323EAE372002928 +:1026C00045D1002BC2F1000B1EDD29782D2901D048 +:1026D0002B290DD1BAF1300F0AD1D8F8003040467D +:1026E000019209F10109DB68013F98470135019A20 +:1026F000D8F80030514640460192DB6898471BF1FC +:10270000010B019AF4D191443B4615E01FB12B22F5 +:102710008DF80C20C7E703A8C7E708222E4603A8B8 +:1027200056F8041BC2E7D8F80020404615F8011BF4 +:10273000D26801939047019B013BF4D5002FA8BFBD +:10274000B9445D462DB9D94435462146A3E69346A2 +:10275000DAE7D8F8003051464046013DDB6898473B +:10276000F0E7A1F16302152A3FF618AF01A353F871 +:1027700022F000BF45260008952600089D25000888 +:102780009D2500089D2500089D2500089526000828 +:102790009D2500089D2500089D2500089D25000811 +:1027A0009D2500081B270008092800089D25000812 +:1027B0009D2500085B2600089D25000805280008C7 +:1027C0009D2500089D25000809280008A1F14F0259 +:1027D000092A3FF6E3AE01A353F822F01B270008B5 +:1027E000092800089D2500089D2500089D25000852 +:1027F0009D250008052800089D2500089D25000846 +:10280000092800080A2289E7102287E7506E00088D +:10281000F0B5054687B016461F460C4689B14A1EDC +:102820000023294601A800F05FF83A46314601A886 +:10283000FFF72AFE049BA3423CBF0022EA5407B0E4 +:10284000F0BD0A46ECE70000D0E902239A421FBF20 +:102850004268D154C36801331ABFC36000206FF0CF +:1028600001007047D0E903239A421FBF4268D25C3F +:102870000133036114BF10466FF001007047000080 +:1028800003692BB1013B426803610020D1547047BA +:102890006FF001007047000038B504460846D4E9DF +:1028A00003315B1A934228BF13461D4663682A46CC +:1028B0001944FEF78DFC236928462B44236138BD5B +:1028C00038B50446D0E902301B1A934228BF13469C +:1028D0001D4663682A461844FEF77AFCE3682846DA +:1028E0002B44E36038BD000010B5C0E90223034C5F +:1028F0000023C0E90041036110BD00BF586E00080D +:1029000008B5074B074A196801F03D019960536803 +:102910000BB190689847BDE8084002F09FBB00BF2C +:1029200000000240C825002008B5084B1968890935 +:1029300001F03D018A019A60054AD3680BB1106924 +:102940009847BDE8084002F089BB00BF0000024084 +:10295000C825002008B5084B1968090C01F03D0195 +:102960000A049A60054A53690BB190699847BDE81B +:10297000084002F073BB00BF00000240C8250020E1 +:1029800008B5084B1968890D01F03D018A059A6068 +:10299000054AD3690BB1106A9847BDE8084002F0B8 +:1029A0005DBB00BF00000240C825002008B5074BF2 +:1029B000074A596801F03D01D960536A0BB1906A2A +:1029C0009847BDE8084002F049BB00BF0000024044 +:1029D000C825002008B5084B5968890901F03D0158 +:1029E0008A01DA60054AD36A0BB1106B9847BDE8DB +:1029F000084002F033BB00BF00000240C8250020A1 +:102A000008B5084B5968090C01F03D010A04DA6069 +:102A1000054A536B0BB1906B9847BDE8084002F034 +:102A20001DBB00BF00000240C825002008B5084BB0 +:102A30005968890D01F03D018A05DA60054AD36BBA +:102A40000BB1106C9847BDE8084002F007BB00BF0F +:102A500000000240C825002008B5074B074A196846 +:102A600001F03D019960536C0BB1906C9847BDE843 +:102A7000084002F0F3BA00BF00040240C82500205D +:102A800008B5084B1968890901F03D018A019A606F +:102A9000054AD36C0BB1106D9847BDE8084002F0B1 +:102AA000DDBA00BF00040240C825002008B5084B6D +:102AB0001968090C01F03D010A049A60054A536D3A +:102AC0000BB1906D9847BDE8084002F0C7BA00BF4F +:102AD00000040240C825002008B5084B1968890D7C +:102AE00001F03D018A059A60054AD36D0BB1106E65 +:102AF0009847BDE8084002F0B1BA00BF00040240A8 +:102B0000C825002008B5074B074A596801F03D0168 +:102B1000D960536E0BB1906E9847BDE8084002F043 +:102B20009DBA00BF00040240C825002008B5084B2C +:102B30005968890901F03D018A01DA60054AD36EBE +:102B40000BB1106F9847BDE8084002F087BA00BF8C +:102B500000040240C825002008B5084B5968090C3C +:102B600001F03D010A04DA60054A536F0BB1906F22 +:102B70009847BDE8084002F071BA00BF0004024067 +:102B8000C825002008B5084B5968890D01F03D01A2 +:102B90008A05DA60054AD36F13B1D2F880009847EE +:102BA000BDE8084002F05ABA00040240C8250020DF +:102BB00000230C4910B51A460B4C0B6054F8230047 +:102BC000026001EB430004334260402BF6D1074A18 +:102BD0004FF0FF339360D360C2F80834C2F80C346E +:102BE00010BD00BFC8250020706E00080000024024 +:102BF0000F28F8B510D9102810D0112811D012289C +:102C000008D10F240720DFF8B4E00126DEF80050D9 +:102C1000A04208D9002649E00446F4E70F2400202A +:102C2000F1E70724FBE706FA00F73D4240D1214CCB +:102C30004FEA001C3D4304EB00160EEBC000CEF83B +:102C40000050C0E90123FBB24BB11B48836B43F03A +:102C500001038363036E43F001030366036E17F4FD +:102C60007F4F09D01448836B43F002038363036EE4 +:102C700043F002030366036E54F80C00036823F06C +:102C80001F030360056815F00105FBD104EB0C037D +:102C90003D2493F80CC05F6804FA0CF43C602124D6 +:102CA0000560446112B1987B00F0A6FA3046F8BD89 +:102CB0000130ADE7706E000800450258C8250020BD +:102CC00010B5302484F31188FFF792FF002383F3BB +:102CD000118810BD10B50446807B00F0A3FA0123D3 +:102CE0001049627B03FA02F20B6823EA0203DAB2AC +:102CF0000B604AB90C4A916B21F001019163116E8E +:102D000021F001011166126E13F47F4F09D1064BB9 +:102D10009A6B22F002029A631A6E22F002021A667D +:102D20001B6E10BDC82500200045025808B5302391 +:102D300083F31188FFF7CEFF002383F3118808BDCA +:102D40008A0710B504461DD50378042B1AD14368B1 +:102D50001B682BB10522027098472378052B01D1FF +:102D600002232370302383F31188002104F108002B +:102D700001F064FA002383F31188E069BDE8104094 +:102D800002F0ECBACB0704D50248BDE8104001F0D0 +:102D9000E1B910BD706F000810B5044C204601F079 +:102DA0005FF8034A0023C4E9062310BD4C26002027 +:102DB0000050005210B503780446012B12D10E4B7F +:102DC00098420FD102460D49102002F099FA0C4B9F +:102DD000E0615A6B42F480425A63DA6D42F48042F9 +:102DE000DA65DB6D6268A36992685A60054A1A6009 +:102DF0001B22DA6010BD00BF4C260020412D0008C8 +:102E0000004502581500020182691B2310B5D360EA +:102E1000D1E9003013F44C4406D19B011461D06118 +:102E200003F44043536110BD0024184313F4406F72 +:102E30001461CC68D4615061F5D08B689361F2E77E +:102E400030B584691B25C069E5600068836104F1C1 +:102E50002003C36102234261013A03614223C3603C +:102E600016238362CB682261E361D1E90023134317 +:102E700012F4406F636101D08B68A361C36843F0B3 +:102E80000103C36030BD000030B5D0E906400068E2 +:102E900004F120058561C36108234261013A0361A1 +:102EA00046230D69C36016238362CB682261E36108 +:102EB000D1E90023134312F4406F43EA854343F002 +:102EC0008063636101D08B68A361C36843F0010331 +:102ED000C36030BD8069036823F0040310B5CC687B +:102EE000036000230361C4618361D1E90043096980 +:102EF000234343EA814343F04063436112B14FF0FF +:102F00001043136010BD000083691A6842F002028A +:102F10001A601A689207FCD41A6842F004021A6018 +:102F2000704700008269936810B5D3609B07044620 +:102F30001DD50378032B1AD143681B682BB10522DA +:102F4000027098472378052B01D102232370302388 +:102F500083F31188002104F1080001F06FF90023C8 +:102F600083F31188E069BDE8104002F0F7B910BDA5 +:102F7000026843681143016003B1184770470000BD +:102F8000024A136843F0C0031360704700440040D6 +:102F9000024A136843F0C003136070470078004092 +:102FA00037B51A4C1A4D204600F0E6FA04F1140029 +:102FB000009400234FF40072164900F0A3F94FF477 +:102FC0000072154904F138000094144B00F01CFA0B +:102FD000134BC4E91735134C204600F0CDFA04F129 +:102FE000140000234FF400720F49009400F08AF996 +:102FF0000E4B4FF400720E4904F13800009400F0BB +:1030000003FA0C4BC4E9173503B030BD6C26002021 +:1030100000E1F50544270020442B0020812F000803 +:1030200000440040D826002044290020912F0008A9 +:10303000442D002000780040037C30B5274C002947 +:1030400018BF0C46012B0CD1254B984236D1254B8D +:103050009A6C42F400329A641A6F42F400321A6792 +:103060001B6F2268036EC16D03EB52038466B3FBD2 +:10307000F2F36268150442BF23F0070503F007036B +:1030800043EA4503CB60A36843F040034B60E36829 +:1030900043F001038B6042F4967343F001030B602D +:1030A0004FF0FF330B62510505D512F0102211D0FD +:1030B000B2F1805F10D080F8643030BD0A4B984286 +:1030C000CFD1084B9A6C42F080429A641A6F42F05A +:1030D0008042C4E77F23EEE73F23ECE7806F0008E0 +:1030E0006C26002000450258D82600202DE9F04724 +:1030F000C66D05463768F469210734621AD014F0AA +:10310000080118BF4FF48071E20748BF41F0200169 +:10311000A3074FF0300348BF41F04001600748BFAC +:1031200041F0800183F31188281DFFF721FF002360 +:1031300083F31188E2050AD5302383F311884FF415 +:103140008061281DFFF714FF002383F311884FF0DF +:1031500030094FF0000A14F0200838D13B0616D58C +:103160004FF0300905F1380A200610D589F311888F +:10317000504600F07DF9002836DA0821281DFFF7B7 +:10318000F7FE27F080033360002383F3118879066C +:1031900014D5620612D5302383F31188D5E91323A1 +:1031A0009A4208D12B6C33B127F040071021281D1B +:1031B000FFF7DEFE3760002383F31188E30618D59E +:1031C000AA6E1369ABB15069BDE8F047184789F39F +:1031D0001188736A284695F86410194000F0E6F9E2 +:1031E0008AF31188F469B6E7B06288F31188F4694C +:1031F000BAE7BDE8F0870000090100F16043012251 +:1032000003F56143C9B283F8001300F01F039A402D +:1032100043099B0003F1604303F56143C3F8802138 +:103220001A60704700F01F0301229A40430900F121 +:1032300060409B0000F5614003F1604303F561438A +:10324000C3F88020C3F88021002380F80033704742 +:10325000F8B51546826804460B46AA4200D2856836 +:10326000A1692669761AB5420BD218462A46FDF79F +:10327000AFFFA3692B44A3612846A3685B1BA3602F +:10328000F8BD0CD9AF1B18463246FDF7A1FF3A46F0 +:10329000E1683044FDF79CFFE3683B44EBE71846E8 +:1032A0002A46FDF795FFE368E5E70000836893424F +:1032B000F7B50446154600D28568D4E90460361A8D +:1032C000B5420BD22A46FDF783FF63692B44636145 +:1032D0002846A3685B1BA36003B0F0BD0DD932463E +:1032E000AF1B0191FDF774FF01993A46E068314444 +:1032F000FDF76EFFE3683B44E9E72A46FDF768FF08 +:10330000E368E4E710B50A440024C361029B8460CB +:10331000C16002610362C0E90000C0E9051110BD8F +:1033200008B5D0E90532934201D1826882B982683A +:10333000013282605A1C426119700021D0E90432C6 +:103340009A4224BFC368436100F092FF002008BD89 +:103350004FF0FF30FBE7000070B5302304460E4607 +:1033600083F31188A568A5B1A368A269013BA36096 +:10337000531CA36115782269934224BFE368A361BB +:10338000E3690BB120469847002383F31188284650 +:1033900007E03146204600F05BFF0028E2DA85F3C3 +:1033A000118870BD2DE9F74F04460E461746984622 +:1033B000D0F81C904FF0300A8AF311884FF0000BC0 +:1033C000154665B12A4631462046FFF741FF0346C0 +:1033D00060B94146204600F03BFF0028F1D00023B1 +:1033E00083F31188781B03B0BDE8F08FB9F1000FAB +:1033F00003D001902046C847019B8BF31188ED1A3A +:103400001E448AF31188DCE7C160C361009B8260BF +:103410000362C0E905111144C0E900000161704771 +:10342000F8B504460D461646302383F31188A76885 +:10343000A7B1A368013BA36063695A1C62611D7058 +:10344000D4E904329A4224BFE3686361E3690BB1B3 +:1034500020469847002080F3118807E03146204637 +:1034600000F0F6FE0028E2DA87F31188F8BD0000CC +:10347000D0E9052310B59A4201D182687AB98268F1 +:103480000021013282605A1C82611C7803699A42D1 +:1034900024BFC368836100F0EBFE204610BD4FF0EF +:1034A000FF30FBE72DE9F74F04460E4617469846D6 +:1034B000D0F81C904FF0300A8AF311884FF0000BBF +:1034C000154665B12A4631462046FFF7EFFE034612 +:1034D00060B94146204600F0BBFE0028F1D0002331 +:1034E00083F31188781B03B0BDE8F08FB9F1000FAA +:1034F00003D001902046C847019B8BF31188ED1A39 +:103500001E448AF31188DCE70268436811430160B6 +:1035100003B11847704700001430FFF743BF0000A5 +:103520004FF0FF331430FFF73DBF00003830FFF796 +:10353000B9BF00004FF0FF333830FFF7B3BF0000D2 +:103540001430FFF709BF00004FF0FF311430FFF7D0 +:1035500003BF00003830FFF763BF00004FF0FF32B9 +:103560003830FFF75DBF0000012914BF6FF0130072 +:1035700000207047FFF714BD044B03600023436035 +:10358000C0E9023301230374704700BF986F00083D +:1035900010B53023044683F31188FFF74DFD022355 +:1035A0000020237480F3118810BD000038B5C36972 +:1035B00004460D461BB904210844FFF7A5FF294620 +:1035C00004F11400FFF7ACFE002806DA201D4FF4CA +:1035D0000061BDE83840FFF797BF38BD0268436817 +:1035E0001143016003B118477047000013B5406BE9 +:1035F00000F58054D4F8A4381A681178042914D13D +:10360000017C022911D11979012312898B401342BF +:103610000BD101A94C3002F0DFFCD4F8A4480246DB +:10362000019B2179206800F0DFF902B010BD000095 +:10363000143002F061BC00004FF0FF33143002F090 +:103640005BBC00004C3002F033BD00004FF0FF3394 +:103650004C3002F02DBD0000143002F02FBC0000F1 +:103660004FF0FF31143002F029BC00004C3002F062 +:10367000FFBC00004FF0FF324C3002F0F9BC0000FC +:103680000020704710B500F58054D4F8A4381A68AB +:103690001178042917D1017C022914D15979012309 +:1036A00052898B4013420ED1143002F0C1FB024606 +:1036B00048B1D4F8A4484FF4407361792068BDE85C +:1036C000104000F07FB910BD406BFFF7DBBF00007A +:1036D000704700007FB5124B0125042604460360A5 +:1036E0000023057400F1840243602946C0E90233D7 +:1036F0000C4B0290143001934FF44073009602F08B +:1037000073FB094B04F69442294604F14C000294E1 +:10371000CDE900634FF4407302F03AFC04B070BD91 +:10372000C06F0008C9360008ED3500080A6830236C +:1037300083F311880B790B3342F823004B79133351 +:1037400042F823008B7913B10B3342F8230000F5C4 +:103750008053C3F8A41802230374002080F3118857 +:103760007047000038B5037F044613B190F8543019 +:10377000ABB90125201D0221FFF730FF04F1140031 +:103780006FF00101257700F07FFD04F14C0084F813 +:1037900054506FF00101BDE8384000F075BD38BDF0 +:1037A00010B5012104460430FFF718FF00232377EA +:1037B00084F8543010BD000038B50446002514309C +:1037C00002F02AFB04F14C00257702F0F9FB201DE2 +:1037D00084F854500121FFF701FF2046BDE838402E +:1037E000FFF750BF90F8803003F06003202B06D124 +:1037F00090F881200023212A03D81F2A06D8002010 +:103800007047222AFBD1C0E91D3303E0034A426717 +:1038100007228267C3670120704700BF342300205E +:1038200037B500F58055D5F8A4381A681178042901 +:103830001AD1017C022917D11979012312898B40F1 +:10384000134211D100F14C04204602F079FC58B12A +:1038500001A9204602F0C0FBD5F8A4480246019B0E +:103860002179206800F0C0F803B030BD01F10B03EE +:10387000F0B550F8236085B004460D46FEB1302304 +:1038800083F3118804EB8507301D0821FFF7A6FE9E +:10389000FB6806F14C005B691B681BB1019002F0EC +:1038A000A9FB019803A902F097FB024648B1039BCC +:1038B0002946204600F098F8002383F3118805B0CC +:1038C000F0BDFB685A691268002AF5D01B8A013BDB +:1038D0001340F1D104F18002EAE70000133138B55A +:1038E00050F82140ECB1302383F3118804F5805364 +:1038F000D3F8A4281368527903EB8203DB689B6931 +:103900005D6845B104216018FFF768FE294604F19F +:10391000140002F097FA2046FFF7B4FE002383F369 +:10392000118838BD7047000001F06ABD01234022B4 +:10393000002110B5044600F8303BFDF77BFC002366 +:10394000C4E9013310BD000010B53023044683F3F1 +:1039500011882422416000210C30FDF76BFC2046C9 +:1039600001F070FD02230020237080F3118810BD48 +:1039700070B500EB8103054650690E461446DA60C7 +:1039800018B110220021FDF755FCA06918B11022D2 +:103990000021FDF74FFC31462846BDE8704001F09C +:1039A00051BE000083682022002103F0011310B5EE +:1039B000044683601030FDF73DFC2046BDE8104012 +:1039C00001F0CCBEF0B4012500EB810447898D40A5 +:1039D000E4683D43A469458123600023A2606360DD +:1039E000F0BC01F0E9BE0000F0B4012500EB810459 +:1039F00007898D40E4683D436469058123600023A5 +:103A0000A2606360F0BC01F05FBF000070B50223EC +:103A100000250446242203702946C0F888500C3043 +:103A200040F8045CFDF706FC204684F8705001F075 +:103A30009DFD63681B6823B129462046BDE87040A0 +:103A4000184770BD0378052B10B504460AD080F8DE +:103A50008C300523037043681B680BB10421984721 +:103A60000023A36010BD00000178052906D190F85D +:103A70008C20436802701B6803B118477047000030 +:103A800070B590F87030044613B1002380F87030A0 +:103A900004F18002204601F085FE63689B68B3B99B +:103AA00094F8803013F0600535D00021204602F0F4 +:103AB00077F90021204602F067F963681B6813B1AB +:103AC000062120469847062384F8703070BD2046B2 +:103AD00098470028E4D0B4F88630A26F9A4288BF95 +:103AE000A36794F98030A56F002B4FF0300380F26C +:103AF0000381002D00F0F280092284F8702083F306 +:103B0000118800212046D4E91D23FFF76DFF002313 +:103B100083F31188DAE794F8812003F07F0343EA06 +:103B2000022340F20232934200F0C58021D8B3F55F +:103B3000807F48D00DD8012B3FD0022B00F093801E +:103B4000002BB2D104F1880262670222A267E36708 +:103B5000C1E7B3F5817F00F09B80B3F5407FA4D12E +:103B600094F88230012BA0D1B4F8883043F00203DE +:103B700032E0B3F5006F4DD017D8B3F5A06F31D058 +:103B8000A3F5C063012B90D86368204694F8822087 +:103B90005E6894F88310B4F88430B047002884D06D +:103BA000436863670368A3671AE0B3F5106F36D004 +:103BB00040F6024293427FF478AF5C4B6367022386 +:103BC000A3670023C3E794F88230012B7FF46DAF25 +:103BD000B4F8883023F00203A4F88830C4E91D55F6 +:103BE000E56778E7B4F88030B3F5A06F0ED194F8AC +:103BF0008230204684F88A3001F016FD63681B6825 +:103C000013B1012120469847032323700023C4E900 +:103C10001D339CE704F18B0363670123C3E723781B +:103C2000042B10D1302383F311882046FFF7BAFE0E +:103C300085F311880321636884F88B5021701B6819 +:103C40000BB12046984794F88230002BDED084F8E0 +:103C50008B300423237063681B68002BD6D00221AD +:103C600020469847D2E794F8843020461D0603F09A +:103C70000F010AD501F088FD012804D002287FF445 +:103C800014AF2B4B9AE72B4B98E701F06FFDF3E74E +:103C900094F88230002B7FF408AF94F8843013F04E +:103CA0000F01B3D01A06204602D502F091F8ADE715 +:103CB00002F082F8AAE794F88230002B7FF4F5AE88 +:103CC00094F8843013F00F01A0D01B06204602D5D3 +:103CD00002F066F89AE702F057F897E7142284F8A2 +:103CE000702083F311882B462A4629462046FFF789 +:103CF00069FE85F31188E9E65DB1152284F870202C +:103D000083F3118800212046D4E91D23FFF75AFED2 +:103D1000FDE60B2284F8702083F311882B462A4697 +:103D200029462046FFF760FEE3E700BFF06F00087A +:103D3000E86F0008EC6F000838B590F87030044662 +:103D4000002B3ED0063BDAB20F2A34D80F2B32D8E4 +:103D5000DFE803F03731310822323131313131318E +:103D600031313737856FB0F886309D4214D2C36841 +:103D70001B8AB5FBF3F203FB12556DB9302383F3B5 +:103D800011882B462A462946FFF72EFE85F3118817 +:103D90000A2384F870300EE0142384F87030302346 +:103DA00083F31188002320461A461946FFF70AFEBE +:103DB000002383F3118838BDC36F03B198470023F4 +:103DC000E7E70021204601F0EBFF0021204601F04B +:103DD000DBFF63681B6813B1062120469847062362 +:103DE000D7E7000010B590F870300446142B29D0A6 +:103DF00017D8062B05D001D81BB110BD093B022BEB +:103E0000FBD80021204601F0CBFF0021204601F025 +:103E1000BBFF63681B6813B1062120469847062341 +:103E200019E0152BE9D10B2380F87030302383F390 +:103E3000118800231A461946FFF7D6FD002383F3A5 +:103E40001188DAE7C3689B695B68002BD5D1C36F23 +:103E500003B19847002384F87030CEE7FEF79CBF8B +:103E6000012100230170C0E901330C3000F01CB9BE +:103E700010B53023044683F311884160FEF79AFFA2 +:103E800002230020237080F3118810BD10B5302369 +:103E9000044683F31188032304F8083BFEF7B4FFBC +:103EA0004FF0FF31204600F0BBF9002383F3118867 +:103EB000C01A18BF012010BD38B50446302585F35F +:103EC0001188032504F8085BFEF7BAFF4FF0FF31B5 +:103ED000204600F0A5F9002383F31188C01A18BF0B +:103EE000012038BD38B50446302585F311880425F6 +:103EF00004F8085BFEF7C8FF4FF0FF31204600F0E2 +:103F00008FF9002383F31188C01A18BF012038BD30 +:103F100010B53023044683F31188FEF7DBFF062338 +:103F20002370002383F3118810BD000010B53023E7 +:103F3000044683F31188FEF7E7FF02232370002372 +:103F400083F3118810BD00000C3000F0C9B80000E8 +:103F50000C3000F0CFB800000023826803750369BD +:103F60001B6899689142FBD25A68036042601060F6 +:103F70005860704700238268037503691B6899685D +:103F80009142FBD85A6803604260106058607047E5 +:103F900008B50846302383F311880A7D0023052ADB +:103FA00006D8DFE802F00B050503120E82691360E4 +:103FB0004FF0FF338361FFF7CFFF002383F31188B6 +:103FC00008BD8269936801339360D0E900321360C1 +:103FD0005A60EDE7FFF7C0BF054BD9680875186850 +:103FE000026853601A600122D8600275FCF712BAA9 +:103FF000482F00200C4B30B5DD684B1C87B00446C1 +:104000000FD02B46094A684600F0D2F92046FFF748 +:10401000E3FF009B13B1684600F0D4F9A86907B02C +:1040200030BDFFF7D9FFF9E7482F0020913F000886 +:1040300038B50C4D04468161EB6881689A689142FD +:1040400003D8BDE83840FFF787BF1846FFF792FF57 +:1040500001230146EC6020462375BDE83840FCF79B +:10406000D9B900BF482F0020044B1A68DB6890685C +:104070009B68984294BF002001207047482F002081 +:10408000084B10B51C68D868226853601A6001227A +:10409000DC602275FFF76EFF01462046BDE8104048 +:1040A000FCF7B8B9482F0020C0E9000081607047D4 +:1040B0008368013B002B10B583600CDA074BDC688A +:1040C0004368A061206063601C6044600520FFF7C6 +:1040D00083FFA06910BD0020FCE700BF482F00202F +:1040E00008B5302383F31188FFF7E2FF002383F341 +:1040F000118808BD08B5302383F311888368013324 +:10410000002B836007DC036800211A68026050609E +:104110001846FFF78DFF002383F3118808BD0000C8 +:1041200038B50123084C00252370656002F044F87F +:1041300002F06AF80549064802F03EF902232370AE +:1041400085F3118838BD00BFB0310020F86F00083A +:10415000482F002008B572B6044B186500F080FDAA +:1041600000F05EFE024B03221A70FEE7482F00208B +:10417000B031002000F05CB9034A516853685B1A03 +:104180009842FBD8704700BF001000E08B6002230C +:10419000086108468B8270478368A3F1840243F864 +:1041A000142C026943F8442C426943F8402C094A14 +:1041B00043F8242CC268A3F1200043F8182C0222F3 +:1041C00003F80C2C002203F80B2C034A43F8102CA4 +:1041D000704700BF2D040008482F002008B5FFF7E6 +:1041E000DBFFBDE80840FFF7F5BE0000024BDB68CF +:1041F00098610F20FFF7F0BE482F0020302383F393 +:104200001188FFF7F3BF000008B50146302383F3A0 +:1042100011880820FFF7EEFE002383F3118808BD04 +:10422000054BDB6821B1036098610320FFF7E2BE14 +:104230004FF0FF30704700BF482F002003682BB1BC +:104240000022026018469961FFF7C4BE7047000063 +:10425000064BDB6839B1426818605A6013604360EE +:104260000420FFF7C7BE4FF0FF307047482F0020F3 +:104270000368984206D01A68026050601846996137 +:10428000FFF7A8BE7047000038B504460D46206809 +:10429000844200D138BD036823605C608561FFF70C +:1042A00099FEF4E7036810B59C68A2420CD85C68DC +:1042B0008A600B604C602160596099688A1A9A6024 +:1042C0004FF0FF33836010BD121B1B68ECE700004A +:1042D0000A2938BF0A2170B504460D460A2660191E +:1042E00001F064FF01F04CFF041BA54203D8751CCC +:1042F00004462E46F3E70A2E04D90120BDE870409B +:1043000002F09AB870BD0000F8B5144B0D460A2AA9 +:104310004FF00A07D96103F11001826038BF0A2209 +:10432000416019691446016048601861A81801F0DD +:104330002DFF01F025FF431B0646A34206D37C1C3C +:1043400028192746354601F031FFF2E70A2F04D934 +:104350000120BDE8F84002F06FB8F8BD482F0020FA +:10436000F8B506460D4601F00BFF0F4A134653F809 +:10437000107F9F4206D12A4601463046BDE8F840EC +:10438000FFF7C2BFD169BB68441A2C1928BF2C465D +:10439000A34202D92946FFF79BFF22463146034834 +:1043A000BDE8F840FFF77EBF482F0020582F0020BF +:1043B000C0E90323002310B45DF8044B4361FFF709 +:1043C000CFBF000010B5194C236998420DD0816809 +:1043D000D0E9003213605A609A680A449A60002358 +:1043E00003604FF0FF33A36110BD0268234643F81A +:1043F000102F53600022026022699A4203D1BDE867 +:10440000104001F0CDBE936881680B44936001F0C9 +:10441000B7FE2269E1699268441AA242E4D91144C4 +:10442000BDE81040091AFFF753BF00BF482F002016 +:104430002DE9F047DFF8BC8008F110072C4ED8F8C2 +:10444000105001F09DFED8F81C40AA68031B9A4248 +:104450003ED814444FF00009D5E90032C8F81C409A +:1044600013605A60C5F80090D8F81030B34201D1FB +:1044700001F096FE89F31188D5E903312846984763 +:10448000302383F311886B69002BD8D001F078FEBC +:104490006A69A0EB040982464A450DD2022001F068 +:1044A000CBFF0022D8F81030B34208D1514628463D +:1044B000BDE8F047FFF728BF121A2244F2E712EBDB +:1044C00009092946384638BF4A46FFF7EBFEB5E7EB +:1044D000D8F81030B34208D01444C8F81C00211A90 +:1044E000A960BDE8F047FFF7F3BEBDE8F08700BF65 +:1044F000582F0020482F002038B501F041FE054A12 +:10450000D2E90845031B181945F10001C2E9080169 +:1045100038BD00BF482F002000207047FEE7000094 +:10452000704700004FF0FF307047000002290CD0A8 +:10453000032904D00129074818BF00207047032A27 +:1045400005D8054800EBC2007047044870470020BA +:10455000704700BF6C7100084C230020D470000825 +:1045600070B59AB005460846144601A900F0FAF85D +:1045700001A8FCF757FE431C0022C6B25B001046A0 +:10458000C5E9003423700323023404F8013C01AB75 +:10459000D1B202348E4201D81AB070BD13F8011B9B +:1045A000013204F8010C04F8021CF1E708B53023CD +:1045B00083F311880448FFF733F90448FFF730F913 +:1045C000002383F3118808BDB8310020604A002021 +:1045D00090F8803003F01F02012A07D190F8812063 +:1045E0000B2A03D10023C0E91D3319E003F0600357 +:1045F000202B27D190F88430ABB990F885300BBBD5 +:1046000090F88120212A03D0222AEBD0202A19D128 +:10461000C3EBC3030C4A1344436707238367002398 +:10462000C36701207047022B0CD190F885304BB93D +:1046300090F88130212B03D0222BD3D0202B01D115 +:104640000123E5E7FFF7CEB83B23002013B505298A +:1046500027D8DFE801F02D26032D2D37302383F3F3 +:1046600011880478042C1ED11B4A01210190FFF708 +:104670007FF91A4A02210198FFF77AF9184A0321B3 +:104680000198FFF775F9174A21460198FFF770F96D +:104690001548FFF791F81548FFF78EF8002383F3CC +:1046A000118802B010BD032CF8D1FFF77BF9F5E7B4 +:1046B000302383F311880C48FFF754F80B48FFF7B9 +:1046C00051F8EBE7302383F311880748FFF768F8C8 +:1046D0000648FFF765F8E1E7247000084870000815 +:1046E0006C70000890700008B8310020604A00200B +:1046F00038B50C4D0C4C2A460C4904F10800FFF764 +:104700002FFF05F1CA0204F110000949FFF728FF45 +:1047100005F5CA7204F118000649BDE83840FFF7F4 +:104720001FBF00BF686300204C23002004700008F6 +:104730000E7000081970000870B5044608460D4652 +:10474000FCF770FDC6B22046013403780BB9184659 +:1047500070BD32462946FCF745FD0028F3D1012003 +:10476000F6E700002DE9F04705460C46FCF75AFD38 +:104770002B49C6B22846FFF7DFFF08B10736F6B26D +:1047800028492846FFF7D8FF08B11036F6B2632E45 +:104790000BD8DFF88C80DFF88C90234FDFF894A0E3 +:1047A0002E7846B92670BDE8F08729462046BDE838 +:1047B000F04702F0F7B9252E2ED1072241462846B0 +:1047C000FCF710FD70B9194B224603F10C0153F8A8 +:1047D000040B8B4242F8040BF9D11B8807350E34C9 +:1047E0001380DDE7082249462846FCF7FBFC98B910 +:1047F000A21C0F4B197802320909C95D02F8041C8A +:1048000013F8011B01F00F015345C95D02F8031CA9 +:10481000F0D118340835C3E7013504F8016BBFE760 +:104820008C71000819700008A371000894710008C9 +:1048300000E8F11F0CE8F11FBFF34F8F044B1A691A +:104840005107FCD1D3F810215207F8D1704700BFAF +:104850000020005208B50D4B1B78ABB9FFF7ECFFF9 +:104860000B4BDA68D10704D50A4A5A6002F1883244 +:104870005A60D3F80C21D20706D5064AC3F80421A2 +:1048800002F18832C3F8042108BD00BFC6650020CC +:10489000002000522301674508B5114B1B78F3B97E +:1048A000104B1A69510703D5DA6842F04002DA600A +:1048B000D3F81021520705D5D3F80C2142F040025D +:1048C000C3F80C21FFF7B8FF064BDA6842F001028B +:1048D000DA60D3F80C2142F00102C3F80C2108BDC4 +:1048E000C6650020002000520F289ABF00F58060A6 +:1048F00040040020704700004FF400307047000073 +:10490000102070470F2808B50BD8FFF7EDFF00F512 +:1049100000330268013204D104308342F9D101200E +:1049200008BD0020FCE700000F2838B505463FD839 +:10493000FFF782FF1F4CFFF78DFF4FF0FF33072873 +:104940006361C4F814311DD82361FFF775FF0302BA +:1049500043F02403E360E36843F08003E3602369EA +:104960005A07FCD42846FFF767FFFFF7BDFF4FF457 +:10497000003100F031FA2846FFF78EFFBDE83840DD +:10498000FFF7C0BFC4F81031FFF756FFA0F10803CE +:104990001B0243F02403C4F80C31D4F80C3143F06B +:1049A0008003C4F80C31D4F810315B07FBD4D9E78D +:1049B000002038BD002000522DE9F84F05460C4676 +:1049C000104645EA0203DE0602D00020BDE8F88F5B +:1049D00020F01F00DFF8BCB0DFF8BCA0FFF73AFF03 +:1049E00004EB0008444503D10120FFF755FFEDE734 +:1049F00020222946204602F0C5F810B9203520347F +:104A0000F0E72B4605F120021F68791CDDD1043345 +:104A10009A42F9D105F178431B481C4EB3F5801F2B +:104A20001B4B38BF184603F1F80332BFD946D146B5 +:104A30001E46FFF701FF0760A5EB040C336804F185 +:104A40001C0143F002033360231FD9F8007017F0F4 +:104A50000507FAD153F8042F8B424CF80320F4D108 +:104A6000BFF34F8FFFF7E8FE4FF0FF3320222146C0 +:104A700003602846336823F00203336002F082F8B3 +:104A80000028BBD03846B0E7142100520C20005259 +:104A900014200052102000521021005210B5084C72 +:104AA000237828B11BB9FFF7D5FE0123237010BD71 +:104AB000002BFCD02070BDE81040FFF7EDBE00BF1A +:104AC000C66500202DE9F04F0D4685B0814658B1EE +:104AD00011F00D0614BF2022082211F008030193E3 +:104AE00004D0431E03426AD0002435E0002E37D0A4 +:104AF00009F11F0121F01F094FF00108324F05F0A5 +:104B00000403DFF8D0A005EA080BBBF1000F32D098 +:104B10007869C0072FD408F101080C37B8F1060FE7 +:104B2000F3D19EB9294D4946A819019201F08EFB97 +:104B3000044600283AD11836019A782EF3D1494616 +:104B400001F084FB0446002830D1019A49462048F0 +:104B500001F07CFB044668BB204605B0BDE8F08F41 +:104B60000029C9D101462846029201F06FFB044694 +:104B7000E0B9029AC0E713B178694107CBD5AC0719 +:104B800002D578698007C6D5019911B17869010706 +:104B9000C1D51820494600FB08A0CDE9022301F049 +:104BA00055FB0446DDE902230028B4D04A46002123 +:104BB000204601E04A460021FCF73CFBCCE70246D8 +:104BC000002E95D198E700BFB4710008F865002069 +:104BD000C8650020E06500200021FFF773BF0000DA +:104BE0000121FFF76FBF0000F8B5144D012418270D +:104BF000134E40F2FF3200210120FCF71BFB07FBA4 +:104C0000046001342A6955F80C1F01F00BFB062CD7 +:104C1000F5D137254FF4C0542046FFF7E1FF014698 +:104C200028B122460748BDE8F84001F0FBBAC4EBC2 +:104C3000C404013D4FEAD404EED1F8BDB4710008BC +:104C4000E0650020C86500200421FFF73BBF00009D +:104C50004843FFF7C1BF000008B101F069BB7047CE +:104C600038B5054D00240334696855F80C0B00F085 +:104C7000C5F8122CF7D138BDB471000870B5AAB1CF +:104C800040EA010313F01F030FD1094C0144A5684A +:104C90006D0706D52568A84203D366683544A94246 +:104CA00004D903330C34122BF1D10022104670BD0D +:104CB000B471000838B5EFF311859DB9EFF30584A1 +:104CC000C4F30804302334B183F31188FFF714FCD4 +:104CD00085F3118838BD83F31188FFF70DFC84F349 +:104CE000118838BDBDE83840FFF706BC10B5FFF7A6 +:104CF000E1FF104CC008104A002340EA4170C90887 +:104D0000A0FB04ECA0FB020E1CEB0000A1FB044C7A +:104D1000A1FB02125B41001943EB0C0011EB0E01E9 +:104D200042F10002411842F10000090941EA007015 +:104D300010BD00BFCFF753E3A59BC4200244074B2F +:104D4000D2B210B5904200D110BD441C00B253F84D +:104D5000200041F8040BE0B2F4E700BF50400058D7 +:104D60000E4B30B51C6F240405D41C6F1C671C6FE0 +:104D700044F400441C670A4C02442368D2B243F452 +:104D800080732360074B904200D130BD441C51F822 +:104D9000045B00B243F82050E0B2F4E7004402584C +:104DA000004802585040005807B5012201A90020D0 +:104DB000FFF7C4FF019803B05DF804FB13B5044688 +:104DC000FFF7F2FFA04205D0012201A900200194C3 +:104DD000FFF7C6FF02B010BD0144BFF34F8F064B73 +:104DE000884204D3BFF34F8FBFF36F8F7047C3F870 +:104DF0005C022030F4E700BF00ED00E00144BFF3A7 +:104E00004F8F064B884204D3BFF34F8FBFF36F8F92 +:104E10007047C3F870022030F4E700BF00ED00E0F7 +:104E200070470000114BDA6952021ED59A69D0070B +:104E300004D50F4A9A6002F144329A600B4BDA694A +:104E4000D107FCD41A6A22F480021A629A6942F0ED +:104E500002029A61DA69D207FCD49A6942F001022F +:104E60009A61024AD369DB07FCD4704700200052E4 +:104E70003B2A190870B5054616460C46012010213C +:104E8000FFF7E6FE286046733CB1204636B1FFF7D7 +:104E9000DBFE2B68186000B19C6070BDFFF7A0FEC0 +:104EA000F7E70000F8B50F461546044648B905F186 +:104EB0001F010126386821F01F01FFF78DFF3046E2 +:104EC000F8BD427B29463868FFF7D8FE0646002821 +:104ED000EDD13B686360A368AB4210D213B1206888 +:104EE000FFF7BAFE637B28462BB1FFF7ADFE2060CB +:104EF00020B9A060E3E7FFF773FEF8E7A56020683C +:104F000005F11F01012621F01F013860FFF764FF42 +:104F10002673D4E710B5044640B10068884205D135 +:104F2000606808B1FCF754F90023237310BD00003A +:104F3000F8B50F461446054648B904F11F0101268D +:104F4000386821F01F01FFF759FF3046F8BD427B5A +:104F500021463868FFF792FE06460028EDD1AB687F +:104F6000A34210D213B12868FFF776FE6B7B204670 +:104F70002BB1FFF769FE286020B9A860E5E7FFF7CD +:104F80002FFEF8E7AC60396819B122462868FCF7B3 +:104F90001FF9286804F11F01012621F01F01386064 +:104FA000FFF72CFF2E73D0E720B103688B4204BFBC +:104FB000002303737047000008B100230373704798 +:104FC000034B1A681AB9034AD2F8D0241A60704702 +:104FD000706600200040025808B5FFF7F1FF024B51 +:104FE0001868C0F3806008BD70660020EFF3098385 +:104FF000054968334A6B22F001024A6383F309884A +:10500000002383F31188704700EF00E0302080F325 +:10501000118862B60D4B0E4AD96821F4E06109048B +:10502000090C0A430B49DA60D3F8FC2042F0807285 +:10503000C3F8FC20084AC2F8B01F116841F0010112 +:1050400011602022DA7783F82200704700ED00E03B +:105050000003FA0555CEACC5001000E0302310B5B2 +:1050600083F311880E4B5B6813F4006314D0F1EEE8 +:10507000103AEFF309844FF08073683CE361094B09 +:10508000DB6B236684F30988FEF7EEFF10B1064B55 +:10509000A36110BD054BFBE783F31188F9E700BF5F +:1050A00000ED00E000EF00E03F04000842040008CB +:1050B00070B5BFF34F8FBFF36F8F1A4A0021C2F84C +:1050C0005012BFF34F8FBFF36F8F536943F4003318 +:1050D0005361BFF34F8FBFF36F8FC2F88410BFF3DC +:1050E0004F8FD2F8803043F6E074C3F3C900C3F3A6 +:1050F0004E335B0103EA0406014646EA8175013935 +:10510000C2F86052F9D2203B13F1200FF2D1BFF365 +:105110004F8F536943F480335361BFF34F8FBFF315 +:105120006F8F70BD00ED00E0FEE70000214B2248CC +:10513000224A70B5904237D3214BC11EDA1C121A95 +:1051400022F003028B4238BF00220021FCF772F8E4 +:105150001C4A0023C2F88430BFF34F8FD2F880304E +:1051600043F6E074C3F3C900C3F34E335B0103EAB3 +:105170000406014646EA81750139C2F86C52F9D23B +:10518000203B13F1200FF2D1BFF34F8FBFF36F8F8E +:10519000BFF34F8FBFF36F8F0023C2F85032BFF3BE +:1051A0004F8FBFF36F8F70BD53F8041B40F8041B83 +:1051B000C0E700BF24740008286900202869002087 +:1051C0002869002000ED00E003681A6899685A60B9 +:1051D00043681BB142EA01418068184770470000EC +:1051E0004FF0A44310B51C68E00702D52848FFF72C +:1051F000EBFFA10702D52748FFF7E6FF620702D5BC +:105200002548FFF7E1FF230702D52448FFF7DCFF1D +:10521000E00602D52248FFF7D7FFA10602D52148B4 +:10522000FFF7D2FF620602D51F48FFF7CDFF230626 +:1052300002D51E48FFF7C8FFE00502D51C48FFF75E +:10524000C3FFA10502D51B48FFF7BEFF620502D5CB +:105250001948FFF7B9FF230502D51848FFF7B4FF37 +:10526000E00402D51648FFF7AFFFA10402D51548A8 +:10527000FFF7AAFF620402D51348FFF7A5FF230436 +:1052800002D51248FFF7A0FFBDE81040FFF7E6BEC9 +:105290007866002084660020906600209C660020CE +:1052A000A8660020B4660020C0660020CC660020FE +:1052B000D8660020E4660020F0660020FC6600202E +:1052C0000867002014670020206700202C6700205A +:1052D00030B5094B0021094C10200725196054F8FE +:1052E000042B0138C3E90121D16003F10C031161E2 +:1052F0005560F4D130BD00BF74660020FC71000819 +:105300000F28F0B50AD9102806D10F230020114C20 +:1053100001272568984203D9002018E00346F6E7E4 +:1053200007FA00F6354213D10C2335434343256079 +:10533000181D2344C3E90212074B20445A6B42F064 +:1053400001025A63DA6D42F00102DA65DB6DF0BDED +:105350000130DFE774660020004502580368D96811 +:10536000DA68C90722F03F02DA6002D51A689207AC +:10537000FCD507225A607047054B996B21EA000162 +:1053800099631A6E22EA00021A661B6E704700BF0C +:105390000045025870B5D0E9244300224FF0FF3594 +:1053A0009E6804EB42135101D3F80009002805DA86 +:1053B000D3F8000940F08040C3F80009D3F8000B8F +:1053C000002805DAD3F8000B40F08040C3F8000B4A +:1053D000013263189642C3F80859C3F8085BE0D25B +:1053E0004FF00113C4F81C3870BD0000890141F072 +:1053F0002001016103699B06FCD41220FEF7BCBEAC +:1054000010B50A4C2046FEF791FA094BC4F89030CB +:10541000084BC4F89430084C2046FEF787FA074B37 +:10542000C4F89030064BC4F8943010BD38670020A3 +:105430000000084060720008D467002000000440AB +:105440006C72000870B503780546012B58D13F4BAC +:10545000D0F89040984254D13D4B0E2165209A6B74 +:1054600042F000629A631A6E42F000621A661B6E86 +:10547000384BD3F8802042F00062C3F88020D3F884 +:10548000802022F00062C3F88020D3F88030FDF73E +:10549000B3FE314BE360314BC4F800380023D5F83C +:1054A0009060C4F8003EC02323604FF40413A3634C +:1054B0003369002BFCDA01230C203361FEF75CFE1C +:1054C0003369DB07FCD41220FEF756FE3369002B4C +:1054D000FCDA00262846A660FFF75CFF6B68C4F87C +:1054E0001068DB68C4F81468C4F81C6863BB1C4B04 +:1054F000A3614FF0FF336361A36843F00103A3602E +:1055000070BD184B9842C9D1114B4FF080609A6B17 +:1055100042F000729A631A6E42F000721A661B6EB5 +:105520000C4BD3F8802042F00072C3F88020D3F8EF +:10553000802022F00072C3F88020D3F88030FFF77B +:105540001BFF0E214D20A2E7074BD1E73867002053 +:105550000045025800440258401400400300200255 +:10556000003C30C0D4670020083C30C0F8B5D0F80B +:105570009040054600214FF000662046FFF736FFB9 +:10558000D5F8941000234FF001128F684FF0FF30D0 +:10559000C4F83438C4F81C2804EB431201339F428A +:1055A000C2F80069C2F8006BC2F80809C2F8080B1B +:1055B000F2D20B68D5F89020C5F8983063621023BA +:1055C0001361166916F01006FBD11220FEF7D4FD08 +:1055D000D4F8003823F4FE63C4F80038A36943F418 +:1055E000402343F01003A3610923C4F81038C4F822 +:1055F00014380B4BEB604FF0C043C4F8103B094B21 +:10560000C4F8003BC4F81069C4F80039D5F89830E4 +:1056100003F1100243F48013C5F89820A362F8BD8B +:105620003C72000840800010D0F8902090F88A105A +:10563000D2F8003823F4FE6343EA0113C2F80038BD +:10564000704700002DE9F84300EB8103D0F890503B +:105650000C468046DA680FFA81F94801166806F0B0 +:105660000306731E022B05EB41134FF0000194BF9C +:10567000B604384EC3F8101B4FF0010104F11003BB +:1056800098BF06F1805601FA03F3916998BF06F5B9 +:10569000004600293AD0578A04F15801374349019E +:1056A0006F50D5F81C180B430021C5F81C382B1877 +:1056B0000127C3F81019A7405369611E9BB3138AD1 +:1056C000928B9B08012A88BF5343D8F898209818DA +:1056D00042EA034301F140022146C8F898002846F7 +:1056E00005EB82025360FFF781FE08EB8900C36877 +:1056F0001B8A43EA845348341E4364012E51D5F873 +:105700001C381F43C5F81C78BDE8F88305EB491722 +:10571000D7F8001B21F40041C7F8001BD5F81C186E +:1057200021EA0303C0E704F13F030B4A2846214660 +:1057300005EB83035A60FFF759FE05EB4910D0F8DB +:10574000003923F40043C0F80039D5F81C3823EAA7 +:105750000707D7E70080001000040002D0F894206B +:105760001268C0F89820FFF715BE00005831D0F835 +:10577000903049015B5813F4004004D013F4001F2B +:105780000CBF0220012070474831D0F89030490109 +:105790005B5813F4004004D013F4001F0CBF022028 +:1057A0000120704700EB8101CB68196A0B68136018 +:1057B0004B6853607047000000EB810330B5DD6833 +:1057C000AA691368D36019B9402B84BF40231360C2 +:1057D0006B8A1468D0F890201C4402EB4110013C05 +:1057E00009B2B4FBF3F46343033323F0030343EA46 +:1057F000C44343F0C043C0F8103B2B6803F00303DD +:10580000012B0ED1D2F8083802EB411013F4807F3F +:10581000D0F8003B14BF43F0805343F00053C0F86E +:10582000003B02EB4112D2F8003B43F00443C2F8C4 +:10583000003B30BD2DE9F041D0F8906005460C46A4 +:1058400006EB4113D3F8087B3A07C3F8087B08D569 +:10585000D6F814381B0704D500EB8103DB685B68BE +:105860009847FA071FD5D6F81438DB071BD505EB88 +:105870008403D968CCB98B69488A5A68B2FBF0F6C0 +:1058800000FB16228AB91868DA6890420DD2121A03 +:10589000C3E90024302383F3118821462846FFF70B +:1058A0008BFF84F31188BDE8F081012303FA04F231 +:1058B0006B8923EA02036B81CB68002BF3D021466E +:1058C0002846BDE8F041184700EB81034A0170B556 +:1058D000DD68D0F890306C692668E66056BB1A44E3 +:1058E0004FF40020C2F810092A6802F00302012ACE +:1058F0000AB20ED1D3F8080803EB421410F4807FEB +:10590000D4F8000914BF40F0805040F00050C4F8B3 +:10591000000903EB4212D2F8000940F00440C2F83B +:1059200000090122D3F8340802FA01F10143C3F857 +:10593000341870BD19B9402E84BF40202060206803 +:105940001A442E8A8419013CB4FBF6F440EAC440A0 +:1059500040F00050C6E700002DE9F843D0F8906011 +:1059600005460C464F0106EB4113D3F8088918F0A1 +:10597000010FC3F808891CD0D6F81038DB0718D5FA +:1059800000EB8103D3F80CC0DCF81430D3F800E04E +:10599000DA68964530D2A2EB0E024FF000091A6089 +:1059A000C3F80490302383F31188FFF78DFF89F348 +:1059B000118818F0800F1DD0D6F834380126A64083 +:1059C000334217D005EB84030134D5F89050D3F857 +:1059D0000CC0E4B22F44DCF8142005EB0434D2F8F8 +:1059E00000E05168714514D3D5F8343823EA06062F +:1059F000C5F83468BDE8F883012303FA01F203898E +:105A000023EA02030381DCF80830002BD1D0984749 +:105A1000CFE7AEEB0103BCF81000834228BF03467A +:105A2000D7F8180980B2B3EB800FE3D89068A0F1E3 +:105A3000040959F8048FC4F80080A0EB09089844C1 +:105A4000B8F1040FF5D818440B4490605360C8E7D0 +:105A50002DE9F84FD0F8905004466E69AB691E40AE +:105A600016F480586E6103D0BDE8F84FFDF7CEBF45 +:105A7000002E12DAD5F8003E9B0705D0D5F8003E7F +:105A800023F00303C5F8003ED5F80438204623F080 +:105A90000103C5F80438FDF7E7FF370505D52046B3 +:105AA000FFF778FC2046FDF7CDFFB0040CD5D5F804 +:105AB000083813F0060FEB6823F470530CBF43F45F +:105AC000105343F4A053EB6031071BD56368DB68C8 +:105AD0001BB9AB6923F00803AB612378052B0CD10C +:105AE000D5F8003E9A0705D0D5F8003E23F0030311 +:105AF000C5F8003E2046FDF7B7FF6368DB680BB1D1 +:105B000020469847F30200F1BA80B70226D5D4F8B0 +:105B1000909000274FF0010A09EB4712D2F8003BA2 +:105B200003F44023B3F5802F11D1D2F8003B002BB2 +:105B30000DDA62890AFA07F322EA0303638104EBB0 +:105B40008703DB68DB6813B1394620469847013785 +:105B5000D4F89430FFB29B689F42DDD9F00619D586 +:105B6000D4F89000026AC2F30A1702F00F0302F49D +:105B7000F012B2F5802F00F0CA80B2F5402F09D1A3 +:105B800004EB8303002200F58050DB681B6A974218 +:105B900040F0B0803003D5F8185835D5E90303D567 +:105BA00000212046FFF746FEAA0303D50121204627 +:105BB000FFF740FE6B0303D502212046FFF73AFEB4 +:105BC0002F0303D503212046FFF734FEE80203D557 +:105BD00004212046FFF72EFEA90203D50521204609 +:105BE000FFF728FE6A0203D506212046FFF722FEB2 +:105BF0002B0203D507212046FFF71CFEEF0103D53A +:105C000008212046FFF716FE700340F1A780E90740 +:105C100003D500212046FFF79FFEAA0703D50121E7 +:105C20002046FFF799FE6B0703D502212046FFF7B8 +:105C300093FE2F0703D503212046FFF78DFEEE06C6 +:105C400003D504212046FFF787FEA80603D50521CA +:105C50002046FFF781FE690603D506212046FFF79F +:105C60007BFE2A0603D507212046FFF775FEEB05CC +:105C700074D520460821BDE8F84FFFF76DBED4F873 +:105C800090904FF0000B4FF0010AD4F894305FFA77 +:105C90008BF79B689F423FF638AF09EB4713D3F869 +:105CA000002902F44022B2F5802F20D1D3F8002938 +:105CB000002A1CDAD3F8002942F09042C3F80029E8 +:105CC000D3F80029002AFBDB3946D4F89000FFF70F +:105CD0008DFB22890AFA07F322EA0303238104EBEE +:105CE0008703DB689B6813B13946204698470BF160 +:105CF000010BCAE7910701D1D0F80080072A02F111 +:105D000001029CBF03F8018B4FEA18283FE704EB20 +:105D1000830300F58050DA68D2F818C0DCF8082058 +:105D2000DCE9001CA1EB0C0C00218F4208D1DB68E0 +:105D30009B699A683A449A605A683A445A6029E7DB +:105D400011F0030F01D1D0F800808C4501F1010161 +:105D500084BF02F8018B4FEA1828E6E7BDE8F88F08 +:105D600008B50348FFF774FEBDE80840FFF776B9B1 +:105D70003867002008B50348FFF76AFEBDE8084011 +:105D8000FFF76CB9D4670020D0F8903003EB4111D5 +:105D9000D1F8003B43F40013C1F8003B704700000A +:105DA000D0F8903003EB4111D1F8003943F40013DF +:105DB000C1F8003970470000D0F8903003EB411172 +:105DC000D1F8003B23F40013C1F8003B70470000FA +:105DD000D0F8903003EB4111D1F8003923F40013CF +:105DE000C1F800397047000030B50433039C0172DC +:105DF000002104FB0325C160C0E90653049B036333 +:105E0000059BC0E90000C0E90422C0E90842C0E9DE +:105E10000A11436330BD00000022416AC260C0E93C +:105E20000411C0E90A226FF00101FEF72DBA00004B +:105E3000D0E90432934201D1C2680AB9181D7047F3 +:105E400000207047036919600021C2680132C260F6 +:105E5000C269134482699342036124BF436A0361A8 +:105E6000FEF706BA38B504460D46E3683BB16269F1 +:105E70000020131D1268A3621344E36207E0237A33 +:105E800033B929462046FEF7E3F90028EDDA38BD9C +:105E90006FF00100FBE70000C368C269013BC3600B +:105EA0004369134482699342436124BF436A436157 +:105EB00000238362036B03B11847704770B530232A +:105EC000044683F31188866A3EB9FFF7CBFF054687 +:105ED00018B186F31188284670BDA36AE26A13F8E8 +:105EE000015B9342A36202D32046FFF7D5FF002354 +:105EF00083F31188EFE700002DE9F84F04460E46C2 +:105F0000174698464FF0300989F311880025AA46B4 +:105F1000D4F828B0BBF1000F09D141462046FFF765 +:105F2000A1FF20B18BF311882846BDE8F88FD4E992 +:105F30000A12A7EB050B521A934528BF9346BBF1F3 +:105F4000400F1BD9334601F1400251F8040B914236 +:105F500043F8040BF9D1A36A403640354033A362BD +:105F6000D4E90A239A4202D32046FFF795FF8AF329 +:105F70001188BD42D8D289F31188C9E730465A4604 +:105F8000FBF726F9A36A5E445D445B44A362E7E73E +:105F900010B5029C0433017203FB0421C460C0E904 +:105FA00006130023C0E90A33039B0363049BC0E983 +:105FB0000000C0E90422C0E90842436310BD0000AC +:105FC000026A6FF00101C260426AC0E90422002245 +:105FD000C0E90A22FEF758B9D0E904239A4201D158 +:105FE000C26822B9184650F8043B0B607047002382 +:105FF0001846FAE7C3680021C2690133C3604369E8 +:10600000134482699342436124BF436A4361FEF7AC +:106010002FB9000038B504460D46E3683BB123694B +:1060200000201A1DA262E2691344E36207E0237AAA +:1060300033B929462046FEF70BF90028EDDA38BDC2 +:106040006FF00100FBE7000003691960C268013AC4 +:10605000C260C269134482699342036124BF436AE8 +:10606000036100238362036B03B11847704700008C +:1060700070B530230D460446114683F31188866AB5 +:106080002EB9FFF7C7FF10B186F3118870BDA36A60 +:106090001D70A36AE26A01339342A36204D3E169EB +:1060A00020460439FFF7D0FF002080F31188EDE788 +:1060B0002DE9F84F04460D46904699464FF0300AB8 +:1060C0008AF311880026B346A76A4FB9494620468D +:1060D000FFF7A0FF20B187F311883046BDE8F88FA5 +:1060E000D4E90A073A1AA8EB0607974228BF1746D1 +:1060F000402F1BD905F1400355F8042B9D4240F871 +:10610000042BF9D1A36A40364033A362D4E90A23B1 +:106110009A4204D3E16920460439FFF795FF8BF3D7 +:1061200011884645D9D28AF31188CDE729463A46E7 +:10613000FBF74EF8A36A3D443E443B44A362E5E7C7 +:10614000D0E904239A4217D1C3689BB1836A8BB10B +:10615000043B9B1A0ED01360C368013BC360C36944 +:106160001A4483699A42026124BF436A036100238F +:1061700083620123184670470023FBE700F00EBA44 +:10618000014B586A704700BF000C0040034B0022CF +:1061900058631A610222DA60704700BF000C0040A9 +:1061A000014B0022DA607047000C0040014B58633D +:1061B000704700BF000C0040024B034A1A60034ABC +:1061C0005A6070478868002028690020000002207B +:1061D000074B494210B55C68201A08401968821ABA +:1061E0008A4203D3A24201D85A6010BD0020FCE7C6 +:1061F0008868002008B5302383F31188FFF7E8FF93 +:10620000002383F3118808BD04480121044B036077 +:106210000023C0E901330C30FDF746BF9068002031 +:10622000F5610008CB1D083A23F00703591A521AEA +:10623000012110B4D2080024C0E9004384600C306E +:106240001C605A605DF8044BFDF72EBF2DE9F84F36 +:10625000364ECD1D0F46002818BF0646082A4FEAC5 +:10626000D50538BF082206F10C08341D914640467A +:10627000FDF736FF09F10701C9F1000E2246246837 +:106280006CB94046FDF736FF3368CBB30822494668 +:10629000E8009847044698B340E9026730E004EB11 +:1062A000010CD4F804A00CEA0E0C0AF10100ACF1C8 +:1062B000080304EBC0009842E0D9A0EB0C0CB5EB4E +:1062C000EC0F4FEAEC0BD9D89C421CD204F1080227 +:1062D000AB45A3EB02024FEAE202626009D9691CF6 +:1062E000ED43206803EBC1025D44556043F8310083 +:1062F00022601C465F60404644F8086BFDF7FAFEDA +:106300002046BDE8F88FAA45216802D111602346D6 +:10631000EFE7013504EBC50344F8351003F108013C +:10632000401AC01058601360F1E700BF9068002069 +:10633000F8B550F8043C044650F8085CA0F1080693 +:1063400007332F1D0C35DB0840F8043C2846FDF7C9 +:10635000C7FE3B469F421A6801D0B34228D20AB119 +:10636000964225D244F8082C54F8042C1E600132C1 +:1063700054F8081C06EBC200814206D1486802446A +:1063800044F8042C0A6844F8082C5868411C03EBB4 +:10639000C1018E4207D154F8042C013202445A60E4 +:1063A00054F8082C1A602846BDE8F840FDF7A2BE54 +:1063B0001346CFE7FEE7000070B51B4B00250446EF +:1063C00086B058600E4685620163FEF71FFE04F139 +:1063D0001003A560E562C4E904334FF0FF33C4E95C +:1063E0000044C4E90635FFF7CBFE2B46024604F114 +:1063F00034012046C4E9082380230C4A2565FDF7B3 +:10640000C5FE01230A4AE06000920375684672687F +:106410000192B268CDE90223064BCDE90435FDF7C0 +:10642000DDFE06B070BD00BFB031002078720008FC +:106430007D720008B5630008024AD36A1843D0622F +:10644000704700BF482F00204B6843608B68836013 +:10645000CB68C3600B6943614B6903628B6943621C +:106460000B6803607047000008B5344B40F2FF70C2 +:10647000196C014319649A6E024331489A66314A95 +:106480009B6E1146FFF7E0FF00F5806002F11C01F2 +:10649000FFF7DAFF00F5806002F13801FFF7D4FF63 +:1064A00000F5806002F15401FFF7CEFF00F5806037 +:1064B00002F17001FFF7C8FF00F5806002F18C0166 +:1064C000FFF7C2FF00F5806002F1A801FFF7BCFFF3 +:1064D00000F5806002F1C401FFF7B6FF00F58060AF +:1064E00002F1E001FFF7B0FF00F5806002F1FC016E +:1064F000FFF7AAFF02F58C7100F58060FFF7A4FF9B +:1065000000F010F9104BD3F8902242F00102C3F8CA +:106510009022D3F8942242F00102C3F8942205227B +:10652000C3F898204FF06052C3F89C20074AC3F884 +:10653000A020BDE80840FEF775BC00BF004502582A +:10654000000002588472000800ED00E01F000803FC +:1065500008B500F0E1FAFDF7E3FD0D4BDA6B42F010 +:106560004002DA635A6E22F040025A665B6E094BB3 +:106570001A6842F008021A601A6842F004021A60AF +:10658000FEF71EFDFEF730FBBDE80840FEF7B0B891 +:106590000045025800180248704700000E4B9A6CE4 +:1065A00042F008029A641A6F42F008021A670B4A16 +:1065B0001B6FD36B43F00803D363C722084B9A6267 +:1065C0004FF0FF32DA6200229A615A63DA605A6051 +:1065D00001225A611A607047004502580010005CA1 +:1065E000000C0040094A08B51169D3680B40D9B2C4 +:1065F0009B076FEA0101116107D5302383F31188EE +:10660000FDF7B8FD002383F3118808BD000C00409E +:10661000044BDA6B0243DA635A6E104358665B6EC2 +:10662000704700BF0045025808B53D4B4FF0FF31A1 +:10663000D3F8802062F00042C3F88020D3F8802095 +:1066400002F00042C3F88020D3F88020D3F88420E1 +:10665000C3F88410D3F884200022C3F88420D3F830 +:106660008400D86F40F0FF4040F4FF0040F4DF406A +:1066700040F07F00D867D86F20F0FF4020F4FF0083 +:1066800020F4DF4020F07F00D867D86FD3F888006F +:106690006FEA40506FEA5050C3F88800D3F8880082 +:1066A000C0F30A00C3F88800D3F88800D3F890003C +:1066B000C3F89010D3F89000C3F89020D3F890005E +:1066C000D3F89400C3F89410D3F89400C3F894203E +:1066D000D3F89400D3F89800C3F89810D3F8980032 +:1066E000C3F89820D3F89800D3F88C00C3F88C1026 +:1066F000D3F88C00C3F88C20D3F88C00D3F89C001E +:10670000C3F89C10D3F89C10C3F89C20D3F89C309D +:10671000FCF74EFAFEF7DCFDBDE8084000F0C8B912 +:106720000044025808B50122504BC3F80821504BD1 +:106730005A6D42F002025A65DA6F42F00202DA67DD +:106740000422DB6F4B4BDA605A689104FCD54A4A4D +:106750001A6001229A60494ADA6000221A614FF4F5 +:1067600040429A61434B9A699204FCD51A6842F4FC +:1067700080721A60424B1A6F12F4407F04D04FF4BB +:1067800080321A6700221A671A6842F001021A6002 +:106790003B4B1A685007FCD500221A611A6912F0A7 +:1067A0003802FBD1012119604FF0804159605A67CE +:1067B000344ADA62344A1A611A6842F480321A6042 +:1067C0002F4B1A689103FCD51A6842F480521A6064 +:1067D0001A689204FCD52D4A2D499A6200225A6308 +:1067E000196301F57C01DA6301F5E77199635A6475 +:1067F000284A1A64284ADA621A6842F0A8521A60D3 +:106800001F4B1A6802F02852B2F1285FF9D14822D2 +:106810009A614FF48862DA6140221A621F4ADA6490 +:106820001F4A1A651F4A5A651F4A9A6532231F4A32 +:106830001360136803F00F03022BFAD1104A136997 +:1068400043F003031361136903F03803182BFAD1E3 +:106850004FF00050FFF7DCFE4FF08040FFF7D8FE0E +:106860004FF00040BDE80840FFF7D2BE0080005165 +:10687000004502580048025800C000F00400000122 +:10688000004402580000FF01008890083220600098 +:1068900063020901470E0508DD0BBF01200000203F +:1068A000000001100910E00000010110002000525A +:1068B0004FF0B04208B5D2F8883003F00103C2F8B7 +:1068C000883023B1044A13680BB150689847BDE87B +:1068D0000840FEF7C3BB00BFA86800204FF0B042DD +:1068E00008B5D2F8883003F00203C2F8883023B12B +:1068F000044A93680BB1D0689847BDE80840FEF79A +:10690000ADBB00BFA86800204FF0B04208B5D2F878 +:10691000883003F00403C2F8883023B1044A1369B5 +:106920000BB150699847BDE80840FEF797BB00BF20 +:10693000A86800204FF0B04208B5D2F8883003F0C4 +:106940000803C2F8883023B1044A93690BB1D069B7 +:106950009847BDE80840FEF781BB00BFA86800204B +:106960004FF0B04208B5D2F8883003F01003C2F8F7 +:10697000883023B1044A136A0BB1506A9847BDE8C6 +:106980000840FEF76BBB00BFA86800204FF0B04383 +:1069900010B5D3F8884004F47872C3F88820A306B1 +:1069A00004D5124A936A0BB1D06A9847600604D5A1 +:1069B0000E4A136B0BB1506B9847210604D50B4A56 +:1069C000936B0BB1D06B9847E20504D5074A136C63 +:1069D0000BB1506C9847A30504D5044A936C0BB1D6 +:1069E000D06C9847BDE81040FEF738BBA86800207F +:1069F0004FF0B04310B5D3F8884004F47C42C3F89C +:106A00008820620504D5164A136D0BB1506D984766 +:106A1000230504D5124A936D0BB1D06D9847E0045D +:106A200004D50F4A136E0BB1506E9847A10404D5DC +:106A30000B4A936E0BB1D06E9847620404D5084A96 +:106A4000136F0BB1506F9847230404D5044A936F1A +:106A50000BB1D06F9847BDE81040FEF7FFBA00BFFA +:106A6000A868002008B50348FCF75CFABDE80840B8 +:106A7000FEF7F4BA4C26002008B50348FCF736FBB5 +:106A8000BDE80840FEF7EABA6C26002008B50348C6 +:106A9000FCF72CFBBDE80840FEF7E0BAD826002042 +:106AA00008B5FFF79FFDBDE80840FEF7D7BA000024 +:106AB000062108B50846FCF79FFB06210720FCF7D6 +:106AC0009BFB06210820FCF797FB06210920FCF719 +:106AD00093FB06210A20FCF78FFB06211720FCF709 +:106AE0008BFB06212820FCF787FB09217A20FCF785 +:106AF00083FB0A215C20FCF77FFB07213220FCF797 +:106B00007BFB0C212620FCF777FB0C215220BDE8F3 +:106B10000840FCF771BB000008B5FFF785FD00F0E9 +:106B20000FF8FCF727FDFCF7FFFEFCF7D1FDFDF7A2 +:106B300095F9FFF731FDBDE80840FFF71FBB0000E6 +:106B40000023054A19460133102BC2E9001102F156 +:106B50000802F8D1704700BFA86800200B46014624 +:106B6000184600F001B8000010B5054C13462CB1D2 +:106B70000A4601460220AFF3008010BD2046FCE724 +:106B80000000000010B501390244904201D10020FC +:106B900005E0037811F8014FA34201D0181B10BD86 +:106BA0000130F2E7034611F8012B03F8012B002A0C +:106BB000F9D1704700000000010000000001000151 +:106BC0000000000000000000000000005265717528 +:106BD000657374656420746F206572617365206DE0 +:106BE0006F7265207468616E2077652063616E0A3C +:106BF00000457261736520436F6D6D616E64205254 +:106C0000656365697665640A0050435420444F4EBD +:106C1000453A2025640A000053544D333248373F2B +:106C20003F3F0053544D3332483733782F37327853 +:106C30000053544D3332483734332F3735332F37E1 +:106C40003530000001105A0003105900012058008F +:106C50000320560053464450000000004A45444576 +:106C6000433A204661696C656420746F20646574E2 +:106C700065637420666C617368206465766963651A +:106C80003A2025730A004A454445433A2046616943 +:106C90006C656420746F20636F6E66696720666C34 +:106CA000617368206465766963653A2025730A001C +:106CB0004A454445433A20446574656374656420DD +:106CC000466C617368204465766963653A20257374 +:106CD0000A0045787420466C617368204E6F7420FA +:106CE000466F756E642100006D7432357100773225 +:106CF000357100773235712D64747200E86C0008CC +:106D000020BA000000000000EE6C0008EF40000018 +:106D100000000000F36C0008EF70000000000000AD +:106D20000000000000000000091C0008711E00089F +:106D30002515000829150008D1150008D91D0008DF +:106D40002D15000831150008D11C0008A1150008F8 +:106D5000311D0008151A00083915000835150008FE +:106D6000091F00089915000800000000000000003D +:106D7000000000000000000001200008452300087A +:106D80004523000805200008092000080D20000800 +:106D9000112000084523000845230008452300086A +:106DA000292000082D200008452000084D2000085B +:106DB000592000085D200008612000084C260020B2 +:106DC0000100000000000000000000009921000800 +:106DD000B1210008012000086D200008E52100080D +:106DE000A12000087D220008AD2200081120000823 +:106DF0008520000871200008812000082920000853 +:106E00002D200008452000084D20000859200008CA +:106E10005D200008612000088920000800000000B3 +:106E20000000000019210008652000086920000802 +:106E30000000000000000000252400082D240008A8 +:106E400011240008192400083D24000841240008EA +:106E5000286E756C6C29000000000000C128000835 +:106E6000992800084928000865280008812800089A +:106E700010000240080002400008024000000B0021 +:106E800028000240080002400408024006010C00ED +:106E900040000240080002400808024010020D00B5 +:106EA00058000240080002400C08024016030E0081 +:106EB000700002400C0002401008024000040F0065 +:106EC000880002400C000240140802400605100031 +:106ED000A00002400C0002401808024010061100F9 +:106EE000B80002400C0002401C08024016072F00A8 +:106EF0001004024008040240200802400008380044 +:106F0000280402400804024024080240060939000F +:106F1000400402400804024028080240100A3A00D7 +:106F200058040240080402402C080240160B3B00A3 +:106F3000700402400C04024030080240000C3C0087 +:106F4000880402400C04024034080240060D44004C +:106F5000A00402400C04024038080240100E450014 +:106F6000B80402400C0402403C080240160F4600E0 +:106F70004D444D41206661696C75726500000000EA +:106F8000009600000000000000000000000000006B +:106F9000000000000000000000000000353500087F +:106FA000213500085D3500084935000855350008D1 +:106FB000413500082D3500081935000869350008ED +:106FC000000000004D36000839360008753600080C +:106FD000613600086D36000859360008453600084D +:106FE0003136000881360008000000000100000072 +:106FF0000000000063300000F46F0008A02F0020A4 +:10700000B03100204375626550696C6F7400437540 +:1070100062655265642D424C002553455249414CEE +:1070200025000000030000000000000025390008D2 +:1070300000000000100000000863002000000000B5 +:10704000010000000000000002000000000000003D +:107050006D380008DD38000840004000186300204B +:107060002863002002000000000000000300000070 +:10707000000000002539000800000000100000009A +:107080003863002000000000010000000000000044 +:1070900002000000000000006D380008DD38000824 +:1070A00040004000486300205863002002000000B8 +:1070B000000000003867002002020100386700204D +:1070C000040403004D4600082D450008D145000882 +:1070D000AD4500088D000000DC70000809028D003D +:1070E000040100C032080B00020202010009040082 +:1070F0000001020201000524001001052401030122 +:107100000424020205240600010705810310000182 +:1071100009040100020A0000000705020240000005 +:1071200007058202400000080B020202020100096A +:1071300004020001020201000524001001052401DF +:107140000303042402020524060203070583031037 +:10715000000109040300020A0000000705040240C0 +:10716000000007058402400000000000120000003B +:107170007471000812010002EF020140AE2D591097 +:1071800000020102030100000403090425424F41EB +:1071900052442500437562655265645072696D61A1 +:1071A0007279003031323334353637383941424321 +:1071B000444546000001002000FF010002000000DD +:1071C000000000300000040008000000000000245F +:1071D00000000800040000000004000000FC0000A3 +:1071E00002000000000004300080000008000000E1 +:1071F00000000038000001000100000040000052C3 +:1072000080000052C00000520001005240010052B4 +:1072100080010052C00100520002005240020052A0 +:1072200080020052C002005200030052400300528C +:1072300080030052C003005200040052000000000E +:10724000813A0008393D0008E53D00084000400053 +:107250007068002070680020010000008068002035 +:107260008000000040010000080000000001000054 +:1072700000100000080000006D61696E0069646C18 +:10728000650000000000802A00000000AAAAAAAA47 +:1072900000000024FFFF00000000000000A00A0022 +:1072A0002000200000000000AAAAAAAA00000000F6 +:1072B000FFFF0000000900000009000000000000BE +:1072C00000000000AAAAAAAA00000000FFFF000018 +:1072D00000000000000000000028800A00000000FC +:1072E000AAAAAAAA00140000FFFF0000000070076D +:1072F000009099002080020000000000AAAAAAAA1B +:1073000000400100FFFF00000009007007000000BE +:107310001000000000000000AAAAAAAA00000000B5 +:10732000FBFF00000000000000000000010400005E +:1073300000000000AAAAAAAA00000000FEFF0000A8 +:10734000000000000000000000000000000000003D +:10735000AAAAAAAA00000000FFFF00000000000087 +:10736000000000000000000000000000AAAAAAAA75 +:1073700000000000FFFF000000000000000000000F +:107380000000000000000000AAAAAAAA0000000055 +:10739000FFFF0000000000000000000000000000EF +:1073A00000000000AAAAAAAA00000000FFFF000037 +:1073B00000000000000000002D040000000000009C +:1073C00000001A0000000002FF000000B831002099 +:1073D0006C26002000000000186C000883040000E8 +:1073E000236C000850040000316C00080096000077 +:1073F0000000080096000000000800960000000051 +:10740000080000000400000088710008000000006F +:10741000000000000000000000000000000000006C +:047420000000000068 :00000001FF diff --git a/Tools/bootloaders/CubeRedSecondary_bl.bin b/Tools/bootloaders/CubeRedSecondary_bl.bin index 403e7e859e420b..821fb93fed1333 100755 Binary files a/Tools/bootloaders/CubeRedSecondary_bl.bin and b/Tools/bootloaders/CubeRedSecondary_bl.bin differ diff --git a/Tools/bootloaders/CubeRedSecondary_bl.hex b/Tools/bootloaders/CubeRedSecondary_bl.hex index 6f4adbe5be9c81..e16421d261731a 100644 --- a/Tools/bootloaders/CubeRedSecondary_bl.hex +++ b/Tools/bootloaders/CubeRedSecondary_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 :1000000000060020E1020008E3020008E302000805 :10001000E3020008E3020008E3020008E30200082C -:10002000E3020008E3020008E3020008F1200008F0 +:10002000E3020008E3020008E30200089D24000840 :10003000E3020008E3020008E3020008E30200080C :10004000E3020008E3020008E3020008E3020008FC -:10005000E3020008E3020008BD240008E9240008C8 -:1000600015250008412500086D250008E302000859 -:10007000E3020008E3020008E3020008E3020008CC -:10008000E3020008E3020008E3020008E3020008BC -:10009000E3020008E3020008E302000899250008D3 +:10005000E3020008E3020008BD2D0008E92D0008B6 +:10006000152E0008412E00086D2E0008F10F000823 +:100070001910000845100008711000089D100008B4 +:10008000C5100008F1100008E3020008E3020008B0 +:10009000E3020008E3020008E3020008992E0008CA :1000A000E3020008E3020008E3020008E30200089C :1000B000E3020008E3020008E3020008E30200088C :1000C000E3020008E3020008E3020008E30200087C :1000D000E3020008E3020008E3020008E30200086C -:1000E000FD250008E3020008E3020008E30200081F -:1000F000E3020008E3020008E3020008E30200084C -:10010000E3020008E302000899260008E302000861 +:1000E000FD2E0008E3020008E3020008E302000816 +:1000F000E3020008E3020008E30200081D11000803 +:10010000E3020008E3020008992F0008E302000858 :10011000E3020008E3020008E3020008E30200082B -:10012000E3020008E3020008E3020008E30200081B -:10013000E3020008E3020008E3020008E30200080B +:1001200049110008711100089D110008C91100084B +:10013000F5110008E3020008E3020008E3020008EA :10014000E3020008E3020008E3020008E3020008FB -:10015000E3020008E3020008E3020008E3020008EB +:100150001D1200084912000875120008E302000889 :10016000E3020008E3020008E3020008E3020008DB :10017000E3020008E3020008E3020008E3020008CB -:10018000E3020008E3020008712600088526000843 +:10018000E3020008E3020008712F0008852F000831 :10019000E3020008E3020008E3020008E3020008AB :1001A000E3020008E3020008E3020008E30200089B :1001B000E3020008E3020008E3020008E30200088B @@ -51,43 +51,43 @@ :100310004F8FBFF36F8F40F20000C0F2F0004EF637 :100320008851CEF200010860BFF34F8FBFF36F8F8B :100330004FF00000E1EE100A4EF63C71CEF20001E3 -:100340000860062080F31488BFF36F8F01F028FD4A -:1003500001F02AFE4FF055301F491B4A91423CBF25 +:100340000860062080F31488BFF36F8F02F008F96D +:1003500002F002FB4FF055301F491B4A91423CBF4F :1003600041F8040BFAE71D49184A91423CBF41F895 :10037000040BFAE71A491B4A1B4B9A423EBF51F83D :10038000040B42F8040BF8E700201849184A914280 -:100390003CBF41F8040BFAE701F040FD01F086FE96 +:100390003CBF41F8040BFAE702F020F902F062FBDF :1003A000144C154DAC4203DA54F8041B8847F9E7A6 :1003B00000F042F8114C124DAC4203DA54F8041B21 -:1003C0008847F9E701F028BD000600200022002040 +:1003C0008847F9E702F008B9000600200022002063 :1003D0000000000808ED00E00000002000060020FA -:1003E000582900080022002030220020302200205E -:1003F000702F0020E0020008E0020008E002000880 +:1003E0007833000800220020302200203022002034 +:1003F000C0300020E0020008E0020008E00200082F :10040000E00200082DE9F04F2DED108AC1F80CD064 :10041000D0F80CD0BDEC108ABDE8F08F002383F338 -:1004200011882846A047002001F08CF9FEE701F072 -:10043000FFF800DFFEE7000038B500F0ADFB01F08B -:100440006FFC054601F0A2FC0446D0B90F4B9D425B -:1004500019D001339D4242F2107512BF04460025A7 -:100460000124002001F066FC0CB100F077F800F0E8 -:1004700023FD00F0EFFB284600F0F0F800F06EF8E6 -:10048000F9E70025EDE70546EBE700BF010007B0FF -:1004900008B500F0ABFBA0F120035842584108BD5D +:1004200011882846A047002001F034FCFEE701F0C7 +:10043000C9FB00DFFEE7000038B500F009FC00F062 +:1004400061FD01F0C3FF054602F01EF80446C0B985 +:100450000E4B9D4217D001339D4242F2107512BFE0 +:10046000044600250124002001F0BAFF0CB100F081 +:1004700075F800F01FFD284600F0F0F800F06EF867 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0A9FBA0F120035842584108BD5F :1004A00007B541F21203022101A8ADF8043000F0B3 -:1004B000BBFB03B05DF804FB38B5302383F3118830 -:1004C000174803680BB101F0FBF90023154A4FF4FC -:1004D0007A71134801F0EAF9002383F31188124C72 +:1004B000B9FB03B05DF804FB38B5302383F3118832 +:1004C000174803680BB101F0A3FC0023154A4FF451 +:1004D0007A71134801F092FC002383F31188124CC7 :1004E000236813B12368013B2360636813B1636819 :1004F000013B63600D4D2B7833B963687BB90220F3 -:1005000000F070FC322363602B78032B07D1636803 -:100510002BB9022000F066FC4FF47A73636038BD9B +:1005000000F06EFC322363602B78032B07D1636805 +:100510002BB9022000F064FC4FF47A73636038BD9D :1005200030220020B9040008502300204822002077 :10053000084B187003280CD8DFE800F00805020803 -:10054000022000F045BC022000F038BC024B002223 +:10054000022000F043BC022000F036BC024B002227 :100550005A6070474822002050230020F8B5394BDC :10056000394A1C46196801316BD004339342F9D1E2 :100570006268364B9A4264D9354B9B6803F100633D -:1005800003F500339A425CD2002000F089FB022080 +:1005800003F500339A425CD2002000F087FB022082 :10059000FFF7CEFF2F4B00219A6C99641A6F1967F1 :1005A0001A6FDA6CD9645A6F59675A6F1A6D1965E8 :1005B0009A6F99679B6F72B64FF0E023C3F8084DAE @@ -102,14 +102,14 @@ :100640002047F8BD0000020820000208FFFF010853 :10065000002200200045025800ED00E02DE9F04F97 :1006600093B0B44B2022FF2100900AA89D6800F0AF -:10067000CDFBB14A1378A3B90121B04811700360D2 -:10068000302383F3118803680BB101F019F90023BB -:10069000AB4A4FF47A71A94801F008F9002383F3BB +:10067000CBFBB14A1378A3B90121B04811700360D4 +:10068000302383F3118803680BB101F0C1FB002311 +:10069000AB4A4FF47A71A94801F0B0FB002383F311 :1006A0001188009B13B1A74B009A1A60A64A1378D1 :1006B000032B03D000231370A24A53604FF0000AAB -:1006C000009CD3465646D146012000F081FB24B160 -:1006D0009C4B1B68002B00F02682002000F086FA5D -:1006E0000390039B002BF2DB012000F067FB039BD0 +:1006C000009CD3465646D146012000F07FFB24B162 +:1006D0009C4B1B68002B00F02682002000F084FA5F +:1006E0000390039B002BF2DB012000F065FB039BD2 :1006F000213B1F2BE8D801A252F823F07D07000808 :10070000A507000839080008C9060008C90600083E :10071000C9060008CB0800089B0A0008B5090008B4 @@ -121,547 +121,709 @@ :10077000C9060008C9060008390800080220FFF76A :1007800087FE002840F0F981009B022105A8BAF1FC :10079000000F08BF1C4641F21233ADF8143000F0D0 -:1007A00043FA91E74FF47A7000F020FA071EEBDB72 +:1007A00041FA91E74FF47A7000F01EFA071EEBDB76 :1007B0000220FFF76DFE0028E6D0013F052F00F272 :1007C000DE81DFE807F0030A0D101336052304214C -:1007D00005A8059300F028FA17E004215548F9E729 +:1007D00005A8059300F026FA17E004215548F9E72B :1007E00004215A48F6E704215948F3E74FF01C0862 -:1007F000404608F1040800F055FA0421059005A8C8 -:1008000000F012FAB8F12C0FF2D101204FF00009DC -:1008100000FA07F747EA0B0B5FFA8BFB00F042FB8D +:1007F000404608F1040800F053FA0421059005A8CA +:1008000000F010FAB8F12C0FF2D101204FF00009DE +:1008100000FA07F747EA0B0B5FFA8BFB00F040FB8F :1008200026B10BF00B030B2B08BF0024FFF738FE9B :100830004AE704214748CDE7002EA5D00BF00B0373 :100840000B2BA1D10220FFF723FE074600289BD0E7 -:100850000120002600F024FA0220FFF769FE5FFA6B -:1008600086F8404600F02CFA0446B0B103994046A1 -:100870000136A1F140025142514100F031FA002805 +:100850000120002600F022FA0220FFF769FE1FFAAD +:1008600086F8404600F02AFA0446B0B103994046A3 +:100870000136A1F140025142514100F02FFA002807 :10088000EDD1BA46044641F21213022105A83E46B4 -:10089000ADF8143000F0C8F916E725460120FFF73F -:1008A00047FE244B9B68AB4207D9284600F0FAF973 +:10089000ADF8143000F0C6F916E725460120FFF741 +:1008A00047FE244B9B68AB4207D9284600F0F8F975 :1008B000013040F067810435F3E70025224BBA464A :1008C0003E461D701F4B5D60A8E7002E3FF45CAFF5 :1008D0000BF00B030B2B7FF457AF0220FFF728FE22 -:1008E000322000F083F9B0F10008FFF64DAF18F0A8 +:1008E000322000F081F9B0F10008FFF64DAF18F0AA :1008F00003077FF449AF0F4A08EB05039268934260 :100900003FF642AFB8F5807F3FF73EAF124BB84598 -:10091000019323DD4FF47A7000F068F90390039A95 +:10091000019323DD4FF47A7000F066F90390039A97 :10092000002AFFF631AF039A0137019B03F8012B30 :10093000EDE700BF002200204C23002030220020E1 :10094000B90400085023002048220020042200207F :10095000082200200C2200204C220020C820FFF793 :1009600097FD074600283FF40FAF1F2D11D8C5F1A2 :1009700020020AAB25F0030084494245184428BFF1 -:100980004246019200F038FA019AFF217F4800F0B8 -:100990003DFA4FEAA803C8F387027C492846019331 -:1009A00000F03CFA064600283FF46DAF019B05EBD2 +:100980004246019200F036FA019AFF217F4800F0BA +:100990003BFA4FEAA803C8F387027C492846019333 +:1009A00000F03AFA064600283FF46DAF019B05EBD4 :1009B000830533E70220FFF76BFD00283FF4E4AE28 -:1009C00000F0ACF900283FF4DFAE0027B846704BCA +:1009C00000F0AAF900283FF4DFAE0027B846704BCC :1009D0009B68BB4218D91F2F11D80A9B01330ED038 :1009E00027F0030312AA134453F8203C0593404612 -:1009F000042205A9043700F087FA8046E7E7384665 -:100A000000F050F90590F2E7CDF81480042105A814 -:100A100000F00AF902E70023642104A8049300F01F -:100A2000F9F800287FF4B0AE0220FFF731FD00286E -:100A30003FF4AAAE049800F067F90590E6E70023BA -:100A4000642104A8049300F0E5F800287FF49CAE2C +:1009F000042205A9043700F0E5FA8046E7E7384607 +:100A000000F04EF90590F2E7CDF81480042105A816 +:100A100000F008F902E70023642104A8049300F021 +:100A2000F7F800287FF4B0AE0220FFF731FD002870 +:100A30003FF4AAAE049800F065F90590E6E70023BC +:100A4000642104A8049300F0E3F800287FF49CAE2E :100A50000220FFF71DFD00283FF496AE049800F039 -:100A600055F9EAE70220FFF713FD00283FF48CAEAA -:100A700000F064F9E1E70220FFF70AFD00283FF4E7 -:100A800083AE05A9142000F05FF907460421049005 -:100A900004A800F0C9F83946B9E7322000F0A6F8FA +:100A600053F9EAE70220FFF713FD00283FF48CAEAC +:100A700000F062F9E1E70220FFF70AFD00283FF4E9 +:100A800083AE05A9142000F05DF907460421049007 +:100A900004A800F0C7F83946B9E7322000F0A4F8FE :100AA000071EFFF671AEBB077FF46EAE384A07EB48 :100AB0000903926893423FF667AE0220FFF7E8FC15 :100AC00000283FF461AE27F003074F44B9453FF4D7 -:100AD000A5AE484609F1040900F0E4F804210590A8 -:100AE00005A800F0A1F8F1E74FF47A70FFF7D0FC09 -:100AF00000283FF449AE00F011F9002844D00A9BC9 -:100B000001330BD008220AA9002000F087F9002841 -:100B10003AD02022FF210AA800F078F9FFF7C0FCA4 -:100B20001C4800F015FE13B0BDE8F08F002E3FF416 +:100AD000A5AE484609F1040900F0E2F804210590AA +:100AE00005A800F09FF8F1E74FF47A70FFF7D0FC0B +:100AF00000283FF449AE00F00FF9002844D00A9BCB +:100B000001330BD008220AA9002000F085F9002843 +:100B10003AD02022FF210AA800F076F9FFF7C0FCA6 +:100B20001C4801F0BDF813B0BDE8F08F002E3FF473 :100B30002BAE0BF00B030B2B7FF426AE00236421AE -:100B400005A8059300F066F8074600287FF41CAE60 +:100B400005A8059300F064F8074600287FF41CAE62 :100B50000220FFF79DFC804600283FF415AEFFF70A -:100B60009FFC41F2883000F0F3FD059800F0B2F9E7 -:100B700046463C4600F096F9A6E506464EE64FF09E +:100B60009FFC41F2883001F09BF8059800F0B0F945 +:100B700046463C4600F094F9A6E506464EE64FF0A0 :100B8000000901E6BA467EE637467CE64C220020A4 -:100B900000220020A086010070470000104B70B5B5 -:100BA0001B780C460133DBB2012B12D80D4B1D68AC -:100BB0004FF47A732968A2FB033222460E6A01467B -:100BC0002846B047844204D1074B002201201A7006 -:100BD00070BD4FF4FA7000F0BBFD0020F8E700BFD5 -:100BE00010220020142200209C230020002307B59F -:100BF000024601210DF107008DF80730FFF7CEFF07 -:100C000020B19DF8070003B05DF804FB4FF0FF3002 -:100C1000F9E700000A46042108B5FFF7BFFF80F09E -:100C20000100C0B2404208BD074B0A4630B41978F3 -:100C3000064B53F82140014623682046DD69044BEA -:100C4000AC4630BC604700BF9C230020142200202B -:100C5000A086010070B5104C0025104E00F038FF42 -:100C600020803068238883420CD8002520880138F2 -:100C700000F02AFF23880544013BB5F5802F23802F -:100C8000F4D370BD00F020FF336805440133B5F59F -:100C9000003F3360E5D3E8E79E230020582300207F -:100CA00000F0F4BF00F1006000F50030006870470C -:100CB00000F10060920000F5003000F06BBF000012 -:100CC000054B1A68054B1B889B1A834202D91044B6 -:100CD00000F0FABE00207047582300209E23002019 -:100CE00038B50446074D29B128682044BDE838408E -:100CF00000F002BF2868204400F0ECFE0028F3D08A -:100D000038BD00BF582300200020704700F1FF507D -:100D100000F58F10D0F8000870470000064991F8E0 -:100D2000243033B100230822086A81F82430FFF709 -:100D3000BFBF0120704700BF5C230020014B186833 -:100D4000704700BF0010005C194B013803220844B3 -:100D500070B51D68174BC5F30B042D0C1E88A642F9 -:100D60000BD15C680A46013C824213460FD214F94B -:100D7000016F4EB102F8016BF6E7013A03F1080387 -:100D8000ECD181420B4602D22C2203F8012B042421 -:100D9000094A1688AE4204D1984284BF967803F877 -:100DA000016B013C02F10402F3D1581A70BD00BF7F -:100DB0000010005C18220020B8270008022803D188 -:100DC000024B4FF080629A61704700BF000C0258DE -:100DD000022803D1024B4FF480629A61704700BF32 -:100DE000000C0258022804D1024A536983F480633C -:100DF00053617047000C0258002310B5934203D092 -:100E0000CC5CC4540133F9E710BD00000244034632 -:100E1000934202D003F8011BFAE770472DE9F8432B -:100E20001F4D14460746884695F8242052BBDFF82C -:100E300070909CB395F824302BB92022FF214846AE -:100E40002F62FFF7E3FF95F824004146C0F1080246 -:100E500005EB8000A24228BF2246D6B29200FFF7DF -:100E6000CBFF95F82430A41B17441E449044E4B2F1 -:100E7000F6B2082E85F82460DBD1FFF74FFF00287B -:100E8000D7D108E02B6A03EB82038342CFD0FFF770 -:100E900045FF0028CBD10020BDE8F8830120FBE707 -:100EA0005C230020024B1A78024B1A70704700BF77 -:100EB0009C23002010220020034B04490B60044BAC -:100EC000186800F01BBB00BF80841E008423002034 -:100ED00014220020094B1822002110B504461846A0 -:100EE000FFF794FF064A074B01461278046053F857 -:100EF0002200BDE8104000F001BB00BF84230020A9 -:100F00009C2300201422002030B50A44084D914251 -:100F10000DD011F8013B5840082340F30004013B79 -:100F20002C4013F0FF0384EA5000F6D1EFE730BD08 -:100F30002083B8ED026843681143016003B118478C -:100F400070470000024A136843F0C0031360704703 -:100F500000780040024A136843F0C00313607047F2 -:100F6000007C004037B51A4C1A4D204600F0BAFA02 -:100F700004F11400009400234FF40072164900F0AD -:100F800077F94FF40072154904F138000094144BBE -:100F900000F0F0F9134BC4E91735134C204600F06C -:100FA000A1FA04F1140000234FF400720F490094D9 -:100FB00000F05EF90E4B4FF400720E4904F1380058 -:100FC000009400F0D7F90C4BC4E9173503B030BDDD -:100FD000A023002000E1F5057824002078280020D7 -:100FE000450F0008007800400C24002078260020DF -:100FF000550F0008782A0020007C0040037C30B5A3 -:10100000274C002918BF0C46012B0CD1254B9842C8 -:1010100036D1254B9A6C42F080429A641A6F42F0A6 -:1010200080421A671B6F2268036EC16D03EB520387 -:101030008466B3FBF2F36268150442BF23F0070530 -:1010400003F0070343EA4503CB60A36843F0400382 -:101050004B60E36843F001038B6042F4967343F006 -:1010600001030B604FF0FF330B62510505D512F001 -:10107000102211D0B2F1805F10D080F8643030BD02 -:101080000A4B9842CFD1084B9A6C42F000429A64C6 -:101090001A6F42F00042C4E77F23EEE73F23ECE7FC -:1010A000C8270008A0230020004502580C24002077 -:1010B0002DE9F047C66D05463768F46921073462AB -:1010C0001AD014F0080118BF4FF48071E20748BF2E -:1010D00041F02001A3074FF0300348BF41F0400129 -:1010E000600748BF41F0800183F31188281DFFF796 -:1010F00021FF002383F31188E2050AD5302383F30F -:1011000011884FF48061281DFFF714FF002383F33B -:1011100011884FF030094FF0000A14F0200838D140 -:101120003B0616D54FF0300905F1380A200610D5D8 -:1011300089F31188504600F051F9002836DA082169 -:10114000281DFFF7F7FE27F080033360002383F3A9 -:101150001188790614D5620612D5302383F31188DD -:10116000D5E913239A4208D12B6C33B127F04007FD -:101170001021281DFFF7DEFE3760002383F311885E -:10118000E30618D5AA6E1369ABB15069BDE8F04704 -:10119000184789F31188736A284695F86410194036 -:1011A00000F0BAF98AF31188F469B6E7B06288F3FF -:1011B0001188F469BAE7BDE8F0870000F8B5154674 -:1011C000826804460B46AA4200D28568A169266956 -:1011D000761AB5420BD218462A46FFF70DFEA369D0 -:1011E0002B44A3612846A3685B1BA360F8BD0CD900 -:1011F000AF1B18463246FFF7FFFD3A46E168304420 -:10120000FFF7FAFDE3683B44EBE718462A46FFF791 -:10121000F3FDE368E5E7000083689342F7B5044611 -:10122000154600D28568D4E90460361AB5420BD25F -:101230002A46FFF7E1FD63692B4463612846A368F2 -:101240005B1BA36003B0F0BD0DD93246AF1B01910B -:10125000FFF7D2FD01993A46E0683144FFF7CCFD33 -:10126000E3683B44E9E72A46FFF7C6FDE368E4E7A5 -:1012700010B50A440024C361029B8460C16002610E -:101280000362C0E90000C0E9051110BD08B5D0E94E -:101290000532934201D1826882B98268013282604C -:1012A0005A1C426119700021D0E904329A4224BFCD -:1012B000C368436100F068FA002008BD4FF0FF30BA -:1012C000FBE7000070B5302304460E4683F3118817 -:1012D000A568A5B1A368A269013BA360531CA361E3 -:1012E00015782269934224BFE368A361E3690BB1D7 -:1012F00020469847002383F31188284607E03146AB -:10130000204600F031FA0028E2DA85F3118870BD3A -:101310002DE9F74F04460E4617469846D0F81C9024 -:101320004FF0300A8AF311884FF0000B154665B173 -:101330002A4631462046FFF741FF034660B9414641 -:10134000204600F011FA0028F1D0002383F3118821 -:10135000781B03B0BDE8F08FB9F1000F03D0019006 -:101360002046C847019B8BF31188ED1A1E448AF36F -:101370001188DCE7C160C361009B82600362C0E941 -:1013800005111144C0E9000001617047F8B5044639 -:101390000D461646302383F31188A768A7B1A368CA -:1013A000013BA36063695A1C62611D70D4E9043279 -:1013B0009A4224BFE3686361E3690BB12046984712 -:1013C000002080F3118807E03146204600F0CCF978 -:1013D0000028E2DA87F31188F8BD0000D0E9052380 -:1013E00010B59A4201D182687AB98268002101322F -:1013F00082605A1C82611C7803699A4224BFC368C8 -:10140000836100F0C1F9204610BD4FF0FF30FBE7CB -:101410002DE9F74F04460E4617469846D0F81C9023 -:101420004FF0300A8AF311884FF0000B154665B172 -:101430002A4631462046FFF7EFFE034660B9414693 -:10144000204600F091F90028F1D0002383F31188A1 -:10145000781B03B0BDE8F08FB9F1000F03D0019005 -:101460002046C847019B8BF31188ED1A1E448AF36E -:101470001188DCE7026843681143016003B1184733 -:10148000704700001430FFF743BF00004FF0FF33F8 -:101490001430FFF73DBF00003830FFF7B9BF000040 -:1014A0004FF0FF333830FFF7B3BF00001430FFF7C1 -:1014B00009BF00004FF0FF311430FFF703BF0000F9 -:1014C0003830FFF763BF00004FF0FF323830FFF7CE -:1014D0005DBF0000012914BF6FF0130000207047AA -:1014E000FFF740BD044B036000234360C0E90233B3 -:1014F00001230374704700BFE027000810B53023B4 -:10150000044683F31188FFF779FD0223002023743A -:1015100080F3118810BD000038B5C36904460D463C -:101520001BB904210844FFF7A5FF294604F1140064 -:10153000FFF7ACFE002806DA201D4FF40061BDE87D -:101540003840FFF797BF38BD0023826803750369F1 -:101550001B6899689142FBD25A6803604260106030 -:101560005860704700238268037503691B68996897 -:101570009142FBD85A68036042601060586070471F -:1015800008B50846302383F311880B7D032B05D063 -:10159000042B0DD02BB983F3118808BD8B69002271 -:1015A0001A604FF0FF338361FFF7CEFF0023F2E7AD -:1015B000D1E9003213605A60F3E70000FFF7C4BFBF -:1015C000054BD96808751868026853601A600122D3 -:1015D000D8600275FEF716BF782C00200C4B30B592 -:1015E000DD684B1C87B004460FD02B46094A68467D -:1015F00000F05CF92046FFF7E3FF009B13B168465B -:1016000000F05EF9A86907B030BDFFF7D9FFF9E730 -:10161000782C002081150008044B1A68DB6890685C -:101620009B68984294BF002001207047782C0020CE -:10163000084B10B51C68D868226853601A600122F4 -:10164000DC602275FFF78EFF01462046BDE81040A2 -:10165000FEF7D8BE782C0020044B1A68DB6892682D -:101660009B689A4201D9FFF7E3BF7047782C0020AE -:1016700038B5074C012300250649074823706560EB -:1016800000F03AFC0223237085F3118838BD00BFB7 -:10169000E02E00200C280008782C002000F046B92D -:1016A000EFF3118020B9EFF30583302282F3118824 -:1016B0007047000010B530B9EFF30584C4F3080497 -:1016C00014B180F3118810BDFFF7C6FF84F31188B1 -:1016D000F9E700008B600223086108468B8270479F -:1016E0008368A3F1840243F8142C026943F8442C64 -:1016F000426943F8402C094A43F8242CC268A3F1FC -:10170000200043F8182C022203F80C2C002203F8C6 -:101710000B2C034A43F8102C704700BF1D0400082F -:10172000782C002008B5FFF7DBFFBDE80840FFF785 -:1017300045BF0000024BDB6898610F20FFF740BFF8 -:10174000782C0020302383F31188FFF7F3BF0000CB -:1017500008B50146302383F311880820FFF73EFFC8 -:10176000002383F3118808BD064BDB6839B142685A -:1017700018605A60136043600420FFF72FBF4FF0DA -:10178000FF307047782C00200368984206D01A6812 -:101790000260506018469961FFF710BF7047000063 -:1017A000036810B59C68A2420CD85C688A600B6024 -:1017B0004C602160596099688A1A9A604FF0FF3333 -:1017C000836010BD121B1B68ECE700000A2938BFBC -:1017D0000A2170B504460D460A26601900F084FB04 -:1017E00000F06CFB041BA54203D8751C04462E4672 -:1017F000F3E70A2E04D90120BDE8704000F0BCBB1D -:1018000070BD0000F8B5144B0D460A2A4FF00A07C8 -:10181000D96103F11001826038BF0A224160196961 -:101820001446016048601861A81800F04DFB00F0F4 -:1018300045FB431B0646A34206D37C1C28192746BA -:10184000354600F051FBF2E70A2F04D90120BDE82C -:10185000F84000F091BBF8BD782C0020F8B50646A2 -:101860000D4600F02BFB0F4A134653F8107F9F42A2 -:1018700006D12A4601463046BDE8F840FFF7C2BF10 -:10188000D169BB68441A2C1928BF2C46A34202D93F -:101890002946FFF79BFF224631460348BDE8F84042 -:1018A000FFF77EBF782C0020882C0020C0E903239E -:1018B000002310B45DF8044B4361FFF7CFBF000075 -:1018C00010B5194C236998420DD08168D0E90032D7 -:1018D00013605A609A680A449A60002303604FF0CC -:1018E000FF33A36110BD0268234643F8102F5360F5 -:1018F0000022026022699A4203D1BDE8104000F044 -:10190000EDBA936881680B44936000F0D7FA2269BE -:10191000E1699268441AA242E4D91144BDE810403A -:10192000091AFFF753BF00BF782C00202DE9F047BC -:10193000DFF8BC8008F110072C4ED8F8105000F0EA -:10194000BDFAD8F81C40AA68031B9A423ED814443A -:101950004FF00009D5E90032C8F81C4013605A6006 -:10196000C5F80090D8F81030B34201D100F0B6FAB3 -:1019700089F31188D5E9033128469847302383F34A -:1019800011886B69002BD8D000F098FA6A69A0EB37 -:10199000040982464A450DD2022000F0EDFA0022E9 -:1019A000D8F81030B34208D151462846BDE8F04778 -:1019B000FFF728BF121A2244F2E712EB0909294661 -:1019C000384638BF4A46FFF7EBFEB5E7D8F8103087 -:1019D000B34208D01444C8F81C00211AA960BDE81D -:1019E000F047FFF7F3BEBDE8F08700BF882C00206A -:1019F000782C002000207047FEE7000070470000B0 -:101A00004FF0FF3070470000BFF34F8F044B1A694F -:101A10005107FCD1D3F810215207F8D1704700BF0D -:101A20000020005208B50D4B1B78ABB9FFF7ECFF57 -:101A30000B4BDA68D10704D50A4A5A6002F18832A2 -:101A40005A60D3F80C21D20706D5064AC3F8042100 -:101A500002F18832C3F8042108BD00BFE82E00203F -:101A6000002000522301674508B5114B1B78F3B9DC -:101A7000104B1A69510703D5DA6842F04002DA6068 -:101A8000D3F81021520705D5D3F80C2142F04002BB -:101A9000C3F80C21FFF7B8FF064BDA6842F00102E9 -:101AA000DA60D3F80C2142F00102C3F80C2108BD22 -:101AB000E82E0020002000520F289ABF00F5806019 -:101AC00040040020704700004FF4003070470000D1 -:101AD000102070470F2808B50BD8FFF7EDFF00F571 -:101AE00000330268013204D104308342F9D101206D -:101AF00008BD0020FCE700000F2870B5054645D85A -:101B0000FFF7CEFD224CFFF77FFF0646FFF78AFF67 -:101B10004FF0FF33072D6361C4F8143120D82361DF -:101B2000FFF772FF2B0243F02403E360E36843F006 -:101B30008003E36023695A07FCD42846FFF764FF5B -:101B40004FF40031FFF7B8FF00F002F93046FFF71D -:101B50008BFFFFF7AFFD2846BDE87040FFF7BABF27 -:101B6000C4F81031FFF750FFA5F108031B0243F042 -:101B70002403C4F80C31D4F80C3143F08003C4F8CA -:101B80000C31D4F810315B07FBD4D6E7002070BDD0 -:101B9000002000522DE9F84F40EA020305460C46AA -:101BA0001746D80602D00020BDE8F88F27F01F079F -:101BB000DFF8D4B0FFF736FF2744BC4203D1012041 -:101BC000FFF752FFF0E720222946204600F0CEFD25 -:101BD00010B920352034F0E72B4605F120021E68AD -:101BE000711CE0D104339A42F9D1FFF759FD05F198 -:101BF0007843234AB3F5801F224B28BF9A4603F14E -:101C0000040338BF9046A2F1080228BF9846A3F10A -:101C100008033ABF9146DA469946FFF7F5FEC8F841 -:101C20000060A5EB040CD9F8002004F11C0142F07F -:101C30000202C9F80020221FDAF8006016F005063B -:101C4000FAD152F8043F8A424CF80230F4D1BFF383 -:101C50004F8FFFF7D9FE4FF0FF32C8F80020D9F8B8 -:101C6000002022F00202C9F80020FFF723FD202205 -:101C70002146284600F07AFD0028AAD030469FE78A -:101C800014200052102100521020005210B5084CB0 -:101C9000237828B11BB9FFF7C5FE0123237010BDBF -:101CA000002BFCD02070BDE81040FFF7DDBE00BF68 -:101CB000E82E00200244074BD2B210B5904200D16A -:101CC00010BD441C00B253F8200041F8040BE0B2F0 -:101CD000F4E700BF504000580E4B30B51C6F240491 -:101CE00005D41C6F1C671C6F44F400441C670A4C2D -:101CF00002442368D2B243F480732360074B9042BE -:101D000000D130BD441C51F8045B00B243F82050B0 -:101D1000E0B2F4E70044025800480258504000582E -:101D200007B5012201A90020FFF7C4FF019803B005 -:101D30005DF804FB13B50446FFF7F2FFA04205D09F -:101D4000012201A900200194FFF7C6FF02B010BDD7 -:101D50000144BFF34F8F064B884204D3BFF34F8F2C -:101D6000BFF36F8F7047C3F85C022030F4E700BF09 -:101D700000ED00E0034B1A681AB9034AD2F8D024E8 -:101D80001A607047EC2E00200040025808B5FFF79B -:101D9000F1FF024B1868C0F3806008BDEC2E0020F4 -:101DA00070B5BFF34F8FBFF36F8F1A4A0021C2F88F -:101DB0005012BFF34F8FBFF36F8F536943F400335B -:101DC0005361BFF34F8FBFF36F8FC2F88410BFF31F -:101DD0004F8FD2F8803043F6E074C3F3C900C3F3E9 -:101DE0004E335B0103EA0406014646EA8175013978 -:101DF000C2F86052F9D2203B13F1200FF2D1BFF3A9 -:101E00004F8F536943F480335361BFF34F8FBFF358 -:101E10006F8F70BD00ED00E0FEE70000214B22480F -:101E2000224A70B5904237D3214BC11EDA1C121AD8 -:101E300022F003028B4238BF00220021FEF7E6FFAA -:101E40001C4A0023C2F88430BFF34F8FD2F8803091 -:101E500043F6E074C3F3C900C3F34E335B0103EAF6 -:101E60000406014646EA81750139C2F86C52F9D27E -:101E7000203B13F1200FF2D1BFF34F8FBFF36F8FD1 -:101E8000BFF34F8FBFF36F8F0023C2F85032BFF301 -:101E90004F8FBFF36F8F70BD53F8041B40F8041BC6 -:101EA000C0E700BF88290008702F0020702F002095 -:101EB000702F002000ED00E000F07CB9014B586A63 -:101EC000704700BF000C0040034B002258631A61AA -:101ED0000222DA60704700BF000C0040014B002274 -:101EE000DA607047000C0040014B5863704700BF38 -:101EF000000C0040FEE7000070B51B4B00250446B7 -:101F000086B058600E468562016300F001F904F165 -:101F10001003A560E562C4E904334FF0FF33C4E960 -:101F20000044C4E90635FFF7C9FF2B46024604F119 -:101F300034012046C4E9082380230C4A2565FFF7B5 -:101F4000C9FB01230A4AE060009203756846726883 -:101F50000192B268CDE90223064BCDE90435FFF7C3 -:101F6000E1FB06B070BD00BFE02E0020182800087D -:101F70001D280008F51E0008024AD36A1843D062E3 -:101F8000704700BF782C00204B6843608B688360EB -:101F9000CB68C3600B6943614B6903628B69436221 -:101FA0000B6803607047000008B53A4B40F2FF71C0 -:101FB0003948D3F888200A43C3F88820D3F888200A -:101FC00022F4FF6222F00702C3F88820D3F8883099 -:101FD000324B1A6C0A431A649A6E0A439A66304A64 -:101FE0009B6E1146FFF7D0FF00F5806002F11C01E7 -:101FF000FFF7CAFF00F5806002F13801FFF7C4FF68 -:1020000000F5806002F15401FFF7BEFF00F580602B -:1020100002F17001FFF7B8FF00F5806002F18C015A -:10202000FFF7B2FF00F5806002F1A801FFF7ACFFF7 -:1020300000F5806002F1C401FFF7A6FF00F58060A3 -:1020400002F1E001FFF7A0FF00F5806002F1FC0162 -:10205000FFF79AFF02F58C7100F58060FFF794FF9F -:1020600000F066F90F4BD3F8902242F00102C3F85A -:102070009022D3F8942242F00102C3F89422052260 -:10208000C3F898204FF06052C3F89C20064AC3F86A -:10209000A02008BD00440258000002580045025824 -:1020A0002428000800ED00E01F00080308B500F038 -:1020B00041FBFFF7DDFA0B4BDA6B42F04002DA63CB -:1020C0005A6E22F040025A665B6E074B1A6842F065 -:1020D00008021A601A6842F004021A60BDE808405B -:1020E000FFF748BE0045025800180248704700003C -:1020F000EFF30983054968334A6B22F001024A6312 -:1021000083F30988002383F31188704700EF00E010 -:10211000302080F3118862B60D4B0E4AD96821F445 -:10212000E0610904090C0A430B49DA60D3F8FC208A -:1021300042F08072C3F8FC20084AC2F8B01F116850 -:1021400041F0010111602022DA7783F82200704704 -:1021500000ED00E00003FA0555CEACC5001000E02C -:10216000302310B583F311880E4B5B6813F40063C2 -:1021700014D0F1EE103AEFF309844FF08073683C0D -:10218000E361094BDB6B236684F30988FFF744FAAC -:1021900010B1064BA36110BD054BFBE783F311881B -:1021A000F9E700BF00ED00E000EF00E02F040008B9 -:1021B000320400080E4B9A6C42F008029A641A6FBF -:1021C00042F008021A670B4A1B6FD36B43F00803F7 -:1021D000D363C722084B9A624FF0FF32DA620022C3 -:1021E0009A615A63DA605A6001225A611A60704734 -:1021F000004502580010005C000C0040094A08B578 -:102200001169D3680B40D9B29B076FEA01011161D4 -:1022100007D5302383F31188FFF740FA002383F3B7 -:10222000118808BD000C0040044BDA6B0243DA63EE -:102230005A6E104358665B6E704700BF00450258E7 -:102240003A4B4FF0FF31D3F8802062F00042C3F8E0 -:102250008020D3F8802002F00042C3F88020D3F819 -:102260008020D3F88420C3F88410D3F8842000227F -:10227000C3F88420D3F88400D86F40F0FF4040F4C6 -:10228000FF0040F4DF4040F07F00D867D86F20F0B7 -:10229000FF4020F4FF0020F4DF4020F07F00D867EB -:1022A000D86FD3F888006FEA40506FEA5050C3F8F7 -:1022B0008800D3F88800C0F30A00C3F88800D3F878 -:1022C0008800D3F89000C3F89010D3F89000C3F8BA -:1022D0009020D3F89000D3F89400C3F89410D3F86A -:1022E0009400C3F89420D3F89400D3F89800C3F86E -:1022F0009810D3F89800C3F89820D3F89800D3F832 -:102300008C00C3F88C10D3F88C00C3F88C20D3F861 -:102310008C00D3F89C00C3F89C10D3F89C10C3F831 -:102320009C20D3F89C3000F0BFB900BF0044025895 -:1023300008B50122504BC3F80821504B5A6D42F0AA -:1023400002025A65DA6F42F00202DA670422DB6F9A -:102350004B4BDA605A689104FCD54A4A1A60012254 -:102360009A60494ADA6000221A614FF440429A6149 -:10237000434B9A699204FCD51A6842F480721A6041 -:10238000424B1A6F12F4407F04D04FF480321A6728 -:1023900000221A671A6842F001021A603B4B1A6861 -:1023A0005007FCD500221A611A6912F03802FBD1DD -:1023B000012119604FF0804159605A67344ADA624E -:1023C000344A1A611A6842F480321A602F4B1A6834 -:1023D0009103FCD51A6842F480521A601A6892047C -:1023E000FCD52D4A2D499A6200225A63196301F5E2 -:1023F0007C01DA6301F5E77199635A64284A1A642B -:10240000284ADA621A6842F0A8521A601F4B1A680A -:1024100002F02852B2F1285FF9D148229A614FF4B4 -:102420008862DA6140221A621F4ADA641F4A1A651A -:102430001F4A5A651F4A9A6532231F4A1360136860 -:1024400003F00F03022BFAD1104A136943F0030380 -:102450001361136903F03803182BFAD14FF00050C1 -:10246000FFF7E2FE4FF08040FFF7DEFE4FF0004046 -:10247000BDE80840FFF7D8BE008000510045025873 -:102480000048025800C000F0040000010044025857 -:102490000000FF01008890083220600063020901FB -:1024A000470E0508DD0BBF012000002000000110D1 -:1024B0000910E00000010110002000524FF0B0426E -:1024C00008B5D2F8883003F00103C2F8883023B190 -:1024D000044A13680BB150689847BDE80840FFF7FD -:1024E0003FBE00BFF02E00204FF0B04208B5D2F83A -:1024F000883003F00203C2F8883023B1044A93689D -:102500000BB1D0689847BDE80840FFF729BE00BF6F -:10251000F02E00204FF0B04208B5D2F8883003F01A -:102520000403C2F8883023B1044A13690BB150691F -:102530009847BDE80840FFF713BE00BFF02E00200B -:102540004FF0B04208B5D2F8883003F00803C2F863 -:10255000883023B1044A93690BB1D0699847BDE82C -:102560000840FFF7FDBD00BFF02E00204FF0B04245 -:1025700008B5D2F8883003F01003C2F8883023B1D0 -:10258000044A136A0BB1506A9847BDE80840FFF748 -:10259000E7BD00BFF02E00204FF0B04310B5D3F8D8 -:1025A000884004F47872C3F88820A30604D5124A40 -:1025B000936A0BB1D06A9847600604D50E4A136B34 -:1025C0000BB1506B9847210604D50B4A936B0BB1A6 -:1025D000D06B9847E20504D5074A136C0BB1506CD9 -:1025E0009847A30504D5044A936C0BB1D06C984767 -:1025F000BDE81040FFF7B4BDF02E00204FF0B0430F -:1026000010B5D3F8884004F47C42C3F888206205F2 -:1026100004D5164A136D0BB1506D9847230504D5A8 -:10262000124A936D0BB1D06D9847E00404D50F4A60 -:10263000136E0BB1506E9847A10404D50B4A936EEC -:102640000BB1D06E9847620404D5084A136F0BB1E2 -:10265000506F9847230404D5044A936F0BB1D06F91 -:102660009847BDE81040FFF77BBD00BFF02E00206B -:1026700008B50348FEF71CFDBDE80840FFF770BD34 -:10268000A023002008B50348FEF712FDBDE808406E -:10269000FFF766BD0C24002008B5FFF7AFFDBDE8CD -:1026A0000840FFF75DBD0000062108B5084600F0B0 -:1026B0002BF80621072000F027F80621082000F05B -:1026C00023F80621092000F01FF806210A2000F057 -:1026D0001BF80621172000F017F80621282000F02B -:1026E00013F809217A2000F00FF80721322000F0BA -:1026F0000BF80C21522000F007F80C215320BDE804 -:10270000084000F001B80000090100F16043012217 -:1027100003F56143C9B283F8001300F01F039A4028 -:1027200043099B0003F1604303F56143C3F8802133 -:102730001A60704708B5FFF783FD00F009F8FEF74F -:10274000CFFEFFF7D3FCBDE80840FFF7B5BB0000A4 -:102750000023054A19460133102BC2E9001102F18A -:102760000802F8D1704700BFF02E002010B50139E3 -:102770000244904201D1002005E0037811F8014F96 -:10278000A34201D0181B10BD0130F2E753544D3362 -:102790003248373F3F3F0053544D33324837337848 -:1027A0002F3732780053544D3332483734332F3774 -:1027B00035332F373530000001105A00031059000F -:1027C0000120580003205600009600000000000081 -:1027D00000000000000000000000000000000000F9 -:1027E00000000000A11400088D140008C91400089E -:1027F000B5140008C1140008AD14000899140008AD -:1028000085140008D514000863300000082800086B -:10281000D02C0020E02E00206D61696E0069646C90 -:10282000650000000000002800000000AAAAAAAA73 -:1028300000000024FFFF0000000000000000000076 -:102840000000000000000000AAAAAAAA00000000E0 -:10285000FFFF00000000000000000000000000007A -:1028600000000000AAAAAAAA00000000FFFF0000C2 -:102870000000000000000000000010000000000048 -:10288000AAAAAAAA00000000FFFF000000000000A2 -:10289000000000000A80020000000000AAAAAAAA04 -:1028A00005400100FFFF00008800007007000000E5 -:1028B0000000000000000000AAAAAAAA0000000070 -:1028C000FFFF00000000000000000000000000000A -:1028D00000000000AAAAAAAA00000000FFFF000052 -:1028E00000000000000000000000000000000000E8 -:1028F000AAAAAAAA00000000FFFF00000000000032 -:10290000000000000000000000000000AAAAAAAA1F -:1029100000000000FFFF00000000000000000000B9 -:102920000000000000000000AAAAAAAA00000000FF -:10293000FFFF000000000000000000000000000099 -:1029400000000000AAAAAAAA00000000FFFF0000E1 -:1029500000000000000000002E0400000000000045 -:1029600000001A0000000000FF000000A02300206B -:10297000000000008C27000883040000972700084F -:0829800050040000A527000827 +:100B900000220020A0860100104B70B51B780C4687 +:100BA0000133DBB2012B12D80D4B1D684FF47A7361 +:100BB0002968A2FB033222460E6A01462846B04746 +:100BC000844204D1074B002201201A7070BD4FF4FB +:100BD000FA7001F065F80020F8E700BF102200204D +:100BE000142200209C230020002307B50246012187 +:100BF0000DF107008DF80730FFF7CEFF20B19DF80B +:100C0000070003B05DF804FB4FF0FF30F9E7000088 +:100C10000A46042108B5FFF7BFFF80F00100C0B20B +:100C2000404208BD074B0A4630B41978064B53F8CA +:100C30002140014623682046DD69044BAC4630BCA8 +:100C4000604700BF9C23002014220020A0860100E2 +:100C500070B5104C0025104E01F0E2F9208030688C +:100C6000238883420CD800252088013801F0D4F96C +:100C700023880544013BB5F5802F2380F4D370BD54 +:100C800001F0CAF9336805440133B5F5003F33601C +:100C9000E5D3E8E79E2300205823002001F08EBA18 +:100CA00000F1006000F500300068704700F100605E +:100CB000920000F5003001F00FBA0000054B1A68F1 +:100CC000054B1B889B1A834202D9104401F0A4B93A +:100CD00000207047582300209E23002038B504468A +:100CE000074D29B128682044BDE8384001F0ACB96F +:100CF0002868204401F096F90028F3D038BD00BFE1 +:100D0000582300200020704700F1FF5000F58F109D +:100D1000D0F8000870470000064991F8243033B13C +:100D200000230822086A81F82430FFF7BFBF0120A2 +:100D3000704700BF5C230020014B1868704700BF5C +:100D40000010005C194B01380322084470B51D687F +:100D5000174BC5F30B042D0C1E88A6420BD15C6803 +:100D60000A46013C824213460FD214F9016F4EB17C +:100D700002F8016BF6E7013A03F10803ECD1814276 +:100D80000B4602D22C2203F8012B0424094A1688B0 +:100D9000AE4204D1984284BF967803F8016B013CBF +:100DA00002F10402F3D1581A70BD00BF0010005CBC +:100DB000182200208C300008022803D1024B4FF08B +:100DC00080629A61704700BF000C0258022803D16C +:100DD000024B4FF480629A61704700BF000C0258CA +:100DE000022804D1024A536983F480635361704737 +:100DF000000C0258002310B5934203D0CC5CC454BD +:100E00000133F9E710BD000002440346934202D0CB +:100E100003F8011BFAE770472DE9F8431F4D14460C +:100E20000746884695F8242052BBDFF870909CB3A3 +:100E300095F824302BB92022FF2148462F62FFF776 +:100E4000E3FF95F824004146C0F1080205EB80005D +:100E5000A24228BF2246D6B29200FFF7CBFF95F8F8 +:100E60002430A41B17441E449044E4B2F6B2082E6A +:100E700085F82460DBD1FFF74FFF0028D7D108E0C9 +:100E80002B6A03EB82038342CFD0FFF745FF002894 +:100E9000CBD10020BDE8F8830120FBE75C230020D4 +:100EA000024B1A78024B1A70704700BF9C23002037 +:100EB00010220020034B04490B60044B186800F01B +:100EC000C7BD00BF80841E008423002014220020A0 +:100ED000094B1822002110B504461846FFF794FF6D +:100EE000064A074B01461278046053F82200BDE819 +:100EF000104000F0ADBD00BF842300209C230020E3 +:100F000014220020F8B571B6002301201A461946B4 +:100F100000F04EFA0446802001F0EEF9002849D096 +:100F20000025254A80274FF4D06C3D26136913F025 +:100F3000C06F26D1D2F8103113F0C06F21D12368D1 +:100F400005F1006199602368D86023685F602368B9 +:100F5000C3F800C021680B6843F001030B602168EF +:100F60000B6823F01E030B6021680B68DB07FCD4C1 +:100F7000237B8035616806FA03F3B5F5001F0B602B +:100F8000D4D1204600F04AFAB5F5001F11D0002454 +:100F90000A4E0B4D012001F011F93388A34205D907 +:100FA00028682044013401F04FF8F6E7002001F0F2 +:100FB00005F961B6F8BD00BF002000529E23002055 +:100FC0005823002030B50A44084D91420DD011F845 +:100FD000013B5840082340F30004013B2C4013F030 +:100FE000FF0384EA5000F6D1EFE730BD2083B8ED6F +:100FF00008B5074B074A196801F03D01996053682D +:101000000BB190689847BDE8084001F07FBA00BF77 +:1010100000000240A023002008B5084B1968890988 +:1010200001F03D018A019A60054AD3680BB110694D +:101030009847BDE8084001F069BA00BF00000240CF +:10104000A023002008B5084B1968090C01F03D01E8 +:101050000A049A60054A53690BB190699847BDE844 +:10106000084001F053BA00BF00000240A023002056 +:1010700008B5084B1968890D01F03D018A059A6091 +:10108000054AD3690BB1106A9847BDE8084001F0E2 +:101090003DBA00BF00000240A023002008B5074B66 +:1010A000074A596801F03D01D960536A0BB1906A53 +:1010B0009847BDE8084001F029BA00BF000002408F +:1010C000A023002008B5084B5968890901F03D01AB +:1010D0008A01DA60054AD36A0BB1106B9847BDE804 +:1010E000084001F013BA00BF00000240A023002016 +:1010F00008B5084B5968090C01F03D010A04DA6093 +:10110000054A536B0BB1906B9847BDE8084001F05E +:10111000FDB900BF00000240A023002008B5084B25 +:101120005968890D01F03D018A05DA60054AD36BE3 +:101130000BB1106C9847BDE8084001F0E7B900BF5B +:1011400000000240A023002008B5074B074A196899 +:1011500001F03D019960536C0BB1906C9847BDE86C +:10116000084001F0D3B900BF00040240A0230020D2 +:1011700008B5084B1968890901F03D018A019A6098 +:10118000054AD36C0BB1106D9847BDE8084001F0DB +:10119000BDB900BF00040240A023002008B5084BE1 +:1011A0001968090C01F03D010A049A60054A536D63 +:1011B0000BB1906D9847BDE8084001F0A7B900BF9A +:1011C00000040240A023002008B5084B1968890DCF +:1011D00001F03D018A059A60054AD36D0BB1106E8E +:1011E0009847BDE8084001F091B900BF00040240F3 +:1011F000A023002008B5074B074A596801F03D01BC +:10120000D960536E0BB1906E9847BDE8084001F06D +:101210007DB900BF00040240A023002008B5084BA0 +:101220005968890901F03D018A01DA60054AD36EE7 +:101230000BB1106F9847BDE8084001F067B900BFD7 +:1012400000040240A023002008B5084B5968090C8F +:1012500001F03D010A04DA60054A536F0BB1906F4B +:101260009847BDE8084001F051B900BF00040240B2 +:10127000A023002008B5084B5968890D01F03D01F5 +:101280008A05DA60054AD36F13B1D2F88000984717 +:10129000BDE8084001F03AB900040240A023002054 +:1012A00000230C4910B51A460B4C0B6054F8230070 +:1012B000026001EB430004334260402BF6D1074A41 +:1012C0004FF0FF339360D360C2F80834C2F80C3497 +:1012D00010BD00BFA02300209C3000080000024089 +:1012E0000F28F8B510D9102810D0112811D01228C5 +:1012F00008D10F240720DFF8B4E00126DEF8005003 +:10130000A04208D9002649E00446F4E70F24002053 +:10131000F1E70724FBE706FA00F73D4240D1214CF4 +:101320004FEA001C3D4304EB00160EEBC000CEF864 +:101330000050C0E90123FBB24BB11B48836B43F063 +:1013400001038363036E43F001030366036E17F426 +:101350007F4F09D01448836B43F002038363036E0D +:1013600043F002030366036E54F80C00036823F095 +:101370001F030360056815F00105FBD104EB0C03A6 +:101380003D2493F80CC05F6804FA0CF43C602124FF +:101390000560446112B1987B00F08EF93046F8BDCB +:1013A0000130ADE79C30000800450258A023002022 +:1013B00010B5302484F31188FFF792FF002383F3E4 +:1013C000118810BD10B50446807B00F08BF9012315 +:1013D0001049627B03FA02F20B6823EA0203DAB2D5 +:1013E0000B604AB90C4A916B21F001019163116EB7 +:1013F00021F001011166126E13F47F4F09D1064BE3 +:101400009A6B22F002029A631A6E22F002021A66A6 +:101410001B6E10BDA02300200045025808B53023E4 +:1014200083F31188FFF7CEFF002383F3118808BDF3 +:10143000026843681143016003B118477047000018 +:10144000024A136843F0C0031360704700780040FD +:10145000024A136843F0C00313607047007C0040E9 +:1014600037B51A4C1A4D204600F0E6FA04F1140084 +:10147000009400234FF40072164900F0A3F94FF4D2 +:101480000072154904F138000094144B00F01CFA66 +:10149000134BC4E91735134C204600F0CDFA04F184 +:1014A000140000234FF400720F49009400F08AF9F1 +:1014B0000E4B4FF400720E4904F13800009400F016 +:1014C00003FA0C4BC4E9173503B030BD24240020C7 +:1014D00000E1F505FC240020FC2800204114000850 +:1014E0000078004090240020FC26002051140008C1 +:1014F000FC2A0020007C0040037C30B5274C0029EA +:1015000018BF0C46012B0CD1254B984236D1254BE8 +:101510009A6C42F080429A641A6F42F080421A67D5 +:101520001B6F2268036EC16D03EB52038466B3FB2D +:10153000F2F36268150442BF23F0070503F00703C6 +:1015400043EA4503CB60A36843F040034B60E36884 +:1015500043F001038B6042F4967343F001030B6088 +:101560004FF0FF330B62510505D512F0102211D058 +:10157000B2F1805F10D080F8643030BD0A4B9842E1 +:10158000CFD1084B9A6C42F000429A641A6F42F035 +:101590000042C4E77F23EEE73F23ECE79C310008DD +:1015A0002424002000450258902400202DE9F04713 +:1015B000C66D05463768F469210734621AD014F005 +:1015C000080118BF4FF48071E20748BF41F02001C5 +:1015D000A3074FF0300348BF41F04001600748BF08 +:1015E00041F0800183F31188281DFFF721FF0023BC +:1015F00083F31188E2050AD5302383F311884FF471 +:101600008061281DFFF714FF002383F311884FF03A +:1016100030094FF0000A14F0200838D13B0616D5E7 +:101620004FF0300905F1380A200610D589F31188EA +:10163000504600F07DF9002836DA0821281DFFF712 +:10164000F7FE27F080033360002383F311887906C7 +:1016500014D5620612D5302383F31188D5E91323FC +:101660009A4208D12B6C33B127F040071021281D76 +:10167000FFF7DEFE3760002383F31188E30618D5F9 +:10168000AA6E1369ABB15069BDE8F047184789F3FA +:101690001188736A284695F86410194000F0E6F93D +:1016A0008AF31188F469B6E7B06288F31188F469A7 +:1016B000BAE7BDE8F0870000090100F160430122AC +:1016C00003F56143C9B283F8001300F01F039A4089 +:1016D00043099B0003F1604303F56143C3F8802194 +:1016E0001A60704700F01F0301229A40430900F17D +:1016F00060409B0000F5614003F1604303F56143E6 +:10170000C3F88020C3F88021002380F8003370479D +:10171000F8B51546826804460B46AA4200D2856891 +:10172000A1692669761AB5420BD218462A46FFF7F8 +:1017300061FBA3692B44A3612846A3685B1BA360DC +:10174000F8BD0CD9AF1B18463246FFF753FB3A469B +:10175000E1683044FFF74EFBE3683B44EBE7184693 +:101760002A46FFF747FBE368E5E7000083689342FA +:10177000F7B50446154600D28568D4E90460361AE8 +:10178000B5420BD22A46FFF735FB63692B446361F0 +:101790002846A3685B1BA36003B0F0BD0DD9324699 +:1017A000AF1B0191FFF726FB01993A46E0683144EF +:1017B000FFF720FBE3683B44E9E72A46FFF71AFB03 +:1017C000E368E4E710B50A440024C361029B846027 +:1017D000C16002610362C0E90000C0E9051110BDEB +:1017E00008B5D0E90532934201D1826882B9826896 +:1017F000013282605A1C426119700021D0E9043222 +:101800009A4224BFC368436100F066FA002008BD15 +:101810004FF0FF30FBE7000070B5302304460E4662 +:1018200083F31188A568A5B1A368A269013BA360F1 +:10183000531CA36115782269934224BFE368A36116 +:10184000E3690BB120469847002383F311882846AB +:1018500007E03146204600F02FFA0028E2DA85F34F +:10186000118870BD2DE9F74F04460E46174698467D +:10187000D0F81C904FF0300A8AF311884FF0000B1B +:10188000154665B12A4631462046FFF741FF03461B +:1018900060B94146204600F00FFA0028F1D000233D +:1018A00083F31188781B03B0BDE8F08FB9F1000F06 +:1018B00003D001902046C847019B8BF31188ED1A95 +:1018C0001E448AF31188DCE7C160C361009B82601B +:1018D0000362C0E905111144C0E9000001617047CD +:1018E000F8B504460D461646302383F31188A768E1 +:1018F000A7B1A368013BA36063695A1C62611D70B4 +:10190000D4E904329A4224BFE3686361E3690BB10E +:1019100020469847002080F3118807E03146204692 +:1019200000F0CAF90028E2DA87F31188F8BD000058 +:10193000D0E9052310B59A4201D182687AB982684C +:101940000021013282605A1C82611C7803699A422C +:1019500024BFC368836100F0BFF9204610BD4FF07B +:10196000FF30FBE72DE9F74F04460E461746984631 +:10197000D0F81C904FF0300A8AF311884FF0000B1A +:10198000154665B12A4631462046FFF7EFFE03466D +:1019900060B94146204600F08FF90028F1D00023BD +:1019A00083F31188781B03B0BDE8F08FB9F1000F05 +:1019B00003D001902046C847019B8BF31188ED1A94 +:1019C0001E448AF31188DCE7026843681143016012 +:1019D00003B11847704700001430FFF743BF000001 +:1019E0004FF0FF331430FFF73DBF00003830FFF7F2 +:1019F000B9BF00004FF0FF333830FFF7B3BF00002E +:101A00001430FFF709BF00004FF0FF311430FFF72B +:101A100003BF00003830FFF763BF00004FF0FF3214 +:101A20003830FFF75DBF0000012914BF6FF01300CD +:101A300000207047FFF714BD044B03600023436090 +:101A4000C0E9023301230374704700BFB4310008BA +:101A500010B53023044683F31188FFF74DFD0223B0 +:101A60000020237480F3118810BD000038B5C369CD +:101A700004460D461BB904210844FFF7A5FF29467B +:101A800004F11400FFF7ACFE002806DA201D4FF425 +:101A90000061BDE83840FFF797BF38BD002382687A +:101AA000037503691B6899689142FBD25A68036009 +:101AB00042601060586070470023826803750369B4 +:101AC0001B6899689142FBD85A68036042601060B5 +:101AD0005860704708B50846302383F311880A7DA3 +:101AE0000023052A06D8DFE802F00B050503120ED5 +:101AF000826913604FF0FF338361FFF7CFFF00234C +:101B000083F3118808BD8269936801339360D0E93B +:101B1000003213605A60EDE7FFF7C0BF054BD9688C +:101B200008751868026853601A600122D86002754F +:101B3000FEF768BC002D00200C4B30B5DD684B1C57 +:101B400087B004460FD02B46094A684600F056F984 +:101B50002046FFF7E3FF009B13B1684600F058F9F9 +:101B6000A86907B030BDFFF7D9FFF9E7002D0020C5 +:101B7000D51A000838B50C4D04468161EB688168C0 +:101B80009A68914203D8BDE83840FFF787BF1846EE +:101B9000FFF792FF01230146EC6020462375BDE864 +:101BA0003840FEF72FBC00BF002D0020044B1A6800 +:101BB000DB6890689B68984294BF002001207047C2 +:101BC000002D0020084B10B51C68D86822685360AF +:101BD0001A600122DC602275FFF76EFF0146204685 +:101BE000BDE81040FEF70EBC002D002038B50123E3 +:101BF000084C00252370656000F05CFD00F082FD5C +:101C00000549064800F014FE0223237085F311886D +:101C100038BD00BF682F0020E0310008002D0020F3 +:101C200000F02CB98B600223086108468B82704754 +:101C30008368A3F1840243F8142C026943F8442C0E +:101C4000426943F8402C094A43F8242CC268A3F1A6 +:101C5000200043F8182C022203F80C2C002203F871 +:101C60000B2C034A43F8102C704700BF1D040008DA +:101C7000002D002008B5FFF7DBFFBDE80840FFF7A7 +:101C80004BBF0000024BDB6898610F20FFF746BF97 +:101C9000002D0020302383F31188FFF7F3BF0000ED +:101CA00008B50146302383F311880820FFF744FF6D +:101CB000002383F3118808BD064BDB6839B1426805 +:101CC00018605A60136043600420FFF735BF4FF07F +:101CD000FF307047002D00200368984206D01A6834 +:101CE0000260506018469961FFF716BF7047000008 +:101CF000036810B59C68A2420CD85C688A600B60CF +:101D00004C602160596099688A1A9A604FF0FF33DD +:101D1000836010BD121B1B68ECE700000A2938BF66 +:101D20000A2170B504460D460A26601900F0BCFC75 +:101D300000F0A4FC041BA54203D8751C04462E46E3 +:101D4000F3E70A2E04D90120BDE8704000F0B0BDD1 +:101D500070BD0000F8B5144B0D460A2A4FF00A0773 +:101D6000D96103F11001826038BF0A22416019690C +:101D70001446016048601861A81800F085FC00F066 +:101D80007DFC431B0646A34206D37C1C281927462C +:101D9000354600F089FCF2E70A2F04D90120BDE89E +:101DA000F84000F085BDF8BD002D0020F8B50646CE +:101DB0000D4600F063FC0F4A134653F8107F9F4214 +:101DC00006D12A4601463046BDE8F840FFF7C2BFBB +:101DD000D169BB68441A2C1928BF2C46A34202D9EA +:101DE0002946FFF79BFF224631460348BDE8F840ED +:101DF000FFF77EBF002D0020102D0020C0E9032337 +:101E0000002310B45DF8044B4361FFF7CFBF00001F +:101E100010B5194C236998420DD08168D0E9003281 +:101E200013605A609A680A449A60002303604FF076 +:101E3000FF33A36110BD0268234643F8102F53609F +:101E40000022026022699A4203D1BDE8104000F0EE +:101E500025BC936881680B44936000F00FFC2269F5 +:101E6000E1699268441AA242E4D91144BDE81040E5 +:101E7000091AFFF753BF00BF002D00202DE9F047DE +:101E8000DFF8BC8008F110072C4ED8F8105000F095 +:101E9000F5FBD8F81C40AA68031B9A423ED81444AC +:101EA0004FF00009D5E90032C8F81C4013605A60B1 +:101EB000C5F80090D8F81030B34201D100F0EEFB25 +:101EC00089F31188D5E9033128469847302383F3F5 +:101ED00011886B69002BD8D000F0D0FB6A69A0EBA9 +:101EE000040982464A450DD2022000F0E1FC00229E +:101EF000D8F81030B34208D151462846BDE8F04723 +:101F0000FFF728BF121A2244F2E712EB090929460B +:101F1000384638BF4A46FFF7EBFEB5E7D8F8103031 +:101F2000B34208D01444C8F81C00211AA960BDE8C7 +:101F3000F047FFF7F3BEBDE8F08700BF102D00208B +:101F4000002D002000207047FEE7000070470000D1 +:101F50004FF0FF3070470000BFF34F8F044B1A69FA +:101F60005107FCD1D3F810215207F8D1704700BFB8 +:101F70000020005208B50D4B1B78ABB9FFF7ECFF02 +:101F80000B4BDA68D10704D50A4A5A6002F188324D +:101F90005A60D3F80C21D20706D5064AC3F80421AB +:101FA00002F18832C3F8042108BD00BF702F002061 +:101FB000002000522301674508B5114B1B78F3B987 +:101FC000104B1A69510703D5DA6842F04002DA6013 +:101FD000D3F81021520705D5D3F80C2142F0400266 +:101FE000C3F80C21FFF7B8FF064BDA6842F0010294 +:101FF000DA60D3F80C2142F00102C3F80C2108BDCD +:10200000702F0020002000520F289ABF00F580603A +:1020100040040020704700004FF40030704700007B +:10202000102070470F2808B50BD8FFF7EDFF00F51B +:1020300000330268013204D104308342F9D1012017 +:1020400008BD0020FCE700000F2838B505463FD842 +:10205000FFF782FF1F4CFFF78DFF4FF0FF3307287C +:102060006361C4F814311DD82361FFF775FF0302C3 +:1020700043F02403E360E36843F08003E3602369F3 +:102080005A07FCD42846FFF767FFFFF7BDFF4FF460 +:10209000003100F0B3F92846FFF78EFFBDE8384065 +:1020A000FFF7C0BFC4F81031FFF756FFA0F10803D7 +:1020B0001B0243F02403C4F80C31D4F80C3143F074 +:1020C0008003C4F80C31D4F810315B07FBD4D9E796 +:1020D000002038BD002000522DE9F84F05460C467F +:1020E000104645EA0203DE0602D00020BDE8F88F64 +:1020F00020F01F00DFF8BCB0DFF8BCA0FFF73AFF0C +:1021000004EB0008444503D10120FFF755FFEDE73C +:1021100020222946204600F093FF10B920352034B4 +:10212000F0E72B4605F120021F68791CDDD104334E +:102130009A42F9D105F178431B481C4EB3F5801F34 +:102140001B4B38BF184603F1F80332BFD946D146BE +:102150001E46FFF701FF0760A5EB040C336804F18E +:102160001C0143F002033360231FD9F8007017F0FD +:102170000507FAD153F8042F8B424CF80320F4D111 +:10218000BFF34F8FFFF7E8FE4FF0FF3320222146C9 +:1021900003602846336823F00203336000F050FFE9 +:1021A0000028BBD03846B0E7142100520C20005262 +:1021B00014200052102000521021005210B5084C7B +:1021C000237828B11BB9FFF7D5FE0123237010BD7A +:1021D000002BFCD02070BDE81040FFF7EDBE00BF23 +:1021E000702F00202DE9F04F0D4685B0814658B183 +:1021F00011F00D0614BF2022082211F008030193EC +:1022000004D0431E03426AD0002435E0002E37D0AC +:1022100009F11F0121F01F094FF00108324F05F0AD +:102220000403DFF8D0A005EA080BBBF1000F32D0A1 +:102230007869C0072FD408F101080C37B8F1060FF0 +:10224000F3D19EB9294D4946A819019200F07CFAB4 +:10225000044600283AD11836019A782EF3D149461F +:1022600000F072FA0446002830D1019A494620480D +:1022700000F06AFA044668BB204605B0BDE8F08F5E +:102280000029C9D101462846029200F05DFA0446B1 +:10229000E0B9029AC0E713B178694107CBD5AC0722 +:1022A00002D578698007C6D5019911B1786901070F +:1022B000C1D51820494600FB08A0CDE9022300F053 +:1022C00043FA0446DDE902230028B4D04A4600213F +:1022D000204601E04A460021FEF796FDCCE7024683 +:1022E000002E95D198E700BFEC310008A42F002004 +:1022F000742F00208C2F00200121FFF773BF0000F6 +:10230000F8B5144D01241827134E40F2FF32002176 +:102310000120FEF779FD07FB046001342A6955F8B6 +:102320000C1F00F0FDF9062CF5D137254FF4C054F1 +:102330002046FFF7E1FF014628B122460748BDE8E5 +:10234000F84000F0EDB9C4EBC404013D4FEAD404F9 +:10235000EED1F8BDEC3100088C2F0020742F002046 +:102360000244074BD2B210B5904200D110BD441CBC +:1023700000B253F8200041F8040BE0B2F4E700BFCC +:10238000504000580E4B30B51C6F240405D41C6F10 +:102390001C671C6F44F400441C670A4C0244236809 +:1023A000D2B243F480732360074B904200D130BD1A +:1023B000441C51F8045B00B243F82050E0B2F4E74B +:1023C00000440258004802585040005807B5012206 +:1023D00001A90020FFF7C4FF019803B05DF804FBDA +:1023E00013B50446FFF7F2FFA04205D0012201A970 +:1023F00000200194FFF7C6FF02B010BD0144BFF3F7 +:102400004F8F064B884204D3BFF34F8FBFF36F8FBC +:102410007047C3F85C022030F4E700BF00ED00E035 +:10242000114BDA6952021ED59A69D00704D50F4ABA +:102430009A6002F144329A600B4BDA69D107FCD4FE +:102440001A6A22F480021A629A6942F002029A61C0 +:10245000DA69D207FCD49A6942F001029A61024A11 +:10246000D369DB07FCD47047002000523B2A1908CF +:10247000034B1A681AB9034AD2F8D0241A6070477D +:102480001C3000200040025808B5FFF7F1FF024B56 +:102490001868C0F3806008BD1C300020EFF309838A +:1024A000054968334A6B22F001024A6383F30988C5 +:1024B000002383F31188704700EF00E0302080F3A1 +:1024C000118862B60D4B0E4AD96821F4E061090407 +:1024D000090C0A430B49DA60D3F8FC2042F0807201 +:1024E000C3F8FC20084AC2F8B01F116841F001018E +:1024F00011602022DA7783F82200704700ED00E0B7 +:102500000003FA0555CEACC5001000E0302310B52D +:1025100083F311880E4B5B6813F4006314D0F1EE63 +:10252000103AEFF309844FF08073683CE361094B84 +:10253000DB6B236684F30988FFF738FB10B1064B89 +:10254000A36110BD054BFBE783F31188F9E700BFDA +:1025500000ED00E000EF00E02F0400083204000866 +:1025600070B5BFF34F8FBFF36F8F1A4A0021C2F8C7 +:102570005012BFF34F8FBFF36F8F536943F4003393 +:102580005361BFF34F8FBFF36F8FC2F88410BFF357 +:102590004F8FD2F8803043F6E074C3F3C900C3F321 +:1025A0004E335B0103EA0406014646EA81750139B0 +:1025B000C2F86052F9D2203B13F1200FF2D1BFF3E1 +:1025C0004F8F536943F480335361BFF34F8FBFF391 +:1025D0006F8F70BD00ED00E0FEE70000214B224848 +:1025E000224A70B5904237D3214BC11EDA1C121A11 +:1025F00022F003028B4238BF00220021FEF704FCC8 +:102600001C4A0023C2F88430BFF34F8FD2F88030C9 +:1026100043F6E074C3F3C900C3F34E335B0103EA2E +:102620000406014646EA81750139C2F86C52F9D2B6 +:10263000203B13F1200FF2D1BFF34F8FBFF36F8F09 +:10264000BFF34F8FBFF36F8F0023C2F85032BFF339 +:102650004F8FBFF36F8F70BD53F8041B40F8041BFE +:10266000C0E700BFA8330008C0300020C030002001 +:10267000C030002000ED00E000F018BA014B586AAD +:10268000704700BF000C0040034B002258631A61E2 +:102690000222DA60704700BF000C0040014B0022AC +:1026A000DA607047000C0040014B5863704700BF70 +:1026B000000C0040024B034A1A60034A5A607047FC +:1026C00020300020C030002000000220074B49428B +:1026D00010B55C68201A08401968821A8A4203D330 +:1026E000A24201D85A6010BD0020FCE72030002033 +:1026F00008B5302383F31188FFF7E8FF002383F345 +:10270000118808BD04480121044B03600023C0E97F +:1027100001330C3000F0D4B828300020F126000836 +:10272000CB1D083A23F00703591A521A012110B49D +:10273000D2080024C0E9004384600C301C605A6059 +:102740005DF8044B00F0BCB82DE9F84F364ECD1DB6 +:102750000F46002818BF0646082A4FEAD50538BF9D +:10276000082206F10C08341D9146404600F0C4F8DA +:1027700009F10701C9F1000E224624686CB94046F0 +:1027800000F0C4F83368CBB308224946E800984704 +:10279000044698B340E9026730E004EB010CD4F83A +:1027A00004A00CEA0E0C0AF10100ACF1080304EBE2 +:1027B000C0009842E0D9A0EB0C0CB5EBEC0F4FEA4F +:1027C000EC0BD9D89C421CD204F10802AB45A3EB18 +:1027D00002024FEAE202626009D9691CED432068F7 +:1027E00003EBC1025D44556043F8310022601C4692 +:1027F0005F60404644F8086B00F088F82046BDE86A +:10280000F88FAA45216802D111602346EFE7013510 +:1028100004EBC50344F8351003F10801401AC01059 +:1028200058601360F1E700BF28300020FEE7000089 +:1028300070B51B4B0025044686B058600E46856275 +:102840000163FFF73BFE04F11003A560E562C4E9F4 +:1028500004334FF0FF33C4E90044C4E90635FFF701 +:102860000DFF2B46024604F134012046C4E908233B +:1028700080230C4A2565FFF7D5F901230A4AE06059 +:1028800000920375684672680192B268CDE902232E +:10289000064BCDE90435FFF7EDF906B070BD00BF7A +:1028A000682F002034320008393200082D28000833 +:1028B000024AD36A1843D062704700BF002D00203F +:1028C000C0E90000816070478368013B002B10B5B0 +:1028D00083600CDA074BDC684368A06120606360AA +:1028E0001C6044600520FFF719F9A06910BD0020A5 +:1028F000FCE700BF002D002008B5302383F31188CA +:10290000FFF7E2FF002383F3118808BD08B53023E9 +:1029100083F3118883680133002B836007DC03682D +:1029200000211A68026050601846FFF723F900235F +:1029300083F3118808BD00004B6843608B68836097 +:10294000CB68C3600B6943614B6903628B69436267 +:102950000B6803607047000008B53C4B40F2FF7104 +:102960003B48D3F888200A43C3F88820D3F888204E +:1029700022F4FF6222F00702C3F88820D3F88830DF +:10298000344B1A6C0A431A649A6E0A439A66324AA6 +:102990009B6E1146FFF7D0FF00F5806002F11C012D +:1029A000FFF7CAFF00F5806002F13801FFF7C4FFAE +:1029B00000F5806002F15401FFF7BEFF00F5806072 +:1029C00002F17001FFF7B8FF00F5806002F18C01A1 +:1029D000FFF7B2FF00F5806002F1A801FFF7ACFF3E +:1029E00000F5806002F1C401FFF7A6FF00F58060EA +:1029F00002F1E001FFF7A0FF00F5806002F1FC01A9 +:102A0000FFF79AFF02F58C7100F58060FFF794FFE5 +:102A100000F00EF9114BD3F8902242F00102C3F8F6 +:102A20009022D3F8942242F00102C3F894220522A6 +:102A3000C3F898204FF06052C3F89C20084AC3F8AE +:102A4000A020BDE80840FFF7EBBC00BF00440258DF +:102A500000000258004502584032000800ED00E036 +:102A60001F00080308B500F0CFFAFFF7BFF80C4BC2 +:102A7000DA6B42F04002DA635A6E22F040025A6684 +:102A80005B6E084B1A6842F008021A601A6842F03E +:102A900004021A60FFF7ECFCBDE80840FFF730BC09 +:102AA0000045025800180248704700000E4B9A6C0F +:102AB00042F008029A641A6F42F008021A670B4A41 +:102AC0001B6FD36B43F00803D363C722084B9A6292 +:102AD0004FF0FF32DA6200229A615A63DA605A607C +:102AE00001225A611A607047004502580010005CCC +:102AF000000C0040094A08B51169D3680B40D9B2EF +:102B00009B076FEA0101116107D5302383F3118818 +:102B1000FFF786F8002383F3118808BD000C0040FE +:102B2000044BDA6B0243DA635A6E104358665B6EED +:102B3000704700BF0045025808B53C4B4FF0FF31CD +:102B4000D3F8802062F00042C3F88020D3F88020C0 +:102B500002F00042C3F88020D3F88020D3F884200C +:102B6000C3F88410D3F884200022C3F88420D3F85B +:102B70008400D86F40F0FF4040F4FF0040F4DF4095 +:102B800040F07F00D867D86F20F0FF4020F4FF00AE +:102B900020F4DF4020F07F00D867D86FD3F888009A +:102BA0006FEA40506FEA5050C3F88800D3F88800AD +:102BB000C0F30A00C3F88800D3F88800D3F8900067 +:102BC000C3F89010D3F89000C3F89020D3F8900089 +:102BD000D3F89400C3F89410D3F89400C3F8942069 +:102BE000D3F89400D3F89800C3F89810D3F898005D +:102BF000C3F89820D3F89800D3F88C00C3F88C1051 +:102C0000D3F88C00C3F88C20D3F88C00D3F89C0048 +:102C1000C3F89C10D3F89C10C3F89C20D3F89C30C8 +:102C2000FEF73EFBBDE8084000F0BEB90044025884 +:102C300008B50122504BC3F80821504B5A6D42F0A1 +:102C400002025A65DA6F42F00202DA670422DB6F91 +:102C50004B4BDA605A689104FCD54A4A1A6001224B +:102C60009A60494ADA6000221A614FF440429A6140 +:102C7000434B9A699204FCD51A6842F480721A6038 +:102C8000424B1A6F12F4407F04D04FF480321A671F +:102C900000221A671A6842F001021A603B4B1A6858 +:102CA0005007FCD500221A611A6912F03802FBD1D4 +:102CB000012119604FF0804159605A67344ADA6245 +:102CC000344A1A611A6842F480321A602F4B1A682B +:102CD0009103FCD51A6842F480521A601A68920473 +:102CE000FCD52D4A2D499A6200225A63196301F5D9 +:102CF0007C01DA6301F5E77199635A64284A1A6422 +:102D0000284ADA621A6842F0A8521A601F4B1A6801 +:102D100002F02852B2F1285FF9D148229A614FF4AB +:102D20008862DA6140221A621F4ADA641F4A1A6511 +:102D30001F4A5A651F4A9A6532231F4A1360136857 +:102D400003F00F03022BFAD1104A136943F0030377 +:102D50001361136903F03803182BFAD14FF00050B8 +:102D6000FFF7DEFE4FF08040FFF7DAFE4FF0004045 +:102D7000BDE80840FFF7D4BE00800051004502586E +:102D80000048025800C000F004000001004402584E +:102D90000000FF01008890083220600063020901F2 +:102DA000470E0508DD0BBF012000002000000110C8 +:102DB0000910E00000010110002000524FF0B04265 +:102DC00008B5D2F8883003F00103C2F8883023B187 +:102DD000044A13680BB150689847BDE80840FFF7F4 +:102DE00095BB00BF403000204FF0B04208B5D2F88C +:102DF000883003F00203C2F8883023B1044A936894 +:102E00000BB1D0689847BDE80840FFF77FBB00BF13 +:102E1000403000204FF0B04208B5D2F8883003F0BF +:102E20000403C2F8883023B1044A13690BB1506916 +:102E30009847BDE80840FFF769BB00BF403000205D +:102E40004FF0B04208B5D2F8883003F00803C2F85A +:102E5000883023B1044A93690BB1D0699847BDE823 +:102E60000840FFF753BB00BF403000204FF0B04296 +:102E700008B5D2F8883003F01003C2F8883023B1C7 +:102E8000044A136A0BB1506A9847BDE80840FFF73F +:102E90003DBB00BF403000204FF0B04310B5D3F829 +:102EA000884004F47872C3F88820A30604D5124A37 +:102EB000936A0BB1D06A9847600604D50E4A136B2B +:102EC0000BB1506B9847210604D50B4A936B0BB19D +:102ED000D06B9847E20504D5074A136C0BB1506CD0 +:102EE0009847A30504D5044A936C0BB1D06C98475E +:102EF000BDE81040FFF70ABB403000204FF0B04360 +:102F000010B5D3F8884004F47C42C3F888206205E9 +:102F100004D5164A136D0BB1506D9847230504D59F +:102F2000124A936D0BB1D06D9847E00404D50F4A57 +:102F3000136E0BB1506E9847A10404D50B4A936EE3 +:102F40000BB1D06E9847620404D5084A136F0BB1D9 +:102F5000506F9847230404D5044A936F0BB1D06F88 +:102F60009847BDE81040FFF7D1BA00BF40300020BD +:102F700008B50348FEF71AFBBDE80840FFF7C6BADC +:102F80002424002008B50348FEF710FBBDE80840E4 +:102F9000FFF7BCBA9024002008B5FFF7ABFDBDE8F1 +:102FA0000840FFF7B3BA0000062108B50846FEF74F +:102FB00083FB06210720FEF77FFB06210820FEF792 +:102FC0007BFB06210920FEF777FB06210A20FEF78E +:102FD00073FB06211720FEF76FFB06212820FEF762 +:102FE0006BFB09217A20FEF767FB07213220FEF7F1 +:102FF00063FB0C215220FEF75FFB0C215320BDE840 +:103000000840FEF759BB000008B5FFF795FD00F03A +:1030100009F8FEF70FFDFFF747FDBDE80840FFF791 +:103020002BBB00000023054A19460133102BC2E9CF +:10303000001102F10802F8D1704700BF40300020B3 +:1030400010B501390244904201D1002005E0037817 +:1030500011F8014FA34201D0181B10BD0130F2E757 +:1030600053544D333248373F3F3F0053544D333272 +:10307000483733782F3732780053544D333248373E +:1030800034332F3735332F373530000001105A00D5 +:103090000310590001205800032056001000024080 +:1030A000080002400008024000000B002800024017 +:1030B000080002400408024006010C0040000240E3 +:1030C000080002400808024010020D0058000240AB +:1030D000080002400C08024016030E007000024077 +:1030E0000C0002401008024000040F00880002405B +:1030F0000C0002401408024006051000A000024027 +:103100000C0002401808024010061100B8000240EE +:103110000C0002401C08024016072F001004024059 +:103120000804024020080240000838002804024039 +:103130000804024024080240060939004004024005 +:103140000804024028080240100A3A0058040240CD +:10315000080402402C080240160B3B007004024099 +:103160000C04024030080240000C3C00880402407D +:103170000C04024034080240060D4400A004024042 +:103180000C04024038080240100E4500B80402400A +:103190000C0402403C080240160F46000096000056 +:1031A000000000000000000000000000000000001F +:1031B0000000000000000000F5190008E1190008F7 +:1031C0001D1A0008091A0008151A0008011A00083B +:1031D000ED190008D9190008291A00086330000009 +:1031E000DC310008582D0020682F0020000000204E +:1031F0000000020002000000000000300000040097 +:103200000800000000000024000008000400000086 +:103210000004000000FC0000020000000000043078 +:1032200000800000080000000000003800000100DD +:10323000010000006D61696E0069646C650000004A +:103240000000002800000000AAAAAAAA000000248A +:10325000FFFF000000000000000000000000000070 +:1032600000000000AAAAAAAA00000000FFFF0000B8 +:10327000000000000000000000000000000000004E +:10328000AAAAAAAA00000000FFFF00000000000098 +:10329000000000000000100000000000AAAAAAAA76 +:1032A00000000000FFFF0000000000000000000020 +:1032B0000A80020000000000AAAAAAAA0540010094 +:1032C000FFFF000088000070070000000000000001 +:1032D00000000000AAAAAAAA00000000FFFF000048 +:1032E00000000000000000000000000000000000DE +:1032F000AAAAAAAA00000000FFFF00000000000028 +:10330000000000000000000000000000AAAAAAAA15 +:1033100000000000FFFF00000000000000000000AF +:103320000000000000000000AAAAAAAA00000000F5 +:10333000FFFF00000000000000000000000000008F +:1033400000000000AAAAAAAA00000000FFFF0000D7 +:10335000000000000000000000000000000000006D +:10336000AAAAAAAA00000000FFFF000000000000B7 +:1033700000000000000000002E040000000000001B +:1033800000001A0000000000FF00000024240020BC +:103390000000000060300008830400006B3000086B +:0833A000500400007930000820 :00000001FF diff --git a/Tools/bootloaders/CubeSolo_bl.bin b/Tools/bootloaders/CubeSolo_bl.bin index 0c2e9ac65cd3a9..b4ec2d94a1edd7 100755 Binary files a/Tools/bootloaders/CubeSolo_bl.bin and b/Tools/bootloaders/CubeSolo_bl.bin differ diff --git a/Tools/bootloaders/CubeSolo_bl.hex b/Tools/bootloaders/CubeSolo_bl.hex index bde42dfb8fde61..e096a9af73dc45 100644 --- a/Tools/bootloaders/CubeSolo_bl.hex +++ b/Tools/bootloaders/CubeSolo_bl.hex @@ -1,1019 +1,1009 @@ :020000040800F2 -:1000000000040020E10100081D0F0008210F000876 -:10001000750F0008210F0008490F0008E3010008D0 -:10002000E3010008E3010008E301000809280008D3 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008F9350008D6 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008713900089D39000838 -:10006000C9390008F5390008213A0008E301000801 +:10005000E3010008E3010008A9380008D1380008CE +:10006000F93800082139000849390008E30100087F :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E30100084D3A00080D +:10009000E3010008E3010008E301000871390008EA :1000A000E3010008E3010008E3010008E3010008A0 :1000B000E3010008E3010008E3010008E301000890 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E30100082511000839110008B8 -:1000E000B53A0008E3010008E3010008E301000855 +:1000D000E3010008E3010008453A0008E3010008D5 +:1000E000D5390008E3010008E3010008E301000836 :1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E301000881370008E30100086B +:10010000E3010008E3010008593A0008E301000890 :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008F52E0008C0 +:10014000E3010008E3010008E3010008A12D000815 :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E30100084D110008E301000845 +:10018000E3010008E3010008E3010008E3010008BF :10019000E3010008E3010008E3010008E3010008AF :1001A000E3010008E3010008E3010008E30100089F :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F017FB03F029FA4FF055301F495A -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE702F0B3 -:1002A000F5FA03F05FFA144C144DAC4203DA54F83B -:1002B000041B8847F9E700F03FF8114C114DAC42A0 -:1002C00003DA54F8041B8847F9E702F0DDBA0000AE -:1002D000000400200024002000000008000000208E -:1002E00000040020603F0008002400202824002093 -:1002F00028240020903D0020E0010008E0010008D3 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F0ECFE4B -:1003300001F09CFE00DFFEE770B5204C092300258C -:1003400023706FF03F061F236570A570E57025715F -:100350006571A571E57125726672A372E57200F090 -:10036000FFFC20B10F2325726672A372E57202F0C2 -:100370001DFA044602F042FA0546D8B9104B9C42D9 -:100380001AD001339C4218BF054641F2883404BF9D -:1003900001250024002002F013FA0DB100F0B6F898 -:1003A00000F062FD00F01AFC204600F00DF900F0AC -:1003B000ADF8F9E70024EDE70446EBE72824002038 -:1003C000010007B008B500F087FBA0F120035842F8 -:1003D000584108BD07B5054B02211B88ADF8043014 -:1003E00001A800F0E5FB03B05DF804FB9C3B0008AE -:1003F000064991F8243033B100230822086A81F8B5 -:10040000243000F00DBC0120704700BF48240020BC -:100410002DE9F84F234C94F82430054688461746BA -:100420008BBB2E46DFF87C90002F38D094F824A0A8 -:10043000BAF1000F05D12022FF214846266200F0C4 -:1004400001FDCAF10805BD4228BF3D465FFA85FBA4 -:10045000AD0041462A4604EB8A0000F0C9FC94F83E -:100460002430A7EB0B079B445FFA8BFBBBF1080F13 -:100470002E44A844FFB284F824B0D5D1FFF7B8FFCA -:100480000028D1D108E0266A06EB8306B042C9D025 -:10049000FFF7AEFF0028C4D10020BDE8F88F01208F -:1004A000BDE8F88F4824002010B5202383F311887D -:1004B0001248C3680BB101F0ADFE0023104A0F488B -:1004C0004FF47A7101F06AFE002383F311880D4C1A -:1004D000236813B12368013B2360636813B1636829 -:1004E000013B6360084B1B7833B9636823B9022072 -:1004F00000F074FC3223636010BD00BF3424002080 -:10050000A9040008782500207024002010B5254B90 -:10051000254953F8042F013200D110BD8B42F8D188 -:10052000224C234B22689A423AD9224B9B6803F112 -:10053000006303F580439A4232D2002000F068FB4A -:100540001D4B0220187000F03FFC1C4B1A6C00225F -:100550001A64196E1A66196E596C5A64596E5A6685 -:100560005A6E5A6942F080025A615A6922F080023A -:100570005A615A691A6942F000521A611A6922F0E6 -:1005800000521A611B6972B60D4A0E4B13601B684C -:100590002268202181F311889D4683F30888104743 -:1005A00010BD00BFFC3F00081C40000804400008CC -:1005B000FF3F00082824002070240020003802405B -:1005C00008ED00E0004000082DE9F04F99B0B34C71 -:1005D00001902022FF2110A8A66800F033FCB04A49 -:1005E0001378A346A3B9AF480121C360117020233B -:1005F00083F31188C3680BB101F00CFE0023AA4AF3 -:10060000A8484FF47A7101F0C9FD002383F31188E3 -:10061000019B13B1A54B019A1A60A54AA349019FFA -:100620000292002313704B6099461C461D46984663 -:10063000012000F0C9FB002F00F012829B4B1B68C9 -:10064000002B40F00D8219B0BDE8F08F0220FFF7BB -:10065000B9FE002840F0FB81019BB9F1000F08BFF3 -:100660001F46944B1B88ADF82C3002210BA800F0DC -:100670009FFADDE74FF47A7000F02EFA031E039321 -:10068000EADB0220FFF79EFE82460028E4D0039BAF -:10069000581E042800F2DD81DFE800F0030E11147B -:1006A000170018A8052340F8343D042100F080FA13 -:1006B00054464FF0000856E004217848F6E704213C -:1006C0007D48F3E704217D48F0E71C24204600F034 -:1006D000A1FA04340B9004210BA800F069FA2C2C29 -:1006E000F4D1E5E7002DB7D0002CB5D00220FFF7FC -:1006F00069FE0546002800F0AF8101206C4C00F037 -:1007000087FA0220207000F05FFB4FF000095FFACB -:1007100089FA504600F08CFA074658B1504600F06E -:1007200097FA09F101090028F1D12C46A9460027C2 -:10073000634B97E701230220237000F03BFB3E460A -:10074000DBF808309E4206D2304600F063FA0130F2 -:10075000EBD10436F4E7029B00261E70534BA946EA -:100760005E602C46374600F075FB15B1002C18BFB3 -:100770000027FFF72FFE5BE7002D3FF46DAF002C45 -:100780003FF46AAF029B0220187000F01DFB32207C -:1007900000F0A2F9B0F1000AC0F25E811AF0030580 -:1007A00040F05A81DBF8082006EB0A03934200F27E -:1007B0005381BAF5807F00F24F8155450DDA4FF431 -:1007C0007A7000F089F90490049B002BC0F24481F8 -:1007D0003C4A049BAB540135EFE7C820FFF7F2FD1C -:1007E0000546002800F038811F2E11D8C6F12004DC -:1007F000544528BF544610AB26F003002246314929 -:10080000184400F0F5FA2246FF212E4800F01AFBAA -:100810004FEAAA0A5FFA8AF22A493046FFF7F8FD42 -:100820000446002800F01A8106EB8A0605469AE77E -:100830000220FFF7C7FD00283FF40EAFFFF7D8FDF9 -:1008400000283FF409AF4FF0000A5346DBF80820B8 -:1008500092451CD2BAF11F0F12D8109A01320FD054 -:100860002AF0030218A90A4452F8202C0B921846C9 -:1008700004220BA900F092FB0AF1040A0346E5E703 -:100880005046039300F0C6F9039B0B90EFE718A8BE -:10089000042140F84C3D00F08BF964E72824002047 -:1008A0007425002034240020A904000878250020A5 -:1008B000702400209E3B00082C24002030240020BF -:1008C000A03B00087424002018A8002340F8343D01 -:1008D000642100F039F900287FF4BEAE0220FFF752 -:1008E00071FD00283FF4B8AE0B9800F0C3F918ABC7 -:1008F00043F8480D04211846CDE718A8002340F816 -:10090000343D642100F020F900287FF4A5AE0220D8 -:10091000FFF758FD00283FF49FAE0B9800F0B8F9A0 -:1009200018AB43F8440DE5E70220FFF74BFD002824 -:100930003FF492AE00F0B2F918AB43F8400DD9E79E -:100940000220FFF73FFD00283FF486AE0BA91420DC -:1009500000F0AAF9824618A8042140F83CAD00F046 -:1009600027F951460BA896E7322000F0B5F8B0F110 -:10097000000AFFF671AE1AF0030F7FF46DAEDBF8DC -:1009800008200AEB080393423FF666AE0220FFF709 -:1009900019FD00283FF460AE2AF0030AC244D04596 -:1009A0003FF4E1AE404600F035F904210A900AA870 -:1009B00000F0FEF808F10408F1E74FF47A70FFF751 -:1009C00001FD00283FF448AEFFF712FD00283FF478 -:1009D000AFAE109B01330CD0082210A90020FFF706 -:1009E00017FD00283FF4A4AE2022FF2110A800F03C -:1009F00029FAFFF7EFFC374801F08CFB23E6002DC6 -:100A00003FF42AAE002C3FF427AE18A8002340F88C -:100A1000343D642100F098F8824600287FF41CAE33 -:100A20000220FFF7CFFC00283FF416AE0390FFF73B -:100A3000D1FC41F2883001F06DFB0B9800F04EFACA -:100A400000F008FA039B57461C461D46F0E5054694 -:100A500089E64FF00008FFE52546FDE52C4667E6F0 -:100A6000002000F039F80490049B002BFFF6E3AD62 -:100A7000012000F09FF9049B213B122B3FF6D8ADDB -:100A800001A252F823F000BF4D06000875060008C9 -:100A9000E5060008310600083106000831060008A6 -:100AA000790700086909000831080008C90800082A -:100AB000FB08000829090008310600084109000860 -:100AC00031060008BB090008670700083106000866 -:100AD000FF090008A08601002DE9F34702AE0024BB -:100AE0004FF47A7506F8014D144FDFF858804543EE -:100AF00097F900305A1C5FFA84F901D0A34212D151 -:100B000058F8240003680122D3F820A031462B4670 -:100B1000D047012807D10A4B9DF8070083F80090C1 -:100B200002B0BDE8F0870134042CE1D14FF4FA7033 -:100B300001F0F0FA4FF0FF30F2E700BF0024002090 -:100B400098250020F43B00082DE9F0474FF47A7512 -:100B5000144FDFF8588006464D43002497F90030C3 -:100B60005A1C5FFA84F901D0A34210D158F824002E -:100B700003680422D3F820A031462B46D04704282E -:100B800005D1094B83F800900020BDE8F0870134BF -:100B9000042CE3D14FF4FA7001F0BCFA4FF0FF30AF -:100BA000BDE8F0870024002098250020F43B0008D1 -:100BB00030B4074B1A78074B53F822402368DD699D -:100BC000054B0A46AC460146204630BC604700BF94 -:100BD00098250020F43B0008A086010070B501F0C4 -:100BE000E1FC094C094E20700025306823788342CF -:100BF00008D901F0D1FC336805440133B5F5804FC5 -:100C00003360F2D370BD00BF9925002080250020FD -:100C100001F07EBD00F1006000F580400068704783 -:100C200000F10060920000F5804001F009BD000075 -:100C3000054B1A68054B1B789B1A834202D9104456 -:100C400001F0AABC002070478025002099250020D3 -:100C500038B5074D04462868204401F0A5FC28B9A2 -:100C600028682044BDE8384001F0B6BC38BD00BF5C -:100C70008025002010F0030308D1B0F5007F05D8CF -:100C800000F10050A0F50840006870470020704750 -:100C9000014BC058704700BF107AFF1F014B186806 -:100CA000704700BF002004E070B52A4B1C68C4F3F5 -:100CB0000B03240C63B140F21342934231D040F253 -:100CC000194293422FD040F2214293422DD1032367 -:100CD000214A0C2505FB03235D6893F9082042F2A5 -:100CE00001039C4224D0B4F5805F23D041F201037C -:100CF0009C4221D041F203039C421FD041F20703E2 -:100D00009C4208BF3122441E0C44013D0B46A342C5 -:100D10001ED215F9016F581C96B1034600F8016CFC -:100D2000F5E70123D4E70223D2E73F220B4DD6E7B4 -:100D30003322E3E74122E1E75A22E4E75922E2E7DE -:100D40002C2584421D7001D9981C5A70401A70BD20 -:100D50001846FBE7002004E0C43B0008A43B000861 -:100D6000124B5A8842F201018A4293B214D0B3F571 -:100D7000805F13D041F20102934211D041F203028D -:100D800093420FD041F2070293420DD10423084A47 -:100D900002EB8303D87870470023F8E70123F6E7D6 -:100DA0000223F4E70323F2E700207047002004E069 -:100DB000B03B0008022802BF024B4FF480529A61F8 -:100DC000704700BF00100240022802BF024B4FF0E4 -:100DD00080529A61704700BF00100240022801BF94 -:100DE000024A536983F480535361704700100240F4 -:100DF00010B50023934203D0CC5CC4540133F9E70F -:100E000010BD000030B5441E14F9010F0B4660B14F -:100E100093F90050854201F1010106D11AB993F905 -:100E20000020801A30BD013AEEE7002AF7D11046C3 -:100E300030BD000002460346981A13F9011B002931 -:100E4000FAD1704702440346934202D003F8011BD3 -:100E5000FAE77047024B1A78024B1A70704700BFCE -:100E60009825002000240020F8B5164C1648174D90 -:100E7000174E154F00F096FC2146134800F0BEFCBB -:100E800024681448626D936B23F40023936301F08C -:100E900041F92046104900F0BDFD626D936B43F4AB -:100EA000002393634FF4E1332B60002456F82400B1 -:100EB000B84202D0294600F0D3FB0134042CF5D10E -:100EC000F8BD00BFDC3C00089433002084250020DE -:100ED000F43B000840420F00083D000838B50B4BBA -:100EE0001A780B4B53F822400A4B9C4205460CD013 -:100EF000094B002118461422FFF7A4FF05600146A4 -:100F00002046BDE8384000F0ABBB38BD9825002036 -:100F1000F43B00089433002084250020FEE7000005 -:100F200000B59BB0EFF3098168226846FFF760FFC8 -:100F3000EFF30583034B9A6B9A6A9A6A9A6A9A6AE4 -:100F40009B6AFEE700ED00E000B59BB0EFF309817E -:100F500068226846FFF74CFFEFF30583044B9A6B5A -:100F60009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFC4 -:100F700000ED00E000B59BB0EFF309816822684600 -:100F8000FFF736FFEFF30583034B5A6B9A6A9A6AB1 -:100F90009A6A9A6A9B6AFEE700ED00E030B5084D58 -:100FA0000A4491420BD011F8013B09245840013CFE -:100FB000F7D040F300032B4083EA5000F7E730BD41 -:100FC0002083B8ED002304491A465A50C818083344 -:100FD000802B4260F9D170479C250020026843684D -:100FE0001143016003B1184770470000024AD368FB -:100FF00043F0C003D360704700440040024AD36806 -:1010000043F0C003D360704700480040024AD368F1 -:1010100043F0C003D3607047007800402DE9F041F1 -:10102000D0F85C64F7683368DA0505469CB20DD5E4 -:10103000202383F311884FF400710430FFF7CEFFB3 -:101040006FF480733360002383F31188202383F3CC -:10105000118805F1040814F02F0333D183F31188AC -:10106000380615D5210613D5202383F3118805F101 -:10107000380000F053FA002846DA0821281DFFF74F -:10108000ADFF4FF67F733B40F360002383F311887D -:101090007A060ED563060CD5202383F31188EA6CFB -:1010A0002B6D9A4202D12B6C002B2FD1002383F39E -:1010B0001188D5F86424D368002B31D01069BDE8BD -:1010C000F0411847230713D014F0080F0CBF00217C -:1010D0008021E00748BF41F02001A20748BF41F04E -:1010E0004001630748BF41F480714046FFF776FF37 -:1010F000A406736805D595F860142846194000F0D9 -:10110000BDFA3468A4B2A6E77060BEE727F04007D6 -:101110003F041021281D3F0CFFF760FFF760C5E773 -:10112000BDE8F08108B50348FFF778FFBDE8084047 -:1011300001F07ABB1C26002008B50348FFF76EFFBC -:10114000BDE8084001F070BB842A002008B50348C0 -:10115000FFF764FFBDE8084001F066BBEC2E0020FD -:1011600010B50E4C0E4A2046002100F057FA0D4BE8 -:10117000C4F85C340C4C0D4A2046002100F04EFAB5 -:101180000B4BC4F85C340B4C0B4A0021204600F09A -:1011900045FA0A4BC4F85C3410BD00BF1C26002081 -:1011A000ED0F000800440040842A0020FD0F0008D5 -:1011B00000480040EC2E00200D1000080078004090 -:1011C00038B5394D037C002918BF0D46012B044664 -:1011D000C0F8645410D1354B984242D1344B1A6C4C -:1011E00042F400321A641A6E42F400321A661B6E20 -:1011F0000B21262000F06AF82E4BD4F85C249A428A -:101200002B6802D02C498A424BD12C4901EB530167 -:10121000B1FBF3F3A988080442BF23F0070003F0F1 -:10122000070343EA40039360EB8843F040039BB21B -:1012300013612B8943F001039BB2536141F40453C2 -:1012400043F02C03D36001F4A05100231360B1F5E7 -:10125000806F136853680CBF7F23FF2384F86034CA -:1012600038BD174B98420CD1114B1A6C42F48022B6 -:101270001A641A6E42F480221A661B6E0B21272014 -:10128000B8E7104B9842B7D1094B1A6C42F0804234 -:101290001A641A6E42F080421A661B6E0B215220AD -:1012A000A8E70949B2E700BF243C00081C2600203B -:1012B00000380240001001400014014000BD01054B -:1012C000842A0020EC2E002080DE800200F16043A2 -:1012D00000F01F02400903F5614309018000C9B213 -:1012E00000F1604083F8001300F561400123934052 -:1012F000C0F8803103607047F8B51546826806690A -:10130000AA420B46816938BF8568761AB542044601 -:1013100007D218462A46FFF76BFDA3692B44A36149 -:101320000DE011D932461846FFF762FDAF1B3A4671 -:10133000E1683044FFF75CFDE2683A44A261A368CB -:101340005B1BA3602846F8BD18462A46FFF750FDF0 -:10135000E368E4E783682DE9F041044693421546CB -:10136000266938BF85684069361AB5420F4606D2ED -:101370002A46FFF73DFD63692B4463610DE012D9F6 -:101380003246A5EB0608FFF733FD4246B919E0687F -:10139000FFF72EFDE26842446261A3685B1BA36015 -:1013A0002846BDE8F0812A46FFF722FDE368E4E71E -:1013B00010B50A440024C361029B00604060846051 -:1013C000C160816141610261036210BD08B582693B -:1013D0004369934201D1826882B982680132826096 -:1013E0005A1C42611970426903699A4201D3C36869 -:1013F0004361002100F0AAFE002008BD4FF0FF303D -:1014000008BD000070B5202304460E4683F3118802 -:10141000A568A5B1A368A269013BA360531CA361A1 -:1014200015782269934224BFE368A361E3690BB195 -:1014300020469847002383F31188284670BD314623 -:10144000204600F073FE0028E2DA85F3118870BDB3 -:101450002DE9F74F05460F4690469A46D0F81C9066 -:10146000202686F311884FF0000B144664B1224603 -:1014700039462846FFF740FF034668B951462846DB -:1014800000F054FE0028F1D0002383F31188A8EB6C -:10149000040003B0BDE8F08FB9F1000F03D0019054 -:1014A0002846C847019B8BF31188E41A1F4486F332 -:1014B0001188DBE7C16081614161C3611144009B18 -:1014C000006040608260016103627047F8B50446C5 -:1014D0000E461746202383F31188A568A5B1A3689B -:1014E000013BA36063695A1C62611E7023696269D3 -:1014F0009A4224BFE3686361E3690BB120469847D1 -:10150000002080F31188F8BD3946204600F00EFE19 -:101510000028E2DA85F31188F8BD0000836942698A -:101520009A4210B501D182687AB98268013282602C -:101530005A1C82611C7803699A4201D3C368836193 -:10154000002100F003FE204610BD4FF0FF3010BD1B -:101550002DE9F74F05460F4690469A46D0F81C9065 -:10156000202686F311884FF0000B144664B1224602 -:1015700039462846FFF7EEFE034668B9514628462D -:1015800000F0D4FD0028F1D0002383F31188A8EBEC -:10159000040003B0BDE8F08FB9F1000F03D0019053 -:1015A0002846C847019B8BF31188E41A1F4486F331 -:1015B0001188DBE7026843681143016003B11847F3 -:1015C000704700001430FFF743BF00004FF0FF33B7 -:1015D0001430FFF73DBF00003830FFF7B9BF0000FF -:1015E0004FF0FF333830FFF7B3BF00001430FFF780 -:1015F00009BF00004FF0FF311430FFF703BF0000B8 -:101600003830FFF763BF00004FF0FF323830FFF78C -:101610005DBF000000207047FFF7A2BD37B50F4B3C -:101620000360002343608360C360012304460374A6 -:10163000154600900B464FF4007200F15C01143027 -:10164000FFF7B6FE00942B464FF4007204F51771B5 -:1016500004F13800FFF72EFF03B030BD383C00081E -:1016600010B52023044683F31188FFF7A9FD022358 -:101670002374002383F3118810BD000038B5C369BB -:1016800004460D461BB904210844FFF793FF294681 -:1016900004F11400FFF79AFE002806DA201D4FF42B -:1016A0008061BDE83840FFF785BF38BD02684368F8 -:1016B0001143016003B118477047000013B5446B34 -:1016C000D4F894341A681178042915D1217C0229A0 -:1016D00012D11979128901238B4013420CD101A92F -:1016E00004F14C0001F056FED4F89444019B21799A -:1016F0000246206800F0DAF902B010BD143001F0A3 -:10170000D9BD00004FF0FF33143001F0D3BD00000D -:101710004C3001F0ABBE00004FF0FF334C3001F015 -:10172000A5BE0000143001F0A7BD00004FF0FF314E -:10173000143001F0A1BD00004C3001F077BE000074 -:101740004FF0FF324C3001F071BE0000D0F894240D -:1017500038B5136819780429054601D0012038BD31 -:10176000017C0229FAD112795C8901209040044061 -:10177000F4D105F1140001F039FD02460028EDD046 -:10178000D5F894544FF480732868697900F07CF997 -:10179000204638BD406BFFF7D9BF000000207047DE -:1017A000704700007FB5124B0360002343608360E5 -:1017B000C360012502260F4B057404460290019375 -:1017C00000F18402294600964FF48073143001F032 -:1017D000E9FC094B0193029400964FF4807304F5E1 -:1017E0002372294604F14C0001F0B0FD04B070BD35 -:1017F000603C000895170008BD1600080B68202201 -:1018000082F311880A7903EB820290614A790932E6 -:1018100043F822008A7912B103EB82039861022314 -:101820000374C0F89414002383F3118870470000F8 -:1018300038B5037F044613B190F85430ABB9201D7E -:1018400001250221FFF732FF04F1140025776FF024 -:10185000010100F087FC84F8545004F14C006FF053 -:101860000101BDE8384000F07DBC38BD10B5012154 -:1018700004460430FFF71AFF0023237784F854301E -:1018800010BD000038B504460025143001F0A2FC5C -:1018900004F14C00257701F071FD201D84F85450AF -:1018A0000121FFF703FF2046BDE83840FFF74EBF98 -:1018B00090F8443003F06003202B19D190F84520B4 -:1018C000212A0AD0222A4FF000030ED0202A0FD15D -:1018D000084A82630722C26304E0064B836307233E -:1018E000C36300230364012070478363C363F9E784 -:1018F0000020704701240020D0F8943437B51A68CE -:101900001178042904461AD1017C022917D11979CA -:10191000128901238B40134211D100F14C05284656 -:1019200001F0ECFD58B101A9284601F033FDD4F8CF -:101930009444019B21790246206800F0B7F803B077 -:1019400030BD000000EB8103F7B59C6905460E46EB -:10195000F4B1202383F3118805EB8607201D0821AD -:10196000FFF7A4FEFB685B691B684C3413B120468B -:1019700001F01EFD01A9204601F00CFD024648B110 -:10198000019B3146284600F091F8002383F311882B -:1019900003B0F0BDFB685A691268002AF5D01B8AB3 -:1019A000013B1340F1D105F14402EAE7093138B5B2 -:1019B00050F82140DCB1202383F31188D4F894241B -:1019C0001368527903EB8203DB689B695D6845B15C -:1019D00004216018FFF76AFE294604F1140001F0A3 -:1019E0000FFC2046FFF7B2FE002383F3118838BDB9 -:1019F0007047000000F0D0BF012303700023436054 -:101A0000C36183620362C3624362036303814381F0 -:101A10007047000038B50446202383F31188002561 -:101A20004160C56005614561856100F0C5FF022325 -:101A3000237085F3118838BD70B500EB810305462E -:101A40005069DA600E46144618B110220021FFF7E3 -:101A5000F9F9A06918B110220021FFF7F3F9314616 -:101A60002846BDE8704001F071B80000028902F01C -:101A700001020281428902F00102428100220261D8 -:101A80004261826101F0F6B8F0B400EB810447894D -:101A9000E4680125A4698D403D434581236000230E -:101AA000A2606360F0BC01F011B90000F0B400EB7B -:101AB00081040789E468012564698D403D430581FF -:101AC00023600023A2606360F0BC01F08BB90000CA -:101AD00070B50223002504460370A0F84C5080F82E -:101AE0004E5080F84F5005814581C56005614561C4 -:101AF000856180F8345000F0C5FF63681B6823B12E -:101B000029462046BDE87040184770BD43680278FA -:101B10001B6880F85020052202700BB10421184781 -:101B200070470000436890F850201B6802700BB1AA -:101B3000052118477047000090F8343070B504460E -:101B400013B1002380F8343004F14402204601F040 -:101B5000B3F863689B6863BB94F8445015F0600663 -:101B600015D194F8453005F07F0545EA032540F28C -:101B700002339D4200F00E815BD8022D00F0DC8024 -:101B80003FD8002D00F08780012D00F0CF8000218C -:101B9000204601F0E9FA0021204601F0DBFA6368F3 -:101BA0001B6813B1062120469847062384F8343079 -:101BB00070BD204698470028CED094F84B2094F86A -:101BC0004A3043EA0223E26B934238BFE36394F95D -:101BD0004430E56B002B4FF0200380F2FD80002D98 -:101BE00000F0EC80092284F8342083F3118800216E -:101BF000E36BA26B2046FFF759FF002383F31188A4 -:101C000070BDB5F5817F00F0B180B5F5407F49D05A -:101C1000B5F5807FBBD194F84630012BB7D1B4F82D -:101C20004C3023F00203A4F84C30A663E66326642C -:101C3000C3E740F201639D421ED8B5F5C06F3BD2A9 -:101C4000B5F5A06FA3D1B4F84430B3F5A06F0ED1B1 -:101C500094F8463084F84E30204600F06BFF6368FD -:101C60001B6813B1012120469847032323700023EA -:101C7000A363E3632364A0E7B5F5106F32D040F6A9 -:101C800002439D4252D0B5F5006F80D104F14F035D -:101C9000A363012324E004F14C03A3630223E36361 -:101CA00025648AE794F84630012B7FF470AFB4F8CE -:101CB0004C3043F00203B6E794F84920616894F889 -:101CC00048304D6894F8471043EA0223204694F8C0 -:101CD0004620A84700283FF45AAF4368A36303682F -:101CE000E363A4E72378042B10D1202383F3118826 -:101CF0002046FFF7BBFE86F31188636884F84F60C7 -:101D00001B68032121700BB12046984794F8463098 -:101D1000002BACD084F84F300423237063681B6819 -:101D2000002BA4D0022120469847A0E7374BA3639D -:101D30000223E36300239DE794F8481011F0800F1D -:101D4000204601F00F010ED000F0A8FF012806D0B8 -:101D500002287FF41CAF2E4BA363E06367E72D4B93 -:101D6000A363E56363E700F08BFFEFE794F8463089 -:101D7000002B7FF40CAF94F8483013F00F013FF4C0 -:101D800076AF1A06204602D501F002FA6FE701F09D -:101D9000F5F96CE794F84630002B7FF4F8AE94F830 -:101DA000483013F00F013FF462AF1B06204602D506 -:101DB00001F0DAF95BE701F0CDF958E7142284F875 -:101DC000342083F311882B462A4629462046FFF704 -:101DD0005BFE85F3118870BD5DB1152284F8342057 -:101DE00083F311880021E36BA26B2046FFF74CFEC2 -:101DF00003E70B2284F8342083F311882B462A460C -:101E000029462046FFF752FEE3E700BF903C00085A -:101E1000883C00088C3C000838B590F83430044603 -:101E2000152B29D8DFE803F03E28282828283E284B -:101E3000280B293928282828282828283E3E90F8C9 -:101E40004B1090F84A20C36B42EA01229A4214D9FF -:101E5000C268128AB3FBF2F502FB15356DB9202377 -:101E600083F311882B462A462946FFF71FFE85F388 -:101E700011880A2384F8343038BD142384F83430B0 -:101E8000202383F3118800231A4619462046FFF7C2 -:101E9000FBFD002383F3118838BD036C03B1984721 -:101EA0000023E7E7002101F05FF90021204601F05F -:101EB00051F963681B6813B1062120469847062331 -:101EC000D8E7000090F83420152A38B5044622D807 -:101ED0000123934040F6416213421DD113F4801553 -:101EE0000FD19B0217D50B2380F83430202383F3C6 -:101EF00011882B462A462946FFF7D8FD85F311881D -:101F000038BDC3689B695B682BB9036C03B1984704 -:101F1000002384F8343038BD002101F025F9002178 -:101F2000204601F017F963681B6813B106212046AB -:101F300098470623EDE70000024B00221B605B6020 -:101F40009A60704754330020002303748268054B65 -:101F50001B6899689142FBD25A6803604260106026 -:101F6000586070475433002008B5202383F311884C -:101F7000037C032B05D0042B0DD02BB983F31188E0 -:101F800008BD436900221A604FF0FF334361FFF739 -:101F9000DBFF0023F2E790E80C001A600268536050 -:101FA000F2E70000002303748268054B1B68996800 -:101FB0009142FBD85A6803604260106058607047D5 -:101FC00054330020054B19690874186802681A60B8 -:101FD0005360186101230374FEF796B9543300204F -:101FE00030B54B1C87B005460A4C10D023690A4A0D -:101FF00001A800F0D3F82846FFF7E4FF049B13B1D3 -:1020000001A800F007F92369586907B030BDFFF750 -:10201000D9FFF8E754330020691F000838B50C4D8C -:1020200041612B6981689A689142044603D8BDE8F2 -:102030003840FFF789BF1846FFF786FF01232C6160 -:10204000014623742046BDE83840FEF75DB900BF65 -:1020500054330020044B1A681B6990689B689842AF -:1020600094BF0020012070475433002010B5084C65 -:10207000236820691A6822605460012223611A745F -:10208000FFF790FF01462069BDE81040FEF73CB91C -:10209000543300208260022202740022427470478E -:1020A0008368A3F17C0243F80C2C026943F83C2CB2 -:1020B000426943F8382C074A43F81C2CC26843F89D -:1020C000102C022203F8082C002203F8072CA3F19D -:1020D000180070472103000810B5202383F31188EE -:1020E000FFF7DEFF00210446FFF798FF002383F38C -:1020F0001188204610BD0000024B1B6958610F205B -:10210000FFF760BF54330020202383F31188FFF7CB -:10211000F3BF000008B50146202383F3118808208F -:10212000FFF75EFF002383F3118808BD49B1064B1A -:1021300042681B6918605A60136043600420FFF70F -:102140004FBF4FF0FF307047543300200368984270 -:1021500006D01A680260506059611846FFF7F4BE55 -:102160007047000038B504460D462068844200D10F -:1021700038BD036823605C604561FFF7E5FEF4E766 -:10218000054B03F114025A619A614FF0FF32DA6194 -:1021900000221A62704700BF54330020F8B5036173 -:1021A0001A4BC2605C6A1A4B1A46022952F8145F35 -:1021B00038BF0221954206461F460AD158619861F0 -:1021C0001C620560456081600819BDE8F84001F0B7 -:1021D000B7B9186AAB68241A0C1902D3E41A2D682F -:1021E00004E09C4202D2204401F0BAF9AB689C4260 -:1021F000F4D86B68736035601E606E60B460A96867 -:102200004FF0FF33091BA960FB61F8BD000C0040D3 -:102210005433002010B41A4C234653F8141F814243 -:1022200010D0416802680A60026851609A424FF01B -:102230000001C16003D0936881680B4493605DF82E -:10224000044B70470A68626100209A425360C8607C -:1022500003D15DF8044B01F07DB9936888680344AD -:102260009360084A206A526A121A9342E7D9991A6F -:10227000012998BF931C18445DF8044B01F070B914 -:1022800054330020000C004000207047FEE700009F -:10229000704700004FF0FF3070470000022906D061 -:1022A000032906D00129064818BF002070470548B9 -:1022B0007047032A9ABF044800EBC2000020704711 -:1022C000643D0008183D00080824002070B59AB04D -:1022D00001AD064608462946144600F095F8284602 -:1022E000FEF7A8FDC0B2431C5B0086E8180023700F -:1022F00003236370002302341946DAB2904204F1DA -:10230000020401D81AB070BDEA5C04F8022C04F88B -:10231000011C0133F1E7000008B5202383F3118885 -:102320000348FFF7E9FA002383F3118808BD00BFD3 -:102330009433002010B50446052916D8DFE801F0D3 -:1023400016150316161D202383F311880E4A01214A -:10235000FFF772FB20460D4A0221FFF76DFB0C4888 -:10236000FFF790FA002383F3118810BD202383F335 -:1023700011880748FFF75CFAF4E7202383F31188FC -:102380000348FFF773FAEDE7943C0008B83C0008F7 -:102390009433002038B50C4D0C4C0D492A4604F1FD -:1023A0000800FFF793FF05F1CA0204F11000094984 -:1023B000FFF78CFF05F5CA7204F118000649BDE865 -:1023C0003840FFF783BF00BF5C380020082400209E -:1023D000E43C0008F13C0008FE3C000870B50446EF -:1023E00008460D46FEF726FDC6B2204601340378A6 -:1023F0000BB9184670BD32462946FEF703FD00288A -:10240000F3D1012070BD00002DE9F84F05460C46C0 -:10241000FEF710FD2A49C6B22846FFF7DFFF08B1D4 -:102420000136F6B227492846FFF7D8FF08B1103623 -:10243000F6B2632E0DD8DFF88890DFF888A0224F1F -:10244000DFF88CB0DFF88C802E7846B92670BDE8B6 -:10245000F88F29462046BDE8F84F01F097BB252E9E -:1024600029D1072249462846FEF7CCFC40B9D8F8C6 -:1024700000302360D8F80430636007350834E3E7A0 -:10248000082251462846FEF7BDFCA0B90F4BA21CFE -:1024900013F8011F09095B45C95D02F8021C197890 -:1024A00001F00F0102F10202C95D02F8031CEFD135 -:1024B00018340835C8E7267001350134C4E700BF79 -:1024C000843D0008FE3C0008953D00080F7AFF1F80 -:1024D0001B7AFF1F8C3D0008BFF34F8F024AD36861 -:1024E000DB03FCD4704700BF003C024008B5094B39 -:1024F0001B7873B9FFF7F0FF074B1A69002ABFBFBB -:10250000064A5A6002F188325A601A6822F48062E0 -:102510001A6008BDBA3A0020003C0240230167451A -:1025200008B50B4B1B7893B9FFF7D6FF094B1A6917 -:1025300042F000421A611A6842F480521A601A6826 -:1025400022F480521A601A6842F480621A6008BD50 -:10255000BA3A0020003C0240172870B513D80B4A45 -:102560000B4C137863B90B4E4FF0006144F8231005 -:1025700056F823500133182B2944F7D10123137047 -:1025800054F8200070BD002070BD00BF1C3B00202F -:10259000BC3A0020A83D0008014B53F820007047CA -:1025A000A83D000818207047172810B5044601D927 -:1025B000002010BDFFF7D0FF064B53F8243018441D -:1025C000C21A0BB9012010BD12680132F0D1043BD0 -:1025D000F6E700BFA83D0008172810B5044629D823 -:1025E000FFF77AFFFFF782FF1349F323CB600C2339 -:1025F000B0FBF3F203FB1200D30143EAC003DBB2EA -:1026000043F4007343F002030B610B6943F480331E -:102610000B61FFF761FF2046FFF79EFF074B53F862 -:10262000241000F0DDF8FFF77BFF2046BDE81040E6 -:10263000FFF7BABF002010BD003C0240A83D0008D3 -:102640002DE9F84312F00103154640D18218B2F18A -:10265000026F3CD22C4B1B6813F0010337D02B4C7C -:10266000FFF744FFF323E360FFF736FF40F2012753 -:10267000032D01D9830713D0244C0F46401A40F292 -:102680000118EB1B0B44012B00EB0706236924D830 -:1026900023F001032361FFF743FF0120BDE8F88326 -:1026A000236923F44073236123693B43236151F879 -:1026B000046B0660BFF34F8FFFF70EFF03689E4267 -:1026C00008D0236923F001032361FFF729FF0020CD -:1026D000BDE8F883043D0430CAE723F44073236166 -:1026E000236943EA08032361B94637F8023B338084 -:1026F000BFF34F8FFFF7F0FE3688B9F80030B6B25F -:10270000B342BED0DDE700BF00380240003C0240CB -:10271000084908B50B7828B153B9FFF7E7FE012344 -:102720000B7008BD23B1BDE808400870FFF7F8BE84 -:1027300008BD00BFBA3A002010B50244064B043968 -:10274000D2B2904200D110BD441C00B253F8200018 -:1027500041F8040FE0B2F4E750280040104B30B5C8 -:102760001C6F240407D41C6F44F400741C671C6F96 -:1027700044F400441C670B4C236843F480732360CB -:102780000244094B0439D2B2904200D130BD441CFE -:1027900000B251F8045F43F82050E0B2F4E700BF04 -:1027A00000380240007000405028004007B5012268 -:1027B00001A90020FFF7C0FF019803B05DF804FBFA -:1027C00013B50446FFF7F2FFA04206D002A901228A -:1027D00041F8044D0020FFF7C1FF02B010BD00001A -:1027E00070470000034B1B689B0042BF024B012255 -:1027F0001A707047743802401D3B0020014B187856 -:10280000704700BF1D3B0020064A536823F00103B8 -:102810005360EFF30983683383F30988002383F35C -:102820001188704730EF00E010B5202383F3118842 -:10283000104B5B6813F4006318D0F1EE103AEFF31D -:1028400009844FF0807344F84C3C0B4BDB6844F830 -:10285000083CA4F1680383F30988FFF7FBFB18B178 -:10286000064B44F8503C10BD054BFAE783F3118842 -:1028700010BD00BF00ED00E030EF00E031030008C4 -:102880003403000870470000FEE70000084A094BC7 -:1028900009498B4204D3094A0021934205D370476A -:1028A00052F8040F43F8040BF3E743F8041BF4E772 -:1028B000843F0008903D0020903D0020903D002086 -:1028C000836D30B500229D68446D11464FF0FF3096 -:1028D00004EB421301329542C3F80019C3F81019F2 -:1028E000C3F80809C3F8001BC3F8101BC3F8080B92 -:1028F000EED24FF00113C4F81C3830BD890141F00D -:102900002001016103699B06FCD4122000F0B4BED3 -:10291000204B03EB80022DE9F047D2F80CE05D6D0F -:10292000DEF81420461CD2F800C005EB063605EB95 -:102930004018516861450BD3D5F83428012303FAB8 -:1029400000F022EA0000C5F834081846BDE8F08718 -:10295000BEF81040ACEB0103A34228BF2346D8F8D1 -:102960001849A4B2B3EB840F10D894681F46A4F1A1 -:10297000040959F804AFC6F800A0042F01D9043F98 -:10298000F7E71C440B4494605360D2E70020BDE895 -:10299000F08700BF203B002010B5054C2046FFF714 -:1029A0002BF84FF0A0436365024BA36510BD00BF39 -:1029B000203B00202C3E00080378012B70B5054613 -:1029C00050D12A4B446D98421BD1294B5A6B42F08F -:1029D00080025A635A6D42F080025A655A6D5A69F4 -:1029E00042F080025A615A6922F080025A610E2137 -:1029F00043205B69FEF76AFC1E4BE3601E4BC4F884 -:102A000000380023C4F8003EC02323606E6D4FF4ED -:102A10005023A3633369002BFCDA012333610C20BC -:102A200000F02AFE3369DB07FCD4122000F024FEFC -:102A30003369002BFCDA0026A6602846FFF740FF2A -:102A40006B68C4F81068DB68C4F81468C4F81C68C4 -:102A50004BB90A4BA3614FF0FF336361A36843F0A6 -:102A60000103A36070BD064BF4E700BF203B0020CC -:102A7000003802404014004003002002003C30C0F7 -:102A8000083C30C0F8B5446D054600212046FFF7EC -:102A900035FFA96D00234FF001128F68C4F8343858 -:102AA0004FF00066C4F81C284FF0FF3004EB4312CF -:102AB00001339F42C2F80069C2F8006BC2F80809EE -:102AC000C2F8080BF2D20B686A6DEB6563621023E3 -:102AD0001361166916F01006FBD1122000F0CCFD30 -:102AE000D4F8003823F4FE63C4F80038A36943F433 -:102AF000402343F01003A3610923C4F81038C4F83D -:102B000014380A4BEB604FF0C043C4F8103B084B3D -:102B1000C4F8003BC4F81069C4F80039EB6D03F148 -:102B2000100243F48013EA65A362F8BD083E000872 -:102B300040800010426D90F84E10D2F8003823F417 -:102B4000FE6343EA0113C2F8003870472DE9F041F3 -:102B50000EB200EB86080D46D8F80C100F6807F08F -:102B60000303022B50D0032B50D03D4A3D4F012B85 -:102B700018BF1746446D4FEA451E04EB0E030022B2 -:102B8000C3F8102B8A6905F1100C002A40D04A8A3C -:102B900005F158035B013A43E2500123D4F81C28A5 -:102BA00003FA0CF31343A6444A69C4F81C38002303 -:102BB000CEF8103905F13F03002A39D00A8A898BF3 -:102BC0009208012988BF4A43C16D04EB830356185C -:102BD00041EA0242C66529465A602046FFF78EFE4A -:102BE000D8F80C301B8A43EA85531F4305F148038C -:102BF0005B01E7500123D4F81C2803FA05F51543BF -:102C0000C4F81C58BDE8F081174FB3E7174FB1E780 -:102C100004EB4613D3F8002B22F40042C3F8002B38 -:102C2000D4F81C28012303FA0CF322EA0303BAE7C1 -:102C300004EB83030E4A5A6004EB461629462046ED -:102C4000FFF75CFED6F8003923F40043C6F80039DC -:102C5000D4F81C38012202FA05F523EA0505CFE76E -:102C600000800010008004100080081000800C100C -:102C700000040002826D1268C265FFF721BE0000E9 -:102C80005831436D49015B5813F4004004D013F4EC -:102C9000001F14BF01200220704700004831436D1F -:102CA00049015B5813F4004004D013F4001F14BF13 -:102CB000012002207047000000EB8101CB68196AF7 -:102CC0000B6813604B6853607047000000EB810392 -:102CD00030B5DD68AA691368D36019B9402B84BF89 -:102CE000402313606B8A1468426D1C44013CB4FBA2 -:102CF000F3F46343033323F0030302EB411043EA8D -:102D0000C44343F0C043C0F8103B2B6803F00303F7 -:102D1000012B09B20ED1D2F8083802EB411013F49E -:102D2000807FD0F8003B14BF43F0805343F0005342 -:102D3000C0F8003B02EB4112D2F8003B43F00443E1 -:102D4000C2F8003B30BD00002DE9F041244D6E6D0E -:102D500006EB40130446D3F8087BC3F8087B38071A -:102D60000AD5D6F81438190706D505EB8403214691 -:102D7000DB6828465B689847FA072FD5D6F81438E1 -:102D8000DB072BD505EB8403D968CCB98B69488A5E -:102D90005E68B6FBF0F200FB12628AB91868DA6866 -:102DA00090420DD2121A83E81400202383F3118875 -:102DB0000B482146FFF78AFF84F31188BDE8F081B4 -:102DC000012303FA04F26B8923EA02036B81CB68C7 -:102DD00023B121460248BDE8F0411847BDE8F08123 -:102DE000203B002000EB810370B5DD68436D6C690A -:102DF0002668E6604A0156BB1A444FF40020C2F828 -:102E000010092A6802F00302012A0AB20ED1D3F88F -:102E1000080803EB421410F4807FD4F8000914BFB3 -:102E200040F0805040F00050C4F8000903EB42121B -:102E3000D2F8000940F00440C2F80009D3F8340881 -:102E4000012202FA01F10143C3F8341870BD19B927 -:102E5000402E84BF4020206020682E8A841940F0D4 -:102E60000050013C1A44B4FBF6F440EAC440C6E703 -:102E7000F8B504461E48456D05EB4413D3F80869C0 -:102E8000C3F80869F10717D5D5F81038DA0713D554 -:102E900000EB8403D9684B691F68DA68974218D23F -:102EA000D21B00271A605F60202383F3118821461C -:102EB000FFF798FF87F31188330617D5D5F8342824 -:102EC0000123A340134211D02046BDE8F840FFF78C -:102ED0001FBD012303FA04F2038923EA02030381DD -:102EE0008B68002BE8D021469847E5E7F8BD00BF86 -:102EF000203B002096482DE9F84F456D6E69AB697F -:102F00001E4016F4805F6E61044605D0FEF7E0FDBA -:102F1000BDE8F84FFFF788BC002E12DAD5F8003E66 -:102F20008B489B071EBFD5F8003E23F00303C5F86E -:102F3000003ED5F8043823F00103C5F80438FEF745 -:102F4000F1FD370502D58248FEF7E0FDB0040CD54F -:102F5000D5F8083813F0060FEB6823F470530CBF54 -:102F600043F4105343F4A053EB60310704D5636876 -:102F7000DB680BB176489847F2025AD4B3020CD5FD -:102F8000D4F85480DFF8C8A100274FF00109A36DE1 -:102F90009B68F9B28B4280F08780F70619D5616D86 -:102FA0000A6AC2F30A1702F00F0302F4F012B2F534 -:102FB000802F00F0A180B2F5402F0AD104EB8303EB -:102FC00001F58051DB68186A00231A469F4240F0E1 -:102FD00087803003D5F8184813D5E10302D50020C7 -:102FE000FFF7B2FEA20302D50120FFF7ADFE630397 -:102FF00002D50220FFF7A8FE270302D50320FFF722 -:10300000A3FE750384D5E00702D50020FFF730FF4B -:10301000A10702D50120FFF72BFF620702D502208E -:10302000FFF726FF23077FF573AF0320FFF720FF8D -:103030006EE7D4F85480DFF818A100274FF001099B -:10304000A36D9B685FFA87FB5B4597D308EB4B1337 -:10305000D3F8002902F44022B2F5802F22D1D3F810 -:103060000029002A1EDAD3F8002942F09042C3F862 -:103070000029D3F80029002AFBDB5946606DFFF7D1 -:103080003DFC228909FA0BF322EA0303238104EBB6 -:103090008B03DB689B6813B15946504698475846E6 -:1030A000FFF736FC0137CBE708EB4112D2F8003BC3 -:1030B00003F44023B3F5802F10D1D2F8003B002B4E -:1030C0000CDA628909FA01F322EA0303638104EB53 -:1030D0008103DB68DB680BB150469847013756E740 -:1030E0009C0708BF0A68072B98BF027003F1010311 -:1030F0009CBF120A013069E7023304EB830201F539 -:103100008051526890690268D0F808C04068A2EB0C -:10311000000E0022104697420AD104EB8304636834 -:103120009B699A683A449A605A6817445F6050E70E -:1031300012F0030F08BF0868964588BF8CF800009E -:1031400002F1010284BF000A0CF1010CE3E700BFA9 -:10315000203B0020436D03EB4111D1F8003B43F4C9 -:103160000013C1F8003B7047436D03EB4111D1F8E8 -:10317000003943F40013C1F800397047436D03EB85 -:103180004111D1F8003B23F40013C1F8003B704714 -:10319000436D03EB4111D1F8003923F40013C1F85A -:1031A0000039704730B5039C0172043304FB0325DA -:1031B000C361049B03630021059B00604060C16004 -:1031C000426102618561046242628162C16243635D -:1031D00030BD00000022416A41610161C26082622B -:1031E000C2626FF00101FEF7BDBF000003694269D2 -:1031F000934203D1C2680AB100207047181D70477E -:1032000003691960C2680132C260C26913448269ED -:103210000361934224BF436A03610021FEF796BF16 -:1032200038B504460D46E3683BB16269131D126868 -:10323000A3621344E362002038BD237A33B92946E0 -:103240002046FEF773FF0028EDDA38BD6FF001006D -:10325000FBE70000C368C269013BC36043691344D4 -:1032600082694361934224BF436A436100238362BE -:10327000036B03B11847704770B52023044683F3EE -:103280001188866A3EB9FFF7CBFF054618B186F371 -:103290001188284670BDA36AE26A13F8015BA36235 -:1032A000934202D32046FFF7D5FF002383F3118812 -:1032B000EFE700002DE9F84F04460E469046994688 -:1032C000202787F311880025AA46D4F828B0BBF13F -:1032D000000F09D149462046FFF7A2FF20B18BF32A -:1032E00011882846BDE8F88FA16AE36AA8EB050BB0 -:1032F0005B1A9B4528BF9B46BBF1400F1BD9334649 -:1033000001F1400251F8040B43F8040B9142F9D14A -:10331000A36A40334036A3624035A26AE36A9A4208 -:1033200002D32046FFF796FF8AF311884545D8D28D -:1033300087F31188C9E730465A46FDF759FDA36A5D -:103340005B445E44A3625D44E7E7000010B5029C65 -:103350000172043303FB0421C36100238362C3624F -:10336000039B0363049B00604060C4604261026190 -:10337000816104624262436310BD0000026AC26060 -:10338000426A4261026100228262C2626FF0010100 -:10339000FEF7E8BE436902699A4203D1C2680AB1E6 -:1033A00000207047184650F8043B0B60704700003F -:1033B000C368C2690133C3604369134482694361CE -:1033C000934224BF436A43610021FEF7BFBE000061 -:1033D00038B504460D46E3683BB123691A1DA26265 -:1033E000E2691344E362002038BD237A33B92946E9 -:1033F0002046FEF79BFE0028EDDA38BD6FF0010095 -:10340000FBE7000003691960C268013AC260C26943 -:10341000134482690361934224BF436A036100231A -:103420008362036B03B118477047000070B5202317 -:1034300004460E4683F31188856A35B91146FFF7B5 -:10344000C7FF10B185F3118870BDA36A1E70A36A0F -:10345000E26A01339342A36204D3E169204604394E -:10346000FFF7D0FF002080F3118870BD2DE9F84FE1 -:1034700004460D4691469A464FF0200888F311887D -:103480000026B346A76A4FB951462046FFF7A0FF72 -:1034900020B187F311883046BDE8F88FA06AE76A4B -:1034A000A9EB06033F1A9F4228BF1F46402F1BD996 -:1034B00005F1400355F8042B40F8042B9D42F9D147 -:1034C000A36A4033A3624036A26AE36A9A4204D3F5 -:1034D000E16920460439FFF795FF8BF311884E45CB -:1034E000D9D288F31188CDE729463A46FDF780FC0A -:1034F000A36A3B443D44A3623E44E5E70269436955 -:103500009A4203D1C3681BB9184670470023FBE7F2 -:10351000836A002BF8D0043B9B1AF5D01360C36874 -:10352000013BC360C3691A44836902619A4224BFA4 -:10353000436A0361002383620123E5E700F034B9A5 -:10354000034B002258631A610222DA60704700BF01 -:10355000000C0040014B0022DA607047000C004074 -:10356000014B5863704700BF000C0040FEE70000AD -:1035700010B5174CFEF7E0FCFEF702FE802215495D -:103580002046FEF787FD012344F8180C0374124B04 -:10359000124AD96821F4E0610904090C0A43104970 -:1035A000DA60CA6842F08072CA600E490A6842F066 -:1035B00001020A601022DA77202283F822200023F9 -:1035C00083F3118862B60848BDE81040FEF784BD59 -:1035D0007C330020383E000800ED00E00003FA05CF -:1035E000F0ED00E0001000E0403E00082DE9F84F4B -:1035F0001F4CDFF88090656904F114074FF0000854 -:10360000D9F82430266AAA689E1B96421DD34FF033 -:10361000200AAA68236AD5F80CB0134423622B68E9 -:10362000BB425F60A6EB02066361C5F80C8001D166 -:10363000FFF790FF88F311882869D8478AF311882B -:103640006569AB689E42E4D2DAE76269BA420CD09F -:10365000916823628E1B9660A86802282CBF1818F8 -:10366000981CBDE8F84FFFF77BBFBDE8F88F00BF9F -:1036700054330020000C0040034B59685A68521A1A -:103680009042FBD8704700BF001000E04B684360D9 -:103690008B688360CB68C3600B6943614B690362CD -:1036A0008B6943620B6803607047000008B5224BCA -:1036B00022481A6940F2FF110A431A611A6922F47A -:1036C000FF7222F001021A611A691A6B0A431A6327 -:1036D0001A6D0A431A651A4A1B6D1146FFF7D6FF89 -:1036E000184802F11C01FFF7D1FF174802F1380119 -:1036F000FFF7CCFF154802F15401FFF7C7FF14484C -:1037000002F17001FFF7C2FF124802F18C01FFF7CE -:10371000BDFF114802F1A801FFF7B8FF0F4802F101 -:10372000C401FFF7B3FF0E4802F1E001FFF7AEFF5F -:10373000BDE8084000F0A4B8003802400000024094 -:10374000603E00080004024000080240000C0240F5 -:10375000001002400014024000180240001C024009 -:103760000020024008B500F0FFF9FFF701FFFFF766 -:1037700039F8BDE80840FEF70DBE000070470000B4 -:10378000084B1A69920710B508D500241C61202344 -:1037900083F31188FFF72AFF84F31188BDE81040F6 -:1037A000FFF742B8000C0040104B1A6C42F00802C0 -:1037B0001A641A6E42F008021A660D4A1B6E93686C -:1037C00043F0080393600B4B53229A624FF0FF3291 -:1037D000DA6200229A615A63DA605A6001225A6101 -:1037E00008211A603220FDF771BD00BF0038024089 -:1037F000002004E0000C00401F4B1A696FEAC2521F -:103800006FEAD2521A611A69C2F308021A614FF0C4 -:10381000FF301A695A69586100215A6959615A6919 -:103820001A6A62F080521A621A6A02F080521A62B0 -:103830001A6A5A6A58625A6A59625A6A1A6C42F08B -:1038400080521A641A6E42F080521A661A6E0B4A3F -:10385000106840F480701060186F00F44070B0F58C -:10386000007F1EBF4FF4803018671967536823F438 -:103870000073536000F058B90038024000700040F7 -:10388000324B4FF080521A64314A4FF4404111607C -:103890001A6842F001021A601A689207FCD59A6809 -:1038A00022F003029A60294B19469A6812F00C0222 -:1038B000FBD1186800F0F90018609A601A6842F4A9 -:1038C00080321A600B689B03FCD54B6F43F00103F9 -:1038D0004B671E4B5A6F9007FCD51E4A5A601A68F8 -:1038E00042F080721A601A4A53685904FCD5174B8B -:1038F0001A689201FCD5184A9A600322C3F88C20FA -:10390000164B1A68164B9A42164B1BD1164A116871 -:10391000164A914216D140F205121A600B4B9A6872 -:1039200042F002029A609A6802F00C02082AFAD168 -:103930005A6C42F480425A645A6E42F480425A668B -:103940005B6E704740F20572E7E700BF0038024047 -:10395000007000401854400700948838002004E0AC -:1039600011640020003C024000ED00E041C20F4124 -:10397000084A08B5536911680B4003F0010353610D -:1039800023B1054A13680BB150689847BDE8084059 -:10399000FEF74ABF003C01409C250020084A08B5BC -:1039A000536911680B4003F00203536123B1054AC8 -:1039B00093680BB1D0689847BDE80840FEF734BF64 -:1039C000003C01409C250020084A08B55369116855 -:1039D0000B4003F00403536123B1054A13690BB193 -:1039E00050699847BDE80840FEF71EBF003C014003 -:1039F0009C250020084A08B5536911680B4003F064 -:103A00000803536123B1054A93690BB1D069984704 -:103A1000BDE80840FEF708BF003C01409C2500209F -:103A2000084A08B5536911680B4003F0100353614D -:103A300023B1054A136A0BB1506A9847BDE80840A4 -:103A4000FEF7F2BE003C01409C250020174B10B54C -:103A50005C691A68144004F478725A61A30604D5AC -:103A6000134A936A0BB1D06A9847600604D5104A8E -:103A7000136B0BB1506B9847210604D50C4A936B1E -:103A80000BB1D06B9847E20504D5094A136C0BB112 -:103A9000506C9847A30504D5054A936C0BB1D06CC4 -:103AA0009847BDE81040FEF7BFBE00BF003C014094 -:103AB0009C2500201A4B10B55C691A68144004F468 -:103AC0007C425A61620504D5164A136D0BB1506DE4 -:103AD0009847230504D5134A936D0BB1D06D9847D1 -:103AE000E00404D50F4A136E0BB1506E9847A10441 -:103AF00004D50C4A936E0BB1D06E9847620404D57E -:103B0000084A136F0BB1506F9847230404D5054A38 -:103B1000936F0BB1D06F9847BDE81040FEF784BE9D -:103B2000003C01409C250020062108B50846FDF711 -:103B3000CDFB06210720FDF7C9FB06210820FDF774 -:103B4000C5FB06210920FDF7C1FB06210A20FDF770 -:103B5000BDFB06211720FDF7B9FB06212820BDE893 -:103B60000840FDF7B3BB000008B5FFF745FEFDF7C1 -:103B700029FAFDF751FDFDF73DFFFDF711FEFFF7B7 -:103B8000FDFDBDE80840FFF7D9BC0000034611F871 -:103B9000012B03F8012B002AF9D1704712101213E0 -:103BA0001211000053544D3332463F3F3F00000096 -:103BB000012033000010410101105A010310590186 -:103BC0000710310100000000A43B00083F00000086 -:103BD00013040000043C00083F000000190400002A -:103BE0000E3C00083F00000021040000183C0008C3 -:103BF0003F000000943300201C260020842A00206F -:103C0000EC2E002053544D33324634307800535458 -:103C10004D3332463432780053544D3332463434C7 -:103C20003658580000960000000000000000000018 -:103C3000000000000000000000000000E115000886 -:103C4000CD15000809160008F51500080116000832 -:103C5000ED150008D9150008C5150008151600084F -:103C60000000000019170008051700084117000898 -:103C70002D1700083917000825170008111700082C -:103C8000FD1600089D17000800000000010000005C -:103C900000000000020000000000000045190008BC -:103CA000AD190008400040002C3800203C380020AE -:103CB00002000000000000000300000000000000FF -:103CC000F119000800000000100000004C3800202E -:103CD000000000000100000000000000203B002068 -:103CE000010102004865782F50726F6669434E43A8 -:103CF0000043756265426C61636B2D424C00255335 -:103D0000455249414C250000352300089D220008FA -:103D1000B11800081923000843000000203D0008E6 -:103D200009024300020100C032090400000102023E -:103D300001000524001001052401000104240202F1 -:103D40000524060001070582030800FF090401009D -:103D5000020A000000070501024000000705810279 -:103D600040000000120000006C3D0008120110012C -:103D700002000040AE2D011000020102030100000C -:103D80000403090425424F415244250043756265EE -:103D9000536F6C6F00303132333435363738394138 -:103DA000424344454600000000400000004000003F -:103DB0000040000000400000000001000000020080 -:103DC00000000200000002000000020000000200EB -:103DD000000002000000020000400000004000005F -:103DE0000040000000400000000001000000020050 -:103DF00000000200000002000000020000000200BB -:103E0000000002000000020000000000391B000852 -:103E1000191E0008C51E000840004000803B00201D -:103E2000803B002001000000903B0020800000004B -:103E300040010000030000006D61696E0000000099 -:103E4000583E0008983B0020903D002001000000F3 -:103E50006D3500080000000069646C65000000001A -:103E60000000812A00020000AAAAAAAA00000000FD -:103E7000FFFF00000000000000A00A00000000009A -:103E800000000000AAAAAAAA00000000FFFF00008C -:103E900000000000000000001400005400000000BA -:103EA000AAAAAAAA14000054FFFF00000000000004 -:103EB0000000000080699A0100000000AAAA8AAAF6 -:103EC00040555501FFFF000000707007777000003B -:103ED0004081020100000000AAAAAAAA0041010034 -:103EE000F7FF000000000080080000000000000054 -:103EF00000000000AAAAAAAA00000000FFFF00001C -:103F000000000000000000000000000000000000B1 -:103F1000AAAAAAAA00000000FFFF000000000000FB -:103F20000000000000000000000000000A00000087 -:103F3000000000000300000000000000000000007E -:103F40000000000000000000000000000000000071 -:103F50000000000000000000000000000000000061 -:103F6000FF0096000000000804000000803D0008EB -:103F70000000000000000000000000000000000041 -:083F8000000000000000000039 +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F070FA05 +:1002500003F070F94FF055301F491B4A91423CBFE3 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F04EFA03F09EF976 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F036BA000600200022002035 +:1002D0000000000808ED00E00000002000060020FB +:1002E000983E0008002200204C22002050220020CE +:1002F00020310020E0010008E0010008E0010008D2 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F098FDFEE701F063 +:1003300027FD00DFFEE7000038B500F0DFFB02F02C +:10034000CBF940B1164B6FF03F01002259720F21DB +:100350001A729972DA7202F0A5F9054602F0DEF916 +:100360000446C8B90F4B9D4218D001339D4218BFB7 +:10037000044641F2883504BF01240025002002F024 +:100380009BF90CB100F076F800F018FD284600F05B +:10039000C1F800F06FF8F9E70025EFE70546EDE753 +:1003A00000220020010007B008B500F073FBA0F1A7 +:1003B00020035842584108BD07B541F212030221FB +:1003C00001A8ADF8043000F083FB03B05DF804FB36 +:1003D00038B5302383F31188174803680BB101F057 +:1003E00009FE164A144800234FF47A7101F0F8FD13 +:1003F000002383F31188124C236813B12368013B57 +:100400002360636813B16368013B63600D4D2B7813 +:1004100033B963687BB9022000F03AFC3223636091 +:100420002B78032B07D163682BB9022000F030FC36 +:100430004FF47A73636038BD50220020D103000866 +:100440007023002068220020084B187003280CD865 +:10045000DFE800F008050208022000F00FBC0220CF +:1004600000F002BC024B00225A6070476822002054 +:1004700070230020234B244A10B51C461968013113 +:100480003FD004339342F9D16268A24239D31F4B63 +:100490009B6803F1006303F580439A4231D2002048 +:1004A00000F046FB0220FFF7CFFF194B1A6C002229 +:1004B0001A64196E1A66196E596C5A64596E5A6626 +:1004C0005A6E5A6942F080025A615A6922F08002DB +:1004D0005A615A691A6942F000521A611A6922F087 +:1004E00000521A611B6972B64FF0E0233021C3F845 +:1004F000084DD4E9003281F311889D4683F30888C2 +:10050000104710BD004000082040000800220020D5 +:10051000003802402DE9F04F93B0AA4B0090202202 +:10052000FF210AA89D6800F0F3FBA74A1378A3B93E +:10053000A648012103601170302383F311880368FA +:100540000BB101F057FDA24AA04800234FF47A7185 +:1005500001F046FD002383F31188009B13B19D4BEE +:10056000009A1A609C4A009C1378032B1EBF00233C +:100570001370984A4FF0000A18BF5360D34656468E +:10058000D146012000F07AFB24B1924B1B68002B6E +:1005900000F01182002000F07DFA0390039B002BF5 +:1005A000F2DB012000F060FB039B213B162BE8D817 +:1005B00001A252F823F000BF150600083D0600080E +:1005C000D10600088305000883050008830500089C +:1005D0005B0700082B09000845080008A708000869 +:1005E000CF080008F508000883050008070900087F +:1005F0008305000879090008B5060008830500088E +:10060000BD09000821060008B5060008830500089A +:10061000A70800080220FFF7C7FE002840F0F58178 +:10062000009B0221BAF1000F08BF1C4605A841F249 +:100630001233ADF8143000F04BFAA2E74FF47A70A1 +:1006400000F028FA071EEBDB0220FFF7ADFE0028C2 +:10065000E6D0013F052F00F2DA81DFE807F0030A58 +:100660000D10133605230593042105A800F030FA78 +:1006700017E054480421F9E758480421F6E75848A0 +:100680000421F3E74FF01C08404600F053FA08F14C +:1006900004080590042105A800F01AFAB8F12C0FFF +:1006A000F2D1012000FA07F747EA0B0B5FFA8BFB48 +:1006B0004FF0000900F078FB26B10BF00B030B2B79 +:1006C00008BF0024FFF778FE5BE746480421CDE72A +:1006D000002EA5D00BF00B030B2BA1D10220FFF7AE +:1006E00063FE074600289BD0012000F021FA02207B +:1006F000FFF7AAFE00261FFA86F8404600F028FA07 +:10070000044690B10021404600F032FA013600283C +:10071000F1D1BA46044641F21213022105A8ADF800 +:1007200014303E4600F0D4F92BE70120FFF78CFE91 +:100730002546244B9B68AB4207D9284600F0FAF9BE +:10074000013040F067810435F3E7234B00251D702D +:10075000204BBA465D603E46ACE7002E3FF460AFEA +:100760000BF00B030B2B7FF45BAF0220FFF76CFE4B +:10077000322000F08FF9B0F10008FFF651AF18F009 +:1007800003077FF44DAF0F4A926808EB05039342CD +:100790003FF646AFB8F5807F3FF742AF124B01936B +:1007A000B84523DD4FF47A7000F074F90390039A92 +:1007B000002AFFF635AF019B039A03F8012B01379E +:1007C000EDE700BF002200206C2300205022002013 +:1007D000D10300087023002068220020042200209A +:1007E000082200200C2200206C220020C820FFF7E5 +:1007F000DBFD074600283FF413AF1F2D11D8C5F1CC +:10080000200242450AAB25F0030028BF4246834937 +:100810000192184400F056FA019A8048FF2100F036 +:1008200077FA4FEAA8037D490193C8F38702284667 +:1008300000F076FA064600283FF46DAF019B05EB09 +:10084000830537E70220FFF7AFFD00283FF4E8AE4D +:1008500000F0BAF900283FF4E3AE0027B846704B29 +:100860009B68BB4218D91F2F11D80A9B01330ED0A9 +:1008700027F0030312AA134453F8203C0593404683 +:10088000042205A900F0F6FA04378046E7E7384667 +:1008900000F050F90590F2E7CDF81480042105A886 +:1008A00000F016F906E70023642104A8049300F081 +:1008B00005F900287FF4B4AE0220FFF775FD00288B +:1008C0003FF4AEAE049800F067F90590E6E7002328 +:1008D000642104A8049300F0F1F800287FF4A0AE8E +:1008E0000220FFF761FD00283FF49AAE049800F063 +:1008F00063F9EAE70220FFF757FD00283FF490AEC6 +:1009000000F072F9E1E70220FFF74EFD00283FF406 +:1009100087AE05A9142000F06DF904210746049064 +:1009200004A800F0D5F83946B9E7322000F0B2F853 +:10093000071EFFF675AEBB077FF472AE384A9268A9 +:1009400007EB090393423FF66BAE0220FFF72CFD45 +:1009500000283FF465AE27F003074F44B9453FF444 +:10096000A9AE484600F0E6F80421059005A800F07D +:10097000AFF809F10409F1E74FF47A70FFF714FDBD +:1009800000283FF44DAE00F01FF9002844D00A9B28 +:1009900001330BD008220AA9002000F0C1F9002879 +:1009A0003AD02022FF210AA800F0B2F9FFF704FD97 +:1009B0001C4801F059FA13B0BDE8F08F002E3FF447 +:1009C0002FAE0BF00B030B2B7FF42AAE0023642118 +:1009D00005A8059300F072F8074600287FF420AEC2 +:1009E0000220FFF7E1FC804600283FF419AEFFF734 +:1009F000E3FC41F2883001F037FA059800F018FA6C +:100A0000464600F0D1F93C46BBE5064652E64FF0BB +:100A1000000905E6BA467EE637467CE66C220020F1 +:100A200000220020A08601002DE9F84F4FF47A73D0 +:100A3000DFF85880DFF8589006460D4602FB03F7B2 +:100A4000002498F900305A1C5FFA84FA01D0A342BE +:100A500012D159F8240003682A46D3F820B0314651 +:100A60003B46D847854207D1074B012083F800A0B9 +:100A7000BDE8F88F0124E4E7002CFBD04FF4FA70B6 +:100A800001F0F2F90020F3E7B82300201022002043 +:100A90001422002007B50023024601210DF10700B2 +:100AA0008DF80730FFF7C0FF20B19DF8070003B0B5 +:100AB0005DF804FB4FF0FF30F9E700000A4608B587 +:100AC0000421FFF7B1FF80F00100C0B2404208BD31 +:100AD00030B4074B0A461978064B53F82140236877 +:100AE000DD69054B0146AC46204630BC604700BF7F +:100AF000B823002014220020A086010070B501F068 +:100B0000CFFC094E094D3080002428683388834289 +:100B100008D901F0BFFC2B6804440133B4F5804FC1 +:100B20002B60F2D370BD00BFBA23002078230020D1 +:100B300001F06CBD00F1006000F580400068704776 +:100B400000F10060920000F5804001F0F7BC000069 +:100B5000054B1A68054B1B889B1A834202D9104427 +:100B600001F098BC0020704778230020BA230020B1 +:100B700038B5084D044629B128682044BDE83840FE +:100B800001F0A8BC2868204401F08CFC0028F3D0B8 +:100B900038BD00BF7823002010F003030AD1B0F560 +:100BA000047F05D200F10050A0F51040D0F80038C5 +:100BB000184670470023FBE700F10050A0F51040F5 +:100BC000D0F8100A70470000064991F8243033B17C +:100BD0000023086A81F824300822FFF7B1BF012002 +:100BE000704700BF7C230020014B1868704700BF8E +:100BF000002004E070B5194B1D68194B0138C5F38E +:100C00000B0408442D0C04221E88A6420BD15C68FC +:100C10000A46013C824213460FD214F9016F4EB1CD +:100C200002F8016BF6E7013A03F10803ECD18142C7 +:100C30000B4602D22C2203F8012B0A4A05241688FF +:100C4000AE4204D1984284BF967803F8016B013C10 +:100C500002F10402F3D1581A70BD00BF002004E075 +:100C6000483B0008343B0008022802BF024B4FF407 +:100C700080529A61704700BF00100240022802BFF4 +:100C8000024B4FF080529A61704700BF0010024043 +:100C9000022801BF024A536983F4805353617047AD +:100CA0000010024070B504464FF47A764CB1412CE6 +:100CB000254628BF412506FB05F001F0D5F8641B49 +:100CC000F4E770BD10B50023934203D0CC5CC4544C +:100CD0000133F9E710BD000010B5013810F9013FEC +:100CE0003BB191F900409C4203D11AB10131013A64 +:100CF000F4E71AB191F90020981A10BD1046FCE7EC +:100D000003460246D01A12F9011B0029FAD1704796 +:100D100002440346934202D003F8011BFAE77047EE +:100D20002DE9F8431F4D144695F8242007468846C0 +:100D300052BBDFF870909CB395F824302BB9202279 +:100D4000FF2148462F62FFF7E3FF95F82400C0F12A +:100D50000802A24228BF2246D6B24146920005EBC5 +:100D60008000FFF7AFFF95F82430A41B1E44F6B2B5 +:100D7000082E17449044E4B285F82460DBD1FFF7D5 +:100D800023FF0028D7D108E02B6A03EB82038342BC +:100D9000CFD0FFF719FF0028CBD10020BDE8F883A2 +:100DA0000120FBE77C230020024B1A78024B1A70CB +:100DB000704700BFB82300201022002038B5174C20 +:100DC000174D204600F0B6FB2946204600F0DEFB1A +:100DD0002D686A6D936B23F4002393634FF47A704C +:100DE000FFF760FF0F49284600F0D6FC6A6D0E4DF4 +:100DF000936B28680D4943F400239363A0424FF49A +:100E0000E1330B6001D000F0F5FA6868A04204D02D +:100E1000BDE83840054900F0EDBA38BD98280020FB +:100E2000543C00085C3C000814220020A42300204D +:100E300070B50C4B0C4D1E780C4B55F826209A4281 +:100E400004460DD00A4B002114221846FFF760FF1C +:100E50000460014655F82600BDE8704000F0CABAAB +:100E600070BD00BFB8230020142200209828002065 +:100E7000A423002030B5094D0A4491420DD011F849 +:100E8000013B5840082340F30004013B2C4013F081 +:100E9000FF0384EA5000F6D1EFE730BD2083B8EDC0 +:100EA000026843681143016003B1184770470000AE +:100EB000024AD36843F0C003D36070470044004047 +:100EC00010B5054C054A0021204600F071FA044A8D +:100ED000044BC4E9972310BDBC230020B10E0008C9 +:100EE0000044004080DE8002234A037C002918BFB2 +:100EF0000A46012B30B5C0F868220CD11F4B98422E +:100F000009D11F4B196C41F400311964196E41F479 +:100F1000003119661B6EB2F904501468D0F86032C3 +:100F2000D0F85C12002D03EB5403B3FBF4F3BEBF07 +:100F300023F0070503F0070343EA450394888B6019 +:100F4000D38843F040030B61138943F001034B61E5 +:100F500044F4045343F02C03CB6004F4A054002366 +:100F60000B60B4F5806F0B684B680CBF7F23FF23C9 +:100F700080F8643230BD00BF683B0008BC2300200D +:100F8000003802402DE9F041D0F85C62F768336820 +:100F9000DA0504469DB20DD5302383F311884FF452 +:100FA00080610430FFF77CFF6FF4807333600023AF +:100FB00083F31188302383F3118804F1040815F0BA +:100FC0002F033AD183F31188380615D5290613D596 +:100FD000302383F3118804F1380000F065F900280C +:100FE0004EDA0821201DFFF75BFF4FF67F733B4071 +:100FF000F360002383F311887A0616D56B0614D5A7 +:10100000302383F31188D4E913239A420AD1236C45 +:1010100043B127F040073F041021201D3F0CFFF78C +:101020003FFFF760002383F31188D4F86822D36868 +:1010300043B3BDE8F041106918472B0714D015F0F1 +:10104000080F0CBF00214FF48071E80748BF41F042 +:101050002001AA0748BF41F040016B0748BF41F09B +:1010600080014046FFF71CFFAD06736805D594F874 +:1010700064122046194000F0CBF93568ADB29EE706 +:101080007060B6E7BDE8F081F8B51546826806697C +:10109000AA420B46816938BF8568761AB542044674 +:1010A0000BD218462A46FFF70DFEA3692B44A36115 +:1010B000A3685B1BA3602846F8BD0CD918463246CE +:1010C000FFF700FEAF1BE1683A463044FFF7FAFD38 +:1010D000E3683B44EBE718462A46FFF7F3FDE36875 +:1010E000E5E7000083689342F7B51546044638BF2C +:1010F0008568D0E90460361AB5420BD22A46FFF75C +:10110000E1FD63692B446361A36828465B1BA36010 +:1011100003B0F0BD0DD932460191FFF7D3FD01991F +:10112000E068AF1B3A463144FFF7CCFDE3683B442F +:10113000E9E72A46FFF7C6FDE368E4E710B50A448D +:101140000024C361029B8460C0E90000C0E905116E +:10115000C1600261036210BD08B5D0E90532934257 +:1011600001D1826882B98268013282605A1C426170 +:101170001970D0E904329A4224BFC3684361002148 +:1011800000F08EFE002008BD4FF0FF30FBE70000AE +:1011900070B5302304460E4683F31188A568A5B1C7 +:1011A000A368A269013BA360531CA361157822695F +:1011B000934224BFE368A361E3690BB120469847DB +:1011C000002383F31188284607E03146204600F0CB +:1011D00057FE0028E2DA85F3118870BD2DE9F74F3C +:1011E00004460E4617469846D0F81C904FF0300A39 +:1011F0008AF311884FF0000B154665B12A46314637 +:101200002046FFF741FF034660B94146204600F003 +:1012100037FE0028F1D0002383F31188781B03B038 +:10122000BDE8F08FB9F1000F03D001902046C84708 +:10123000019B8BF31188ED1A1E448AF31188DCE7B9 +:10124000C0E90511C160C3611144009B8260C0E91F +:101250000000016103627047F8B504460D4616466A +:10126000302383F31188A768A7B1A368013BA3606B +:1012700063695A1C62611D70D4E904329A4224BF2A +:10128000E3686361E3690BB120469847002080F36F +:10129000118807E03146204600F0F2FD0028E2DA2E +:1012A00087F31188F8BD0000D0E905239A4210B5F4 +:1012B00001D182687AB98268013282605A1C8261E7 +:1012C0001C7803699A4224BFC3688361002100F03F +:1012D000E7FD204610BD4FF0FF30FBE72DE9F74F4B +:1012E00004460E4617469846D0F81C904FF0300A38 +:1012F0008AF311884FF0000B154665B12A46314636 +:101300002046FFF7EFFE034660B94146204600F055 +:10131000B7FD0028F1D0002383F31188781B03B0B8 +:10132000BDE8F08FB9F1000F03D001902046C84707 +:10133000019B8BF31188ED1A1E448AF31188DCE7B8 +:10134000026843681143016003B118477047000009 +:101350001430FFF743BF00004FF0FF331430FFF7A6 +:101360003DBF00003830FFF7B9BF00004FF0FF333A +:101370003830FFF7B3BF00001430FFF709BF00009B +:101380004FF0FF311430FFF703BF00003830FFF794 +:1013900063BF00004FF0FF323830FFF75DBF000041 +:1013A000012914BF6FF0130000207047FFF788BDBC +:1013B00037B515460E4A026000224260C0E902229B +:1013C0000122044602740B46009000F15C014FF4C8 +:1013D00080721430FFF7B2FE00942B464FF48072F7 +:1013E00004F5AE7104F13800FFF72AFF03B030BDF9 +:1013F0007C3B000810B53023044683F31188FFF7C7 +:1014000073FD02232374002080F3118810BD0000B7 +:1014100038B5C36904460D461BB904210844FFF7DB +:101420008FFF294604F11400FFF796FE002806DA24 +:10143000201D4FF40061BDE83840FFF781BF38BD83 +:10144000026843681143016003B118477047000008 +:1014500013B5446BD4F894341A681178042915D163 +:10146000217C022912D11979128901238B40134260 +:101470000CD101A904F14C0001F012FFD4F89444FE +:10148000019B21790246206800F0D0F902B010BD1E +:10149000143001F095BE00004FF0FF33143001F01E +:1014A0008FBE00004C3001F067BF00004FF0FF33EB +:1014B0004C3001F061BF0000143001F063BE000049 +:1014C0004FF0FF31143001F05DBE00004C3001F0F0 +:1014D00033BF00004FF0FF324C3001F02DBF000051 +:1014E0000020704710B5D0F894341A681178042998 +:1014F000044617D1017C022914D15979528901235C +:101500008B4013420ED1143001F0F6FD024648B173 +:10151000D4F894444FF4807361792068BDE810409A +:1015200000F072B910BD0000406BFFF7DBBF000098 +:10153000704700007FB5124B036000234360C0E991 +:101540000233012502260F4B0574044602900193D5 +:1015500000F18402294600964FF48073143001F0A4 +:10156000A7FD094B0294CDE9006304F523724FF403 +:101570008073294604F14C0001F06EFE04B070BD8A +:10158000A43B000829150008511400080B683022FC +:1015900082F311880A7903EB820290614A79093259 +:1015A00043F822008A7912B103EB82039861022387 +:1015B000C0F894140374002080F311887047000071 +:1015C00038B5037F044613B190F85430ABB9201DF1 +:1015D00001250221FFF734FF04F1140025776FF095 +:1015E000010100F069FC84F8545004F14C006FF0E4 +:1015F0000101BDE8384000F05FBC38BD10B50121E5 +:1016000004460430FFF71CFF0023237784F854308E +:1016100010BD000038B504460025143001F060FD0F +:1016200004F14C00257701F02FFE201D84F8545062 +:101630000121FFF705FF2046BDE83840FFF752BF04 +:1016400090F8443003F06003202B07D190F8452038 +:10165000212A4FF0000303D81F2A06D80020704724 +:10166000222AFBD1C0E90E3303E0034A826307223A +:10167000C2630364012070471C22002037B5D0F8F4 +:1016800094341A681178042904461AD1017C02297D +:1016900017D11979128901238B40134211D100F11E +:1016A0004C05284601F0B0FE58B101A9284601F0CA +:1016B000F7FDD4F89444019B21790246206800F09C +:1016C000B5F803B030BD0000F0B500EB810385B084 +:1016D0009E6904460D46FEB1302383F3118804EB66 +:1016E0008507301D0821FFF7ABFEFB685B691B68AF +:1016F00006F14C001BB1019001F0E0FD019803A937 +:1017000001F0CEFD024648B1039B2946204600F079 +:101710008DF8002383F3118805B0F0BDFB685A698A +:101720001268002AF5D01B8A013B1340F1D104F165 +:101730004402EAE7093138B550F82140DCB13023E2 +:1017400083F31188D4F894241368527903EB82034D +:10175000DB689B695D6845B104216018FFF770FE86 +:10176000294604F1140001F0D1FC2046FFF7BAFE2F +:10177000002383F3118838BD7047000001F030B8B2 +:10178000012303700023C0E90133C3618362036254 +:10179000C36243620363704738B50446302383F362 +:1017A00011880025C0E90355C0E90555416001F0E5 +:1017B00027F80223237085F31188284638BD0000DE +:1017C00070B500EB810305465069DA600E46144699 +:1017D00018B110220021FFF79BFAA06918B110225E +:1017E0000021FFF795FA31462846BDE8704001F028 +:1017F000D1B80000826802F0011282600022C0E9C4 +:101800000422826101F052B9F0B400EB81044789EF +:10181000E4680125A4698D403D4345812360002390 +:10182000A2606360F0BC01F06DB90000F0B400EBA1 +:1018300081040789E468012564698D403D43058181 +:1018400023600023A2606360F0BC01F0E7B90000F0 +:1018500070B50223002504460370C0E90255C0E9B3 +:101860000455C564856180F8345001F02FF8636831 +:101870001B6823B129462046BDE87040184770BD5B +:101880000378052B10B504460AD080F850300523A4 +:10189000037043681B680BB1042198470023A360C1 +:1018A00010BD00000178052906D190F8502043684A +:1018B00002701B6803B118477047000070B590F8BC +:1018C0003430044613B1002380F8343004F144026C +:1018D000204601F00DF963689B68B3B994F8443071 +:1018E00013F0600535D00021204601F0ADFB00214A +:1018F000204601F09FFB63681B6813B10621204658 +:101900009847062384F8343070BD20469847002855 +:10191000E4D0B4F84A30E26B9A4288BFE36394F9AA +:101920004430E56B002B4FF0300380F20381002D33 +:1019300000F0F280092284F8342083F3118800211A +:10194000D4E90E232046FFF771FF002383F31188AB +:10195000DAE794F8452003F07F0343EA022340F2DC +:101960000232934200F0C58021D8B3F5807F48D081 +:101970000DD8012B3FD0022B00F09380002BB2D169 +:1019800004F14C02A2630222E2632364C1E7B3F5CF +:10199000817F00F09B80B3F5407FA4D194F846305E +:1019A000012BA0D1B4F84C3043F0020332E0B3F580 +:1019B000006F4DD017D8B3F5A06F31D0A3F5C06339 +:1019C000012B90D8636894F846205E6894F847101D +:1019D000B4F848302046B047002884D04368A36359 +:1019E0000368E3631AE0B3F5106F36D040F60242A5 +:1019F00093427FF478AF5C4BA3630223E36300233D +:101A0000C3E794F84630012B7FF46DAFB4F84C3047 +:101A100023F00203C4E90E55A4F84C30256478E79E +:101A2000B4F84430B3F5A06F0ED194F8463084F882 +:101A30004E30204600F0A2FF63681B6813B10121FD +:101A400020469847032323700023C4E90E339CE704 +:101A500004F14F03A3630123C3E72378042B10D1C0 +:101A6000302383F311882046FFF7C4FE85F31188E5 +:101A70000321636884F84F5021701B680BB1204626 +:101A8000984794F84630002BDED084F84F3004237A +:101A9000237063681B68002BD6D00221204698472C +:101AA000D2E794F848301D0603F00F0120460AD50E +:101AB00001F010F8012804D002287FF414AF2B4B5A +:101AC0009AE72B4B98E700F0F7FFF3E794F84630DE +:101AD000002B7FF408AF94F8483013F00F01B3D017 +:101AE0001A06204602D501F0C3FAADE701F0B6FAB6 +:101AF000AAE794F84630002B7FF4F5AE94F848300E +:101B000013F00F01A0D01B06204602D501F09CFA6D +:101B10009AE701F08FFA97E7142284F8342083F3D0 +:101B200011882B462A4629462046FFF76DFE85F38D +:101B30001188E9E65DB1152284F8342083F3118819 +:101B40000021D4E90E232046FFF75EFEFDE60B22BE +:101B500084F8342083F311882B462A4629462046F0 +:101B6000FFF764FEE3E700BFD43B0008CC3B00086E +:101B7000D03B000838B590F834300446002B3ED0F6 +:101B8000063BDAB20F2A34D80F2B32D8DFE803F045 +:101B9000373131082232313131313131313137375A +:101BA000C56BB0F84A309D4214D2C3681B8AB5FB9E +:101BB000F3F203FB12556DB9302383F311882B46E2 +:101BC0002A462946FFF732FE85F311880A2384F856 +:101BD00034300EE0142384F83430302383F311883A +:101BE00000231A4619462046FFF70EFE002383F312 +:101BF000118838BD036C03B198470023E7E7002143 +:101C0000204601F021FA0021204601F013FA636812 +:101C10001B6813B10621204698470623D7E700002A +:101C200010B590F83430142B044629D017D8062B61 +:101C300005D001D81BB110BD093B022BFBD80021F8 +:101C4000204601F001FA0021204601F0F3F9636813 +:101C50001B6813B1062120469847062319E0152B6F +:101C6000E9D10B2380F83430302383F3118800232B +:101C70001A461946FFF7DAFD002383F31188DAE7E5 +:101C8000C3689B695B68002BD5D1036C03B198478F +:101C9000002384F83430CEE700230375826803699B +:101CA0001B6899689142FBD25A68036042601060D9 +:101CB0005860704700230375826803691B68996840 +:101CC0009142FBD85A6803604260106058607047C8 +:101CD00008B50846302383F311880B7D032B05D00C +:101CE000042B0DD02BB983F3118808BD8B6900221A +:101CF0001A604FF0FF338361FFF7CEFF0023F2E756 +:101D0000D1E9003213605A60F3E70000FFF7C4BF67 +:101D1000054BD9680875186802681A60536001227B +:101D20000275D860FEF7EEBA2826002030B50C4BBD +:101D3000DD684B1C87B004460FD02B46094A684625 +:101D400000F04EF92046FFF7E3FF009B13B1684611 +:101D500000F050F9A86907B030BDFFF7D9FFF9E7E7 +:101D600028260020D11C0008044B1A68DB68906804 +:101D70009B68984294BF00200120704728260020CD +:101D8000084B10B51C68D86822681A60536001229D +:101D90002275DC60FFF78EFF01462046BDE810404B +:101DA000FEF7B0BA2826002038B5074C0749084886 +:101DB000012300252370656001F064FB022323707A +:101DC00085F3118838BD00BF90280020DC3B000857 +:101DD0002826002000F044B9034A516853685B1A72 +:101DE0009842FBD8704700BF001000E08B600223D0 +:101DF00008618B82084670478368A3F1840243F828 +:101E0000142C026943F8442C426943F8402C094AD7 +:101E100043F8242CC26843F8182C022203F80C2C37 +:101E2000002203F80B2C044A43F8102CA3F12000E5 +:101E3000704700BF1D0300082826002008B5FFF7E3 +:101E4000DBFFBDE80840FFF761BF0000024BDB6825 +:101E500098610F20FFF75CBF28260020302383F312 +:101E60001188FFF7F3BF000008B50146302383F364 +:101E700011880820FFF75AFF002383F3118808BD5B +:101E8000064BDB6839B1426818605A6013604360E2 +:101E90000420FFF74BBF4FF0FF307047282600208B +:101EA0000368984206D01A6802605060996118462B +:101EB000FFF72CBF7047000038B504460D46206878 +:101EC000844200D138BD036823605C608561FFF700 +:101ED0001DFFF4E710B503689C68A2420CD85C684B +:101EE0008A600B604C602160596099688A1A9A6018 +:101EF0004FF0FF33836010BD1B68121BECE700003E +:101F00000A2938BF0A2170B504460D460A26601911 +:101F100001F0B0FA01F098FA041BA54203D8751C31 +:101F20002E460446F3E70A2E04D9BDE8704001208E +:101F300001F0E8BA70BD0000F8B5144B0D46D96148 +:101F400003F1100141600A2A1969826038BF0A2230 +:101F5000016048601861A818144601F07BFA0A274E +:101F600001F072FA431BA342064606D37C1C2819D3 +:101F700001F080FA27463546F2E70A2F04D9BDE87A +:101F8000F840012001F0BEBAF8BD00BF28260020AD +:101F9000F8B506460D4601F057FA0F4A134653F8B6 +:101FA000107F9F4206D12A4601463046BDE8F840E0 +:101FB000FFF7C2BFD169BB68441A2C1928BF2C4651 +:101FC000A34202D92946FFF79BFF22463146034828 +:101FD000BDE8F840FFF77EBF282600203826002005 +:101FE00010B4C0E9032300235DF8044B4361FFF7FD +:101FF000CFBF000010B5194C236998420DD0D0E92D +:102000000032816813605A609A680A449A6000231B +:1020100003604FF0FF33A36110BD2346026843F80D +:10202000102F53600022026022699A4203D1BDE85A +:10203000104001F019BA936881680B44936001F075 +:1020400003FA2269E1699268441AA242E4D9114470 +:10205000BDE81040091AFFF753BF00BF2826002033 +:102060002DE9F047DFF8BC8008F110072C4ED8F8B6 +:10207000105001F0E9F9D8F81C40AA68031B9A42F5 +:102080003ED81444D5E900324FF00009C8F81C408E +:1020900013605A60C5F80090D8F81030B34201D1EF +:1020A00001F0E2F989F31188D5E903312846984710 +:1020B000302383F311886B69002BD8D001F0C4F969 +:1020C0006A69A0EB04094A4582460DD2022001F05C +:1020D00019FA0022D8F81030B34208D151462846E8 +:1020E000BDE8F047FFF728BF121A2244F2E712EBCF +:1020F000090938BF4A4629463846FFF7EBFEB5E7DF +:10210000D8F81030B34208D01444211AC8F81C0083 +:10211000A960BDE8F047FFF7F3BEBDE8F08700BF58 +:10212000382600202826002000207047FEE7000007 +:10213000704700004FF0FF307047000002290CD0BC +:10214000032904D00129074818BF00207047032A3B +:1021500005D8054800EBC2007047044870470020CE +:10216000704700BFB83C00082C2200206C3C0008DF +:1021700070B59AB00546084601A9144600F0C2F8A9 +:1021800001A8FEF7BDFD431C5B00C5E90034002239 +:10219000237003236370C6B201AB02341046D1B280 +:1021A0008E4204F1020401D81AB070BD13F8011B6D +:1021B00004F8021C04F8010C0132F0E708B53023E2 +:1021C00083F311880348FFF759FA002383F311883A +:1021D00008BD00BF9828002090F8443003F01F028B +:1021E000012A07D190F845200B2A03D10023C0E92A +:1021F0000E3315E003F06003202B08D1B0F848300F +:102200002BB990F84520212A03D81F2A04D8FFF7BC +:1022100017BA222AEBD0FAE7034A82630722C26385 +:1022200003640120704700BF2322002007B5052961 +:1022300017D8DFE801F0191603191920302383F3AA +:102240001188104A01900121FFF7BAFA01980E4A4D +:102250000221FFF7B5FA0D48FFF7DCF9002383F3FD +:10226000118803B05DF804FB302383F3118807481D +:10227000FFF7A6F9F2E7302383F311880348FFF74D +:10228000BDF9EBE70C3C0008303C00089828002022 +:1022900038B50C4D0C4C0D492A4604F10800FFF7E7 +:1022A00067FF05F1CA0204F110000949FFF760FF5A +:1022B00005F5CA7204F118000649BDE83840FFF779 +:1022C00057BF00BF602D00202C220020E83B0008F3 +:1022D000F53B0008003C000870B5044608460D4672 +:1022E000FEF70EFDC6B22046013403780BB918463E +:1022F00070BD32462946FEF7EFFC0028F3D10120DD +:10230000F6E700002DE9F84F05460C46FEF7F8FC0D +:102310002949C6B22846FFF7DFFF08B10136F6B2F9 +:1023200026492846FFF7D8FF08B11036F6B2632ECB +:102330000DD8DFF88490DFF884A0214FDFF888B053 +:10234000DFF888802E7846B92670BDE8F88F2946D8 +:102350002046BDE8F84F01F0CFBB252E28D107223B +:1023600049462846FEF7B8FC40B9D8F8003023604B +:10237000D8F80430636007350834E3E70822514693 +:102380002846FEF7A9FC98B90E4BA21C197809093A +:102390000232C95D02F8041C13F8011B01F00F01A1 +:1023A0005B45C95D02F8031CF0D118340835C9E754 +:1023B00004F8016B0135C5E7D83C0008003C000873 +:1023C000E93C0008107AFF1F1C7AFF1FE03C000860 +:1023D000BFF34F8F024AD368DB03FCD4704700BFC2 +:1023E000003C024008B5094B1B7873B9FFF7F0FFBA +:1023F000074B1A69002ABFBF064A5A6002F18832A9 +:102400005A601A6822F480621A6008BDBE2F00204C +:10241000003C02402301674508B50B4B1B7893B97C +:10242000FFF7D6FF094B1A6942F000421A611A6899 +:1024300042F480521A601A6822F480521A601A68B4 +:1024400042F480621A6008BDBE2F0020003C0240AA +:102450001728F0B516D80C4C0C4923787BB90C4DD5 +:102460000E4618234FF0006255F8047B46F8042B03 +:10247000013B13F0FF033A44F6D10123237051F8D6 +:102480002000F0BD0020FCE720300020C02F0020FD +:10249000FC3C0008014B53F820007047FC3C00084E +:1024A00018207047172810B5044601D9002010BD28 +:1024B000FFF7CEFF064B53F824301844C21A0BB96D +:1024C0000120F4E712680132F0D1043BF6E700BFC7 +:1024D000FC3C0008172838B5044628D81549FFF7F2 +:1024E00077FFFFF77FFFF323CB600C23B0FBF3F202 +:1024F00003FB1205D30143EAC503DBB243F40073C7 +:1025000043F002030B610B6943F480330B61FFF767 +:102510005FFFFFF79DFF084B53F8241000F0DAF837 +:10252000FFF77AFF2046BDE83840FFF7BBBF002029 +:1025300038BD00BF003C0240FC3C0008F8B512F07A +:102540000103144642D18218B2F1026F57D82D4BC5 +:102550001B6813F0010352D02B4DFFF743FFF32309 +:10256000EB60FFF735FF40F20127032C15D824F06C +:1025700001046618244C401A40F20117B142236945 +:1025800000EB010524D123F001032361FFF744FF91 +:102590000120F8BD043C0430E7E78307E7D12B694D +:1025A00023F440732B612B693B432B6151F8046B7F +:1025B0000660BFF34F8FFFF70BFF03689E42E9D021 +:1025C0002B6923F001032B61FFF726FF0020E0E7D2 +:1025D00023F44073236123693B4323610B882B80E1 +:1025E000BFF34F8FFFF7F4FE2D8831F8023BADB2F9 +:1025F000AB42C3D0236923F001032361E4E718460B +:10260000C7E700BF00380240003C0240084908B557 +:102610000B7828B11BB9FFF7E5FE01230B7008BD4D +:10262000002BFCD0BDE808400870FFF7F5BE00BFE6 +:10263000BE2F002010B50244064BD2B2904200D10A +:1026400010BD441C00B253F8200041F8040BE0B266 +:10265000F4E700BF502800400F4B30B51C6F240436 +:1026600007D41C6F44F400741C671C6F44F40044CE +:102670001C670A4C236843F4807323600244084BB0 +:10268000D2B2904200D130BD441C00B251F8045B7C +:1026900043F82050E0B2F4E70038024000700040F8 +:1026A0005028004007B5012201A90020FFF7C2FF12 +:1026B000019803B05DF804FB13B50446FFF7F2FF81 +:1026C000A04205D0012201A900200194FFF7C4FF18 +:1026D00002B010BD70470000094B5A88B2F5805F08 +:1026E00010460BD022F0020341F20102934205D0C2 +:1026F00041F20703C31A58425841704701207047FE +:10270000002004E0034B1A681AB9034AD2F874286F +:102710001A607047243000200030024008B5FFF7EF +:10272000F1FF024B1868C0F3407008BD2430002050 +:1027300070470000FEE700000A4B0B480B4A90422E +:102740000BD30B4BDA1C121AC11E22F003028B4270 +:1027500038BF00220021FEF7DBBA53F8041B40F813 +:10276000041BECE7E43E000820310020203100206B +:102770002031002070B5D0E915439E6800224FF04B +:10278000FF3504EB42135101D3F800090028BEBF06 +:10279000D3F8000940F08040C3F80009D3F8000BDB +:1027A0000028BEBFD3F8000B40F08040C3F8000BF8 +:1027B000013263189642C3F80859C3F8085BE0D2A7 +:1027C0004FF00113C4F81C3870BD0000890141F0BE +:1027D0002001016103699B06FCD41220FFF7FCBABB +:1027E00010B5054C2046FEF7CBFF4FF0A0436365C4 +:1027F000024BA36510BD00BF28300020803D0008BB +:1028000070B50378012B054650D12A4B446D984290 +:102810001BD1294B5A6B42F080025A635A6D42F029 +:1028200080025A655A6D5A6942F080025A615A69AB +:1028300022F080025A610E2143205B6900F022FCE5 +:102840001E4BE3601E4BC4F800380023C4F8003E62 +:10285000C02323606E6D4FF45023A3633369002BB4 +:10286000FCDA012333610C20FFF7B6FA3369DB078A +:10287000FCD41220FFF7B0FA3369002BFCDA0026F3 +:10288000A6602846FFF776FF6B68C4F81068DB681F +:10289000C4F81468C4F81C684BB90A4BA3614FF024 +:1028A000FF336361A36843F00103A36070BD064B6F +:1028B000F4E700BF283000200038024040140040F8 +:1028C00003002002003C30C0083C30C0F8B5446D25 +:1028D000054600212046FFF779FFA96D00234FF040 +:1028E00001128F68C4F834384FF00066C4F81C2811 +:1028F0004FF0FF3004EB431201339F42C2F80069EE +:10290000C2F8006BC2F80809C2F8080BF2D20B68D3 +:102910006A6DEB65636210231361166916F0100689 +:10292000FBD11220FFF758FAD4F8003823F4FE63E5 +:10293000C4F80038A36943F4402343F01003A361B3 +:102940000923C4F81038C4F814380A4BEB604FF070 +:10295000C043C4F8103B084BC4F8003BC4F81069EE +:10296000C4F80039EB6D03F1100243F48013EA65FB +:10297000A362F8BD5C3D000840800010426D90F8F5 +:102980004E10D2F8003823F4FE6343EA0113C2F874 +:10299000003870472DE9F84300EB8103456DDA6894 +:1029A000166806F00306731E022B05EB41130C4656 +:1029B00080460FFA81F94FEA41104FF00001C3F849 +:1029C000101B4FF0010104F1100398BFB60401FA87 +:1029D00003F391698EBF334E06F1805606F500462B +:1029E00000293AD0578A04F15801490137436F5002 +:1029F000D5F81C180B43C5F81C382B180021C3F858 +:102A0000101953690127611EA7409BB3138A928B4B +:102A10009B08012A88BF5343D8F85C20981842EAE3 +:102A2000034301F1400205EB8202C8F85C00214635 +:102A300053602846FFF7CAFE08EB8900C3681B8A6B +:102A400043EA8453483464011E432E51D5F81C38A0 +:102A50001F43C5F81C78BDE8F88305EB4917D7F884 +:102A6000001B21F40041C7F8001BD5F81C1821EA0F +:102A70000303C0E704F13F0305EB83030A4A5A60EE +:102A800028462146FFF7A2FE05EB4910D0F8003991 +:102A900023F40043C0F80039D5F81C3823EA0707AF +:102AA000D7E700BF0080001000040002826D1268AA +:102AB000C265FFF75FBE00005831436D49015B58A6 +:102AC00013F4004004D013F4001F0CBF02200120B7 +:102AD000704700004831436D49015B5813F40040D2 +:102AE00004D013F4001F0CBF022001207047000027 +:102AF00000EB8101CB68196A0B6813604B68536067 +:102B00007047000000EB810330B5DD68AA691368E7 +:102B1000D36019B9402B84BF402313606B8A1468BB +:102B2000426D1C44013CB4FBF3F46343033323F0D4 +:102B3000030302EB411043EAC44343F0C043C0F82F +:102B4000103B2B6803F00303012B09B20ED1D2F81E +:102B5000083802EB411013F4807FD0F8003B14BF1B +:102B600043F0805343F00053C0F8003B02EB4112A6 +:102B7000D2F8003B43F00443C2F8003B30BD0000F4 +:102B80002DE9F041244D6E6D06EB40130446D3F859 +:102B9000087BC3F8087B38070AD5D6F8143819071C +:102BA00006D505EB84032146DB6828465B68984719 +:102BB000FA071FD5D6F81438DB071BD505EB8403BD +:102BC000D968CCB98B69488A5A68B2FBF0F600FB29 +:102BD00016228AB91868DA6890420DD2121AC3E92F +:102BE0000024302383F311880B482146FFF78AFF26 +:102BF00084F31188BDE8F081012303FA04F26B89A4 +:102C000023EA02036B81CB68002BF3D021460248F4 +:102C1000BDE8F041184700BF2830002000EB8103D9 +:102C200070B5DD68436D6C692668E6604A0156BB85 +:102C30001A444FF40020C2F810092A6802F0030277 +:102C4000012A0AB20ED1D3F8080803EB421410F49B +:102C5000807FD4F8000914BF40F0805040F000504D +:102C6000C4F8000903EB4212D2F8000940F0044016 +:102C7000C2F80009D3F83408012202FA01F1014335 +:102C8000C3F8341870BD19B9402E84BF40202060AD +:102C900020682E8A8419013CB4FBF6F440EAC44053 +:102CA00040F000501A44C6E72DE9F8433B4D6E6DE5 +:102CB00006EB40130446D3F80889C3F8088918F0D6 +:102CC000010F4FEA40171AD0D6F81038DB0716D597 +:102CD00005EB8003D9684B691868DA68904230D2F6 +:102CE000121A4FF000091A60C3F80490302383F3DE +:102CF000118821462846FFF791FF89F3118818F0C3 +:102D0000800F1CD0D6F834380126A640334216D0A6 +:102D100005EB84036D6DD3F80CC0DCF8142001348E +:102D2000E4B2D2F800E005EB04342F445168714559 +:102D300015D3D5F8343823EA0606C5F83468BDE85B +:102D4000F883012303FA04F22B8923EA02032B817F +:102D50008B68002BD3D0214628469847CFE7BCF894 +:102D60001000AEEB0103834228BF0346D7F81809D1 +:102D700080B2B3EB800FE2D89068A0F1040959F853 +:102D8000048FC4F80080A0EB09089844B8F1040F40 +:102D9000F5D818440B4490605360C7E728300020F2 +:102DA0002DE9F74FA24C656D6E69AB691E4016F4B4 +:102DB00080586E6107D02046FEF74AFD03B0BDE89B +:102DC000F04F00F04DBC002E12DAD5F8003E9848C6 +:102DD0009B071EBFD5F8003E23F00303C5F8003E55 +:102DE000D5F8043823F00103C5F80438FEF75AFD7E +:102DF000370505D58E48FFF7BDFC8D48FEF740FD31 +:102E0000B0040CD5D5F8083813F0060FEB6823F49E +:102E100070530CBF43F4105343F4A053EB603107DD +:102E20001BD56368DB681BB9AB6923F00803AB6192 +:102E30002378052B0CD1D5F8003E7D489A071EBF9C +:102E4000D5F8003E23F00303C5F8003EFEF72AFD47 +:102E50006368DB680BB176489847F30274D4B70215 +:102E600027D5D4F85490DFF8C8B100274FF0010AF5 +:102E700009EB4712D2F8003B03F44023B3F5802F4F +:102E800011D1D2F8003B002B0DDA62890AFA07F360 +:102E900022EA0303638104EB8703DB68DB6813B179 +:102EA000394658469847A36D01379B68FFB29F4249 +:102EB000DED9F00617D5676D3A6AC2F30A1002F040 +:102EC0000F0302F4F012B2F5802F00F08580B2F506 +:102ED000402F08D104EB83030022DB681B6A07F54F +:102EE000805790426AD13003D5F8184813D5E103D2 +:102EF00002D50020FFF744FEA20302D50120FFF710 +:102F00003FFE630302D50220FFF73AFE270302D5F6 +:102F10000320FFF735FE75037FF550AFE00702D5BC +:102F20000020FFF7C1FEA10702D50120FFF7BCFE7C +:102F3000620702D50220FFF7B7FE23077FF53EAFF9 +:102F40000320FFF7B1FE39E7636DDFF8E4A00193DA +:102F500000274FF00109A36D9B685FFA87FB9B4533 +:102F60003FF67DAF019B03EB4B13D3F8001901F43F +:102F70004021B1F5802F1FD1D3F8001900291BDAA9 +:102F8000D3F8001941F09041C3F80019D3F80019A3 +:102F90000029FBDB5946606DFFF718FC218909FA0F +:102FA0000BF321EA0303238104EB8B03DB689B68AB +:102FB00013B15946504698470137CCE7910708BFEF +:102FC000D7F80080072A98BF03F8018B02F10102AD +:102FD00098BF4FEA182884E7023304EB830207F511 +:102FE00080575268D2F818C0DCF80820DCE9001CD1 +:102FF000A1EB0C0C002188420AD104EB8304636826 +:103000009B699A6802449A605A6802445A606AE767 +:1030100011F0030F08BFD7F800808C4588BF02F875 +:10302000018B01F1010188BF4FEA1828E3E700BFD7 +:1030300028300020436D03EB4111D1F8003B43F4ED +:103040000013C1F8003B7047436D03EB4111D1F809 +:10305000003943F40013C1F800397047436D03EBA6 +:103060004111D1F8003B23F40013C1F8003B704735 +:10307000436D03EB4111D1F8003923F40013C1F87B +:103080000039704700F1604303F561430901C9B29B +:1030900083F80013012200F01F039A4043099B00AC +:1030A00003F1604303F56143C3F880211A60704760 +:1030B00030B5039C0172043304FB0325C0E90653B9 +:1030C000049B03630021059BC160C0E90000C0E9C7 +:1030D0000422C0E90842C0E90A11436330BD000080 +:1030E000416A0022C0E90411C0E90A22C2606FF0FF +:1030F0000101FEF7E1BE0000D0E90432934201D1A4 +:10310000C2680AB9181D704700207047036919602A +:10311000C2680132C260C26913448269036193428A +:1031200024BF436A03610021FEF7BABE38B50446E6 +:103130000D46E3683BB16269131D1268A362134434 +:10314000E362002007E0237A33B929462046FEF7E0 +:1031500097FE0028EDDA38BD6FF00100FBE70000B4 +:10316000C368C269013BC360436913448269436118 +:10317000934224BF436A436100238362036B03B11C +:103180001847704770B53023044683F31188866A68 +:103190003EB9FFF7CBFF054618B186F311882846E4 +:1031A00070BDA36AE26A13F8015BA362934202D383 +:1031B0002046FFF7D5FF002383F31188EFE70000D7 +:1031C0002DE9F84F04460E46174698464FF0300951 +:1031D00089F311880025AA46D4F828B0BBF1000F66 +:1031E00009D141462046FFF7A1FF20B18BF311889A +:1031F0002846BDE8F88FD4E90A12A7EB050B521A4E +:10320000934528BF9346BBF1400F1BD9334601F1CC +:10321000400251F8040B43F8040B9142F9D1A36A20 +:1032200040334036A3624035D4E90A239A4202D3A0 +:103230002046FFF795FF8AF31188BD42D8D289F363 +:103240001188C9E730465A46FDF73CFDA36A5B4446 +:103250005E44A3625D44E7E710B5029C017204334B +:1032600003FB0421C0E906130023C0E90A33039BD2 +:103270000363049BC460C0E90000C0E90422C0E904 +:103280000842436310BD0000026AC260426AC0E99E +:1032900004220022C0E90A226FF00101FEF70CBEF1 +:1032A000D0E904239A4201D1C26822B9184650F8E5 +:1032B000043B0B60704700231846FAE7C368C269F5 +:1032C0000133C3604369134482694361934224BF5D +:1032D000436A43610021FEF7E3BD000038B50446B0 +:1032E0000D46E3683BB123691A1DA262E2691344EB +:1032F000E362002007E0237A33B929462046FEF72F +:10330000BFFD0028EDDA38BD6FF00100FBE70000DB +:1033100003691960C268013AC260C26913448269D4 +:103320000361934224BF436A036100238362036BFA +:1033300003B118477047000070B530230D460446AE +:10334000114683F31188866A2EB9FFF7C7FF10B1C3 +:1033500086F3118870BDA36A1D70A36AE26A013307 +:103360009342A36204D3E16920460439FFF7D0FFFA +:10337000002080F31188EDE72DE9F84F04460D4653 +:10338000904699464FF0300A8AF311880026B346DA +:10339000A76A4FB949462046FFF7A0FF20B187F33F +:1033A00011883046BDE8F88FD4E90A073A1AA8EB2D +:1033B0000607974228BF1746402F1BD905F1400347 +:1033C00055F8042B40F8042B9D42F9D1A36A4033F1 +:1033D000A3624036D4E90A239A4204D3E169204625 +:1033E0000439FFF795FF8BF311884645D9D28AF34C +:1033F0001188CDE729463A46FDF764FCA36A3B44B1 +:103400003D44A3623E44E5E7D0E904239A4217D144 +:10341000C3689BB1836A8BB1043B9B1A0ED01360C7 +:10342000C368013BC360C3691A44836902619A425D +:1034300024BF436A03610023836201231846704757 +:103440000023FBE700F036B9014B586A704700BF14 +:10345000000C0040034B002258631A610222DA601C +:10346000704700BF000C0040014B0022DA6070473B +:10347000000C0040014B5863704700BF000C004037 +:10348000FEE7000070B51B4B01630025044686B0C3 +:10349000586085620E4600F0BFF804F11003C4E9DD +:1034A00004334FF0FF33C4E90635C4E90044A56096 +:1034B000E562FFF7C9FF2B460246C4E9082304F181 +:1034C00034010D4A256580232046FEF78FFC012339 +:1034D000E0600A4A0375009272680192B268CDE911 +:1034E0000223074B6846CDE90435FEF7A7FC06B07A +:1034F00070BD00BF902800208C3D0008913D000861 +:1035000081340008024AD36A1843D062704700BF72 +:10351000282600204B6843608B688360CB68C360BB +:103520000B6943614B6903628B6943620B680360FB +:103530007047000008B5264B26481A6940F2FF1173 +:103540000A431A611A6922F4FF7222F001021A6119 +:103550001A691A6B0A431A631A6D0A431A651E4ADE +:103560001B6D1146FFF7D6FF02F11C0100F58060CC +:10357000FFF7D0FF02F1380100F58060FFF7CAFFC6 +:1035800002F1540100F58060FFF7C4FF02F1700101 +:1035900000F58060FFF7BEFF02F18C0100F580604E +:1035A000FFF7B8FF02F1A80100F58060FFF7B2FF56 +:1035B00002F1C40100F58060FFF7ACFF02F1E00109 +:1035C00000F58060FFF7A6FFBDE8084000F0F0B806 +:1035D0000038024000000240983D000808B500F0A5 +:1035E0006BFAFEF7E1FBFFF78DF8BDE80840FEF748 +:1035F0004FBE000070470000EFF3098305494A6B96 +:1036000022F001024A63683383F30988002383F3BD +:103610001188704700EF00E0302080F3118862B617 +:103620000C4B0D4AD96821F4E0610904090C0A43E6 +:10363000DA60D3F8FC20094942F08072C3F8FC201C +:103640000A6842F001020A602022DA7783F8220039 +:10365000704700BF00ED00E00003FA05001000E035 +:1036600010B5302383F311880E4B5B6813F40063AD +:1036700014D0F1EE103AEFF30984683C4FF08073F8 +:10368000E361094BDB6B236684F30988FEF76CFB6F +:1036900010B1064BA36110BD054BFBE783F3118806 +:1036A000F9E700BF00ED00E000EF00E02F030008A5 +:1036B000320300080E4B1A6C42F008021A641A6EAC +:1036C00042F008021A660B4A1B6E936843F0080327 +:1036D0009360094B53229A624FF0FF32DA62002264 +:1036E0009A615A63DA605A6001225A611A6070471F +:1036F00000380240002004E0000C0040094A08B5F0 +:103700001169D3680B40D9B2C9439B07116107D532 +:10371000302383F31188FEF75DFB002383F31188C8 +:1037200008BD00BF000C00401F4B1A696FEAC2526F +:103730006FEAD2521A611A69C2F308021A614FF095 +:10374000FF301A695A69586100215A6959615A69EA +:103750001A6A62F080521A621A6A02F080521A6281 +:103760001A6A5A6A58625A6A59625A6A1A6C42F05C +:1037700080521A641A6E42F080521A661A6E0B4A10 +:10378000106840F480701060186F00F44070B0F55D +:10379000007F1EBF4FF4803018671967536823F409 +:1037A0000073536000F060B90038024000700040C0 +:1037B000344B4FF080521A64334A4FF44041116049 +:1037C0001A6842F001021A601A689107FCD59A68DB +:1037D00022F003029A602B4B9A6812F00C02FBD184 +:1037E000196801F0F90119609A601A6842F4803290 +:1037F0001A601A689203FCD55A6F42F001025A67A8 +:10380000204B5A6F9007FCD5204A5A601A6842F044 +:1038100080721A601C4A53685904FCD5194B1A6807 +:103820009201FCD51A4A9A600322C3F88C20194BE6 +:103830001A68194B9A42194B21D1194A1168194A31 +:1038400091421CD140F205121A60144A136803F029 +:103850000F03052BFAD10B4B9A6842F002029A60D3 +:103860009A6802F00C02082AFAD15A6C42F480429B +:103870005A645A6E42F480425A665B6E704740F258 +:103880000572E1E70038024000700040185440071C +:1038900000948838002004E011640020003C0240BD +:1038A00000ED00E041C20F41074A08B5536903F03B +:1038B0000103536123B1054A13680BB1506898475F +:1038C000BDE80840FFF7CCBE003C0140A03000201E +:1038D000074A08B5536903F00203536123B1054A4F +:1038E00093680BB1D0689847BDE80840FFF7B8BEB1 +:1038F000003C0140A0300020074A08B5536903F09E +:103900000403536123B1054A13690BB15069984709 +:10391000BDE80840FFF7A4BE003C0140A0300020F5 +:10392000074A08B5536903F00803536123B1054AF8 +:1039300093690BB1D0699847BDE80840FFF790BE86 +:10394000003C0140A0300020074A08B5536903F04D +:103950001003536123B1054A136A0BB1506A9847AB +:10396000BDE80840FFF77CBE003C0140A0300020CD +:10397000164B10B55C6904F478725A61A30604D53D +:10398000134A936A0BB1D06A9847600604D5104A6F +:10399000136B0BB1506B9847210604D50C4A936BFF +:1039A0000BB1D06B9847E20504D5094A136C0BB1F3 +:1039B000506C9847A30504D5054A936C0BB1D06CA5 +:1039C0009847BDE81040FFF74BBE00BF003C0140E8 +:1039D000A0300020194B10B55C6904F47C425A6198 +:1039E000620504D5164A136D0BB1506D9847230537 +:1039F00004D5134A936D0BB1D06D9847E00404D5FC +:103A00000F4A136E0BB1506E9847A10404D50C4AAF +:103A1000936E0BB1D06E9847620404D5084A136FB9 +:103A20000BB1506F9847230404D5054A936F0BB12F +:103A3000D06F9847BDE81040FFF712BE003C014030 +:103A4000A030002008B50348FDF79CFABDE8084007 +:103A5000FFF706BEBC23002008B5FFF74FFEBDE808 +:103A60000840FFF7FDBD0000062108B50846FFF736 +:103A700009FB06210720FFF705FB06210820FFF7B9 +:103A800001FB06210920FFF7FDFA06210A20FFF7B6 +:103A9000F9FA06211720FFF7F5FA06212820FFF78B +:103AA000F1FA07213220FFF7EDFABDE808400C21BA +:103AB0002620FFF7E7BA000008B5FFF735FE00F053 +:103AC0000DF8FDF773FCFDF759FEFDF731FDFFF72B +:103AD00091FDBDE80840FFF7B5BC00000023054A92 +:103AE00019460133102BC2E9001102F10802F8D186 +:103AF000704700BFA0300020034611F8012B03F8E7 +:103B0000012B002AF9D1704753544D3332463F3FC1 +:103B10003F0053544D3332463430780053544D33C4 +:103B200032463432780053544D33324634343658AA +:103B300058000000012033000010410001105A001D +:103B4000031059000710310000000000083B000876 +:103B500013040000123B0008190400001C3B00087D +:103B600021040000263B0008009600000000000031 +:103B70000000000000000000000000000000000045 +:103B80006D130008591300089513000881130008ED +:103B90008D130008791300086513000851130008FD +:103BA000A113000800000000AD14000899140008DB +:103BB000D5140008C1140008CD140008B914000879 +:103BC000A514000891140008E1140008000000008A +:103BD000010000000000000063300000D83B000836 +:103BE00080260020902800204865782F50726F664C +:103BF00069434E430025424F415244252D424C001B +:103C00002553455249414C250000000002000000A8 +:103C100000000000C91600083517000840004000E9 +:103C2000302D0020402D0020020000000000000088 +:103C300003000000000000007917000800000000E9 +:103C400010000000502D00200000000001000000C6 +:103C50000000000028300020010102002D22000891 +:103C60003D210008D9210008BD21000843000000C3 +:103C7000743C000809024300020100C0320904003C +:103C800000010202010005240010010524010001C9 +:103C9000042402020524060001070582030800FF30 +:103CA00009040100020A00000007050102400000AB +:103CB000070581024000000012000000C03C00081F +:103CC0001201100102000040AE2D0110000201029D +:103CD000030100000403090425424F41524425001A +:103CE00043756265536F6C6F003031323334353653 +:103CF0003738394142434445460000000040000047 +:103D000000400000004000000040000000000100F2 +:103D1000000002000000020000000200000002009B +:103D2000000002000000020000000200004000004D +:103D300000400000004000000040000000000100C2 +:103D4000000002000000020000000200000002006B +:103D5000000002000000020000000200000000005D +:103D6000BD180008751B0008211C00084000400019 +:103D700088300020883000200100000098300020AA +:103D80008000000040010000030000006D61696ECA +:103D90000069646C650000000000812A00020000D8 +:103DA000AAAAAAAA00000024FFFF00000000000049 +:103DB00000A00A000000000000000000AAAAAAAAB1 +:103DC00000000000FFFF00000000000000000000F5 +:103DD0001400005400000000AAAAAAAA140000546B +:103DE000FFFF0000000000000000000080691000DC +:103DF00000000000AAAA8AAA40561000FFFF000097 +:103E00000070700700000000400100010000000089 +:103E1000AAAAAAAA00010000F7FF00000000000003 +:103E2000000000000000000000000000AAAAAAAAEA +:103E300000000000FFFF0000000000000000000084 +:103E40000000000000000000AAAAAAAA00000000CA +:103E5000FFFF000000000000000000000000000064 +:103E6000000000000A000000000000000300000045 +:103E70000000000000000000000000000000000042 +:103E80000000000000000000000000000000000032 +:103E90000000000000000000090000000000000019 +:103EA00000C01F0000000000FF0000009828002054 +:103EB000BC230020009600000000080096000000CF +:103EC0000008000004000000D43C000800000000CE +:103ED00000000000000000000000000000000000E2 +:043EE00000000000DE :00000001FF diff --git a/Tools/bootloaders/CubeYellow-bdshot_bl.bin b/Tools/bootloaders/CubeYellow-bdshot_bl.bin index d0e5fb604aaf0a..b21c17fb95ee69 100755 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 2ddca5245c64f9..2a7ebae909abbd 100644 --- a/Tools/bootloaders/CubeYellow-bdshot_bl.hex +++ b/Tools/bootloaders/CubeYellow-bdshot_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:100000000006022001020008850F0008050F000805 -:100010005D0F0008050F0008310F000803020008FB -:10002000030200080302000803020008ED2800088C +:1000000000060220010200080302000803020008A3 +:1000100003020008030200080302000803020008AC +:100020000302000803020008030200084938000820 :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:100050000302000803020008513A0008793A000838 -:10006000A13A0008C93A0008F13A00080302000862 +:100050000302000803020008ED3A0008153B0008FF +:100060003D3B0008653B00088D3B0008030200088B :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008193B0008DD +:10009000030200080302000803020008B53B000841 :1000A000030200080302000803020008030200081C -:1000B000293C0008030200080302000803020008AC +:1000B000C53C000803020008030200080302000810 :1000C00003020008030200080302000803020008FC -:1000D0000302000803020008ED3B0008013C000891 -:1000E0007D3B000803020008030200080302000829 +:1000D0000302000803020008893C00089D3C000858 +:1000E000193C00080302000803020008030200088C :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008A1300008AF +:10014000030200080302000803020008C12F000890 :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B -:100180000302000803020008153C000803020008EF +:100180000302000803020008B13C00080302000853 :10019000030200080302000803020008030200082B :1001A000030200080302000803020008030200081B :1001B000030200080302000803020008030200080B @@ -31,1010 +31,1018 @@ :1001D00003020008030200080302000803020008EB :1001E00003020008030200080302000803020008DB :1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B63A4880F3088892 -:10021000394880F3098839484EF60851CEF200017A -:10022000086040F20000CCF200004EF63471CEF2CD -:1002300000010860BFF34F8FBFF36F8F40F20000E3 -:10024000C0F2F0004EF68851CEF200010860BFF314 -:100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 -:100260003C71CEF200010860062080F31488BFF3D1 -: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 -:100CA000B1BF0120704700BF90230220014B18689C -:100CB000704700BF002004E0204B0246F0B51868E2 -:100CC0001F4BC0F30B06000C1F885D68BE4293F9F2 -:100CD000084022D09F89BE4221D01F8BBE4206D140 -:100CE00002240C2505FB04335D6893F90840B0F538 -:100CF000805F16D041F20103984208BF5A24013A9E -:100D0000013D0B460A4493420DD215F9016F581C60 -:100D10005EB1034600F8016CF5E70024E1E7012429 -:100D2000DFE74124EBE7184605E02C2590421D70D3 -:100D300001D2981C5C70401AF0BD00BF002004E096 -:100D40001422022070470000704700007047000026 -:100D5000002310B5934203D0CC5CC4540133F9E7AF -: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 +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F02F006FB4E +:1002700003F07CFA4FF055301F491B4A91423CBFB6 +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE702F01EFB03F0B6FA6C +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E702F006BB000602200022022040 +:1002F0000000000808ED00E00000022000060220D7 +:10030000F0400008002202206C220220702202200D +:10031000183A02200002000800020008000200084B +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F048FEFEE701F092 +:10035000D7FD00DFFEE7000038B500F01FFC02F01B +:100360004DFA054602F080FA0446C0B90E4B9D4294 +:1003700017D001339D4241F2883512BF0446002553 +:100380000124002002F044FA0CB100F075F800F0EE +:1003900055FD284600F0FAF800F06EF8F9E7002560 +:1003A000EFE70546EDE700BF010007B008B500F034 +:1003B000C1FBA0F120035842584108BD07B541F2E6 +:1003C0001203022101A8ADF8043000F0D1FB03B004 +:1003D0005DF804FB38B5302383F3118817480368B0 +:1003E0000BB101F0C7FE0023154A4FF47A71134890 +:1003F00001F0B6FE002383F31188124C236813B179 +:100400002368013B2360636813B16368013B636049 +:100410000D4D2B7833B963687BB9022000F080FC66 +:10042000322363602B78032B07D163682BB902203A +:1004300000F076FC4FF47A73636038BD70220220BE +:10044000D50300089023022088220220084B187050 +:1004500003280CD8DFE800F008050208022000F0AD +:100460005DBC022000F058BC024B00225A6070476D +:100470008822022090230220F8B53F4B3F4A1C46B9 +:100480001968013177D004339342F9D16268A242EE +:1004900071D33B4B9B6803F1006303F5C0339A4271 +:1004A00069D2002000F094FB0220FFF7CFFF354B0C +:1004B00000211A6C19641A6E19661A6E5A6C596406 +:1004C0005A6E59665A6E5A6942F080025A615A69E8 +:1004D00022F080025A615A691A6942F000521A6188 +:1004E0001A6922F000521A611B6972B64FF0E023BC +:1004F000C3F8084DD4E90004BFF34F8FBFF36F8FEB +:10050000214AC2F88410BFF34F8F536923F480331C +:100510005361BFF34F8FD2F8803043F6E076C3F3D8 +:10052000C905C3F34E335B0103EA060C29464CEAC6 +:1005300081770139C2F87472F9D2203B13F1200F90 +:10054000F2D1BFF34F8FBFF36F8FBFF34F8FBFF366 +:100550006F8F536923F4003353610023C2F8503284 +:10056000BFF34F8FBFF36F8F302383F3118885461E +:1005700080F308882047F8BD00800108208001082A +:10058000002202200038024000ED00E02DE9F04F8B +:1005900093B0B44B2022FF2100900AA89D6800F080 +:1005A000F7FBB14A1378A3B90121B0481170036079 +:1005B000302383F3118803680BB101F0DBFD0023C6 +:1005C000AB4A4FF47A71A94801F0CAFD002383F3C6 +:1005D0001188009B13B1A74B009A1A60A64A1378A2 +:1005E000032B03D000231370A24A53604FF0000A7C +:1005F000009CD3465646D146012000F08FFB24B123 +:100600009C4B1B68002B00F02682002000F092FA21 +:100610000390039B002BF2DB012000F07DFB039B8A +:10062000213B1F2BE8D801A252F823F0AD060008A9 +:10063000D506000869070008F9050008F905000853 +:10064000F9050008FB070008CB090008E5080008C9 +:10065000470900086F09000895090008F905000816 +:10066000A7090008F9050008190A00084D07000845 +:10067000F90500085D0A0008B90600084D070008E2 +:10068000F905000847090008F9050008F905000800 +:10069000F9050008F9050008F9050008F905000842 +:1006A000F9050008F9050008690700080220FFF7AE +:1006B0007DFE002840F0F981009B022105A8BAF1D7 +:1006C000000F08BF1C4641F21233ADF8143000F0A1 +:1006D0004FFA91E74FF47A7000F02CFA071EEBDB2B +:1006E0000220FFF763FE0028E6D0013F052F00F24D +:1006F000DE81DFE807F0030A0D101336052304211D +:1007000005A8059300F034FA17E004215548F9E7ED +:1007100004215A48F6E704215948F3E74FF01C0832 +:10072000404608F1040800F055FA0421059005A898 +:1007300000F01EFAB8F12C0FF2D101204FF00009A1 +:1007400000FA07F747EA0B0B5FFA8BFB00F06CFB34 +:1007500026B10BF00B030B2B08BF0024FFF72EFE76 +:100760004AE704214748CDE7002EA5D00BF00B0344 +:100770000B2BA1D10220FFF719FE074600289BD0C2 +:100780000120002600F024FA0220FFF75FFE1FFA86 +:1007900086F8404600F02CFA0446B0B10399404672 +:1007A0000136A1F140025142514100F031FA0028D6 +:1007B000EDD1BA46044641F21213022105A83E4685 +:1007C000ADF8143000F0D4F916E725460120FFF704 +:1007D0003DFE244B9B68AB4207D9284600F0FAF94E +:1007E000013040F067810435F3E70025224BBA461B +:1007F0003E461D701F4B5D60A8E7002E3FF45CAFC6 +:100800000BF00B030B2B7FF457AF0220FFF71EFEFC +:10081000322000F08FF9B0F10008FFF64DAF18F06C +:1008200003077FF449AF0F4A08EB05039268934230 +:100830003FF642AFB8F5807F3FF73EAF124BB84569 +:10084000019323DD4FF47A7000F074F90390039A5A +:10085000002AFFF631AF039A0137019B03F8012B01 +:10086000EDE700BF002202208C230220702202202C +:10087000D5030008902302208822022004220220AF +:10088000082202200C2202208C220220C820FFF71E +:100890008DFD074600283FF40FAF1F2D11D8C5F17D +:1008A00020020AAB25F0030084494245184428BFC2 +:1008B0004246019200F046FA019AFF217F4800F07B +:1008C00067FA4FEAA803C8F387027C4928460193D8 +:1008D00000F066FA064600283FF46DAF019B05EB79 +:1008E000830533E70220FFF761FD00283FF4E4AE03 +:1008F00000F0BAF900283FF4DFAE0027B846704B8D +:100900009B68BB4218D91F2F11D80A9B01330ED008 +:1009100027F0030312AA134453F8203C05934046E2 +:10092000042205A9043700F0E7FA8046E7E73846D5 +:1009300000F050F90590F2E7CDF81480042105A8E5 +:1009400000F016F902E70023642104A8049300F0E4 +:1009500005F900287FF4B0AE0220FFF727FD00283C +:100960003FF4AAAE049800F067F90590E6E700238B +:10097000642104A8049300F0F1F800287FF49CAEF1 +:100980000220FFF713FD00283FF496AE049800F014 +:1009900063F9EAE70220FFF709FD00283FF48CAE77 +:1009A00000F072F9E1E70220FFF700FD00283FF4B4 +:1009B00083AE05A9142000F06DF9074604210490C8 +:1009C00004A800F0D5F83946B9E7322000F0B2F8B3 +:1009D000071EFFF671AEBB077FF46EAE384A07EB19 +:1009E0000903926893423FF667AE0220FFF7DEFCF0 +:1009F00000283FF461AE27F003074F44B9453FF4A8 +:100A0000A5AE484609F1040900F0E4F80421059078 +:100A100005A800F0ADF8F1E74FF47A70FFF7C6FCD7 +:100A200000283FF449AE00F01FF9002844D00A9B8B +:100A300001330BD008220AA9002000F0B1F90028E8 +:100A40003AD02022FF210AA800F0A2F9FFF7B6FC55 +:100A50001C4801F0C9FA13B0BDE8F08F002E3FF436 +:100A60002BAE0BF00B030B2B7FF426AE002364217F +:100A700005A8059300F072F8074600287FF41CAE25 +:100A80000220FFF793FC804600283FF415AEFFF7E5 +:100A900095FC41F2883001F0A7FA059800F00AFAB7 +:100AA00046463C4600F0C0F9A6E506464EE64FF045 +:100AB000000901E6BA467EE637467CE68C22022033 +:100AC00000220220A08601002DE9F84F4FF47A732E +:100AD00006460D46002402FB03F7DFF85080DFF8DE +:100AE000509098F900305FFA84FA5A1C01D0A34262 +:100AF00010D159F824002A4631460368D3F820B0B3 +:100B00003B46D847854205D1074B012083F800A01A +:100B1000BDE8F88F0134042CE3D14FF4FA7001F0F2 +:100B200063FA0020F4E700BFDC2302201022022039 +:100B300014220220002307B5024601210DF107000F +:100B40008DF80730FFF7C0FF20B19DF8070003B014 +:100B50005DF804FB4FF0FF30F9E700000A4604217E +:100B600008B5FFF7B1FF80F00100C0B2404208BDF8 +:100B7000074B0A4630B41978064B53F8214001461A +:100B800023682046DD69044BAC4630BC604700BF9B +:100B9000DC23022014220220A086010070B50A4E38 +:100BA00000240A4D01F030FD3080286833888342EC +:100BB00008D901F023FD2B6804440133B4F5C03F8C +:100BC0002B60F2D370BD00BFDE23022098230220E9 +:100BD00001F0C8BD00F1006000F5C030006870474A +:100BE00000F10060920000F5C03001F053BD00003C +:100BF000054B1A68054B1B889B1A834202D9104487 +:100C000001F0FCBC0020704798230220DE23022064 +:100C100038B50446074D29B128682044BDE838405E +:100C200001F00CBD2868204401F0F0FC0028F3D04E +:100C300038BD00BF9823022010F0030309D1B0F59E +:100C4000846F04D200F10050A0F5712003681846AB +:100C500070470023FBE7000000F10050A0F5712071 +:100C6000D0F8200470470000064991F8243033B1D1 +:100C700000230822086A81F82430FFF7B1BF012061 +:100C8000704700BF9C230220014B1868704700BFCB +:100C9000002004E01E4B0138F0B51D680A1803233C +:100CA0001C482E0CC5F30B0435460788A7420BD110 +:100CB00044680B46013C934218461BD214F9010FBD +:100CC00048B103F8010BF6E7013B00F10800ECD155 +:100CD00091420ED20B4618462C24B6F5805F00F8E0 +:100CE000014B0AD1824202D94122981C5A70401A03 +:100CF000F0BD0846B6F5805FF9D041F201039D4290 +:100D0000F5D18242F3D95A2300F8013BEFE700BF47 +:100D1000002004E0242202207047000070470000F9 +:100D20007047000070B504464FF47A764CB1412C00 +:100D3000254628BF412506FB05F0641B01F054F948 +:100D4000F4E770BD002310B5934203D0CC5CC454CB +:100D50000133F9E710BD0000013810B510F9013F6B +:100D60003BB191F900409C4203D11AB10131013AE3 +:100D7000F4E71AB191F90020981A10BD1046FCE76B +:100D800003460246D01A12F9011B0029FAD1704716 +:100D900002440346934202D003F8011BFAE770476E +:100DA0002DE9F8431F4D14460746884695F8242040 +:100DB00052BBDFF870909CB395F824302BB92022F9 +:100DC000FF2148462F62FFF7E3FF95F824004146D4 +:100DD000C0F1080205EB8000A24228BF2246D6B22D +:100DE0009200FFF7AFFF95F82430A41B17441E4470 +:100DF0009044E4B2F6B2082E85F82460DBD1FFF708 +:100E000033FF0028D7D108E02B6A03EB820383422B +:100E1000CFD0FFF729FF0028CBD10020BDE8F88311 +:100E20000120FBE79C230220024B1A78024B1A7028 +:100E3000704700BFDC23022010220220F8B5184CB6 +:100E4000184800F02FFC2146164800F057FC246893 +:100E50004FF47A70144EE26E144DD2F80438114FEC +:100E600043F00203C2F80438FFF75CFF2046104944 +:100E700000F04CFDE26E0424D2F8043823F00203A3 +:100E8000C2F804384FF4E133336055F8040BB8422C +:100E900002D0314600F066FB013CF6D1F8BD00BF40 +:100EA000A03E0008982D0220C42302201422022014 +:100EB000A83E00080C4B70B50C4D04461E780C4B38 +:100EC00055F826209A420DD00A4B002118221846C8 +:100ED000FFF75EFF0460014655F82600BDE870404C +:100EE00000F040BB70BD00BFDC23022014220220B2 +:100EF000982D0220C423022030B50A44084D9142A7 +:100F00000DD011F8013B5840082340F30004013B89 +:100F10002C4013F0FF0384EA5000F6D1EFE730BD18 +:100F20002083B8ED026843681143016003B118479C +:100F300070470000024A136843F0C0031360704713 +:100F400000440040024A136843F0C0031360704736 +:100F500000480040024A136843F0C0031360704722 +:100F60000078004037B5274C274D204600F0EEFAB8 +:100F700004F11400009400234FF48072234900F020 +:100F8000ABF94FF48072224904F138000094214BF0 +:100F900000F024FA204BC4E91735204C204600F01D +:100FA000D5FA04F11400009400234FF480721C4918 +:100FB00000F092F94FF480721A4904F1380000945D +:100FC000194B00F00BFA194BC4E91735184C2046A1 +:100FD00000F0BCFA04F1140000234FF480721549AC +:100FE000009400F079F9144B4FF48072134904F126 +:100FF0003800009400F0F2F9114BC4E9173503B042 +:1010000030BD00BFE023022080F9370324250220F1 +:1010100024280220350F0008004400404C24022000 +:101020002426022024290220450F00080048004001 +:10103000B824022024270220550F0008242A022069 +:1010400000780040037C30B52E4C002918BF0C46B8 +:10105000012B13D12C4B98420AD12C4B1A6C42F421 +:1010600000321A641A6E42F400321A661B6E05E0F2 +:10107000274B98422FD0274B984235D02268036ED9 +:10108000C16D03EB52038466B3FBF2F3626815048F +:1010900042BF23F0070503F0070343EA4503CB6093 +:1010A000A36843F040034B60E36843F001038B60A7 +:1010B00042F4967343F001030B604FF0FF330B6271 +:1010C000510505D512F0102217D0B2F1805F16D06D +:1010D00080F8643030BD0D4B1A6C42F480221A64E3 +:1010E0001A6E42F48022C0E7084B1A6C42F080422C +:1010F0001A641A6E42F08042B7E77F23E8E73F2385 +:10110000E6E700BFB03D0008E023022000380240BF +:101110004C240220B82402202DE9F047C66D054674 +:101120003768F469210734621AD014F0080118BF37 +:101130004FF48071E20748BF41F02001A3074FF050 +:10114000300348BF41F04001600748BF41F08001D3 +:1011500083F31188281DFFF7E5FE002383F3118830 +:10116000E2050AD5302383F311884FF48061281DEE +:10117000FFF7D8FE002383F311884FF030094FF0BA +:10118000000A14F0200838D13B0616D54FF030097C +:1011900005F1380A200610D589F31188504600F071 +:1011A00051F9002836DA0821281DFFF7BBFE27F089 +:1011B00080033360002383F31188790614D5620617 +:1011C00012D5302383F31188D5E913239A4208D12D +:1011D0002B6C33B127F040071021281DFFF7A2FE2A +:1011E0003760002383F31188E30618D5AA6E1369CC +:1011F000ABB15069BDE8F047184789F31188736AAD +:10120000284695F86410194000F0BAF98AF311885D +:10121000F469B6E7B06288F31188F469BAE7BDE80B +:10122000F0870000F8B51546826804460B46AA42CE +:1012300000D28568A1692669761AB5420BD2184694 +:101240002A46FFF77FFDA3692B44A3612846A368C4 +:101250005B1BA360F8BD0CD9AF1B18463246FFF7E5 +:1012600071FD3A46E1683044FFF76CFDE3683B44AA +:10127000EBE718462A46FFF765FDE368E5E700005F +:1012800083689342F7B50446154600D28568D4E9D1 +:101290000460361AB5420BD22A46FFF753FD636944 +:1012A0002B4463612846A3685B1BA36003B0F0BDB9 +:1012B0000DD93246AF1B0191FFF744FD01993A4623 +:1012C000E0683144FFF73EFDE3683B44E9E72A4626 +:1012D000FFF738FDE368E4E710B50A440024C36172 +:1012E000029B8460C16002610362C0E90000C0E942 +:1012F000051110BD08B5D0E90532934201D18268CD +:1013000082B98268013282605A1C426119700021E0 +:10131000D0E904329A4224BFC368436100F080FEE2 +:10132000002008BD4FF0FF30FBE7000070B5302310 +:1013300004460E4683F31188A568A5B1A368A26987 +:10134000013BA360531CA36115782269934224BF1B +:10135000E368A361E3690BB120469847002383F358 +:101360001188284607E03146204600F049FE002853 +:10137000E2DA85F3118870BD2DE9F74F04460E4679 +:1013800017469846D0F81C904FF0300A8AF311881F +:101390004FF0000B154665B12A4631462046FFF74F +:1013A00041FF034660B94146204600F029FE00286F +:1013B000F1D0002383F31188781B03B0BDE8F08FD0 +:1013C000B9F1000F03D001902046C847019B8BF371 +:1013D0001188ED1A1E448AF31188DCE7C160C361ED +:1013E000009B82600362C0E905111144C0E900005E +:1013F00001617047F8B504460D461646302383F365 +:101400001188A768A7B1A368013BA36063695A1C50 +:1014100062611D70D4E904329A4224BFE3686361BB +:10142000E3690BB120469847002080F3118807E05C +:101430003146204600F0E4FD0028E2DA87F3118807 +:10144000F8BD0000D0E9052310B59A4201D18268A9 +:101450007AB982680021013282605A1C82611C784C +:1014600003699A4224BFC368836100F0D9FD204616 +:1014700010BD4FF0FF30FBE72DE9F74F04460E4655 +:1014800017469846D0F81C904FF0300A8AF311881E +:101490004FF0000B154665B12A4631462046FFF74E +:1014A000EFFE034660B94146204600F0A9FD002842 +:1014B000F1D0002383F31188781B03B0BDE8F08FCF +:1014C000B9F1000F03D001902046C847019B8BF370 +:1014D0001188ED1A1E448AF31188DCE7026843681C +:1014E0001143016003B11847704700001430FFF743 +:1014F00043BF00004FF0FF331430FFF73DBF000043 +:101500003830FFF7B9BF00004FF0FF333830FFF736 +:10151000B3BF00001430FFF709BF00004FF0FF31E8 +:101520001430FFF703BF00003830FFF763BF00003F +:101530004FF0FF323830FFF75DBF0000012914BFC4 +:101540006FF0130000207047FFF70CBD044B0360E1 +:1015500000234360C0E9023301230374704700BFD6 +:10156000C83D000810B53023044683F31188FFF707 +:1015700069FD02230020237480F3118810BD000050 +:1015800038B5C36904460D461BB904210844FFF76A +:10159000A5FF294604F11400FFF7ACFE002806DA87 +:1015A000201D4FF40061BDE83840FFF797BF38BDFC +:1015B000026843681143016003B118477047000097 +:1015C00013B5446BD4F8A4381A681178042915D1DE +:1015D000217C022912D11979012312898B401342EF +:1015E0000CD101A904F14C0001F07CFFD4F8A4480F +:1015F0000246019B2179206800F0D6F902B010BDA7 +:10160000143001F0FFBE00004FF0FF33143001F042 +:10161000F9BE00004C3001F0D1BF00004FF0FF33A5 +:101620004C3001F0CBBF0000143001F0CDBE000003 +:101630004FF0FF31143001F0C7BE00004C3001F014 +:101640009DBF00004FF0FF324C3001F097BF00000B +:1016500000207047D0F8A4381A6810B511780446F5 +:10166000042917D1017C022914D159790123528907 +:101670008B4013420ED1143001F060FE024648B197 +:10168000D4F8A4484FF4807361792068BDE8104015 +:1016900000F078B910BD0000406BFFF7DBBF000021 +:1016A000704700007FB5124B0125042604460360F5 +:1016B0000023057400F1840243602946C0E9023327 +:1016C0000C4B0290143001934FF48073009601F09C +:1016D00011FE094B04F29442294604F14C00029495 +:1016E000CDE900634FF4807301F0D8FE04B070BD03 +:1016F000F03D000899160008C11500080B6830225B +:1017000082F311880A7903EB820210624A790D3262 +:1017100043F822008A7912B103EB82031862022394 +:10172000C0F8A4180374002080F3118870470000EB +:1017300038B5037F044613B190F85430ABB9012596 +:10174000201D0221FFF734FF04F114006FF00101A6 +:10175000257700F071FC04F14C0084F854506FF0D0 +:101760000101BDE8384000F067BC38BD10B501216B +:1017700004460430FFF71CFF0023237784F854301D +:1017800010BD000038B504460025143001F0CAFD34 +:1017900004F14C00257701F099FE201D84F8545087 +:1017A0000121FFF705FF2046BDE83840FFF752BF93 +:1017B00090F85C3003F06003202B06D190F85D2098 +:1017C0000023212A03D81F2A06D800207047222A86 +:1017D000FBD1C0E9143303E0034A026507224265E6 +:1017E00083650120704700BF3C220220D0F8A43856 +:1017F00037B51A680446117804291AD1017C0229E8 +:1018000017D11979012312898B40134211D100F1AC +:101810004C05284601F01AFF58B101A9284601F0ED +:1018200061FED4F8A4480246019B2179206800F0AB +:10183000BBF803B030BD000000EB8103F0B51E6AB9 +:1018400085B004460D46FEB1302383F3118804EBC6 +:101850008507301D0821FFF7ABFEFB6806F14C0041 +:101860005B691B681BB1019001F04AFE019803A956 +:1018700001F038FE024648B1039B2946204600F09D +:1018800093F8002383F3118805B0F0BDFB685A6913 +:101890001268002AF5D01B8A013B1340F1D104F1F4 +:1018A0005C02EAE70D3138B550F82140DCB1302355 +:1018B00083F31188D4F8A4281368527903EB8203C8 +:1018C000DB689B695D6845B104216018FFF770FE15 +:1018D000294604F1140001F03BFD2046FFF7BAFE53 +:1018E000002383F3118838BD7047000001F088B8E9 +:1018F00001232822002110B5044600F8243BFFF7FD +:1019000047FA0023C4E9013310BD000038B504468E +:10191000302383F3118800254160C0E90355C0E9F5 +:101920000555C0E9075501F07BF80223237085F3C4 +:101930001188284638BD000070B500EB81030546CC +:1019400050690E461446DA6018B110220021FFF7E4 +:101950001FFAA06918B110220021FFF719FA3146C9 +:101960002846BDE8704001F025B90000826802F009 +:10197000011282600022C0E90422C0E9062202624C +:1019800001F0A4B9F0B4012500EB810447898D4032 +:10199000E4683D43A469458123600023A26063603D +:1019A000F0BC01F0BFB90000F0B4012500EB8104E8 +:1019B00007898D40E4683D43646905812360002305 +:1019C000A2606360F0BC01F039BA000070B5022378 +:1019D0000025044603704566056280F84C50C0E956 +:1019E0000255C0E90455C0E9065501F07FF8636867 +:1019F0001B6823B129462046BDE87040184770BDDA +:101A00000378052B10B504460AD080F8683005230A +:101A1000037043681B680BB1042198470023A3603F +:101A200010BD00000178052906D190F868204368B0 +:101A300002701B6803B118477047000070B590F83A +:101A40004C30044613B1002380F84C3004F15C02A2 +:101A5000204601F05DF963689B68B3B994F85C3087 +:101A600013F0600535D00021204601F00FFC002165 +:101A7000204601F001FC63681B6813B10621204673 +:101A80009847062384F84C3070BD204698470028BC +:101A9000E4D0B4F86230626D9A4288BF636594F90D +:101AA0005C30656D002B4FF0300380F20381002D18 +:101AB00000F0F280092284F84C2083F31188002181 +:101AC0002046D4E91423FFF76FFF002383F3118826 +:101AD000DAE794F85D2003F07F0343EA022340F243 +:101AE0000232934200F0C58021D8B3F5807F48D000 +:101AF0000DD8012B3FD0022B00F09380002BB2D1E8 +:101B000004F16402226502226265A365C1E7B3F5B0 +:101B1000817F00F09B80B3F5407FA4D194F85E30C4 +:101B2000012BA0D1B4F8643043F0020332E0B3F5E6 +:101B3000006F4DD017D8B3F5A06F31D0A3F5C063B7 +:101B4000012B90D86368204694F85E205E6894F874 +:101B50005F10B4F86030B047002884D04368236534 +:101B6000036863651AE0B3F5106F36D040F60242A1 +:101B700093427FF478AF5C4B2365022363650023B7 +:101B8000C3E794F85E30012B7FF46DAFB4F8643096 +:101B900023F00203A4F86430C4E91455A56578E77E +:101BA000B4F85C30B3F5A06F0ED194F85E302046E7 +:101BB00084F8663000F0F2FF63681B6813B10121FE +:101BC00020469847032323700023C4E914339CE77D +:101BD00004F1670323650123C3E72378042B10D1A5 +:101BE000302383F311882046FFF7C0FE85F3118868 +:101BF0000321636884F8675021701B680BB120468D +:101C0000984794F85E30002BDED084F867300423C8 +:101C1000237063681B68002BD6D0022120469847AA +:101C2000D2E794F8603020461D0603F00F010AD574 +:101C300001F060F8012804D002287FF414AF2B4B88 +:101C40009AE72B4B98E701F047F8F3E794F85E30FA +:101C5000002B7FF408AF94F8603013F00F01B3D07D +:101C60001A06204602D501F025FBADE701F018FB6E +:101C7000AAE794F85E30002B7FF4F5AE94F860305C +:101C800013F00F01A0D01B06204602D501F0FEFA8A +:101C90009AE701F0F1FA97E7142284F84C2083F3D5 +:101CA00011882B462A4629462046FFF76BFE85F30E +:101CB0001188E9E65DB1152284F84C2083F3118880 +:101CC00000212046D4E91423FFF75CFEFDE60B2239 +:101CD00084F84C2083F311882B462A462946204657 +:101CE000FFF762FEE3E700BF203E0008183E000851 +:101CF0001C3E000838B590F84C300446002B3ED00E +:101D0000063BDAB20F2A34D80F2B32D8DFE803F0C3 +:101D100037313108223231313131313131313737D8 +:101D2000456DB0F862309D4214D2C3681B8AB5FB82 +:101D3000F3F203FB12556DB9302383F311882B4660 +:101D40002A462946FFF730FE85F311880A2384F8D6 +:101D50004C300EE0142384F84C30302383F3118888 +:101D6000002320461A461946FFF70CFE002383F392 +:101D7000118838BD836D03B198470023E7E7002140 +:101D8000204601F083FA0021204601F075FA6368CD +:101D90001B6813B10621204698470623D7E70000A9 +:101DA00010B590F84C300446142B29D017D8062BC8 +:101DB00005D001D81BB110BD093B022BFBD8002177 +:101DC000204601F063FA0021204601F055FA6368CD +:101DD0001B6813B1062120469847062319E0152BEE +:101DE000E9D10B2380F84C30302383F31188002392 +:101DF0001A461946FFF7D8FD002383F31188DAE766 +:101E0000C3689B695B68002BD5D1836D03B198478C +:101E1000002384F84C30CEE7002382680375036901 +:101E20001B6899689142FBD25A6803604260106057 +:101E30005860704700238268037503691B689968BE +:101E40009142FBD85A680360426010605860704746 +:101E500008B50846302383F311880B7D032B05D08A +:101E6000042B0DD02BB983F3118808BD8B69002298 +:101E70001A604FF0FF338361FFF7CEFF0023F2E7D4 +:101E8000D1E9003213605A60F3E70000FFF7C4BFE6 +:101E9000054BD96808751868026853601A600122FA +:101EA000D8600275FEF73EBA282B02200C4B30B5E5 +:101EB000DD684B1C87B004460FD02B46094A6846A4 +:101EC00000F04EF92046FFF7E3FF009B13B1684690 +:101ED00000F050F9A86907B030BDFFF7D9FFF9E766 +:101EE000282B0220511E0008044B1A68DB689068FA +:101EF0009B68984294BF002001207047282B022045 +:101F0000084B10B51C68D868226853601A6001221B +:101F1000DC602275FFF78EFF01462046BDE81040C9 +:101F2000FEF700BA282B022038B5074C0123002504 +:101F3000064907482370656001F0C0FB0223237047 +:101F400085F3118838BD00BF902D0220283E00087F +:101F5000282B022000F044B9034A516853685B1AE9 +:101F60009842FBD8704700BF001000E08B6002234E +:101F7000086108468B8270478368A3F1840243F8A6 +:101F8000142C026943F8442C426943F8402C094A56 +:101F900043F8242CC268A3F1200043F8182C022235 +:101FA00003F80C2C002203F80B2C034A43F8102CE6 +:101FB000704700BF3D030008282B022008B5FFF73B +:101FC000DBFFBDE80840FFF761BF0000024BDB68A4 +:101FD00098610F20FFF75CBF282B0220302383F38A +:101FE0001188FFF7F3BF000008B50146302383F3E3 +:101FF00011880820FFF75AFF002383F3118808BDDA +:10200000064BDB6839B1426818605A601360436060 +:102010000420FFF74BBF4FF0FF307047282B022002 +:102020000368984206D01A680260506018469961A9 +:10203000FFF72CBF7047000038B504460D462068F6 +:10204000844200D138BD036823605C608561FFF77E +:102050001DFFF4E7036810B59C68A2420CD85C68C9 +:102060008A600B604C602160596099688A1A9A6096 +:102070004FF0FF33836010BD121B1B68ECE70000BC +:102080000A2938BF0A2170B504460D460A26601990 +:1020900001F00EFB01F0FAFA041BA54203D8751CEF +:1020A00004462E46F3E70A2E04D90120BDE870400D +:1020B00001F044BB70BD0000F8B5144B0D460A2A70 +:1020C0004FF00A07D96103F11001826038BF0A227C +:1020D000416019691446016048601861A81801F050 +:1020E000D9FA01F0D3FA431B0646A34206D37C1C5F +:1020F00028192746354601F0DBFAF2E70A2F04D902 +:102100000120BDE8F84001F019BBF8BD282B0220E2 +:10211000F8B506460D4601F0B9FA0F4A134653F8D2 +:10212000107F9F4206D12A4601463046BDE8F8405E +:10213000FFF7C2BFD169BB68441A2C1928BF2C46CF +:10214000A34202D92946FFF79BFF224631460348A6 +:10215000BDE8F840FFF77EBF282B0220382B022075 +:10216000C0E90323002310B45DF8044B4361FFF77B +:10217000CFBF000010B5194C236998420DD081687B +:10218000D0E9003213605A609A680A449A600023CA +:1021900003604FF0FF33A36110BD0268234643F88C +:1021A000102F53600022026022699A4203D1BDE8D9 +:1021B000104001F077BA936881680B44936001F096 +:1021C00065FA2269E1699268441AA242E4D911448D +:1021D000BDE81040091AFFF753BF00BF282B0220AB +:1021E0002DE9F047DFF8BC8008F110072C4ED8F835 +:1021F000105001F04BFAD8F81C40AA68031B9A4211 +:102200003ED814444FF00009D5E90032C8F81C400C +:1022100013605A60C5F80090D8F81030B34201D16D +:1022200001F040FA89F31188D5E90331284698472F +:10223000302383F311886B69002BD8D001F026FA84 +:102240006A69A0EB040982464A450DD2022001F0DA +:1022500075FA0022D8F81030B34208D1514628460A +:10226000BDE8F047FFF728BF121A2244F2E712EB4D +:1022700009092946384638BF4A46FFF7EBFEB5E75D +:10228000D8F81030B34208D01444C8F81C00211A02 +:10229000A960BDE8F047FFF7F3BEBDE8F08700BFD7 +:1022A000382B0220282B022000207047FEE7000078 +:1022B000704700004FF0FF307047000002290CD03B +:1022C000032904D00129074818BF00207047032ABA +:1022D00005D8054800EBC20070470448704700204D +:1022E000704700BF043F00084C220220B83E00089F +:1022F00070B59AB005460846144601A900F0C2F828 +:1023000001A8FEF73DFD431C0022C6B25B0010464B +:10231000C5E9003423700323023404F8013C01AB07 +:10232000D1B202348E4201D81AB070BD13F8011B2D +:10233000013204F8010C04F8021CF1E708B530235F +:1023400083F311880348FFF751FA002383F31188C0 +:1023500008BD00BF982D022090F85C3003F01F02EA +:10236000012A07D190F85D200B2A03D10023C0E990 +:10237000143315E003F06003202B08D1B0F860306F +:102380002BB990F85D20212A03D81F2A04D8FFF723 +:102390000FBA222AEBD0FAE7034A02650722426508 +:1023A00083650120704700BF4322022007B505293D +:1023B00017D8DFE801F0191603191920302383F329 +:1023C0001188104A01210190FFF7B6FA0198022105 +:1023D0000D4AFFF7B1FA0D48FFF7D4F9002383F354 +:1023E000118803B05DF804FB302383F3118807489C +:1023F000FFF79EF9F2E7302383F311880348FFF7D4 +:10240000B5F9EBE7583E00087C3E0008982D022005 +:1024100038B50C4D0C4C2A460C4904F10800FFF766 +:1024200067FF05F1CA0204F110000949FFF760FFD8 +:1024300005F5CA7204F118000649BDE83840FFF7F7 +:1024400057BF00BF703602204C220220343E0008E5 +:10245000413E00084C3E000870B5044608460D4653 +:10246000FEF78EFCC6B22046013403780BB918463D +:1024700070BD32462946FEF76FFC0028F3D10120DB +:10248000F6E700002DE9F04705460C46FEF778FC1C +:102490002B49C6B22846FFF7DFFF08B10A36F6B26D +:1024A00028492846FFF7D8FF08B11036F6B2632E48 +:1024B0000BD8DFF88C80DFF88C90234FDFF894A0E6 +:1024C0002E7846B92670BDE8F08729462046BDE83B +:1024D000F04701F04FBC252E2ED107224146284659 +:1024E000FEF73AFC70B9194B224603F1100153F87C +:1024F000040B8B4242F8040BF9D11B7807351134D9 +:102500001370DDE7082249462846FEF725FC98B9F6 +:10251000A21C0F4B197802320909C95D02F8041C8C +:1025200013F8011B01F00F015345C95D02F8031CAC +:10253000F0D118340835C3E7013504F8016BBFE763 +:10254000243F00084C3E00083E3F00082C3F000896 +:1025500020F4F01F2CF4F01FBFF34F8F024AD36812 +:10256000DB03FCD4704700BF003C024008B5074BBA +:102570001B7853B9FFF7F0FF054B1A69002A04DAFC +:10258000044A5A6002F188325A6008BDCE380220EF +:10259000003C02402301674508B5054B1B7833B961 +:1025A000FFF7DAFF034A136943F00043136108BDE4 +:1025B000CE380220003C02400B28F0B516D80C4C57 +:1025C0000C4923787BB90E460B4D0C234FF000626B +:1025D000013B55F8047B46F8042B13F0FF033A4403 +:1025E000F6D10123237051F82000F0BD0020FCE754 +:1025F00000390220D0380220503F0008014B53F828 +:1026000020007047503F00080C2070470B2810B581 +:10261000044601D9002010BDFFF7CEFF064B53F84A +:1026200024301844C21A0BB90120F4E712680132B1 +:10263000F0D1043BF6E700BF503F00080B2810B56F +:10264000044621D8FFF788FFFFF790FF0F4AF323D6 +:10265000D360C300DBB243F4007343F002031361A1 +:10266000136943F480331361FFF776FFFFF7A4FF8C +:10267000074B53F8241000F0D9F82046FFF78CFFE1 +:10268000BDE81040FFF7C2BF002010BD003C024073 +:10269000503F0008F8B512F00103144642D18218E9 +:1026A000B2F1026F57D82D4B1B6813F0010352D0C3 +:1026B000FFF75CFF2A4DF32340F20127EB60FFF7A1 +:1026C0004BFF032C15D824F00104401A40F20117E7 +:1026D0006618234CB14200EB0105236924D123F095 +:1026E000010301202361FFF757FFF8BD043C0430CC +:1026F000E7E78307E7D12B6923F440732B612B694C +:102700003B432B6151F8046B0660BFF34F8FFFF71B +:1027100023FF03689E42E9D02B6923F001032B615C +:10272000FFF73AFF0020E0E723F4407323612369B9 +:102730003B4323610B882B80BFF34F8FFFF70CFFC8 +:102740002D88ADB231F8023BAB42C3D0236923F0F0 +:1027500001032361E4E71846C7E700BF00380240E1 +:10276000003C0240084908B50B7828B11BB9FFF7B7 +:10277000FDFE01230B7008BD002BFCD00870BDE8E6 +:102780000840FFF709BF00BFCE3802200244074BC4 +:10279000D2B210B5904200D110BD441C00B253F823 +:1027A000200041F8040BE0B2F4E700BF50280040DD +:1027B0000F4B30B51C6F240407D41C6F44F4007415 +:1027C0001C671C6F44F400441C670A4C02442368D5 +:1027D000D2B243F480732360074B904200D130BDE6 +:1027E000441C51F8045B00B243F82050E0B2F4E717 +:1027F00000380240007000405028004007B5012218 +:1028000001A90020FFF7C2FF019803B05DF804FBA7 +:1028100013B50446FFF7F2FFA04205D0012201A93B +:1028200000200194FFF7C4FF02B010BD0144BFF3C4 +:102830004F8F064B884204D3BFF34F8FBFF36F8F88 +:102840007047C3F85C022030F4E700BF00ED00E001 +:10285000034B1A681AB9034AD2F874281A607047F1 +:10286000043902200030024008B5FFF7F1FF024BA7 +:102870001868C0F3407008BD0439022070B5BFF37A +:102880004F8FBFF36F8F1A4A0021C2F85012BFF367 +:102890004F8FBFF36F8F536943F400335361BFF31E +:1028A0004F8FBFF36F8FC2F88410BFF34F8FD2F8F2 +:1028B000803043F6E074C3F3C900C3F34E335B01C9 +:1028C00003EA0406014646EA81750139C2F86052FE +:1028D000F9D2203B13F1200FF2D1BFF34F8F536990 +:1028E00043F480335361BFF34F8FBFF36F8F70BDDD +:1028F00000ED00E0FEE70000214B2248224A70B5BF +:10290000904237D3214BC11EDA1C121A22F0030267 +:102910008B4238BF00220021FEF73AFA1C4A0023FE +:10292000C2F88430BFF34F8FD2F8803043F6E074A2 +:10293000C3F3C900C3F34E335B0103EA0406014647 +:1029400046EA81750139C2F86C52F9D2203B13F185 +:10295000200FF2D1BFF34F8FBFF36F8FBFF34F8FB5 +:10296000BFF36F8F0023C2F85032BFF34F8FBFF316 +:102970006F8F70BD53F8041B40F8041BC0E700BF05 +:102980005C410008183A0220183A0220183A022046 +:1029900000ED00E070B5D0E91B4300224FF0FF3599 +:1029A0009E6804EB42135101D3F80009002805DAB0 +:1029B000D3F8000940F08040C3F80009D3F8000BB9 +:1029C000002805DAD3F8000B40F08040C3F8000B74 +:1029D000013263189642C3F80859C3F8085BE0D285 +:1029E0004FF00113C4F81C3870BD0000890141F09C +:1029F0002001016103699B06FCD41220FFF7ACBAE9 +:102A000010B5054C2046FEF773FF4FF0A043E36678 +:102A1000024B236710BD00BF08390220A43F000805 +:102A200070B503780546012B50D12A4BC46E9842ED +:102A30001BD1294B0E2143205A6B42F080025A636E +:102A40005A6D42F080025A655A6D5A6942F080020E +:102A50005A615A6922F080025A615B6900F034FCC5 +:102A60001E4BE3601E4BC4F800380023EE6EC4F822 +:102A7000003EC02323604FF40413A3633369002B8B +:102A8000FCDA01230C203361FFF766FA3369DB07B8 +:102A9000FCD41220FFF760FA3369002BFCDA002621 +:102AA0002846A660FFF776FF6B68C4F81068DB68FD +:102AB000C4F81468C4F81C684BB90A4BA3614FF002 +:102AC000FF336361A36843F00103A36070BD064B4D +:102AD000F4E700BF083902200038024040140040EB +:102AE00003002002003C30C0083C30C0F8B5C46E82 +:102AF000054600214FF000662046FFF777FF296F5B +:102B000000234FF001128F684FF0FF30C4F83438C3 +:102B1000C4F81C2804EB431201339F42C2F8006939 +:102B2000C2F8006BC2F80809C2F8080BF2D20B68B1 +:102B3000EA6E6B67636210231361166916F0100664 +:102B4000FBD11220FFF708FAD4F8003823F4FE6313 +:102B5000C4F80038A36943F4402343F01003A36191 +:102B60000923C4F81038C4F814380A4BEB604FF04E +:102B7000C043C4F8103B084BC4F8003BC4F81069CC +:102B8000C4F800396B6F03F1100243F480136A67D5 +:102B9000A362F8BD803F000840800010C26E90F82C +:102BA0006610D2F8003823F4FE6343EA0113C2F83A +:102BB000003870472DE9F84300EB8103C56E0C46E1 +:102BC0008046DA680FFA81F94801166806F00306B4 +:102BD000731E022B05EB41134FF0000194BFB604A6 +:102BE000384EC3F8101B4FF0010104F1100398BFD9 +:102BF00006F1805601FA03F3916998BF06F5004685 +:102C000000293AD0578A04F15801374349016F50DF +:102C1000D5F81C180B430021C5F81C382B180127C8 +:102C2000C3F81019A7405369611E9BB3138A928B96 +:102C30009B08012A88BF5343D8F87420981842EAA9 +:102C4000034301F140022146C8F87400284605EB11 +:102C500082025360FFF7CAFE08EB8900C3681B8A33 +:102C600043EA845348341E4364012E51D5F81C387E +:102C70001F43C5F81C78BDE8F88305EB4917D7F862 +:102C8000001B21F40041C7F8001BD5F81C1821EAED +:102C90000303C0E704F13F030B4A2846214605EB36 +:102CA00083035A60FFF7A2FE05EB4910D0F8003904 +:102CB00023F40043C0F80039D5F81C3823EA07078D +:102CC000D7E700BF0080001000040002026F126806 +:102CD0004267FFF75FBE00005831C36E49015B5881 +:102CE00013F4004004D013F4001F0CBF0220012095 +:102CF000704700004831C36E49015B5813F400402F +:102D000004D013F4001F0CBF022001207047000004 +:102D100000EB8101CB68196A0B6813604B68536044 +:102D20007047000000EB810330B5DD68AA691368C5 +:102D3000D36019B9402B84BF402313606B8A146899 +:102D4000C26E1C4402EB4110013C09B2B4FBF3F427 +:102D50006343033323F0030343EAC44343F0C04314 +:102D6000C0F8103B2B6803F00303012B0ED1D2F8FF +:102D7000083802EB411013F4807FD0F8003B14BFF9 +:102D800043F0805343F00053C0F8003B02EB411284 +:102D9000D2F8003B43F00443C2F8003B30BD0000D2 +:102DA0002DE9F041244D0446EE6E06EB4013D3F8B6 +:102DB000087B3807C3F8087B0AD5D6F814381907FA +:102DC00006D505EB840321462846DB685B689847F7 +:102DD000FA071FD5D6F81438DB071BD505EB84039B +:102DE000D968CCB98B69488A5A68B2FBF0F600FB07 +:102DF00016228AB91868DA6890420DD2121AC3E90D +:102E00000024302383F311880B482146FFF78AFF03 +:102E100084F31188BDE8F081012303FA04F26B8981 +:102E200023EA02036B81CB68002BF3D021460248D2 +:102E3000BDE8F041184700BF0839022000EB8103CC +:102E40004A0170B5DD68C36E6C692668E66056BBE2 +:102E50001A444FF40020C2F810092A6802F0030255 +:102E6000012A0AB20ED1D3F8080803EB421410F479 +:102E7000807FD4F8000914BF40F0805040F000502B +:102E8000C4F8000903EB4212D2F8000940F00440F4 +:102E9000C2F800090122D3F8340802FA01F1014313 +:102EA000C3F8341870BD19B9402E84BF402020608B +:102EB00020681A442E8A8419013CB4FBF6F440EAD7 +:102EC000C44040F00050C6E72DE9F8433B4D0446AE +:102ED0004701EE6E06EB4013D3F8088918F0010F96 +:102EE000C3F808891AD0D6F81038DB0716D505EBD9 +:102EF0008003D9684B691868DA68904230D2121A98 +:102F00004FF000091A60C3F80490302383F311884E +:102F100021462846FFF792FF89F3118818F0800FA9 +:102F20001CD0D6F834380126A640334216D005EB23 +:102F300084030134ED6ED3F80CC0E4B22F44DCF806 +:102F4000142005EB0434D2F800E05168714515D324 +:102F5000D5F8343823EA0606C5F83468BDE8F883A6 +:102F6000012303FA04F22B8923EA02032B818B68E5 +:102F7000002BD3D0214628469847CFE7AEEB01037C +:102F8000BCF81000834228BF0346D7F8180980B266 +:102F9000B3EB800FE2D89068A0F1040959F8048FD0 +:102FA000C4F80080A0EB09089844B8F1040FF5D8E4 +:102FB00018440B4490605360C7E700BF08390220F3 +:102FC0002DE9F74FA44CE56E6E69AB691E4016F40F +:102FD00080586E6107D02046FEF7F8FC03B0BDE8CC +:102FE000F04F00F069BC002E12DAD5F8003E9B07C6 +:102FF00005D0D5F8003E23F00303C5F8003ED5F810 +:103000000438954823F00103C5F80438FEF70AFD9B +:10301000370505D59048FFF7BDFC8F48FEF7F0FC5B +:10302000B0040CD5D5F8083813F0060FEB6823F47C +:1030300070530CBF43F4105343F4A053EB603107BB +:103040001BD56368DB681BB9AB6923F00803AB6170 +:103050002378052B0CD1D5F8003E9A0705D0D5F87A +:10306000003E23F00303C5F8003E7B48FEF7DAFC80 +:103070006368DB680BB178489847F30200F18980F8 +:10308000B70227D5D4F86C9000274FF0010ADFF87B +:10309000C8B109EB4712D2F8003B03F44023B3F563 +:1030A000802F11D1D2F8003B002B0DDA62890AFA89 +:1030B00007F322EA0303638104EB8703DB68DB6821 +:1030C00013B13946584698470137236FFFB29B68C2 +:1030D0009F42DED9F00617D5E76E3A6AC2F30A10AE +:1030E00002F00F0302F4F012B2F5802F00F0988086 +:1030F000B2F5402F08D104EB8303002207F5805777 +:10310000DB681B6A90427ED13303D5F818481DD581 +:10311000E70302D50020FFF743FEA50302D50120F7 +:10312000FFF73EFE600302D50220FFF739FE2103C0 +:1031300002D50320FFF734FEE20202D50420FFF798 +:103140002FFEA30202D50520FFF72AFE77037FF5A5 +:1031500045AFE60702D50020FFF7B6FEA50702D56A +:103160000120FFF7B1FE600702D50220FFF7ACFE99 +:10317000210702D50320FFF7A7FEE20602D50420AF +:10318000FFF7A2FEA3067FF529AF0520FFF79CFEFF +:1031900024E7E36E00274FF00109DFF8BCA001939C +:1031A000236F5FFA87FB9B689B453FF669AF019BE6 +:1031B00003EB4B13D3F8001901F44021B1F5802F34 +:1031C0001FD1D3F8001900291BDAD3F8001941F0F8 +:1031D0009041C3F80019D3F800190029FBDB5946C8 +:1031E000E06EFFF703FC218909FA0BF321EA0303E0 +:1031F000238104EB8B03DB689B6813B1594650466F +:1032000098470137CCE7910701D1D7F80080072A0A +:1032100002F101029CBF03F8018B4FEA182871E705 +:10322000023307F5805704EB83025268D2F818C0C6 +:10323000DCF80820DCE9001CA1EB0C0C0021884222 +:103240000CD104EB830463689B699A6802449A601A +:103250005A6802445A6057E70839022011F0030FF8 +:1032600001D1D7F800808C4501F1010184BF02F83B +:10327000018B4FEA1828E2E7C36E03EB4111D1F846 +:10328000003B43F40013C1F8003B7047C36E03EBEF +:103290004111D1F8003943F40013C1F800397047E7 +:1032A000C36E03EB4111D1F8003B23F40013C1F8C6 +:1032B000003B7047C36E03EB4111D1F8003923F492 +:1032C0000013C1F800397047090100F16043012281 +:1032D00003F56143C9B283F8001300F01F039A405D +:1032E00043099B0003F1604303F56143C3F8802168 +:1032F0001A60704730B50433039C0172002104FB4F +:103300000325C160C0E90653049B0363059BC0E924 +:103310000000C0E90422C0E90842C0E90A11436381 +:1033200030BD00000022416AC260C0E90411C0E95A +:103330000A226FF00101FEF77FBE0000D0E90432DF +:10334000934201D1C2680AB9181D70470020704726 +:10335000036919600021C2680132C260C269134466 +:1033600082699342036124BF436A0361FEF758BE3A +:1033700038B504460D46E3683BB162690020131D71 +:103380001268A3621344E36207E0237A33B9294643 +:103390002046FEF735FE0028EDDA38BD6FF001005B +:1033A000FBE70000C368C269013BC3604369134483 +:1033B00082699342436124BF436A4361002383626D +:1033C000036B03B11847704770B53023044683F38D +:1033D0001188866A3EB9FFF7CBFF054618B186F320 +:1033E0001188284670BDA36AE26A13F8015B934214 +:1033F000A36202D32046FFF7D5FF002383F3118891 +:10340000EFE700002DE9F84F04460E4617469846B0 +:103410004FF0300989F311880025AA46D4F828B066 +:10342000BBF1000F09D141462046FFF7A1FF20B1B3 +:103430008BF311882846BDE8F88FD4E90A12A7EB70 +:10344000050B521A934528BF9346BBF1400F1BD979 +:10345000334601F1400251F8040B914243F8040B4A +:10346000F9D1A36A403640354033A362D4E90A2338 +:103470009A4202D32046FFF795FF8AF31188BD4296 +:10348000D8D289F31188C9E730465A46FDF75AFC6D +:10349000A36A5E445D445B44A362E7E710B5029C07 +:1034A0000433017203FB0421C460C0E90613002346 +:1034B000C0E90A33039B0363049BC0E90000C0E931 +:1034C0000422C0E90842436310BD0000026A6FF0A5 +:1034D0000101C260426AC0E904220022C0E90A2256 +:1034E000FEF7AABDD0E904239A4201D1C26822B9ED +:1034F000184650F8043B0B60704700231846FAE763 +:10350000C3680021C2690133C360436913448269FF +:103510009342436124BF436A4361FEF781BD0000CB +:1035200038B504460D46E3683BB1236900201A1DF7 +:10353000A262E2691344E36207E0237A33B92946C1 +:103540002046FEF75DFD0028EDDA38BD6FF0010082 +:10355000FBE7000003691960C268013AC260C269F2 +:10356000134482699342036124BF436A03610023C9 +:103570008362036B03B118477047000070B53023B6 +:103580000D460446114683F31188866A2EB9FFF76B +:10359000C7FF10B186F3118870BDA36A1D70A36ABE +:1035A000E26A01339342A36204D3E16920460439FD +:1035B000FFF7D0FF002080F31188EDE72DE9F84FE9 +:1035C00004460D46904699464FF0300A8AF311881A +:1035D0000026B346A76A4FB949462046FFF7A0FF29 +:1035E00020B187F311883046BDE8F88FD4E90A0787 +:1035F0003A1AA8EB0607974228BF1746402F1BD957 +:1036000005F1400355F8042B9D4240F8042BF9D1F5 +:10361000A36A40364033A362D4E90A239A4204D312 +:10362000E16920460439FFF795FF8BF31188464581 +:10363000D9D28AF31188CDE729463A46FDF782FBB5 +:10364000A36A3D443E443B44A362E5E7D0E904233A +:103650009A4217D1C3689BB1836A8BB1043B9B1A12 +:103660000ED01360C368013BC360C3691A44836909 +:103670009A42026124BF436A0361002383620123EB +:10368000184670470023FBE700F040B94FF0804335 +:10369000586A70474FF08043002258631A61022233 +:1036A000DA6070474FF080430022DA607047000014 +:1036B0004FF0804358637047FEE7000070B51B4B26 +:1036C0000025044686B058600E468562016300F00E +:1036D000CBF804F11003A560E562C4E904334FF0B0 +:1036E000FF33C4E90044C4E90635FFF7CFFF2B469A +:1036F000024604F134012046C4E9082380230C4A21 +:103700002565FEF733FC01230A4AE0600092037549 +:10371000684672680192B268CDE90223064BCDE992 +:103720000435FEF74BFC06B070BD00BF902D0220A3 +:10373000B03F0008B53F0008B9360008024AD36A16 +:103740001843D062704700BF282B02204B684360AB +:103750008B688360CB68C3600B6943614B6903620C +:103760008B6943620B6803607047000008B52C4BFF +:1037700040F2FF712B481A690A431A611A6922F450 +:10378000FF6222F007021A611A691A6B0A431A6370 +:103790001A6D0A431A65244A1B6D1146FFF7D6FFBE +:1037A00000F5806002F11C01FFF7D0FF00F580609A +:1037B00002F13801FFF7CAFF00F5806002F1540101 +:1037C000FFF7C4FF00F5806002F17001FFF7BEFF54 +:1037D00000F5806002F18C01FFF7B8FF00F5806012 +:1037E00002F1A801FFF7B2FF00F5806002F1C40109 +:1037F000FFF7ACFF00F5806002F1E001FFF7A6FFE4 +:1038000000F5806002F1FC01FFF7A0FF02F58C716A +:1038100000F58060FFF79AFFBDE8084000F0ECB8C3 +:103820000038024000000240BC3F000808B500F02C +:1038300081FAFEF779FBFFF70BF8BDE80840FEF7C9 +:10384000E7BD000070470000EFF3098305496833C6 +:103850004A6B22F001024A6383F30988002383F351 +:103860001188704700EF00E0302080F3118862B6C5 +:103870000D4B0E4AD96821F4E0610904090C0A4392 +:103880000B49DA60D3F8FC2042F08072C3F8FC20C8 +:10389000084AC2F8B01F116841F0010111602022EE +:1038A000DA7783F82200704700ED00E00003FA05A4 +:1038B00055CEACC5001000E0302310B583F311885D +:1038C0000E4B5B6813F4006314D0F1EE103AEFF383 +:1038D00009844FF08073683CE361094BDB6B23661E +:1038E00084F30988FEF700FB10B1064BA36110BDFD +:1038F000054BFBE783F31188F9E700BF00ED00E01B +:1039000000EF00E04F030008520300080F4B1A6C51 +:1039100042F001021A641A6E42F001021A660C4A61 +:103920001B6E936843F0010393604FF080436B225A +:103930009A624FF0FF32DA6200229A615A63DA60CB +:103940005A6001225A611A60704700BF0038024075 +:10395000002004E04FF0804208B51169D3680B40A5 +:10396000D9B29B076FEA0101116107D5302383F3B8 +:103970001188FEF7EFFA002383F3118808BD0000D9 +:103980001B4B4FF0FF3000211A696FEA42526FEA79 +:1039900052521A611A69C2F30A021A611A695A6903 +:1039A00058615A6959615A691A6A62F080521A62FA +:1039B0001A6A02F080521A621A6A5A6A58625A6A7D +:1039C00059625A6A0B4A106840F480701060186F90 +:1039D00000F44070B0F5007F03D04FF480301867DA +:1039E0001967536823F40073536000F073B900BF84 +:1039F0000038024000700040364B4FF44041364AD8 +:103A00001A64364A11601A6842F001021A601A6894 +:103A10009207FCD59A6822F003029A602D4B9A68AF +:103A200012F00C02FBD1196801F0F90119609A60DB +:103A30001A6842F480321A601A689003FCD55A6FF3 +:103A400042F001025A67234B5A6F9107FCD5244A72 +:103A50005A601A6842F080721A60204B5A68520409 +:103A6000FCD51A6842F480321A605A68D003FCD53B +:103A70001A6842F400321A60184A53689903FCD558 +:103A8000144B1A689201FCD5164A9A6040F2011252 +:103A9000C3F88C200022C3F8902040F20733124A6A +:103AA0001360136803F00F03072BFAD1094B9A68D0 +:103AB00042F002029A609A6802F00C02082AFAD1D7 +:103AC0005A6C42F480425A645A6E42F480425A66FA +:103AD0005B6E704700380240000400100070004028 +:103AE000186C400900948838003C0240074A08B529 +:103AF000536903F00103536123B1054A13680BB105 +:103B000050689847BDE80840FFF7D6BE003C01402A +:103B100098390220074A08B5536903F0020353613C +:103B200023B1054A93680BB1D0689847BDE80840B7 +:103B3000FFF7C2BE003C014098390220074A08B591 +:103B4000536903F00403536123B1054A13690BB1B0 +:103B500050699847BDE80840FFF7AEBE003C014001 +:103B600098390220074A08B5536903F008035361E6 +:103B700023B1054A93690BB1D0699847BDE8084065 +:103B8000FFF79ABE003C014098390220074A08B569 +:103B9000536903F01003536123B1054A136A0BB153 +:103BA000506A9847BDE80840FFF786BE003C0140D8 +:103BB00098390220164B10B55C6904F478725A618A +:103BC000A30604D5134A936A0BB1D06A98476006DE +:103BD00004D5104A136B0BB1506B9847210604D5DE +:103BE0000C4A936B0BB1D06B9847E20504D5094A98 +:103BF000136C0BB1506C9847A30504D5054A936C20 +:103C00000BB1D06C9847BDE81040FFF755BE00BF20 +:103C1000003C014098390220194B10B55C6904F44E +:103C20007C425A61620504D5164A136D0BB1506D82 +:103C30009847230504D5134A936D0BB1D06D98476F +:103C4000E00404D50F4A136E0BB1506E9847A104DF +:103C500004D50C4A936E0BB1D06E9847620404D51C +:103C6000084A136F0BB1506F9847230404D5054AD7 +:103C7000936F0BB1D06F9847BDE81040FFF71CBEA3 +:103C8000003C01409839022008B50348FDF744FA8A +:103C9000BDE80840FFF710BEE023022008B5034846 +:103CA000FDF73AFABDE80840FFF706BE4C240220B3 +:103CB00008B50348FDF730FABDE80840FFF7FCBD42 +:103CC000B824022008B5FFF745FEBDE80840FFF71D +:103CD000F3BD0000062108B50846FFF7F5FA0621F6 +:103CE0000720FFF7F1FA06210820FFF7EDFA062179 +:103CF0000920FFF7E9FA06210A20FFF7E5FA062175 +:103D00001720FFF7E1FA06212820FFF7DDFA072147 +:103D10001C20FFF7D9FA0C212620FFF7D5FA0C2139 +:103D20002720FFF7D1FA0C215220BDE80840FFF709 +:103D3000CBBA000008B5FFF723FE00F00DF8FDF741 +:103D400003FCFDF7D3FDFDF7ABFCFFF77BFDBDE802 +:103D50000840FFF799BC00000023054A19460133CB +:103D6000102BC2E9001102F10802F8D1704700BF20 +:103D700098390220034611F8012B03F8012B002A81 +:103D8000F9D1704753544D3332463F3F3F3F3F3F99 +:103D90000053544D333246375B347C355D780053E5 +:103DA000544D333246375B367C375D780000000077 +:103DB000009600000000000000000000000000006D +:103DC00000000000000000000000000009150008CD +:103DD000F5140008311500081D1500082915000804 +:103DE0001515000801150008ED1400083D15000820 +:103DF000000000001D1600080916000845160008FE +:103E0000311600083D16000829160008151600088E +:103E10000116000851160008000000000100000013 +:103E20000000000063300000243E0008802B0220C8 +:103E3000902D02204865782F50726F6669434E437B +:103E40000025424F415244252D424C0025534552F6 +:103E500049414C2500000000020000000000000065 +:103E600039180008A518000840004000403602201C +:103E70005036022002000000000000000300000095 +:103E800000000000E9180008000000001000000019 +:103E90006036022000000000010000000000000069 +:103EA0000839022001010200AD230008BD220008EC +:103EB000592300083D23000843000000C03E0008CD +:103EC00009024300020100C032090400000102029D +:103ED0000100052400100105240100010424020250 +:103EE0000524060001070582030800FF09040100FC +:103EF000020A0000000705010240000007058102D8 +:103F000040000000120000000C3F000812011001E8 +:103F100002000040AE2D0210000201020301000069 +:103F20000403090425424F4152442500437562654C +:103F300059656C6C6F772D626473686F74003031F3 +:103F40003233343536373839414243444546000030 +:103F50000080000000800000008000000080000061 +:103F60000000020000000400000004000000040043 +:103F70000000040000000400000004000000040031 +:103F8000000000003D1A0008F51C0008A11D0008F3 +:103F900040004000803902208039022001000000EA +:103FA0009039022080000000400100000500000060 +:103FB0006D61696E0069646C650000000000802A14 +:103FC00000000000AAAAAAAA00000024FFFF000027 +:103FD0000000000000A00A00000100000000000036 +:103FE000AAAAAAAA00000000FFFF0000000000002B +:103FF000000000001400005400000000AAAAAAAAB1 +:1040000014000054FFFF000000000000000000004A +:1040100080699A0100000000AAAA8AAA40565502A7 +:10402000FFFF000000707007777000000081020041 +:1040300000000000AAAAAAAA00410100FFFF000098 +:1040400000000080080000000000000000000000E8 +:10405000AAAAAAAA00000000FFFF000000000000BA +:10406000000000000000000000000000AAAAAAAAA8 +:1040700000000000FFFF0000000000000000000042 +:104080000000000000000000AAAAAAAA0000000088 +:10409000FFFF000000000000000000000000000022 +:1040A00000000000AAAAAAAA00000000FFFF00006A +:1040B0000000000000000000000000000000000000 +:1040C000AAAAAAAA00000000FFFF0000000000004A +:1040D000000000000000000000000000AAAA00008C +:1040E00000000000FF0000000000000000000000D1 +:1040F000780000000000000000801E0000000000AA +:10410000FF000000982D0220E02302204C24022012 +:10411000B824022000000000843D0008490400008B +:10412000913D0008510400009F3D000800960000EA +:1041300000000800960000000008000004000000D5 +:10414000203F000800000000000000000000000008 +:0C41500000000000000000000000000063 :00000001FF diff --git a/Tools/bootloaders/CubeYellow_bl.bin b/Tools/bootloaders/CubeYellow_bl.bin index e6ce61e6a07093..f1f44928647c89 100755 Binary files a/Tools/bootloaders/CubeYellow_bl.bin and b/Tools/bootloaders/CubeYellow_bl.bin differ diff --git a/Tools/bootloaders/CubeYellow_bl.elf b/Tools/bootloaders/CubeYellow_bl.elf index 8b7844ee48414c..a735c9852b6ff6 100755 Binary files a/Tools/bootloaders/CubeYellow_bl.elf and b/Tools/bootloaders/CubeYellow_bl.elf differ diff --git a/Tools/bootloaders/CubeYellow_bl.hex b/Tools/bootloaders/CubeYellow_bl.hex index 01d3405d8630e4..8f48aec0b86e5d 100644 --- a/Tools/bootloaders/CubeYellow_bl.hex +++ b/Tools/bootloaders/CubeYellow_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:100000000004022001020008450F0008490F000803 -:100010009D0F0008490F0008710F00080302000837 -:100020000302000803020008030200087128000808 +:1000000000060220010200080302000803020008A3 +:1000100003020008030200080302000803020008AC +:100020000302000803020008030200084D3800081C :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:100050000302000803020008813A0008AD3A0008D4 -:10006000D93A0008053B0008313B000803020008AC +:100050000302000803020008F13A0008193B0008F7 +:10006000413B0008693B0008913B0008030200087F :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:100090000302000803020008030200085D3B000899 +:10009000030200080302000803020008B93B00083D :1000A000030200080302000803020008030200081C -:1000B000A538000803020008030200080302000834 +:1000B000C93C00080302000803020008030200080C :1000C00003020008030200080302000803020008FC -:1000D000030200080302000851110008651100081E -:1000E000C53B0008030200080302000803020008E1 +:1000D00003020008030200088D3C0008A13C000850 +:1000E0001D3C000803020008030200080302000888 :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008DD2F000874 +:10014000030200080302000803020008C52F00088C :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B -:1001800003020008030200087911000803020008B6 +:100180000302000803020008B53C0008030200084F :10019000030200080302000803020008030200082B :1001A000030200080302000803020008030200081B :1001B000030200080302000803020008030200080B @@ -31,1005 +31,1018 @@ :1001D00003020008030200080302000803020008EB :1001E00003020008030200080302000803020008DB :1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B6394880F3088893 -:10021000384880F3098838484EF60851CEF200017C -:10022000086040F20000CCF200004EF63471CEF2CD -:1002300000010860BFF34F8FBFF36F8F40F20000E3 -:10024000C0F2F0004EF68851CEF200010860BFF314 -:100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 -:100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F03BFB03F09DFA4FF055301F49A2 -:100280001B4A91423CBF41F8040BFAE71C49194A4A -:1002900091423CBF41F8040BFAE71A491A4A1B4B3A -:1002A0009A423EBF51F8040B42F8040BF8E70020D5 -:1002B0001749184A91423CBF41F8040BFAE702F093 -:1002C00059FB03F0E1FA144C144DAC4203DA54F834 -:1002D000041B8847F9E700F03FF8114C114DAC4280 -:1002E00003DA54F8041B8847F9E702F041BB000029 -:1002F0000004022000240220000000080000022068 -:100300000004022040400008002402205024022063 -:1003100050240220B03D0220000200080002000824 -:1003200000020008000200082DE9F04F2DED108AB0 -:10033000C1F80CD0D0F80CD0BDEC108ABDE8F08F1D -:10034000002383F311882846A047002001F016FF00 -:1003500001F0C6FE00DFFEE770B578231F4C0025D4 -:100360006FF07F0623701E236570A570E570257100 -:100370006571A571E57125726672A372E57200F070 -:100380002BFD20B10E2325726672A372E57202F076 -:1003900031FA044602F066FA0546D0B9104B9C4289 -:1003A00019D001339C4241F2883412BF0546002423 -:1003B0000125002002F028FA0DB100F0B7F800F096 -:1003C00063FD00F05DFC204600F050F900F0AEF84F -:1003D000F9E70024EDE70446EBE700BF50240220D4 -:1003E000010007B008B500F0C9FBA0F12003584296 -:1003F000584108BD054B07B51B88022101A8ADF87F -:10040000043000F027FC03B05DF804FBAC3C0008AE -:10041000064991F8243033B100230822086A81F894 -:10042000243000F051BC0120704700BF702402202E -:100430002DE9F84F234C05468846174694F824309A -:100440008BBB2E46DFF87C90002F38D094F824A088 -:10045000BAF1000F05D12022FF214846266200F0A4 -:1004600001FDCAF10805414604EB8A00BD4228BFE0 -:100470003D465FFA85FBAD00A7EB0B072A462E44ED -:1004800000F0C8FC94F82430A844FFB29B445FFA03 -:100490008BFBBBF1080F84F824B0D5D1FFF7B8FF70 -:1004A0000028D1D108E0266A06EB8306B042C9D005 -:1004B000FFF7AEFF0028C4D10020BDE8F88F01206F -:1004C000BDE8F88F7024022010B5202383F3118833 -:1004D0001248C3680BB101F0D7FE0023104A4FF455 -:1004E0007A710E4801F094FE002383F311880D4CBD -:1004F000236813B12368013B2360636813B1636809 -:10050000013B6360084B1B7833B9636823B9022051 -:1005100000F07EFC3223636010BD00BF5C2402202B -:10052000C9040008A025022098240220454B464912 -:100530002DE9F04153F8042F013201D1BDE8F081DB -:100540008B42F7D1414C424B22689A4278D9414BB9 -:100550009B6803F1006303F5C0339A4270D2002018 -:1005600000F0AAFB02203C4B187000F04FFC3B4B04 -:100570001A6C00221A64196E1A66196E596C5A6444 -:10058000596E5A66596E596941F08001596159692D -:1005900021F0800159615969196941F000511961CF -:1005A000196921F0005119611B6972B62C4B2D4954 -:1005B0000B601D682468BFF34F8FBFF36F8F2A4B0A -:1005C000C3F88420BFF34F8F5A6922F480325A61F6 -:1005D000BFF34F8FD3F8802043F6E07EC2F3C90605 -:1005E000C2F34E32B707520102EA0E0838463146CE -:1005F000013948EA000C00F14040B1F1FF3FC3F877 -:1006000074C2F5D1203A12F1200FEDD1BFF34F8F14 -:10061000BFF36F8FBFF34F8FBFF36F8F5A6922F411 -:1006200000325A610022C3F85022BFF34F8FBFF34C -:100630006F8F202383F31188AD4685F30888204708 -:10064000BDE8F081FC7F01081C80010804800108DE -:10065000FF7F010850240220982402200038024025 -:100660000080010808ED00E000ED00E02DE9F04F0A -:1006700099B0B34C2022FF21019010A8A66800F089 -:10068000F1FBB04AA3461378A3B90121AE4811701B -:10069000C360202383F31188C3680BB101F0F4FD1C -:1006A0000023AA4A4FF47A71A74801F0B1FD002354 -:1006B00083F31188019B13B1A54B019A1A600023A3 -:1006C000A44AA349019F99461C461D4698461370AB -:1006D0004B600292012000F099FB002F00F0128283 -:1006E0009B4B1B68002B40F00D8219B0BDE8F08FCA -:1006F0000220FFF777FE002840F0FB81019BB9F153 -:10070000000F08BF1F46944B1B8802210BA8ADF8B1 -:100710002C3000F09FFADDE74FF47A7000F02EFAEB -:10072000031E0393EADB0220FFF75CFE82460028EB -:10073000E4D0039B581E042800F2DD81DFE800F0BE -:10074000030E1114170018A80523042140F8343DA6 -:1007500000F080FA54464FF0000856E00421784833 -:10076000F6E704217D48F3E704217D48F0E71C24E7 -:100770002046043400F0A2FA04210B900BA800F0EC -:1007800069FA2C2CF4D1E5E7002DB7D0002CB5D0B8 -:100790000220FFF727FE0546002800F0AF81012068 -:1007A0006C4C00F089FA4FF000090220207000F034 -:1007B0002DFB5FFA89FA504600F08EFA074658B1D1 -:1007C000504609F1010900F097FA0028F1D12C46B2 -:1007D000A9460027634B97E701233E46022023707A -:1007E00000F012FBDBF808309E4206D2304600F0E3 -:1007F00065FA0130EBD10436F4E70026029BA946E6 -:100800002C461E703746524B5E6000F033FB15B12C -:10081000002C18BF0027FFF7EDFD5BE7002D3FF42C -:100820006DAF002C3FF46AAF0220029B187000F0FD -:10083000EDFA322000F0A2F9B0F1000AC0F25E81B8 -:100840001AF0030540F05A8106EB0A03DBF8082092 -:10085000934200F25381BAF5807F00F24F815545F3 -:100860000DDA4FF47A7000F089F90490049B002BA4 -:10087000C0F24481049B3C4AAB540135EFE7C820E9 -:10088000FFF7B0FD0546002800F038811F2E11D873 -:10089000C6F1200410AB26F0030033495445184438 -:1008A00028BF5446224600F0B5FA2246FF212E48C2 -:1008B00000F0D8FA4FEAAA0A2B4930465FFA8AF2CA -:1008C000FFF7B6FD0446002800F01A8106EB8A0601 -:1008D00005469AE70220FFF785FD00283FF40EAF9A -:1008E000FFF796FD00283FF409AF4FF0000A53468A -:1008F000DBF8082092451CD2BAF11F0F12D8109ACB -:1009000001320FD02AF0030218A90A4452F8202C11 -:100910000B92184604220BA90AF1040A00F052FBBC -:100920000346E5E75046039300F0C8F9039B0B909C -:10093000EFE718A8042140F84C3D00F08BF964E77C -:10094000502402209C2502205C240220C9040008B7 -:10095000A025022098240220AE3C00085424022046 -:1009600058240220B03C00089C24022018A8002330 -:10097000642140F8343D00F039F900287FF4BEAE20 -:100980000220FFF72FFD00283FF4B8AE0B9800F0CF -:10099000C5F918AB43F8480D04211846CDE718A84F -:1009A0000023642140F8343D00F020F900287FF452 -:1009B000A5AE0220FFF716FD00283FF49FAE0B986E -:1009C00000F0BAF918AB43F8440DE5E70220FFF751 -:1009D00009FD00283FF492AE00F0B4F918AB43F8DB -:1009E000400DD9E70220FFF7FDFC00283FF486AE5A -:1009F0000BA9142000F0ACF9824618A8042140F895 -:100A00003CAD00F027F951460BA896E7322000F0E4 -:100A1000B5F8B0F1000AFFF671AE1AF0030F7FF4DB -:100A20006DAE0AEB0803DBF8082093423FF666AE92 -:100A30000220FFF7D7FC00283FF460AE2AF0030A3B -:100A4000C244D0453FF4E1AE404608F1040800F04E -:100A500035F904210A900AA800F0FCF8F1E74FF4F8 -:100A60007A70FFF7BFFC00283FF448AEFFF7D0FCD8 -:100A700000283FF4AFAE109B01330CD0082210A920 -:100A80000020FFF7D5FC00283FF4A4AE2022FF2170 -:100A900010A800F0E7F9FFF7ADFC374801F074FB50 -:100AA00023E6002D3FF42AAE002C3FF427AE18A811 -:100AB0000023642140F8343D00F098F88246002875 -:100AC0007FF41CAE0220FFF78DFC00283FF416AE29 -:100AD0000390FFF78FFC41F28830574601F054FB3A -:100AE0000B9800F00FFA00F0C5F9039B1C461D4659 -:100AF000F0E5054689E64FF00008FFE52546FDE5EF -:100B00002C4667E6002000F039F80490049B002B87 -:100B1000FFF6E3AD012000F077F9049B213B122B97 -:100B20003FF6D8AD01A252F823F000BFF10600084D -:100B30001907000889070008D5060008D50600082F -:100B4000D50600081D0800080D0A0008D508000891 -:100B50006D0900089F090008CD090008D5060008A6 -:100B6000E5090008D50600085F0A00080B08000820 -:100B7000D5060008A30A0008A08601002DE9F34766 -:100B80004FF47A75002402AE154F4543DFF85880C4 -:100B900006F8014D97F900305FFA84F95A1C01D02C -:100BA000A34212D158F82400012231460368D3F839 -:100BB00020A02B46D047012807D10A4B9DF80700FB -:100BC00083F8009002B0BDE8F0870134042CE1D135 -:100BD0004FF4FA7001F0D8FA4FF0FF30F2E700BF9F -:100BE00000240220C4250220BC3C00082DE9F04767 -:100BF0004FF47A7506460024134F4D43DFF85080BA -:100C000097F900305FFA84F95A1C01D0A34210D141 -:100C100058F82400042231460368D3F820A02B465C -:100C2000D047042805D1094B002083F80090BDE887 -:100C3000F0870134042CE3D14FF4FA7001F0A4FAE8 -:100C40004FF0FF30BDE8F08700240220C4250220C9 -:100C5000BC3C0008074B30B41A78074B53F82240CD -:100C60000A46014623682046DD69044BAC4630BC89 -:100C7000604700BFC4250220BC3C0008A0860100DC -:100C8000F8B50A4C00250A4E01F0BAFC094F207055 -:100C900030682378834207D901F0ACFC33680544FF -:100CA0000133BD423360F3D9F8BD00BFC525022032 -:100CB000A8250220FF7F010001F04EBD00F1006079 -:100CC00000F5C0300068704700F10060920000F548 -:100CD000C03001F0DBBC0000054B1A68054B1B78E7 -:100CE0009B1A834202D9104401F084BC0020704753 -:100CF000A8250220C525022038B5074D04462868DE -:100D0000204401F07FFC28B928682044BDE8384021 -:100D100001F090BC38BD00BFA825022010F00303ED -:100D200008D1B0F5806F05D800F10050A0F5712012 -:100D30000068704700207047014BC058704700BFE3 -:100D400020F4F01F014B1868704700BF002004E03A -:100D50001F4BF0B51E681F4BC6F30B02360C1F88E5 -:100D60005D68BA4293F9084022D09F89BA4221D0E7 -:100D70001F8BBA4206D102220C2404FB02335D68A9 -:100D800093F90840B6F5805F16D041F201039E4208 -:100D900008BF5A24421E013D0B460A44934215D215 -:100DA00015F9016F581C4EB1034600F8016CF5E7C8 -:100DB0000022E1E70122DFE74124EBE72C25824214 -:100DC0001D7001D9981C5C70401AF0BD1846FBE7F5 -:100DD000002004E004240220094B5B88B3F5805F07 -:100DE00009D041F20102934207D10122054B03EBE6 -:100DF0008203D87870470022F8E70020704700BFD0 -:100E0000002004E0B43C0008704700007047000078 -:100E100070470000002310B5934203D0CC5CC4544B -:100E20000133F9E710BD000030B5441E14F9010F7D -:100E30000B4658B193F900500131854206D11AB9D9 -:100E400093F90020801A30BD013AEFE7002AF7D16C -:100E5000104630BD02460346981A13F9011B0029BB -:100E6000FAD1704702440346934202D003F8011BB3 -:100E7000FAE77047024B1A78024B1A70704700BFAE -:100E8000C425022000240220F8B5184C184800F0B0 -:100E9000BBFC2146164800F0E3FC24681548E26ECE -:100EA000154DD2F80438154E43F00203104FC2F826 -:100EB000043801F069F92046114900F0DFFDE26EC7 -:100EC0000024D2F8043823F00203C2F804384FF4A7 -:100ED000E1332B6056F82400B84202D0294600F0D6 -:100EE000F1FB0134042CF5D1F8BD00BFB43D00087E -:100EF000CC33022040420F00AC250220BC3C00084D -:100F0000E03D000838B50B4B05461A780A4B53F8FC -:100F100022400A4B9C420CD0094B00211822184653 -:100F2000FFF7A0FF056001462046BDE8384000F00D -:100F3000C9BB38BDC4250220BC3C0008CC3302200C -:100F4000AC250220FEE7000000B59BB0EFF309815D -:100F500068226846FFF75EFFEFF30583034B9A6B49 -:100F60009A6A9A6A9A6A9A6A9B6AFEE700ED00E0BA -:100F700000B59BB0EFF3098168226846FFF74AFF8E -:100F8000EFF30583044B9A6B9A6A9A6A9A6A9A6A93 -:100F90009A6A9B6AFEE700BF00ED00E000B59BB0D7 -:100FA000EFF3098168226846FFF734FFEFF305830A -:100FB000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE724 -:100FC00000ED00E030B50A44074D91420BD011F816 -:100FD000013B09245840013CF7D040F300032B406B -:100FE00083EA5000F7E730BD2083B8ED00230449C1 -:100FF0001A465A50C81808334260802BF9D17047FE -:10100000C8250220026843681143016003B11847F4 -:1010100070470000024A136843F0C0031360704732 -:1010200000440040024A136843F0C0031360704755 -:1010300000480040024A136843F0C0031360704741 -:10104000007800402DE9F047C66D05463768F46921 -:10105000200734621AD014F0080F0CBF0021802141 -:10106000E20748BF41F02001A3074FF0200348BF2B -:1010700041F04001600748BF41F4807183F311885B -:10108000281DFFF7BFFF002383F31188E2050AD56F -:10109000202383F311884FF40071281DFFF7B2FF5E -:1010A000002383F311884FF020094FF0000A14F059 -:1010B000200831D13B0616D54FF0200905F1380A3A -:1010C000200610D589F31188504600F06FFA0028E9 -:1010D0002FDA0821281DFFF795FF27F080033360E2 -:1010E000002383F3118879060DD562060BD52023E2 -:1010F00083F31188EA6C2B6D9A4201D12B6CEBB90A -:10110000002383F31188E30620D5AA6E1369EBB19F -:101110005069BDE8F047184789F31188736A28467B -:1011200095F86410194000F0DBFA8AF31188F4692D -:10113000BDE7B06288F31188F469C1E727F0400782 -:101140001021281DFFF75EFF3760D9E7BDE8F08763 -:1011500008B50348FFF776FFBDE8084001F098BBEB -:101160004826022008B50348FFF76CFFBDE8084099 -:1011700001F08EBBB426022008B50348FFF762FFDA -:10118000BDE8084001F084BB2027022037B52D4C74 -:101190002D4D204600F08AFA009404F1140000233B -:1011A0004FF40072294900F04BF94FF4007200949B -:1011B00004F13800264B274900F0C4F9264B256678 -:1011C0000B21E3652620254C00F0C4F8204600F0F2 -:1011D0006DFA009404F1140000234FF400722049CA -:1011E00000F02EF94FF40072009404F138001D4B0A -:1011F0001D4900F0A7F91D4B25660B21E36527204B -:101200001B4C00F0A7F8204600F050FA04F114003F -:10121000009400234FF40072164900F011F904F114 -:10122000380000944FF40072134B144900F08AF90F -:10123000134B0B215220E365256603B0BDE8304017 -:1012400000F088B84826022080F937038C27022056 -:10125000151000088C2D022000440040B426022006 -:101260008C290220251000088C2F02200048004005 -:10127000202702208C2B0220351000088C31022000 -:10128000007800402E4B002908BF1946037C012B33 -:10129000816630B50CD12B4B984235D12A4B1A6C54 -:1012A00042F400321A641A6E42F400321A661B6E5F -:1012B0000A68036EC46D03EB5203B3FBF2F34A6892 -:1012C000150442BF23F0070503F0070343EA450373 -:1012D000E3608B6843F040036360CB68510543F0E3 -:1012E0000103A36042F4967343F0010323604FF0BF -:1012F000FF33236205D512F010221DD0B2F1805FBA -:101300001CD080F8643030BD104B984208D10E4B91 -:101310001A6C42F480221A641A6E42F48022C5E7E5 -:101320000B4B9842C4D1084B1A6C42F080421A64AD -:101330001A6E42F08042B9E77F23E2E73F23E0E7FD -:10134000F83C00084826022000380240B42602205B -:101350002027022000F1604300F01F02090140092C -:1013600003F56143C9B2800083F80013012300F143 -:101370006040934000F56140C0F8803103607047E1 -:10138000F8B51546826804460B46AA4200D2856825 -:10139000A1692669761AB54207D218462A46FFF790 -:1013A00039FDA3692B44A3610DE011D9AF1B32466F -:1013B0001846FFF72FFD3A46E1683044FFF72AFD53 -:1013C000E2683A44A261A36828465B1BA360F8BDAB -:1013D00018462A46FFF71EFDE368E4E78368934258 -:1013E0002DE9F04104460F46154600D28568606934 -:1013F0002669361AB54207D22A463946FFF70AFD52 -:1014000063692B4463610EE013D9A5EB06083246ED -:101410003946FFF7FFFC4246B919E068FFF7FAFCCE -:10142000E26842446261A36828465B1BA360BDE892 -:10143000F0812A463946FFF7EDFCE368E2E7000059 -:1014400010B50A440024C361029B006040608460C0 -:10145000C160816141610261036210BD08B58269AA -:101460004369934201D1826882B982680132826005 -:101470005A1C42611970426903699A4201D3C368D8 -:101480004361002100F09CFE002008BD4FF0FF30BA -:1014900008BD000070B5202304460E4683F3118872 -:1014A000A568A5B1A368A269013BA360531CA36111 -:1014B00015782269934224BFE368A361E3690BB105 -:1014C00020469847002383F31188284670BD314693 -:1014D000204600F065FE0028E2DA85F3118870BD31 -:1014E0002DE9F74F05460F4690469A46D0F81C90D6 -:1014F000202686F311884FF0000B144664B1224673 -:1015000039462846FFF73CFF034668B9514628464E -:1015100000F046FE0028F1D0002383F31188A8EBE9 -:10152000040003B0BDE8F08FB9F1000F03D00190C3 -:101530002846C847019B8BF31188E41A1F4486F3A1 -:101540001188DBE7C160816141611144C361009B87 -:10155000006040608260016103627047F8B5044634 -:101560000E461746202383F31188A568A5B1A3680A -:10157000013BA36063695A1C62611E702369626942 -:101580009A4224BFE3686361E3690BB12046984740 -:10159000002080F31188F8BD3946204600F000FE97 -:1015A0000028E2DA85F31188F8BD000083694269FA -:1015B0009A4210B501D182687AB98268013282609C -:1015C0005A1C82611C7803699A4201D3C368836103 -:1015D000002100F0F5FD204610BD4FF0FF3010BD9A -:1015E0002DE9F74F05460F4690469A46D0F81C90D5 -:1015F000202686F311884FF0000B144664B1224672 -:1016000039462846FFF7EAFE034668B951462846A0 -:1016100000F0C6FD0028F1D0002383F31188A8EB69 -:10162000040003B0BDE8F08FB9F1000F03D00190C2 -:101630002846C847019B8BF31188E41A1F4486F3A0 -:101640001188DBE7026843681143016003B1184762 -:10165000704700001430FFF743BF00004FF0FF3326 -:101660001430FFF73DBF00003830FFF7B9BF00006E -:101670004FF0FF333830FFF7B3BF00001430FFF7EF -:1016800009BF00004FF0FF311430FFF703BF000027 -:101690003830FFF763BF00004FF0FF323830FFF7FC -:1016A0005DBF000000207047FFF770BD044B036072 -:1016B000002343608360C36001230374704700BF4D -:1016C000103D000810B52023044683F31188FFF76E -:1016D000D9FD02232374002383F3118810BD000079 -:1016E00038B5C36904460D461BB904210844FFF709 -:1016F000A9FF294604F11400FFF7B0FE002806DA1E -:10170000201D4FF48061BDE83840FFF79BBF38BD16 -:10171000026843681143016003B118477047000035 -:1017200013B5446BD4F894341A681178042915D190 -:10173000217C022912D11979012312898B4013428D -:101740000CD101A904F14C0001F0AAFED4F8944494 -:101750000246019B2179206800F0E0F902B010BD3B -:10176000143001F02DBE00004FF0FF33143001F0B3 -:1017700027BE00004C3001F0FFBE00004FF0FF33E9 -:101780004C3001F0F9BE0000143001F0FBBD000048 -:101790004FF0FF31143001F0F5BD00004C3001F086 -:1017A000CBBE00004FF0FF324C3001F0C5BE000050 -:1017B000D0F8942438B5136805461978042901D067 -:1017C000012038BD017C0229FAD1127901205C89FF -:1017D00090400440F4D105F1140001F08DFD024663 -:1017E0000028EDD0D5F894544FF4807328686979B7 -:1017F00000F082F9204638BD406BFFF7D9BF0000EA -:1018000000207047704700007FB5124B012502266B -:10181000044603600023057400F1840243602946F6 -:101820008360C3600C4B0290143001934FF48073BB -:10183000009601F03DFD094B04F523722946019302 -:1018400004F14C004FF480730294009601F004FE02 -:1018500004B070BD383D0008F917000821170008D2 -:101860000B68202282F311880A7903EB820210624E -:101870004A790D3243F822008A7912B103EB8203D0 -:1018800018620223C0F894140374002383F31188B0 -:101890007047000038B5037F044613B190F8543008 -:1018A000ABB90125201D0221FFF732FF04F114001E -:1018B00025776FF0010100F08FFC84F8545004F19B -:1018C0004C006FF00101BDE8384000F085BC38BD28 -:1018D00010B5012104460430FFF71AFF00232377D7 -:1018E00084F8543010BD000038B50446002514308B -:1018F00001F0F6FC04F14C00257701F0C5FD201D38 -:1019000084F854500121FFF703FF2046BDE838401A -:10191000FFF74EBF90F85C3003F06003202B19D125 -:1019200090F85D20212A0AD0222A4FF000030ED021 -:10193000202A0FD1084A02650722426504E0064BBF -:101940000365072343650023836501207047036512 -:101950004365F9E70020704728240220D0F894342A -:1019600037B51A680446117804291AD1017C022976 -:1019700017D11979012312898B40134211D100F13B -:101980004C05284601F040FE58B101A9284601F057 -:1019900087FDD4F894440246019B2179206800F029 -:1019A000BDF803B030BD000000EB8103F7B51C6A41 -:1019B00005460E46F4B1202383F3118805EB860714 -:1019C000201D08214C34FFF7A3FEFB685B691B68F0 -:1019D00013B1204601F072FD01A9204601F060FD1F -:1019E000024648B1019B3146284600F097F8002393 -:1019F00083F3118803B0F0BDFB685A691268002AAE -:101A0000F5D01B8A013B1340F1D105F15C02EAE7F6 -:101A10000D3138B550F82140DCB1202383F3118813 -:101A2000D4F894241368527903EB8203DB689B6932 -:101A30005D6845B104216018FFF76AFE294604F18C -:101A4000140001F063FC2046FFF7B2FE002383F38D -:101A5000118838BD7047000001F012B8012300F171 -:101A6000240200F1380103700023436042F8043B74 -:101A70008A421361FAD103814381704738B5044625 -:101A8000202383F3118800254160C560056145610D -:101A90008561C561056201F003F80223237085F3B7 -:101AA000118838BD70B500EB8103054650690E46BC -:101AB0001446DA6018B110220021FFF7D3F9A069AB -:101AC00018B110220021FFF7CDF931462846BDE8B4 -:101AD000704001F0AFB80000028902F001020281FB -:101AE000428902F001024281002202614261826168 -:101AF000C261026201F032B9F0B4012500EB810449 -:101B000047898D40E4683D43A469458123600023F3 -:101B1000A2606360F0BC01F04DB90000F0B4012593 -:101B200000EB810407898D40E4683D4364690581C9 -:101B300023600023A2606360F0BC01F0C7B900001D -:101B400070B50223002504460370A0F8645080F8A5 -:101B5000665080F8675005814581C5600561456123 -:101B60008561C561056280F84C5000F0FFFF636835 -:101B70001B6823B129462046BDE87040184770BD58 -:101B80000278436880F8682005221B6802700BB158 -:101B90000421184770470000436890F868201B68CC -:101BA00002700BB1052118477047000090F84C30C7 -:101BB00070B5044613B1002380F84C3004F15C0288 -:101BC000204601F0EDF863689B6863BB94F85C50B5 -:101BD00015F0600615D194F85D3005F07F0545EAF3 -:101BE000032540F202339D4200F00E815BD8022DA6 -:101BF00000F0DC803FD8002D00F08780012D00F040 -:101C0000CF800021204601F035FB0021204601F065 -:101C100027FB63681B6813B10621204698470623FB -:101C200084F84C3070BD204698470028CED094F8F8 -:101C3000632094F8623043EA0223626D934238BF16 -:101C4000636594F95C30656D002B4FF0200380F2E2 -:101C5000FD80002D00F0EC80092284F84C2083F3F5 -:101C600011880021636D226D2046FFF757FF002386 -:101C700083F3118870BDB5F5817F00F0B180B5F5B3 -:101C8000407F49D0B5F5807FBBD194F85E30012B01 -:101C9000B7D1B4F8643023F00203A4F864302665A9 -:101CA0006665A665C3E740F201639D421ED8B5F59F -:101CB000C06F3BD2B5F5A06FA3D1B4F85C30B3F5DB -:101CC000A06F0ED194F85E30204684F8663000F0A4 -:101CD000A5FF63681B6813B10121204698470323C1 -:101CE0002370002323656365A365A0E7B5F5106F36 -:101CF00032D040F602439D4252D0B5F5006F80D1FC -:101D000004F167032365012324E004F16403A5655E -:101D10002365022363658AE794F85E30012B7FF424 -:101D200070AFB4F8643043F00203B6E794F8612072 -:101D30002046616894F860304D6843EA022394F8C5 -:101D40005F1094F85E20A84700283FF45AAF43681C -:101D5000236503686365A4E72378042B10D120234F -:101D600083F311882046FFF7B7FE86F31188636876 -:101D7000032184F867601B6821700BB120469847E7 -:101D800094F85E30002BACD084F8673004232370C5 -:101D900063681B68002BA4D0022120469847A0E767 -:101DA000374B23650223636500239DE794F8601099 -:101DB000204611F0800F01F00F010ED000F0E2FF7D -:101DC000012806D002287FF41CAF2E4B60652365E6 -:101DD00067E72D4B6565236563E700F0C5FFEFE717 -:101DE00094F85E30002B7FF40CAF94F8603013F061 -:101DF0000F013FF476AF1A06204602D501F04EFAE5 -:101E00006FE701F041FA6CE794F85E30002B7FF445 -:101E1000F8AE94F8603013F00F013FF462AF1B0688 -:101E2000204602D501F026FA5BE701F019FA58E7DF -:101E3000142284F84C2083F311882B462A46294625 -:101E40002046FFF759FE85F3118870BD5DB115225C -:101E500084F84C2083F311880021636D226D2046A5 -:101E6000FFF74AFE03E70B2284F84C2083F3118826 -:101E70002B462A4629462046FFF750FEE3E700BFDF -:101E8000683D0008603D0008643D000838B590F8E2 -:101E90004C300446152B29D8DFE803F03E282828CB -:101EA00028283E28280B29392828282828282828A7 -:101EB0003E3E90F8631090F86220436D42EA0122A2 -:101EC0009A4214D9C268128AB3FBF2F502FB1535A7 -:101ED0006DB9202383F311882B462A462946FFF744 -:101EE0001DFE85F311880A2384F84C3038BD142375 -:101EF00084F84C30202383F31188002320461A46AF -:101F00001946FFF7F9FD002383F3118838BD836D6F -:101F100003B198470023E7E7002101F0ABF9002166 -:101F2000204601F09DF963681B6813B10621204625 -:101F300098470623D8E7000090F84C20152A38B5BA -:101F4000044622D80123934040F6416213421DD13A -:101F500013F480150FD19B0217D50B2380F84C305A -:101F6000202383F311882B462A462946FFF7D6FD06 -:101F700085F3118838BDC3689B695B682BB9836D95 -:101F800003B19847002384F84C3038BD002101F09C -:101F900071F90021204601F063F963681B6813B1F1 -:101FA0000621204698470623EDE70000024B002259 -:101FB0001B605B609A6070478C330220002382684C -:101FC0000374054B1B6899689142FBD25A68036001 -:101FD00042601060586070478C33022008B520239F -:101FE00083F31188037C032B05D0042B0DD02BB970 -:101FF00083F3118808BD436900221A604FF0FF3354 -:102000004361FFF7DBFF0023F2E790E80C001A6062 -:1020100002685360F2E70000002382680374054BF6 -:102020001B6899689142FBD85A680360426010604F -:10203000586070478C330220054B19690874186882 -:10204000026853601A60186101230374FEF76CB9CB -:102050008C3302204B1C30B5054687B00A4C10D09B -:10206000236901A8094A00F0D3F82846FFF7E4FFE6 -:10207000049B13B101A800F007F92369586907B060 -:1020800030BDFFF7D9FFF8E78C330220DD1F0008D1 -:1020900038B50C4D044641612B6981689A689142BC -:1020A00003D8BDE83840FFF789BF1846FFF786FF21 -:1020B00001232C61014623742046BDE83840FEF719 -:1020C00033B900BF8C330220044B1A681B69906837 -:1020D0009B68984294BF0020012070478C330220F7 -:1020E00010B5084C236820691A68546022600122E8 -:1020F00023611A74FFF790FF01462069BDE8104084 -:10210000FEF712B98C330220826002220274002290 -:10211000427470478368A3F17C0243F80C2C026977 -:1021200043F83C2C426943F8382C074A43F81C2CEE -:10213000C268A3F1180043F8102C022203F8082CFF -:10214000002203F8072C70474103000810B5202334 -:1021500083F31188FFF7DEFF00210446FFF798FFA5 -:10216000002383F31188204610BD0000024B1B6939 -:1021700058610F20FFF760BF8C330220202383F3C8 -:102180001188FFF7F3BF000008B50146202383F351 -:1021900011880820FFF75EFF002383F3118808BD34 -:1021A00049B1064B42681B6918605A60136043606E -:1021B0000420FFF74FBF4FF0FF3070478C330220F1 -:1021C0000368984206D01A68026050601846596148 -:1021D000FFF7F4BE7047000038B504460D4620688E -:1021E000844200D138BD036823605C604561FFF71D -:1021F000E5FEF4E7054B03F114025A619A614FF0D2 -:10220000FF32DA6100221A62704700BF8C3302206D -:10221000F8B503614FF08043C26002295C6A06464C -:10222000184B38BF02211A461F4652F8145F9542D8 -:102230000AD1586198611C62056045608160081987 -:10224000BDE8F84001F002BA186AAB68241A0C190C -:1022500002D3E41A2D6804E09C4202D2204401F02B -:1022600003FAAB689C42F4D86B68356073601E60FB -:102270004FF0FF336E60B460A968091BA960FB6171 -:10228000F8BD00BF8C33022010B41B4C234653F81A -:10229000141F814210D0416802680A6002685160D0 -:1022A0009A424FF00001C16003D0936881680B44EB -:1022B00093605DF8044B70470A6800209A4262619F -:1022C0005360C86003D15DF8044B01F0C7B993684F -:1022D00088680344206A93604FF08042526A121A61 -:1022E0009342E6D9991A5DF8044B012998BF931CD3 -:1022F000184401F0B9B900BF8C33022000207047A8 -:10230000FEE70000704700004FF0FF30704700000C -:10231000022906D0032906D00129064818BF00204B -:10232000704705487047032A9ABF044800EBC20073 -:10233000002070473C3E0008F03D00083024022099 -:1023400070B59AB006460846144601AD294600F01D -:1023500095F82846FEF77EFDC0B2431C5B0086E878 -:10236000180023700323023404F8013C00231946AB -:10237000DAB20234904201D81AB070BDEA5C01337F -:1023800004F8011C04F8022CF2E7000008B5202331 -:1023900083F311880348FFF7E1FA002383F31188E0 -:1023A00008BD00BFCC33022010B50446052916D85D -:1023B000DFE801F016150316161D202383F311889C -:1023C0000E4A0121FFF76EFB20460D4A0221FFF75E -:1023D00069FB0C48FFF788FA002383F3118810BDCE -:1023E000202383F311880748FFF754FAF4E72023EA -:1023F00083F311880348FFF76BFAEDE76C3D0008A3 -:10240000903D0008CC33022038B50C4D0C4C2A46C8 -:102410000C4904F10800FFF793FF05F1CA0204F12B -:1024200010000949FFF78CFF05F5CA7204F1180086 -:102430000649BDE83840FFF783BF00BF943802204B -:1024400030240220BC3D0008C93D0008D73D0008EB -:1024500070B5044608460D46FEF7FCFCC6B22046A1 -:10246000013403780BB9184670BD32462946FEF791 -:10247000DBFC0028F3D1012070BD00002DE9F84FEE -:1024800005460C46FEF7E6FC2C49C6B22846FFF787 -:10249000DFFF08B10336F6B229492846FFF7D8FF17 -:1024A00008B11036F6B2632E0DD8DFF89080DFF851 -:1024B0009090244FDFF894A0DFF894B02E7846B9BE -:1024C0002670BDE8F88F29462046BDE8F84F01F098 -:1024D000E5BB252E2ED1072241462846FEF7A4FC57 -:1024E00070B9DBF8003007350A3444F80A3CDBF8F1 -:1024F000043044F8063CBBF8083024F8023CDDE721 -:10250000082249462846FEF78FFC98B9A21C0E4BBC -:1025100013F8011F023209095345C95D02F8041C72 -:10252000197801F00F01C95D02F8031CF0D11834CD -:102530000835C3E7267001350134BFE75C3E00086B -:10254000D73D00086F3E00081FF4F01F2BF4F01F6A -:10255000643E0008BFF34F8F024AD368DB03FCD40C -:10256000704700BF003C024008B5074B1B7853B9C9 -:10257000FFF7F0FF054B1A69002A04DA044A5A6093 -:1025800002F188325A6008BDF23A0220003C024053 -:102590002301674508B5054B1B7833B9FFF7DAFF10 -:1025A000034A136943F00043136108BDF23A022065 -:1025B000003C02400B2870B513D80B4A0B4C137823 -:1025C00063B94FF000610A4E44F8231056F82350C7 -:1025D00001330C2B2944F7D10123137054F8200048 -:1025E00070BD002070BD00BF243B0220F43A0220E1 -:1025F000803E0008014B53F820007047803E0008E1 -:102600000C2070470B2810B5044601D9002010BDDE -:10261000FFF7D0FF064B53F824301844C21A0BB909 -:10262000012010BD12680132F0D1043BF6E700BF73 -:10263000803E00080B2810B5044621D8FFF78AFF1A -:10264000FFF792FF0F4AF323D360C300DBB243F4DA -:10265000007343F002031361136943F48033136181 -:10266000FFF778FFFFF7A6FF074B53F8241000F0A1 -:10267000DBF8FFF78FFF2046BDE81040FFF7C2BF31 -:10268000002010BD003C0240803E00082DE9F843C8 -:1026900012F0010315463FD18218B2F1026F3BD20E -:1026A0002B4B1B6813F0010336D0FFF75DFF294C5D -:1026B000F32340F20127E360FFF74CFF032D01D91C -:1026C000830712D00F46401A224C40F20118EB1B30 -:1026D000C6190B44012B236924D823F0010323617D -:1026E000FFF758FF0120BDE8F883236923F4407306 -:1026F000236123693B43236151F8046B0660BFF3F8 -:102700004F8FFFF727FF03689E4208D0236923F00D -:1027100001032361FFF73EFF0020BDE8F883043D7D -:102720000430CBE723F44073B9462361236943EABD -:102730000803236137F8023B3380BFF34F8FFFF765 -:1027400009FF3688B6B2B9F80030B342BFD0DDE732 -:1027500000380240003C0240084908B50B7828B117 -:1027600053B9FFF701FF01230B7008BD23B10870B7 -:10277000BDE80840FFF70EBF08BD00BFF23A0220D7 -:1027800002440439064BD2B210B5904200D110BDBC -:10279000441C00B253F8200041F8040FE0B2F4E703 -:1027A00050280040104B30B51C6F240407D41C6F18 -:1027B00044F400741C671C6F44F400441C670B4C09 -:1027C000024404392368D2B243F480732360084B77 -:1027D000904200D130BD441C51F8045F00B243F870 -:1027E0002050E0B2F4E700BF003802400070004023 -:1027F0005028004007B5012201A90020FFF7C0FFC3 -:10280000019803B05DF804FB13B50446FFF7F2FF2F -:10281000A04206D002A90122002041F8044DFFF792 -:10282000C1FF02B010BD00000144BFF34F8F064B43 -:10283000884204D3BFF34F8FBFF36F8F7047C3F845 -:102840005C022030F4E700BF00ED00E0034B1B68A2 -:102850009B0042BF0122024B1A707047743802403D -:10286000253B0220014B1878704700BF253B022012 -:10287000064A536823F001035360EFF3098368337A -:1028800083F30988002383F31188704730EF00E059 -:1028900010B5202383F31188104B5B6813F4006399 -:1028A00018D0F1EE103AEFF309844FF0807344F83A -:1028B0004C3C0B4BDB6844F8083CA4F1680383F301 -:1028C0000988FFF701FC18B1064B44F8503C10BDD5 -:1028D000054BFAE783F3118810BD00BF00ED00E05F -:1028E00030EF00E05103000854030008F0B5BFF3D7 -:1028F0004F8FBFF36F8F1D4B0021C3F85012BFF3F2 -:102900004F8FBFF36F8F5A6942F400325A61BFF3A1 -:102910004F8FBFF36F8FC3F88410BFF34F8FD3F87F -:10292000802043F6E076C2F3C904C2F34E32A50715 -:10293000520102EA060E284621464EEA00070139F6 -:1029400000F14040C3F860724F1CF6D1203A12F1FA -:10295000200FEED1BFF34F8F5A6942F480325A6193 -:10296000BFF34F8FBFF36F8FF0BD00BF00ED00E0EE -:10297000FEE70000084A094B09498B4204D3094A83 -:102980000021934205D3704752F8040F43F8040B1B -:10299000F3E743F8041BF4E78C400008B03D022045 -:1029A000B03D0220B03D0220036F002230B5114639 -:1029B000C46E9D684FF0FF3004EB42130132954224 -:1029C000C3F80019C3F81019C3F80809C3F8001BAD -:1029D000C3F8101BC3F8080BEED24FF00113C4F874 -:1029E0001C3830BD890141F02001016103699B065B -:1029F000FCD4122000F0C4BE204B03EB80022DE972 -:102A0000F047D2F80CE0461CDD6EDEF8142005EB32 -:102A10000636D2F800C005EB4018516861450BD36B -:102A20000123D5F8342803FA00F022EA0000C5F8A3 -:102A300034081846BDE8F087ACEB0103BEF810403F -:102A4000A34228BF2346D8F81849A4B2B3EB840F99 -:102A500010D894681F46A4F1040959F804AF042F54 -:102A6000C6F800A001D9043FF7E71C440B4494606A -:102A70005360D2E70020BDE8F08700BF283B02206A -:102A800010B5054C2046FEF7E9FF4FF0A043E36682 -:102A9000024B236710BD00BF283B0220D43E000834 -:102AA0000378012B70B5054650D12A4BC46E98426D -:102AB0001BD1294B0E2143205A6B42F080025A63EE -:102AC0005A6D42F080025A655A6D5A6942F080028E -:102AD0005A615A6922F080025A615B69FEF73AFC3A -:102AE0001E4BE3601E4BC4F800380023EE6EC4F8A2 -:102AF000003EC02323604FF40413A3633369002B0B -:102B0000FCDA01230C20336100F03AFE3369DB0765 -:102B1000FCD4122000F034FE3369002BFCDA0026CE -:102B20002846A660FFF740FF6B68C4F81068DB68B2 -:102B3000C4F81468C4F81C684BB90A4BA3614FF081 -:102B4000FF336361A36843F00103A36070BD064BCC -:102B5000F4E700BF283B0220003802404014004048 -:102B600003002002003C30C0083C30C0F8B5C46E01 -:102B7000054600214FF000662046FFF733FF296F1E -:102B800000234FF001128F684FF0FF30C4F8343843 -:102B9000C4F81C2804EB431201339F42C2F80069B9 -:102BA000C2F8006BC2F80809C2F8080BF2D20B6831 -:102BB000EA6E6B67636210231361166916F01006E4 -:102BC000FBD1122000F0DCFDD4F8003823F4FE63C2 -:102BD000C4F80038A36943F4402343F01003A36111 -:102BE0000923C4F81038C4F814380A4BEB604FF0CE -:102BF000C043C4F8103B084BC4F8003BC4F810694C -:102C0000C4F800396B6F03F1100243F480136A6754 -:102C1000A362F8BDB03E000840800010C26E90F87C -:102C20006610D2F8003823F4FE6343EA0113C2F8B9 -:102C3000003870472DE9F0410EB20D4600EB8608D2 -:102C4000D8F80C100F6807F00303022B50D0032BA9 -:102C500050D03D4A3D4F012B18BF1746C46E4FEA76 -:102C6000451E002205F1100C04EB0E03C3F8102BD7 -:102C70008A69002A40D04A8A05F158033A435B0129 -:102C8000E2500123D4F81C2803FA0CF31343C4F8D0 -:102C90001C38A64400234A69CEF8103905F13F03D9 -:102CA000002A39D00A8A04EB8303898B9208012910 -:102CB00088BF4A43416F561841EA02422946466797 -:102CC00020465A60FFF78EFED8F80C301B8A43EA84 -:102CD00085531F4305F148035B01E7500123D4F8F6 -:102CE0001C2803FA05F51543C4F81C58BDE8F0810B -:102CF000174FB3E7174FB1E704EB4613D3F8002B98 -:102D000022F40042C3F8002B0123D4F81C2803FA54 -:102D10000CF322EA0303BAE704EB83030E4A04EB45 -:102D2000461629465A602046FFF75CFED6F8003961 -:102D3000012223F4004302FA05F5C6F80039D4F85D -:102D40001C3823EA0505CFE700800010008004103E -:102D50000080081000800C1000040002026F12684E -:102D60004267FFF721BE00005831C36E49015B582E -:102D700013F4004004D013F4001F14BF01200220FC -:102D8000704700004831C36E49015B5813F400409E -:102D900004D013F4001F14BF01200220704700006C -:102DA00000EB8101CB68196A0B6813604B685360B4 -:102DB0007047000000EB810330B5DD68AA69136835 -:102DC000D36019B9402B84BF402313606B8A146809 -:102DD000C26E1C4402EB4110013C09B2B4FBF3F497 -:102DE0006343033323F0030343EAC44343F0C04384 -:102DF000C0F8103B2B6803F00303012B0ED1D2F86F -:102E0000083802EB411013F4807FD0F8003B14BF68 -:102E100043F0805343F00053C0F8003B02EB4112F3 -:102E2000D2F8003B43F00443C2F8003B30BD000041 -:102E30002DE9F041244D0446EE6E06EB4013D3F825 -:102E4000087B3807C3F8087B0AD5D6F81438190769 -:102E500006D505EB840321462846DB685B68984766 -:102E6000FA072FD5D6F81438DB072BD505EB8403EA -:102E7000D968CCB98B69488A5E68B6FBF0F200FB72 -:102E800012628AB91868DA6890420DD2121A83E881 -:102E90001400202383F311880B482146FFF78AFF93 -:102EA00084F31188BDE8F081012303FA04F26B89F1 -:102EB00023EA02036B81CB6823B121460248BDE8B7 -:102EC000F0411847BDE8F081283B022000EB810368 -:102ED0004A0170B5DD68C36E6C692668E66056BB52 -:102EE0001A444FF40020C2F810092A6802F00302C5 -:102EF000012A0AB20ED1D3F8080803EB421410F4E9 -:102F0000807FD4F8000914BF40F0805040F000509A -:102F1000C4F8000903EB4212D2F8000940F0044063 -:102F2000C2F800090122D3F8340802FA01F1014382 -:102F3000C3F8341870BD19B9402E84BF40202060FA -:102F400020681A442E8A841940F00050013CB4FBDA -:102F5000F6F440EAC440C6E7F8B504461E48C56E1C -:102F600005EB4413D3F80869F107C3F8086917D5CE -:102F7000D5F81038DA0713D500EB8403D9684B690C -:102F80001F68DA68974218D2D21B00271A605F6068 -:102F9000202383F311882146FFF798FF87F31188D8 -:102FA000330617D50123D5F83428A340134211D096 -:102FB0002046BDE8F840FFF71FBD012303FA04F2E5 -:102FC000038923EA020303818B68002BE8D02146A2 -:102FD0009847E5E7F8BD00BF283B02209F482DE950 -:102FE000F84FC56E04466E69AB691E4016F4805FEB -:102FF0006E6105D0FEF7A4FDBDE8F84FFFF748BCB1 -:10300000002E12DAD5F8003E9B0705D0D5F8003E19 -:1030100023F00303C5F8003ED5F804388F4823F0A9 -:103020000103C5F80438FEF7B7FD370502D58B4814 -:10303000FEF7A6FDB0040CD5D5F8083813F0060F3E -:10304000EB6823F470530CBF43F4105343F4A053C4 -:10305000EB60310704D56368DB680BB17F489847A4 -:10306000F2026FD4B3020CD5D4F86C8000274FF075 -:103070000109DFF8E8A1236FF9B29B688B4280F069 -:103080009C80F70619D5E16E0A6AC2F30A1702F0AE -:103090000F0302F4F012B2F5802F00F0B580B2F504 -:1030A000402F0AD104EB830301F58051DB68186AD5 -:1030B00000231A469F4240F09C803303D5F81848FD -:1030C0001DD5E70302D50020FFF7B2FEA50302D508 -:1030D0000120FFF7ADFE600302D50220FFF7A8FE36 -:1030E000210302D50320FFF7A3FEE20202D504204C -:1030F000FFF79EFEA30202D50520FFF799FE770396 -:103100007FF57AAFE60702D50020FFF725FFA50778 -:1031100002D50120FFF720FF600702D50220FFF74C -:103120001BFF210702D50320FFF716FFE20602D599 -:103130000420FFF711FFA3067FF55EAF0520FFF720 -:103140000BFF59E7D4F86C8000274FF00109DFF836 -:103150000CA1236F5FFA87FB9B685B4582D308EB6A -:103160004B13D3F8002902F44022B2F5802F22D16C -:10317000D3F80029002A1EDAD3F8002942F0904241 -:10318000C3F80029D3F80029002AFBDB5946E06E7A -:10319000FFF728FC228909FA0BF322EA03032381B3 -:1031A00004EB8B03DB689B6813B159465046984784 -:1031B0005846FFF721FC0137CBE708EB4112D2F864 -:1031C000003B03F44023B3F5802F10D1D2F8003B2D -:1031D000002B0CDA628909FA01F322EA0303638106 -:1031E00004EB8103DB68DB680BB15046984701377D -:1031F00041E79C0700D10A68072B03F101039EBF3A -:103200000270120A013055E7023301F5805104EBD8 -:103210008302526890690268D0F808C04068A2EB47 -:10322000000E0022104697420AD104EB8304636823 -:103230009B699A683A449A605A6817445F603CE711 -:1032400012F0030F00D10868964502F1010282BF17 -:103250008CF80000000A0CF1010CE4E7283B022086 -:10326000C36E03EB4111D1F8003B43F40013C1F8E6 -:10327000003B7047C36E03EB4111D1F8003943F4B2 -:103280000013C1F800397047C36E03EB4111D1F848 -:10329000003B23F40013C1F8003B7047C36E03EBFF -:1032A0004111D1F8003923F40013C1F800397047F7 -:1032B00030B50433039C0172002104FB0325C36174 -:1032C000049B00600363059B4060C1604261026132 -:1032D0008561046242628162C162436330BD000065 -:1032E0000022416AC260416101616FF001018262A6 -:1032F000C262FEF771BF000003694269934203D1C5 -:10330000C2680AB100207047181D70470369196030 -:103310000021C2680132C260C269134482699342CB -:10332000036124BF436A0361FEF74ABF38B5044610 -:103330000D46E3683BB162690020131D1268A36269 -:103340001344E36238BD237A33B929462046FEF799 -:1033500027FF0028EDDA38BD6FF00100FBE7000021 -:10336000C368C269013BC3604369134482699342E5 -:10337000436124BF436A436100238362036B03B14B -:103380001847704770B52023044683F31188866A76 -:103390003EB9FFF7CBFF054618B186F311882846E2 -:1033A00070BDA36AE26A13F8015B9342A36202D381 -:1033B0002046FFF7D5FF002383F31188EFE70000D5 -:1033C0002DE9F84F04460E4690469946202787F38C -:1033D00011880025AA46D4F828B0BBF1000F09D106 -:1033E00049462046FFF7A2FF20B18BF311882846FB -:1033F000BDE8F88FA16AA8EB050BE36A5B1A9B4551 -:1034000028BF9B46BBF1400F1BD9334601F1400258 -:1034100051F8040B914243F8040BF9D1A36A4036EA -:1034200040354033A362A26AE36A9A4202D320463F -:10343000FFF796FF8AF311884545D8D287F31188A4 -:10344000C9E730465A46FDF7E5FCA36A5E445D4491 -:103450005B44A362E7E7000010B5029C04330172ED -:10346000C36103FB0421002300608362C362039BEA -:1034700040600363049BC460426102618161046235 -:103480004262436310BD0000026A6FF00101C26036 -:10349000426A4261026100228262C262FEF79CBE01 -:1034A000436902699A4203D1C2680AB10020704799 -:1034B000184650F8043B0B6070470000C3680021B9 -:1034C000C2690133C3604369134482699342436113 -:1034D00024BF436A4361FEF773BE000038B504465B -:1034E0000D46E3683BB1236900201A1DA262E26920 -:1034F0001344E36238BD237A33B929462046FEF7E8 -:103500004FFE0028EDDA38BD6FF00100FBE7000048 -:1035100003691960C268013AC260C26913448269D2 -:103520009342036124BF436A036100238362036BF8 -:1035300003B118477047000070B5202304460E46BB -:1035400083F31188856A35B91146FFF7C7FF10B1BB -:1035500085F3118870BDA36A1E70A36AE26A013305 -:103560009342A36204D3E16920460439FFF7D0FFF8 -:10357000002080F3118870BD2DE9F84F04460D46F8 -:1035800091469A464FF0200888F311880026B346EA -:10359000A76A4FB951462046FFF7A0FF20B187F335 -:1035A00011883046BDE8F88FA06AA9EB0603E76AE8 -:1035B0003F1A9F4228BF1F46402F1BD905F14003E9 -:1035C00055F8042B9D4240F8042BF9D1A36A4036EC -:1035D0004033A362A26AE36A9A4204D3E1692046B7 -:1035E0000439FFF795FF8BF311884E45D9D288F344 -:1035F0001188CDE729463A46FDF70CFCA36A3D4405 -:103600003E443B44A362E5E7026943699A4203D121 -:10361000C3681BB9184670470023FBE7836A002B79 -:10362000F8D0043B9B1AF5D01360C368013BC3601C -:10363000C3691A4483699A42026124BF436A0361E1 -:10364000002383620123E5E700F040B94FF0804397 -:10365000002258631A610222DA60704700224FF09C -:103660008043DA60704700004FF080435863704732 -:10367000FEE7000010B5194CFEF798FCFEF7BAFD06 -:10368000802217492046FEF73FFD012344F8180C1D -:103690000374144B144AD96821F4E0610904090C3D -:1036A0000A431249DA60CA6842F08072CA60104A5E -:1036B0001049C2F8B01F116841F0010111601022D9 -:1036C000DA77202283F82220002383F3118862B660 -:1036D0000948BDE81040FEF739BD00BFB4330220F1 -:1036E000E03E000800ED00E00003FA05F0ED00E028 -:1036F000001000E055CEACC5E83E00082DE9F84FBB -:103700001E4C4FF00008656904F11407C1464FF0E4 -:103710008043266AAA685B6A9E1B96421CD34FF0C0 -:10372000200AAA68236AD5F80CB0B61A134423629B -:103730002B68BB425F606361C5F80C8001D1FFF765 -:103740008DFF89F311882869D8478AF31188656944 -:10375000AB689E42E5D2DAE76269BA420CD0916862 -:1037600023628E1B9660A86802282CBF1818981C2C -:10377000BDE8F84FFFF778BFBDE8F88F8C33022023 -:10378000034B59685A68521A9042FBD8704700BFE1 -:10379000001000E04B6843608B688360CB68C360B7 -:1037A0000B6943614B6903628B6943620B68036079 -:1037B0007047000008B5274B40F2FF7126481A6990 -:1037C0000A431A611A6922F4FF6222F007021A61A1 -:1037D0001A691A6B0A431A631A6D0A431A651F4A5B -:1037E0001B6D1146FFF7D6FF1D4802F11C01FFF7C4 -:1037F000D1FF1C4802F13801FFF7CCFF1A4802F153 -:103800005401FFF7C7FF194802F17001FFF7C2FF2B -:10381000174802F18C01FFF7BDFF164802F1A8011D -:10382000FFF7B8FF144802F1C401FFF7B3FF1348D4 -:1038300002F1E001FFF7AEFF114802F1FC01FFF7D2 -:10384000A9FF104802F58C71FFF7A4FFBDE80840FE -:1038500000F09EB80038024000000240083F000817 -:103860000004024000080240000C02400010024028 -:103870000014024000180240001C024000200240D8 -:10388000002402400028024008B500F0F5F9FFF7D7 -:10389000F1FEFEF7DBFFBDE80840FEF7B5BD000016 -:1038A000704700004FF080431A69920710B508D5A1 -:1038B00000241C61202383F31188FFF71FFF84F38A -:1038C0001188BDE81040FEF7E3BF0000104B08214F -:1038D0001C201A6C42F001021A641A6E42F00102B6 -:1038E0001A660C4A1B6E936843F0010393604FF015 -:1038F00080436B229A624FF0FF32DA6200229A61B3 -:103900005A63DA605A6001225A611A60FDF722BDDB -:1039100000380240002004E01B4B4FF0FF30002134 -:103920001A696FEA42526FEA52521A611A69C2F377 -:103930000A021A611A695A6958615A6959615A69C1 -:103940001A6A62F080521A621A6A02F080521A628F -:103950001A6A5A6A58625A6A59625A6A0B4A106855 -:1039600040F480701060186F00F44070B0F5007F74 -:1039700003D04FF4803018671967536823F400733D -:10398000536000F059B900BF003802400070004099 -:10399000354B4FF44041354A1A64354A11601A6874 -:1039A00042F001021A601A689207FCD59A6822F068 -:1039B00003029A602C4B19469A6812F00C02FBD154 -:1039C000186800F0F90018609A601A6842F48032B2 -:1039D0001A600B689B03FCD54B6F43F001034B67E8 -:1039E000214B5A6F9007FCD5224A5A601A6842F060 -:1039F00080721A601E4B1A4659684904FCD5196832 -:103A000041F4803119605368D803FCD5136843F43E -:103A100000331360164A53689903FCD5124B1A6899 -:103A20009201FCD5144A40F207319A6040F201122B -:103A3000C3F88C200022C3F89020104A11609A68C5 -:103A400042F002029A60084B9A6802F00C02082ABF -:103A5000FAD15A6C42F480425A645A6E42F480425F -:103A60005A665B6E704700BF0038024000040010C9 -:103A700000700040186C400900948838003C0240F7 -:103A8000084A08B5536911680B4003F001035361FC -:103A900023B1054A13680BB150689847BDE8084048 -:103AA000FEF7F6BE003C0140C8250220084A08B5D2 -:103AB000536911680B4003F00203536123B1054AB7 -:103AC00093680BB1D0689847BDE80840FEF7E0BEA8 -:103AD000003C0140C8250220084A08B55369116816 -:103AE0000B4003F00403536123B1054A13690BB182 -:103AF00050699847BDE80840FEF7CABE003C014047 -:103B0000C8250220084A08B5536911680B4003F024 -:103B10000803536123B1054A93690BB1D0699847F3 -:103B2000BDE80840FEF7B4BE003C0140C8250220B5 -:103B3000084A08B5536911680B4003F0100353613C -:103B400023B1054A136A0BB1506A9847BDE8084093 -:103B5000FEF79EBE003C0140C8250220174B10B561 -:103B60005C691A68144004F478725A61A30604D59B -:103B7000134A936A0BB1D06A9847600604D5104A7D -:103B8000136B0BB1506B9847210604D50C4A936B0D -:103B90000BB1D06B9847E20504D5094A136C0BB101 -:103BA000506C9847A30504D5054A936C0BB1D06CB3 -:103BB0009847BDE81040FEF76BBE00BF003C0140D7 -:103BC000C82502201A4B10B55C691A68144004F429 -:103BD0007C425A61620504D5164A136D0BB1506DD3 -:103BE0009847230504D5134A936D0BB1D06D9847C0 -:103BF000E00404D50F4A136E0BB1506E9847A10430 -:103C000004D50C4A936E0BB1D06E9847620404D56C -:103C1000084A136F0BB1506F9847230404D5054A27 -:103C2000936F0BB1D06F9847BDE81040FEF730BEE0 -:103C3000003C0140C8250220062108B50846FDF7D2 -:103C400089FB06210720FDF785FB06210820FDF7EB -:103C500081FB06210920FDF77DFB06210A20FDF7E7 -:103C600079FB06211720FDF775FB06212820BDE80A -:103C70000840FDF76FBB000008B5FFF74DFEFDF7EC -:103C8000B5F9FDF711FDFDF7E7FEFDF7BBFDFFF709 -:103C900007FEBDE80840FFF7D7BC0000034611F857 -:103CA000012B03F8012B002AF9D1704712101213CF -:103CB000121100000010410001105A00CC33022004 -:103CC00048260220B42602202027022053544D33D8 -:103CD00032463F3F3F3F3F3F0053544D333246371C -:103CE0005B347C355D780053544D333246375B3658 -:103CF0007C375D78000000000096000000000000A6 -:103D000000000000000000000000000000000000B3 -:103D100000000000711600085D16000899160008E2 -:103D200085160008911600087D160008691600081F -:103D300055160008A5160008000000007D170008B1 -:103D400069170008A5170008911700089D170008BB -:103D50008917000875170008611700080118000886 -:103D60000000000001000000000000000200000050 -:103D700000000000A9190008111A000840004000C6 -:103D800064380220743802200200000000000000A5 -:103D90000300000000000000551A000800000000A9 -:103DA0001000000084380220000000000100000024 -:103DB00000000000283B0220010102004865782F26 -:103DC00050726F6669434E43004375626559656C76 -:103DD0006C6F772D424C002553455249414C2500CC -:103DE000A923000811230008151900088D230008D5 -:103DF00043000000F83D000809024300020100C032 -:103E0000320904000001020201000524001001052E -:103E10002401000104240202052406000107058292 -:103E2000030800FF09040100020A00000007050161 -:103E3000024000000705810240000000120000005F -:103E4000443E00081201100102000040AE2D021095 -:103E500000020102030100000403090425424F414E -:103E6000524425004375626559656C6C6F7700306C -:103E700031323334353637383941424344454600D0 -:103E80000080000000800000008000000080000032 -:103E90000000020000000400000004000000040014 -:103EA0000000040000000400000004000000040002 -:103EB00000000000AD1B00088D1E0008391F00081F -:103EC00040004000A03B0220A03B02200100000077 -:103ED000B03B02208000000040010000050000000F -:103EE0006D61696E00000000003F0008B83B0220D1 -:103EF000B03D022001000000713600080000000003 -:103F000069646C65000000000000802A0000000069 -:103F1000AAAAAAAA00000000FFFF000000000000FB -:103F200000A00A000001000000000000AAAAAAAA3E -:103F300000000000FFFF0000000000000000000083 -:103F40001400005400000000AAAAAAAA14000054F9 -:103F5000FFFF0000000000000000000080699A01DF -:103F600000000000AAAA8AAA40555501FFFF0000E0 -:103F700000707007777000000081020000000000F0 -:103F8000AAAAAAAA00410100FFFF000000000080C9 -:103F9000080000000000000000000000AAAAAAAA71 -:103FA00000000000FFFF0000000000000000000013 -:103FB0000000000000000000AAAAAAAA0000000059 -:103FC000FFFF0000000000000000000000000000F3 -:103FD00000000000AAAAAAAA00000000FFFF00003B -:103FE00000000000000000000000000000000000D1 -:103FF000AAAAAAAA00000000FFFF0000000000001B -:1040000000000000000000000000000000000000B0 -:1040100000000000000000000000000000000000A0 -:104020000000000000000000000000000000000090 -:104030000000000000000000000000000000000080 -:10404000FF00000000000000CC3C00083F00000022 -:1040500049040000D93C00083F0000005104000062 -:10406000E73C00083F000000009600000000080048 -:1040700004000000583E000800000000000000009E -:104080000000000000000000000000000000000030 +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F02F008FB4C +:1002700003F07EFA4FF055301F491B4A91423CBFB4 +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE702F020FB03F0B8FA68 +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E702F008BB00060220002202203E +:1002F0000000000808ED00E00000022000060220D7 +:10030000F0400008002202206C220220702202200D +:10031000183A02200002000800020008000200084B +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F048FEFEE701F092 +:10035000D7FD00DFFEE7000038B500F01FFC02F01B +:100360004FFA054602F082FA0446C0B90E4B9D4290 +:1003700017D001339D4241F2883512BF0446002553 +:100380000124002002F046FA0CB100F075F800F0EC +:1003900055FD284600F0FAF800F06EF8F9E7002560 +:1003A000EFE70546EDE700BF010007B008B500F034 +:1003B000C1FBA0F120035842584108BD07B541F2E6 +:1003C0001203022101A8ADF8043000F0D1FB03B004 +:1003D0005DF804FB38B5302383F3118817480368B0 +:1003E0000BB101F0C7FE0023154A4FF47A71134890 +:1003F00001F0B6FE002383F31188124C236813B179 +:100400002368013B2360636813B16368013B636049 +:100410000D4D2B7833B963687BB9022000F080FC66 +:10042000322363602B78032B07D163682BB902203A +:1004300000F076FC4FF47A73636038BD70220220BE +:10044000D50300089023022088220220084B187050 +:1004500003280CD8DFE800F008050208022000F0AD +:100460005DBC022000F058BC024B00225A6070476D +:100470008822022090230220F8B53F4B3F4A1C46B9 +:100480001968013177D004339342F9D16268A242EE +:1004900071D33B4B9B6803F1006303F5C0339A4271 +:1004A00069D2002000F094FB0220FFF7CFFF354B0C +:1004B00000211A6C19641A6E19661A6E5A6C596406 +:1004C0005A6E59665A6E5A6942F080025A615A69E8 +:1004D00022F080025A615A691A6942F000521A6188 +:1004E0001A6922F000521A611B6972B64FF0E023BC +:1004F000C3F8084DD4E90004BFF34F8FBFF36F8FEB +:10050000214AC2F88410BFF34F8F536923F480331C +:100510005361BFF34F8FD2F8803043F6E076C3F3D8 +:10052000C905C3F34E335B0103EA060C29464CEAC6 +:1005300081770139C2F87472F9D2203B13F1200F90 +:10054000F2D1BFF34F8FBFF36F8FBFF34F8FBFF366 +:100550006F8F536923F4003353610023C2F8503284 +:10056000BFF34F8FBFF36F8F302383F3118885461E +:1005700080F308882047F8BD00800108208001082A +:10058000002202200038024000ED00E02DE9F04F8B +:1005900093B0B44B2022FF2100900AA89D6800F080 +:1005A000F7FBB14A1378A3B90121B0481170036079 +:1005B000302383F3118803680BB101F0DBFD0023C6 +:1005C000AB4A4FF47A71A94801F0CAFD002383F3C6 +:1005D0001188009B13B1A74B009A1A60A64A1378A2 +:1005E000032B03D000231370A24A53604FF0000A7C +:1005F000009CD3465646D146012000F08FFB24B123 +:100600009C4B1B68002B00F02682002000F092FA21 +:100610000390039B002BF2DB012000F07DFB039B8A +:10062000213B1F2BE8D801A252F823F0AD060008A9 +:10063000D506000869070008F9050008F905000853 +:10064000F9050008FB070008CB090008E5080008C9 +:10065000470900086F09000895090008F905000816 +:10066000A7090008F9050008190A00084D07000845 +:10067000F90500085D0A0008B90600084D070008E2 +:10068000F905000847090008F9050008F905000800 +:10069000F9050008F9050008F9050008F905000842 +:1006A000F9050008F9050008690700080220FFF7AE +:1006B0007DFE002840F0F981009B022105A8BAF1D7 +:1006C000000F08BF1C4641F21233ADF8143000F0A1 +:1006D0004FFA91E74FF47A7000F02CFA071EEBDB2B +:1006E0000220FFF763FE0028E6D0013F052F00F24D +:1006F000DE81DFE807F0030A0D101336052304211D +:1007000005A8059300F034FA17E004215548F9E7ED +:1007100004215A48F6E704215948F3E74FF01C0832 +:10072000404608F1040800F055FA0421059005A898 +:1007300000F01EFAB8F12C0FF2D101204FF00009A1 +:1007400000FA07F747EA0B0B5FFA8BFB00F06CFB34 +:1007500026B10BF00B030B2B08BF0024FFF72EFE76 +:100760004AE704214748CDE7002EA5D00BF00B0344 +:100770000B2BA1D10220FFF719FE074600289BD0C2 +:100780000120002600F024FA0220FFF75FFE1FFA86 +:1007900086F8404600F02CFA0446B0B10399404672 +:1007A0000136A1F140025142514100F031FA0028D6 +:1007B000EDD1BA46044641F21213022105A83E4685 +:1007C000ADF8143000F0D4F916E725460120FFF704 +:1007D0003DFE244B9B68AB4207D9284600F0FAF94E +:1007E000013040F067810435F3E70025224BBA461B +:1007F0003E461D701F4B5D60A8E7002E3FF45CAFC6 +:100800000BF00B030B2B7FF457AF0220FFF71EFEFC +:10081000322000F08FF9B0F10008FFF64DAF18F06C +:1008200003077FF449AF0F4A08EB05039268934230 +:100830003FF642AFB8F5807F3FF73EAF124BB84569 +:10084000019323DD4FF47A7000F074F90390039A5A +:10085000002AFFF631AF039A0137019B03F8012B01 +:10086000EDE700BF002202208C230220702202202C +:10087000D5030008902302208822022004220220AF +:10088000082202200C2202208C220220C820FFF71E +:100890008DFD074600283FF40FAF1F2D11D8C5F17D +:1008A00020020AAB25F0030084494245184428BFC2 +:1008B0004246019200F046FA019AFF217F4800F07B +:1008C00067FA4FEAA803C8F387027C4928460193D8 +:1008D00000F066FA064600283FF46DAF019B05EB79 +:1008E000830533E70220FFF761FD00283FF4E4AE03 +:1008F00000F0BAF900283FF4DFAE0027B846704B8D +:100900009B68BB4218D91F2F11D80A9B01330ED008 +:1009100027F0030312AA134453F8203C05934046E2 +:10092000042205A9043700F0E7FA8046E7E73846D5 +:1009300000F050F90590F2E7CDF81480042105A8E5 +:1009400000F016F902E70023642104A8049300F0E4 +:1009500005F900287FF4B0AE0220FFF727FD00283C +:100960003FF4AAAE049800F067F90590E6E700238B +:10097000642104A8049300F0F1F800287FF49CAEF1 +:100980000220FFF713FD00283FF496AE049800F014 +:1009900063F9EAE70220FFF709FD00283FF48CAE77 +:1009A00000F072F9E1E70220FFF700FD00283FF4B4 +:1009B00083AE05A9142000F06DF9074604210490C8 +:1009C00004A800F0D5F83946B9E7322000F0B2F8B3 +:1009D000071EFFF671AEBB077FF46EAE384A07EB19 +:1009E0000903926893423FF667AE0220FFF7DEFCF0 +:1009F00000283FF461AE27F003074F44B9453FF4A8 +:100A0000A5AE484609F1040900F0E4F80421059078 +:100A100005A800F0ADF8F1E74FF47A70FFF7C6FCD7 +:100A200000283FF449AE00F01FF9002844D00A9B8B +:100A300001330BD008220AA9002000F0B1F90028E8 +:100A40003AD02022FF210AA800F0A2F9FFF7B6FC55 +:100A50001C4801F0C9FA13B0BDE8F08F002E3FF436 +:100A60002BAE0BF00B030B2B7FF426AE002364217F +:100A700005A8059300F072F8074600287FF41CAE25 +:100A80000220FFF793FC804600283FF415AEFFF7E5 +:100A900095FC41F2883001F0A7FA059800F00AFAB7 +:100AA00046463C4600F0C0F9A6E506464EE64FF045 +:100AB000000901E6BA467EE637467CE68C22022033 +:100AC00000220220A08601002DE9F84F4FF47A732E +:100AD00006460D46002402FB03F7DFF85080DFF8DE +:100AE000509098F900305FFA84FA5A1C01D0A34262 +:100AF00010D159F824002A4631460368D3F820B0B3 +:100B00003B46D847854205D1074B012083F800A01A +:100B1000BDE8F88F0134042CE3D14FF4FA7001F0F2 +:100B200063FA0020F4E700BFDC2302201022022039 +:100B300014220220002307B5024601210DF107000F +:100B40008DF80730FFF7C0FF20B19DF8070003B014 +:100B50005DF804FB4FF0FF30F9E700000A4604217E +:100B600008B5FFF7B1FF80F00100C0B2404208BDF8 +:100B7000074B0A4630B41978064B53F8214001461A +:100B800023682046DD69044BAC4630BC604700BF9B +:100B9000DC23022014220220A086010070B50A4E38 +:100BA00000240A4D01F032FD3080286833888342EA +:100BB00008D901F025FD2B6804440133B4F5C03F8A +:100BC0002B60F2D370BD00BFDE23022098230220E9 +:100BD00001F0CABD00F1006000F5C0300068704748 +:100BE00000F10060920000F5C03001F055BD00003A +:100BF000054B1A68054B1B889B1A834202D9104487 +:100C000001F0FEBC0020704798230220DE23022062 +:100C100038B50446074D29B128682044BDE838405E +:100C200001F00EBD2868204401F0F2FC0028F3D04A +:100C300038BD00BF9823022010F0030309D1B0F59E +:100C4000846F04D200F10050A0F5712003681846AB +:100C500070470023FBE7000000F10050A0F5712071 +:100C6000D0F8200470470000064991F8243033B1D1 +:100C700000230822086A81F82430FFF7B1BF012061 +:100C8000704700BF9C230220014B1868704700BFCB +:100C9000002004E01E4B0138F0B51D680A1803233C +:100CA0001C482E0CC5F30B0435460788A7420BD110 +:100CB00044680B46013C934218461BD214F9010FBD +:100CC00048B103F8010BF6E7013B00F10800ECD155 +:100CD00091420ED20B4618462C24B6F5805F00F8E0 +:100CE000014B0AD1824202D94122981C5A70401A03 +:100CF000F0BD0846B6F5805FF9D041F201039D4290 +:100D0000F5D18242F3D95A2300F8013BEFE700BF47 +:100D1000002004E0242202207047000070470000F9 +:100D20007047000070B504464FF47A764CB1412C00 +:100D3000254628BF412506FB05F0641B01F054F948 +:100D4000F4E770BD002310B5934203D0CC5CC454CB +:100D50000133F9E710BD0000013810B510F9013F6B +:100D60003BB191F900409C4203D11AB10131013AE3 +:100D7000F4E71AB191F90020981A10BD1046FCE76B +:100D800003460246D01A12F9011B0029FAD1704716 +:100D900002440346934202D003F8011BFAE770476E +:100DA0002DE9F8431F4D14460746884695F8242040 +:100DB00052BBDFF870909CB395F824302BB92022F9 +:100DC000FF2148462F62FFF7E3FF95F824004146D4 +:100DD000C0F1080205EB8000A24228BF2246D6B22D +:100DE0009200FFF7AFFF95F82430A41B17441E4470 +:100DF0009044E4B2F6B2082E85F82460DBD1FFF708 +:100E000033FF0028D7D108E02B6A03EB820383422B +:100E1000CFD0FFF729FF0028CBD10020BDE8F88311 +:100E20000120FBE79C230220024B1A78024B1A7028 +:100E3000704700BFDC23022010220220F8B5184CB6 +:100E4000184800F02FFC2146164800F057FC246893 +:100E50004FF47A70144EE26E144DD2F80438114FEC +:100E600043F00203C2F80438FFF75CFF2046104944 +:100E700000F04CFDE26E0424D2F8043823F00203A3 +:100E8000C2F804384FF4E133336055F8040BB8422C +:100E900002D0314600F066FB013CF6D1F8BD00BF40 +:100EA000A43E0008982D0220C42302201422022010 +:100EB000AC3E00080C4B70B50C4D04461E780C4B34 +:100EC00055F826209A420DD00A4B002118221846C8 +:100ED000FFF75EFF0460014655F82600BDE870404C +:100EE00000F040BB70BD00BFDC23022014220220B2 +:100EF000982D0220C423022030B50A44084D9142A7 +:100F00000DD011F8013B5840082340F30004013B89 +:100F10002C4013F0FF0384EA5000F6D1EFE730BD18 +:100F20002083B8ED026843681143016003B118479C +:100F300070470000024A136843F0C0031360704713 +:100F400000440040024A136843F0C0031360704736 +:100F500000480040024A136843F0C0031360704722 +:100F60000078004037B5274C274D204600F0EEFAB8 +:100F700004F11400009400234FF48072234900F020 +:100F8000ABF94FF48072224904F138000094214BF0 +:100F900000F024FA204BC4E91735204C204600F01D +:100FA000D5FA04F11400009400234FF480721C4918 +:100FB00000F092F94FF480721A4904F1380000945D +:100FC000194B00F00BFA194BC4E91735184C2046A1 +:100FD00000F0BCFA04F1140000234FF480721549AC +:100FE000009400F079F9144B4FF48072134904F126 +:100FF0003800009400F0F2F9114BC4E9173503B042 +:1010000030BD00BFE023022080F9370324250220F1 +:1010100024280220350F0008004400404C24022000 +:101020002426022024290220450F00080048004001 +:10103000B824022024270220550F0008242A022069 +:1010400000780040037C30B52E4C002918BF0C46B8 +:10105000012B13D12C4B98420AD12C4B1A6C42F421 +:1010600000321A641A6E42F400321A661B6E05E0F2 +:10107000274B98422FD0274B984235D02268036ED9 +:10108000C16D03EB52038466B3FBF2F3626815048F +:1010900042BF23F0070503F0070343EA4503CB6093 +:1010A000A36843F040034B60E36843F001038B60A7 +:1010B00042F4967343F001030B604FF0FF330B6271 +:1010C000510505D512F0102217D0B2F1805F16D06D +:1010D00080F8643030BD0D4B1A6C42F480221A64E3 +:1010E0001A6E42F48022C0E7084B1A6C42F080422C +:1010F0001A641A6E42F08042B7E77F23E8E73F2385 +:10110000E6E700BFB43D0008E023022000380240BB +:101110004C240220B82402202DE9F047C66D054674 +:101120003768F469210734621AD014F0080118BF37 +:101130004FF48071E20748BF41F02001A3074FF050 +:10114000300348BF41F04001600748BF41F08001D3 +:1011500083F31188281DFFF7E5FE002383F3118830 +:10116000E2050AD5302383F311884FF48061281DEE +:10117000FFF7D8FE002383F311884FF030094FF0BA +:10118000000A14F0200838D13B0616D54FF030097C +:1011900005F1380A200610D589F31188504600F071 +:1011A00051F9002836DA0821281DFFF7BBFE27F089 +:1011B00080033360002383F31188790614D5620617 +:1011C00012D5302383F31188D5E913239A4208D12D +:1011D0002B6C33B127F040071021281DFFF7A2FE2A +:1011E0003760002383F31188E30618D5AA6E1369CC +:1011F000ABB15069BDE8F047184789F31188736AAD +:10120000284695F86410194000F0BAF98AF311885D +:10121000F469B6E7B06288F31188F469BAE7BDE80B +:10122000F0870000F8B51546826804460B46AA42CE +:1012300000D28568A1692669761AB5420BD2184694 +:101240002A46FFF77FFDA3692B44A3612846A368C4 +:101250005B1BA360F8BD0CD9AF1B18463246FFF7E5 +:1012600071FD3A46E1683044FFF76CFDE3683B44AA +:10127000EBE718462A46FFF765FDE368E5E700005F +:1012800083689342F7B50446154600D28568D4E9D1 +:101290000460361AB5420BD22A46FFF753FD636944 +:1012A0002B4463612846A3685B1BA36003B0F0BDB9 +:1012B0000DD93246AF1B0191FFF744FD01993A4623 +:1012C000E0683144FFF73EFDE3683B44E9E72A4626 +:1012D000FFF738FDE368E4E710B50A440024C36172 +:1012E000029B8460C16002610362C0E90000C0E942 +:1012F000051110BD08B5D0E90532934201D18268CD +:1013000082B98268013282605A1C426119700021E0 +:10131000D0E904329A4224BFC368436100F080FEE2 +:10132000002008BD4FF0FF30FBE7000070B5302310 +:1013300004460E4683F31188A568A5B1A368A26987 +:10134000013BA360531CA36115782269934224BF1B +:10135000E368A361E3690BB120469847002383F358 +:101360001188284607E03146204600F049FE002853 +:10137000E2DA85F3118870BD2DE9F74F04460E4679 +:1013800017469846D0F81C904FF0300A8AF311881F +:101390004FF0000B154665B12A4631462046FFF74F +:1013A00041FF034660B94146204600F029FE00286F +:1013B000F1D0002383F31188781B03B0BDE8F08FD0 +:1013C000B9F1000F03D001902046C847019B8BF371 +:1013D0001188ED1A1E448AF31188DCE7C160C361ED +:1013E000009B82600362C0E905111144C0E900005E +:1013F00001617047F8B504460D461646302383F365 +:101400001188A768A7B1A368013BA36063695A1C50 +:1014100062611D70D4E904329A4224BFE3686361BB +:10142000E3690BB120469847002080F3118807E05C +:101430003146204600F0E4FD0028E2DA87F3118807 +:10144000F8BD0000D0E9052310B59A4201D18268A9 +:101450007AB982680021013282605A1C82611C784C +:1014600003699A4224BFC368836100F0D9FD204616 +:1014700010BD4FF0FF30FBE72DE9F74F04460E4655 +:1014800017469846D0F81C904FF0300A8AF311881E +:101490004FF0000B154665B12A4631462046FFF74E +:1014A000EFFE034660B94146204600F0A9FD002842 +:1014B000F1D0002383F31188781B03B0BDE8F08FCF +:1014C000B9F1000F03D001902046C847019B8BF370 +:1014D0001188ED1A1E448AF31188DCE7026843681C +:1014E0001143016003B11847704700001430FFF743 +:1014F00043BF00004FF0FF331430FFF73DBF000043 +:101500003830FFF7B9BF00004FF0FF333830FFF736 +:10151000B3BF00001430FFF709BF00004FF0FF31E8 +:101520001430FFF703BF00003830FFF763BF00003F +:101530004FF0FF323830FFF75DBF0000012914BFC4 +:101540006FF0130000207047FFF70CBD044B0360E1 +:1015500000234360C0E9023301230374704700BFD6 +:10156000CC3D000810B53023044683F31188FFF703 +:1015700069FD02230020237480F3118810BD000050 +:1015800038B5C36904460D461BB904210844FFF76A +:10159000A5FF294604F11400FFF7ACFE002806DA87 +:1015A000201D4FF40061BDE83840FFF797BF38BDFC +:1015B000026843681143016003B118477047000097 +:1015C00013B5446BD4F8A4381A681178042915D1DE +:1015D000217C022912D11979012312898B401342EF +:1015E0000CD101A904F14C0001F07EFFD4F8A4480D +:1015F0000246019B2179206800F0D6F902B010BDA7 +:10160000143001F001BF00004FF0FF33143001F03F +:10161000FBBE00004C3001F0D3BF00004FF0FF33A1 +:101620004C3001F0CDBF0000143001F0CFBE0000FF +:101630004FF0FF31143001F0C9BE00004C3001F012 +:101640009FBF00004FF0FF324C3001F099BF000007 +:1016500000207047D0F8A4381A6810B511780446F5 +:10166000042917D1017C022914D159790123528907 +:101670008B4013420ED1143001F062FE024648B195 +:10168000D4F8A4484FF4807361792068BDE8104015 +:1016900000F078B910BD0000406BFFF7DBBF000021 +:1016A000704700007FB5124B0125042604460360F5 +:1016B0000023057400F1840243602946C0E9023327 +:1016C0000C4B0290143001934FF48073009601F09C +:1016D00013FE094B04F29442294604F14C00029493 +:1016E000CDE900634FF4807301F0DAFE04B070BD01 +:1016F000F43D000899160008C11500080B68302257 +:1017000082F311880A7903EB820210624A790D3262 +:1017100043F822008A7912B103EB82031862022394 +:10172000C0F8A4180374002080F3118870470000EB +:1017300038B5037F044613B190F85430ABB9012596 +:10174000201D0221FFF734FF04F114006FF00101A6 +:10175000257700F071FC04F14C0084F854506FF0D0 +:101760000101BDE8384000F067BC38BD10B501216B +:1017700004460430FFF71CFF0023237784F854301D +:1017800010BD000038B504460025143001F0CCFD32 +:1017900004F14C00257701F09BFE201D84F8545085 +:1017A0000121FFF705FF2046BDE83840FFF752BF93 +:1017B00090F85C3003F06003202B06D190F85D2098 +:1017C0000023212A03D81F2A06D800207047222A86 +:1017D000FBD1C0E9143303E0034A026507224265E6 +:1017E00083650120704700BF3C220220D0F8A43856 +:1017F00037B51A680446117804291AD1017C0229E8 +:1018000017D11979012312898B40134211D100F1AC +:101810004C05284601F01CFF58B101A9284601F0EB +:1018200063FED4F8A4480246019B2179206800F0A9 +:10183000BBF803B030BD000000EB8103F0B51E6AB9 +:1018400085B004460D46FEB1302383F3118804EBC6 +:101850008507301D0821FFF7ABFEFB6806F14C0041 +:101860005B691B681BB1019001F04CFE019803A954 +:1018700001F03AFE024648B1039B2946204600F09B +:1018800093F8002383F3118805B0F0BDFB685A6913 +:101890001268002AF5D01B8A013B1340F1D104F1F4 +:1018A0005C02EAE70D3138B550F82140DCB1302355 +:1018B00083F31188D4F8A4281368527903EB8203C8 +:1018C000DB689B695D6845B104216018FFF770FE15 +:1018D000294604F1140001F03DFD2046FFF7BAFE51 +:1018E000002383F3118838BD7047000001F08AB8E7 +:1018F00001232822002110B5044600F8243BFFF7FD +:1019000047FA0023C4E9013310BD000038B504468E +:10191000302383F3118800254160C0E90355C0E9F5 +:101920000555C0E9075501F07DF80223237085F3C2 +:101930001188284638BD000070B500EB81030546CC +:1019400050690E461446DA6018B110220021FFF7E4 +:101950001FFAA06918B110220021FFF719FA3146C9 +:101960002846BDE8704001F027B90000826802F007 +:10197000011282600022C0E90422C0E9062202624C +:1019800001F0A6B9F0B4012500EB810447898D4030 +:10199000E4683D43A469458123600023A26063603D +:1019A000F0BC01F0C1B90000F0B4012500EB8104E6 +:1019B00007898D40E4683D43646905812360002305 +:1019C000A2606360F0BC01F03BBA000070B5022376 +:1019D0000025044603704566056280F84C50C0E956 +:1019E0000255C0E90455C0E9065501F081F8636865 +:1019F0001B6823B129462046BDE87040184770BDDA +:101A00000378052B10B504460AD080F8683005230A +:101A1000037043681B680BB1042198470023A3603F +:101A200010BD00000178052906D190F868204368B0 +:101A300002701B6803B118477047000070B590F83A +:101A40004C30044613B1002380F84C3004F15C02A2 +:101A5000204601F05FF963689B68B3B994F85C3085 +:101A600013F0600535D00021204601F011FC002163 +:101A7000204601F003FC63681B6813B10621204671 +:101A80009847062384F84C3070BD204698470028BC +:101A9000E4D0B4F86230626D9A4288BF636594F90D +:101AA0005C30656D002B4FF0300380F20381002D18 +:101AB00000F0F280092284F84C2083F31188002181 +:101AC0002046D4E91423FFF76FFF002383F3118826 +:101AD000DAE794F85D2003F07F0343EA022340F243 +:101AE0000232934200F0C58021D8B3F5807F48D000 +:101AF0000DD8012B3FD0022B00F09380002BB2D1E8 +:101B000004F16402226502226265A365C1E7B3F5B0 +:101B1000817F00F09B80B3F5407FA4D194F85E30C4 +:101B2000012BA0D1B4F8643043F0020332E0B3F5E6 +:101B3000006F4DD017D8B3F5A06F31D0A3F5C063B7 +:101B4000012B90D86368204694F85E205E6894F874 +:101B50005F10B4F86030B047002884D04368236534 +:101B6000036863651AE0B3F5106F36D040F60242A1 +:101B700093427FF478AF5C4B2365022363650023B7 +:101B8000C3E794F85E30012B7FF46DAFB4F8643096 +:101B900023F00203A4F86430C4E91455A56578E77E +:101BA000B4F85C30B3F5A06F0ED194F85E302046E7 +:101BB00084F8663000F0F4FF63681B6813B10121FC +:101BC00020469847032323700023C4E914339CE77D +:101BD00004F1670323650123C3E72378042B10D1A5 +:101BE000302383F311882046FFF7C0FE85F3118868 +:101BF0000321636884F8675021701B680BB120468D +:101C0000984794F85E30002BDED084F867300423C8 +:101C1000237063681B68002BD6D0022120469847AA +:101C2000D2E794F8603020461D0603F00F010AD574 +:101C300001F062F8012804D002287FF414AF2B4B86 +:101C40009AE72B4B98E701F049F8F3E794F85E30F8 +:101C5000002B7FF408AF94F8603013F00F01B3D07D +:101C60001A06204602D501F027FBADE701F01AFB6A +:101C7000AAE794F85E30002B7FF4F5AE94F860305C +:101C800013F00F01A0D01B06204602D501F000FB87 +:101C90009AE701F0F3FA97E7142284F84C2083F3D3 +:101CA00011882B462A4629462046FFF76BFE85F30E +:101CB0001188E9E65DB1152284F84C2083F3118880 +:101CC00000212046D4E91423FFF75CFEFDE60B2239 +:101CD00084F84C2083F311882B462A462946204657 +:101CE000FFF762FEE3E700BF243E00081C3E000849 +:101CF000203E000838B590F84C300446002B3ED00A +:101D0000063BDAB20F2A34D80F2B32D8DFE803F0C3 +:101D100037313108223231313131313131313737D8 +:101D2000456DB0F862309D4214D2C3681B8AB5FB82 +:101D3000F3F203FB12556DB9302383F311882B4660 +:101D40002A462946FFF730FE85F311880A2384F8D6 +:101D50004C300EE0142384F84C30302383F3118888 +:101D6000002320461A461946FFF70CFE002383F392 +:101D7000118838BD836D03B198470023E7E7002140 +:101D8000204601F085FA0021204601F077FA6368C9 +:101D90001B6813B10621204698470623D7E70000A9 +:101DA00010B590F84C300446142B29D017D8062BC8 +:101DB00005D001D81BB110BD093B022BFBD8002177 +:101DC000204601F065FA0021204601F057FA6368C9 +:101DD0001B6813B1062120469847062319E0152BEE +:101DE000E9D10B2380F84C30302383F31188002392 +:101DF0001A461946FFF7D8FD002383F31188DAE766 +:101E0000C3689B695B68002BD5D1836D03B198478C +:101E1000002384F84C30CEE7002382680375036901 +:101E20001B6899689142FBD25A6803604260106057 +:101E30005860704700238268037503691B689968BE +:101E40009142FBD85A680360426010605860704746 +:101E500008B50846302383F311880B7D032B05D08A +:101E6000042B0DD02BB983F3118808BD8B69002298 +:101E70001A604FF0FF338361FFF7CEFF0023F2E7D4 +:101E8000D1E9003213605A60F3E70000FFF7C4BFE6 +:101E9000054BD96808751868026853601A600122FA +:101EA000D8600275FEF73EBA282B02200C4B30B5E5 +:101EB000DD684B1C87B004460FD02B46094A6846A4 +:101EC00000F04EF92046FFF7E3FF009B13B1684690 +:101ED00000F050F9A86907B030BDFFF7D9FFF9E766 +:101EE000282B0220511E0008044B1A68DB689068FA +:101EF0009B68984294BF002001207047282B022045 +:101F0000084B10B51C68D868226853601A6001221B +:101F1000DC602275FFF78EFF01462046BDE81040C9 +:101F2000FEF700BA282B022038B5074C0123002504 +:101F3000064907482370656001F0C2FB0223237045 +:101F400085F3118838BD00BF902D02202C3E00087B +:101F5000282B022000F044B9034A516853685B1AE9 +:101F60009842FBD8704700BF001000E08B6002234E +:101F7000086108468B8270478368A3F1840243F8A6 +:101F8000142C026943F8442C426943F8402C094A56 +:101F900043F8242CC268A3F1200043F8182C022235 +:101FA00003F80C2C002203F80B2C034A43F8102CE6 +:101FB000704700BF3D030008282B022008B5FFF73B +:101FC000DBFFBDE80840FFF761BF0000024BDB68A4 +:101FD00098610F20FFF75CBF282B0220302383F38A +:101FE0001188FFF7F3BF000008B50146302383F3E3 +:101FF00011880820FFF75AFF002383F3118808BDDA +:10200000064BDB6839B1426818605A601360436060 +:102010000420FFF74BBF4FF0FF307047282B022002 +:102020000368984206D01A680260506018469961A9 +:10203000FFF72CBF7047000038B504460D462068F6 +:10204000844200D138BD036823605C608561FFF77E +:102050001DFFF4E7036810B59C68A2420CD85C68C9 +:102060008A600B604C602160596099688A1A9A6096 +:102070004FF0FF33836010BD121B1B68ECE70000BC +:102080000A2938BF0A2170B504460D460A26601990 +:1020900001F010FB01F0FCFA041BA54203D8751CEB +:1020A00004462E46F3E70A2E04D90120BDE870400D +:1020B00001F046BB70BD0000F8B5144B0D460A2A6E +:1020C0004FF00A07D96103F11001826038BF0A227C +:1020D000416019691446016048601861A81801F050 +:1020E000DBFA01F0D5FA431B0646A34206D37C1C5B +:1020F00028192746354601F0DDFAF2E70A2F04D900 +:102100000120BDE8F84001F01BBBF8BD282B0220E0 +:10211000F8B506460D4601F0BBFA0F4A134653F8D0 +:10212000107F9F4206D12A4601463046BDE8F8405E +:10213000FFF7C2BFD169BB68441A2C1928BF2C46CF +:10214000A34202D92946FFF79BFF224631460348A6 +:10215000BDE8F840FFF77EBF282B0220382B022075 +:10216000C0E90323002310B45DF8044B4361FFF77B +:10217000CFBF000010B5194C236998420DD081687B +:10218000D0E9003213605A609A680A449A600023CA +:1021900003604FF0FF33A36110BD0268234643F88C +:1021A000102F53600022026022699A4203D1BDE8D9 +:1021B000104001F079BA936881680B44936001F094 +:1021C00067FA2269E1699268441AA242E4D911448B +:1021D000BDE81040091AFFF753BF00BF282B0220AB +:1021E0002DE9F047DFF8BC8008F110072C4ED8F835 +:1021F000105001F04DFAD8F81C40AA68031B9A420F +:102200003ED814444FF00009D5E90032C8F81C400C +:1022100013605A60C5F80090D8F81030B34201D16D +:1022200001F042FA89F31188D5E90331284698472D +:10223000302383F311886B69002BD8D001F028FA82 +:102240006A69A0EB040982464A450DD2022001F0DA +:1022500077FA0022D8F81030B34208D15146284608 +:10226000BDE8F047FFF728BF121A2244F2E712EB4D +:1022700009092946384638BF4A46FFF7EBFEB5E75D +:10228000D8F81030B34208D01444C8F81C00211A02 +:10229000A960BDE8F047FFF7F3BEBDE8F08700BFD7 +:1022A000382B0220282B022000207047FEE7000078 +:1022B000704700004FF0FF307047000002290CD03B +:1022C000032904D00129074818BF00207047032ABA +:1022D00005D8054800EBC20070470448704700204D +:1022E000704700BF083F00084C220220BC3E000897 +:1022F00070B59AB005460846144601A900F0C2F828 +:1023000001A8FEF73DFD431C0022C6B25B0010464B +:10231000C5E9003423700323023404F8013C01AB07 +:10232000D1B202348E4201D81AB070BD13F8011B2D +:10233000013204F8010C04F8021CF1E708B530235F +:1023400083F311880348FFF751FA002383F31188C0 +:1023500008BD00BF982D022090F85C3003F01F02EA +:10236000012A07D190F85D200B2A03D10023C0E990 +:10237000143315E003F06003202B08D1B0F860306F +:102380002BB990F85D20212A03D81F2A04D8FFF723 +:102390000FBA222AEBD0FAE7034A02650722426508 +:1023A00083650120704700BF4322022007B505293D +:1023B00017D8DFE801F0191603191920302383F329 +:1023C0001188104A01210190FFF7B6FA0198022105 +:1023D0000D4AFFF7B1FA0D48FFF7D4F9002383F354 +:1023E000118803B05DF804FB302383F3118807489C +:1023F000FFF79EF9F2E7302383F311880348FFF7D4 +:10240000B5F9EBE75C3E0008803E0008982D0220FD +:1024100038B50C4D0C4C2A460C4904F10800FFF766 +:1024200067FF05F1CA0204F110000949FFF760FFD8 +:1024300005F5CA7204F118000649BDE83840FFF7F7 +:1024400057BF00BF703602204C220220383E0008E1 +:10245000453E0008503E000870B5044608460D464B +:10246000FEF78EFCC6B22046013403780BB918463D +:1024700070BD32462946FEF76FFC0028F3D10120DB +:10248000F6E700002DE9F84F05460C46FEF778FC0C +:102490002C49C6B22846FFF7DFFF08B10336F6B273 +:1024A00029492846FFF7D8FF08B11036F6B2632E47 +:1024B0000DD8DFF89080DFF89090244FDFF894A0DB +:1024C000DFF894B02E7846B92670BDE8F88F29461B +:1024D0002046BDE8F84F01F04FBC252E2ED1072233 +:1024E00041462846FEF738FC70B9DBF80030073566 +:1024F0000A3444F80A3CDBF8043044F8063CBBF8E4 +:10250000083024F8023CDDE7082249462846FEF759 +:1025100023FC98B9A21C0E4B197802320909C95D37 +:1025200002F8041C13F8011B01F00F015345C95DAB +:1025300002F8031CF0D118340835C3E7013504F85C +:10254000016BBFE7283F0008503E00083B3F0008F2 +:1025500020F4F01F2CF4F01F303F0008BFF34F8F22 +:10256000024AD368DB03FCD4704700BF003C024042 +:1025700008B5074B1B7853B9FFF7F0FF054B1A69F5 +:10258000002A04DA044A5A6002F188325A6008BD0F +:10259000CE380220003C02402301674508B5054BB8 +:1025A0001B7833B9FFF7DAFF034A136943F000439E +:1025B000136108BDCE380220003C02400B28F0B564 +:1025C00016D80C4C0C4923787BB90E460B4D0C23C6 +:1025D0004FF00062013B55F8047B46F8042B13F0E2 +:1025E000FF033A44F6D10123237051F82000F0BDD7 +:1025F0000020FCE700390220D03802204C3F0008C0 +:10260000014B53F8200070474C3F00080C207047E6 +:102610000B2810B5044601D9002010BDFFF7CEFFEE +:10262000064B53F824301844C21A0BB90120F4E7C2 +:1026300012680132F0D1043BF6E700BF4C3F0008BE +:102640000B2810B5044621D8FFF788FFFFF790FF4D +:102650000F4AF323D360C300DBB243F4007343F0AB +:1026600002031361136943F480331361FFF776FFAC +:10267000FFF7A4FF074B53F8241000F0D9F82046C9 +:10268000FFF78CFFBDE81040FFF7C2BF002010BD70 +:10269000003C02404C3F0008F8B512F0010314461C +:1026A00042D18218B2F1026F57D82D4B1B6813F03C +:1026B000010352D0FFF75CFF2A4DF32340F20127BC +:1026C000EB60FFF74BFF032C15D824F00104401AF0 +:1026D00040F201176618234CB14200EB0105236953 +:1026E00024D123F0010301202361FFF757FFF8BD38 +:1026F000043C0430E7E78307E7D12B6923F44073F8 +:102700002B612B693B432B6151F8046B0660BFF3CF +:102710004F8FFFF723FF03689E42E9D02B6923F018 +:1027200001032B61FFF73AFF0020E0E723F4407339 +:10273000236123693B4323610B882B80BFF34F8FB9 +:10274000FFF70CFF2D88ADB231F8023BAB42C3D08E +:10275000236923F001032361E4E71846C7E700BFBC +:1027600000380240003C0240084908B50B7828B107 +:102770001BB9FFF7FDFE01230B7008BD002BFCD039 +:102780000870BDE80840FFF709BF00BFCE3802203F +:102790000244074BD2B210B5904200D110BD441C88 +:1027A00000B253F8200041F8040BE0B2F4E700BF98 +:1027B000502800400F4B30B51C6F240407D41C6F09 +:1027C00044F400741C671C6F44F400441C670A4CFA +:1027D00002442368D2B243F480732360074B9042D3 +:1027E00000D130BD441C51F8045B00B243F82050C6 +:1027F000E0B2F4E70038024000700040502800408A +:1028000007B5012201A90020FFF7C2FF019803B01C +:102810005DF804FB13B50446FFF7F2FFA04205D0B4 +:10282000012201A900200194FFF7C4FF02B010BDEE +:102830000144BFF34F8F064B884204D3BFF34F8F41 +:10284000BFF36F8F7047C3F85C022030F4E700BF1E +:1028500000ED00E0034B1A681AB9034AD2F8742855 +:102860001A607047043902200030024008B5FFF7B3 +:10287000F1FF024B1868C0F3407008BD0439022014 +:1028800070B5BFF34F8FBFF36F8F1A4A0021C2F8A4 +:102890005012BFF34F8FBFF36F8F536943F4003370 +:1028A0005361BFF34F8FBFF36F8FC2F88410BFF334 +:1028B0004F8FD2F8803043F6E074C3F3C900C3F3FE +:1028C0004E335B0103EA0406014646EA817501398D +:1028D000C2F86052F9D2203B13F1200FF2D1BFF3BE +:1028E0004F8F536943F480335361BFF34F8FBFF36E +:1028F0006F8F70BD00ED00E0FEE70000214B224825 +:10290000224A70B5904237D3214BC11EDA1C121AED +:1029100022F003028B4238BF00220021FEF738FA72 +:102920001C4A0023C2F88430BFF34F8FD2F88030A6 +:1029300043F6E074C3F3C900C3F34E335B0103EA0B +:102940000406014646EA81750139C2F86C52F9D293 +:10295000203B13F1200FF2D1BFF34F8FBFF36F8FE6 +:10296000BFF34F8FBFF36F8F0023C2F85032BFF316 +:102970004F8FBFF36F8F70BD53F8041B40F8041BDB +:10298000C0E700BF5C410008183A0220183A022054 +:10299000183A022000ED00E070B5D0E91B43002298 +:1029A0004FF0FF359E6804EB42135101D3F8000944 +:1029B000002805DAD3F8000940F08040C3F8000988 +:1029C000D3F8000B002805DAD3F8000B40F0804064 +:1029D000C3F8000B013263189642C3F80859C3F8D4 +:1029E000085BE0D24FF00113C4F81C3870BD000042 +:1029F000890141F02001016103699B06FCD412208A +:102A0000FFF7AABA10B5054C2046FEF771FF4FF04C +:102A1000A043E366024B236710BD00BF08390220C4 +:102A2000A03F000870B503780546012B50D12A4B12 +:102A3000C46E98421BD1294B0E2143205A6B42F0A1 +:102A400080025A635A6D42F080025A655A6D5A6983 +:102A500042F080025A615A6922F080025A615B6931 +:102A600000F034FC1E4BE3601E4BC4F8003800231A +:102A7000EE6EC4F8003EC02323604FF40413A3633A +:102A80003369002BFCDA01230C203361FFF764FA71 +:102A90003369DB07FCD41220FFF75EFA3369002BA1 +:102AA000FCDA00262846A660FFF776FF6B68C4F8BC +:102AB0001068DB68C4F81468C4F81C684BB90A4B8A +:102AC000A3614FF0FF336361A36843F00103A36088 +:102AD00070BD064BF4E700BF083902200038024001 +:102AE0004014004003002002003C30C0083C30C0CD +:102AF000F8B5C46E054600214FF000662046FFF78A +:102B000077FF296F00234FF001128F684FF0FF30DD +:102B1000C4F83438C4F81C2804EB431201339F4234 +:102B2000C2F80069C2F8006BC2F80809C2F8080BC5 +:102B3000F2D20B68EA6E6B67636210231361166949 +:102B400016F01006FBD11220FFF706FAD4F8003871 +:102B500023F4FE63C4F80038A36943F4402343F030 +:102B60001003A3610923C4F81038C4F814380A4BC1 +:102B7000EB604FF0C043C4F8103B084BC4F8003B77 +:102B8000C4F81069C4F800396B6F03F1100243F404 +:102B900080136A67A362F8BD7C3F00084080001084 +:102BA000C26E90F86610D2F8003823F4FE6343EA50 +:102BB0000113C2F8003870472DE9F84300EB810398 +:102BC000C56E0C468046DA680FFA81F9480116682E +:102BD00006F00306731E022B05EB41134FF00001B4 +:102BE00094BFB604384EC3F8101B4FF0010104F136 +:102BF000100398BF06F1805601FA03F3916998BF5C +:102C000006F5004600293AD0578A04F158013743A7 +:102C100049016F50D5F81C180B430021C5F81C382A +:102C20002B180127C3F81019A7405369611E9BB3E5 +:102C3000138A928B9B08012A88BF5343D8F87420CB +:102C4000981842EA034301F140022146C8F8740093 +:102C5000284605EB82025360FFF7CAFE08EB8900A5 +:102C6000C3681B8A43EA845348341E4364012E51CF +:102C7000D5F81C381F43C5F81C78BDE8F88305EB70 +:102C80004917D7F8001B21F40041C7F8001BD5F8FD +:102C90001C1821EA0303C0E704F13F030B4A28464E +:102CA000214605EB83035A60FFF7A2FE05EB4910AE +:102CB000D0F8003923F40043C0F80039D5F81C38A7 +:102CC00023EA0707D7E700BF0080001000040002D6 +:102CD000026F12684267FFF75FBE00005831C36E93 +:102CE00049015B5813F4004004D013F4001F0CBFDB +:102CF00002200120704700004831C36E49015B5833 +:102D000013F4004004D013F4001F0CBF0220012074 +:102D10007047000000EB8101CB68196A0B681360F3 +:102D20004B6853607047000000EB810330B5DD68ED +:102D3000AA691368D36019B9402B84BF402313607C +:102D40006B8A1468C26E1C4402EB4110013C09B24C +:102D5000B4FBF3F46343033323F0030343EAC443B4 +:102D600043F0C043C0F8103B2B6803F00303012B72 +:102D70000ED1D2F8083802EB411013F4807FD0F85E +:102D8000003B14BF43F0805343F00053C0F8003BB6 +:102D900002EB4112D2F8003B43F00443C2F8003B7F +:102DA00030BD00002DE9F041244D0446EE6E06EBE7 +:102DB0004013D3F8087B3807C3F8087B0AD5D6F848 +:102DC0001438190706D505EB840321462846DB682D +:102DD0005B689847FA071FD5D6F81438DB071BD570 +:102DE00005EB8403D968CCB98B69488A5A68B2FB71 +:102DF000F0F600FB16228AB91868DA6890420DD204 +:102E0000121AC3E90024302383F311880B482146AA +:102E1000FFF78AFF84F31188BDE8F081012303FAEC +:102E200004F26B8923EA02036B81CB68002BF3D099 +:102E300021460248BDE8F041184700BF083902208A +:102E400000EB81034A0170B5DD68C36E6C692668CA +:102E5000E66056BB1A444FF40020C2F810092A68F5 +:102E600002F00302012A0AB20ED1D3F8080803EBDC +:102E7000421410F4807FD4F8000914BF40F0805051 +:102E800040F00050C4F8000903EB4212D2F80009E8 +:102E900040F00440C2F800090122D3F8340802FAD5 +:102EA00001F10143C3F8341870BD19B9402E84BF35 +:102EB0004020206020681A442E8A8419013CB4FB0B +:102EC000F6F440EAC44040F00050C6E72DE9F8436C +:102ED0003B4D04464701EE6E06EB4013D3F80889DC +:102EE00018F0010FC3F808891AD0D6F81038DB079C +:102EF00016D505EB8003D9684B691868DA689042EB +:102F000030D2121A4FF000091A60C3F8049030232F +:102F100083F3118821462846FFF792FF89F3118831 +:102F200018F0800F1CD0D6F834380126A640334262 +:102F300016D005EB84030134ED6ED3F80CC0E4B277 +:102F40002F44DCF8142005EB0434D2F800E051687B +:102F5000714515D3D5F8343823EA0606C5F8346828 +:102F6000BDE8F883012303FA04F22B8923EA020364 +:102F70002B818B68002BD3D0214628469847CFE77A +:102F8000AEEB0103BCF81000834228BF0346D7F81C +:102F9000180980B2B3EB800FE2D89068A0F1040961 +:102FA00059F8048FC4F80080A0EB09089844B8F1E0 +:102FB000040FF5D818440B4490605360C7E700BF76 +:102FC000083902202DE9F74FA44CE56E6E69AB6914 +:102FD0001E4016F480586E6107D02046FEF7F6FCBE +:102FE00003B0BDE8F04F00F069BC002E12DAD5F84E +:102FF000003E9B0705D0D5F8003E23F00303C5F83B +:10300000003ED5F80438954823F00103C5F804388C +:10301000FEF708FD370505D59048FFF7BDFC8F4842 +:10302000FEF7EEFCB0040CD5D5F8083813F0060F07 +:10303000EB6823F470530CBF43F4105343F4A053D4 +:10304000EB6031071BD56368DB681BB9AB6923F004 +:103050000803AB612378052B0CD1D5F8003E9A0705 +:1030600005D0D5F8003E23F00303C5F8003E7B48A9 +:10307000FEF7D8FC6368DB680BB178489847F30229 +:1030800000F18980B70227D5D4F86C9000274FF063 +:10309000010ADFF8C8B109EB4712D2F8003B03F48C +:1030A0004023B3F5802F11D1D2F8003B002B0DDA6D +:1030B00062890AFA07F322EA0303638104EB8703B8 +:1030C000DB68DB6813B13946584698470137236FF0 +:1030D000FFB29B689F42DED9F00617D5E76E3A6AC9 +:1030E000C2F30A1002F00F0302F4F012B2F5802FBF +:1030F00000F09880B2F5402F08D104EB8303002242 +:1031000007F58057DB681B6A90427ED13303D5F800 +:1031100018481DD5E70302D50020FFF743FEA5039D +:1031200002D50120FFF73EFE600302D50220FFF723 +:1031300039FE210302D50320FFF734FEE20202D557 +:103140000420FFF72FFEA30202D50520FFF72AFE79 +:1031500077037FF545AFE60702D50020FFF7B6FEFF +:10316000A50702D50120FFF7B1FE600702D50220B6 +:10317000FFF7ACFE210702D50320FFF7A7FEE2060A +:1031800002D50420FFF7A2FEA3067FF529AF052094 +:10319000FFF79CFE24E7E36E00274FF00109DFF8FC +:1031A000BCA00193236F5FFA87FB9B689B453FF6AA +:1031B00069AF019B03EB4B13D3F8001901F44021D5 +:1031C000B1F5802F1FD1D3F8001900291BDAD3F8ED +:1031D000001941F09041C3F80019D3F800190029F3 +:1031E000FBDB5946E06EFFF703FC218909FA0BF37C +:1031F00021EA0303238104EB8B03DB689B6813B193 +:103200005946504698470137CCE7910701D1D7F886 +:103210000080072A02F101029CBF03F8018B4FEAEC +:10322000182871E7023307F5805704EB83025268D0 +:10323000D2F818C0DCF80820DCE9001CA1EB0C0C6B +:10324000002188420CD104EB830463689B699A686F +:1032500002449A605A6802445A6057E708390220CB +:1032600011F0030F01D1D7F800808C4501F1010165 +:1032700084BF02F8018B4FEA1828E2E7C36E03EB24 +:103280004111D1F8003B43F40013C1F8003B7047F3 +:10329000C36E03EB4111D1F8003943F40013C1F8B8 +:1032A00000397047C36E03EB4111D1F8003B23F4A2 +:1032B0000013C1F8003B7047C36E03EB4111D1F816 +:1032C000003923F40013C1F800397047090100F1F7 +:1032D0006043012203F56143C9B283F8001300F093 +:1032E0001F039A4043099B0003F1604303F56143C8 +:1032F000C3F880211A60704730B50433039C017213 +:10330000002104FB0325C160C0E90653049B03634D +:10331000059BC0E90000C0E90422C0E90842C0E9F9 +:103320000A11436330BD00000022416AC260C0E957 +:103330000411C0E90A226FF00101FEF77DBE000012 +:10334000D0E90432934201D1C2680AB9181D70470E +:1033500000207047036919600021C2680132C26011 +:10336000C269134482699342036124BF436A0361C3 +:10337000FEF756BE38B504460D46E3683BB16269B8 +:103380000020131D1268A3621344E36207E0237A4E +:1033900033B929462046FEF733FE0028EDDA38BD62 +:1033A0006FF00100FBE70000C368C269013BC36026 +:1033B0004369134482699342436124BF436A436172 +:1033C00000238362036B03B11847704770B5302345 +:1033D000044683F31188866A3EB9FFF7CBFF0546A2 +:1033E00018B186F31188284670BDA36AE26A13F803 +:1033F000015B9342A36202D32046FFF7D5FF00236F +:1034000083F31188EFE700002DE9F84F04460E46DC +:10341000174698464FF0300989F311880025AA46CF +:10342000D4F828B0BBF1000F09D141462046FFF780 +:10343000A1FF20B18BF311882846BDE8F88FD4E9AD +:103440000A12A7EB050B521A934528BF9346BBF10E +:10345000400F1BD9334601F1400251F8040B914251 +:1034600043F8040BF9D1A36A403640354033A362D8 +:10347000D4E90A239A4202D32046FFF795FF8AF344 +:103480001188BD42D8D289F31188C9E730465A461F +:10349000FDF758FCA36A5E445D445B44A362E7E722 +:1034A00010B5029C0433017203FB0421C460C0E91F +:1034B00006130023C0E90A33039B0363049BC0E99E +:1034C0000000C0E90422C0E90842436310BD0000C7 +:1034D000026A6FF00101C260426AC0E90422002260 +:1034E000C0E90A22FEF7A8BDD0E904239A4201D11F +:1034F000C26822B9184650F8043B0B60704700239D +:103500001846FAE7C3680021C2690133C360436902 +:10351000134482699342436124BF436A4361FEF7C7 +:103520007FBD000038B504460D46E3683BB1236912 +:1035300000201A1DA262E2691344E36207E0237AC5 +:1035400033B929462046FEF75BFD0028EDDA38BD89 +:103550006FF00100FBE7000003691960C268013ADF +:10356000C260C269134482699342036124BF436A03 +:10357000036100238362036B03B1184770470000A7 +:1035800070B530230D460446114683F31188866AD0 +:103590002EB9FFF7C7FF10B186F3118870BDA36A7B +:1035A0001D70A36AE26A01339342A36204D3E16906 +:1035B00020460439FFF7D0FF002080F31188EDE7A3 +:1035C0002DE9F84F04460D46904699464FF0300AD3 +:1035D0008AF311880026B346A76A4FB949462046A8 +:1035E000FFF7A0FF20B187F311883046BDE8F88FC0 +:1035F000D4E90A073A1AA8EB0607974228BF1746EC +:10360000402F1BD905F1400355F8042B9D4240F88B +:10361000042BF9D1A36A40364033A362D4E90A23CC +:103620009A4204D3E16920460439FFF795FF8BF3F2 +:1036300011884645D9D28AF31188CDE729463A4602 +:10364000FDF780FBA36A3D443E443B44A362E5E7AB +:10365000D0E904239A4217D1C3689BB1836A8BB126 +:10366000043B9B1A0ED01360C368013BC360C3695F +:103670001A4483699A42026124BF436A03610023AA +:1036800083620123184670470023FBE700F040B92E +:103690004FF08043586A70474FF0804300225863D0 +:1036A0001A610222DA6070474FF080430022DA602C +:1036B000704700004FF0804358637047FEE70000FA +:1036C00070B51B4B0025044686B058600E468562D7 +:1036D000016300F0CBF804F11003A560E562C4E9D2 +:1036E00004334FF0FF33C4E90044C4E90635FFF763 +:1036F000CFFF2B46024604F134012046C4E90823DB +:1037000080230C4A2565FEF731FC01230A4AE0605C +:1037100000920375684672680192B268CDE902238F +:10372000064BCDE90435FEF749FC06B070BD00BF7D +:10373000902D0220AC3F0008B13F0008BD360008C4 +:10374000024AD36A1843D062704700BF282B022078 +:103750004B6843608B688360CB68C3600B694361CF +:103760004B6903628B6943620B680360704700001A +:1037700008B52C4B40F2FF712B481A690A431A61B5 +:103780001A6922F4FF6222F007021A611A691A6BA1 +:103790000A431A631A6D0A431A65244A1B6D1146BF +:1037A000FFF7D6FF00F5806002F11C01FFF7D0FFA4 +:1037B00000F5806002F13801FFF7CAFF00F5806074 +:1037C00002F15401FFF7C4FF00F5806002F17001BF +:1037D000FFF7BEFF00F5806002F18C01FFF7B8FF34 +:1037E00000F5806002F1A801FFF7B2FF00F58060EC +:1037F00002F1C401FFF7ACFF00F5806002F1E001C7 +:10380000FFF7A6FF00F5806002F1FC01FFF7A0FFC3 +:1038100002F58C7100F58060FFF79AFFBDE8084063 +:1038200000F0ECB80038024000000240B83F000849 +:1038300008B500F081FAFEF777FBFFF70BF8BDE85B +:103840000840FEF7E5BD000070470000EFF3098374 +:10385000054968334A6B22F001024A6383F3098801 +:10386000002383F31188704700EF00E0302080F3DD +:10387000118862B60D4B0E4AD96821F4E061090443 +:10388000090C0A430B49DA60D3F8FC2042F080723D +:10389000C3F8FC20084AC2F8B01F116841F00101CA +:1038A00011602022DA7783F82200704700ED00E0F3 +:1038B0000003FA0555CEACC5001000E0302310B56A +:1038C00083F311880E4B5B6813F4006314D0F1EEA0 +:1038D000103AEFF309844FF08073683CE361094BC1 +:1038E000DB6B236684F30988FEF7FEFA10B1064B02 +:1038F000A36110BD054BFBE783F31188F9E700BF17 +:1039000000ED00E000EF00E04F0300085203000864 +:103910000F4B1A6C42F001021A641A6E42F0010257 +:103920001A660C4A1B6E936843F0010393604FF0D4 +:1039300080436B229A624FF0FF32DA6200229A6172 +:103940005A63DA605A6001225A611A60704700BFF8 +:1039500000380240002004E04FF0804208B51169B1 +:10396000D3680B40D9B29B076FEA0101116107D5FB +:10397000302383F31188FEF7EDFA002383F31188D7 +:1039800008BD00001B4B4FF0FF3000211A696FEAA1 +:1039900042526FEA52521A611A69C2F30A021A615C +:1039A0001A695A6958615A6959615A691A6A62F002 +:1039B00080521A621A6A02F080521A621A6A5A6AAD +:1039C00058625A6A59625A6A0B4A106840F4807009 +:1039D0001060186F00F44070B0F5007F03D04FF412 +:1039E000803018671967536823F40073536000F040 +:1039F00073B900BF0038024000700040364B4FF4EE +:103A00004041364A1A64364A11601A6842F001028F +:103A10001A601A689207FCD59A6822F003029A602D +:103A20002D4B9A6812F00C02FBD1196801F0F901D4 +:103A300019609A601A6842F480321A601A6890031A +:103A4000FCD55A6F42F001025A67234B5A6F910717 +:103A5000FCD5244A5A601A6842F080721A60204BE2 +:103A60005A685204FCD51A6842F480321A605A68C7 +:103A7000D003FCD51A6842F400321A60184A536821 +:103A80009903FCD5144B1A689201FCD5164A9A602A +:103A900040F20112C3F88C200022C3F8902040F2BB +:103AA0000733124A1360136803F00F03072BFAD190 +:103AB000094B9A6842F002029A609A6802F00C027E +:103AC000082AFAD15A6C42F480425A645A6E42F47F +:103AD00080425A665B6E7047003802400004001056 +:103AE00000700040186C400900948838003C024087 +:103AF000074A08B5536903F00103536123B1054A2E +:103B000013680BB150689847BDE80840FFF7D6BE70 +:103B1000003C014098390220074A08B5536903F078 +:103B20000203536123B1054A93680BB1D0689847EB +:103B3000BDE80840FFF7C2BE003C014098390220B2 +:103B4000074A08B5536903F00403536123B1054ADA +:103B500013690BB150699847BDE80840FFF7AEBE46 +:103B6000003C014098390220074A08B5536903F028 +:103B70000803536123B1054A93690BB1D069984793 +:103B8000BDE80840FFF79ABE003C0140983902208A +:103B9000074A08B5536903F01003536123B1054A7E +:103BA000136A0BB1506A9847BDE80840FFF786BE1C +:103BB000003C014098390220164B10B55C6904F4B2 +:103BC00078725A61A30604D5134A936A0BB1D06A7E +:103BD0009847600604D5104A136B0BB1506B984799 +:103BE000210604D50C4A936B0BB1D06B9847E205C4 +:103BF00004D5094A136C0BB1506C9847A30504D542 +:103C0000054A936C0BB1D06C9847BDE81040FFF7A4 +:103C100055BE00BF003C014098390220194B10B539 +:103C20005C6904F47C425A61620504D5164A136D3E +:103C30000BB1506D9847230504D5134A936D0BB112 +:103C4000D06D9847E00404D50F4A136E0BB1506E47 +:103C50009847A10404D50C4A936E0BB1D06E9847D7 +:103C6000620404D5084A136F0BB1506F98472304C0 +:103C700004D5054A936F0BB1D06F9847BDE810404B +:103C8000FFF71CBE003C01409839022008B50348EC +:103C9000FDF742FABDE80840FFF710BEE02302201E +:103CA00008B50348FDF738FABDE80840FFF706BE3F +:103CB0004C24022008B50348FDF72EFABDE8084061 +:103CC000FFF7FCBDB824022008B5FFF745FEBDE8AC +:103CD0000840FFF7F3BD0000062108B50846FFF7CE +:103CE000F5FA06210720FFF7F1FA06210820FFF771 +:103CF000EDFA06210920FFF7E9FA06210A20FFF76D +:103D0000E5FA06211720FFF7E1FA06212820FFF740 +:103D1000DDFA07211C20FFF7D9FA0C212620FFF736 +:103D2000D5FA0C212720FFF7D1FA0C215220BDE84B +:103D30000840FFF7CBBA000008B5FFF723FE00F0FC +:103D40000DF8FDF701FCFDF7D1FDFDF7A9FCFFF72C +:103D50007BFDBDE80840FFF799BC00000023054A41 +:103D600019460133102BC2E9001102F10802F8D103 +:103D7000704700BF98390220034611F8012B03F861 +:103D8000012B002AF9D1704753544D3332463F3F3F +:103D90003F3F3F3F0053544D333246375B347C3511 +:103DA0005D780053544D333246375B367C375D784F +:103DB000000000000096000000000000000000006D +:103DC00000000000000000000000000000000000F3 +:103DD00009150008F5140008311500081D15000824 +:103DE000291500081515000801150008ED14000834 +:103DF0003D150008000000001D1600080916000807 +:103E000045160008311600083D160008291600085E +:103E100015160008011600085116000800000000E1 +:103E2000010000000000000063300000283E000890 +:103E3000802B0220902D02204865782F50726F66EB +:103E400069434E430025424F415244252D424C00C8 +:103E50002553455249414C25000000000200000056 +:103E60000000000039180008A518000840004000B4 +:103E70004036022050360220020000000000000000 +:103E80000300000000000000E91800080000000026 +:103E90001000000060360220000000000100000059 +:103EA000000000000839022001010200AD230008D3 +:103EB000BD220008592300083D23000843000000EC +:103EC000C43E000809024300020100C03209040098 +:103ED0000001020201000524001001052401000177 +:103EE000042402020524060001070582030800FFDE +:103EF00009040100020A0000000705010240000059 +:103F0000070581024000000012000000103F000879 +:103F10001201100102000040AE2D02100002010249 +:103F2000030100000403090425424F4152442500C7 +:103F30004375626559656C6C6F770030313233348C +:103F40003536373839414243444546000080000049 +:103F500000800000008000000080000000000200DF +:103F60000000040000000400000004000000040041 +:103F70000000040000000400000004000000000035 +:103F80003D1A0008F51C0008A11D00084000400073 +:103F9000803902208039022001000000903902207F +:103FA0008000000040010000050000006D61696EA6 +:103FB0000069646C650000000000802A00000000B9 +:103FC000AAAAAAAA00000024FFFF00000000000027 +:103FD00000A00A000001000000000000AAAAAAAA8E +:103FE00000000000FFFF00000000000000000000D3 +:103FF0001400005400000000AAAAAAAA1400005449 +:10400000FFFF0000000000000000000080699A012E +:1040100000000000AAAA8AAA40565502FFFF00002D +:10402000007070077770000000810200000000003F +:10403000AAAAAAAA00410100FFFF00000000008018 +:10404000080000000000000000000000AAAAAAAAC0 +:1040500000000000FFFF0000000000000000000062 +:104060000000000000000000AAAAAAAA00000000A8 +:10407000FFFF000000000000000000000000000042 +:1040800000000000AAAAAAAA00000000FFFF00008A +:104090000000000000000000000000000000000020 +:1040A000AAAAAAAA00000000FFFF0000000000006A +:1040B000000000000000000000000000AAAAAAAA58 +:1040C00000000000FFFF00000000000000000000F2 +:1040D0000000000000000000AAAA0000000000008C +:1040E000FF000000000000000000000000000000D1 +:1040F000780000000000000000801E0000000000AA +:10410000FF000000982D0220E02302204C24022012 +:10411000B824022000000000883D00084904000087 +:10412000953D000851040000A33D000800960000E2 +:1041300000000800960000000008000004000000D5 +:10414000243F000800000000000000000000000004 +:0C41500000000000000000000000000063 :00000001FF diff --git a/Tools/bootloaders/F4BY_F427_bl.bin b/Tools/bootloaders/F4BY_F427_bl.bin new file mode 100755 index 00000000000000..92ed4fbdb6564e Binary files /dev/null and b/Tools/bootloaders/F4BY_F427_bl.bin differ diff --git a/Tools/bootloaders/FlywooF405HD-AIOv2_bl.bin b/Tools/bootloaders/FlywooF405HD-AIOv2_bl.bin new file mode 100644 index 00000000000000..94048db4bb4e14 Binary files /dev/null and b/Tools/bootloaders/FlywooF405HD-AIOv2_bl.bin differ diff --git a/Tools/bootloaders/FlywooF405HD-AIOv2_bl.hex b/Tools/bootloaders/FlywooF405HD-AIOv2_bl.hex new file mode 100644 index 00000000000000..9a9abe8114d317 --- /dev/null +++ b/Tools/bootloaders/FlywooF405HD-AIOv2_bl.hex @@ -0,0 +1,894 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E30100086D2F000868 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008153200083D32000802 +:10006000653200088D320008B5320008E30100084F +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008DD32000885 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000B1330008E3010008E3010008E301000890 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00041330008E3010008E3010008E3010008D0 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E3010008212700089B +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F030FF41 +:1002500002F02AFE4FF055301F491B4A91423CBF25 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F00EFF02F058FEF4 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F0F6BE000600200022002072 +:1002D0000000000808ED00E00000002000060020FB +:1002E0007837000800220020402200204022002011 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F072FAFEE701F08C +:1003300001FA00DFFEE7000038B500F0BBFB01F07A +:1003400087FE054601F0AAFE0446C8B90E4B9D4241 +:1003500018D001339D4218BF044641F2883504BFCE +:1003600001240025002001F07DFE0CB100F074F89E +:1003700000F000FD284600F0BFF800F06DF8F9E746 +:100380000025EFE70546EDE7010007B008B500F0EE +:1003900063FBA0F120035842584108BD07B541F264 +:1003A0001203022101A8ADF8043000F073FB03B082 +:1003B0005DF804FB38B5302383F3118817480368D0 +:1003C0000BB101F0F1FA164A144800234FF47A7188 +:1003D00001F0E0FA002383F31188124C236813B173 +:1003E0002368013B2360636813B16368013B63606A +:1003F0000D4D2B7833B963687BB9022000F024FCE3 +:10040000322363602B78032B07D163682BB902205A +:1004100000F01AFC4FF47A73636038BD402200206C +:10042000B50300086023002058220020084B1870F4 +:1004300003280CD8DFE800F008050208022000F0CD +:10044000F9BB022000F0ECBB024B00225A6070475F +:100450005822002060230020234B244A10B51C465C +:10046000196801313FD004339342F9D16268A24246 +:1004700039D31F4B9B6803F1006303F540439A4255 +:1004800031D2002000F030FB0220FFF7CFFF194BE4 +:100490001A6C00221A64196E1A66196E596C5A6425 +:1004A000596E5A665A6E5A6942F080025A615A6908 +:1004B00022F080025A615A691A6942F000521A61A8 +:1004C0001A6922F000521A611B6972B64FF0E023DC +:1004D0003021C3F8084DD4E9003281F311889D46DC +:1004E00083F30888104710BD00C0000820C0000832 +:1004F00000220020003802402DE9F04F93B0AA4BB3 +:1005000000902022FF210AA89D6800F0DDFBA74A89 +:100510001378A3B9A648012103601170302383F337 +:10052000118803680BB101F03FFAA24AA0480023EA +:100530004FF47A7101F02EFA002383F31188009BA7 +:1005400013B19D4B009A1A609C4A009C1378032BB0 +:100550001EBF00231370984A4FF0000A18BF536063 +:10056000D3465646D146012000F064FB24B1924B9D +:100570001B68002B00F01182002000F06DFA039040 +:10058000039B002BF2DB012000F04AFB039B213B85 +:10059000162BE8D801A252F823F000BFF905000895 +:1005A00021060008B5060008670500086705000871 +:1005B000670500083F0700080F0900082908000820 +:1005C0008B080008B3080008D90800086705000870 +:1005D000EB080008670500085D0900089906000897 +:1005E00067050008A109000805060008990600082B +:1005F000670500088B0800080220FFF7C7FE0028E7 +:1006000040F0F581009B0221BAF1000F08BF1C46A3 +:1006100005A841F21233ADF8143000F03BFAA2E71E +:100620004FF47A7000F018FA071EEBDB0220FFF798 +:10063000ADFE0028E6D0013F052F00F2DA81DFE8A9 +:1006400007F0030A0D10133605230593042105A8AE +:1006500000F020FA17E054480421F9E75848042133 +:10066000F6E758480421F3E74FF01C08404600F035 +:100670003DFA08F104080590042105A800F00AFAE3 +:10068000B8F12C0FF2D1012000FA07F747EA0B0B63 +:100690005FFA8BFB4FF0000900F062FB26B10BF014 +:1006A0000B030B2B08BF0024FFF778FE5BE74648DF +:1006B0000421CDE7002EA5D00BF00B030B2BA1D10D +:1006C0000220FFF763FE074600289BD0012000F0C0 +:1006D0000BFA0220FFF7AAFE00261FFA86F8404612 +:1006E00000F012FA044690B10021404600F01CFAD6 +:1006F00001360028F1D1BA46044641F21213022114 +:1007000005A8ADF814303E4600F0C4F92BE70120EF +:10071000FFF78CFE2546244B9B68AB4207D9284641 +:1007200000F0E4F9013040F067810435F3E7234B32 +:1007300000251D70204BBA465D603E46ACE7002E9A +:100740003FF460AF0BF00B030B2B7FF45BAF022089 +:10075000FFF76CFE322000F07FF9B0F10008FFF6E1 +:1007600051AF18F003077FF44DAF0F4A926808EBC2 +:10077000050393423FF646AFB8F5807F3FF742AF9F +:10078000124B0193B84523DD4FF47A7000F064F901 +:100790000390039A002AFFF635AF019B039A03F8F2 +:1007A000012B0137EDE700BF002200205C23002071 +:1007B00040220020B50300086023002058220020BA +:1007C00004220020082200200C2200205C220020AD +:1007D000C820FFF7DBFD074600283FF413AF1F2DAD +:1007E00011D8C5F1200242450AAB25F0030028BF0D +:1007F000424683490192184400F040FA019A804829 +:10080000FF2100F061FA4FEAA8037D490193C8F384 +:100810008702284600F060FA064600283FF46DAFD4 +:10082000019B05EB830537E70220FFF7AFFD0028AA +:100830003FF4E8AE00F0A4F900283FF4E3AE00274F +:10084000B846704B9B68BB4218D91F2F11D80A9B22 +:1008500001330ED027F0030312AA134453F8203CAF +:1008600005934046042205A900F0AEFA04378046FD +:10087000E7E7384600F03AF90590F2E7CDF8148042 +:10088000042105A800F006F906E70023642104A866 +:10089000049300F0F5F800287FF4B4AE0220FFF7CF +:1008A00075FD00283FF4AEAE049800F051F90590B4 +:1008B000E6E70023642104A8049300F0E1F800288F +:1008C0007FF4A0AE0220FFF761FD00283FF49AAE4E +:1008D000049800F04DF9EAE70220FFF757FD0028E1 +:1008E0003FF490AE00F05CF9E1E70220FFF74EFD27 +:1008F00000283FF487AE05A9142000F057F9042121 +:100900000746049004A800F0C5F83946B9E732203C +:1009100000F0A2F8071EFFF675AEBB077FF472AEBB +:10092000384A926807EB090393423FF66BAE022008 +:10093000FFF72CFD00283FF465AE27F003074F4476 +:10094000B9453FF4A9AE484600F0D0F8042105901F +:1009500005A800F09FF809F10409F1E74FF47A7057 +:10096000FFF714FD00283FF44DAE00F009F9002810 +:1009700044D00A9B01330BD008220AA9002000F0C2 +:10098000ABF900283AD02022FF210AA800F09CF9F8 +:10099000FFF704FD1C4800F041FF13B0BDE8F08FE5 +:1009A000002E3FF42FAE0BF00B030B2B7FF42AAE7F +:1009B0000023642105A8059300F062F8074600288B +:1009C0007FF420AE0220FFF7E1FC804600283FF4D0 +:1009D00019AEFFF7E3FC41F2883000F01FFF0598E5 +:1009E00000F0F0F9464600F0BBF93C46BBE5064690 +:1009F00052E64FF0000905E6BA467EE637467CE649 +:100A00005C22002000220020A086010070B50F4B60 +:100A10001B780133DBB2012B0C4611D80C4D296831 +:100A20004FF47A730E6AA2FB03320146224628462F +:100A3000B047844204D1074B00221A70012070BDD8 +:100A40004FF4FA7000F0EAFE0020F8E710220020D0 +:100A5000082600209423002007B500230246012128 +:100A60000DF107008DF80730FFF7D0FF20B19DF89A +:100A7000070003B05DF804FB4FF0FF30F9E700001A +:100A80000A4608B50421FFF7C1FF80F00100C0B29B +:100A9000404208BD30B4054C2368DD69044B0A466A +:100AA000AC460146204630BC604700BF0826002007 +:100AB000A086010070B501F0D1F9094E094D3080D2 +:100AC000002428683388834208D901F0C1F92B68D3 +:100AD00004440133B4F5404F2B60F2D370BD00BF26 +:100AE000962300206823002001F066BA00F1006020 +:100AF00000F540400068704700F10060920000F58A +:100B0000404001F0F1B90000054B1A68054B1B8805 +:100B10009B1A834202D9104401F09AB90020704711 +:100B2000682300209623002038B5084D044629B1DB +:100B300028682044BDE8384001F0AAB9286820445C +:100B400001F08EF90028F3D038BD00BF68230020E3 +:100B500010F003030AD1B0F5047F05D200F1005074 +:100B6000A0F51040D0F80038184670470023FBE786 +:100B700000F10050A0F51040D0F8100A70470000B6 +:100B8000064991F8243033B10023086A81F82430F3 +:100B90000822FFF7B1BF0120704700BF6C2300207F +:100BA000014B1868704700BF002004E070B5194B76 +:100BB0001D68194B0138C5F30B0408442D0C0422A1 +:100BC0001E88A6420BD15C680A46013C824213464D +:100BD0000FD214F9016F4EB102F8016BF6E7013A3A +:100BE00003F10803ECD181420B4602D22C2203F818 +:100BF000012B0A4A05241688AE4204D1984284BFCC +:100C0000967803F8016B013C02F10402F3D1581A03 +:100C100070BD00BF002004E0943400088034000858 +:100C2000022802BF024B4FF000729A61704700BF6A +:100C300000000240022802BF024B4FF400729A618A +:100C4000704700BF00000240022801BF024A5369FA +:100C500083F40073536170470000024070B504468E +:100C60004FF47A764CB1412C254628BF412506FB2E +:100C700005F000F0D3FD641BF4E770BD10B5002350 +:100C8000934203D0CC5CC4540133F9E710BD00009B +:100C900010B5013810F9013F3BB191F900409C4279 +:100CA00003D11AB10131013AF4E71AB191F90020E8 +:100CB000981A10BD1046FCE703460246D01A12F9F6 +:100CC000011B0029FAD1704702440346934202D027 +:100CD00003F8011BFAE770472DE9F8431F4D14464E +:100CE00095F824200746884652BBDFF870909CB3E5 +:100CF00095F824302BB92022FF2148462F62FFF7B8 +:100D0000E3FF95F82400C0F10802A24228BF224662 +:100D1000D6B24146920005EB8000FFF7AFFF95F891 +:100D20002430A41B1E44F6B2082E17449044E4B2AB +:100D300085F82460DBD1FFF723FF0028D7D108E036 +:100D40002B6A03EB82038342CFD0FFF719FF002801 +:100D5000CBD10020BDE8F8830120FBE76C23002005 +:100D6000024B1A78024B1A70704700BF9423002080 +:100D70001022002010B5104C104800F0B5F82146A4 +:100D80000E4800F0DDF82468626DD2F8043843F0B4 +:100D90000203C2F804384FF47A70FFF75FFF084986 +:100DA000204600F0D3F9626DD2F8043823F0020334 +:100DB000C2F8043810BD00BF6035000808260020C6 +:100DC000683500087047000030B5094D0A4491426B +:100DD0000DD011F8013B5840082340F30004013BBB +:100DE0002C4013F0FF0384EA5000F6D1EFE730BD4A +:100DF0002083B8ED026843681143016003B11847CE +:100E00007047000013B5446BD4F894341A68117815 +:100E1000042915D1217C022912D1197912890123C3 +:100E20008B4013420CD101A904F14C0001F0F8FEF3 +:100E3000D4F89444019B21790246206800F0D0F94F +:100E400002B010BD143001F07BBE00004FF0FF3344 +:100E5000143001F075BE00004C3001F04DBF0000B1 +:100E60004FF0FF334C3001F047BF0000143001F069 +:100E700049BE00004FF0FF31143001F043BE0000C6 +:100E80004C3001F019BF00004FF0FF324C3001F040 +:100E900013BF00000020704710B5D0F894341A68D2 +:100EA00011780429044617D1017C022914D15979FB +:100EB000528901238B4013420ED1143001F0DCFD26 +:100EC000024648B1D4F894444FF4807361792068A5 +:100ED000BDE8104000F072B910BD0000406BFFF794 +:100EE000DBBF0000704700007FB5124B036000239A +:100EF0004360C0E90233012502260F4B0574044606 +:100F00000290019300F18402294600964FF4807309 +:100F1000143001F08DFD094B0294CDE9006304F516 +:100F200023724FF48073294604F14C0001F054FE03 +:100F300004B070BDB4340008DD0E0008050E0008D2 +:100F40000B68302282F311880A7903EB82029061E8 +:100F50004A79093243F822008A7912B103EB8203FD +:100F600098610223C0F894140374002080F3118860 +:100F70007047000038B5037F044613B190F8543031 +:100F8000ABB9201D01250221FFF734FF04F1140045 +:100F900025776FF0010100F069FC84F8545004F1EA +:100FA0004C006FF00101BDE8384000F05FBC38BD77 +:100FB00010B5012104460430FFF71CFF00232377FE +:100FC00084F8543010BD000038B5044600251430B4 +:100FD00001F046FD04F14C00257701F015FE201DBF +:100FE00084F854500121FFF705FF2046BDE8384042 +:100FF000FFF752BF90F8443003F06003202B07D175 +:1010000090F84520212A4FF0000303D81F2A06D864 +:1010100000207047222AFBD1C0E90E3303E0034AC7 +:1010200082630722C26303640120704711220020FB +:1010300037B5D0F894341A681178042904461AD1C7 +:10104000017C022917D11979128901238B4013429F +:1010500011D100F14C05284601F096FE58B101A9C6 +:10106000284601F0DDFDD4F89444019B2179024625 +:10107000206800F0B5F803B030BD0000F0B500EB1B +:10108000810385B09E6904460D46FEB1302383F38B +:10109000118804EB8507301D0821FFF7ABFEFB68C4 +:1010A0005B691B6806F14C001BB1019001F0C6FDA5 +:1010B000019803A901F0B4FD024648B1039B2946FB +:1010C000204600F08DF8002383F3118805B0F0BDB1 +:1010D000FB685A691268002AF5D01B8A013B13404D +:1010E000F1D104F14402EAE7093138B550F8214062 +:1010F000DCB1302383F31188D4F894241368527937 +:1011000003EB8203DB689B695D6845B104216018CD +:10111000FFF770FE294604F1140001F0B7FC2046E9 +:10112000FFF7BAFE002383F3118838BD7047000033 +:1011300001F016B8012303700023C0E90133C36135 +:1011400083620362C36243620363704738B5044637 +:10115000302383F311880025C0E90355C0E9055504 +:10116000416001F00DF80223237085F311882846B1 +:1011700038BD000070B500EB810305465069DA60A8 +:101180000E46144618B110220021FFF79DFDA069FC +:1011900018B110220021FFF797FD31462846BDE81F +:1011A000704001F0B7B80000826802F0011282605E +:1011B0000022C0E90422826101F038B9F0B400EBEA +:1011C00081044789E4680125A4698D403D43458138 +:1011D00023600023A2606360F0BC01F053B90000FB +:1011E000F0B400EB81040789E468012564698D404F +:1011F0003D43058123600023A2606360F0BC01F0E1 +:10120000CDB9000070B50223002504460370C0E983 +:101210000255C0E90455C564856180F8345001F079 +:1012200015F863681B6823B129462046BDE8704065 +:10123000184770BD0378052B10B504460AD080F816 +:1012400050300523037043681B680BB10421984795 +:101250000023A36010BD00000178052906D190F895 +:101260005020436802701B6803B1184770470000A4 +:1012700070B590F83430044613B1002380F8343050 +:1012800004F14402204601F0F3F863689B68B3B9A7 +:1012900094F8443013F0600535D00021204601F069 +:1012A00093FB0021204601F085FB63681B6813B1A6 +:1012B000062120469847062384F8343070BD204626 +:1012C00098470028E4D0B4F84A30E26B9A4288BFCD +:1012D000E36394F94430E56B002B4FF0300380F268 +:1012E0000381002D00F0F280092284F8342083F37A +:1012F00011880021D4E90E232046FFF771FF002357 +:1013000083F31188DAE794F8452003F07F0343EA7A +:10131000022340F20232934200F0C58021D8B3F597 +:10132000807F48D00DD8012B3FD0022B00F0938056 +:10133000002BB2D104F14C02A2630222E2632364C7 +:10134000C1E7B3F5817F00F09B80B3F5407FA4D166 +:1013500094F84630012BA0D1B4F84C3043F002038E +:1013600032E0B3F5006F4DD017D8B3F5A06F31D090 +:10137000A3F5C063012B90D8636894F846205E689B +:1013800094F84710B4F848302046B047002884D07D +:101390004368A3630368E3631AE0B3F5106F36D0C4 +:1013A00040F6024293427FF478AF5C4BA363022382 +:1013B000E3630023C3E794F84630012B7FF46DAF5D +:1013C000B4F84C3023F00203C4E90E55A4F84C30B5 +:1013D000256478E7B4F84430B3F5A06F0ED194F8E3 +:1013E000463084F84E30204600F088FF63681B6862 +:1013F00013B1012120469847032323700023C4E939 +:101400000E339CE704F14F03A3630123C3E7237862 +:10141000042B10D1302383F311882046FFF7C4FE3C +:1014200085F311880321636884F84F5021701B688D +:101430000BB12046984794F84630002BDED084F854 +:101440004F300423237063681B68002BD6D0022121 +:1014500020469847D2E794F848301D0603F00F0164 +:1014600020460AD500F0F6FF012804D002287FF4B8 +:1014700014AF2B4B9AE72B4B98E700F0DDFFF3E717 +:1014800094F84630002B7FF408AF94F8483013F0FE +:101490000F01B3D01A06204602D501F0A9FAADE734 +:1014A00001F09CFAAAE794F84630002B7FF4F5AEE1 +:1014B00094F8483013F00F01A0D01B06204602D547 +:1014C00001F082FA9AE701F075FA97E7142284F89E +:1014D000342083F311882B462A4629462046FFF7FD +:1014E0006DFE85F31188E9E65DB1152284F834209C +:1014F00083F311880021D4E90E232046FFF75EFE16 +:10150000FDE60B2284F8342083F311882B462A460B +:1015100029462046FFF764FEE3E700BFE4340008F5 +:10152000DC340008E034000838B590F83430044664 +:10153000002B3ED0063BDAB20F2A34D80F2B32D81C +:10154000DFE803F0373131082232313131313131C6 +:1015500031313737C56BB0F84A309D4214D2C36879 +:101560001B8AB5FBF3F203FB12556DB9302383F3ED +:1015700011882B462A462946FFF732FE85F311884B +:101580000A2384F834300EE0142384F834303023F6 +:1015900083F3118800231A4619462046FFF70EFEF2 +:1015A000002383F3118838BD036C03B198470023EF +:1015B000E7E70021204601F007FA0021204601F06C +:1015C000F9F963681B6813B1062120469847062382 +:1015D000D7E7000010B590F83430142B044629D01A +:1015E00017D8062B05D001D81BB110BD093B022B23 +:1015F000FBD80021204601F0E7F90021204601F048 +:10160000D9F963681B6813B1062120469847062361 +:1016100019E0152BE9D10B2380F83430302383F304 +:10162000118800231A461946FFF7DAFD002383F3D9 +:101630001188DAE7C3689B695B68002BD5D1036C1E +:1016400003B19847002384F83430CEE700230375B4 +:10165000826803691B6899689142FBD25A680360EB +:101660004260106058607047002303758268036908 +:101670001B6899689142FBD85A6803604260106009 +:101680005860704708B50846302383F311880B7DF6 +:10169000032B05D0042B0DD02BB983F3118808BD83 +:1016A0008B6900221A604FF0FF338361FFF7CEFF92 +:1016B0000023F2E7D1E9003213605A60F3E700003B +:1016C000FFF7C4BF054BD9680875186802681A602F +:1016D000536001220275D860FEF714BE98230020E3 +:1016E00030B50C4BDD684B1C87B004460FD02B4641 +:1016F000094A684600F04EF92046FFF7E3FF009BD9 +:1017000013B1684600F050F9A86907B030BDFFF783 +:10171000D9FFF9E79823002085160008044B1A68C2 +:10172000DB6890689B68984294BF00200120704756 +:1017300098230020084B10B51C68D86822681A60EE +:10174000536001222275DC60FFF78EFF01462046C0 +:10175000BDE81040FEF7D6BD9823002038B5074CF1 +:1017600007490848012300252370656001F044FB08 +:101770000223237085F3118838BD00BF00260020A6 +:10178000EC3400089823002000F044B9034A516863 +:1017900053685B1A9842FBD8704700BF001000E006 +:1017A0008B60022308618B82084670478368A3F12F +:1017B000840243F8142C026943F8442C426943F82C +:1017C000402C094A43F8242CC26843F8182C022202 +:1017D00003F80C2C002203F80B2C044A43F8102CBD +:1017E000A3F12000704700BF1D03000898230020CC +:1017F00008B5FFF7DBFFBDE80840FFF761BF000059 +:10180000024BDB6898610F20FFF75CBF9823002034 +:10181000302383F31188FFF7F3BF000008B50146BA +:10182000302383F311880820FFF75AFF002383F346 +:10183000118808BD064BDB6839B1426818605A60F0 +:10184000136043600420FFF74BBF4FF0FF30704739 +:10185000982300200368984206D01A6802605060FE +:1018600099611846FFF72CBF7047000038B5044651 +:101870000D462068844200D138BD036823605C6057 +:101880008561FFF71DFFF4E710B503689C68A2426D +:101890000CD85C688A600B604C6021605960996864 +:1018A0008A1A9A604FF0FF33836010BD1B68121BC9 +:1018B000ECE700000A2938BF0A2170B504460D463E +:1018C0000A26601901F092FA01F07EFA041BA54283 +:1018D00003D8751C2E460446F3E70A2E04D9BDE84A +:1018E0007040012001F0C8BA70BD0000F8B5144B7B +:1018F0000D46D96103F1100141600A2A196982601D +:1019000038BF0A22016048601861A818144601F027 +:101910005FFA0A2701F058FA431BA342064606D392 +:101920007C1C281901F062FA27463546F2E70A2F97 +:1019300004D9BDE8F840012001F09EBAF8BD00BF0F +:1019400098230020F8B506460D4601F03DFA0F4AEF +:10195000134653F8107F9F4206D12A46014630466F +:10196000BDE8F840FFF7C2BFD169BB68441A2C1923 +:1019700028BF2C46A34202D92946FFF79BFF2246E7 +:1019800031460348BDE8F840FFF77EBF98230020AA +:10199000A823002010B4C0E9032300235DF8044B02 +:1019A0004361FFF7CFBF000010B5194C236998427F +:1019B0000DD0D0E90032816813605A609A680A44F9 +:1019C0009A60002303604FF0FF33A36110BD2346EC +:1019D000026843F8102F53600022026022699A4285 +:1019E00003D1BDE8104001F0FBB9936881680B4456 +:1019F000936001F0E9F92269E1699268441AA24210 +:101A0000E4D91144BDE81040091AFFF753BF00BFE5 +:101A1000982300202DE9F047DFF8BC8008F110077B +:101A20002C4ED8F8105001F0CFF9D8F81C40AA6815 +:101A3000031B9A423ED81444D5E900324FF0000906 +:101A4000C8F81C4013605A60C5F80090D8F81030F0 +:101A5000B34201D101F0C4F989F31188D5E903310A +:101A600028469847302383F311886B69002BD8D020 +:101A700001F0AAF96A69A0EB04094A4582460DD231 +:101A8000022001F0F9F90022D8F81030B34208D151 +:101A900051462846BDE8F047FFF728BF121A2244F6 +:101AA000F2E712EB090938BF4A4629463846FFF7E4 +:101AB000EBFEB5E7D8F81030B34208D01444211A31 +:101AC000C8F81C00A960BDE8F047FFF7F3BEBDE809 +:101AD000F08700BFA8230020982300200020704733 +:101AE000FEE70000704700004FF0FF307047000035 +:101AF00002290CD0032904D00129074818BF00206F +:101B00007047032A05D8054800EBC2007047044817 +:101B100070470020704700BFC43500082022002015 +:101B20007835000870B59AB00546084601A91446F4 +:101B300000F0C2F801A8FFF7BFF8431C5B00C5E93D +:101B400000340022237003236370C6B201AB023459 +:101B50001046D1B28E4204F1020401D81AB070BD11 +:101B600013F8011B04F8021C04F8010C0132F0E721 +:101B700008B5302383F311880348FFF759FA00238F +:101B800083F3118808BD00BF0826002090F8443078 +:101B900003F01F02012A07D190F845200B2A03D138 +:101BA0000023C0E90E3315E003F06003202B08D1B9 +:101BB000B0F848302BB990F84520212A03D81F2AC5 +:101BC00004D8FFF717BA222AEBD0FAE7034A826358 +:101BD0000722C26303640120704700BF182200205F +:101BE00007B5052917D8DFE801F0191603191920E0 +:101BF000302383F31188104A01900121FFF7BAFACC +:101C000001980E4A0221FFF7B5FA0D48FFF7DCF9FB +:101C1000002383F3118803B05DF804FB302383F3C2 +:101C200011880748FFF7A6F9F2E7302383F31188FC +:101C30000348FFF7BDF9EBE7183500083C3500080D +:101C40000826002038B50C4D0C4C0D492A4604F1ED +:101C50000800FFF767FF05F1CA0204F11000094907 +:101C6000FFF760FF05F5CA7204F118000649BDE8E8 +:101C70003840FFF757BF00BFD02A002020220020A5 +:101C8000F8340008023500080D35000870B5044628 +:101C900008460D46FFF710F8C6B220460134037817 +:101CA0000BB9184670BD32462946FEF7F1FF0028F1 +:101CB000F3D10120F6E700002DE9F04705460C4678 +:101CC000FEF7FAFF2B49C6B22846FFF7DFFF08B13F +:101CD0000B36F6B228492846FFF7D8FF08B1103670 +:101CE000F6B2632E0BD8DFF88C80DFF88C90234F90 +:101CF000DFF894A02E7846B92670BDE8F087294613 +:101D00002046BDE8F04701F09DBB252E2ED10722CD +:101D100041462846FEF7BCFF70B9194B224603F135 +:101D2000100153F8040B42F8040B8B42F9D11B88C5 +:101D3000138007351234DDE7082249462846FEF7AE +:101D4000A7FF98B90F4BA21C197809090232C95D87 +:101D500002F8041C13F8011B01F00F015345C95D83 +:101D600002F8031CF0D118340835C3E704F8016BFE +:101D70000135BFE7E43500080D350008FF350008E0 +:101D8000EC350008107AFF1F1C7AFF1FBFF34F8F3E +:101D9000024AD368DB03FCD4704700BF003C02401A +:101DA00008B5094B1B7873B9FFF7F0FF074B1A69A9 +:101DB000002ABFBF064A5A6002F188325A601A6888 +:101DC00022F480621A6008BD2E2D0020003C0240E3 +:101DD0002301674508B50B4B1B7893B9FFF7D6FF76 +:101DE000094B1A6942F000421A611A6842F48052A3 +:101DF0001A601A6822F480521A601A6842F48062EB +:101E00001A6008BD2E2D0020003C02400B28F0B5C2 +:101E100016D80C4C0C4923787BB90C4D0E460C237C +:101E20004FF0006255F8047B46F8042B013B13F099 +:101E3000FF033A44F6D10123237051F82000F0BD8E +:101E40000020FCE7602D0020302D00201036000817 +:101E5000014B53F820007047103600080C207047E3 +:101E60000B2810B5044601D9002010BDFFF7CEFFA6 +:101E7000064B53F824301844C21A0BB90120F4E77A +:101E800012680132F0D1043BF6E700BF10360008BB +:101E90000B2810B5044621D8FFF778FFFFF780FF25 +:101EA0000F4AF323D360C300DBB243F4007343F063 +:101EB00002031361136943F480331361FFF766FF74 +:101EC000FFF7A4FF074B53F8241000F0D9F8FFF7F1 +:101ED00081FF2046BDE81040FFF7C2BF002010BDC3 +:101EE000003C024010360008F8B512F00103144619 +:101EF00042D18218B2F1016F57D82D4B1B6813F0F5 +:101F0000010352D02B4DFFF74BFFF323EB60FFF79C +:101F10003DFF40F20127032C15D824F00104661878 +:101F2000244C401A40F20117B142236900EB01052D +:101F300024D123F001032361FFF74CFF0120F8BDFA +:101F4000043C0430E7E78307E7D12B6923F44073AF +:101F50002B612B693B432B6151F8046B0660BFF387 +:101F60004F8FFFF713FF03689E42E9D02B6923F0E0 +:101F700001032B61FFF72EFF0020E0E723F44073FD +:101F8000236123693B4323610B882B80BFF34F8F71 +:101F9000FFF7FCFE2D8831F8023BADB2AB42C3D057 +:101FA000236923F001032361E4E71846C7E700BF74 +:101FB00000380240003C0240084908B50B7828B1BF +:101FC0001BB9FFF7EDFE01230B7008BD002BFCD001 +:101FD000BDE808400870FFF7FDBE00BF2E2D0020B1 +:101FE00010B50244064BD2B2904200D110BD441C41 +:101FF00000B253F8200041F8040BE0B2F4E700BF50 +:10200000502800400F4B30B51C6F240407D41C6FC0 +:1020100044F400741C671C6F44F400441C670A4CB1 +:10202000236843F4807323600244084BD2B2904289 +:1020300000D130BD441C00B251F8045B43F820507D +:10204000E0B2F4E700380240007000405028004041 +:1020500007B5012201A90020FFF7C2FF019803B0D4 +:102060005DF804FB13B50446FFF7F2FFA04205D06C +:10207000012201A900200194FFF7C4FF02B010BDA6 +:1020800070470000034B1A681AB9034AD2F8742843 +:102090001A607047642D00200030024008B5FFF739 +:1020A000F1FF024B1868C0F3407008BD642D00209A +:1020B00070470000FEE700000A4B0B480B4A9042B5 +:1020C0000BD30B4BDA1C121AC11E22F003028B42F7 +:1020D00038BF00220021FEF7F7BD53F8041B40F87B +:1020E000041BECE7B8370008602E0020602E0020AB +:1020F000602E002070B5D0E915439E6800224FF095 +:10210000FF3504EB42135101D3F800090028BEBF8C +:10211000D3F8000940F08040C3F80009D3F8000B61 +:102120000028BEBFD3F8000B40F08040C3F8000B7E +:10213000013263189642C3F80859C3F8085BE0D22D +:102140004FF00113C4F81C3870BD0000890141F044 +:102150002001016103699B06FCD41220FFF716BB26 +:1021600010B5054C2046FEF7E5FF4FF0A043636530 +:10217000024BA36510BD00BF682D00206436000827 +:1021800070B50378012B054650D12A4B446D984217 +:102190001BD1294B5A6B42F080025A635A6D42F0B0 +:1021A00080025A655A6D5A6942F080025A615A6932 +:1021B00022F080025A610E2143205B6900F022FC6C +:1021C0001E4BE3601E4BC4F800380023C4F8003EE9 +:1021D000C02323606E6D4FF40413A3633369002B97 +:1021E000FCDA012333610C20FFF7D0FA3369DB07F7 +:1021F000FCD41220FFF7CAFA3369002BFCDA002660 +:10220000A6602846FFF776FF6B68C4F81068DB68A5 +:10221000C4F81468C4F81C684BB90A4BA3614FF0AA +:10222000FF336361A36843F00103A36070BD064BF5 +:10223000F4E700BF682D0020003802404014004041 +:1022400003002002003C30C0083C30C0F8B5446DAB +:10225000054600212046FFF779FFA96D00234FF0C6 +:1022600001128F68C4F834384FF00066C4F81C2897 +:102270004FF0FF3004EB431201339F42C2F8006974 +:10228000C2F8006BC2F80809C2F8080BF2D20B685A +:102290006A6DEB65636210231361166916F0100610 +:1022A000FBD11220FFF772FAD4F8003823F4FE6352 +:1022B000C4F80038A36943F4402343F01003A3613A +:1022C0000923C4F81038C4F814380A4BEB604FF0F7 +:1022D000C043C4F8103B084BC4F8003BC4F8106975 +:1022E000C4F80039EB6D03F1100243F48013EA6582 +:1022F000A362F8BD4036000840800010426D90F89F +:102300004E10D2F8003823F4FE6343EA0113C2F8FA +:10231000003870472DE9F84300EB8103456DDA681A +:10232000166806F00306731E022B05EB41130C46DC +:1023300080460FFA81F94FEA41104FF00001C3F8CF +:10234000101B4FF0010104F1100398BFB60401FA0D +:1023500003F391698EBF334E06F1805606F50046B1 +:1023600000293AD0578A04F15801490137436F5088 +:10237000D5F81C180B43C5F81C382B180021C3F8DE +:10238000101953690127611EA7409BB3138A928BD2 +:102390009B08012A88BF5343D8F85C20981842EA6A +:1023A000034301F1400205EB8202C8F85C002146BC +:1023B00053602846FFF7CAFE08EB8900C3681B8AF2 +:1023C00043EA8453483464011E432E51D5F81C3827 +:1023D0001F43C5F81C78BDE8F88305EB4917D7F80B +:1023E000001B21F40041C7F8001BD5F81C1821EA96 +:1023F0000303C0E704F13F0305EB83030A4A5A6075 +:1024000028462146FFF7A2FE05EB4910D0F8003917 +:1024100023F40043C0F80039D5F81C3823EA070735 +:10242000D7E700BF0080001000040002826D126830 +:10243000C265FFF75FBE00005831436D49015B582C +:1024400013F4004004D013F4001F0CBF022001203D +:10245000704700004831436D49015B5813F4004058 +:1024600004D013F4001F0CBF0220012070470000AD +:1024700000EB8101CB68196A0B6813604B685360ED +:102480007047000000EB810330B5DD68AA6913686E +:10249000D36019B9402B84BF402313606B8A146842 +:1024A000426D1C44013CB4FBF3F46343033323F05B +:1024B000030302EB411043EAC44343F0C043C0F8B6 +:1024C000103B2B6803F00303012B09B20ED1D2F8A5 +:1024D000083802EB411013F4807FD0F8003B14BFA2 +:1024E00043F0805343F00053C0F8003B02EB41122D +:1024F000D2F8003B43F00443C2F8003B30BD00007B +:102500002DE9F041244D6E6D06EB40130446D3F8DF +:10251000087BC3F8087B38070AD5D6F814381907A2 +:1025200006D505EB84032146DB6828465B6898479F +:10253000FA071FD5D6F81438DB071BD505EB840343 +:10254000D968CCB98B69488A5A68B2FBF0F600FBAF +:1025500016228AB91868DA6890420DD2121AC3E9B5 +:102560000024302383F311880B482146FFF78AFFAC +:1025700084F31188BDE8F081012303FA04F26B892A +:1025800023EA02036B81CB68002BF3D0214602487B +:10259000BDE8F041184700BF682D002000EB810323 +:1025A00070B5DD68436D6C692668E6604A0156BB0C +:1025B0001A444FF40020C2F810092A6802F00302FE +:1025C000012A0AB20ED1D3F8080803EB421410F422 +:1025D000807FD4F8000914BF40F0805040F00050D4 +:1025E000C4F8000903EB4212D2F8000940F004409D +:1025F000C2F80009D3F83408012202FA01F10143BC +:10260000C3F8341870BD19B9402E84BF4020206033 +:1026100020682E8A8419013CB4FBF6F440EAC440D9 +:1026200040F000501A44C6E72DE9F8433B4D6E6D6B +:1026300006EB40130446D3F80889C3F8088918F05C +:10264000010F4FEA40171AD0D6F81038DB0716D51D +:1026500005EB8003D9684B691868DA68904230D27C +:10266000121A4FF000091A60C3F80490302383F364 +:10267000118821462846FFF791FF89F3118818F049 +:10268000800F1CD0D6F834380126A640334216D02D +:1026900005EB84036D6DD3F80CC0DCF81420013415 +:1026A000E4B2D2F800E005EB04342F4451687145E0 +:1026B00015D3D5F8343823EA0606C5F83468BDE8E2 +:1026C000F883012303FA04F22B8923EA02032B8106 +:1026D0008B68002BD3D0214628469847CFE7BCF81B +:1026E0001000AEEB0103834228BF0346D7F8180958 +:1026F00080B2B3EB800FE2D89068A0F1040959F8DA +:10270000048FC4F80080A0EB09089844B8F1040FC6 +:10271000F5D818440B4490605360C7E7682D00203B +:102720002DE9F74FA24C656D6E69AB691E4016F43A +:1027300080586E6107D02046FEF764FD03B0BDE807 +:10274000F04F00F047BC002E12DAD5F8003E984852 +:102750009B071EBFD5F8003E23F00303C5F8003EDB +:10276000D5F8043823F00103C5F80438FEF774FDEA +:10277000370505D58E48FFF7BDFC8D48FEF75AFD9D +:10278000B0040CD5D5F8083813F0060FEB6823F425 +:1027900070530CBF43F4105343F4A053EB60310764 +:1027A0001BD56368DB681BB9AB6923F00803AB6119 +:1027B0002378052B0CD1D5F8003E7D489A071EBF23 +:1027C000D5F8003E23F00303C5F8003EFEF744FDB4 +:1027D0006368DB680BB176489847F30274D4B7029C +:1027E00027D5D4F85490DFF8C8B100274FF0010A7C +:1027F00009EB4712D2F8003B03F44023B3F5802FD6 +:1028000011D1D2F8003B002B0DDA62890AFA07F3E6 +:1028100022EA0303638104EB8703DB68DB6813B1FF +:10282000394658469847A36D01379B68FFB29F42CF +:10283000DED9F00617D5676D3A6AC2F30A1002F0C6 +:102840000F0302F4F012B2F5802F00F08580B2F58C +:10285000402F08D104EB83030022DB681B6A07F5D5 +:10286000805790426AD13003D5F8184813D5E10358 +:1028700002D50020FFF744FEA20302D50120FFF796 +:102880003FFE630302D50220FFF73AFE270302D57D +:102890000320FFF735FE75037FF550AFE00702D543 +:1028A0000020FFF7C1FEA10702D50120FFF7BCFE03 +:1028B000620702D50220FFF7B7FE23077FF53EAF80 +:1028C0000320FFF7B1FE39E7636DDFF8E4A0019361 +:1028D00000274FF00109A36D9B685FFA87FB9B45BA +:1028E0003FF67DAF019B03EB4B13D3F8001901F4C6 +:1028F0004021B1F5802F1FD1D3F8001900291BDA30 +:10290000D3F8001941F09041C3F80019D3F8001929 +:102910000029FBDB5946606DFFF718FC218909FA95 +:102920000BF321EA0303238104EB8B03DB689B6831 +:1029300013B15946504698470137CCE7910708BF75 +:10294000D7F80080072A98BF03F8018B02F1010233 +:1029500098BF4FEA182884E7023304EB830207F597 +:1029600080575268D2F818C0DCF80820DCE9001C57 +:10297000A1EB0C0C002188420AD104EB83046368AC +:102980009B699A6802449A605A6802445A606AE7EE +:1029900011F0030F08BFD7F800808C4588BF02F8FC +:1029A000018B01F1010188BF4FEA1828E3E700BF5E +:1029B000682D0020436D03EB4111D1F8003B43F437 +:1029C0000013C1F8003B7047436D03EB4111D1F890 +:1029D000003943F40013C1F800397047436D03EB2D +:1029E0004111D1F8003B23F40013C1F8003B7047BC +:1029F000436D03EB4111D1F8003923F40013C1F802 +:102A00000039704700F1604303F561430901C9B221 +:102A100083F80013012200F01F039A4043099B0032 +:102A200003F1604303F56143C3F880211A607047E6 +:102A300030B5039C0172043304FB0325C0E906533F +:102A4000049B03630021059BC160C0E90000C0E94D +:102A50000422C0E90842C0E90A11436330BD000006 +:102A6000416A0022C0E90411C0E90A22C2606FF085 +:102A70000101FEF7FBBE0000D0E90432934201D110 +:102A8000C2680AB9181D70470020704703691960B1 +:102A9000C2680132C260C269134482690361934211 +:102AA00024BF436A03610021FEF7D4BE38B5044653 +:102AB0000D46E3683BB16269131D1268A3621344BB +:102AC000E362002007E0237A33B929462046FEF767 +:102AD000B1FE0028EDDA38BD6FF00100FBE7000021 +:102AE000C368C269013BC36043691344826943619F +:102AF000934224BF436A436100238362036B03B1A3 +:102B00001847704770B53023044683F31188866AEE +:102B10003EB9FFF7CBFF054618B186F3118828466A +:102B200070BDA36AE26A13F8015BA362934202D309 +:102B30002046FFF7D5FF002383F31188EFE700005D +:102B40002DE9F84F04460E46174698464FF03009D7 +:102B500089F311880025AA46D4F828B0BBF1000FEC +:102B600009D141462046FFF7A1FF20B18BF3118820 +:102B70002846BDE8F88FD4E90A12A7EB050B521AD4 +:102B8000934528BF9346BBF1400F1BD9334601F153 +:102B9000400251F8040B43F8040B9142F9D1A36AA7 +:102BA00040334036A3624035D4E90A239A4202D327 +:102BB0002046FFF795FF8AF31188BD42D8D289F3EA +:102BC0001188C9E730465A46FEF758F8A36A5B44B5 +:102BD0005E44A3625D44E7E710B5029C01720433D2 +:102BE00003FB0421C0E906130023C0E90A33039B59 +:102BF0000363049BC460C0E90000C0E90422C0E98B +:102C00000842436310BD0000026AC260426AC0E924 +:102C100004220022C0E90A226FF00101FEF726BE5D +:102C2000D0E904239A4201D1C26822B9184650F86B +:102C3000043B0B60704700231846FAE7C368C2697B +:102C40000133C3604369134482694361934224BFE3 +:102C5000436A43610021FEF7FDBD000038B504461C +:102C60000D46E3683BB123691A1DA262E269134471 +:102C7000E362002007E0237A33B929462046FEF7B5 +:102C8000D9FD0028EDDA38BD6FF00100FBE7000048 +:102C900003691960C268013AC260C269134482695B +:102CA0000361934224BF436A036100238362036B81 +:102CB00003B118477047000070B530230D46044635 +:102CC000114683F31188866A2EB9FFF7C7FF10B14A +:102CD00086F3118870BDA36A1D70A36AE26A01338E +:102CE0009342A36204D3E16920460439FFF7D0FF81 +:102CF000002080F31188EDE72DE9F84F04460D46DA +:102D0000904699464FF0300A8AF311880026B34660 +:102D1000A76A4FB949462046FFF7A0FF20B187F3C5 +:102D200011883046BDE8F88FD4E90A073A1AA8EBB3 +:102D30000607974228BF1746402F1BD905F14003CD +:102D400055F8042B40F8042B9D42F9D1A36A403377 +:102D5000A3624036D4E90A239A4204D3E1692046AB +:102D60000439FFF795FF8BF311884645D9D28AF3D2 +:102D70001188CDE729463A46FDF780FFA36A3B4418 +:102D80003D44A3623E44E5E7D0E904239A4217D1CB +:102D9000C3689BB1836A8BB1043B9B1A0ED013604E +:102DA000C368013BC360C3691A44836902619A42E4 +:102DB00024BF436A036100238362012318467047DE +:102DC0000023FBE700F030B94FF08043586A7047AA +:102DD0004FF08043002258631A610222DA60704784 +:102DE0004FF080430022DA60704700004FF08043CC +:102DF00058637047FEE7000070B51B4B0163002568 +:102E0000044686B0586085620E4600F0BFF804F1B3 +:102E10001003C4E904334FF0FF33C4E90635C4E9B5 +:102E20000044A560E562FFF7CFFF2B460246C4E9E8 +:102E3000082304F134010D4A256580232046FEF75E +:102E4000AFFC0123E0600A4A0375009272680192A8 +:102E5000B268CDE90223074B6846CDE90435FEF799 +:102E6000C7FC06B070BD00BF002600207036000809 +:102E700075360008F52D0008024AD36A1843D0625F +:102E8000704700BF982300204B6843608B688360C5 +:102E9000CB68C3600B6943614B6903628B69436212 +:102EA0000B6803607047000008B5264B26481A6976 +:102EB00040F2FF110A431A611A6922F4FF7222F0EC +:102EC00001021A611A691A6B0A431A631A6D0A43DE +:102ED0001A651E4A1B6D1146FFF7D6FF02F11C0151 +:102EE00000F58060FFF7D0FF02F1380100F5806047 +:102EF000FFF7CAFF02F1540100F58060FFF7C4FF3D +:102F000002F1700100F58060FFF7BEFF02F18C0155 +:102F100000F58060FFF7B8FF02F1A80100F58060BE +:102F2000FFF7B2FF02F1C40100F58060FFF7ACFFCC +:102F300002F1E00100F58060FFF7A6FFBDE8084060 +:102F400000F0EEB800380240000002407C36000875 +:102F500008B500F059FAFEF701FCFFF793F8BDE859 +:102F60000840FEF76FBE000070470000EFF30983D2 +:102F700005494A6B22F001024A63683383F30988EA +:102F8000002383F31188704700EF00E0302080F3C6 +:102F9000118862B60C4B0D4AD96821F4E06109042E +:102FA000090C0A43DA60D3F8FC20094942F0807228 +:102FB000C3F8FC200A6842F001020A602022DA7796 +:102FC00083F82200704700BF00ED00E00003FA051F +:102FD000001000E010B5302383F311880E4B5B68BE +:102FE00013F4006314D0F1EE103AEFF30984683C57 +:102FF0004FF08073E361094BDB6B236684F3098830 +:10300000FEF78CFB10B1064BA36110BD054BFBE72F +:1030100083F31188F9E700BF00ED00E000EF00E066 +:103020002F030008320300080F4B1A6C42F0010214 +:103030001A641A6E42F001021A660C4A1B6E9368FB +:1030400043F0010393604FF0804353229A624FF0A4 +:10305000FF32DA6200229A615A63DA605A60012212 +:103060005A611A60704700BF00380240002004E037 +:103070004FF0804208B51169D3680B40D9B2C943FB +:103080009B07116107D5302383F31188FEF77CFB82 +:10309000002383F3118808BD1F4B1A696FEAC252DF +:1030A0006FEAD2521A611A69C2F308021A614FF02C +:1030B000FF301A695A69586100215A6959615A6981 +:1030C0001A6A62F080521A621A6A02F080521A6218 +:1030D0001A6A5A6A58625A6A59625A6A1A6C42F0F3 +:1030E00080521A641A6E42F080521A661A6E0B4AA7 +:1030F000106840F480701060186F00F44070B0F5F4 +:10310000007F1EBF4FF4803018671967536823F49F +:103110000073536000F054B9003802400070004062 +:10312000334B4FF080521A64324A4FF440411160E1 +:103130001A6842F001021A601A689107FCD59A6871 +:1031400022F003029A602A4B9A6812F00C02FBD11B +:10315000196801F0F90119609A601A6842F4803226 +:103160001A601A689203FCD55A6F42F001025A673E +:103170001F4B5A6F9007FCD51F4A5A601A6842F0DD +:1031800080721A601B4A53685904FCD5184B1A68A0 +:103190009201FCD5194A9A60194B1A68194B9A4248 +:1031A000194B21D1194A1168194A91421CD140F298 +:1031B00005121A60144A136803F00F03052BFAD1A5 +:1031C0000B4B9A6842F002029A609A6802F00C0275 +:1031D000082AFAD15A6C42F480425A645A6E42F478 +:1031E00080425A665B6E704740F20572E1E700BFAD +:1031F00000380240007000400854400700948838AE +:10320000002004E011640020003C024000ED00E0DA +:1032100041C20F41074A08B5536903F001035361E6 +:1032200023B1054A13680BB150689847BDE80840C0 +:10323000FFF7D0BE003C0140E02D0020074A08B552 +:10324000536903F00203536123B1054A93680BB13C +:10325000D0689847BDE80840FFF7BCBE003C01407D +:10326000E02D0020074A08B5536903F004035361B9 +:1032700023B1054A13690BB150699847BDE808406E +:10328000FFF7A8BE003C0140E02D0020074A08B52A +:10329000536903F00803536123B1054A93690BB1E5 +:1032A000D0699847BDE80840FFF794BE003C014054 +:1032B000E02D0020074A08B5536903F0100353615D +:1032C00023B1054A136A0BB1506A9847BDE808401C +:1032D000FFF780BE003C0140E02D0020164B10B5EA +:1032E0005C6904F478725A61A30604D5134A936AA0 +:1032F0000BB1D06A9847600604D5104A136B0BB126 +:10330000506B9847210604D50C4A936B0BB1D06BD8 +:103310009847E20504D5094A136C0BB1506C9847E5 +:10332000A30504D5054A936C0BB1D06C9847BDE852 +:103330001040FFF74FBE00BF003C0140E02D0020D1 +:10334000194B10B55C6904F47C425A61620504D5DE +:10335000164A136D0BB1506D9847230504D5134AD7 +:10336000936D0BB1D06D9847E00404D50F4A136EEE +:103370000BB1506E9847A10404D50C4A936E0BB163 +:10338000D06E9847620404D5084A136F0BB1506F92 +:103390009847230404D5054A936F0BB1D06F984723 +:1033A000BDE81040FFF716BE003C0140E02D0020B4 +:1033B00008B5FFF75DFEBDE80840FFF70BBE000053 +:1033C000062108B50846FFF71DFB06210720FFF779 +:1033D00019FB06210820FFF715FB06210920FFF73E +:1033E00011FB06210A20FFF70DFB06211720FFF72E +:1033F00009FB06212820FFF705FBBDE8084007214F +:103400001C20FFF7FFBA000008B5FFF745FE00F0EB +:103410000BF8FDF78DFEFDF765FDFFF7A5FDBDE897 +:103420000840FFF7CFBC00000023054A19460133CE +:10343000102BC2E9001102F10802F8D1704700BF59 +:10344000E02D0020034611F8012B03F8012B002A80 +:10345000F9D1704753544D3332463F3F3F005354E8 +:103460004D3332463430780053544D333246343283 +:10347000780053544D3332463434365858000000E7 +:10348000012033000010410001105A0003105900C0 +:10349000071031000000000054340008130400003D +:1034A0005E3400081904000068340008210400009C +:1034B0007234000800000000610E00084D0E000884 +:1034C000890E0008750E0008810E00086D0E0008B8 +:1034D000590E0008450E0008950E00080000000077 +:1034E000010000000000000063300000E834000824 +:1034F000F0230020002600204172647550696C6F33 +:10350000740025424F415244252D424C002553451D +:103510005249414C2500000002000000000000005C +:103520007D100008E910000840004000A02A00209B +:10353000B02A00200200000000000000030000008C +:10354000000000002D110008000000001000000025 +:10355000C02A002000000000010000000000000060 +:10356000682D002001010200E11B0008F11A00088B +:103570008D1B0008711B0008430000008035000807 +:1035800009024300020100C03209040000010202E6 +:103590000100052400100105240100010424020299 +:1035A0000524060001070582030800FF0904010045 +:1035B000020A000000070501024000000705810221 +:1035C0004000000012000000CC350008120110017C +:1035D00002000040091241570002010203010000ED +:1035E0000403090425424F4152442500466C797773 +:1035F0006F6F4634303548442D41494F76320030A4 +:103600003132333435363738394142434445460048 +:1036100000400000004000000040000000400000AA +:103620000000010000000200000002000000020093 +:103630000000020000000200000002000000020082 +:10364000000000007112000829150008D5150008B7 +:1036500040004000C82D0020C82D002001000000BF +:10366000D82D002080000000400100000300000071 +:103670006D61696E0069646C650000000000842A59 +:1036800000000000AAAAAAAA00000024FFFD000072 +:103690000000000000A00A0040000011000000002F +:1036A000AAAAAAAA40000011FFFF00000000000023 +:1036B000000000000000000000000000AAAAAAAA62 +:1036C00000000000FFFF00000000000000000000FC +:1036D0000000000000000000AAAAAAAA0000000042 +:1036E000FFFF0000000000000000000000000000DC +:1036F00000000000AAAAAAAA00000000FFFF000024 +:1037000000000000000000000000000000000000B9 +:10371000AAAAAAAA00000000FFFF00000000000003 +:10372000000000000000000000000000AAAAAAAAF1 +:1037300000000000FFFF000000000000000000008B +:1037400000000000000000000A000000000000006F +:103750000300000000000000000000000000000066 +:103760000000000000000000000000000000000059 +:1037700000000000000000009C04000000000000A9 +:1037800000400F0000000000FF009600000000084D +:10379000009600000000080004000000E03500086A +:1037A0000000000000000000000000000000000019 +:0837B000000000000000000011 +:00000001FF diff --git a/Tools/bootloaders/FlywooH743Pro_bl.bin b/Tools/bootloaders/FlywooH743Pro_bl.bin new file mode 100644 index 00000000000000..576d2e3d21e1c9 Binary files /dev/null and b/Tools/bootloaders/FlywooH743Pro_bl.bin differ diff --git a/Tools/bootloaders/FlywooH743Pro_bl.hex b/Tools/bootloaders/FlywooH743Pro_bl.hex new file mode 100644 index 00000000000000..905a8eed7f05ce --- /dev/null +++ b/Tools/bootloaders/FlywooH743Pro_bl.hex @@ -0,0 +1,1167 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008352A0008A2 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E302000895410008C1410008DE +:10006000ED410008194200084542000879100008D7 +:10007000A1100008CD100008F91000082511000893 +:100080004D11000879110008E3020008E30200089E +:10009000E3020008E3020008E302000871420008DE +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000D5420008E3020008E3020008E30200082A +:1000F000E3020008E3020008E3020008A51100087B +:10010000E3020008E302000849430008E302000894 +:10011000E3020008E3020008E3020008E30200082B +:10012000D1110008F9110008251200085112000829 +:100130007D120008E3020008E3020008E302000861 +:10014000E3020008E3020008E3020008E3020008FB +:10015000A5120008D1120008FD120008E3020008F1 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000821360008E3020008E302000859 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200080D360008E3020008E30200080D +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0D4FB9F +:1003500003F0DAFC4FF055301F491B4A91423CBF75 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F0ECFB03F038FD38 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0D4BB000600200022002095 +:1003D0000000000808ED00E00000002000060020FA +:1003E00070480008002200205C22002060220020CB +:1003F00084440020E0020008E0020008E002000857 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0CCFDFEE701F02E +:1004300057FD00DFFEE7000038B500F02FFC00F0AC +:10044000A9FD02F0B7FA054602F0EAFA0446C0B97F +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0AEFA0CB100F091 +:1004700075F800F063FD284600F01EF900F06EF8F4 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F049FE0023154A4FF4A9 +:1004D0007A71134801F038FE002383F31188124C1F +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F086FC322363602B78032B07D16368ED +:100510002BB9022000F07CFC4FF47A73636038BD85 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05BBC022000F050BC024B0022F5 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E1FBB14ABA +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F039FD0023AB4A4FF4C8 +:1006F0007A71A94801F028FD002383F31188009B3B +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F069FB24B19C4B1B6862 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F056FB26B10BF03F +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F030FA019AFF217F4800F051FA4FEAF7 +:1009F000A803C8F387027C492846019300F050FA07 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0FBFA8046E7E7384600F03AF941 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09BF900283AD0202290 +:100B7000FF210AA800F08CF9FFF792FC1C4801F055 +:100B800027FA13B0BDE8F08F002E3FF42BAE0BF028 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F005FA059800F0E2F946463C4607 +:100BD00000F0AAF9A6E506464EE64FF0000901E648 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0D0F963 +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F0B0FC30802868338883426C +:100CB00008D901F0A5FC2B6804440133B4F5C02F1A +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F068BD00F1006000F5C02000687047B9 +:100CE00000F10060920000F5C02001F0E9BC0000B6 +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F07EBC0020704788230020B62300201D +:100D100038B50446074D29B128682044BDE838405D +:100D200001F086BC2868204401F070FC0028F3D054 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C1422002040440008022802D1B8 +:100DF000014B08229A61704700100258022803D163 +:100E0000024B4FF400229A61704700BF0010025855 +:100E1000022804D1024A536983F0080353617047E2 +:100E20000010025870B504464FF47A764CB1412C4C +:100E3000254628BF412506FB05F0641B01F0C8F8D4 +:100E4000F4E770BD002310B5934203D0CC5CC454CA +:100E50000133F9E710BD0000013810B510F9013F6A +:100E60003BB191F900409C4203D11AB10131013AE2 +:100E7000F4E71AB191F90020981A10BD1046FCE76A +:100E800003460246D01A12F9011B0029FAD1704715 +:100E900002440346934202D003F8011BFAE770476D +:100EA0002DE9F8431F4D14460746884695F824203F +:100EB00052BBDFF870909CB395F824302BB92022F8 +:100EC000FF2148462F62FFF7E3FF95F824004146D3 +:100ED000C0F1080205EB8000A24228BF2246D6B22C +:100EE0009200FFF7AFFF95F82430A41B17441E446F +:100EF0009044E4B2F6B2082E85F82460DBD1FFF707 +:100F000025FF0028D7D108E02B6A03EB8203834238 +:100F1000CFD0FFF71BFF0028CBD10020BDE8F8831E +:100F20000120FBE78C230020024B1A78024B1A7039 +:100F3000704700BFB42300201022002010B5114CD0 +:100F4000114800F075FB21460F4800F09DFB246816 +:100F50004FF47A70D4F89020D2F8043843F00203AA +:100F6000C2F80438FFF75EFF0849204600F09AFCFB +:100F7000D4F89020D2F8043823F00203C2F80438E1 +:100F800010BD00BFFC450008B02600200446000844 +:100F900070470000F8B571B6002301201A461946C3 +:100FA00000F054FA0446802001F09AFC002845D055 +:100FB0000025234A80274FF4D06C3D26136923BBBC +:100FC000D2F810310BBB236805F1006199602368EA +:100FD000D86023685F602368C3F800C021680B688D +:100FE00043F001030B6021680B6823F01E030B60C4 +:100FF00021680B68DB07FCD4237B8035616806FA27 +:1010000003F3B5F5001F0B60D8D1204600F05EFA5F +:10101000B5F5001F11D000240A4E0B4D012001F040 +:10102000C1FB3388A34205D928682044013401F06C +:10103000FFFAF6E7002001F0B5FB61B6F8BD00BF8E +:1010400000200052B62300208823002030B50A4437 +:10105000084D91420DD011F8013B5840082340F350 +:101060000004013B2C4013F0FF0384EA5000F6D14A +:10107000EFE730BD2083B8ED08B5074B074A196884 +:1010800001F03D01996053680BB190689847BDE845 +:10109000084001F007BD00BF00000240B823002057 +:1010A00008B5084B1968890901F03D018A019A6069 +:1010B000054AD3680BB110699847BDE8084001F0B4 +:1010C000F1BC00BF00000240B823002008B5084B67 +:1010D0001968090C01F03D010A049A60054A536938 +:1010E0000BB190699847BDE8084001F0DBBC00BF38 +:1010F00000000240B823002008B5084B1968890D8C +:1011000001F03D018A059A60054AD3690BB1106A66 +:101110009847BDE8084001F0C5BC00BF0000024090 +:10112000B823002008B5074B074A596801F03D0174 +:10113000D960536A0BB1906A9847BDE8084001F046 +:10114000B1BC00BF00000240B823002008B5084B26 +:101150005968890901F03D018A01DA60054AD36ABC +:101160000BB1106B9847BDE8084001F09BBC00BF75 +:1011700000000240B823002008B5084B5968090C4C +:1011800001F03D010A04DA60054A536B0BB1906B24 +:101190009847BDE8084001F085BC00BF0000024050 +:1011A000B823002008B5084B5968890D01F03D01AE +:1011B0008A05DA60054AD36B0BB1106C9847BDE81D +:1011C000084001F06FBC00BF00000240B8230020BF +:1011D00008B5074B074A196801F03D019960536C47 +:1011E0000BB1906C9847BDE8084001F05BBC00BFB4 +:1011F00000040240B823002008B5084B196889098B +:1012000001F03D018A019A60054AD36C0BB1106D63 +:101210009847BDE8084001F045BC00BF000402400B +:10122000B823002008B5084B1968090C01F03D01EE +:101230000A049A60054A536D0BB1906D9847BDE85A +:10124000084001F02FBC00BF00040240B82300207A +:1012500008B5084B1968890D01F03D018A059A60AF +:10126000054AD36D0BB1106E9847BDE8084001F0F8 +:1012700019BC00BF00040240B823002008B5074B8A +:10128000074A596801F03D01D960536E0BB1906E69 +:101290009847BDE8084001F005BC00BF00040240CB +:1012A000B823002008B5084B5968890901F03D01B1 +:1012B0008A01DA60054AD36E0BB1106F9847BDE81A +:1012C000084001F0EFBB00BF00040240B82300203B +:1012D00008B5084B5968090C01F03D010A04DA60B1 +:1012E000054A536F0BB1906F9847BDE8084001F075 +:1012F000D9BB00BF00040240B823002008B5084B4A +:101300005968890D01F03D018A05DA60054AD36FFD +:1013100013B1D2F880009847BDE8084001F0C2BB85 +:1013200000040240B823002000230C4910B51A46DF +:101330000B4C0B6054F82300026001EB43000433B4 +:101340004260402BF6D1074A4FF0FF339360D360E1 +:10135000C2F80834C2F80C3410BD00BFB823002016 +:1013600050440008000002400F28F8B510D910289A +:1013700010D0112811D0122808D10F240720DFF82F +:10138000C8E00126DEF80050A04208D9002653E04C +:101390000446F4E70F240020F1E70724FBE706FAF0 +:1013A00000F73D424AD1264C4FEA001C3D4304EB76 +:1013B00000160EEBC000CEF80050C0E90123FBB2CE +:1013C00073B12048D0F8D83043F00103C0F8D830CA +:1013D000D0F8003143F00103C0F80031D0F80031FB +:1013E00017F47F4F0ED01748D0F8D83043F00203DF +:1013F000C0F8D830D0F8003143F00203C0F8003113 +:10140000D0F8003154F80C00036823F01F03036088 +:10141000056815F00105FBD104EB0C033D2493F89E +:101420000CC05F6804FA0CF43C6021240560446140 +:1014300012B1987B00F054F83046F8BD0130A3E7B4 +:101440005044000800440258B823002010B530244E +:1014500084F31188FFF788FF002383F3118810BD00 +:1014600010B50446807B00F051F801231549627BDA +:1014700003FA02F20B6823EA0203DAB20B6072B9D4 +:10148000114AD2F8D81021F00101C2F8D810D2F8D0 +:10149000001121F00101C2F80011D2F8002113F46B +:1014A0007F4F0ED1084BD3F8D82022F00202C3F8A8 +:1014B000D820D3F8002122F00202C3F80021D3F88B +:1014C000003110BDB82300200044025808B5302375 +:1014D00083F31188FFF7C4FF002383F3118808BD4D +:1014E000090100F16043012203F56143C9B283F8A9 +:1014F000001300F01F039A4043099B0003F160436F +:1015000003F56143C3F880211A60704700F01F03A0 +:1015100001229A40430900F160409B0000F56140C0 +:1015200003F1604303F56143C3F88020C3F88021D1 +:10153000002380F80033704702684368114301605C +:1015400003B118477047000013B5406B00F5805495 +:10155000D4F8A4381A681178042914D1017C02291E +:1015600011D11979012312898B4013420BD101A9A2 +:101570004C3002F087F9D4F8A4480246019B217947 +:10158000206800F0DFF902B010BD0000143002F056 +:1015900009B900004FF0FF33143002F003B9000026 +:1015A0004C3002F0DBB900004FF0FF334C3002F05A +:1015B000D5B90000143002F0D7B800004FF0FF3169 +:1015C000143002F0D1B800004C3002F0A7B900008E +:1015D0004FF0FF324C3002F0A1B9000000207047FC +:1015E00010B500F58054D4F8A4381A68117804298D +:1015F00017D1017C022914D15979012352898B40DA +:1016000013420ED1143002F069F8024648B1D4F802 +:10161000A4484FF4407361792068BDE8104000F0A1 +:101620007FB910BD406BFFF7DBBF000070470000C3 +:101630007FB5124B01250426044603600023057480 +:1016400000F1840243602946C0E902330C4B02904A +:10165000143001934FF44073009602F01BF8094BCD +:1016600004F69442294604F14C000294CDE900634B +:101670004FF4407302F0E2F804B070BD504500082A +:1016800025160008491500080A68302383F31188DD +:101690000B790B3342F823004B79133342F82300C4 +:1016A0008B7913B10B3342F8230000F58053C3F854 +:1016B000A41802230374002080F3118870470000EF +:1016C00038B5037F044613B190F85430ABB9012507 +:1016D000201D0221FFF730FF04F114006FF001011B +:1016E000257700F09DFC04F14C0084F854506FF015 +:1016F0000101BDE8384000F093BC38BD10B50121B0 +:1017000004460430FFF718FF0023237784F8543091 +:1017100010BD000038B504460025143001F0D2FF9A +:1017200004F14C00257702F0A1F8201D84F85450F4 +:101730000121FFF701FF2046BDE83840FFF750BF09 +:1017400090F8803003F06003202B06D190F88120C0 +:101750000023212A03D81F2A06D800207047222AF6 +:10176000FBD1C0E91D3303E0034A426707228267C9 +:10177000C3670120704700BF2C22002037B500F559 +:101780008055D5F8A4381A68117804291AD1017C3B +:10179000022917D11979012312898B40134211D1E3 +:1017A00000F14C04204602F021F958B101A920466D +:1017B00002F068F8D5F8A4480246019B2179206818 +:1017C00000F0C0F803B030BD01F10B03F0B550F8E4 +:1017D000236085B004460D46FEB1302383F31188A3 +:1017E00004EB8507301D0821FFF7A6FEFB6806F114 +:1017F0004C005B691B681BB1019002F051F8019825 +:1018000003A902F03FF8024648B1039B294620464F +:1018100000F098F8002383F3118805B0F0BDFB6851 +:101820005A691268002AF5D01B8A013B1340F1D196 +:1018300004F18002EAE70000133138B550F8214086 +:10184000ECB1302383F3118804F58053D3F8A42836 +:101850001368527903EB8203DB689B695D6845B1CD +:1018600004216018FFF768FE294604F1140001F016 +:101870003FFF2046FFF7B4FE002383F3118838BDF5 +:101880007047000001F00CBA01234022002110B57E +:10189000044600F8303BFFF7FBFA0023C4E90133AC +:1018A00010BD000010B53023044683F311882422B4 +:1018B000416000210C30FFF7EBFA204601F012FAEC +:1018C00002230020237080F3118810BD70B500EB57 +:1018D0008103054650690E461446DA6018B110229D +:1018E0000021FFF7D5FAA06918B110220021FFF7F7 +:1018F000CFFA31462846BDE8704001F0F9BA000041 +:1019000083682022002103F0011310B50446836090 +:101910001030FFF7BDFA2046BDE8104001F074BB5F +:10192000F0B4012500EB810447898D40E4683D4314 +:10193000A469458123600023A2606360F0BC01F0CC +:1019400091BB0000F0B4012500EB810407898D40B4 +:10195000E4683D436469058123600023A2606360FD +:10196000F0BC01F007BC000070B50223002504465E +:10197000242203702946C0F888500C3040F8045CDB +:10198000FFF786FA204684F8705001F045FA636844 +:101990001B6823B129462046BDE87040184770BD3A +:1019A0000378052B10B504460AD080F88C30052347 +:1019B000037043681B680BB1042198470023A360A0 +:1019C00010BD00000178052906D190F88C204368ED +:1019D00002701B6803B118477047000070B590F89B +:1019E0007030044613B1002380F8703004F1800297 +:1019F000204601F02DFB63689B68B3B994F88030F2 +:101A000013F0600535D00021204601F01FFE0021B3 +:101A1000204601F00FFE63681B6813B106212046C3 +:101A20009847062384F8703070BD204698470028F8 +:101A3000E4D0B4F88630A26F9A4288BFA36794F9C5 +:101A40008030A56F002B4FF0300380F20381002D12 +:101A500000F0F280092284F8702083F311880021BD +:101A60002046D4E91D23FFF76DFF002383F311887F +:101A7000DAE794F8812003F07F0343EA022340F27F +:101A80000232934200F0C58021D8B3F5807F48D060 +:101A90000DD8012B3FD0022B00F09380002BB2D148 +:101AA00004F1880262670222A267E367C1E7B3F527 +:101AB000817F00F09B80B3F5407FA4D194F8823001 +:101AC000012BA0D1B4F8883043F0020332E0B3F523 +:101AD000006F4DD017D8B3F5A06F31D0A3F5C06318 +:101AE000012B90D86368204694F882205E6894F8B1 +:101AF0008310B4F88430B047002884D0436863670B +:101B00000368A3671AE0B3F5106F36D040F60242BF +:101B100093427FF478AF5C4B63670223A367002393 +:101B2000C3E794F88230012B7FF46DAFB4F88830AE +:101B300023F00203A4F88830C4E91D55E56778E76F +:101B4000B4F88030B3F5A06F0ED194F882302046FF +:101B500084F88A3001F0BEF963681B6813B1012173 +:101B600020469847032323700023C4E91D339CE7D4 +:101B700004F18B0363670123C3E72378042B10D19F +:101B8000302383F311882046FFF7BAFE85F31188CE +:101B90000321636884F88B5021701B680BB12046C9 +:101BA000984794F88230002BDED084F88B300423E1 +:101BB000237063681B68002BD6D00221204698470B +:101BC000D2E794F8843020461D0603F00F010AD5B1 +:101BD00001F030FA012804D002287FF414AF2B4B17 +:101BE0009AE72B4B98E701F017FAF3E794F8823065 +:101BF000002B7FF408AF94F8843013F00F01B3D0BA +:101C00001A06204602D501F039FDADE701F02AFDA4 +:101C1000AAE794F88230002B7FF4F5AE94F8843074 +:101C200013F00F01A0D01B06204602D501F00EFDD7 +:101C30009AE701F0FFFC97E7142284F8702083F301 +:101C400011882B462A4629462046FFF769FE85F370 +:101C50001188E9E65DB1152284F8702083F31188BC +:101C600000212046D4E91D23FFF75AFEFDE60B2292 +:101C700084F8702083F311882B462A462946204693 +:101C8000FFF760FEE3E700BF8045000878450008E5 +:101C90007C45000838B590F870300446002B3ED0E3 +:101CA000063BDAB20F2A34D80F2B32D8DFE803F024 +:101CB0003731310822323131313131313131373739 +:101CC000856FB0F886309D4214D2C3681B8AB5FB7D +:101CD000F3F203FB12556DB9302383F311882B46C1 +:101CE0002A462946FFF72EFE85F311880A2384F839 +:101CF00070300EE0142384F87030302383F31188A1 +:101D0000002320461A461946FFF70AFE002383F3F4 +:101D1000118838BDC36F03B198470023E7E700215E +:101D2000204601F093FC0021204601F083FC63680B +:101D30001B6813B10621204698470623D7E7000009 +:101D400010B590F870300446142B29D017D8062B04 +:101D500005D001D81BB110BD093B022BFBD80021D7 +:101D6000204601F073FC0021204601F063FC63680B +:101D70001B6813B1062120469847062319E0152B4E +:101D8000E9D10B2380F87030302383F311880023CE +:101D90001A461946FFF7D6FD002383F31188DAE7C8 +:101DA000C3689B695B68002BD5D1C36F03B19847AB +:101DB000002384F87030CEE700238268037503693E +:101DC0001B6899689142FBD25A68036042601060B8 +:101DD0005860704700238268037503691B6899681F +:101DE0009142FBD85A6803604260106058607047A7 +:101DF00008B50846302383F311880A7D0023052A9D +:101E000006D8DFE802F00B050503120E82691360A5 +:101E10004FF0FF338361FFF7CFFF002383F3118877 +:101E200008BD8269936801339360D0E90032136082 +:101E30005A60EDE7FFF7C0BF054BD9680875186811 +:101E4000026853601A600122D8600275FEF7DABAA0 +:101E5000402400200C4B30B5DD684B1C87B0044695 +:101E60000FD02B46094A684600F06EF92046FFF76E +:101E7000E3FF009B13B1684600F070F9A86907B052 +:101E800030BDFFF7D9FFF9E740240020F11D00081D +:101E900038B50C4D04468161EB6881689A689142BF +:101EA00003D8BDE83840FFF787BF1846FFF792FF19 +:101EB00001230146EC6020462375BDE83840FEF75B +:101EC000A1BA00BF40240020044B1A68DB68906868 +:101ED0009B68984294BF0020012070474024002056 +:101EE000084B10B51C68D868226853601A6001223C +:101EF000DC602275FFF76EFF01462046BDE810400A +:101F0000FEF780BA4024002038B50123084C002594 +:101F10002370656001F0A6FD01F0CCFD054906487F +:101F200001F05EFE0223237085F3118838BD00BFE7 +:101F3000A8260020884500084024002000F044B96D +:101F4000034A516853685B1A9842FBD8704700BF38 +:101F5000001000E08B600223086108468B82704706 +:101F60008368A3F1840243F8142C026943F8442CDB +:101F7000426943F8402C094A43F8242CC268A3F173 +:101F8000200043F8182C022203F80C2C002203F83E +:101F90000B2C034A43F8102C704700BF1D040008A7 +:101FA0004024002008B5FFF7DBFFBDE80840FFF73D +:101FB00041BF0000024BDB6898610F20FFF73CBF78 +:101FC00040240020302383F31188FFF7F3BF000083 +:101FD00008B50146302383F311880820FFF73AFF44 +:101FE000002383F3118808BD064BDB6839B14268D2 +:101FF00018605A60136043600420FFF72BBF4FF056 +:10200000FF307047402400200368984206D01A68C9 +:102010000260506018469961FFF70CBF70470000DE +:1020200038B504460D462068844200D138BD0368A7 +:1020300023605C608561FFF7FDFEF4E7036810B57F +:102040009C68A2420CD85C688A600B604C6021607E +:10205000596099688A1A9A604FF0FF33836010BD07 +:10206000121B1B68ECE700000A2938BF0A2170B573 +:1020700004460D460A26601901F0EEFC01F0D6FC7C +:10208000041BA54203D8751C04462E46F3E70A2E0E +:1020900004D90120BDE8704001F0E2BD70BD000030 +:1020A000F8B5144B0D460A2A4FF00A07D96103F11F +:1020B0001001826038BF0A2241601969144601602C +:1020C00048601861A81801F0B7FC01F0AFFC431B91 +:1020D0000646A34206D37C1C28192746354601F044 +:1020E000BBFCF2E70A2F04D90120BDE8F84001F05B +:1020F000B7BDF8BD40240020F8B506460D4601F0F6 +:1021000095FC0F4A134653F8107F9F4206D12A468A +:1021100001463046BDE8F840FFF7C2BFD169BB6851 +:10212000441A2C1928BF2C46A34202D92946FFF78E +:102130009BFF224631460348BDE8F840FFF77EBFCB +:102140004024002050240020C0E90323002310B4C1 +:102150005DF8044B4361FFF7CFBF000010B5194C89 +:10216000236998420DD08168D0E9003213605A602B +:102170009A680A449A60002303604FF0FF33A3611A +:1021800010BD0268234643F8102F536000220260FE +:1021900022699A4203D1BDE8104001F057BC936810 +:1021A00081680B44936001F041FC2269E169926807 +:1021B000441AA242E4D91144BDE81040091AFFF7BD +:1021C00053BF00BF402400202DE9F047DFF8BC805A +:1021D00008F110072C4ED8F8105001F027FCD8F861 +:1021E0001C40AA68031B9A423ED814444FF00009D1 +:1021F000D5E90032C8F81C4013605A60C5F8009059 +:10220000D8F81030B34201D101F020FC89F31188D5 +:10221000D5E9033128469847302383F311886B6949 +:10222000002BD8D001F002FC6A69A0EB04098246B9 +:102230004A450DD2022001F013FD0022D8F81030DB +:10224000B34208D151462846BDE8F047FFF728BF02 +:10225000121A2244F2E712EB09092946384638BF20 +:102260004A46FFF7EBFEB5E7D8F81030B34208D086 +:102270001444C8F81C00211AA960BDE8F047FFF714 +:10228000F3BEBDE8F08700BF5024002040240020AA +:1022900000207047FEE70000704700004FF0FF305D +:1022A0007047000002290CD0032904D001290748F7 +:1022B00018BF00207047032A05D8054800EBC2006C +:1022C0007047044870470020704700BF6046000810 +:1022D0003C2200201446000870B59AB00546084616 +:1022E000144601A900F0C2F801A8FEF7C9FD431C7D +:1022F0000022C6B25B001046C5E9003423700323F8 +:10230000023404F8013C01ABD1B202348E4201D850 +:102310001AB070BD13F8011B013204F8010C04F867 +:10232000021CF1E708B5302383F311880348FFF757 +:1023300025FA002383F3118808BD00BFB0260020D2 +:1023400090F8803003F01F02012A07D190F8812015 +:102350000B2A03D10023C0E91D3315E003F060030D +:10236000202B08D1B0F884302BB990F88120212A95 +:1023700003D81F2A04D8FFF7E3B9222AEBD0FAE7E3 +:10238000034A426707228267C3670120704700BF84 +:102390003322002007B5052917D8DFE801F0191608 +:1023A00003191920302383F31188104A0121019069 +:1023B000FFF78CFA019802210D4AFFF787FA0D48C2 +:1023C000FFF7A8F9002383F3118803B05DF804FB3D +:1023D000302383F311880748FFF772F9F2E73023BF +:1023E00083F311880348FFF789F9EBE7B445000848 +:1023F000D8450008B026002038B50C4D0C4C2A46B4 +:102400000C4904F10800FFF767FF05F1CA0204F167 +:1024100010000949FFF760FF05F5CA7204F11800C2 +:102420000649BDE83840FFF757BF00BF883F00208E +:102430003C220020944500089E450008A94500085C +:1024400070B5044608460D46FEF71AFDC6B2204692 +:10245000013403780BB9184670BD32462946FEF7A1 +:10246000FBFC0028F3D10120F6E700002DE9F0473E +:1024700005460C46FEF704FD2B49C6B22846FFF779 +:10248000DFFF08B10636F6B228492846FFF7D8FF25 +:1024900008B11036F6B2632E0BD8DFF88C80DFF867 +:1024A0008C90234FDFF894A02E7846B92670BDE8B3 +:1024B000F08729462046BDE8F04701F0A3BF252E4E +:1024C0002ED1072241462846FEF7C6FC70B9194BAB +:1024D000224603F10C0153F8040B8B4242F8040B23 +:1024E000F9D11B7807350D341370DDE70822494612 +:1024F0002846FEF7B1FC98B9A21C0F4B197802329E +:102500000909C95D02F8041C13F8011B01F00F0151 +:102510005345C95D02F8031CF0D118340835C3E7F0 +:10252000013504F8016BBFE780460008A9450008A3 +:10253000964600088846000800E8F11F0CE8F11FE5 +:10254000BFF34F8F044B1A695107FCD1D3F8102108 +:102550005207F8D1704700BF0020005208B50D4B5C +:102560001B78ABB9FFF7ECFF0B4BDA68D10704D54A +:102570000A4A5A6002F188325A60D3F80C21D20715 +:1025800006D5064AC3F8042102F18832C3F80421B3 +:1025900008BD00BFE641002000200052230167452E +:1025A00008B5114B1B78F3B9104B1A69510703D5C5 +:1025B000DA6842F04002DA60D3F81021520705D5FC +:1025C000D3F80C2142F04002C3F80C21FFF7B8FF0A +:1025D000064BDA6842F00102DA60D3F80C2142F0CF +:1025E0000102C3F80C2108BDE64100200020005282 +:1025F0000F289ABF00F5806040040020704700005B +:102600004FF4003070470000102070470F2808B5C5 +:102610000BD8FFF7EDFF00F500330268013204D15B +:1026200004308342F9D1012008BD0020FCE70000FE +:102630000F2838B505463FD8FFF782FF1F4CFFF73C +:102640008DFF4FF0FF3307286361C4F814311DD8A4 +:102650002361FFF775FF030243F02403E360E3689F +:1026600043F08003E36023695A07FCD42846FFF750 +:1026700067FFFFF7BDFF4FF4003100F0B3F92846C4 +:10268000FFF78EFFBDE83840FFF7C0BFC4F8103138 +:10269000FFF756FFA0F108031B0243F02403C4F820 +:1026A0000C31D4F80C3143F08003C4F80C31D4F869 +:1026B00010315B07FBD4D9E7002038BD0020005261 +:1026C0002DE9F84F05460C46104645EA0203DE06A2 +:1026D00002D00020BDE8F88F20F01F00DFF8BCB06A +:1026E000DFF8BCA0FFF73AFF04EB0008444503D134 +:1026F0000120FFF755FFEDE720222946204601F093 +:1027000071FE10B920352034F0E72B4605F1200288 +:102710001F68791CDDD104339A42F9D105F1784361 +:102720001B481C4EB3F5801F1B4B38BF184603F1E6 +:10273000F80332BFD946D1461E46FFF701FF0760B6 +:10274000A5EB040C336804F11C0143F00203336071 +:10275000231FD9F8007017F00507FAD153F8042F9A +:102760008B424CF80320F4D1BFF34F8FFFF7E8FE04 +:102770004FF0FF332022214603602846336823F0C0 +:102780000203336001F02EFE0028BBD03846B0E7CC +:10279000142100520C20005214200052102000522C +:1027A0001021005210B5084C237828B11BB9FFF74F +:1027B000D5FE0123237010BD002BFCD02070BDE896 +:1027C0001040FFF7EDBE00BFE64100202DE9F04FBD +:1027D0000D4685B0814658B111F00D0614BF202278 +:1027E000082211F00803019304D0431E03426AD06B +:1027F000002435E0002E37D009F11F0121F01F0918 +:102800004FF00108324F05F00403DFF8D0A005EACD +:10281000080BBBF1000F32D07869C0072FD408F144 +:1028200001080C37B8F1060FF3D19EB9294D49467E +:10283000A819019201F060F9044600283AD118362F +:10284000019A782EF3D1494601F056F90446002842 +:1028500030D1019A4946204801F04EF9044668BB40 +:10286000204605B0BDE8F08F0029C9D101462846B1 +:10287000029201F041F90446E0B9029AC0E713B1AF +:1028800078694107CBD5AC0702D578698007C6D5F2 +:10289000019911B178690107C1D51820494600FB9B +:1028A00008A0CDE9022301F027F90446DDE902235F +:1028B0000028B4D04A460021204601E04A460021C3 +:1028C000FEF7E6FACCE70246002E95D198E700BF66 +:1028D000A846000818420020E841002000420020DD +:1028E0000121FFF773BF0000F8B5144D012418272C +:1028F000134E40F2FF3200210120FEF7C9FA07FB18 +:10290000046001342A6955F80C1F01F0E1F8062C27 +:10291000F5D137254FF4C0542046FFF7E1FF0146BB +:1029200028B122460748BDE8F84001F0D1B8C4EB11 +:10293000C404013D4FEAD404EED1F8BDA846000816 +:1029400000420020E84100200244074BD2B210B5FB +:10295000904200D110BD441C00B253F8200041F851 +:10296000040BE0B2F4E700BF504000580E4B30B506 +:102970001C6F240405D41C6F1C671C6F44F40044B6 +:102980001C670A4C02442368D2B243F4807323606C +:10299000074B904200D130BD441C51F8045B00B29B +:1029A00043F82050E0B2F4E70044025800480258CF +:1029B0005040005807B5012201A90020FFF7C4FFCD +:1029C000019803B05DF804FB13B50446FFF7F2FF6E +:1029D000A04205D0012201A900200194FFF7C6FF03 +:1029E00002B010BD0144BFF34F8F064B884204D3A1 +:1029F000BFF34F8FBFF36F8F7047C3F85C02203077 +:102A0000F4E700BF00ED00E0034B1A681AB9034A6F +:102A1000D2F8D0241A60704790420020004002583B +:102A200008B5FFF7F1FF024B1868C0F3806008BDDE +:102A300090420020EFF30983054968334A6B22F086 +:102A400001024A6383F30988002383F311887047E6 +:102A500000EF00E0302080F3118862B60D4B0E4A83 +:102A6000D96821F4E0610904090C0A430B49DA60D2 +:102A7000D3F8FC2042F08072C3F8FC20084AC2F868 +:102A8000B01F116841F0010111602022DA7783F84C +:102A90002200704700ED00E00003FA0555CEACC5FA +:102AA000001000E0302310B583F311880E4B5B68F3 +:102AB00013F4006314D0F1EE103AEFF309844FF0F1 +:102AC0008073683CE361094BDB6B236684F3098800 +:102AD000FFF7FAF910B1064BA36110BD054BFBE7F8 +:102AE00083F31188F9E700BF00ED00E000EF00E09C +:102AF0002F0400083204000870B5BFF34F8FBFF3F6 +:102B00006F8F1A4A0021C2F85012BFF34F8FBFF3E4 +:102B10006F8F536943F400335361BFF34F8FBFF39B +:102B20006F8FC2F88410BFF34F8FD2F8803043F616 +:102B3000E074C3F3C900C3F34E335B0103EA040638 +:102B4000014646EA81750139C2F86052F9D2203B4C +:102B500013F1200FF2D1BFF34F8F536943F4803349 +:102B60005361BFF34F8FBFF36F8F70BD00ED00E077 +:102B7000FEE70000214B2248224A70B5904237D32D +:102B8000214BC11EDA1C121A22F003028B4238BFFD +:102B900000220021FEF77CF91C4A0023C2F8843091 +:102BA000BFF34F8FD2F8803043F6E074C3F3C9000F +:102BB000C3F34E335B0103EA0406014646EA81751E +:102BC0000139C2F86C52F9D2203B13F1200FF2D137 +:102BD000BFF34F8FBFF36F8FBFF34F8FBFF36F8F75 +:102BE0000023C2F85032BFF34F8FBFF36F8F70BD19 +:102BF00053F8041B40F8041BC0E700BFCC48000892 +:102C000084440020844400208444002000ED00E03F +:102C1000074BD3F8D81021EA0001C3F8D810D3F835 +:102C2000002122EA0002C3F80021D3F800317047E6 +:102C30000044025870B5D0E9244300224FF0FF351C +:102C40009E6804EB42135101D3F80009002805DA0D +:102C5000D3F8000940F08040C3F80009D3F8000B16 +:102C6000002805DAD3F8000B40F08040C3F8000BD1 +:102C7000013263189642C3F80859C3F8085BE0D2E2 +:102C80004FF00113C4F81C3870BD0000890141F0F9 +:102C90002001016103699B06FCD41220FFF750B9A3 +:102CA00010B50A4C2046FEF7EFFD094BC4F89030F2 +:102CB000084BC4F89430084C2046FEF7E5FD074B5E +:102CC000C4F89030064BC4F8943010BD94420020F4 +:102CD0000000084014470008304300200000044072 +:102CE0002047000870B503780546012B5CD1434BA3 +:102CF000D0F89040984258D1414B0E216520D3F82E +:102D0000D82042F00062C3F8D820D3F8002142F066 +:102D10000062C3F80021D3F80021D3F8802042F0EC +:102D20000062C3F88020D3F8802022F00062C3F84C +:102D30008020D3F88030FEF7D3FB324BE360324B78 +:102D4000C4F800380023D5F89060C4F8003EC023D2 +:102D500023604FF40413A3633369002BFCDA0123CF +:102D60000C203361FFF7ECF83369DB07FCD4122049 +:102D7000FFF7E6F83369002BFCDA00262846A66048 +:102D8000FFF758FF6B68C4F81068DB68C4F8146874 +:102D9000C4F81C6883BB1D4BA3614FF0FF33636114 +:102DA000A36843F00103A36070BD194B9842C9D1D9 +:102DB000134B4FF08060D3F8D82042F00072C3F874 +:102DC000D820D3F8002142F00072C3F80021D3F8D4 +:102DD0000021D3F8802042F00072C3F88020D3F89D +:102DE000802022F00072C3F88020D3F88030FFF7F3 +:102DF0000FFF0E214D209EE7064BCDE794420020A9 +:102E0000004402584014004003002002003C30C03F +:102E100030430020083C30C0F8B5D0F8904005465B +:102E200000214FF000662046FFF730FFD5F89410E0 +:102E300000234FF001128F684FF0FF30C4F8343890 +:102E4000C4F81C2804EB431201339F42C2F8006906 +:102E5000C2F8006BC2F80809C2F8080BF2D20B687E +:102E6000D5F89020C5F89830636210231361166975 +:102E700016F01006FBD11220FFF762F8D4F80038E4 +:102E800023F4FE63C4F80038A36943F4402343F0FD +:102E90001003A3610923C4F81038C4F814380B4B8D +:102EA000EB604FF0C043C4F8103B094BC4F8003B43 +:102EB000C4F81069C4F80039D5F8983003F110024D +:102EC00043F48013C5F89820A362F8BDF0460008CB +:102ED00040800010D0F8902090F88A10D2F8003886 +:102EE00023F4FE6343EA0113C2F800387047000080 +:102EF0002DE9F84300EB8103D0F890500C46804652 +:102F0000DA680FFA81F94801166806F00306731EA5 +:102F1000022B05EB41134FF0000194BFB604384E6D +:102F2000C3F8101B4FF0010104F1100398BF06F124 +:102F3000805601FA03F3916998BF06F5004600290F +:102F40003AD0578A04F15801374349016F50D5F8F8 +:102F50001C180B430021C5F81C382B180127C3F897 +:102F60001019A7405369611E9BB3138A928B9B086B +:102F7000012A88BF5343D8F89820981842EA03439F +:102F800001F140022146C8F89800284605EB82026C +:102F90005360FFF77BFE08EB8900C3681B8A43EA96 +:102FA000845348341E4364012E51D5F81C381F4306 +:102FB000C5F81C78BDE8F88305EB4917D7F8001B66 +:102FC00021F40041C7F8001BD5F81C1821EA0303BF +:102FD000C0E704F13F030B4A2846214605EB830373 +:102FE0005A60FFF753FE05EB4910D0F8003923F47F +:102FF0000043C0F80039D5F81C3823EA0707D7E7A3 +:103000000080001000040002D0F894201268C0F87C +:103010009820FFF70FBE00005831D0F890304901DA +:103020005B5813F4004004D013F4001F0CBF0220BF +:10303000012070474831D0F8903049015B5813F4B3 +:10304000004004D013F4001F0CBF02200120704781 +:1030500000EB8101CB68196A0B6813604B68536001 +:103060007047000000EB810330B5DD68AA69136882 +:10307000D36019B9402B84BF402313606B8A146856 +:10308000D0F890201C4402EB4110013C09B2B4FB83 +:10309000F3F46343033323F0030343EAC44343F0ED +:1030A000C043C0F8103B2B6803F00303012B0ED183 +:1030B000D2F8083802EB411013F4807FD0F8003BBF +:1030C00014BF43F0805343F00053C0F8003B02EBC1 +:1030D0004112D2F8003B43F00443C2F8003B30BD3C +:1030E0002DE9F041D0F8906005460C4606EB4113FF +:1030F000D3F8087B3A07C3F8087B08D5D6F814380C +:103100001B0704D500EB8103DB685B689847FA076F +:103110001FD5D6F81438DB071BD505EB8403D96817 +:10312000CCB98B69488A5A68B2FBF0F600FB1622CC +:103130008AB91868DA6890420DD2121AC3E90024DD +:10314000302383F3118821462846FFF78BFF84F351 +:103150001188BDE8F081012303FA04F26B8923EAA8 +:1031600002036B81CB68002BF3D021462846BDE8D3 +:10317000F041184700EB81034A0170B5DD68D0F8D3 +:1031800090306C692668E66056BB1A444FF4002004 +:10319000C2F810092A6802F00302012A0AB20ED10D +:1031A000D3F8080803EB421410F4807FD4F8000928 +:1031B00014BF40F0805040F00050C4F8000903EB09 +:1031C0004212D2F8000940F00440C2F8000901227E +:1031D000D3F8340802FA01F10143C3F8341870BD82 +:1031E00019B9402E84BF4020206020681A442E8ADE +:1031F0008419013CB4FBF6F440EAC44040F00050AE +:10320000C6E700002DE9F843D0F8906005460C466B +:103210004F0106EB4113D3F8088918F0010FC3F8EA +:1032200008891CD0D6F81038DB0718D500EB8103CD +:10323000D3F80CC0DCF81430D3F800E0DA68964517 +:1032400030D2A2EB0E024FF000091A60C3F80490CE +:10325000302383F31188FFF78DFF89F3118818F06D +:10326000800F1DD0D6F834380126A640334217D03F +:1032700005EB84030134D5F89050D3F80CC0E4B2C8 +:103280002F44DCF8142005EB0434D2F800E0516838 +:10329000714514D3D5F8343823EA0606C5F83468E6 +:1032A000BDE8F883012303FA01F2038923EA02034C +:1032B0000381DCF80830002BD1D09847CFE7AEEB84 +:1032C0000103BCF81000834228BF0346D7F8180951 +:1032D00080B2B3EB800FE3D89068A0F1040959F8ED +:1032E000048FC4F80080A0EB09089844B8F1040FDB +:1032F000F5D818440B4490605360C8E72DE9F84FA7 +:10330000D0F8905004466E69AB691E4016F48058A0 +:103310006E6103D0BDE8F84FFEF726BB002E12DA2F +:10332000D5F8003E9B0705D0D5F8003E23F00303F7 +:10333000C5F8003ED5F80438204623F00103C5F84F +:103340000438FEF73FFB370505D52046FFF772FC32 +:103350002046FEF725FBB0040CD5D5F8083813F04D +:10336000060FEB6823F470530CBF43F4105343F47F +:10337000A053EB6031071BD56368DB681BB9AB69F1 +:1033800023F00803AB612378052B0CD1D5F8003E60 +:103390009A0705D0D5F8003E23F00303C5F8003E98 +:1033A0002046FEF70FFB6368DB680BB120469847A9 +:1033B000F30200F1BA80B70226D5D4F89090002726 +:1033C0004FF0010A09EB4712D2F8003B03F4402307 +:1033D000B3F5802F11D1D2F8003B002B0DDA6289B2 +:1033E0000AFA07F322EA0303638104EB8703DB682D +:1033F000DB6813B13946204698470137D4F894303A +:10340000FFB29B689F42DDD9F00619D5D4F8900031 +:10341000026AC2F30A1702F00F0302F4F012B2F5C7 +:10342000802F00F0CA80B2F5402F09D104EB83034E +:10343000002200F58050DB681B6A974240F0B080A4 +:103440003003D5F8185835D5E90303D500212046B7 +:10345000FFF746FEAA0303D501212046FFF740FEF1 +:103460006B0303D502212046FFF73AFE2F0303D555 +:1034700003212046FFF734FEE80203D5042120464D +:10348000FFF72EFEA90203D505212046FFF728FEEF +:103490006A0203D506212046FFF722FE2B0203D540 +:1034A00007212046FFF71CFEEF0103D50821204627 +:1034B000FFF716FE700340F1A780E90703D500214E +:1034C0002046FFF79FFEAA0703D501212046FFF7FC +:1034D00099FE6B0703D502212046FFF793FE2F07C5 +:1034E00003D503212046FFF78DFEEE0603D5042108 +:1034F0002046FFF787FEA80603D505212046FFF7E3 +:1035000081FE690603D506212046FFF77BFE2A06C9 +:1035100003D507212046FFF775FEEB0574D520463D +:103520000821BDE8F84FFFF76DBED4F890904FF03A +:10353000000B4FF0010AD4F894305FFA8BF79B68C8 +:103540009F423FF638AF09EB4713D3F8002902F446 +:103550004022B2F5802F20D1D3F80029002A1CDAAE +:10356000D3F8002942F09042C3F80029D3F800298B +:10357000002AFBDB3946D4F89000FFF787FB22894D +:103580000AFA07F322EA0303238104EB8703DB68CB +:103590009B6813B13946204698470BF1010BCAE7E7 +:1035A000910701D1D0F80080072A02F101029CBFE7 +:1035B00003F8018B4FEA18283FE704EB830300F57B +:1035C0008050DA68D2F818C0DCF80820DCE9001C6A +:1035D000A1EB0C0C00218F4208D1DB689B699A6833 +:1035E0003A449A605A683A445A6029E711F0030F46 +:1035F00001D1D0F800808C4501F1010184BF02F8AF +:10360000018B4FEA1828E6E7BDE8F88F08B50348B4 +:10361000FFF774FEBDE80840FFF744BA944200206B +:1036200008B50348FFF76AFEBDE80840FFF73ABA5D +:1036300030430020D0F8903003EB4111D1F8003B2B +:1036400043F40013C1F8003B70470000D0F89030FD +:1036500003EB4111D1F8003943F40013C1F80039EC +:1036600070470000D0F8903003EB4111D1F8003BD7 +:1036700023F40013C1F8003B70470000D0F89030ED +:1036800003EB4111D1F8003923F40013C1F80039DC +:103690007047000030B50433039C0172002104FB25 +:1036A0000325C160C0E90653049B0363059BC0E981 +:1036B0000000C0E90422C0E90842C0E90A114363DE +:1036C00030BD00000022416AC260C0E90411C0E9B7 +:1036D0000A226FF00101FEF7A3BC0000D0E904321A +:1036E000934201D1C2680AB9181D70470020704783 +:1036F000036919600021C2680132C260C2691344C3 +:1037000082699342036124BF436A0361FEF77CBC74 +:1037100038B504460D46E3683BB162690020131DCD +:103720001268A3621344E36207E0237A33B929469F +:103730002046FEF759FC0028EDDA38BD6FF0010095 +:10374000FBE70000C368C269013BC36043691344DF +:1037500082699342436124BF436A436100238362C9 +:10376000036B03B11847704770B53023044683F3E9 +:103770001188866A3EB9FFF7CBFF054618B186F37C +:103780001188284670BDA36AE26A13F8015B934270 +:10379000A36202D32046FFF7D5FF002383F31188ED +:1037A000EFE700002DE9F84F04460E46174698460D +:1037B0004FF0300989F311880025AA46D4F828B0C3 +:1037C000BBF1000F09D141462046FFF7A1FF20B110 +:1037D0008BF311882846BDE8F88FD4E90A12A7EBCD +:1037E000050B521A934528BF9346BBF1400F1BD9D6 +:1037F000334601F1400251F8040B914243F8040BA7 +:10380000F9D1A36A403640354033A362D4E90A2394 +:103810009A4202D32046FFF795FF8AF31188BD42F2 +:10382000D8D289F31188C9E730465A46FDF70AFB1A +:10383000A36A5E445D445B44A362E7E710B5029C63 +:103840000433017203FB0421C460C0E906130023A2 +:10385000C0E90A33039B0363049BC0E90000C0E98D +:103860000422C0E90842436310BD0000026A6FF001 +:103870000101C260426AC0E904220022C0E90A22B2 +:10388000FEF7CEBBD0E904239A4201D1C26822B927 +:10389000184650F8043B0B60704700231846FAE7BF +:1038A000C3680021C2690133C3604369134482695C +:1038B0009342436124BF436A4361FEF7A5BB000006 +:1038C00038B504460D46E3683BB1236900201A1D54 +:1038D000A262E2691344E36207E0237A33B929461E +:1038E0002046FEF781FB0028EDDA38BD6FF00100BD +:1038F000FBE7000003691960C268013AC260C2694F +:10390000134482699342036124BF436A0361002325 +:103910008362036B03B118477047000070B5302312 +:103920000D460446114683F31188866A2EB9FFF7C7 +:10393000C7FF10B186F3118870BDA36A1D70A36A1A +:10394000E26A01339342A36204D3E1692046043959 +:10395000FFF7D0FF002080F31188EDE72DE9F84F45 +:1039600004460D46904699464FF0300A8AF3118876 +:103970000026B346A76A4FB949462046FFF7A0FF85 +:1039800020B187F311883046BDE8F88FD4E90A07E3 +:103990003A1AA8EB0607974228BF1746402F1BD9B3 +:1039A00005F1400355F8042B9D4240F8042BF9D152 +:1039B000A36A40364033A362D4E90A239A4204D36F +:1039C000E16920460439FFF795FF8BF311884645DE +:1039D000D9D28AF31188CDE729463A46FDF732FA63 +:1039E000A36A3D443E443B44A362E5E7D0E9042397 +:1039F0009A4217D1C3689BB1836A8BB1043B9B1A6F +:103A00000ED01360C368013BC360C3691A44836965 +:103A10009A42026124BF436A036100238362012347 +:103A2000184670470023FBE700F01EBA014B586AA6 +:103A3000704700BF000C0040034B002258631A611E +:103A40000222DA60704700BF000C0040014B0022E8 +:103A5000DA607047000C0040014B5863704700BFAC +:103A6000000C0040024B034A1A60034A5A60704738 +:103A7000E44300208844002000000220074B494214 +:103A800010B55C68201A08401968821A8A4203D36C +:103A9000A24201D85A6010BD0020FCE7E443002098 +:103AA00008B5302383F31188FFF7E8FF002383F381 +:103AB000118808BD04480121044B03600023C0E9BC +:103AC00001330C3000F0D4B8EC430020A13A0008D8 +:103AD000CB1D083A23F00703591A521A012110B4DA +:103AE000D2080024C0E9004384600C301C605A6096 +:103AF0005DF8044B00F0BCB82DE9F84F364ECD1DF3 +:103B00000F46002818BF0646082A4FEAD50538BFD9 +:103B1000082206F10C08341D9146404600F0C4F816 +:103B200009F10701C9F1000E224624686CB940462C +:103B300000F0C4F83368CBB308224946E800984740 +:103B4000044698B340E9026730E004EB010CD4F876 +:103B500004A00CEA0E0C0AF10100ACF1080304EB1E +:103B6000C0009842E0D9A0EB0C0CB5EBEC0F4FEA8B +:103B7000EC0BD9D89C421CD204F10802AB45A3EB54 +:103B800002024FEAE202626009D9691CED43206833 +:103B900003EBC1025D44556043F8310022601C46CE +:103BA0005F60404644F8086B00F088F82046BDE8A6 +:103BB000F88FAA45216802D111602346EFE701354D +:103BC00004EBC50344F8351003F10801401AC01096 +:103BD00058601360F1E700BFEC430020FEE70000EF +:103BE00070B51B4B0025044686B058600E468562B2 +:103BF0000163FEF72FFF04F11003A560E562C4E93D +:103C000004334FF0FF33C4E90044C4E90635FFF73D +:103C10000DFF2B46024604F134012046C4E9082377 +:103C200080230C4A2565FEF795F901230A4AE060D6 +:103C300000920375684672680192B268CDE902236A +:103C4000064BCDE90435FEF7ADF906B070BD00BFF7 +:103C5000A82600202C47000831470008DD3B00085B +:103C6000024AD36A1843D062704700BF4024002044 +:103C7000C0E90000816070478368013B002B10B5EC +:103C800083600CDA074BDC684368A06120606360E6 +:103C90001C6044600520FEF7CFF8A06910BD00202D +:103CA000FCE700BF4024002008B5302383F31188CF +:103CB000FFF7E2FF002383F3118808BD08B5302326 +:103CC00083F3118883680133002B836007DC03686A +:103CD00000211A68026050601846FEF7D9F80023E8 +:103CE00083F3118808BD00004B6843608B688360D4 +:103CF000CB68C3600B6943614B6903628B694362A4 +:103D00000B6803607047000008B53C4B40F2FF7140 +:103D10003B48D3F888200A43C3F88820D3F888208A +:103D200022F4FF6222F00702C3F88820D3F888202B +:103D3000D3F8E0200A43C3F8E020D3F808210A436F +:103D4000C3F808212F4AD3F808311146FFF7CCFFFA +:103D500000F5806002F11C01FFF7C6FF00F58060EE +:103D600002F13801FFF7C0FF00F5806002F1540155 +:103D7000FFF7BAFF00F5806002F17001FFF7B4FFB2 +:103D800000F5806002F18C01FFF7AEFF00F5806066 +:103D900002F1A801FFF7A8FF00F5806002F1C4015D +:103DA000FFF7A2FF00F5806002F1E001FFF79CFF42 +:103DB00000F5806002F1FC01FFF796FF02F58C71BF +:103DC00000F58060FFF790FF00F01AF90E4BD3F872 +:103DD000902242F00102C3F89022D3F8942242F0DC +:103DE0000102C3F894220522C3F898204FF06052D4 +:103DF000C3F89C20054AC3F8A02008BD004402581F +:103E0000000002583847000800ED00E01F000803DA +:103E100008B500F0C9FAFEF777F8104BD3F8DC20AC +:103E200042F04002C3F8DC20D3F8042122F0400223 +:103E3000C3F80421D3F80431094B1A6842F0080290 +:103E40001A601A6842F004021A60FEF7DDFDFEF700 +:103E50004BFDBDE80840FEF7CFBA00BF0044025852 +:103E60000018024870470000114BD3F8E82042F0D8 +:103E70000802C3F8E820D3F8102142F00802C3F882 +:103E800010210C4AD3F81031D36B43F00803D363ED +:103E9000C722094B9A624FF0FF32DA6200229A6120 +:103EA0005A63DA605A6001225A611A60704700BF93 +:103EB000004402580010005C000C0040094A08B59C +:103EC0001169D3680B40D9B29B076FEA01011161F8 +:103ED00007D5302383F31188FEF730F8002383F3EE +:103EE000118808BD000C0040064BD3F8DC200243CB +:103EF000C3F8DC20D3F804211043C3F80401D3F83D +:103F0000043170470044025808B53C4B4FF0FF3174 +:103F1000D3F8802062F00042C3F88020D3F88020DC +:103F200002F00042C3F88020D3F88020D3F8842028 +:103F3000C3F88410D3F884200022C3F88420D3F877 +:103F40008400D86F40F0FF4040F4FF0040F4DF40B1 +:103F500040F07F00D867D86F20F0FF4020F4FF00CA +:103F600020F4DF4020F07F00D867D86FD3F88800B6 +:103F70006FEA40506FEA5050C3F88800D3F88800C9 +:103F8000C0F30A00C3F88800D3F88800D3F8900083 +:103F9000C3F89010D3F89000C3F89020D3F89000A5 +:103FA000D3F89400C3F89410D3F89400C3F8942085 +:103FB000D3F89400D3F89800C3F89810D3F8980079 +:103FC000C3F89820D3F89800D3F88C00C3F88C106D +:103FD000D3F88C00C3F88C20D3F88C00D3F89C0065 +:103FE000C3F89C10D3F89C10C3F89C20D3F89C30E5 +:103FF000FDF79AF9BDE8084000F0AEB90044025858 +:1040000008B50122534BC3F80821534BD3F8F420D1 +:1040100042F00202C3F8F420D3F81C2142F002025D +:10402000C3F81C210222D3F81C314C4BDA605A68C9 +:104030009104FCD54A4A1A6001229A60494ADA6022 +:1040400000221A614FF440429A61444B9A699204EB +:10405000FCD51A6842F480721A603F4B1A6F12F452 +:10406000407F04D04FF480321A6700221A671A6822 +:1040700042F001021A60384B1A685007FCD5002242 +:104080001A611A6912F03802FBD1012119604FF050 +:10409000804159605A67344ADA62344A1A611A68B0 +:1040A00042F480321A602C4B1A689103FCD51A68CE +:1040B00042F480521A601A689204FCD52C4A2D49A9 +:1040C0009A6200225A63196301F57C01DA6301F2F6 +:1040D000E71199635A64284A1A64284ADA621A680E +:1040E00042F0A8521A601C4B1A6802F02852B2F132 +:1040F000285FF9D148229A614FF48862DA61402240 +:104100001A621F4ADA641F4A1A651F4A5A651F4A13 +:104110009A6532231E4A1360136803F00F03022BC3 +:10412000FAD10D4A136943F003031361136903F0D5 +:104130003803182BFAD14FF00050FFF7D5FE4FF09F +:104140008040FFF7D1FE4FF00040BDE80840FFF788 +:10415000CBBE00BF00800051004402580048025806 +:1041600000C000F0020000010000FF01008890087C +:104170001210200063020901470E0508DD0BBF0184 +:1041800020000020000001100910E00000010110D3 +:10419000002000524FF0B04208B5D2F8883003F04A +:1041A0000103C2F8883023B1044A13680BB1506888 +:1041B0009847BDE80840FEF775BC00BF04440020E6 +:1041C0004FF0B04208B5D2F8883003F00203C2F8CD +:1041D000883023B1044A93680BB1D0689847BDE892 +:1041E0000840FEF75FBC00BF044400204FF0B0421F +:1041F00008B5D2F8883003F00403C2F8883023B140 +:10420000044A13690BB150699847BDE80840FEF7AE +:1042100049BC00BF044400204FF0B04208B5D2F8BA +:10422000883003F00803C2F8883023B1044A936948 +:104230000BB1D0699847BDE80840FEF733BC00BF1A +:10424000044400204FF0B04208B5D2F8883003F0A3 +:104250001003C2F8883023B1044A136A0BB1506AC4 +:104260009847BDE80840FEF71DBC00BF044400208D +:104270004FF0B04310B5D3F8884004F47872C3F817 +:104280008820A30604D5124A936A0BB1D06A9847D6 +:10429000600604D50E4A136B0BB1506B984721068C +:1042A00004D50B4A936B0BB1D06B9847E20504D54C +:1042B000074A136C0BB1506C9847A30504D5044A08 +:1042C000936C0BB1D06C9847BDE81040FEF7EABB89 +:1042D000044400204FF0B04310B5D3F8884004F4F4 +:1042E0007C42C3F88820620504D5164A136D0BB1D1 +:1042F000506D9847230504D5124A936D0BB1D06DCC +:104300009847E00404D50F4A136E0BB1506E9847DE +:10431000A10404D50B4A936E0BB1D06E984762048A +:1043200004D5084A136F0BB1506F9847230404D586 +:10433000044A936F0BB1D06F9847BDE81040FEF769 +:10434000B1BB00BF0444002008B5FFF7B7FDBDE8CE +:104350000840FEF7A7BB0000062108B50846FDF798 +:10436000BFF806210720FDF7BBF806210820FDF75E +:10437000B7F806210920FDF7B3F806210A20FDF75A +:10438000AFF806211720FDF7ABF806212820FDF72E +:10439000A7F809217A20FDF7A3F807213220BDE80C +:1043A0000840FDF79DB8000008B5FFF7ADFD00F02F +:1043B0000BF8FDF767FAFDF739F9FFF753FDBDE894 +:1043C0000840FFF731BB00000023054A19460133BE +:1043D000102BC2E9001102F10802F8D1704700BFAA +:1043E0000444002010B501390244904201D100205C +:1043F00005E0037811F8014FA34201D0181B10BD4E +:104400000130F2E7034611F8012B03F8012B002AD3 +:10441000F9D1704753544D333248373F3F3F005333 +:10442000544D3332483733782F3732780053544D58 +:104430003332483734332F3735332F373530000098 +:1044400001105A00031059000120580003205600A3 +:1044500010000240080002400008024000000B006B +:1044600028000240080002400408024006010C0037 +:1044700040000240080002400808024010020D00FF +:1044800058000240080002400C08024016030E00CB +:10449000700002400C0002401008024000040F00AF +:1044A000880002400C00024014080240060510007B +:1044B000A00002400C000240180802401006110043 +:1044C000B80002400C0002401C08024016072F00F2 +:1044D000100402400804024020080240000838008E +:1044E000280402400804024024080240060939005A +:1044F000400402400804024028080240100A3A0022 +:1045000058040240080402402C080240160B3B00ED +:10451000700402400C04024030080240000C3C00D1 +:10452000880402400C04024034080240060D440096 +:10453000A00402400C04024038080240100E45005E +:10454000B80402400C0402403C080240160F46002A +:1045500000000000A915000895150008D1150008F5 +:10456000BD150008C9150008B5150008A1150008FB +:104570008D150008DD150008000000000100000096 +:1045800000000000633000008445000898240020EB +:10459000A82600204172647550696C6F7400254232 +:1045A0004F415244252D424C002553455249414C20 +:1045B000250000000200000000000000C9170008EC +:1045C0003918000840004000583F0020683F002094 +:1045D00002000000000000000300000000000000D6 +:1045E000811800080000000010000000783F002043 +:1045F00000000000010000000000000094420020C4 +:104600000101020095230008A522000841230008AB +:1046100025230008430000001C460008090243004F +:10462000020100C032090400000102020100052459 +:1046300000100105240100010424020205240600E3 +:1046400001070582030800FF09040100020A0000B7 +:10465000000705010240000007058102400000003C +:10466000120000006846000812011001020000401C +:10467000091241570002010203010000040309046A +:1046800025424F4152442500466C79776F6F483779 +:10469000343350726F003031323334353637383975 +:1046A0004142434445460000000000200000020053 +:1046B00002000000000000300000040008000000BC +:1046C00000000024000008000400000000040000B6 +:1046D00000FC000002000000000004300080000028 +:1046E0000800000000000038000001000100000088 +:1046F00000000000DD190008951C0008411D00089D +:1047000040004000CC430020CC43002001000000CA +:10471000DC43002080000000400100000800000091 +:104720000001000000100000080000006D61696ECB +:104730000069646C650000000000802A0000000031 +:10474000AAAAAAAA00000024FFFF0000000000009F +:1047500000A00A000000000100000000AAAAAAAA06 +:1047600000000001FFFF000000000000000000004A +:104770000000004000000000AAAAAAAA0000004011 +:10478000FFFF0000000000000000000000005000DB +:1047900000000000AAAAAAAA00000000FFFF000073 +:1047A0000000000000000000400040000000000089 +:1047B000AAAAAAAA00004000F7FF0000000000001B +:1047C000000000000000000000000000AAAAAAAA41 +:1047D00000000000FFFF00000000000000000000DB +:1047E0000000000000000000AAAAAAAA0000000021 +:1047F000FFFF0000000000000000000000000000BB +:1048000000000000AAAAAAAA00000000FFFF000002 +:104810000000000000000000000000000000000098 +:10482000AAAAAAAA00000000FFFF000000000000E2 +:10483000000000000000000000000000AAAAAAAAD0 +:1048400000000000FFFF000000000000000000006A +:104850000000000000000000AAAAAAAA00000000B0 +:10486000FFFF00000000000000000000000000004A +:104870009D0400000000000000001A00000000007D +:10488000FF00000000000000144400088304000042 +:104890001F440008500400002D440008009600004A +:1048A000000008009600000000080000040000005E +:1048B0007C4600080000000000000000000000002E +:0C48C000000000000000000000000000EC +:00000001FF diff --git a/Tools/bootloaders/GEPRCF745BTHD_bl.bin b/Tools/bootloaders/GEPRCF745BTHD_bl.bin new file mode 100755 index 00000000000000..f22488d4072a44 Binary files /dev/null and b/Tools/bootloaders/GEPRCF745BTHD_bl.bin differ diff --git a/Tools/bootloaders/GEPRCF745BTHD_bl.hex b/Tools/bootloaders/GEPRCF745BTHD_bl.hex new file mode 100644 index 00000000000000..0e3e28b66ea5a9 --- /dev/null +++ b/Tools/bootloaders/GEPRCF745BTHD_bl.hex @@ -0,0 +1,930 @@ +:020000040800F2 +:1000000000060120010200080302000803020008A4 +:1000100003020008030200080302000803020008AC +:1000200003020008030200080302000899310008D7 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:100050000302000803020008413400086934000864 +:1000600091340008B9340008E134000803020008A4 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:1000900003020008030200080302000809350008F3 +:1000A000030200080302000803020008030200081C +:1000B000DD350008030200080302000803020008FF +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E0006D3500080302000803020008030200083F +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200080D2900084A +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F01F0A8FFA9 +:1002700002F024FF4FF055301F491B4A91423CBF0A +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE701F0C0FF02F05EFF1B +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E701F0A8BF00060120002201209D +:1002F0000000000808ED00E00000012000060120D9 +:1003000098390008002201205C220120602201208F +:10031000882E0120000200080002000800020008E8 +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F0E4FAFEE701F0FA +:100350006DFA00DFFEE7000038B500F011FC01F097 +:10036000EFFE054601F022FF0446C8B90E4B9D4240 +:1003700018D001339D4218BF044641F2883504BFAE +:1003800001240025002001F0E5FE0CB100F076F814 +:1003900000F05EFD284600F0FDF800F06FF8F9E788 +:1003A0000025EFE70546EDE7010007B008B500F0CE +:1003B000B9FBA0F120035842584108BD07B541F2EE +:1003C0001203022101A8ADF8043000F0C9FB03B00C +:1003D0005DF804FB38B572B6302383F3118862B63A +:1003E000174803680BB101F063FB164A1448002359 +:1003F0004FF47A7101F052FB002383F31188124C01 +:10040000236813B12368013B2360636813B16368F9 +:10041000013B63600D4D2B7833B963687BB90220D3 +:1004200000F080FC322363602B78032B07D16368D4 +:100430002BB9022000F076FC4FF47A73636038BD6C +:1004400060220120D50300088023012078220120AA +:10045000084B187003280CD8DFE800F008050208E4 +:10046000022000F055BC022000F048BC024B0022E4 +:100470005A6070477822012080230120F8B5404B54 +:10048000404A1C461968013179D004339342F9D1AE +:100490006268A24273D33C4B9B6803F1006303F58F +:1004A000C0339A426BD2002000F084FB0220FFF799 +:1004B000CFFF364B00211A6C19641A6E19661A6E3A +:1004C0005A6C59645A6E59665A6E5A6942F08002E3 +:1004D0005A615A6922F080025A615A691A6942F0D7 +:1004E00000521A611A6922F000521A611B6972B631 +:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 +:10050000BFF36F8F224AC2F88410BFF34F8F536935 +:1005100023F480335361BFF34F8FD2F88030C3F39D +:10052000C905C3F34E335B0143F6E07603EA060CDC +:1005300029464CEA81770139C2F87472F9D2203B1E +:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 +:100550004F8FBFF36F8F536923F400335361002330 +:10056000C2F85032BFF34F8FBFF36F8F72B6302394 +:1005700083F3118862B6854680F308882047F8BD6A +:10058000008001082080010800220120003802407C +:1005900000ED00E02DE9F04F93B0B64B0090202223 +:1005A000FF210AA89D6800F0FDFBB34A1378B3B998 +:1005B000B24801211170036072B6302383F31188B1 +:1005C00062B603680BB101F073FAAD4AAB48002381 +:1005D0004FF47A7101F062FA002383F31188009BD3 +:1005E00013B1A84B009A1A60A74A009C1378032BFA +:1005F0001EBF00231370A34A4FF0000A18BF5360B8 +:10060000D3465646D146012000F082FB24B19D4BD3 +:100610001B68002B00F02782002000F083FA039073 +:10062000039B002BF2DB012000F068FB039B213BC6 +:100630001F2BE8D801A252F823F000BFBD06000826 +:10064000E506000879070008070600080706000805 +:10065000070600080B080008DB090008F508000879 +:10066000570900087F090008A509000807060008C7 +:10067000B709000807060008290A00085D070008F6 +:10068000070600086D0A0008C90600085D07000893 +:1006900007060008570900080706000807060008B3 +:1006A00007060008070600080706000807060008F6 +:1006B0000706000807060008790700080220FFF770 +:1006C00075FE002840F0F981009B0221BAF1000F6D +:1006D00008BF1C4605A841F21233ADF8143000F0F3 +:1006E0003FFA90E74FF47A7000F01CFA071EEBDB3C +:1006F0000220FFF75BFE0028E6D0013F052F00F245 +:10070000DE81DFE807F0030A0D1013360523059399 +:10071000042105A800F024FA17E056480421F9E75F +:100720005A480421F6E75A480421F3E74FF01C0821 +:10073000404600F041FA08F104080590042105A89C +:1007400000F00EFAB8F12C0FF2D1012000FA07F7F1 +:1007500047EA0B0B5FFA8BFB4FF0000900F06EFBD2 +:1007600026B10BF00B030B2B08BF0024FFF726FE6E +:1007700049E748480421CDE7002EA5D00BF00B0334 +:100780000B2BA1D10220FFF711FE074600289BD0BA +:10079000012000F00FFA0220FFF75AFE00261FFA90 +:1007A00086F8404600F016FA0446B0B10399A1F16C +:1007B000400251425141404600F01CFA01360028E7 +:1007C000EDD1BA46044641F21213022105A8ADF854 +:1007D00014303E4600F0C4F915E70120FFF738FE5B +:1007E0002546244B9B68AB4207D9284600F0E4F924 +:1007F000013040F067810435F3E7234B00251D707D +:10080000204BBA465D603E46A8E7002E3FF45CAF41 +:100810000BF00B030B2B7FF457AF0220FFF718FEF2 +:10082000322000F07FF9B0F10008FFF64DAF18F06C +:1008300003077FF449AF0F4A926808EB0503934220 +:100840003FF642AFB8F5807F3FF73EAF124B0193C2 +:10085000B84523DD4FF47A7000F064F90390039AF1 +:10086000002AFFF631AF019B039A03F8012B0137F1 +:10087000EDE700BF002201207C230120602201203F +:10088000D5030008802301207822012004220120C2 +:10089000082201200C2201207C220120C820FFF721 +:1008A00085FD074600283FF40FAF1F2D11D8C5F175 +:1008B000200242450AAB25F0030028BF4246834987 +:1008C0000192184400F048FA019A8048FF2100F094 +:1008D00069FA4FEAA8037D490193C8F387022846C5 +:1008E00000F068FA064600283FF46DAF019B05EB67 +:1008F000830533E70220FFF759FD00283FF4E4AEFB +:1009000000F0A4F900283FF4DFAE0027B846704B92 +:100910009B68BB4218D91F2F11D80A9B01330ED0F8 +:1009200027F0030312AA134453F8203C05934046D2 +:10093000042205A900F0B6FA04378046E7E73846F6 +:1009400000F03AF90590F2E7CDF81480042105A8EB +:1009500000F006F902E70023642104A8049300F0E4 +:10096000F5F800287FF4B0AE0220FFF71FFD002845 +:100970003FF4AAAE049800F051F90590E6E7002391 +:10098000642104A8049300F0E1F800287FF49CAEF1 +:100990000220FFF70BFD00283FF496AE049800F00C +:1009A0004DF9EAE70220FFF701FD00283FF48CAE85 +:1009B00000F05CF9E1E70220FFF7F8FC00283FF4C3 +:1009C00083AE05A9142000F057F9042107460490CE +:1009D00004A800F0C5F83946B9E7322000F0A2F8C3 +:1009E000071EFFF671AEBB077FF46EAE384A926801 +:1009F00007EB090393423FF667AE0220FFF7D6FCF0 +:100A000000283FF461AE27F003074F44B9453FF497 +:100A1000A5AE484600F0D0F80421059005A800F0E6 +:100A20009FF809F10409F1E74FF47A70FFF7BEFC73 +:100A300000283FF449AE00F009F9002844D00A9B91 +:100A400001330BD008220AA9002000F0B3F90028D6 +:100A50003AD02022FF210AA800F0A4F9FFF7AEFC4B +:100A60001C4800F05FFF13B0BDE8F08F002E3FF48C +:100A70002BAE0BF00B030B2B7FF426AE002364216F +:100A800005A8059300F062F8074600287FF41CAE25 +:100A90000220FFF78BFC804600283FF415AEFFF7DD +:100AA0008DFC41F2883000F03DFF059800F0F8F928 +:100AB000464600F0C3F93C46A5E506464EE64FF033 +:100AC000000901E6BA467EE637467CE67C22012034 +:100AD00000220120A086010070B50F4B1B78013366 +:100AE000DBB2012B0C4611D80C4D29684FF47A73F8 +:100AF0000E6AA2FB0332014622462846B0478442D2 +:100B000004D1074B00221A70012070BD4FF4FA7017 +:100B100000F008FF0020F8E710220120282601201D +:100B2000B423012007B50023024601210DF107007F +:100B30008DF80730FFF7D0FF20B19DF8070003B014 +:100B40005DF804FB4FF0FF30F9E700000A4608B5F6 +:100B50000421FFF7C1FF80F00100C0B2404208BD90 +:100B600030B4054C2368DD69044B0A46AC460146A7 +:100B7000204630BC604700BF28260120A086010027 +:100B800070B501F0E3F9094E094D30800024286862 +:100B90003388834208D901F0D3F92B680444013328 +:100BA000B4F5C03F2B60F2D370BD00BFB623012067 +:100BB0008823012001F078BA00F1006000F5C03010 +:100BC0000068704700F10060920000F5C03001F04D +:100BD00003BA0000054B1A68054B1B889B1A834219 +:100BE00002D9104401F0ACB90020704788230120DD +:100BF000B623012038B5084D044629B128682044A1 +:100C0000BDE8384001F0BCB92868204401F0A0F9E3 +:100C10000028F3D038BD00BF8823012010F0030363 +:100C200009D1B0F5846F04D200F10050A0F5712015 +:100C30000368184670470023FBE7000000F10050EE +:100C4000A0F57120D0F8200470470000064991F803 +:100C5000243033B10023086A81F824300822FFF7DA +:100C6000B1BF0120704700BF8C230120014B1868E1 +:100C7000704700BF002004E0F0B51E4B1D6801382E +:100C80002E0C0A181C48C5F30B04032335460788AD +:100C9000A7420BD144680B46013C934218461BD235 +:100CA00014F9010F48B103F8010BF6E7013B00F11D +:100CB0000800ECD191420ED20B4618462C24B6F512 +:100CC000805F00F8014B0AD1824202D94122981C70 +:100CD0005A70401AF0BD0846B6F5805FF9D041F26F +:100CE00001039D42F5D18242F3D95A2300F8013B1A +:100CF000EFE700BF002004E014220120022802BF19 +:100D0000024B4FF000529A61704700BF000802404A +:100D1000022802BF024B4FF400529A61704700BF95 +:100D200000080240022801BF024A536983F40053BD +:100D3000536170470008024070B504464FF47A765C +:100D40004CB1412C254628BF412506FB05F000F09B +:100D5000E9FD641BF4E770BD10B50023934203D096 +:100D6000CC5CC4540133F9E710BD000010B5013864 +:100D700010F9013F3BB191F900409C4203D11AB1F7 +:100D80000131013AF4E71AB191F90020981A10BD27 +:100D90001046FCE703460246D01A12F9011B00294F +:100DA000FAD1704702440346934202D003F8011B74 +:100DB000FAE770472DE9F8431F4D144695F82420B3 +:100DC0000746884652BBDFF870909CB395F82430F4 +:100DD0002BB92022FF2148462F62FFF7E3FF95F849 +:100DE0002400C0F10802A24228BF2246D6B24146E2 +:100DF000920005EB8000FFF7AFFF95F82430A41BAD +:100E00001E44F6B2082E17449044E4B285F82460DC +:100E1000DBD1FFF71BFF0028D7D108E02B6A03EBDB +:100E200082038342CFD0FFF711FF0028CBD10020EF +:100E3000BDE8F8830120FBE78C230120024B1A78E0 +:100E4000024B1A70704700BFB4230120102201200A +:100E500010B5104C104800F0BBF821460E4800F0C9 +:100E6000E3F82468E26ED2F8043843F00203C2F8D3 +:100E700004384FF47A70FFF75FFF0849204600F00E +:100E8000E1F9E26ED2F8043823F00203C2F8043824 +:100E900010BD00BF58370008282601206037000821 +:100EA0007047000030B5094D0A4491420DD011F849 +:100EB000013B5840082340F30004013B2C4013F051 +:100EC000FF0384EA5000F6D1EFE730BD2083B8ED90 +:100ED00072B6302383F3118862B6704702684368A4 +:100EE0001143016003B118477047000013B5446B0C +:100EF000D4F894341A681178042915D1217C022978 +:100F000012D11979128901238B4013420CD101A906 +:100F100004F14C0001F090FFD4F89444019B217936 +:100F20000246206800F0DAF902B010BD143001F07A +:100F300015BF00004FF0FF33143001F00FBF000069 +:100F40004C3001F0E5BF00004FF0FF334C3001F0B2 +:100F5000DFBF0000143001F0E5BE00004FF0FF31AC +:100F6000143001F0DFBE00004C3001F0B1BF0000D2 +:100F70004FF0FF324C3001F0ABBF00000020704753 +:100F800010B5D0F894341A6811780429044617D1A2 +:100F9000017C022914D15979528901238B401342D3 +:100FA0000ED1143001F078FE024648B1D4F89444D2 +:100FB0004FF4807361792068BDE8104000F07CB97F +:100FC00010BD0000406BFFF7DBBF00007047000062 +:100FD0007FB5124B036000234360C0E90233012553 +:100FE00002260F4B057404460290019300F184021F +:100FF000294600964FF48073143001F029FE094B06 +:101000000294CDE9006304F523724FF480732946FE +:1010100004F14C0001F0ECFE04B070BDAC360008E9 +:10102000C50F0008ED0E000808B50A68FFF750FF6D +:101030000B7902EB830318624B790D3342F82300DE +:101040008B7913B102EB830210620223C0F894146F +:101050000374002080F3118808BD000038B5037FB9 +:10106000044613B190F85430ABB9201D012502217C +:10107000FFF734FF04F1140025776FF0010100F051 +:1010800079FC84F8545004F14C006FF00101BDE884 +:10109000384000F06FBC38BD10B501210446043063 +:1010A000FFF71CFF0023237784F8543010BD0000A5 +:1010B00038B504460025143001F0E2FD04F14C007F +:1010C000257701F0ADFE201D84F854500121FFF773 +:1010D00005FF2046BDE83840FFF752BF90F85C306E +:1010E00003F06003202B07D190F85D20212A4FF0F8 +:1010F000000303D81F2A06D800207047222AFBD1FC +:10110000C0E9143303E0034A0265072242658365A0 +:10111000012070472C22012037B5D0F894341A688A +:101120001178042904461AD1017C022917D11979B2 +:10113000128901238B40134211D100F14C0528463E +:1011400001F02CFF58B101A9284601F075FED4F832 +:101150009444019B21790246206800F0BFF803B057 +:1011600030BD0000F0B500EB810385B01E6A044677 +:101170000D46F6B104EB8507301D0821FFF7A8FEE8 +:10118000FFF7ACFEFB685B691B6806F14C001BB106 +:10119000019001F05FFE019803A901F04DFE0246A7 +:1011A00048B1039B2946204600F098F8002383F3BA +:1011B000118805B0F0BDFB685A691268002AF5D0A5 +:1011C0001B8A013B1340F1D104F15C02EAE7000005 +:1011D0000D3138B550F82140D4B1FFF779FED4F87D +:1011E00094241368527903EB8203DB689B695D6882 +:1011F00045B104216018FFF771FE294604F114007F +:1012000001F054FD2046FFF7BBFE002383F3118855 +:1012100038BD00007047000072B6302383F3118898 +:1012200062B6704701F08EB810B50123044628223B +:1012300000F8243B0021FFF7B5FD0023C4E901338A +:1012400010BD000038B50025FFF7E6FF0446C0E9F1 +:101250000355C0E90555C0E90755416001F082F822 +:101260000223237085F31188284638BD70B500EB42 +:10127000810305465069DA600E46144618B1102203 +:101280000021FFF78FFDA06918B110220021FFF7A0 +:1012900089FD31462846BDE8704001F02DB90000B7 +:1012A000826802F0011282600022C0E90422C0E9D3 +:1012B0000622026201F0ACB9F0B400EB8104478968 +:1012C000E4680125A4698D403D43458123600023E6 +:1012D000A2606360F0BC01F0C7B90000F0B400EB9D +:1012E00081040789E468012564698D403D430581D7 +:1012F00023600023A2606360F0BC01F043BA0000E9 +:1013000070B50223002504460370C0E90255C0E908 +:101310000455C0E906554566056280F84C5001F059 +:1013200087F863681B6823B129462046BDE87040F2 +:10133000184770BD0378052B10B504460AD080F815 +:1013400068300523037043681B680BB1042198477C +:101350000023A36010BD00000178052906D190F894 +:101360006820436802701B6803B11847704700008B +:1013700070B590F84C30044613B1002380F84C301F +:1013800004F15C02204601F065F963689B68B3B91B +:1013900094F85C3013F0600533D00021204601F052 +:1013A0001DFC0021204601F00FFC63681B6813B18F +:1013B000062120469847062384F84C3070BD20460D +:1013C00098470028E4D0B4F86230626D9A4288BF32 +:1013D000636594F95C30656D002B80F20281002D0D +:1013E00000F0F180092384F84C30FFF715FF00214D +:1013F000D4E914232046FFF771FF002383F31188FB +:10140000DCE794F85D2003F07F0343EA022340F217 +:101410000232934200F0C48021D8B3F5807F48D0D7 +:101420000DD8012B3FD0022B00F09280002BB4D1BD +:1014300004F16402226502226265A365C3E7B3F585 +:10144000817F00F09A80B3F5407FA6D194F85E309A +:10145000012BA2D1B4F8643043F0020332E0B3F5BB +:10146000006F4DD017D8B3F5A06F31D0A3F5C0638E +:10147000012B92D8636894F85E205E6894F85F1040 +:10148000B4F860302046B047002886D04368236512 +:10149000036863651AE0B3F5106F36D040F6024278 +:1014A00093427FF47AAF5B4B23650223636500238D +:1014B000C3E794F85E30012B7FF46FAFB4F864306B +:1014C00023F00203C4E91455A4F86430A5657AE753 +:1014D000B4F85C30B3F5A06F0ED194F85E3084F8A8 +:1014E0006630204600F0FCFF63681B6813B10121E1 +:1014F00020469847032323700023C4E914339CE754 +:1015000004F1670323650123C3E72378042B0FD17C +:101510002046FFF781FEFFF7C3FE85F31188032104 +:10152000636884F8675021701B680BB120469847A8 +:1015300094F85E30002BDFD084F8673004232370EA +:1015400063681B68002BD7D0022120469847D3E759 +:1015500094F860301D0603F00F0120460AD501F013 +:101560006BF8012804D002287FF417AF2A4B9BE7C1 +:101570002A4B99E701F052F8F3E794F85E30002B1C +:101580007FF40BAF94F8603013F00F01B4D01A065B +:10159000204602D501F036FBAEE701F029FBABE7B0 +:1015A00094F85E30002B7FF4F8AE94F8603013F0BE +:1015B0000F01A1D01B06204602D501F00FFB9BE7CF +:1015C00001F002FB98E7142384F84C30FFF724FE67 +:1015D0002A462B4629462046FFF76EFE85F31188E2 +:1015E000ECE65DB1152384F84C30FFF715FE0021C1 +:1015F000D4E914232046FFF75FFEFEE60B2384F8B0 +:101600004C30FFF709FE2A462B4629462046FFF7B5 +:1016100065FEE3E7DC360008D4360008D83600085B +:1016200038B590F84C300446002B3CD0063BDAB27B +:101630000F2A32D80F2B30D8DFE803F0352F2F08D0 +:1016400021302F2F2F2F2F2F2F2F3535456DB0F80D +:1016500062309D4213D2C3681B8AB5FBF3F203FBD1 +:10166000125565B9FFF7D8FD2A462B462946FFF7E4 +:1016700035FE85F311880A2384F84C300DE01423DD +:1016800084F84C30FFF7C8FD00231A46194620465F +:10169000FFF712FE002383F3118838BD836D03B179 +:1016A00098470023E8E70021204601F097FA00213F +:1016B000204601F089FA63681B6813B106212046B1 +:1016C00098470623D8E7000010B590F84C30142B4B +:1016D000044628D017D8062B05D001D81BB110BD61 +:1016E000093B022BFBD80021204601F077FA0021AC +:1016F000204601F069FA63681B6813B10621204691 +:101700009847062318E0152BE9D10B2380F84C30BD +:10171000FFF782FD00231A461946FFF7DFFD00237D +:1017200083F31188DBE7C3689B695B68002BD6D124 +:10173000836D03B19847002384F84C30CFE7000055 +:1017400000230375826803691B6899689142FBD284 +:101750005A68036042601060586070470023037548 +:10176000826803691B6899689142FBD85A680360D4 +:10177000426010605860704708B5084672B6302362 +:1017800083F3118862B60B7D032B05D0042B0DD09B +:101790002BB983F3118808BD8B6900221A604FF0C2 +:1017A000FF338361FFF7CCFF0023F2E7D1E900327A +:1017B00013605A60F3E70000FFF7C2BF054BD9681A +:1017C0000875186802681A60536001220275D860B3 +:1017D000FEF7A8BDB823012030B50C4BDD684B1CCB +:1017E00087B004460FD02B46094A684600F056F9E8 +:1017F0002046FFF7E3FF009B13B1684600F058F95D +:10180000A86907B030BDFFF7D9FFF9E7B823012079 +:1018100079170008044B1A68DB6890689B68984247 +:1018200094BF002001207047B8230120084B10B559 +:101830001C68D86822681A60536001222275DC6037 +:10184000FFF78CFF01462046BDE81040FEF76ABD59 +:10185000B823012038B5074C074908480123002563 +:101860002370656001F0D2FB0223237085F3118899 +:1018700038BD00BF20260120E4360008B82301202F +:1018800000F04CB9034A516853685B1A9842FBD880 +:10189000704700BF001000E072B6302383F3118858 +:1018A00062B670478B60022308618B8208467047DE +:1018B0008368A3F1840243F8142C026943F8442C92 +:1018C000426943F8402C094A43F8242CC26843F883 +:1018D000182C022203F80C2C002203F80B2C044ACB +:1018E00043F8102CA3F12000704700BF3D0300080F +:1018F000B823012008B5FFF7DBFFBDE80840FFF77C +:101900005BBF0000024BDB6898610F20FFF756BFFA +:10191000B823012008B5FFF7BFFFBDE80840FFF777 +:10192000F1BF000008B501460820FFF7B5FFFFF73B +:1019300053FF002383F3118808BD0000064BDB68CA +:1019400039B1426818605A60136043600420FFF7A1 +:1019500043BF4FF0FF307047B8230120036898421F +:1019600006D01A680260506099611846FFF724BFDC +:101970007047000038B504460D462068844200D107 +:1019800038BD036823605C608561FFF715FFF4E7ED +:1019900010B503689C68A2420CD85C688A600B6032 +:1019A0004C602160596099688A1A9A604FF0FF3341 +:1019B000836010BD1B68121BECE700000A2938BFCA +:1019C0000A2170B504460D460A26601901F018FB7D +:1019D00001F004FB041BA54203D8751C2E460446E7 +:1019E000F3E70A2E04D9BDE87040012001F04EBB98 +:1019F00070BD0000F8B5144B0D46D96103F110011C +:101A000041600A2A1969826038BF0A220160486071 +:101A10001861A818144601F0E5FA0A2701F0DEFA69 +:101A2000431BA342064606D37C1C281901F0E8FAA2 +:101A300027463546F2E70A2F04D9BDE8F8400120D1 +:101A400001F024BBF8BD00BFB8230120F8B506465D +:101A50000D4601F0C3FA0F4A134653F8107F9F4218 +:101A600006D12A4601463046BDE8F840FFF7C2BF1E +:101A7000D169BB68441A2C1928BF2C46A34202D94D +:101A80002946FFF79BFF224631460348BDE8F84050 +:101A9000FFF77EBFB8230120C823012010B4C0E99E +:101AA000032300235DF8044B4361FFF7CFBF000021 +:101AB00010B5194C236998420DD0D0E900328168E5 +:101AC00013605A609A680A449A60002303604FF0DA +:101AD000FF33A36110BD2346026843F8102F536003 +:101AE0000022026022699A4203D1BDE8104001F051 +:101AF00081BA936881680B44936001F06FFA2269A0 +:101B0000E1699268441AA242E4D91144BDE8104048 +:101B1000091AFFF753BF00BFB82301202DE9F04792 +:101B2000DFF8C08008F110072D4ED8F8105001F0F2 +:101B300055FAD8F81C40AA68031B9A4240D81444AE +:101B4000D5E900324FF00009C8F81C4013605A6014 +:101B5000C5F80090D8F81030B34201D101F04AFA2C +:101B600089F31188D5E903312846984772B63023A6 +:101B700083F3118862B66B69002BD6D001F02EFA80 +:101B80006A69A0EB04094A4582460DD2022001F0A1 +:101B90007DFA0022D8F81030B34208D151462846C9 +:101BA000BDE8F047FFF726BF121A2244F2E712EB16 +:101BB000090938BF4A4629463846FFF7E9FEB3E728 +:101BC000D8F81030B34208D01444211AC8F81C00C9 +:101BD000A960BDE8F047FFF7F1BEBDE8F08700BFA0 +:101BE000C8230120B823012000207047FEE7000031 +:101BF000704700004FF0FF307047000072B630238E +:101C000083F3118862B6704702290CD0032904D0EF +:101C10000129074818BF00207047032A05D8054846 +:101C200000EBC2007047044870470020704700BFB7 +:101C3000BC3700083C2201207037000870B59AB00C +:101C40000546084601A9144600F0BEF801A8FFF7B2 +:101C5000A1F8431C5B00C5E9003400222370032374 +:101C60006370C6B201AB02341046D1B28E4204F1A9 +:101C7000020401D81AB070BD13F8011B04F8021C4D +:101C800004F8010C0132F0E708B50448FFF7B6FF8D +:101C9000FFF742FA002383F3118808BD28260120AC +:101CA00090F85C3003F01F02012A07D190F85D2004 +:101CB0000B2A03D10023C0E9143315E003F06003BD +:101CC000202B08D1B0F860302BB990F85D20212A84 +:101CD00003D81F2A04D8FFF701BA222AEBD0FAE76B +:101CE000034A02650722426583650120704700BFF1 +:101CF0003322012007B5052916D8DFE801F01815B1 +:101D00000318181E104A0121FFF778FF0190FFF712 +:101D1000ADFA01980D4A0221FFF7A8FA0C48FFF727 +:101D2000C7F9002383F3118803B05DF804FB08486A +:101D3000FFF764FFFFF792F9F3E70548FFF75EFF4F +:101D4000FFF7AAF9EDE700BF1037000834370008A5 +:101D50002826012038B50C4D0C4C0D492A4604F1BB +:101D60000800FFF76BFF05F1CA0204F110000949F2 +:101D7000FFF764FF05F5CA7204F118000649BDE8D3 +:101D80003840FFF75BBF00BFF02A01203C22012052 +:101D9000F0360008FA3600080537000870B504462A +:101DA00008460D46FEF7F6FFC6B22046013403781A +:101DB0000BB9184670BD32462946FEF7D7FF0028FA +:101DC000F3D10120F6E700002DE9F04705460C4667 +:101DD000FEF7E0FF2B49C6B22846FFF7DFFF08B148 +:101DE0000636F6B228492846FFF7D8FF08B1103664 +:101DF000F6B2632E0BD8DFF88C80DFF88C90234F7F +:101E0000DFF894A02E7846B92670BDE8F087294601 +:101E10002046BDE8F04701F02BBC252E2ED107222D +:101E200041462846FEF7A2FF70B9194B224603F13E +:101E30000C0153F8040B42F8040B8B42F9D11B78C8 +:101E4000137007350D34DDE7082249462846FEF7B2 +:101E50008DFF98B90F4BA21C197809090232C95D90 +:101E600002F8041C13F8011B01F00F015345C95D72 +:101E700002F8031CF0D118340835C3E704F8016BED +:101E80000135BFE7DC37000805370008F2370008E6 +:101E9000E437000820F4F01F2CF4F01FBFF34F8F3D +:101EA000024AD368DB03FCD4704700BF003C024009 +:101EB00008B5074B1B7853B9FFF7F0FF054B1A69BC +:101EC000002ABFBF044A5A6002F188325A6008BD36 +:101ED0004E2D0120003C02402301674508B5054B0B +:101EE0001B7833B9FFF7DAFF034A136943F0004365 +:101EF000136108BD4E2D0120003C02400728F0B5BB +:101F000016D80C4C0C4923787BB90C4D0E4608238F +:101F10004FF0006255F8047B46F8042B013B13F0A8 +:101F2000FF033A44F6D10123237051F82000F0BD9D +:101F30000020FCE7702D0120502D012004380008FE +:101F4000014B53F820007047043800080820704700 +:101F5000072810B5044601D9002010BDFFF7CEFFB9 +:101F6000064B53F824301844C21A0BB90120F4E789 +:101F700012680132F0D1043BF6E700BF04380008D4 +:101F8000072810B5044621D8FFF788FFFFF790FF18 +:101F90000F4AF323D360C300DBB243F4007343F072 +:101FA00002031361136943F480331361FFF776FF73 +:101FB000FFF7A4FF074B53F8241000F0D9F8FFF700 +:101FC0008DFF2046BDE81040FFF7C2BF002010BDC6 +:101FD000003C024004380008F8B512F00103144632 +:101FE00042D18218B2F1016F57D82D4B1B6813F004 +:101FF000010352D02B4DFFF75BFFF323EB60FFF79C +:102000004DFF40F20127032C15D824F00104661877 +:10201000244C401A40F20117B142236900EB01053C +:1020200024D123F001032361FFF758FF0120F8BDFD +:10203000043C0430E7E78307E7D12B6923F44073BE +:102040002B612B693B432B6151F8046B0660BFF396 +:102050004F8FFFF723FF03689E42E9D02B6923F0DF +:1020600001032B61FFF73AFF0020E0E723F4407300 +:10207000236123693B4323610B882B80BFF34F8F80 +:10208000FFF70CFF2D8831F8023BADB2AB42C3D055 +:10209000236923F001032361E4E71846C7E700BF83 +:1020A00000380240003C0240084908B50B7828B1CE +:1020B0001BB9FFF7FDFE01230B7008BD002BFCD000 +:1020C000BDE808400870FFF709BF00BF4E2D012092 +:1020D00010B50244064BD2B2904200D110BD441C50 +:1020E00000B253F8200041F8040BE0B2F4E700BF5F +:1020F000502800400F4B30B51C6F240407D41C6FD0 +:1021000044F400741C671C6F44F400441C670A4CC0 +:10211000236843F4807323600244084BD2B2904298 +:1021200000D130BD441C00B251F8045B43F820508C +:10213000E0B2F4E700380240007000405028004050 +:1021400007B5012201A90020FFF7C2FF019803B0E3 +:102150005DF804FB13B50446FFF7F2FFA04205D07B +:10216000012201A900200194FFF7C4FF02B010BDB5 +:102170000144BFF34F8F064B884204D3BFF34F8F08 +:10218000BFF36F8F7047C3F85C022030F4E700BFE5 +:1021900000ED00E0034B1A681AB9034AD2F874281C +:1021A0001A607047742D01200030024008B5FFF717 +:1021B000F1FF024B1868C0F3407008BD742D012078 +:1021C00070B5BFF34F8FBFF36F8F1A4A0021C2F86B +:1021D0005012BFF34F8FBFF36F8F536943F4003337 +:1021E0005361BFF34F8FBFF36F8FC2F88410BFF3FB +:1021F0004F8FD2F88030C3F3C900C3F34E335B0175 +:1022000043F6E07403EA0406014646EA81750139A3 +:10221000C2F86052F9D2203B13F1200FF2D1BFF384 +:102220004F8F536943F480335361BFF34F8FBFF334 +:102230006F8F70BD00ED00E0FEE7000070B5214B30 +:102240002148224A904237D3214BDA1C121AC11E70 +:1022500022F003028B4238BF00220021FEF7A2FDCC +:102260001C4A0023C2F88430BFF34F8FD2F880306D +:10227000C3F3C900C3F34E335B0143F6E07403EAD2 +:102280000406014646EA81750139C2F86C52F9D25A +:10229000203B13F1200FF2D1BFF34F8FBFF36F8FAD +:1022A000BFF34F8FBFF36F8F0023C2F85032BFF3DD +:1022B0004F8FBFF36F8F70BD53F8041B40F8041BA2 +:1022C000C0E700BFF4390008882E0120882E0120C5 +:1022D000882E012000ED00E070B5D0E91B439E6818 +:1022E00000224FF0FF3504EB42135101D3F80009EF +:1022F0000028BEBFD3F8000940F08040C3F80009B1 +:10230000D3F8000B0028BEBFD3F8000B40F080408C +:10231000C3F8000B013263189642C3F80859C3F89A +:10232000085BE0D24FF00113C4F81C3870BD000008 +:10233000890141F02001016103699B06FCD4122050 +:10234000FFF7A0BA10B5054C2046FEF76DFF4FF021 +:10235000A043E366024B236710BD00BF782D012028 +:102360004838000870B50378012B054650D12A4B38 +:10237000C46E98421BD1294B5A6B42F080025A63BB +:102380005A6D42F080025A655A6D5A6942F08002D5 +:102390005A615A6922F080025A610E2143205B691A +:1023A00000F03AFC1E4BE3601E4BC4F800380023DB +:1023B000C4F8003EC0232360EE6E4FF40413A36301 +:1023C0003369002BFCDA012333610C20FFF75AFA42 +:1023D0003369DB07FCD41220FFF754FA3369002B72 +:1023E000FCDA0026A6602846FFF776FF6B68C4F883 +:1023F0001068DB68C4F81468C4F81C684BB90A4B51 +:10240000A3614FF0FF336361A36843F00103A3604E +:1024100070BD064BF4E700BF782D01200038024064 +:102420004014004003002002003C30C0083C30C093 +:10243000F8B5C46E054600212046FFF779FF296FE5 +:1024400000234FF001128F68C4F834384FF0006653 +:10245000C4F81C284FF0FF3004EB431201339F42B5 +:10246000C2F80069C2F8006BC2F80809C2F8080B8C +:10247000F2D20B68EA6E6B67636210231361166910 +:1024800016F01006FBD11220FFF7FCF9D4F8003843 +:1024900023F4FE63C4F80038A36943F4402343F0F7 +:1024A0001003A3610923C4F81038C4F814380A4B88 +:1024B000EB604FF0C043C4F8103B084BC4F8003B3E +:1024C000C4F81069C4F800396B6F03F1100243F4CB +:1024D00080136A67A362F8BD2438000840800010AA +:1024E000C26E90F86610D2F8003823F4FE6343EA17 +:1024F0000113C2F8003870472DE9F84300EB81035F +:10250000C56EDA68166806F00306731E022B05EB2B +:1025100041130C4680460FFA81F94FEA41104FF003 +:102520000001C3F8101B4FF0010104F1100398BF24 +:10253000B60401FA03F391698EBF334E06F180565B +:1025400006F5004600293AD0578A04F1580149019E +:1025500037436F50D5F81C180B43C5F81C382B189F +:102560000021C3F8101953690127611EA7409BB3CE +:10257000138A928B9B08012A88BF5343D8F8742092 +:10258000981842EA034301F1400205EB8202C8F8C1 +:102590007400214653602846FFF7CAFE08EB890005 +:1025A000C3681B8A43EA8453483464011E432E5196 +:1025B000D5F81C381F43C5F81C78BDE8F88305EB37 +:1025C0004917D7F8001B21F40041C7F8001BD5F8C4 +:1025D0001C1821EA0303C0E704F13F0305EB830362 +:1025E0000A4A5A6028462146FFF7A2FE05EB491029 +:1025F000D0F8003923F40043C0F80039D5F81C386E +:1026000023EA0707D7E700BF00800010000400029C +:10261000026F12684267FFF75FBE00005831C36E59 +:1026200049015B5813F4004004D013F4001F0CBFA1 +:1026300002200120704700004831C36E49015B58F9 +:1026400013F4004004D013F4001F0CBF022001203B +:102650007047000000EB8101CB68196A0B681360BA +:102660004B6853607047000000EB810330B5DD68B4 +:10267000AA691368D36019B9402B84BF4023136043 +:102680006B8A1468C26E1C44013CB4FBF3F46343D0 +:10269000033323F0030302EB411043EAC44343F046 +:1026A000C043C0F8103B2B6803F00303012B09B2B1 +:1026B0000ED1D2F8083802EB411013F4807FD0F825 +:1026C000003B14BF43F0805343F00053C0F8003B7D +:1026D00002EB4112D2F8003B43F00443C2F8003B46 +:1026E00030BD00002DE9F041254DEE6E06EB4013A4 +:1026F0000446D3F8087BC3F8087B38070AD5D6F818 +:102700001438190706D505EB84032146DB682846F3 +:102710005B689847FA0721D5D6F81438DB071DD532 +:1027200005EB8403D968DCB98B69488A5A68B2FB27 +:10273000F0F600FB16229AB91868DA6890420FD2B8 +:10274000121AC3E9002472B6302383F3118862B6EB +:102750000B482146FFF788FF84F31188BDE8F0811C +:10276000012303FA04F26B8923EA02036B81CB682D +:10277000002BF3D021460248BDE8F041184700BFC6 +:10278000782D012000EB810370B5DD68C36E6C69A4 +:102790002668E6604A0156BB1A444FF40020C2F88E +:1027A00010092A6802F00302012A0AB20ED1D3F8F6 +:1027B000080803EB421410F4807FD4F8000914BF1A +:1027C00040F0805040F00050C4F8000903EB421282 +:1027D000D2F8000940F00440C2F80009D3F83408E8 +:1027E000012202FA01F10143C3F8341870BD19B98E +:1027F000402E84BF4020206020682E8A8419013C2E +:10280000B4FBF6F440EAC44040F000501A44C6E776 +:102810002DE9F8433C4DEE6E06EB40130446D3F829 +:102820000889C3F8088918F0010F4FEA40171CD037 +:10283000D6F81038DB0718D505EB8003D9684B694B +:102840001868DA68904232D2121A4FF000091A6002 +:10285000C3F8049072B6302383F3118862B6214620 +:102860002846FFF78FFF89F3118818F0800F1CD0DE +:10287000D6F834380126A640334216D005EB84033F +:10288000ED6ED3F80CC0DCF814200134E4B2D2F8B9 +:1028900000E005EB04342F445168714515D3D5F899 +:1028A000343823EA0606C5F83468BDE8F883012306 +:1028B00003FA04F22B8923EA02032B818B68002B95 +:1028C000D3D0214628469847CFE7BCF81000AEEB9E +:1028D0000103834228BF0346D7F8180980B2B3EB3F +:1028E000800FE2D89068A0F1040959F8048FC4F869 +:1028F0000080A0EB09089844B8F1040FF5D81844FB +:102900000B4490605360C7E7782D01202DE9F74F05 +:10291000AC4CE56E6E69AB691E4016F480586E6172 +:1029200007D02046FEF7ECFC03B0BDE8F04F00F006 +:102930006BBC002E12DAD5F8003EA2489B071EBFE2 +:10294000D5F8003E23F00303C5F8003ED5F804385F +:1029500023F00103C5F80438FEF7FEFC370505D562 +:102960009848FFF7B9FC9748FEF7E4FCB0040CD593 +:10297000D5F8083813F0060FEB6823F470530CBF3A +:1029800043F4105343F4A053EB6031071BD5636845 +:10299000DB681BB9AB6923F00803AB612378052B17 +:1029A0000CD1D5F8003E87489A071EBFD5F8003EE7 +:1029B00023F00303C5F8003EFEF7CEFC6368DB6836 +:1029C0000BB180489847F30200F18980B70227D500 +:1029D000D4F86C90DFF8ECB100274FF0010A09EB56 +:1029E0004712D2F8003B03F44023B3F5802F11D1F6 +:1029F000D2F8003B002B0DDA62890AFA07F322EACB +:102A00000303638104EB8703DB68DB6813B139469A +:102A100058469847236F01379B68FFB29F42DED923 +:102A2000F00617D5E76E3A6AC2F30A1002F00F03F8 +:102A300002F4F012B2F5802F00F09980B2F5402F29 +:102A400008D104EB83030022DB681B6A07F580577B +:102A500090427ED13303D5F818481DD5E70302D53F +:102A60000020FFF73FFEA50302D50120FFF73AFE45 +:102A7000600302D50220FFF735FE210302D50320B3 +:102A8000FFF730FEE20202D50420FFF72BFEA3027F +:102A900002D50520FFF726FE77037FF545AFE60751 +:102AA00002D50020FFF7B4FEA50702D50120FFF7ED +:102AB000AFFE600702D50220FFF7AAFE210702D56C +:102AC0000320FFF7A5FEE20602D50420FFF7A0FED3 +:102AD000A3067FF529AF0520FFF79AFE24E7E36EF2 +:102AE000DFF8E0A0019300274FF00109236F9B68F6 +:102AF0005FFA87FB9B453FF669AF019B03EB4B13E6 +:102B0000D3F8001901F44021B1F5802F1FD1D3F87B +:102B1000001900291BDAD3F8001941F09041C3F8DD +:102B20000019D3F800190029FBDB5946E06EFFF7C6 +:102B3000FFFB218909FA0BF321EA0303238104EB4C +:102B40008B03DB689B6813B15946504698470137A1 +:102B5000CCE7910708BFD7F80080072A98BF03F891 +:102B6000018B02F1010298BF4FEA182870E7023387 +:102B700004EB830207F580575268D2F818C0DCF8DE +:102B80000820DCE9001CA1EB0C0C002188420AD1D2 +:102B900004EB830463689B699A6802449A605A68EC +:102BA00002445A6056E711F0030F08BFD7F80080BF +:102BB0008C4588BF02F8018B01F1010188BF4FEA03 +:102BC0001828E3E7782D0120C36E03EB4111D1F8FB +:102BD000003B43F40013C1F8003B7047C36E03EBA6 +:102BE0004111D1F8003943F40013C1F8003970479E +:102BF000C36E03EB4111D1F8003B23F40013C1F87D +:102C0000003B7047C36E03EB4111D1F8003923F448 +:102C10000013C1F80039704700F1604303F56143C8 +:102C20000901C9B283F80013012200F01F039A4082 +:102C300043099B0003F1604303F56143C3F880211E +:102C40001A60704772B6302383F3118862B67047FA +:102C500030B5039C0172043304FB0325C0E906531D +:102C6000049B03630021059BC160C0E90000C0E92B +:102C70000422C0E90842C0E90A11436330BD0000E4 +:102C8000416A0022C0E90411C0E90A22C2606FF063 +:102C90000101FEF76FBE0000D0E90432934201D17A +:102CA000C2680AB9181D704700207047036919608F +:102CB000C2680132C260C2691344826903619342EF +:102CC00024BF436A03610021FEF748BE38B50446BD +:102CD0000D46E3683BB16269131D1268A362134499 +:102CE000E362002007E0237A33B929462046FEF745 +:102CF00025FE0028EDDA38BD6FF00100FBE700008B +:102D0000C368C269013BC36043691344826943617C +:102D1000934224BF436A436100238362036B03B180 +:102D20001847704770B5FFF78DFF866A04463EB9B5 +:102D3000FFF7CCFF054618B186F31188284670BD11 +:102D4000A36AE26A13F8015BA362934202D32046AE +:102D5000FFF7D6FF002383F31188EFE72DE9F04753 +:102D60009846FFF76FFF002504460E461746A94612 +:102D7000D4F828A0BAF1000F09D141462046FFF748 +:102D8000A5FF20B18AF311882846BDE8F087D4E971 +:102D90000A12A7EB050A521A924528BF9246BAF1C9 +:102DA000400F1BD9334601F1400251F8040B43F8A0 +:102DB000040B9142F9D1A36A40334036A3624035F7 +:102DC000D4E90A239A4202D32046FFF799FF89F3F8 +:102DD0001188BD42D8D2FFF735FFC9E730465246C9 +:102DE000FDF7BAFFA36A53445644A3625544E7E78C +:102DF00010B5029C0172043303FB0421C0E90613E1 +:102E00000023C0E90A33039B0363049BC460C0E949 +:102E10000000C0E90422C0E90842436310BD00007D +:102E2000026AC260426AC0E904220022C0E90A22A2 +:102E30006FF00101FEF79EBDD0E904239A4201D153 +:102E4000C26822B9184650F8043B0B607047002353 +:102E50001846FAE7C368C2690133C3604369134483 +:102E600082694361934224BF436A43610021FEF7B4 +:102E700075BD000038B504460D46E3683BB12369D3 +:102E80001A1DA262E2691344E362002007E0237A7C +:102E900033B929462046FEF751FD0028EDDA38BD4A +:102EA0006FF00100FBE7000003691960C268013A96 +:102EB000C260C269134482690361934224BF436ABA +:102EC000036100238362036B03B11847704700005E +:102ED00070B5FFF7B7FE866A0D46044611462EB957 +:102EE000FFF7C8FF10B186F3118870BDA36A1D708B +:102EF000A36AE26A01339342A36204D3E1692046E4 +:102F00000439FFF7D1FF002080F31188EDE70000BE +:102F10002DE9F0479946FFF795FE002604460D4639 +:102F20009046B246A76A4FB949462046FFF7A2FF2E +:102F300020B187F311883046BDE8F087D4E90A074D +:102F40003A1AA8EB0607974228BF1746402F1BD90D +:102F500005F1400355F8042B40F8042B9D42F9D1AC +:102F6000A36A4033A3624036D4E90A239A4204D3C9 +:102F7000E16920460439FFF797FF8AF31188464537 +:102F8000D9D2FFF75FFECDE729463A46FDF7E4FECA +:102F9000A36A3B443D44A3623E44E5E7D0E90423F1 +:102FA0009A4217D1C3689BB1836A8BB1043B9B1AC9 +:102FB0000ED01360C368013BC360C3691A448369C0 +:102FC00002619A4224BF436A0361002383620123A2 +:102FD000184670470023FBE700F042B94FF08043EA +:102FE000586A70474FF08043002258631A610222EA +:102FF000DA6070474FF080430022DA6070470000CB +:103000004FF0804358637047FEE7000070B51B4BDC +:1030100001630025044686B0586085620E4600F0C4 +:10302000CBF804F11003C4E904334FF0FF33C4E9D3 +:103030000635C4E90044A560E562FFF7CFFF2B46E3 +:103040000246C4E9082304F134010D4A25658023B2 +:103050002046FEF727FC0123E0600A4A0375009230 +:1030600072680192B268CDE90223074B6846CDE948 +:103070000435FEF73FFC06B070BD00BF20260120DE +:10308000543800085938000809300008024AD36A49 +:103090001843D062704700BFB82301204B684360DB +:1030A0008B688360CB68C3600B6943614B690362C3 +:1030B0008B6943620B6803607047000008B52C4BB6 +:1030C0002C481A6940F2FF710A431A611A6922F406 +:1030D000FF6222F007021A611A691A6B0A431A6327 +:1030E0001A6D0A431A65244A1B6D1146FFF7D6FF75 +:1030F00002F11C0100F58060FFF7D0FF02F13801FA +:1031000000F58060FFF7CAFF02F1540100F580600E +:10311000FFF7C4FF02F1700100F58060FFF7BEFF0A +:1031200002F18C0100F58060FFF7B8FF02F1A80101 +:1031300000F58060FFF7B2FF02F1C40100F5806086 +:10314000FFF7ACFF02F1E00100F58060FFF7A6FF9A +:1031500002F1FC0100F58060FFF7A0FF02F58C7121 +:1031600000F58060FFF79AFFBDE8084000F0EEB878 +:1031700000380240000002406038000808B500F046 +:1031800059FAFEF767FBFFF705F8BDE80840FEF7C0 +:10319000E1BD000070470000EFF3098305494A6B69 +:1031A00022F001024A63683383F30988002383F322 +:1031B0001188704700EF00E0302080F3118862B67C +:1031C0000D4B0E4AD96821F4E0610904090C0A4349 +:1031D000DA60D3F8FC200A4942F08072C3F8FC2080 +:1031E000084AC2F8B01F116841F0010111602022A5 +:1031F000DA7783F82200704700ED00E00003FA055B +:1032000055CEACC5001000E010B572B6302383F384 +:10321000118862B60E4B5B6813F4006314D0F1EEB4 +:10322000103AEFF30984683C4FF08073E361094B77 +:10323000DB6B236684F30988FEF7ECFA10B1064BCA +:10324000A36110BD054BFBE783F31188F9E700BFCD +:1032500000ED00E000EF00E04F030008520300081B +:103260000F4B1A6C42F001021A641A6E42F001020E +:103270001A660C4A1B6E936843F0010393604FF08B +:1032800080436B229A624FF0FF32DA6200229A6129 +:103290005A63DA605A6001225A611A60704700BFAF +:1032A00000380240002004E04FF0804208B5116968 +:1032B000D3680B40D9B2C9439B07116109D572B6D7 +:1032C000302383F3118862B6FEF7DAFA002383F322 +:1032D000118808BD1B4B1A696FEA42526FEA5252BD +:1032E0001A611A69C2F30A021A614FF0FF301A69B3 +:1032F0005A69586100215A6959615A691A6A62F01B +:1033000080521A621A6A02F080521A621A6A5A6A63 +:1033100058625A6A59625A6A0B4A106840F48070BF +:103320001060186F00F44070B0F5007F1EBF4FF4BE +:10333000803018671967536823F40073536000F0F6 +:1033400055B900BF0038024000700040374B4FF0C5 +:1033500080521A64364A4FF4404111601A6842F0B4 +:1033600001021A601A689207FCD59A6822F00302DB +:103370009A602E4B9A6812F00C02FBD1196801F08A +:10338000F90119609A601A6842F480321A601A686A +:103390009003FCD55A6F42F001025A67234B5A6FD3 +:1033A0009107FCD5234A5A601A6842F080721A606D +:1033B0001F4B5A685204FCD51A6842F480321A60D6 +:1033C0005A68D003FCD51A6842F400321A60184AD1 +:1033D00053689903FCD5154B1A689201FCD5164A1F +:1033E0009A6040F20112C3F88C200022C3F89020AA +:1033F000124A40F207331360136803F00F03072BE0 +:10340000FAD10A4B9A6842F002029A609A6802F076 +:103410000C02082AFAD15A6C42F480425A645A6E5D +:1034200042F480425A665B6E704700BF003802402B +:1034300000700040086C400900948838003C02404D +:10344000074A08B5536903F00103536123B1054AE4 +:1034500013680BB150689847BDE80840FFF7D4BE29 +:10346000003C0140082E0120074A08B5536903F0CB +:103470000203536123B1054A93680BB1D0689847A2 +:10348000BDE80840FFF7C0BE003C0140082E012007 +:10349000074A08B5536903F00403536123B1054A91 +:1034A00013690BB150699847BDE80840FFF7ACBEFF +:1034B000003C0140082E0120074A08B5536903F07B +:1034C0000803536123B1054A93690BB1D06998474A +:1034D000BDE80840FFF798BE003C0140082E0120DF +:1034E000074A08B5536903F01003536123B1054A35 +:1034F000136A0BB1506A9847BDE80840FFF784BED5 +:10350000003C0140082E0120164B10B55C6904F404 +:1035100078725A61A30604D5134A936A0BB1D06A34 +:103520009847600604D5104A136B0BB1506B98474F +:10353000210604D50C4A936B0BB1D06B9847E2057A +:1035400004D5094A136C0BB1506C9847A30504D5F8 +:10355000054A936C0BB1D06C9847BDE81040FFF75B +:1035600053BE00BF003C0140082E0120194B10B58E +:103570005C6904F47C425A61620504D5164A136DF5 +:103580000BB1506D9847230504D5134A936D0BB1C9 +:10359000D06D9847E00404D50F4A136E0BB1506EFE +:1035A0009847A10404D50C4A936E0BB1D06E98478E +:1035B000620404D5084A136F0BB1506F9847230477 +:1035C00004D5054A936F0BB1D06F9847BDE8104002 +:1035D000FFF71ABE003C0140082E012008B5FFF796 +:1035E00063FEBDE80840FFF70FBE0000062108B5E6 +:1035F0000846FFF711FB06210720FFF70DFB062108 +:103600000820FFF709FB06210920FFF705FB06212B +:103610000A20FFF701FB06211720FFF7FDFA06211C +:103620002820FFF7F9FABDE8084007211C20FFF722 +:10363000F3BA000008B5FFF74DFE00F00BF8FDF7F8 +:10364000F1FDFDF7C3FCFFF7A5FDBDE80840FFF75E +:10365000C3BC00000023054A19460133102BC2E900 +:10366000001102F10802F8D1704700BF082E0120B6 +:10367000034611F8012B03F8012B002AF9D17047FA +:1036800053544D3332463F3F3F3F3F3F0053544D2D +:10369000333246375B347C355D780053544D3332DA +:1036A00046375B367C375D78000000000000000084 +:1036B000490F0008350F0008710F00085D0F000862 +:1036C000690F0008550F0008410F00082D0F000872 +:1036D0007D0F000800000000010000000000000055 +:1036E00063300000E036000810240120202601206D +:1036F0004172647550696C6F740025424F415244A9 +:10370000252D424C002553455249414C25000000CF +:10371000020000000000000065110008D11100083F +:1037200040004000C02A0120D02A012002000000F1 +:103730000000000003000000000000001512000857 +:103740000000000010000000E02A0120000000003E +:103750000100000000000000782D0120010102009E +:10376000F51C0008091C0008A11C0008891C0008A1 +:10377000430000007837000809024300020100C03E +:1037800032090400000102020100052400100105B5 +:103790002401000104240202052406000107058219 +:1037A000030800FF09040100020A000000070501E8 +:1037B00002400000070581024000000012000000E6 +:1037C000C4370008120110010200004009124157DD +:1037D00000020102030100000403090425424F41D5 +:1037E00052442500474550524346373435425448E9 +:1037F000440030313233343536373839414243446E +:1038000045460000008000000080000000800000AD +:10381000008000000000020000000400000004001E +:1038200000000400000000007113000821160008C9 +:10383000C916000840004000F02D0120F02D0120A5 +:1038400001000000002E0120800000004001000067 +:10385000050000006D61696E0069646C6500000020 +:103860000001806A00000000AAAAAAAA0001006460 +:10387000FFFF00000000000000A00A000505000195 +:1038800000000000AAAAAAAA00000001CCFF0000C4 +:10389000000000000000000000000504000000001F +:1038A000AAAAAAAA00000000FFDC00000000000095 +:1038B000000000001000000500000000AAAAAAAA4B +:1038C00020000000FBCF000000000000000000000E +:1038D0000001000000000000AAAAAAAA000100003E +:1038E000FFFF0000000000000000000000000000DA +:1038F00000000000AAAAAAAA00000000FFFF000022 +:1039000000000000000000000000000000000000B7 +:10391000AAAAAAAA00000000FFFF00000000000001 +:103920000000000000000000000000000A0000008D +:103930000000000003000000000000000000000084 +:103940000000000000000000000000000000000077 +:103950000000000000000000000000000000000067 +:103960000000000000000000000000000000000057 +:103970000000000000000000000000000000000047 +:103980000000000000000000000000000000000037 +:103990000000000000000000DD0500000000000045 +:1039A00000800E0000000000FF000000000000008A +:1039B00080360008490400008D36000851040000DC +:1039C0009B360008009600000000080096000000EA +:1039D0000008000004000000D837000800000000C4 +:1039E00000000000000000000000000000000000D7 +:0439F00000000000D3 +:00000001FF diff --git a/Tools/bootloaders/Here4AP_bl.bin b/Tools/bootloaders/Here4AP_bl.bin index be76f1f4814ac1..e232031b40dc2b 100755 Binary files a/Tools/bootloaders/Here4AP_bl.bin and b/Tools/bootloaders/Here4AP_bl.bin differ diff --git a/Tools/bootloaders/Here4FC_bl.bin b/Tools/bootloaders/Here4FC_bl.bin index b84daeaa0e02db..7b39428c8d9935 100755 Binary files a/Tools/bootloaders/Here4FC_bl.bin and b/Tools/bootloaders/Here4FC_bl.bin differ diff --git a/Tools/bootloaders/Here4FC_bl.hex b/Tools/bootloaders/Here4FC_bl.hex index 3d421f5cea1709..6d4de6555fe617 100644 --- a/Tools/bootloaders/Here4FC_bl.hex +++ b/Tools/bootloaders/Here4FC_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:1000000000070020F102000849330008013300080E -:10001000293300080133000821330008F3020008E7 -:10002000F3020008F3020008F30200082D43000861 +:1000000000070020F1020008E133000899330008DE +:10001000C133000899330008B9330008F30200081F +:10002000F3020008F3020008F3020008CD430008C1 :10003000F3020008F3020008F3020008F3020008CC :10004000F3020008F3020008F3020008F3020008BC -:10005000F3020008F30200084D5F0008795F000812 -:10006000A55F0008D15F0008FD5F0008F1430008AC -:100070001944000845440008714400089D440008E4 -:10008000C5440008F1440008F3020008B13200083A -:10009000D9320008C5320008ED3200082960000896 +:10005000F3020008F302000881640008AD640008A0 +:10006000D96400080565000831650008914400085E +:10007000B9440008E5440008114500083D45000862 +:100080006545000891450008F3020008493300085F +:10009000713300085D330008853300085D65000892 :1000A000F3020008F3020008F3020008F30200085C :1000B000F3020008F3020008F3020008F30200084C :1000C000F3020008F3020008F3020008F30200083C -:1000D000F302000801610008F3020008F3020008BF -:1000E0008D600008F3020008F3020008F302000824 -:1000F000F3020008F3020008F30200081D4500089F -:10010000F3020008F302000829610008F302000866 +:1000D000F302000835660008F3020008F302000886 +:1000E000C1650008F3020008F3020008F3020008EB +:1000F000F3020008F3020008F3020008BD450008FF +:10010000F3020008F30200085D660008F30200082D :10011000F3020008F3020008F3020008F3020008EB -:1001200049450008714500089D450008C94500087B -:10013000F5450008F3020008F3020008F302000886 +:10012000E9450008114600083D46000869460008F8 +:1001300095460008F3020008F3020008F3020008E5 :10014000F3020008F3020008F3020008F3020008BB -:100150001D4600084946000875460008F3020008DD +:10015000BD460008E946000815470008F3020008FC :10016000F3020008F3020008F3020008F30200089B :10017000F3020008F3020008F3020008F30200088B -:10018000F3020008F3020008F302000815610008FA +:10018000F3020008F3020008F302000849660008C1 :10019000F3020008F3020008F3020008F30200086B :1001A000F3020008F3020008F3020008F30200085B :1001B000F3020008F3020008F3020008F30200084B @@ -52,50 +52,50 @@ :100320004F8FBFF36F8F40F20000C0F2F0004EF627 :100330008851CEF200010860BFF34F8FBFF36F8F7B :100340004FF00000E1EE100A4EF63C71CEF20001D3 -:100350000860062080F31488BFF36F8F05F0C6FA9B -:1003600005F0C8FB4FF055301F491B4A91423CBF76 +:100350000860062080F31488BFF36F8F05F020FC3F +:1003600005F05CFE4FF055301F491B4A91423CBFDF :1003700041F8040BFAE71D49184A91423CBF41F885 :10038000040BFAE71A491B4A1B4B9A423EBF51F82D :10039000040B42F8040BF8E700201849184A914270 -:1003A0003CBF41F8040BFAE705F0DEFA05F024FC47 +:1003A0003CBF41F8040BFAE705F038FC05F0BCFE51 :1003B000144C154DAC4203DA54F8041B8847F9E796 :1003C00000F042F8114C124DAC4203DA54F8041B11 -:1003D0008847F9E705F0C6BA00070020002300208F +:1003D0008847F9E705F020BC000700200023002033 :1003E0000000000808ED00E00001002000070020E8 -:1003F0005866000800230020A0230020A02300202E -:100400007C700020E0020008E4020008E40200081A +:1003F000786B0008002300203C23002040230020CD +:10040000E4700020E0020008E4020008E4020008B2 :10041000E40200082DE9F04F2DED108AC1F80CD050 :10042000D0F80CD0BDEC108ABDE8F08F002383F328 -:1004300011882846A047002004F098FEFEE704F04B -:1004400021FE00DFFEE70000F8B501F055F901F0EC -:1004500003FA01F04DFB05F0CDF9074605F03CFA33 +:1004300011882846A047002004F00CFFFEE704F0D6 +:1004400091FE00DFFEE70000F8B501F055F901F07C +:1004500003FA01F04DFB05F0FFFA074605F096FBA5 :100460000546A8BB1F4B9F4232D001339F4232D07A :1004700027F0FF021C4B9A4230D12E4642F21074F4 :10048000F8B200F06FFF00F073FF08B100242646B9 -:1004900001F076FD20B10024032000F079F8264613 -:1004A00035B1124B9F4203D0002405F00DFA2646C9 -:1004B000002005F0A9F90EB100F080F801F0EAFA89 +:1004900001F0BEFD20B10024032000F079F82646CB +:1004A00035B1124B9F4203D0002405F067FB26466E +:1004B000002005F0DBFA0EB100F080F801F0EAFA56 :1004C00000F08AFF204600F00BF900F077F8F9E71A :1004D0002E460024D7E704460126D4E7064641F21B :1004E0008834D0E7010007B0000008B0263A09B010 :1004F00008B501F07DF9A0F120035842584108BD2C :1005000007B541F21203022101A8ADF8043001F051 :100510008DF903B05DF804FB38B5302383F31188FF -:10052000174803680BB104F0DFFE0023154A4FF4AF -:100530007A71134804F0CEFE002383F31188124C25 +:10052000174803680BB104F053FF0023154A4FF43A +:100530007A71134804F042FF002383F31188124CB0 :10054000236813B12368013B2360636813B16368B8 :10055000013B63600D4D2B7833B963687BB9022092 :1005600001F02EFA322363602B78032B07D16368E6 :100570002BB9022001F024FA4FF47A73636038BD7E -:10058000A023002019050008C0240020B823002063 +:100580004023002019050008602400205823002083 :10059000084B187003280CD8DFE800F008050208A3 :1005A000022001F00BBA022001F006BA024B002231 -:1005B0005A607047B8230020C0240020F8B501F02D -:1005C000DFFC30B13E4B03221A7000223D4B5A60D3 +:1005B0005A6070475823002060240020F8B501F0ED +:1005C00027FD30B13E4B03221A7000223D4B5A608A :1005D000F8BD3D4B3D4A1C4619680131F8D0043343 :1005E0009342F9D162683A4B9A42F1D9394B9B68F0 -:1005F00003F1006303F580239A42E9D205F038F94C -:1006000005F04AF9002001F04DF90220FFF7C0FF84 +:1005F00003F1006303F580239A42E9D205F092FAF1 +:1006000005F0A4FA002001F04DF90220FFF7C0FF29 :10061000314B00219A6C99641A6F19671A6FDA6C62 :10062000D9645A6F59675A6F1A6D19659A6F99672D :100630009B6F72B64FF0E023C3F8084DD4E9000475 @@ -107,12 +107,12 @@ :100690006F8FBFF34F8FBFF36F8F536923F4003316 :1006A00053610023C2F85032BFF34F8FBFF36F8FF7 :1006B000302383F31188854680F30888204787E735 -:1006C000B8230020C02400200000040820000408F3 +:1006C00058230020602400200000040820000408B3 :1006D000FFFF0308002300200045025800ED00E062 :1006E0002DE9F04F93B0B74B2022FF2100900AA8CC :1006F0009D6801F079F9B44A1378A3B90121B34890 :1007000011700360302383F3118803680BB104F088 -:10071000EBFD0023AE4A4FF47A71AC4804F0DAFDE9 +:100710005FFE0023AE4A4FF47A71AC4804F04EFEFF :10072000002383F31188009B13B1AA4B009A1A602F :10073000A94A1378032B03D000231370A54A5360F2 :100740004FF0000A009CD3465646D146012001F0E6 @@ -155,9 +155,9 @@ :100990003FF642AFB8F5807F3FF73EAF124BB84508 :1009A000019323DD4FF47A7000F022FF0390039A45 :1009B000002AFFF631AF039A0137019B03F8012BA0 -:1009C000EDE700BF00230020BC240020A02300206E -:1009D00019050008C0240020B823002004230020AB -:1009E000082300200C230020BC230020C820FFF790 +:1009C000EDE700BF002300205C240020402300202E +:1009D000190500086024002058230020042300206B +:1009E000082300200C2300205C230020C820FFF7F0 :1009F0007FFD074600283FF40FAF1F2D11D8C5F12A :100A000020020AAB25F0030084494245184428BF60 :100A10004246019200F0D6FF019AFF217F4800F084 @@ -167,7 +167,7 @@ :100A500000F062FF00283FF4DFAE0027B846704B7D :100A60009B68BB4218D91F2F11D80A9B01330ED0A7 :100A700027F0030312AA134453F8203C0593404681 -:100A8000042205A9043701F065FA8046E7E73846F5 +:100A8000042205A9043701F0ADFA8046E7E73846AD :100A900000F00AFF0590F2E7CDF81480042105A8C4 :100AA00000F0C4FE02E70023642104A8049300F0D0 :100AB000B3FE00287FF4B0AE0220FFF719FD002836 @@ -186,13 +186,13 @@ :100B800000283FF449AE00F0C7FE002844D00A9B7D :100B900001330BD008220AA9002000F02DFF002805 :100BA0003AD02022FF210AA800F01EFFFFF7A8FC80 -:100BB0001C4804F0E1FA13B0BDE8F08F002E3FF4BA +:100BB0001C4804F055FB13B0BDE8F08F002E3FF445 :100BC0002BAE0BF00B030B2B7FF426AE002364211E :100BD00005A8059300F020FE074600287FF41CAE10 :100BE0000220FFF785FC804600283FF415AEFFF792 -:100BF00087FC41F2883004F0BFFA059800F05EFFF0 +:100BF00087FC41F2883004F033FB059800F05EFF7B :100C000046463C4600F03CFFA0E506464EE64FF067 -:100C1000000901E6BA467EE637467CE6BC230020A2 +:100C1000000901E6BA467EE637467CE65C23002002 :100C200000230020A0860100094A49F269001368E8 :100C300099B21B0C00FB013344F250611360054B69 :100C4000186882B2000C01FB0200186080B2704785 @@ -201,51 +201,51 @@ :100C700010BD00BF00E8F11F2DE9F041ADF54E7D3C :100C80000D46002140F275126CAC07460EA80D917E :100C900000F0AAFE4FF4C4720021204600F0A4FE2A -:100CA0000DF1340802F058FB4FF47A72264BB0FB7A +:100CA0000DF1340802F0A4FB4FF47A72264BB0FB2E :100CB000F2F0186093E80700022384E807000DF5BE :100CC000E9702382FFF7C8FF41F204331F4907A8E8 -:100CD000238405F0BFFA15230DF2E3220DF12C0C4D +:100CD000238405F04FFD15230DF2E3220DF12C0CBA :100CE00084F8323107AB1E46083203CE664542F81F :100CF000080C42F8041C3346F5D1306841461060B8 -:100D0000204633791371012200F048FF002380B29E +:100D0000204633791371012200F052FF002380B294 :100D1000E97E0393AB7E029305F11903019301234E :100D2000009307A3D3E90023CDE90480384602F0FD -:100D3000D1FE0DF54E7DBDE8F08100BFAFF3008020 -:100D40009E6AC421818A46EEC8240020646200089D +:100D30001DFF0DF54E7DBDE8F08100BFAFF30080D3 +:100D40009E6AC421818A46EE6824002084670008D8 :100D50002DE9F0412C4CDAB080460D46237A5BBB7E -:100D600027A9284601F028F80746002842D19DF817 +:100D600027A9284601F048F80746002842D19DF8F7 :100D70009D60C82E3ED801464FF4A662204600F082 :100D800033FE4FF4807332460DF19E01C4F8F83102 :100D90004FF4007304F109002644C4F80C334FF4F7 :100DA0004073C4F8203400F00DFE9DF89C3077723B :100DB00023720BB9EB7E237206AC8122002127A897 -:100DC00000F012FE0122214627A801F031F800238D +:100DC00000F012FE0122214627A801F05BF8002363 :100DD00080B2E97E0393AB7E029305F11903019380 :100DE0002823CDE904400093404605A3D3E900231E -:100DF00002F070FE5AB0BDE8F08100BFAFF3008092 -:100E000026417272DF25D7B7905E0020F0B5254EDF +:100DF00002F0BCFE5AB0BDE8F08100BFAFF3008046 +:100E000026417272DF25D7B7305E0020F0B5254E3F :100E10004FF48A75F1B0002405FB006596F8D830D0 :100E2000D822214685F8DC303AA885F8E84006AF9C :100E300000F0DAFD06F1090000F0CEFDD5F8E4304F :100E4000C2B206F109018DF8F0000DF1F100CDE913 -:100E50003A3400F0B7FD394601223AA801F014F8FF +:100E50003A3400F0B7FD394601223AA801F048F8CB :100E6000082380B2317ACDE9047001270E48CDE91C :100E7000023706F1D80301933023009307A3D3E987 -:100E8000002302F027FEA04206DD02F065FAC5F855 +:100E8000002302F073FEA04206DD02F0B1FAC5F8BD :100E9000E000384671B0F0BD2046FBE778F6339F9E -:100EA00093CACD8D905E0020E03400202DE9F04FF4 -:100EB000264F87B0DFF8A080254E384602F036FE78 +:100EA00093CACD8D305E0020803400202DE9F04FB4 +:100EB000264F87B0DFF8A080254E384602F082FE2C :100EC000034600283AD00024224DADF81440A14634 :100ED0000294A246CDE90344027B8DF8142003AAB4 :100EE0009968406803C21B6843F0004302932B6873 -:100EF00004F5A664D3F810B002F030FA10EB080243 +:100EF00004F5A664D3F810B002F07CFA10EB0802F7 :100F0000CDF800A0284605F5A65541F1000302A939 :100F1000D8470028C8BF49F00109B4F5266FE6D1CB -:100F2000B9F1000F05D0384602F004FE86F800A0A3 +:100F2000B9F1000F05D0384602F050FE86F800A057 :100F3000C3E73378072B04D80133337007B0BDE81B -:100F4000F08F024802F0F6FDF8E700BFE034002021 -:100F5000C56300201035002040420F0070B50D46DB -:100F600014461E4602F012FD50B9022E10D1012C7B +:100F4000F08F024802F042FEF8E700BF8034002034 +:100F500065630020B034002040420F0070B50D469C +:100F600014461E4602F05EFD50B9022E10D1012C2F :100F70000ED112A3D3E900230120C5E9002307E025 :100F8000282C10D005D8012C09D0052C0FD000201A :100F900070BD302CFBD10BA3D3E90023ECE70BA3EE @@ -257,21 +257,21 @@ :100FF00081FCA4F82C55B4F82C0500F063FC78B102 :10100000B4F82C0500F06EFC014648B9B4F82C0584 :1010100000F070FCB4F82C350133A4F82C35EAE765 -:1010200038BD00BF905E0020F8B50D4C02260D4F74 +:1010200038BD00BF305E0020F8B50D4C02260D4FD4 :10103000A4F5805343F8307C237E3BB965692DB11C -:10104000284601F01BF8284605F0BAF82046A4F51A -:10105000A65401F013F8012E00D1F8BD0126E7E7F0 -:10106000005A00201C6300082DE9F04F8FB00546A0 -:101070000C4600AF02F08AFC002849D1237E022BE7 -:101080001BD1E38A012B18D102F066F90646FFF75F +:10104000284601F063F8284601F09CF92046A4F5F3 +:10105000A65401F05BF8012E00D1F8BD0126E7E7A8 +:10106000A05900203C6800082DE9F04F8FB00546DC +:101070000C4600AF02F0D6FC002849D1237E022B9B +:101080001BD1E38A012B18D102F0B2F90646FFF713 :10109000CBFD03464FF4C87006F51676DFF8C08224 :1010A000B3FBF0F202FB103316FA83F3C8F80030FA :1010B000E37E33B9A34B00221A703C37BD46BDE82E -:1010C000F08F07F12401204600F034FE0028F4D10F +:1010C000F08F07F12401204600F04AFE0028F4D1F9 :1010D00007F11400FFF7C0FD97F8264007F114014F -:1010E00007F12700224605F083F80028E2D10F2CF3 +:1010E00007F12700224605F013FB0028E2D10F2C60 :1010F00008D8944B1C70D8F80030A3F51673C8F8C4 -:101100000030DAE797F82410284602F037FCD4E7DD +:101100000030DAE797F82410284602F083FCD4E791 :10111000E38A282B2BD010D8012B23D0052BCCD140 :10112000BFF34F8F8849894BCA6802F4E0621343CA :10113000CB60BFF34F8F00BFFDE7302BBDD1844E96 @@ -292,14 +292,14 @@ :10122000D42005EB0209C6F8D49000F04BFB8145B1 :1012300009D396F8D220D6F8D4000132001B86F8E4 :10124000D220C6F8D400FF2D0FD80024347200F04D -:1012500063FB204600F026FB00F092FE3D4B188118 +:1012500063FB204600F026FB00F0DAFE3D4B1881D0 :1012600008B9FFF7ABF9C54627E7BB6896F8D90080 :101270000AFB0362FB68D2F8E41082F8E83001F55B :101280008061C2F8E030C2F8E410FFF7BFFDFFF75D :101290000DFE96F8D920013202F0030286F8D9201B :1012A000B6E74FF48A7A20460AFB02F505F1EA0117 -:1012B000314400F015FEF86000287FF4FEAE0122F4 -:1012C000354485F8E82002F047F8D5F8E020D6ED5F +:1012B000314400F051FEF86000287FF4FEAE0122B8 +:1012C000354485F8E82002F093F8D5F8E020D6ED13 :1012D000007A801A40F6B832B8EE677ADFED1E6AFF :1012E000192838BF1920904228BF104607EE900AEF :1012F000F8EEE77A67EEA67ADFED186AE7EE267A6F @@ -307,26 +307,26 @@ :1013100073680AFB02F4321992F8E81059B1D2F856 :10132000E410E8468B423FF427AF002182F8E81032 :10133000C2F8E010C5467368064A9B0A0133138160 -:10134000BBE600BFD934002000ED00E00400FA0540 -:10135000905E0020C8240020CDCCCC3D6666663F60 -:10136000DC340020014B1870704700BFD4240020EB -:1013700038B54FF00054144B22689A4221D1627D57 -:101380000025124B12481A70C922237D09301149D9 -:1013900000F8013C4FF48073C0F8DB50C0F8EF3127 -:1013A0004FF40073C0F803334FF44073C0F81734A0 -:1013B00000F008FBE0222946204600F015FB012042 -:1013C00038BD0020FCE700BF9AAD44C5D4240020FE -:1013D000905E00201600002037B500F0D1FD1F4CB4 +:10134000BBE600BF7934002000ED00E00400FA05A0 +:10135000305E002068240020CDCCCC3D6666663F20 +:101360007C340020014B1870704700BF74240020AB +:1013700038B54FF00054144B22689A4222D1607D58 +:10138000F8B1124B0025C922114918701148237D6C +:101390000930C0F8DB5000F8013C4FF48073C0F80E +:1013A000EF314FF40073C0F803334FF44073C0F8CB +:1013B000173400F007FBE0222946204600F014FB1A +:1013C000012038BD0020FCE79AAD44C574240020FC +:1013D00016000020305E002037B500F019FE1F4CCB :1013E0001F4D022301221F496B712368288120466B :1013F0005B68984704F5805301221A49D3F8C0343A :1014000004F5A6505B689847002317494FF48052B3 -:101410000193164B16480093164B02F087FA164BB1 -:10142000197811B1124802F0A9FA01F095FF0446AB +:101410000193164B16480093164B02F0D3FA164B65 +:10142000197811B1124802F0F5FA01F0E1FF044613 :10143000FFF7FAFB4FF4C873B0FBF3F202FB1303A0 -:1014400004F5167010FA83F00C4B186004F044FA9F -:1014500008B10F232B8103B030BD00BF1035002031 -:10146000C824002040420F00D82400205D0F00084F -:10147000E034002069100008D4240020DC3400206F +:1014400004F5167010FA83F00C4B186004F09EFB44 +:1014500008B10F232B8103B030BD00BFB034002092 +:101460006824002040420F00782400205D0F00080F +:101470008034002069100008742400207C3400208F :101480002DE9F04F00242DED028B93B00DF12C08C7 :101490004FF0010ADFF814B2FFF708FD0A94ADF827 :1014A00034400B94C8F804409FED798B00267E4DA4 @@ -336,73 +336,73 @@ :1014E00000F082FA2B6808AA0AA95F6928460DF164 :1014F0001E03B8470FAB4F4698E8030083E803008C :101500009DF834300EA958468DF844300A9B0E934E -:10151000DDE9082302F0ECFC06F5A66605F5A65504 -:10152000B6F5266FC5D1002FC0D1604802F02EFA63 -:1015300000283FD15E4E01F00FFF3368984239D347 -:1015400001F00AFF0546FFF76FFB4FF4C8738DF8F3 +:10151000DDE9082302F038FD06F5A66605F5A655B7 +:10152000B6F5266FC5D1002FC0D1604802F07AFA17 +:1015300000283FD15E4E01F05BFF3368984239D3FB +:1015400001F056FF0546FFF76FFB4FF4C8738DF8A7 :101550002870B0FBF3F202FB130305F5167010FAC6 :1015600083F03060534E377817B901238DF8283057 :10157000C7F110050EA8FFF76FFB0EABEDB20DF132 :101580002900D919062D28BF06252A46013500F065 :1015900019FA0AABEDB24548039318230495029358 :1015A000454B0193012300933BA3D3E9002302F0B1 -:1015B00033FA347001F0D0FE404A414D1368C31A2B -:1015C000B3F57A7F2FD3106001F0C8FE02460B46B8 -:1015D000364802F0B9FA354802F0D8F918B32B7A38 +:1015B0007FFA347001F01CFF404A414D1368C31A92 +:1015C000B3F57A7F2FD3106001F014FF02460B466B +:1015D000364802F005FB354802F024FA18B32B7A9E :1015E0000EAF384E002B14BF03230223737101F09A -:1015F000B3FE4FF47A7301223946B0FBF3F030604A -:10160000304600F06FFB182380B202932E4B0193FB +:1015F000FFFE4FF47A7301223946B0FBF3F03060FE +:10160000304600F085FB182380B202932E4B0193E5 :1016100040F25513CDE903700093244820A3D3E989 -:10162000002302F0F9F92B7A93B101F095FE002620 +:10162000002302F045FA2B7A93B101F0E1FE002687 :1016300007464FF48A7895F8D900304400F003004B :1016400008FB005393F8E82072B10136042EF2D162 -:10165000C82003F091FD2B7A002B7FF417AF13B055 +:10165000C82003F005FE2B7A002B7FF417AF13B0E0 :10166000BDEC028BBDE8F08FD3F8E02042B12B68CF :10167000BA1AFA2B38BFFA230533B2EB430FE4D37F :10168000FFF7C4FB0028E0D1E2E700BFAFF3008022 :101690000000000000000000401DA12026812A0B50 -:1016A000F1C6A7C1D068080F10350020E034002033 -:1016B000DC340020D9340020D8340020C06300205E -:1016C000905E0020C8240020C463002010B5074CA1 -:1016D000204601F005F904F5A65001F001F9044A8D -:1016E00004490020BDE8104004F064BD103500201E -:1016F0002064002029100008F8B50A25204C01229A -:101700004FF400712046192703F0A0F8204601226B -:101710004FF4807103F09AF84FF480766520013819 +:1016A000F1C6A7C1D068080FB034002080340020F4 +:1016B0007C340020793400207834002060630020DE +:1016C000305E0020682400206463002010B5074CC1 +:1016D000204601F051F904F5A65001F04DF9044AF5 +:1016E00004490020BDE8104004F0FEBFB0340020E3 +:1016F000C063002029100008F8B50A25204C0122FB +:101700004FF400712046192703F0F0F8204601221B +:101710004FF4807103F0EAF84FF4807665200138C9 :1017200025D00822A2F10801B646332905D84FF08A :10173000000C66834FF000730DE0A1F13403668363 :10174000B3FBF7FC07FB1C33002B0CBF4FF0010C65 :101750004FF0000CEED1013143EA4C238A42A361E1 :10176000A4F818E0E1D10832A02AD8D0DAE7013D88 -:1017700042F2107003F000FD15F0FF05BFD1F8BD77 +:1017700042F2107003F074FD15F0FF05BFD1F8BD03 :10178000000402582DE9F84F4FF47A7306460D46CF :10179000002402FB03F7DFF85080DFF8509098F93F :1017A00000305FFA84FA5A1C01D0A34212D159F8D2 :1017B00024002A4631460368D3F820B03B46D84778 :1017C000854207D1074B012083F800A0BDE8F88FC0 -:1017D0000124E4E7002CFBD04FF4FA7003F0CCFCBA -:1017E0000020F3E70C640020182300201C230020B5 +:1017D0000124E4E7002CFBD04FF4FA7003F040FD45 +:1017E0000020F3E7AC630020182300201C23002016 :1017F000002307B5024601210DF107008DF80730DF :10180000FFF7C0FF20B19DF8070003B05DF804FBAF :101810004FF0FF30F9E700000A46042108B5FFF752 :10182000B1FF80F00100C0B2404208BD074B0A463C :1018300030B41978064B53F82140014623682046FE -:10184000DD69044BAC4630BC604700BF0C6400202F +:10184000DD69044BAC4630BC604700BFAC63002090 :101850001C230020A086010070B5104C0025104EFE -:1018600003F05AFE20803068238883420CD800257C -:101870002088013803F04CFE23880544013BB5F570 -:10188000802F2380F4D370BD03F042FE33680544FB -:101890000133B5F5802F3360E5D3E8E70E6400200F -:1018A000C863002003F006BF00F1006000F580204F +:1018600003F0CEFE20803068238883420CD8002508 +:101870002088013803F0C0FE23880544013BB5F5FC +:10188000802F2380F4D370BD03F0B6FE3368054487 +:101890000133B5F5802F3360E5D3E8E7AE63002070 +:1018A0006863002003F07ABF00F1006000F580203B :1018B0000068704700F10060920000F5802003F09E -:1018C00087BE0000054B1A68054B1B889B1A834294 -:1018D00002D9104403F01CBE00207047C8630020EA -:1018E0000E640020024B1B68184403F017BE00BFB3 -:1018F000C8630020024B1B68184403F021BE00BFE0 -:10190000C86300200020704700F1FF5000F58F10E1 +:1018C000FBBE0000054B1A68054B1B889B1A834220 +:1018D00002D9104403F090BE0020704768630020D6 +:1018E000AE630020024B1B68184403F08BBE00BFA0 +:1018F00068630020024B1B68184403F095BE00BFCC +:10190000686300200020704700F1FF5000F58F1041 :10191000D0F8000870470000064991F8243033B130 :1019200000230822086A81F82430FFF7C3BF012092 -:10193000704700BFCC630020014B1868704700BFA0 +:10193000704700BF6C630020014B1868704700BF00 :101940000010005C194B01380322084470B51D6873 :10195000174BC5F30B042D0C1E88A6420BD15C68F7 :101960000A46013C824213460FD214F9016F4EB170 @@ -410,7 +410,7 @@ :101980000B4602D22C2203F8012B0424094A1688A4 :10199000AE4204D1984284BF967803F8016B013CB3 :1019A00002F10402F3D1581A70BD00BF0010005CB0 -:1019B00024230020A8620008704700007047000040 +:1019B00024230020C867000870470000704700001B :1019C00070470000002310B5934203D0CC5CC45490 :1019D0000133F9E710BD000003460246D01A12F9A0 :1019E000011B0029FAD1704702440346934202D0FA @@ -422,1229 +422,1305 @@ :101A40002430A41B17441E449044E4B2F6B2082E7E :101A500085F82460DBD1FFF75FFF0028D7D108E0CD :101A60002B6A03EB82038342CFD0FFF755FF002898 -:101A7000CBD10020BDE8F8830120FBE7CC63002038 -:101A8000024B1A78024B1A70704700BF0C6400209A +:101A7000CBD10020BDE8F8830120FBE76C63002098 +:101A8000024B1A78024B1A70704700BFAC630020FB :101A90001823002010B5074C4FF4E13306492068A5 -:101AA0000B6003F055FA60680349BDE8104003F08D -:101AB0004FBA00BF1C230020F4630020094B1822FA +:101AA0000B6003F0A5FA60680349BDE8104003F03D +:101AB0009FBA00BF1C23002094630020094B18220A :101AC000002110B504461846FFF78EFF064A074B63 :101AD00001461278046053F82200BDE8104003F07C -:101AE00037BA00BFF46300200C6400201C230020E0 -:101AF000F0B5A1B071B600230120002480261A465B -:101B0000194602F055FE4FF4D067214A3D2513696E -:101B100023BBD2F810310BBB036804F1006199605C -:101B20000368C3F80CD003685E6003681F60016837 -:101B30000B6843F001030B6001680B6823F01E0380 -:101B40000B6001680B68DB07FCD4037B80344168C1 -:101B500005FA03F3B4F5001F0B60D8D102F05EFE66 -:101B6000B4F5001F11D000240A4E0B4D012003F0E4 -:101B7000A1FD3388A34205D928682044013403F02D -:101B8000DFFCF6E7002003F095FD61B621B0F0BD63 -:101B9000002000520E640020C86300202DE9F047A9 -:101BA0000D46044600219046284640F27912FFF780 -:101BB0001BFF234620220021284604F1220702F0C1 -:101BC00039F9231D022220212846C02602F032F9CD -:101BD000631D03222221284602F02CF9A31D0322B3 -:101BE0002521284602F026F904F1080310222821B5 -:101BF000284602F01FF904F1100308223821284674 -:101C000002F018F904F1110308224021284602F0DD -:101C100011F904F1120308224821284602F00AF9BA -:101C200004F1140320225021284602F003F904F1A4 -:101C3000180340227021284602F0FCF804F120032A -:101C40000822B021284602F0F5F804F12103082209 -:101C5000B821284602F0EEF8314608363B46082205 -:101C60002846013702F0E6F8B6F5A07FF4D1002748 -:101C700004F1330A04F1320308223146284602F007 -:101C8000D9F894F832304FEAC7099F4209F5A47693 -:101C900015D3B8F1000F08D1314609F24F1604F5FB -:101CA00099730722284602F0C5F827463B1B94F893 -:101CB000322193420CD3F01DC008BDE8F0870AEB37 -:101CC0000703082231462846013702F0B3F8D8E767 -:101CD00007F233133146082228460836013702F04E -:101CE000A9F8E3E713B5044608460021202223465D -:101CF00001900160C0F8031002F09CF8231D0198C8 -:101D00000222202102F096F8631D0198032222216D -:101D100002F090F8A31D01980322252102F08AF811 -:101D2000019804F108031022282102F083F807200B -:101D300002B010BD0023F7B50E46047F07220091C4 -:101D40001946054601F03AFF731C01220721009352 -:101D50002846002301F032FFC4B9B31C0522082134 -:101D60002846009323460D2401F028FF3746BB1B6D -:101D7000B278934211D307342B7FA88AE408BBB909 -:101D8000844294BF0020012003B0F0BDAB8A082438 -:101D9000DB00083BDB08B370E8E7FB1C21460822A8 -:101DA0002846009300230834013701F007FFDEE7DF -:101DB000201A18BF0120E7E70023F7B50E46047F7D -:101DC000082200911946054601F0F8FE731CC4B9BB -:101DD00008220093234610241146284601F0EEFE07 -:101DE00001235F1C7278013B934211D307342B7F90 -:101DF000A88AE408BBB9844294BF0020012003B044 -:101E0000F0BDAB8A0824DB00083BDB087370E7E712 -:101E1000F3192146082228460093002301F0CEFE44 -:101E200008343B46DDE7201A18BF0120E7E7000031 -:101E3000F8B50E4605461446002181223046FFF7CC -:101E4000D3FD2B4608220021304601F0F3FF7CB978 -:101E50000F246B1C07220821304601F0EBFF012301 -:101E60005F1C6A78013B934204D3E01DC008F8BDB3 -:101E70000824F4E7EB1921460822304601F0DAFF86 -:101E800008343B46ECE70000F8B50E46054614461C -:101E90000021CE223046FFF7A7FD2B462822002145 -:101EA000304601F0C7FF7CB9302405F10803082251 -:101EB0002821304601F0BEFF2F467B1B2A7A934231 -:101EC00004D3E01DC008F8BD2824F5E707F1090395 -:101ED0002146082230460834013701F0ABFFECE719 -:101EE000F7B5047F0E46009101231022002105461C -:101EF00001F064FEC4B9B31C0922102128460093E6 -:101F00002346192401F05AFE37467288BB1B9A42B9 -:101F100011D807342B7FA88AE408BBB9844294BF48 -:101F20000020012003B0F0BDAB8A1024DB00103B81 -:101F3000DB087380E8E73B1D214608222846009312 -:101F400000230834013701F039FEDEE7201A18BFFC -:101F50000120E7E730B50A44084D91420DD011F851 -:101F6000013B5840082340F30004013B2C4013F090 -:101F7000FF0384EA5000F6D1EFE730BD2083B8EDCF -:101F8000F7B5384A6B46106851686A4603C30823A0 -:101F90003549364804F03CF90446002833D10A2577 -:101FA000334A6B46106851686A4603C308233149B7 -:101FB0002E4804F02DF90446002849D00369B3F5F2 -:101FC000E01F45D8B0F8661040F2134291423FD16D -:101FD000294A024402F15C018B4239D35C3B23491C -:101FE00000209E1AFFF7B6FF04F16401074632464F -:101FF0000020FFF7AFFFA3689F4229D1E368984212 -:1020000008BF002524E00369B3F5E01F27D8418B02 -:1020100040F21342914220D1174A024402F11001CA -:102020008B4218D3103B114900209D1AFFF792FFF5 -:1020300004F1180106462A460020FFF78BFFA3682B -:102040009E4202D1E368984201D00D25A8E7002501 -:10205000284603B0F0BD1025A2E70C25A0E70B250C -:102060009EE700BFB8620008DCFF1B000000040808 -:10207000C162000890FF1B000800FCF710B5037C4C -:10208000044613B9006804F0ABF8204610BD000008 -:102090000023BFF35B8FC360BFF35B8FBFF35B8F26 -:1020A0008360BFF35B8F7047BFF35B8F0068BFF344 -:1020B0005B8F704770B505460C30FFF7F5FF04469F -:1020C00005F108063046FFF7EFFFA04206D96D681C -:1020D0003046FFF7E9FF2544281A70BD3046FFF768 -:1020E000E3FF201AF9E7000070B505464068A0B18B -:1020F00005F10C0605F10800FFF7D6FF044630464F -:10210000FFF7D2FF844204F1FF34304694BF6D687C -:102110000025FFF7C9FF2C44201A70BD38B50C46C6 -:102120000546FFF7C7FFA04210D305F10800FFF7EF -:10213000BBFF04446868BFF35B8FB4FBF0F100FBA6 -:1021400011440120AC60BFF35B8F38BD0020FCE779 -:102150002DE9F041144607460D46FFF7C5FF8442BE -:1021600028BF0446D4B1B84658F80C6B4046FFF778 -:102170009BFF3044286040467E68FFF795FF331A86 -:102180009C4203D801206C60BDE8F081A41B6B6009 -:102190003B682044AB60E8600220F5E72046F3E7A7 -:1021A00038B50C460546FFF79FFFA04210D305F156 -:1021B0000C00FFF779FF04446868BFF35B8FB4FB42 -:1021C000F0F100FB11440120EC60BFF35B8F38BDE0 -:1021D0000020FCE72DE9FF418846694607466C462A -:1021E000FFF7B6FF002506B204EBC606B4420AD0DC -:1021F000626808EB050120680834FFF7E3FB54F838 -:10220000043C1D44F2E729463846FFF7C9FF28463B -:1022100004B0BDE8F0810000F8B505460C300F466B -:10222000FFF742FF05F1080604463046FFF73CFF82 -:10223000A042304688BF6C68FFF736FF201A38602E -:1022400020B12C683046FFF72FFF2044F8BD000076 -:1022500073B5144606460D46FFF72CFF84420190E5 -:1022600028BF0446DCB101A93046FFF7D5FF019B2A -:1022700033B93268C5E90233C5E9002401200CE016 -:102280009C42286038BF0194019884426860F5D967 -:102290003368241A0220AB60EC6002B070BD2046A7 -:1022A000FBE700002DE9FF410F4669466C46FFF74A -:1022B000CFFF00B2002604EBC005AC4209D0D4F831 -:1022C0000480B81954F8081B42464644FFF77AFBCD -:1022D000F3E7304604B0BDE8F081000038B50546AC -:1022E000FFF7E0FF044601462846FFF717FF2046A8 -:1022F00038BD00007047000010B41346026814682F -:102300000022A4465DF8044B6047000000F58050B1 -:1023100090F859047047000000F5805090F852047E -:102320007047000000F5805090F958047047000095 -:102330004E207047302383F3118800F58052D2F885 -:102340009C34D2F898041844D2F894341844D2F843 -:102350007C341844D2F88C341844D2F888341844A9 -:10236000002383F31188704700F58050C0F854149F -:10237000012070472DE9F04F0C4600F5805185B0E3 -:102380001F4691F8523405469046BDF838909BB1EF -:10239000D1F878340133C1F878342368980006D432 -:1023A000237B082B0BD9627B0AB10F2B07D9D1F8FD -:1023B0007C340133C1F87C344FF0FF3010E030231F -:1023C00083F31188EB6AD3F8C42012F4001B0AD0FF -:1023D000D1F8803400200133C1F8803480F31188B3 -:1023E00005B0BDE8F08F20684822D3F8C43000283B -:1023F000C3F3044A6B6AB4BF40F08040800412FB10 -:102400000A334FEA4A161860226852004FEA0A62FD -:1024100044BF40F000501860207B42EA00425A60FE -:10242000607B10B342F440125A60D1F8B0240132FC -:10243000C1F8B024AA1902F58352117B41F02001A2 -:102440001173207B039300F0E3FF0330039B8010A4 -:102450005FFA8BF20BF1010B82420DDA04EB820181 -:1024600003EB820249689160F2E7AA1902F58352F0 -:10247000117B60F34511E3E70122EB6A05EB4A119A -:1024800002FA0AF201F58251C3F8D020AB191831D3 -:1024900004F10C0203F58253C3E90487234653F881 -:1024A000040B934241F8040BF9D11B882E440B8096 -:1024B00041F2680346F803A006F5805609F00303CD -:1024C00096F86C2043F0100322F01F02134386F8A5 -:1024D0006C30002383F3118842463B462146284650 -:1024E000CDF8009000F05AFF012079E72DE9F04780 -:1024F00000F58056044696F85254002D40F00381B2 -:10250000037C032B40F0948028462B462F465FFA2D -:1025100080FC944510DA01EBCC0E51F83CC0BCF1C4 -:10252000000F04DBDEF804C0BCF1000F02DB013752 -:102530000130ECE70133FBE7302080F31188E06ADB -:10254000F3B9D0F8803043F00203C0F880304E2356 -:10255000E06A002F6FD1D0F8803043F00103C0F85B -:1025600080306A4B6A4A1B6803F1805303F52C5391 -:102570009B009342A36240F2B080664800F0E6FE02 -:102580004D2B42D8DFF884814FEA034EDFF8889163 -:10259000D8F800C04EEA8C0EC0F884E00CF18050F0 -:1025A00000F52C508000606103EB0C00D4F82CC0C7 -:1025B000C3F14E03C8F80000DCF8800040F03000A2 -:1025C000CCF880004FF0000CD4F81480E6465FFA97 -:1025D0008CF08242BCDD01EBC00A51F830000028CB -:1025E00010DBDAF804A0BAF1000F0BDA09EA0040B8 -:1025F0000AF07F0A40EA0A0040F0084048F82E003E -:102600000EF1010E0CF1010CE1E7836923F00103E7 -:10261000836100F0A1FE0646E36A9B69D90704D5F1 -:1026200000F09AFE831BFA2BF6D9002383F311885E -:102630002846BDE8F087B7EB530F3DD2DFF8CCE07A -:102640004FEA074CDEF800304CEA830CC0F888C033 -:1026500003F1805003EB4703002700F52C50CEF820 -:102660000030BC468000A061E06AD0F8803043F0C2 -:102670000C03C0F88030D4F818E0FBB29A427FF720 -:1026800070AF51F8330001EBC3080028D8F80430CC -:1026900001DB002B0EDB20F0604023F0604340F0B4 -:1026A000005043F000434EF83C000EEBCC000CF120 -:1026B000010C43600137E0E7836923F00103836184 -:1026C00000F04AFE0646E36A9B69DA07ADD500F0E2 -:1026D00043FE831BFA2BF6D9A7E7E26A936923F03E -:1026E0000103936100F038FE0746E36A9B69DB074C -:1026F00005D500F031FEC31BFA2BF6D995E701256D -:1027000086F8525491E7002592E700BF1C64002030 -:10271000FCB50040CC6200080000FF0713B500F5CF -:1027200080540191606CFFF7DFFC1F280AD920223A -:102730000199606CFFF74EFDA0F12003584258410B -:1027400002B010BD0020FBE708B5302383F31188E9 -:1027500000F58050406CFFF79BFC002383F3118849 -:1027600008BD0000002202608281426082607047E2 -:102770000022002310B5C0E90023002304460C30DA -:1027800020F8043CFFF7EEFF204610BD2DE9F0478E -:102790009A4688B0074688469146302383F31188CD -:1027A00007F580546846FFF7E3FF606CFFF782FC93 -:1027B0001F282ED920226946606CFFF78FFD202844 -:1027C00027D194F8523423B303AD444605AB2E46CB -:1027D000083403CE9E4244F8080C44F8041C3546E5 -:1027E000F5D130682060B388A380DDE90023C9E912 -:1027F0000023BDF80830AAF80030002383F31188C5 -:1028000053464A464146384608B0BDE8F04700F016 -:10281000B3BD002080F3118808B0BDE8F087000048 -:102820002DE9F84F0023064600F5815405468846F9 -:102830001034C0E90133274B46F8303B3746384661 -:102840002037FFF795FFA742F9D105F580544FF4E3 -:10285000805305F5A3594FF0000A266300266764EC -:1028600005F5835709F110094FF0000B1037E663A7 -:10287000C4E90D36012384F8403084F84830A7F1CC -:102880001800203747E910ABFFF76CFF47F8286CBA -:102890004F45F4D1B8F1010F84F85884A4F85A6474 -:1028A000A4F85C64A4F85E6484F86064A4F86264CC -:1028B000A4F86464A4F8666484F8686402D90648DD -:1028C00000F044FD054B284653F82830EB62BDE884 -:1028D000F88F00BF1C630008F06200080C6300085A -:1028E000044B10B5197804464A1C1A70FFF798FF7C -:1028F000204610BD196400202DE9F04300295AD06C -:102900002E4E2F48B6FBF1F481428CBF0A201120D5 -:10291000431EB4FBF0F700FB1740DDB220B1022BE1 -:102920001846F5D8002032E07B1EB3F5806F2ED21A -:10293000C5EBC5084FF47A7308F103044FEAE40EBF -:10294000C4F3C7040EF10109281B0EFB033E5FFA16 -:1029500080FC59FA80F0BEFBF0F0B0F5617F18DC26 -:1029600083B2601C5CFA80F07843B6FBF0F08142E1 -:10297000D8D1611E0F29D5D80CF1FF310729D1D844 -:102980000120138057801071547182F806C0BDE891 -:10299000F08308F1FF34E010C4F3C70400F1010E26 -:1029A0002D1B00FB03335FFA85FC5EFA85F5B3FB54 -:1029B000F5F39BB2D5E70846E9E700BF00B4C404CD -:1029C0003F420F0030B50D4B05200D4D1C786C4378 -:1029D0008C420ED159780120518099785171D97863 -:1029E0009171197911715B7903EB83035B0013809B -:1029F00030BD013803F10603E8D1F9E75C63000854 -:102A000040420F0038B540F27772C36A154CC3F8E4 -:102A1000BC200722C36AC3F8C8202268C16A930099 -:102A200043F4C023C1F8A03002F1805302F16C01DD -:102A3000C56A03F52C53EA3289009B00226041F0FD -:102A4000E061094AC361C5F8C01003F5D87103F508 -:102A50006A7341629342836202D9044800F076FCB3 -:102A600038BD00BF1C640020FCB50040CC620008EB -:102A70002DE9F04F00F580551F4689B0044695F8C2 -:102A8000583489469046022B04D90026304609B0B6 -:102A9000BDE8F08FA84A52F8231009B942F8230084 -:102AA000A648C4F80C9001782774C9B9302383F381 -:102AB0001188A34BD3F8EC2042F48072C3F8EC20C9 -:102AC000D3F8942042F48072C3F89420D3F8942071 -:102AD00022F48072C3F894200123037081F31188DB -:102AE00095F851347BB9302383F31188954A95F8D2 -:102AF0005834D35C0BB3012B28D0012385F8513413 -:102B0000002383F31188302383F31188E26A9369E9 -:102B100023F01003936100F01FFC8246E36A9E6974 -:102B200016F0080619D000F017FCA0EB0A03FA2BE8 -:102B3000F4D9002686F31188A8E70321132002F0B8 -:102B40003BF80321152002F037F8D6E703211420C3 -:102B500002F032F803211620F5E79A6942F00102EB -:102B60009A6100F0F9FB8246E36A9A69D00706D4BD -:102B700000F0F2FBA0EB0A03FA2BF5D9D9E79A692A -:102B80004FF0000A42F002029A61E36AC3F854A0CF -:102B90008AF3118804F5825B686CFFF779FA0BF110 -:102BA000100B202200216846FEF71EFF02A8FFF747 -:102BB000D9FD6A460BEB06030DF1180ECDF818A0EF -:102BC00094460833BCE80300F44543F8080C43F886 -:102BD000041C6246F4D1DCF8000020361860B6F51B -:102BE000806F9CF804201A71DBD1002304F5A252F7 -:102BF000494620461A3285F8503485F85334FFF799 -:102C00007BFE064690B9E26A936923F00103936163 -:102C100000F0A2FB0546E36A9B69D9077FF535AF53 -:102C200000F09AFB431BFA2BF5D92EE795F85E349A -:102C3000C5F86C94591E95F85F34E26A013B1B029B -:102C400043EA416395F8601401390B43B5F85C140D -:102C5000013943EA0143D361B8F1000F36D004F5DE -:102C6000A352414620460232FFF7ACFE90B9E26A19 -:102C7000936923F00103936100F06EFB0546E36A5C -:102C80009B69DA077FF501AF00F066FB431BFA2B67 -:102C9000F5D9FAE695F86724C5F87084511E95F8C1 -:102CA0006824E36A013A120142EA012295F86614A7 -:102CB00001390A43B5F86414013942EA014242F489 -:102CC0000002DA604FF42062E36A9A64E36A4FF02C -:102CD00000082046C3F8BC80FFF794FE85F85984AD -:102CE0006FF04042E36A1A65174AE36A5A654FF08B -:102CF0000222E36A9A654FF0FF32E36AC3F8E020EC -:102D00000322E36A9742DA653FF4C0AEE26A936950 -:102D100023F00103936100F01FFB0746E36A9B6900 -:102D2000DB0705D500F018FBC31BFA2BF6D9ACE680 -:102D3000012385F85234A9E61064002018640020AD -:102D40000044025804630008550200022DE9F04FC8 -:102D5000054689B090469946002741F2680A00F579 -:102D60008056EB6AD3F8D830FB40D80751D505EB35 -:102D700047124FEA471B52441379190749D4D6F832 -:102D800084340133C6F8843405F5A553C3E90089BA -:102D900013799A0605EB0B0248BFD6F8B4345244B7 -:102DA00044BF0133C6F8B434137943F008031371F8 -:102DB000DB0723D596F8533403B305F582546846F0 -:102DC000FFF7D6FC03AB18345C4404F1080C206810 -:102DD000083454F8041C1A46644503C21346F6D15D -:102DE0002068694610602846A2889A800123ADF8C1 -:102DF00008302B68CDE90089DB6B9847D6F8A834FA -:102E0000D6F854040133C6F8A83410B103681B691E -:102E100098470137202FA4D109B0BDE8F08F0000FA -:102E20002DE9F04F0F468DB0044600F097FA824628 -:102E30008946002F5BD1E36AD3F8A02012F4FE0F7D -:102E400003D100200DB0BDE8F08FD3F8A42092018B -:102E500041BF04F58051D1F898240132C1F898247B -:102E6000D3F8A4205606ECD0D3F8A450E669C5F3F5 -:102E700005254823E8464FF0000B03FB0566404656 -:102E8000FFF770FC326851004ABF22F06043C2F382 -:102E90008A4343F00043920048BF43F080430093CD -:102EA000736813F400131BBF012304F580528DF8DF -:102EB0000D308DF80D301EBFD2F8B8340133C2F892 -:102EC000B834F38803F00F038DF80C309DF80C0034 -:102ED00000F09EFA5FFA8BF3984225D9F2180CA9FC -:102EE0000BF1010B127A0B4403F82C2CEEE7012FA7 -:102EF000A7D1E36AD3F8B02012F4FE0FA1D0D3F823 -:102F0000B420950141BF04F58051D1F898240132D5 -:102F1000C1F89824D3F8B420500692D0D3F8B45016 -:102F2000266AC5F30525A4E7EFB9E36AC3F8A850FC -:102F300004A807ADFFF71CFC98E80F0007C52B801D -:102F40000023204604A9ADF81830236804F5805406 -:102F5000DB6BCDE904A9984758B1D4F8903401331C -:102F6000C4F890346EE7012FE2D1E36AC3F8B85099 -:102F7000DEE7D4F8943401200133C4F8943461E7D7 -:102F80002DE9F04105460F4600F5805401263946EB -:102F90002846FFF745FF10B184F85364F7E7D4F8EB -:102FA000A834D4F854040133C4F8A83420B1036819 -:102FB000BDE8F0411B691847BDE8F081C36AF0B570 -:102FC0001A6C12F47F0F2BD01B6C00F5805441F269 -:102FD00068054FF0010CC4F8AC340023471900EB2E -:102FE00043125E012A44117911F0020F15D04907EE -:102FF00013D4B959C66A0CFA01F1D6F8CCE011EA3B -:103000000E0F0AD0C6F8D410117941F004011171E5 -:10301000D4F88C240132C4F88C240133202BDED167 -:10302000F0BD00002B4B70B51E561B5C012B30D839 -:10303000294D2A4A55F8233052F8264013B349B394 -:10304000236D9A0510D54FF40073236500F086F9BF -:1030500050EA01020B4602D0013861F1000302463A -:1030600055F82600FFF772FE236D9B012CD54FF01B -:10307000007255F82630226503F58053012283F84B -:10308000592421E001232365102323654FF4805345 -:10309000236570BD236DDA0702D4236D5B0706D567 -:1030A0000523002155F826002365FFF769FF236DEE -:1030B000D80602D4236D590606D55023012155F8B0 -:1030C00026002365FFF75CFF55F82600BDE8704039 -:1030D000FFF774BF08630008106400200C63000849 -:1030E00008B5302383F31188FFF768FF002383F3CB -:1030F000118808BDC36AD3F8C00010F07C5005D019 -:10310000D3F8C40080F40010C0F3405070470000B2 -:1031100008B5302383F3118800F58050406CFEF72A -:10312000C9FF002383F3118843090CBF012000204D -:1031300008BD000000F5805393F8592462B1C16ABC -:103140008A6922F001028A61D3F89C240132C3F813 -:103150009C24002283F85924704700002DE9F7438E -:10316000302181F3118800F58251002541F2680E6B -:103170004FF00108103100F5805C00EB45147444F9 -:10318000267977071CD4F6061AD58E69D0F82C90CC -:1031900008FA06F6D9F8CC703E4211D04F68019774 -:1031A0000F689742019F9F410AD2C9F8D4602679DF -:1031B00046F004062671DCF888440134CCF88844D3 -:1031C00001352031202DD8D1002383F3118803B09D -:1031D000BDE8F083F8B51E4600230F460546137080 -:1031E0001446FFF795FF80F0010038701EB12846A5 -:1031F000FFF780FF2070F8BD2DE9F04F85B09946AC -:103200000D468046164691F800B0DDE90EA3029304 -:103210001378019300F0A2F82B7804460F4613B9F7 -:103220003378002B41D022463B464046FFF796FFBD -:10323000FFF756FFFFF77EFF4B4632462946FFF762 -:10324000C9FF2B7833B1BBF1000F03D0012005B0CB -:10325000BDE8F08F337813B1019B002BF6D108F550 -:10326000805303935445029B77EB03031DD2039BCA -:10327000D3F85404C8B10368AAEB04011B6898474B -:103280004B46324629464046FFF7A4FF2B7813B140 -:10329000BBF1000FDAD1337813B1019B002BD5D1EC -:1032A00000F05CF804460F46DCE70020CFE70000A2 -:1032B000002108B50846FFF7B5FEBDE8084001F05B -:1032C0006DB8000008B501210020FFF7ABFEBDE896 -:1032D000084001F063B8000008B500210120FFF7A5 -:1032E000A1FEBDE8084001F059B80000012108B571 -:1032F0000846FFF797FEBDE8084001F04FB8000010 -:1033000000B59BB0EFF3098168226846FEF75AFBCF -:10331000EFF30583014B9B6BFEE700BF00ED00E080 -:1033200008B5FFF7EDFF000000B59BB0EFF3098192 -:1033300068226846FEF746FBEFF30583014B5B6BA3 -:10334000FEE700BF00ED00E0FEE700000FB408B5A7 -:10335000029801F0C1FEFEE702F0EEB902F0D0B92A -:1033600013B56C46031D84E8060094E8030083E867 -:103370000500012002B010BD73B58568019155B1FB -:103380001B885B0707D4D0E900369B6B9847019AEE -:10339000C1B23046A847012002B070BDF0B58668C2 -:1033A00089B005460C465EB1BDF838305B070AD4DB -:1033B000D0E900379B6B98472246C1B23846B047E8 -:1033C000012009B0F0BD0022002301F10806CDE97B -:1033D000002300230A46ADF8083003AB106808321A -:1033E00052F8041C1C46B24203C42346F6D11068AE -:1033F00020609288A280FFF7B1FF0423ADF8083067 -:103400002B68CDE90001DB6B694628469847D7E772 -:10341000082817D909280CD00A280CD00B280CD062 -:103420000C280CD00D280CD00E2814BF40203020C2 -:1034300070470C20704710207047142070471820E8 -:1034400070472020704700002DE9F041456A15B90A -:103450004162BDE8F0814B68AC4623F06047C3F39E -:103460008A464FEAD37EC3F3807816EA230638BF34 -:103470003E462B465A68BEEBD27F22F060440AD00B -:10348000002A18DAA40CB44217D19D420FD10D6066 -:10349000DEE71346EEE7A74207D102F08044C2F30D -:1034A000807242450BD054B1EFE708D2EDE7CCF87B -:1034B00000100B60CDE7B44201D0B442E5D81A68E1 -:1034C0009C46002AE5D11960C3E700002DE9F047CA -:1034D000089D01F0070400EBD1004FF47F494FEA4B -:1034E000D508224405F00705944201D1BDE8F087D4 -:1034F00004F0070705F0070A111B08EBD50E574526 -:103500003E4613F80EC038BF5646C6F108068E4236 -:1035100028BF0E46E108415C34443544B94029FADD -:1035200006F721FA0AF1FFB28CEA010147FA0AF71D -:1035300039408CEA010C03F80EC0D5E780EA01207F -:10354000082341F2210201B2013B4000002980B270 -:10355000B8BF504013F0FF03F5D1704738B50C46A3 -:103560008D18A54200D138BD14F8011BFFF7E6FF06 -:10357000F7E7000042684AB11368818943604389D4 -:1035800001339BB29942438138BF83811046704713 -:1035900070B588B0044620220D4668460021FEF72B -:1035A00023FA20460495FFF7E5FF024660B16B461B -:1035B000054608AE1C46083503CCB44245F8080C55 -:1035C00045F8041C2346F5D1104608B070BD000034 -:1035D000082817D909280CD00A280CD00B280CD0A1 -:1035E0000C280CD00D280CD00E2814BF4020302001 -:1035F00070470C2070471020704714207047182027 -:103600007047202070470000082817D90C280CD9D3 -:1036100010280CD914280CD918280CD920280CD91A -:1036200030288CBF0F200E207047092070470A20D9 -:1036300070470B2070470C2070470D20704700002A -:103640002DE9F843078C0446072F1ED900254FF6B5 -:10365000FF73D0E90298C5F12006A5F1200029FAF0 -:1036600005F1083508FA06F628FA00F0314301435F -:103670001846C9B2FFF762FF402D0346EBD13A4628 -:10368000E169BDE8F843FFF769BF4FF6FF70BDE899 -:10369000F883000010B54B6823B9CA8A63F30902A6 -:1036A000CA8210BD04691A681C600361C38A013BA9 -:1036B000C3824A60EFE700002DE9F84F1D46CB8A30 -:1036C0000F468146C3F30901924605290B4630D0C7 -:1036D0000020AAB207F11A049EB21FFA80F8042E45 -:1036E0000FD8904503F1010306D30A44FB8A62F325 -:1036F00009030120FB821AE01AF800600130E65449 -:10370000EAE79045F1D2A1F1050B1C237C68BBFBD5 -:10371000F3F203FB12BB1FFA8BF6002C45D148468F -:10372000FFF728FF044638B978606FF00200BDE863 -:10373000F88F4FF00008E6E7002606607860ADB22B -:103740004FF0000B454510D90AEB0803221D13F872 -:10375000011B08F101089155B1B21FFA88F81B2925 -:103760002BD0454506F10106F1D8FB8AC3F30902C7 -:10377000154465F30903BCE701321C4692B2236885 -:10378000002BF9D16B1F0B441C21B3FBF1F3013368 -:103790009BB29A42D3D2BBF1000FD0D14846FFF77B -:1037A000E9FE20B9C4F800B0BFE70122E7E7C0F89E -:1037B00000B05E4620600446C1E74545D5D948467D -:1037C000FFF7D8FE08B92060AFE7C0F800B00026C8 -:1037D00020600446B6E700002DE9F04F1C4607467E -:1037E00088462DED028B83B05B690192002B00F0BF -:1037F0009A80238C2BB1E269002A00F09480072B79 -:1038000035D807F10C00FFF7B5FE054638B96FF063 -:103810000205284603B0BDEC028BBDE8F08F1422F0 -:103820000021FEF7E1F8228CE16905F10800FEF7BE -:10383000C9F8208C48F00041013080B2FFF7E4FE67 -:10384000FFF7C6FE013880B2208401302874384664 -:103850006369228C1B782A4403F01F0363F03F0343 -:10386000137269602946FFF7EFFD0125D1E74FF09C -:10387000000900F10C034FF0800A4E464D4608EE59 -:10388000103A18EE100AFFF775FE83460028BED0E6 -:1038900014220021FEF7A8F8002E3AD1019B022243 -:1038A000ABF808300BF1080E1FFA82FC218C0CF1EA -:1038B0000100BCF1060F80B201D88E422BD3FFF776 -:1038C000A3FE8E4208BF4FF0400AFFF781FE6269F7 -:1038D0000138013512781BFA80F1013002F01F0225 -:1038E0002DB242EA491289F001094AEA020A48F077 -:1038F000004281F808A059468BF810003846CBF8F2 -:1039000004204FF0000AFFF79FFD238CB342B8D18B -:103910007FE70022C6E7E169895D01360EF80210F3 -:10392000B6B20132C0E76FF0010572E7F8B515468F -:103930000E463022002104461F46FEF755F8069B2E -:10394000B5F5001FA760636004F11000079B34BF4A -:103950006A094FF6FF72E661A362002397B29A42AA -:1039600006D800230360A782E3822383E360F8BDC7 -:103970000660013330462036F1E7000003781BB9BA -:103980004BB2002BC8BF0170704700000078704731 -:10399000F8B50C46C969074611B9238C002B37D1FD -:1039A000257E1F2D34D8387828BB228C072A2CD8A6 -:1039B000268A36F003032BD14FF6FF70FFF7CEFDBA -:1039C00020F0010031024FF6FF72400441EA056128 -:1039D000400C41EA4025234629463846FFF7FCFEC5 -:1039E000002807DD626913780133DBB21F2B88BF23 -:1039F00000231370F8BD218A2D0645EA01250543F1 -:103A00002046FFF71DFE0246E5E76FF00300F1E7F1 -:103A10006FF00100EEE7000070B58AB0044616466C -:103A20000021282268461D46FDF7DEFFBDF838302C -:103A300069462046ADF810300F9B05939DF8403045 -:103A40008DF81830119B0793BDF84830CDE9026519 -:103A5000ADF82030FFF79CFF0AB070BD2DE9F041B2 -:103A6000D36905460C4616460BB9138C5BBB377EF3 -:103A70001F2F28D895F80080B8F1000F26D03046C7 -:103A8000FFF7DEFD337821020246284641EAC331C2 -:103A9000338A41EA080141EA076141EA03413346BA -:103AA00041F08001FFF798FE00280ADD3378012BF2 -:103AB00007D1726913780133DBB21F2B88BF002353 -:103AC0001370BDE8F0816FF00100FAE76FF00300BA -:103AD000F7E70000F0B58BB004460D46174600210D -:103AE000282268461E46FDF77FFF9DF84C30294688 -:103AF00020465A1E534253416A468DF800309DF8C5 -:103B00004030ADF81030119B05939DF848308DF88A -:103B10001830149B0793BDF85430CDE90276ADF808 -:103B20002030FFF79BFF0BB0F0BD0000406A00B1F2 -:103B300004307047436A1A68426202691A6003617E -:103B4000C38A013BC38270472DE9F041D0F8208041 -:103B500014461D46184E4146002709B9BDE8F081BC -:103B6000D1E90223A21A65EB0303964277EB030324 -:103B70001ED2036A8B420DD1FFF78CFD036A1B68CE -:103B8000036203690B60C38A0161013B016AC3825E -:103B90008846E2E7FFF77EFD0B68C8F8003003694E -:103BA0000B60C38A0161013BC382D8F80010D4E7DF -:103BB00088460968D1E700BF80841E002DE9F04FD8 -:103BC0008BB00D4614469B46DDF850908046002889 -:103BD00000F01881B9F1000F00F01481531E3F2B43 -:103BE00000F21081012A03D1BBF1000F40F00A81DD -:103BF0000023CDE90833B8F81430B5EBC30F4FEA12 -:103C0000C30703D300200BB0BDE8F08F2B199F42F0 -:103C1000D8F80C3036BF7F1B2746FFB21BB9D8F847 -:103C20001030002B7AD0272D4DD8C5F1280600235F -:103C30002946B742009308ABD8F808002CBFF6B26B -:103C40003E46A7EB060A354432465FFA8AFAFFF78A -:103C50003DFCB8F81430282103F10053053BDB008C -:103C60000493D8F80C300393039B13B1BAF1000FFF -:103C70002CD1D8F8100040B1BAF1000F05D008AB34 -:103C80005246691A0096FFF721FC38B2002FB9D0CE -:103C900066070AD00AAB624203EBD40102F00702C6 -:103CA00011F8083C134101F8083C082C3DD9102CB0 -:103CB00040F2B580202C40F2B780BBF1000F00F03D -:103CC0009C80082335E0BA460026C2E7049BE02B1F -:103CD00028BFE02306930B44AB42059315D95A1B2A -:103CE0000398691A0096924508AB00F1040034BFAE -:103CF0005246D2B20792FFF7E9FB079A1644AAEBA5 -:103D0000020A1544F6B25FFA8AFA049B069A0599EC -:103D10009B1A0493039B1B680393A5E700933A4601 -:103D200008AB2946D8F80800ADE7BBF1000F13D067 -:103D30000123B4EBC30F6BD0082C12D89DF82030B0 -:103D4000621E23FA02F2D50706D54FF0FF3202FABF -:103D500004F423438DF820309DF8203089F800309A -:103D600051E7102C12D8BDF82030621E23FA02F25F -:103D7000D10706D54FF0FF3202FA04F42343ADF821 -:103D80002030BDF82030A9F800303CE7202C0FD8B7 -:103D90000899631E21FA03F3DA0705D54FF0FF32C5 -:103DA00002FA04F40C430894089BC9F800302AE78F -:103DB000402C2AD0611EC4F12102A4F12103DDE9C7 -:103DC000086526FA01F105FA02F225FA03F3114318 -:103DD0001943CB0711D50122A4F12003C4F120011E -:103DE00002FA03F322FA01F1A2400B43524263EBC1 -:103DF000430332432B43CDE90823DDE90823C9E916 -:103E0000002300E76FF00100FDE66FF00800FAE61E -:103E1000082CA1D9102CB4D9202CEED8C4E7BBF1C2 -:103E2000000FAED0022384E7BBF1000FBCD0042307 -:103E30007FE70000012A30B5144638BF012485B061 -:103E40000025402C28BF4024012ACDE9025518D86E -:103E50001B788DF8083063070AD004AB624203EB8D -:103E6000D40502F0070215F8083C934005F8083C19 -:103E7000034600912246002102A8FFF727FB05B068 -:103E800030BD082AE4D9102A03D81B88ADF80830C1 -:103E9000E1E7202A95BF1B68D3E900230293CDE90F -:103EA0000223D8E710B5CB681BB98B600B618B82FE -:103EB00010BD04691A681C600361C38A013BC38298 -:103EC000CA60F0E703064CBFC0F3C0300220704761 -:103ED00008B50246FFF7F6FF022806D15306C2F3E3 -:103EE0000F2001D100F0030008BDC2F30740FBE73B -:103EF0002DE9F04F93B004460D46CDE903230A683F -:103F00001046FFF7DFFF0228824614BFC2F30626E1 -:103F10000026002A80F2F38112F0C04940F0EF81C0 -:103F2000097B002900F0EB81022803D02378B342FB -:103F300040F0E881C2F3046310462944069302F07E -:103F40007F030593FFF7C4FF059B002283464FEADA -:103F50008348002348EA0A4848EA4668CE78CDE913 -:103F60000823F30948EA0008029368D0059B02463B -:103F700008A92046009353466768B847002800F018 -:103F8000C481276A4FB9414604F10C00FFF700FBDA -:103F9000074690B96FF0020055E03B6998450DD097 -:103FA0003F68002FF9D1414604F10C00FFF7F0FA09 -:103FB00007460028EED0236A3B60276297F817C0B7 -:103FC00006F01F08CCF3840CACEB0800A8EB0C0344 -:103FD0001FFA80FE0028B8BF0EF120001FFA83FEF2 -:103FE000B8BF00B2002B0793B8BF0EF12003D7E98A -:103FF0000221BCBF1BB2079352EA010338D0039BD6 -:104000004FF0000CDFF820E39A1A049B63EB0101E8 -:1040100096457CEB01032BD36B7B97F81AE0734535 -:1040200019D1029B002B78D0012821DC7868F8B9DF -:10403000DFF8F0C2944570EB010316D337E0276A2E -:1040400027B96FF00C0013B0BDE8F08F3B699845BD -:10405000B4D03F68F4E7B34890427CEB010301D34E -:104060000020F0E7029B002BFAD0079B0F2B17DCF8 -:10407000FA7DB3003946204602F0030203F07C03C8 -:104080001343FB75FFF706FB6B7BBB76029B3BB9CB -:10409000FB7DC3F38402013262F38603FB75D0E734 -:1040A0006A7BBB7E9A42DBD1029B002B35D0B309E1 -:1040B000022B32D0039B142200210DA8BB60049B6D -:1040C000FB60FDF791FC039B0AA920460A93049B21 -:1040D000ADF83EB00B932B1D8DF840A00C932B7BBD -:1040E0008DF84180013BDBB2ADF83C30069B8DF88A -:1040F0004230059B8DF8433094F82C3083F0010357 -:104100008DF84430A3689847FB7DC3F384030133E3 -:1041100003F01F039B02FB82A2E7FB7DC6F3401264 -:10412000B2EBD31F40F0F480C3F38403434540F067 -:10413000F280029AB6092B7B002A4DD0F2075DD49B -:10414000032B40F2EB80039BAE1D394604F10C00BB -:10415000BB603246049BFB602B7B033BDBB2FFF76B -:10416000ABFA00280CDA39462046FFF793FAFB7DBC -:10417000C3F38403013303F01F039B02FB8209E7AF -:10418000AB88DDE908843B834FF6FF73C9F120005B -:10419000A9F1200228FA09F109F1080904FA00F04E -:1041A00024FA02F2014318461143C9B2FFF7C6F9D7 -:1041B000B9F1400F0346E9D1B88231462A7B033A70 -:1041C000D2B2FFF7CBF9FB7DB882DA43C2F3C0125B -:1041D00062F3C713FB7543E786B92E1D013B3946D1 -:1041E00004F10C00DBB23246FFF766FA0028BADBB6 -:1041F0002A7B3146B88A013AD2B2E2E7F98A013B1A -:10420000C1F30901DAB204295BD8281D002307F1A4 -:104210001B069A4208D910F801CB013306F801C0F9 -:104220000131DBB20529F4D1039993420A9138BFD9 -:10423000043304992CBF002355FA83F30B9107F143 -:104240001B010C9179680E930D91291DFB8AADF825 -:104250003EB0C3F309038DF840A08DF841801A44A5 -:10426000069B8DF84230059BADF83C208DF843301D -:1042700094F82C3083F001038DF844300023B88A81 -:104280007B602A7B013AFFF769F93B8BB882834256 -:1042900003D1A3680AA92046984720460AA9FFF738 -:1042A00001FEFB7DBA8AC3F38403013303F01F03CD -:1042B0009B02FB823B8B9A420CBF00206FF01000E8 -:1042C000C1E67B68002BAFD0052001E01C303346EF -:1042D0001E68002EFAD1091A2E1D081D184401EB84 -:1042E000090C5FFA89F3BCF11B0F9DD89A429BD948 -:1042F00016F8013B09F1010900F8013BEFE76FF007 -:104300000900A0E66FF00A009DE66FF00B009AE648 -:104310006FF00D0097E66FF00E0094E66FF00F005F -:1043200091E600BF40420F0080841E00EFF3098336 -:10433000054968334A6B22F001024A6383F3098816 -:10434000002383F31188704700EF00E0302080F3F2 -:10435000118862B60D4B0E4AD96821F4E061090458 -:10436000090C0A430B49DA60D3F8FC2042F0807252 -:10437000C3F8FC20084AC2F8B01F116841F00101DF -:1043800011602022DA7783F82200704700ED00E008 -:104390000003FA0555CEACC5001000E0302310B57F -:1043A00083F311880E4B5B6813F4006314D0F1EEB5 -:1043B000103AEFF309844FF08073683CE361094BD6 -:1043C000DB6B236684F3098800F050FE10B1064BC6 -:1043D000A36110BD054BFBE783F31188F9E700BF2C -:1043E00000ED00E000EF00E03F0400084204000898 -:1043F00008B5074B074A196801F03D0199605368F9 -:104400000BB190689847BDE80840FFF7C7BF00BFF1 -:10441000000002402464002008B5084B196889098F -:1044200001F03D018A019A60054AD3680BB1106919 -:104430009847BDE80840FFF7B1BF00BF0000024049 -:104440002464002008B5084B1968090C01F03D01EF -:104450000A049A60054A53690BB190699847BDE810 -:104460000840FFF79BBF00BF00000240246400200B -:1044700008B5084B1968890D01F03D018A059A605D -:10448000054AD3690BB1106A9847BDE80840FFF7A9 -:1044900085BF00BF000002402464002008B5074B20 -:1044A000074A596801F03D01D960536A0BB1906A1F -:1044B0009847BDE80840FFF771BF00BF0000024009 -:1044C0002464002008B5084B5968890901F03D01B2 -:1044D0008A01DA60054AD36A0BB1106B9847BDE8D0 -:1044E0000840FFF75BBF00BF0000024024640020CB -:1044F00008B5084B5968090C01F03D010A04DA605F -:10450000054A536B0BB1906B9847BDE80840FFF725 -:1045100045BF00BF000002402464002008B5084BDE -:104520005968890D01F03D018A05DA60054AD36BAF -:104530000BB1106C9847BDE80840FFF72FBF00BFD4 -:10454000000002402464002008B5074B074A1968A0 -:1045500001F03D019960536C0BB1906C9847BDE838 -:104560000840FFF71BBF00BF000402402464002086 -:1045700008B5084B1968890901F03D018A019A6064 -:10458000054AD36C0BB1106D9847BDE80840FFF7A2 -:1045900005BF00BF000402402464002008B5084B9A -:1045A0001968090C01F03D010A049A60054A536D2F -:1045B0000BB1906D9847BDE80840FFF7EFBE00BF14 -:1045C000000402402464002008B5084B1968890DD6 -:1045D00001F03D018A059A60054AD36D0BB1106E5A -:1045E0009847BDE80840FFF7D9BE00BF000402406D -:1045F0002464002008B5074B074A596801F03D01C3 -:10460000D960536E0BB1906E9847BDE80840FFF734 -:10461000C5BE00BF000402402464002008B5084B5A -:104620005968890901F03D018A01DA60054AD36EB3 -:104630000BB1106F9847BDE80840FFF7AFBE00BF51 -:10464000000402402464002008B5084B5968090C96 -:1046500001F03D010A04DA60054A536F0BB1906F17 -:104660009847BDE80840FFF799BE00BF000402402C -:104670002464002008B5084B5968890D01F03D01FC -:104680008A05DA60054AD36F13B1D2F880009847E3 -:10469000BDE80840FFF782BE000402402464002009 -:1046A00000230C4910B51A460B4C0B6054F823003C -:1046B000026001EB430004334260402BF6D1074A0D -:1046C0004FF0FF339360D360C2F80834C2F80C3463 -:1046D00010BD00BF246400207C630008000002407D -:1046E0000F28F8B510D9102810D0112811D0122891 -:1046F00008D10F240720DFF8B4E00126DEF80050CF -:10470000A04208D9002649E00446F4E70F2400201F -:10471000F1E70724FBE706FA00F73D4240D1214CC0 -:104720004FEA001C3D4304EB00160EEBC000CEF830 -:104730000050C0E90123FBB24BB11B48836B43F02F -:1047400001038363036E43F001030366036E17F4F2 -:104750007F4F09D01448836B43F002038363036ED9 -:1047600043F002030366036E54F80C00036823F061 -:104770001F030360056815F00105FBD104EB0C0372 -:104780003D2493F80CC05F6804FA0CF43C602124CB -:104790000560446112B1987B00F00EFA3046F8BD16 -:1047A0000130ADE77C630008004502582464002016 -:1047B00010B5302484F31188FFF792FF002383F3B0 -:1047C000118810BD10B50446807B00F00BFA012360 -:1047D0001049627B03FA02F20B6823EA0203DAB2A1 -:1047E0000B604AB90C4A916B21F001019163116E83 -:1047F00021F001011166126E13F47F4F09D1064BAF -:104800009A6B22F002029A631A6E22F002021A6672 -:104810001B6E10BD246400200045025808B53023EB -:1048200083F31188FFF7CEFF002383F3118808BDBF -:104830000023054A19460133102BC2E9001102F189 -:104840000802F8D1704700BFA86400202DE9F74F97 -:1048500002F0030AC2F3C313C2F38009C2F3C10812 -:10486000C2F3411E574600224FF00F0B0193CB07B6 -:1048700033D502F00703019C012556009B00BAF1D5 -:10488000020F05FA02F504FA03FC44680BFA03F37D -:1048900024EA05046FEA030344EA090444604FF084 -:1048A0000304856804FA06F625EA06056FEA06049D -:1048B00045EA08058560C56825EA060545EA0E054E -:1048C000C5601BD1072A13D8056A2B4043EA0C03A5 -:1048D000036203681C403C430460490822D04FEA4D -:1048E000490901324FEA88084FEA8E0EBF00BEE741 -:1048F000456A2B4043EA0C034362EAE70568072A4E -:1049000004EA050444EA0704046005D8046A234065 -:1049100043EA0C030362E0E7446A234043EA0C03E2 -:104920004362DAE703B0BDE8F08F00000268436835 -:104930001143016003B1184770470000024A136831 -:1049400043F0C0031360704700100140024A13682F -:1049500043F0C00313607047007C004037B51A4C29 -:104960001A4D204600F0E8FA04F1140000940023E8 -:104970004FF40072164900F0A5F94FF40072154982 -:1049800004F138000094144B00F01EFA134BC4E9F4 -:104990001735134C204600F0CFFA04F11400002321 -:1049A0004FF400720F49009400F08CF90E4B4FF455 -:1049B00000720E4904F13800009400F005FA0C4B27 -:1049C000C4E9173503B030BD2865002000E1F505C6 -:1049D00000660020006A00203D49000800100140E8 -:1049E00094650020006800204D490008006C0020FC -:1049F000007C0040037C30B5284C002918BF0C46D1 -:104A0000012B0CD1264B984236D1264B1A6D42F021 -:104A100010021A659A6F42F010029A679B6F226823 -:104A2000036EC16D03EB52038466B3FBF2F362685D -:104A3000150442BF23F0070503F0070343EA4503CB -:104A4000CB60A36843F040034B60E36843F001038D -:104A50008B6042F4967343F001030B604FF0FF3319 -:104A60000B62510505D512F0102213D0B2F1805F10 -:104A700012D080F8643030BD0B4B9842CFD1094B37 -:104A80009A6C42F000429A641A6F42F000421A6730 -:104A90001B6FC4E77F23ECE73F23EAE77C64000851 -:104AA0002865002000450258946500202DE9F04754 -:104AB000C66D05463768F469210734621AD014F0D0 -:104AC000080118BF4FF48071E20748BF41F0200190 -:104AD000A3074FF0300348BF41F04001600748BFD3 -:104AE00041F0800183F31188281DFFF71FFF002389 -:104AF00083F31188E2050AD5302383F311884FF43C -:104B00008061281DFFF712FF002383F311884FF007 -:104B100030094FF0000A14F0200838D13B0616D5B2 -:104B20004FF0300905F1380A200610D589F31188B5 -:104B3000504600F07DF9002836DA0821281DFFF7DD -:104B4000F5FE27F080033360002383F31188790694 -:104B500014D5620612D5302383F31188D5E91323C7 -:104B60009A4208D12B6C33B127F040071021281D41 -:104B7000FFF7DCFE3760002383F31188E30618D5C6 -:104B8000AA6E1369ABB15069BDE8F047184789F3C5 -:104B90001188736A284695F86410194000F0E6F908 -:104BA0008AF31188F469B6E7B06288F31188F46972 -:104BB000BAE7BDE8F0870000090100F16043012277 -:104BC00003F56143C9B283F8001300F01F039A4054 -:104BD00043099B0003F1604303F56143C3F880215F -:104BE0001A60704700F01F0301229A40430900F148 -:104BF00060409B0000F5614003F1604303F56143B1 -:104C0000C3F88020C3F88021002380F80033704768 -:104C1000F8B51546826804460B46AA4200D285685C -:104C2000A1692669761AB5420BD218462A46FCF7C6 -:104C3000C9FEA3692B44A3612846A3685B1BA3603C -:104C4000F8BD0CD9AF1B18463246FCF7BBFE3A46FE -:104C5000E1683044FCF7B6FEE3683B44EBE71846F6 -:104C60002A46FCF7AFFEE368E5E70000836893425D -:104C7000F7B50446154600D28568D4E90460361AB3 -:104C8000B5420BD22A46FCF79DFE63692B44636153 -:104C90002846A3685B1BA36003B0F0BD0DD9324664 -:104CA000AF1B0191FCF78EFE01993A46E068314452 -:104CB000FCF788FEE3683B44E9E72A46FCF782FEFE -:104CC000E368E4E710B50A440024C361029B8460F2 -:104CD000C16002610362C0E90000C0E9051110BDB6 -:104CE00008B5D0E90532934201D1826882B9826861 -:104CF000013282605A1C426119700021D0E90432ED -:104D00009A4224BFC368436100F052FA002008BDF4 -:104D10004FF0FF30FBE7000070B5302304460E462D -:104D200083F31188A568A5B1A368A269013BA360BC -:104D3000531CA36115782269934224BFE368A361E1 -:104D4000E3690BB120469847002383F31188284676 -:104D500007E03146204600F01BFA0028E2DA85F32E -:104D6000118870BD2DE9F74F04460E461746984648 -:104D7000D0F81C904FF0300A8AF311884FF0000BE6 -:104D8000154665B12A4631462046FFF741FF0346E6 -:104D900060B94146204600F0FBF90028F1D000231D -:104DA00083F31188781B03B0BDE8F08FB9F1000FD1 -:104DB00003D001902046C847019B8BF31188ED1A60 -:104DC0001E448AF31188DCE7C160C361009B8260E6 -:104DD0000362C0E905111144C0E900000161704798 -:104DE000F8B504460D461646302383F31188A768AC -:104DF000A7B1A368013BA36063695A1C62611D707F -:104E0000D4E904329A4224BFE3686361E3690BB1D9 -:104E100020469847002080F3118807E0314620465D -:104E200000F0B6F90028E2DA87F31188F8BD000037 -:104E3000D0E9052310B59A4201D182687AB9826817 -:104E40000021013282605A1C82611C7803699A42F7 -:104E500024BFC368836100F0ABF9204610BD4FF05A -:104E6000FF30FBE72DE9F74F04460E4617469846FC -:104E7000D0F81C904FF0300A8AF311884FF0000BE5 -:104E8000154665B12A4631462046FFF7EFFE034638 -:104E900060B94146204600F07BF90028F1D000239C -:104EA00083F31188781B03B0BDE8F08FB9F1000FD0 -:104EB00003D001902046C847019B8BF31188ED1A5F -:104EC0001E448AF31188DCE70268436811430160DD -:104ED00003B11847704700001430FFF743BF0000CC -:104EE0004FF0FF331430FFF73DBF00003830FFF7BD -:104EF000B9BF00004FF0FF333830FFF7B3BF0000F9 -:104F00001430FFF709BF00004FF0FF311430FFF7F6 -:104F100003BF00003830FFF763BF00004FF0FF32DF -:104F20003830FFF75DBF0000012914BF6FF0130098 -:104F300000207047FFF712BD044B0360002343605D -:104F4000C0E9023301230374704700BF9464000872 -:104F500010B53023044683F31188FFF74BFD02237D -:104F60000020237480F3118810BD000038B5C36998 -:104F700004460D461BB904210844FFF7A5FF294646 -:104F800004F11400FFF7ACFE002806DA201D4FF4F0 -:104F90000061BDE83840FFF797BF38BD0023826845 -:104FA000037503691B6899689142FBD25A680360D4 -:104FB000426010605860704700238268037503697F -:104FC0001B6899689142FBD85A6803604260106080 -:104FD0005860704708B50846302383F311880B7D6D -:104FE000032B05D0042B0DD02BB983F3118808BDFA -:104FF0008B6900221A604FF0FF338361FFF7CEFF09 -:105000000023F2E7D1E9003213605A60F3E70000B1 -:10501000FFF7C4BF054BD96808751868026853606C -:105020001A600122D8600275FBF7F4B9006E002007 -:105030000C4B30B5DD684B1C87B004460FD02B46B7 -:10504000094A684600F046F92046FFF7E3FF009B57 -:1050500013B1684600F048F9A86907B030BDFFF702 -:10506000D9FFF9E7006E0020D54F0008044B1A68FD -:10507000DB6890689B68984294BF002001207047CD -:10508000006E0020084B10B51C68D8682268536079 -:105090001A600122DC602275FFF78EFF0146204670 -:1050A000BDE81040FBF7B6B9006E002038B5074CDC -:1050B00001230025064907482370656000F0C2FC03 -:1050C0000223237085F3118838BD00BF687000206B -:1050D000C0640008006E002008B572B6044B186565 -:1050E00000F0FCFA00F0C2FB024B03221A70FEE74C -:1050F000006E00206870002000F02CB98B60022345 -:10510000086108468B8270478368A3F1840243F8E4 -:10511000142C026943F8442C426943F8402C094A94 -:1051200043F8242CC268A3F1200043F8182C022273 -:1051300003F80C2C002203F80B2C034A43F8102C24 -:10514000704700BF2D040008006E002008B5FFF76F -:10515000DBFFBDE80840FFF75BBF0000024BDB68E8 -:1051600098610F20FFF756BF006E0020302383F3B5 -:105170001188FFF7F3BF000008B50146302383F321 -:1051800011880820FFF754FF002383F3118808BD1E -:10519000064BDB6839B1426818605A60136043609F -:1051A0000420FFF745BF4FF0FF307047006E00202E -:1051B0000368984206D01A680260506018469961E8 -:1051C000FFF726BF70470000036810B59C68A24235 -:1051D0000CD85C688A600B604C60216059609968EB -:1051E0008A1A9A604FF0FF33836010BD121B1B6850 -:1051F000ECE700000A2938BF0A2170B504460D46C5 -:105200000A26601900F016FC00F0FEFB041BA54204 -:1052100003D8751C04462E46F3E70A2E04D9012054 -:10522000BDE8704000F04EBC70BD0000F8B5144BF6 -:105230000D460A2A4FF00A07D96103F11001826076 -:1052400038BF0A224160196914460160486018613C -:10525000A81800F0DFFB00F0D7FB431B0646A34273 -:1052600006D37C1C28192746354600F0E3FBF2E7FD -:105270000A2F04D90120BDE8F84000F023BCF8BD96 -:10528000006E0020F8B506460D4600F0BDFB0F4A43 -:10529000134653F8107F9F4206D12A4601463046F6 -:1052A000BDE8F840FFF7C2BFD169BB68441A2C19AA -:1052B00028BF2C46A34202D92946FFF79BFF22466E -:1052C00031460348BDE8F840FFF77EBF006E00207E -:1052D000106E0020C0E90323002310B45DF8044BD6 -:1052E0004361FFF7CFBF000010B5194C2369984206 -:1052F0000DD08168D0E9003213605A609A680A4480 -:105300009A60002303604FF0FF33A36110BD026871 -:10531000234643F8102F53600022026022699A420C -:1053200003D1BDE8104000F07FBB936881680B4457 -:10533000936000F069FB2269E1699268441AA24215 -:10534000E4D91144BDE81040091AFFF753BF00BF6C -:10535000006E00202DE9F047DFF8BC8008F110074F -:105360002C4ED8F8105000F04FFBD8F81C40AA681B -:10537000031B9A423ED814444FF00009D5E900328D -:10538000C8F81C4013605A60C5F80090D8F8103077 -:10539000B34201D100F048FB89F31188D5E903310C -:1053A00028469847302383F311886B69002BD8D0A7 -:1053B00000F02AFB6A69A0EB040982464A450DD237 -:1053C000022000F07FFB0022D8F81030B34208D151 -:1053D00051462846BDE8F047FFF728BF121A22447D -:1053E000F2E712EB09092946384638BF4A46FFF76B -:1053F000EBFEB5E7D8F81030B34208D01444C8F833 -:105400001C00211AA960BDE8F047FFF7F3BEBDE814 -:10541000F08700BF106E0020006E002038B500F04D -:10542000F3FA054AD2E90845031B181945F10001B2 -:10543000C2E9080138BD00BF006E0020002070479F -:10544000FEE70000704700004FF0FF30704700009B -:10545000BFF34F8F044B1A695107FCD1D3F81021C9 -:105460005207F8D1704700BF0020005208B50D4B1D -:105470001B78ABB9FFF7ECFF0B4BDA68D10704D50B -:105480000A4A5A6002F188325A60D3F80C21D207D6 -:1054900006D5064AC3F8042102F18832C3F8042174 -:1054A00008BD00BF70700020002000522301674536 -:1054B00008B5114B1B78F3B9104B1A69510703D586 -:1054C000DA6842F04002DA60D3F81021520705D5BD -:1054D000D3F80C2142F04002C3F80C21FFF7B8FFCB -:1054E000064BDA6842F00102DA60D3F80C2142F090 -:1054F0000102C3F80C2108BD70700020002000528A -:105500000F289ABF00F5806040040020704700001B -:105510004FF4003070470000102070470F2808B586 -:105520000BD8FFF7EDFF00F500330268013204D11C -:1055300004308342F9D1012008BD0020FCE70000BF -:105540000F2838B505463FD8FFF782FF1F4CFFF7FD -:105550008DFF4FF0FF3307286361C4F814311DD865 -:105560002361FFF775FF030243F02403E360E36860 -:1055700043F08003E36023695A07FCD42846FFF711 -:1055800067FFFFF7BDFF4FF4003100F04BF92846ED -:10559000FFF78EFFBDE83840FFF7C0BFC4F81031F9 -:1055A000FFF756FFA0F108031B0243F02403C4F8E1 -:1055B0000C31D4F80C3143F08003C4F80C31D4F82A -:1055C00010315B07FBD4D9E7002038BD0020005222 -:1055D0002DE9F84F05460C46104645EA0203DE0663 -:1055E00002D00020BDE8F88F20F01F00DFF8BCB02B -:1055F000DFF8BCA0FFF73AFF04EB0008444503D1F5 -:105600000120FFF755FFEDE720222946204600F054 -:10561000EFFD10B920352034F0E72B4605F12002CC -:105620001F68791CDDD104339A42F9D105F1784322 -:105630001B481C4EB3F5801F1B4B38BF184603F1A7 -:10564000F80332BFD946D1461E46FFF701FF076077 -:10565000A5EB040C336804F11C0143F00203336032 -:10566000231FD9F8007017F00507FAD153F8042F5B -:105670008B424CF80320F4D1BFF34F8FFFF7E8FEC5 -:105680004FF0FF332022214603602846336823F081 -:105690000203336000F0ACFD0028BBD03846B0E711 -:1056A000142100520C2000521420005210200052ED -:1056B0001021005210B5084C237828B11BB9FFF710 -:1056C000D5FE0123237010BD002BFCD02070BDE857 -:1056D0001040FFF7EDBE00BF7070002038B5054DDB -:1056E00000240334696855F80C0B00F0ADF8122C57 -:1056F000F7D138BDCC640008084600F071BD000049 -:1057000038B5EFF311859DB9EFF30584C4F30804B0 -:10571000302334B183F31188FFF780FE85F31188BD -:1057200038BD83F31188FFF779FE84F3118838BD03 -:10573000BDE83840FFF772BE10B5FFF7E1FF104C2F -:10574000C008104A002340EA4170C908A0FB04ECDD -:10575000A0FB020E1CEB0000A1FB044CA1FB0212FB -:105760005B41001943EB0C0011EB0E0142F100020A -:10577000411842F10000090941EA007010BD00BF64 -:10578000CFF753E3A59BC4200244074BD2B210B518 -:10579000904200D110BD441C00B253F8200041F8E3 -:1057A000040BE0B2F4E700BF504000580E4B30B598 -:1057B0001C6F240405D41C6F1C671C6F44F4004448 -:1057C0001C670A4C02442368D2B243F480732360FE -:1057D000074B904200D130BD441C51F8045B00B22D -:1057E00043F82050E0B2F4E7004402580048025861 -:1057F0005040005807B5012201A90020FFF7C4FF5F -:10580000019803B05DF804FB13B50446FFF7F2FFFF -:10581000A04205D0012201A900200194FFF7C6FF94 -:1058200002B010BD0144BFF34F8F064B884204D332 -:10583000BFF34F8FBFF36F8F7047C3F85C02203008 -:10584000F4E700BF00ED00E00144BFF34F8F064BCB -:10585000884204D3BFF34F8FBFF36F8F7047C3F8F5 -:1058600070022030F4E700BF00ED00E07047000058 -:10587000074B45F255521A6002225A6040F6FF72F9 -:105880009A604CF6CC421A600122024B1A707047A3 -:105890000048005878700020034B1B781BB1034B65 -:1058A0004AF6AA221A607047787000200048005813 -:1058B000034B1A681AB9034AD2F8D0241A60704709 -:1058C0007470002000400258024B4FF48032C3F83D -:1058D000D02470470040025808B5FFF7E9FF024B9B -:1058E0001868C0F3806008BD7470002070B5BFF305 -:1058F0004F8FBFF36F8F1A4A0021C2F85012BFF3C7 -:105900004F8FBFF36F8F536943F400335361BFF37D -:105910004F8FBFF36F8FC2F88410BFF34F8FD2F851 -:10592000803043F6E074C3F3C900C3F34E335B0128 -:1059300003EA0406014646EA81750139C2F860525D -:10594000F9D2203B13F1200FF2D1BFF34F8F5369EF -:1059500043F480335361BFF34F8FBFF36F8F70BD3C -:1059600000ED00E0FEE70000214B2248224A70B51E -:10597000904237D3214BC11EDA1C121A22F00302C7 -:105980008B4238BF00220021FCF72EF81C4A00236E -:10599000C2F88430BFF34F8FD2F8803043F6E07402 -:1059A000C3F3C900C3F34E335B0103EA04060146A7 -:1059B00046EA81750139C2F86C52F9D2203B13F1E5 -:1059C000200FF2D1BFF34F8FBFF36F8FBFF34F8F15 -:1059D000BFF36F8F0023C2F85032BFF34F8FBFF376 -:1059E0006F8F70BD53F8041B40F8041BC0E700BF65 -:1059F000F86600087C7000207C7000207C7000201D -:105A000000ED00E000F01AB9014B586A704700BF82 -:105A1000000C0040034B002258631A610222DA6036 -:105A2000704700BF000C0040014B0022DA60704755 -:105A3000000C0040014B5863704700BF000C004051 -:105A4000FEE7000070B51B4B0025044686B0586089 -:105A50000E4685620163FEF779FC04F11003A56030 -:105A6000E562C4E904334FF0FF33C4E90044C4E9FC -:105A70000635FFF7C9FF2B46024604F134012046E4 -:105A8000C4E9082380230C4A2565FFF737FB01236F -:105A90000A4AE06000920375684672680192B26833 -:105AA000CDE90223064BCDE90435FFF74FFB06B0E5 -:105AB00070BD00BF687000201465000819650008FB -:105AC000415A0008024AD36A1843D062704700BFA7 -:105AD000006E00204B6843608B688360CB68C360B6 -:105AE0000B6943614B6903628B6943620B68036016 -:105AF0007047000008B53A4B40F2FF713948D3F8BF -:105B000088200A43C3F88820D3F8882022F4FF6253 -:105B100022F00702C3F88820D3F88830324B1A6C81 -:105B20000A431A649A6E0A439A66304A9B6E11467B -:105B3000FFF7D0FF00F5806002F11C01FFF7CAFFFC -:105B400000F5806002F13801FFF7C4FF00F58060C6 -:105B500002F15401FFF7BEFF00F5806002F1700111 -:105B6000FFF7B8FF00F5806002F18C01FFF7B2FF8C -:105B700000F5806002F1A801FFF7ACFF00F580603E -:105B800002F1C401FFF7A6FF00F5806002F1E00119 -:105B9000FFF7A0FF00F5806002F1FC01FFF79AFF1C -:105BA00002F58C7100F58060FFF794FF00F008F9B2 -:105BB0000F4BD3F8902242F00102C3F89022D3F8A1 -:105BC000942242F00102C3F894220522C3F89820DF -:105BD0004FF06052C3F89C20064AC3F8A02008BDCD -:105BE0000044025800000258004502582065000891 -:105BF00000ED00E01F00080308B500F0CDFAFFF744 -:105C000055FA0B4BDA6B42F04002DA635A6E22F01F -:105C100040025A665B6E074B1A6842F008021A602F -:105C20001A6842F004021A60BDE80840FFF740BE5F -:105C30000045025800180248704700000E4B9A6C4D -:105C400042F008029A641A6F42F008021A670B4A7F -:105C50001B6FD36B43F00803D363C722084B9A62D0 -:105C60004FF0FF32DA6200229A615A63DA605A60BA -:105C700001225A611A607047004502580010005C0A -:105C8000000C0040094A08B51169D3680B40D9B22D -:105C90009B076FEA0101116107D5302383F3118857 -:105CA000FFF72AFA002383F3118808BD000C004097 -:105CB000044BDA6B0243DA635A6E104358665B6E2C -:105CC000704700BF0045025808B53C4B4FF0FF310C -:105CD000D3F8802062F00042C3F88020D3F88020FF -:105CE00002F00042C3F88020D3F88020D3F884204B -:105CF000C3F88410D3F884200022C3F88420D3F89A -:105D00008400D86F40F0FF4040F4FF0040F4DF40D3 -:105D100040F07F00D867D86F20F0FF4020F4FF00EC -:105D200020F4DF4020F07F00D867D86FD3F88800D8 -:105D30006FEA40506FEA5050C3F88800D3F88800EB -:105D4000C0F30A00C3F88800D3F88800D3F89000A5 -:105D5000C3F89010D3F89000C3F89020D3F89000C7 -:105D6000D3F89400C3F89410D3F89400C3F89420A7 -:105D7000D3F89400D3F89800C3F89810D3F898009B -:105D8000C3F89820D3F89800D3F88C00C3F88C108F -:105D9000D3F88C00C3F88C20D3F88C00D3F89C0087 -:105DA000C3F89C10D3F89C10C3F89C20D3F89C3007 -:105DB000FEF776FCBDE8084000F0BEB9004402588A -:105DC00008B50122504BC3F80821504B5A6D42F0E0 -:105DD00002025A65DA6F42F00202DA670422DB6FD0 -:105DE0004B4BDA605A689104FCD54A4A1A6001228A -:105DF0009A60494ADA6000221A614FF440429A617F -:105E0000434B9A699204FCD51A6842F480721A6076 -:105E1000424B1A6F12F4407F04D04FF480321A675D -:105E200000221A671A6842F001021A603B4B1A6896 -:105E30005007FCD500221A611A6912F03802FBD112 -:105E4000012119604FF0804159605A67344ADA6283 -:105E5000344A1A611A6842F480321A602F4B1A6869 -:105E60009103FCD51A6842F480521A601A689204B1 -:105E7000FCD52D4A2D499A6200225A63196301F517 -:105E80007C01DA6301F5E77199635A64284A1A6460 -:105E9000284ADA621A6842F0A8521A601F4B1A6840 -:105EA00002F02852B2F1285FF9D148229A614FF4EA -:105EB0008862DA6140221A621F4ADA641F4A1A6550 -:105EC0001F4A5A651F4A9A6532231F4A1360136896 -:105ED00003F00F03022BFAD1104A136943F00303B6 -:105EE0001361136903F03803182BFAD14FF00050F7 -:105EF000FFF7DEFE4FF08040FFF7DAFE4FF0004084 -:105F0000BDE80840FFF7D4BE0080005100450258AC -:105F10000048025800C000F004000001004402588C -:105F20000000FF0100889008322060006302090130 -:105F3000470E0508DD0BBF01200000200000011006 -:105F40000910E00000010110002000524FF0B042A3 -:105F500008B5D2F8883003F00103C2F8883023B1C5 -:105F6000044A13680BB150689847BDE80840FEF733 -:105F700015BA00BFA86400204FF0B04208B5D2F8AF -:105F8000883003F00203C2F8883023B1044A9368D2 -:105F90000BB1D0689847BDE80840FEF7FFB900BFD5 -:105FA000A86400204FF0B04208B5D2F8883003F062 -:105FB0000403C2F8883023B1044A13690BB1506955 -:105FC0009847BDE80840FEF7E9B900BFA864002083 -:105FD0004FF0B04208B5D2F8883003F00803C2F899 -:105FE000883023B1044A93690BB1D0699847BDE862 -:105FF0000840FEF7D3B900BFA86400204FF0B042BC -:1060000008B5D2F8883003F01003C2F8883023B105 -:10601000044A136A0BB1506A9847BDE80840FEF77E -:10602000BDB900BFA86400204FF0B04310B5D3F84D -:10603000884004F47872C3F88820A30604D5124A75 -:10604000936A0BB1D06A9847600604D50E4A136B69 -:106050000BB1506B9847210604D50B4A936B0BB1DB -:10606000D06B9847E20504D5074A136C0BB1506C0E -:106070009847A30504D5044A936C0BB1D06C98479C -:10608000BDE81040FEF78AB9A86400204FF0B04385 -:1060900010B5D3F8884004F47C42C3F88820620528 -:1060A00004D5164A136D0BB1506D9847230504D5DE -:1060B000124A936D0BB1D06D9847E00404D50F4A96 -:1060C000136E0BB1506E9847A10404D50B4A936E22 -:1060D0000BB1D06E9847620404D5084A136F0BB118 -:1060E000506F9847230404D5044A936F0BB1D06FC7 -:1060F0009847BDE81040FEF751B900BFA8640020E2 -:1061000008B50348FEF7D2FCBDE80840FEF746B9E3 -:106110002865002008B50348FEF7C8FCBDE8084024 -:10612000FEF73CB99465002008B5FFF7ABFDBDE86C -:106130000840FEF733B90000062108B50846FEF70F -:106140003BFD06210720FEF737FD06210820FEF75C -:1061500033FD06210920FEF72FFD06210A20FEF758 -:106160002BFD06211720FEF727FD06212820FEF72C -:1061700023FD09217A20FEF71FFD07213220FEF7BB -:106180001BFD0C212520FEF717FD0C215320BDE837 -:106190000840FEF711BD000008B5FFF795FDFEF7BA -:1061A00047FBFEF7C7FEFFF747FDBDE80840FFF7D6 -:1061B00029BC00000B460146184600F003B8000059 -:1061C00000F00EB810B5054C13462CB10A46014636 -:1061D0000220AFF3008010BD2046FCE70000000065 -:1061E000024B01461868FFF787BA00BF3C23002026 -:1061F00010B501390244904201D1002005E0037836 -:1062000011F8014FA34201D0181B10BD0130F2E775 -:106210002DE9F041A3B1C91A17780144044603F1EE -:10622000FF3C8C42204601D9002009E00578BD42A0 -:1062300004F10104F5D10CEB0405D618A54201D1F7 -:10624000BDE8F08115F8018D16F801EDF045F5D0A7 -:10625000E7E70000034611F8012B03F8012B002AA1 -:10626000F9D17047636F6D2E6375626570696C6FED -:10627000742E6865726534666300000053544D33B4 -:106280003248373F3F3F0053544D3332483733781D -:106290002F3732780053544D3332483734332F3749 -:1062A00035332F373530000001105A0003105900E4 -:1062B000012058000320560040A2E4F164689106D2 -:1062C0000041A3E5F26569920700000043414E4694 -:1062D0004449666163653A204D6573736167652063 -:1062E00052414D204F766572666C6F772100000039 -:1062F0004261642043414E496661636520696E6472 -:1063000065782E00000100000001FF0000A00040A1 -:1063100000A400400000000000000000712A0008F6 -:10632000F9220008F93100086923000875230008E4 -:106330008D270008ED2400083123000835230008CC -:106340000D230008F522000849270008192300083A -:1063500061330008252300081D27000801040E05ED -:10636000054B02020E05054B04010E05054B050108 -:106370000B04044B08010603034600001000024012 -:10638000080002400008024000000B002800024004 -:10639000080002400408024006010C0040000240D0 -:1063A000080002400808024010020D005800024098 -:1063B000080002400C08024016030E007000024064 -:1063C0000C0002401008024000040F008800024048 -:1063D0000C0002401408024006051000A000024014 -:1063E0000C0002401808024010061100B8000240DC -:1063F0000C0002401C08024016072F001004024047 -:106400000804024020080240000838002804024026 -:1064100008040240240802400609390040040240F2 -:106420000804024028080240100A3A0058040240BA -:10643000080402402C080240160B3B007004024086 -:106440000C04024030080240000C3C00880402406A -:106450000C04024034080240060D4400A00402402F -:106460000C04024038080240100E4500B8040240F7 -:106470000C0402403C080240160F46000096000043 -:10648000000000000000000000000000000000000C -:106490000000000000000000F54E0008E14E00087A -:1064A0001D4F0008094F0008154F0008014F000854 -:1064B000ED4E0008D94E0008294F00086330000057 -:1064C000BC640008586E00206870002000010020A5 -:1064D00000FF010002000000000000300000040086 -:1064E0000800000000000024000008000400000074 -:1064F0000004000000FC0000020000000000043066 -:1065000000800000080000000000003800000100CA -:10651000010000006D61696E0069646C6500000037 -:106520000000002800000000AAAAAAAA0000002477 -:10653000FFFF0000000000000000000000A0550A5E -:1065400000000000AAAA9AAA00500000FFF2000072 -:10655000000000770000990000000000000000002B -:10656000AAAAAAAA00000000FFFF00000000000085 -:10657000000000005A000000000000009AAAAAAA29 -:1065800000000000F3FF0000990000000000000080 -:106590000A00000000000000AAAAAAAA0500000044 -:1065A000FFFF000088000000000000000000000065 -:1065B00000000000AAAAAAAA00000000FFFF000035 -:1065C00000000000000000000000000000000000CB -:1065D000AAAAAAAA00000000FFFF00000000000015 -:1065E000000000000000000000000000AAAAAAAA03 -:1065F00000000000FFFF000000000000000000009D -:106600000000000000000000AAAAAAAA00000000E2 -:10661000FFFF00000000000000000000000000007C -:1066200000000000AAAAAAAA00000000FFFF0000C4 -:10663000000000000000000000000000000000005A -:10664000AAAAAAAA00000000FFFF000000000000A4 -:106650000000000000000000130400000000000023 -:106660000000180000000000FE2A0100D204000013 -:10667000FF00000028650020946500200000000055 -:106680007C62000883040000876200085004000058 -:106690009562000840230020000000000000000078 -:1066A00000000000000000000000000000000000EA -:1066B00000000000000000000000000000000000DA -:1066C00000000000000000000000000000000000CA -:1066D00000000000000000000000000000000000BA -:1066E00000000000000000000000000000000000AA -:0866F0000000000000000000A2 +:101AE00087BA00BF94630020AC6300201C23002051 +:101AF000F8B571B6002301201A46194602F0A8FE77 +:101B00000446802003F0E8FE002849D00025254A3D +:101B100080274FF4D06C3D26136913F0C06F26D197 +:101B2000D2F8103113F0C06F21D1236805F10061A4 +:101B300099602368D86023685F602368C3F800C099 +:101B400021680B6843F001030B6021680B6823F0E8 +:101B50001E030B6021680B68DB07FCD4237B8035F8 +:101B6000616806FA03F3B5F5001F0B60D4D1204677 +:101B700002F0A4FEB5F5001F11D000240A4E0B4D53 +:101B8000012003F00BFE3388A34205D928682044C6 +:101B9000013403F049FDF6E7002003F0FFFD61B6D4 +:101BA000F8BD00BF00200052AE6300206863002033 +:101BB0002DE9F3470D46044600219046284640F2A1 +:101BC0007912FFF711FF234620220021284604F155 +:101BD000220702F07BF9231D022220212846C0267D +:101BE00002F074F9631D03222221284602F06EF9E7 +:101BF000A31D03222521284602F068F904F10803F9 +:101C000010222821284602F061F904F1100308226D +:101C10003821284602F05AF904F111030822402124 +:101C2000284602F053F904F11203082248212846FD +:101C300002F04CF904F1140320225021284602F04E +:101C400045F904F1180340227021284602F03EF9BC +:101C500004F120030822B021284602F037F904F1EC +:101C600021030822B821284602F030F9314608360F +:101C70003B4608222846013702F028F9B6F5A07F36 +:101C8000F4D194F83230314604F1330A00268DF84D +:101C9000073008220DF10703284602F017F99DF8D6 +:101CA00007304FEAC6099E4209F5A47720D394F87D +:101CB0003231502B28BF50238DF80730B8F1000F78 +:101CC00008D1394609F24F170DF1070307222846BC +:101CD00002F0FCF8002604F233149DF8073007EBFD +:101CE000C6019E420DD30731C80802B0BDE8F08797 +:101CF0000AEB0603082239462846013602F0E6F8C8 +:101D0000CDE7A31908222846013602F0DFF8E4E700 +:101D100013B50446084600212022234601900160A5 +:101D2000C0F8031002F0D2F8231D019802222021EE +:101D300002F0CCF8631D01980322222102F0C6F8BC +:101D4000A31D01980322252102F0C0F8019804F197 +:101D500008031022282102F0B9F8072002B010BDB4 +:101D6000F7B5047F05460E462CB1838A122B02D9A3 +:101D7000012003B0F0BD0023072228460096194633 +:101D800001F068FF731C01220721009328460023FD +:101D900001F060FFD4B9B31C052208212846009346 +:101DA00023460D2401F056FFB378102BE0D83746B8 +:101DB000BB1BB278934210D307342B7FA88AE40868 +:101DC000B3B9844294BF00200120D2E7AB8A082433 +:101DD000DB00083BDB08B370E6E7FB1C214608226A +:101DE0002846009300230834013701F033FFDFE772 +:101DF000201A18BF0120BCE7F7B5047F05460E4640 +:101E00002CB1838ACA2B02D9012003B0F0BD002374 +:101E1000082228460096194601F01CFF731CD4B90D +:101E200008220093234610241146284601F012FF91 +:101E30007378C82BE8D801235F1C7278013B93426A +:101E400010D307342B7FA88AE408B3B9844294BF27 +:101E500000200120D9E7AB8A0824DB00083BDB081F +:101E60007370E5E7F3192146082228460093002302 +:101E700001F0F0FE08343B46DEE7201A18BF0120CF +:101E8000C3E70000F7B50D46044600211646284674 +:101E90008122FFF7A9FD234608220021284602F0EF +:101EA00015F894F901206378002AB8BF7F238DF8D4 +:101EB00007309EB90F270DF1070307220821284696 +:101EC00002F004F8002602349DF8073007EBC60143 +:101ED0009E4205D30731C80803B0F0BD0827F1E7DB +:101EE000A31908222846013601F0F0FFECE70000B4 +:101EF000F7B50E460546002114463046CE22FFF7C0 +:101F000073FD2B4628220021304601F0DFFF2B7A9B +:101F1000C82B28BFC8238DF807308CB930240DF1A9 +:101F2000070308222821304601F0D0FF2F467B1BF3 +:101F30009DF80720934205D3E01DC00803B0F0BD13 +:101F40002824F3E707F10903214608223046083424 +:101F5000013701F0BBFFEAE7F7B5047F05460E46FF +:101F600034B1838AB3F5827F02D9012003B0F0BD7A +:101F70000123102200212846009601F06BFEDCB9F7 +:101F8000B31C09221021284600932346192401F08E +:101F900061FE7388B3F5807FE7D83746BB1B728834 +:101FA000934210D307342B7FA88AE408B3B9844244 +:101FB00094BF00200120D9E7AB8A1024DB00103B3E +:101FC000DB087380E5E73B1D214608222846009385 +:101FD00000230834013701F03DFEDFE7201A18BF67 +:101FE0000120C3E730B50A44084D91420DD011F8E5 +:101FF000013B5840082340F30004013B2C4013F000 +:10200000FF0384EA5000F6D1EFE730BD2083B8ED3E +:10201000F7B5384A6B46106851686A4603C308230F +:102020003549364804F084FB0446002833D10A259C +:10203000334A6B46106851686A4603C30823314926 +:102040002E4804F075FB0446002849D00369B3F517 +:10205000E01F45D8B0F8661040F2134291423FD1DC +:10206000294A024402F15C018B4239D35C3B23498B +:1020700000209E1AFFF7B6FF04F1640107463246BE +:102080000020FFF7AFFFA3689F4229D1E368984281 +:1020900008BF002524E00369B3F5E01F27D8418B72 +:1020A00040F21342914220D1174A024402F110013A +:1020B0008B4218D3103B114900209D1AFFF792FF65 +:1020C00004F1180106462A460020FFF78BFFA3689B +:1020D0009E4202D1E368984201D00D25A8E7002571 +:1020E000284603B0F0BD1025A2E70C25A0E70B257C +:1020F0009EE700BFD8670008DCFF1B000000040853 +:10210000E167000890FF1B000800FCF710B5037C96 +:10211000044613B9006803F013FC204610BD00000C +:102120000023BFF35B8FC360BFF35B8FBFF35B8F95 +:102130008360BFF35B8F7047BFF35B8F0068BFF3B3 +:102140005B8F704770B505460C30FFF7F5FF04460E +:1021500005F108063046FFF7EFFFA04206D96D688B +:102160003046FFF7E9FF2544281A70BD3046FFF7D7 +:10217000E3FF201AF9E7000070B505464068A0B1FA +:1021800005F10C0605F10800FFF7D6FF04463046BE +:10219000FFF7D2FF844204F1FF34304694BF6D68EC +:1021A0000025FFF7C9FF2C44201A70BD38B50C4636 +:1021B0000546FFF7C7FFA04210D305F10800FFF75F +:1021C000BBFF04446868BFF35B8FB4FBF0F100FB16 +:1021D00011440120AC60BFF35B8F38BD0020FCE7E9 +:1021E0002DE9F041144607460D46FFF7C5FF84422E +:1021F00028BF0446D4B1B84658F80C6B4046FFF7E8 +:102200009BFF3044286040467E68FFF795FF331AF5 +:102210009C4203D801206C60BDE8F081A41B6B6078 +:102220003B682044AB60E8600220F5E72046F3E716 +:1022300038B50C460546FFF79FFFA04210D305F1C5 +:102240000C00FFF779FF04446868BFF35B8FB4FBB1 +:10225000F0F100FB11440120EC60BFF35B8F38BD4F +:102260000020FCE72DE9FF418846694607466C4699 +:10227000FFF7B6FF002506B204EBC606B4420AD04B +:10228000626808EB050120680834FFF79BFB54F8EF +:10229000043C1D44F2E729463846FFF7C9FF2846AB +:1022A00004B0BDE8F0810000F8B505460C300F46DB +:1022B000FFF742FF05F1080604463046FFF73CFFF2 +:1022C000A042304688BF6C68FFF736FF201A38609E +:1022D00020B12C683046FFF72FFF2044F8BD0000E6 +:1022E00073B5144606460D46FFF72CFF8442019055 +:1022F00028BF0446DCB101A93046FFF7D5FF019B9A +:1023000033B93268C5E90233C5E9002401200CE085 +:102310009C42286038BF0194019884426860F5D9D6 +:102320003368241A0220AB60EC6002B070BD204616 +:10233000FBE700002DE9FF410F4669466C46FFF7B9 +:10234000CFFF00B2002604EBC005AC4209D0D4F8A0 +:102350000480B81954F8081B42464644FFF732FB84 +:10236000F3E7304604B0BDE8F081000038B505461B +:10237000FFF7E0FF044601462846FFF717FF204617 +:1023800038BD000008B103F0DBBA704770470000A9 +:1023900010B41346026814680022A4465DF8044B8A +:1023A0006047000000F5805090F859047047000025 +:1023B00000F5805090F852047047000000F58050FE +:1023C00090F95804704700004E207047302383F383 +:1023D000118800F58052D2F89C34D2F89804184441 +:1023E000D2F894341844D2F87C341844D2F88C349F +:1023F0001844D2F888341844002383F311887047B6 +:1024000000F58050C0F85414012070472DE9F04FBA +:102410000C4600F5805185B01F4691F852340546B0 +:102420009046BDF838909BB1D1F878340133C1F8AB +:1024300078342368980006D4237B082B0BD9627B61 +:102440000AB10F2B07D9D1F87C340133C1F87C34A1 +:102450004FF0FF3010E0302383F31188EB6AD3F89C +:10246000C42012F4001B0AD0D1F8803400200133BC +:10247000C1F8803480F3118805B0BDE8F08F206882 +:102480004822D3F8C4300028C3F3044A6B6AB4BFAF +:1024900040F08040800412FB0A334FEA4A1618606D +:1024A000226852004FEA0A6244BF40F000501860B0 +:1024B000207B42EA00425A60607B10B342F4401233 +:1024C0005A60D1F8B0240132C1F8B024AA1902F53B +:1024D0008352117B41F020011173207B039300F0A4 +:1024E000E3FF0330039B80105FFA8BF20BF1010BCB +:1024F00082420DDA04EB820103EB820249689160AB +:10250000F2E7AA1902F58352117B60F34511E3E764 +:102510000122EB6A05EB4A1102FA0AF201F5825137 +:10252000C3F8D020AB19183104F10C0203F5825323 +:10253000C3E90487234653F8040B934241F8040B84 +:10254000F9D11B882E440B8041F2680346F803A0A2 +:1025500006F5805609F0030396F86C2043F010034B +:1025600022F01F02134386F86C30002383F3118896 +:1025700042463B4621462846CDF8009000F05AFFDF +:10258000012079E72DE9F04700F58056044696F8DA +:102590005254002D40F00381037C032B40F09480C3 +:1025A00028462B462F465FFA80FC944510DA01EB53 +:1025B000CC0E51F83CC0BCF1000F04DBDEF804C0C7 +:1025C000BCF1000F02DB01370130ECE70133FBE720 +:1025D000302080F31188E06AF3B9D0F8803043F0FE +:1025E0000203C0F880304E23E06A002F6FD1D0F88C +:1025F000803043F00103C0F880306A4B6A4A1B68A0 +:1026000003F1805303F52C539B009342A36240F2E5 +:10261000B080664800F0E6FE4D2B42D8DFF884819A +:102620004FEA034EDFF88891D8F800C04EEA8C0ECE +:10263000C0F884E00CF1805000F52C5080006061FF +:1026400003EB0C00D4F82CC0C3F14E03C8F8000013 +:10265000DCF8800040F03000CCF880004FF0000C37 +:10266000D4F81480E6465FFA8CF08242BCDD01EBC0 +:10267000C00A51F83000002810DBDAF804A0BAF1E3 +:10268000000F0BDA09EA00400AF07F0A40EA0A006C +:1026900040F0084048F82E000EF1010E0CF1010C3C +:1026A000E1E7836923F00103836100F0A1FE0646A0 +:1026B000E36A9B69D90704D500F09AFE831BFA2BC5 +:1026C000F6D9002383F311882846BDE8F087B7EBDD +:1026D000530F3DD2DFF8CCE04FEA074CDEF8003074 +:1026E0004CEA830CC0F888C003F1805003EB470329 +:1026F000002700F52C50CEF80030BC468000A061C9 +:10270000E06AD0F8803043F00C03C0F88030D4F891 +:1027100018E0FBB29A427FF770AF51F8330001EB3B +:10272000C3080028D8F8043001DB002B0EDB20F0B2 +:10273000604023F0604340F0005043F000434EF807 +:102740003C000EEBCC000CF1010C43600137E0E7DC +:10275000836923F00103836100F04AFE0646E36AC1 +:102760009B69DA07ADD500F043FE831BFA2BF6D93F +:10277000A7E7E26A936923F00103936100F038FE52 +:102780000746E36A9B69DB0705D500F031FEC31BF2 +:10279000FA2BF6D995E7012586F8525491E70025E2 +:1027A00092E700BFBC630020FCB50040EC67000866 +:1027B0000000FF0713B500F580540191606CFFF72E +:1027C000DBFC1F280AD920220199606CFFF74AFD23 +:1027D000A0F120035842584102B010BD0020FBE791 +:1027E00008B5302383F3118800F58050406CFFF763 +:1027F00097FC002383F3118808BD000000220260CB +:1028000082814260826070470022002310B5C0E9D7 +:102810000023002304460C3020F8043CFFF7EEFFB1 +:10282000204610BD2DE9F0479A4688B007468846F5 +:102830009146302383F3118807F580546846FFF7EB +:10284000E3FF606CFFF77EFC1F282ED9202269462B +:10285000606CFFF78BFD202827D194F8523423B306 +:1028600003AD444605AB2E46083403CE9E4244F8E1 +:10287000080C44F8041C3546F5D130682060B38854 +:10288000A380DDE90023C9E90023BDF80830AAF8D8 +:102890000030002383F3118853464A4641463846A8 +:1028A00008B0BDE8F04700F0B3BD002080F3118808 +:1028B00008B0BDE8F08700002DE9F84F0023064678 +:1028C00000F58154054688461034C0E90133274B92 +:1028D00046F8303B374638462037FFF795FFA7428A +:1028E000F9D105F580544FF4805305F5A3594FF005 +:1028F000000A26630026676405F5835709F110096D +:102900004FF0000B1037E663C4E90D36012384F85D +:10291000403084F84830A7F11800203747E910AB61 +:10292000FFF76CFF47F8286C4F45F4D1B8F1010F61 +:1029300084F85884A4F85A64A4F85C64A4F85E642B +:1029400084F86064A4F86264A4F86464A4F866641B +:1029500084F8686402D9064800F044FD054B284617 +:1029600053F82830EB62BDE8F88F00BF3C680008E0 +:10297000106800082C680008044B10B5197804464C +:102980004A1C1A70FFF798FF204610BDB96300205B +:102990002DE9F04300295AD02E4E2F48B6FBF1F412 +:1029A00081428CBF0A201120431EB4FBF0F700FBCC +:1029B0001740DDB220B1022B1846F5D8002032E0D6 +:1029C0007B1EB3F5806F2ED2C5EBC5084FF47A732A +:1029D00008F103044FEAE40EC4F3C7040EF1010941 +:1029E000281B0EFB033E5FFA80FC59FA80F0BEFB09 +:1029F000F0F0B0F5617F18DC83B2601C5CFA80F007 +:102A00007843B6FBF0F08142D8D1611E0F29D5D8AA +:102A10000CF1FF310729D1D80120138057801071A4 +:102A2000547182F806C0BDE8F08308F1FF34E0106D +:102A3000C4F3C70400F1010E2D1B00FB03335FFA42 +:102A400085FC5EFA85F5B3FBF5F39BB2D5E7084646 +:102A5000E9E700BF00B4C4043F420F0030B50D4B9E +:102A600005200D4D1C786C438C420ED15978012005 +:102A7000518099785171D9789171197911715B7977 +:102A800003EB83035B00138030BD013803F10603C1 +:102A9000E8D1F9E77C68000840420F0038B540F201 +:102AA0007772C36A154CC3F8BC200722C36AC3F807 +:102AB000C8202268C16A930043F4C023C1F8A03043 +:102AC00002F1805302F16C01C56A03F52C53EA321E +:102AD00089009B00226041F0E061094AC361C5F8AA +:102AE000C01003F5D87103F56A73416293428362A3 +:102AF00002D9044800F076FC38BD00BFBC6300205A +:102B0000FCB50040EC6700082DE9F04F00F580555A +:102B10001F4689B0044695F8583489469046022BE2 +:102B200004D90026304609B0BDE8F08FA84A52F813 +:102B3000231009B942F82300A648C4F80C90017884 +:102B40002774C9B9302383F31188A34BD3F8EC2041 +:102B500042F48072C3F8EC20D3F8942042F48072DF +:102B6000C3F89420D3F8942022F48072C3F8942000 +:102B70000123037081F3118895F851347BB9302318 +:102B800083F31188954A95F85834D35C0BB3012B25 +:102B900028D0012385F85134002383F31188302392 +:102BA00083F31188E26A936923F01003936100F0C4 +:102BB0001FFC8246E36A9E6916F0080619D000F0F1 +:102BC00017FCA0EB0A03FA2BF4D9002686F3118830 +:102BD000A8E70321132002F03FF80321152002F09B +:102BE0003BF8D6E70321142002F036F80321162023 +:102BF000F5E79A6942F001029A6100F0F9FB82461A +:102C0000E36A9A69D00706D400F0F2FBA0EB0A034E +:102C1000FA2BF5D9D9E79A694FF0000A42F002027F +:102C20009A61E36AC3F854A08AF3118804F5825BC1 +:102C3000686CFFF775FA0BF1100B20220021684633 +:102C4000FEF7D2FE02A8FFF7D9FD6A460BEB06039A +:102C50000DF1180ECDF818A094460833BCE8030017 +:102C6000F44543F8080C43F8041C6246F4D1DCF840 +:102C7000000020361860B6F5806F9CF804201A71A9 +:102C8000DBD1002304F5A252494620461A3285F8CA +:102C9000503485F85334FFF77BFE064690B9E26A5C +:102CA000936923F00103936100F0A2FB0546E36AF8 +:102CB0009B69D9077FF535AF00F09AFB431BFA2BD0 +:102CC000F5D92EE795F85E34C5F86C94591E95F841 +:102CD0005F34E26A013B1B0243EA416395F86014EA +:102CE00001390B43B5F85C14013943EA0143D36160 +:102CF000B8F1000F36D004F5A35241462046023207 +:102D0000FFF7ACFE90B9E26A936923F00103936187 +:102D100000F06EFB0546E36A9B69DA077FF501AFB9 +:102D200000F066FB431BFA2BF5D9FAE695F8672409 +:102D3000C5F87084511E95F86824E36A013A1201BF +:102D400042EA012295F8661401390A43B5F8641481 +:102D5000013942EA014242F40002DA604FF4206293 +:102D6000E36A9A64E36A4FF000082046C3F8BC8027 +:102D7000FFF794FE85F859846FF04042E36A1A65C4 +:102D8000174AE36A5A654FF00222E36A9A654FF0E8 +:102D9000FF32E36AC3F8E0200322E36A9742DA6570 +:102DA0003FF4C0AEE26A936923F00103936100F03F +:102DB0001FFB0746E36A9B69DB0705D500F018FB9C +:102DC000C31BFA2BF6D9ACE6012385F85234A9E6E9 +:102DD000B0630020B8630020004402582468000853 +:102DE000550200022DE9F04F054689B090469946FC +:102DF000002741F2680A00F58056EB6AD3F8D83014 +:102E0000FB40D80751D505EB47124FEA471B524408 +:102E10001379190749D4D6F884340133C6F88434B9 +:102E200005F5A553C3E9008913799A0605EB0B0252 +:102E300048BFD6F8B434524444BF0133C6F8B43462 +:102E4000137943F008031371DB0723D596F8533445 +:102E500003B305F582546846FFF7D6FC03AB18347C +:102E60005C4404F1080C2068083454F8041C1A4629 +:102E7000644503C21346F6D12068694610602846AF +:102E8000A2889A800123ADF808302B68CDE900892B +:102E9000DB6B9847D6F8A834D6F854040133C6F84B +:102EA000A83410B103681B6998470137202FA4D1BB +:102EB00009B0BDE8F08F00002DE9F04F0F468DB04E +:102EC000044600F097FA82468946002F5BD1E36AF8 +:102ED000D3F8A02012F4FE0F03D100200DB0BDE8FE +:102EE000F08FD3F8A420920141BF04F58051D1F8AE +:102EF00098240132C1F89824D3F8A4205606ECD0C7 +:102F0000D3F8A450E669C5F305254823E8464FF0F9 +:102F1000000B03FB05664046FFF770FC326851006A +:102F20004ABF22F06043C2F38A4343F00043920059 +:102F300048BF43F080430093736813F400131BBF32 +:102F4000012304F580528DF80D308DF80D301EBF31 +:102F5000D2F8B8340133C2F8B834F38803F00F0361 +:102F60008DF80C309DF80C0000F09EFA5FFA8BF3A0 +:102F7000984225D9F2180CA90BF1010B127A0B44D7 +:102F800003F82C2CEEE7012FA7D1E36AD3F8B02089 +:102F900012F4FE0FA1D0D3F8B420950141BF04F57F +:102FA0008051D1F898240132C1F89824D3F8B42084 +:102FB000500692D0D3F8B450266AC5F30525A4E78D +:102FC000EFB9E36AC3F8A85004A807ADFFF71CFCEB +:102FD00098E80F0007C52B800023204604A9ADF810 +:102FE0001830236804F58054DB6BCDE904A99847B9 +:102FF00058B1D4F890340133C4F890346EE7012FFF +:10300000E2D1E36AC3F8B850DEE7D4F89434012083 +:103010000133C4F8943461E72DE9F04105460F46C9 +:1030200000F58054012639462846FFF745FF10B1C8 +:1030300084F85364F7E7D4F8A834D4F8540401337F +:10304000C4F8A83420B10368BDE8F0411B691847F3 +:10305000BDE8F081C36AF0B51A6C12F47F0F2BD073 +:103060001B6C00F5805441F268054FF0010CC4F868 +:10307000AC340023471900EB43125E012A44117956 +:1030800011F0020F15D0490713D4B959C66A0CFACA +:1030900001F1D6F8CCE011EA0E0F0AD0C6F8D41030 +:1030A000117941F004011171D4F88C240132C4F873 +:1030B0008C240133202BDED1F0BD00002B4B70B5EA +:1030C0001E561B5C012B30D8294D2A4A55F8233057 +:1030D00052F8264013B349B3236D9A0510D54FF427 +:1030E0000073236500F086F950EA01020B4602D016 +:1030F000013861F10003024655F82600FFF772FE21 +:10310000236D9B012CD54FF0007255F826302265B7 +:1031100003F58053012283F8592421E0012323651C +:10312000102323654FF48053236570BD236DDA07A8 +:1031300002D4236D5B0706D50523002155F8260030 +:103140002365FFF769FF236DD80602D4236D590666 +:1031500006D55023012155F826002365FFF75CFFB3 +:1031600055F82600BDE87040FFF774BF28680008D6 +:10317000B06300202C68000808B5302383F3118861 +:10318000FFF768FF002383F3118808BDC36AD3F8F3 +:10319000C00010F07C5005D0D3F8C40080F40010BB +:1031A000C0F340507047000008B5302383F3118806 +:1031B00000F58050406CFEF7C5FF002383F31188B3 +:1031C00043090CBF0120002008BD000000F580531A +:1031D00093F8592462B1C16A8A6922F001028A61B6 +:1031E000D3F89C240132C3F89C24002283F859248C +:1031F000704700002DE9F743302181F3118800F575 +:103200008251002541F2680E4FF00108103100F59F +:10321000805C00EB45147444267977071CD4F606CD +:103220001AD58E69D0F82C9008FA06F6D9F8CC7029 +:103230003E4211D04F6801970F689742019F9F410E +:103240000AD2C9F8D460267946F004062671DCF863 +:1032500088440134CCF8884401352031202DD8D160 +:10326000002383F3118803B0BDE8F083F8B51E4650 +:1032700000230F46054613701446FFF795FF80F0B4 +:10328000010038701EB12846FFF780FF2070F8BD9E +:103290002DE9F04F85B099460D468046164691F8C7 +:1032A00000B0DDE90EA302931378019300F0A2F8B9 +:1032B0002B7804460F4613B93378002B41D02246B1 +:1032C0003B464046FFF796FFFFF756FFFFF77EFFAE +:1032D0004B4632462946FFF7C9FF2B7833B1BBF185 +:1032E000000F03D0012005B0BDE8F08F337813B193 +:1032F000019B002BF6D108F5805303935445029BA4 +:1033000077EB03031DD2039BD3F85404C8B10368C1 +:10331000AAEB04011B6898474B46324629464046B3 +:10332000FFF7A4FF2B7813B1BBF1000FDAD133788C +:1033300013B1019B002BD5D100F05CF804460F4679 +:10334000DCE70020CFE70000002108B50846FFF7C2 +:10335000B5FEBDE8084001F071B8000008B50121D4 +:103360000020FFF7ABFEBDE8084001F067B80000A1 +:1033700008B500210120FFF7A1FEBDE8084001F0DB +:103380005DB80000012108B50846FFF797FEBDE8CB +:10339000084001F053B8000000B59BB0EFF309817D +:1033A00068226846FEF70EFBEFF30583014B9B6B2B +:1033B000FEE700BF00ED00E008B5FFF7EDFF0000FD +:1033C00000B59BB0EFF3098168226846FEF7FAFA70 +:1033D000EFF30583014B5B6BFEE700BF00ED00E000 +:1033E000FEE700000FB408B5029801F0E9FEFEE721 +:1033F00002F0D4BA02F0B6BA13B56C46031D84E8E5 +:10340000060094E8030083E80500012002B010BD27 +:1034100073B58568019155B11B885B0707D4D0E966 +:1034200000369B6B9847019AC1B23046A8470120ED +:1034300002B070BDF0B5866889B005460C465EB135 +:10344000BDF838305B070AD4D0E900379B6B98474A +:103450002246C1B23846B047012009B0F0BD002273 +:10346000002301F10806CDE9002300230A46ADF848 +:10347000083003AB1068083252F8041C1C46B242F4 +:1034800003C42346F6D1106820609288A280FFF71B +:10349000B1FF0423ADF808302B68CDE90001DB6BE8 +:1034A000694628469847D7E7082817D909280CD035 +:1034B0000A280CD00B280CD00C280CD00D280CD0CE +:1034C0000E2814BF4020302070470C207047102079 +:1034D0007047142070471820704720207047000064 +:1034E0002DE9F041456A15B94162BDE8F0814B68AC +:1034F000AC4623F06047C3F38A464FEAD37EC3F35A +:10350000807816EA230638BF3E462B465A68BEEB43 +:10351000D27F22F060440AD0002A18DAA40CB44208 +:1035200017D19D420FD10D60DEE71346EEE7A742AB +:1035300007D102F08044C2F3807242450BD054B1EF +:10354000EFE708D2EDE7CCF800100B60CDE7B4420E +:1035500001D0B442E5D81A689C46002AE5D119602A +:10356000C3E700002DE9F047089D01F0070400EBD8 +:10357000D1004FF47F494FEAD508224405F00705F2 +:10358000944201D1BDE8F08704F0070705F0070A6F +:10359000111B08EBD50E57453E4613F80EC038BF39 +:1035A0005646C6F108068E4228BF0E46E108415C29 +:1035B00034443544B94029FA06F721FA0AF1FFB23A +:1035C0008CEA010147FA0AF739408CEA010C03F84A +:1035D0000EC0D5E780EA0120082341F2210201B2A2 +:1035E000013B4000002980B2B8BF504013F0FF03F8 +:1035F000F5D1704738B50C468D18A54200D138BDBD +:1036000014F8011BFFF7E6FFF7E7000042684AB134 +:10361000136881894360438901339BB29942438196 +:1036200038BF83811046704770B588B004462022A9 +:103630000D4668460021FEF7D7F920460495FFF7AE +:10364000E5FF024660B16B46054608AE1C460835EC +:1036500003CCB44245F8080C45F8041C2346F5D1C8 +:10366000104608B070BD0000082817D909280CD0F2 +:103670000A280CD00B280CD00C280CD00D280CD00C +:103680000E2814BF4020302070470C2070471020B7 +:1036900070471420704718207047202070470000A2 +:1036A000082817D90C280CD910280CD914280CD9A3 +:1036B00018280CD920280CD930288CBF0F200E20B8 +:1036C0007047092070470A2070470B2070470C2074 +:1036D00070470D20704700002DE9F843078C044621 +:1036E000072F1ED900254FF6FF73D0E90298C5F1C8 +:1036F0002006A5F1200029FA05F1083508FA06F69A +:1037000028FA00F0314301431846C9B2FFF762FFBF +:10371000402D0346EBD13A46E169BDE8F843FFF797 +:1037200069BF4FF6FF70BDE8F883000010B54B6825 +:1037300023B9CA8A63F30902CA8210BD04691A68F0 +:103740001C600361C38A013BC3824A60EFE700004B +:103750002DE9F84F1D46CB8A0F468146C3F3090178 +:10376000924605290B4630D00020AAB207F11A0470 +:103770009EB21FFA80F8042E0FD8904503F1010382 +:1037800006D30A44FB8A62F309030120FB821AE094 +:103790001AF800600130E654EAE79045F1D2A1F151 +:1037A000050B1C237C68BBFBF3F203FB12BB1FFA67 +:1037B0008BF6002C45D14846FFF728FF044638B960 +:1037C00078606FF00200BDE8F88F4FF00008E6E780 +:1037D000002606607860ADB24FF0000B454510D969 +:1037E0000AEB0803221D13F8011B08F1010891558B +:1037F000B1B21FFA88F81B292BD0454506F1010606 +:10380000F1D8FB8AC3F30902154465F30903BCE749 +:1038100001321C4692B22368002BF9D16B1F0B4476 +:103820001C21B3FBF1F301339BB29A42D3D2BBF11B +:10383000000FD0D14846FFF7E9FE20B9C4F800B028 +:10384000BFE70122E7E7C0F800B05E46206004460B +:10385000C1E74545D5D94846FFF7D8FE08B92060ED +:10386000AFE7C0F800B0002620600446B6E70000CD +:103870002DE9F04F1C46074688462DED028B83B09C +:103880005B690192002B00F09A80238C2BB1E269D6 +:10389000002A00F09480072B35D807F10C00FFF7C1 +:1038A000B5FE054638B96FF00205284603B0BDECF9 +:1038B000028BBDE8F08F14220021FEF795F8228CD0 +:1038C000E16905F10800FEF77DF8208C48F0004121 +:1038D000013080B2FFF7E4FEFFF7C6FE013880B288 +:1038E00020840130287438466369228C1B782A446E +:1038F00003F01F0363F03F03137269602946FFF76B +:10390000EFFD0125D1E74FF0000900F10C034FF066 +:10391000800A4E464D4608EE103A18EE100AFFF7A0 +:1039200075FE83460028BED014220021FEF75CF805 +:10393000002E3AD1019B0222ABF808300BF1080EA1 +:103940001FFA82FC218C0CF10100BCF1060F80B241 +:1039500001D88E422BD3FFF7A3FE8E4208BF4FF053 +:10396000400AFFF781FE62690138013512781BFABF +:1039700080F1013002F01F022DB242EA491289F0B3 +:1039800001094AEA020A48F0004281F808A05946B3 +:103990008BF810003846CBF804204FF0000AFFF7F0 +:1039A0009FFD238CB342B8D17FE70022C6E7E169CF +:1039B000895D01360EF80210B6B20132C0E76FF031 +:1039C000010572E7F8B515460E463022002104467F +:1039D0001F46FEF709F8069BB5F5001FA760636058 +:1039E00004F11000079B34BF6A094FF6FF72E661CD +:1039F000A362002397B29A4206D800230360A782ED +:103A0000E3822383E360F8BD06600133304620364D +:103A1000F1E7000003781BB94BB2002BC8BF01705F +:103A20007047000000787047F8B50C46C969074632 +:103A300011B9238C002B37D1257E1F2D34D838782F +:103A400028BB228C072A2CD8268A36F003032BD1D8 +:103A50004FF6FF70FFF7CEFD20F0010031024FF668 +:103A6000FF72400441EA0561400C41EA40252346CB +:103A700029463846FFF7FCFE002807DD6269137807 +:103A80000133DBB21F2B88BF00231370F8BD218ADE +:103A90002D0645EA012505432046FFF71DFE024697 +:103AA000E5E76FF00300F1E76FF00100EEE70000DB +:103AB00070B58AB0044616460021282268461D4685 +:103AC000FDF792FFBDF8383069462046ADF810305A +:103AD0000F9B05939DF840308DF81830119B07938C +:103AE000BDF84830CDE90265ADF82030FFF79CFF06 +:103AF0000AB070BD2DE9F041D36905460C46164663 +:103B00000BB9138C5BBB377E1F2F28D895F800802C +:103B1000B8F1000F26D03046FFF7DEFD33782102E2 +:103B20000246284641EAC331338A41EA080141EAA4 +:103B3000076141EA0341334641F08001FFF798FEF7 +:103B400000280ADD3378012B07D17269137801331D +:103B5000DBB21F2B88BF00231370BDE8F0816FF02C +:103B60000100FAE76FF00300F7E70000F0B58BB053 +:103B700004460D4617460021282268461E46FDF7DA +:103B800033FF9DF84C30294620465A1E534253417C +:103B90006A468DF800309DF84030ADF81030119B2A +:103BA00005939DF848308DF81830149B0793BDF8A5 +:103BB0005430CDE90276ADF82030FFF79BFF0BB013 +:103BC000F0BD0000406A00B104307047436A1A68D3 +:103BD000426202691A600361C38A013BC382704773 +:103BE0002DE9F041D0F8208014461D46184E41467C +:103BF000002709B9BDE8F081D1E90223A21A65EBDB +:103C00000303964277EB03031ED2036A8B420DD166 +:103C1000FFF78CFD036A1B68036203690B60C38AAC +:103C20000161013B016AC3828846E2E7FFF77EFD3E +:103C30000B68C8F8003003690B60C38A0161013B5F +:103C4000C382D8F80010D4E788460968D1E700BFDE +:103C500080841E002DE9F04F8BB00D4614469B4624 +:103C6000DDF850908046002800F01881B9F1000F6F +:103C700000F01481531E3F2B00F21081012A03D162 +:103C8000BBF1000F40F00A810023CDE90833B8F8FA +:103C90001430B5EBC30F4FEAC30703D300200BB0BA +:103CA000BDE8F08F2B199F42D8F80C3036BF7F1B30 +:103CB0002746FFB21BB9D8F81030002B7AD0272D39 +:103CC0004DD8C5F1280600232946B742009308AB1A +:103CD000D8F808002CBFF6B23E46A7EB060A3544DA +:103CE00032465FFA8AFAFFF73DFCB8F81430282113 +:103CF00003F10053053BDB000493D8F80C30039329 +:103D0000039B13B1BAF1000F2CD1D8F8100040B1C9 +:103D1000BAF1000F05D008AB5246691A0096FFF7BA +:103D200021FC38B2002FB9D066070AD00AAB624234 +:103D300003EBD40102F0070211F8083C134101F82B +:103D4000083C082C3DD9102C40F2B580202C40F2C4 +:103D5000B780BBF1000F00F09C80082335E0BA4625 +:103D60000026C2E7049BE02B28BFE02306930B4408 +:103D7000AB42059315D95A1B0398691A00969245D0 +:103D800008AB00F1040034BF5246D2B20792FFF7ED +:103D9000E9FB079A1644AAEB020A1544F6B25FFA49 +:103DA0008AFA049B069A05999B1A0493039B1B6845 +:103DB0000393A5E700933A4608AB2946D8F80800D4 +:103DC000ADE7BBF1000F13D00123B4EBC30F6BD0F1 +:103DD000082C12D89DF82030621E23FA02F2D50773 +:103DE00006D54FF0FF3202FA04F423438DF8203059 +:103DF0009DF8203089F8003051E7102C12D8BDF81A +:103E00002030621E23FA02F2D10706D54FF0FF32AE +:103E100002FA04F42343ADF82030BDF82030A9F8AD +:103E200000303CE7202C0FD80899631E21FA03F3D9 +:103E3000DA0705D54FF0FF3202FA04F40C43089478 +:103E4000089BC9F800302AE7402C2AD0611EC4F133 +:103E50002102A4F12103DDE9086526FA01F105FA42 +:103E600002F225FA03F311431943CB0711D50122BE +:103E7000A4F12003C4F1200102FA03F322FA01F1B4 +:103E8000A2400B43524263EB430332432B43CDE941 +:103E90000823DDE90823C9E9002300E76FF00100EA +:103EA000FDE66FF00800FAE6082CA1D9102CB4D971 +:103EB000202CEED8C4E7BBF1000FAED0022384E77C +:103EC000BBF1000FBCD004237FE70000012A30B50E +:103ED000144638BF012485B00025402C28BF40245B +:103EE000012ACDE9025518D81B788DF808306307F0 +:103EF0000AD004AB624203EBD40502F0070215F8C6 +:103F0000083C934005F8083C0346009122460021F6 +:103F100002A8FFF727FB05B030BD082AE4D9102A14 +:103F200003D81B88ADF80830E1E7202A95BF1B684D +:103F3000D3E900230293CDE90223D8E710B5CB687B +:103F40001BB98B600B618B8210BD04691A681C6001 +:103F50000361C38A013BC382CA60F0E703064CBF1A +:103F6000C0F3C0300220704708B50246FFF7F6FFE5 +:103F7000022806D15306C2F30F2001D100F003003E +:103F800008BDC2F30740FBE72DE9F04F93B00446AC +:103F90000D46CDE903230A681046FFF7DFFF02282C +:103FA000824614BFC2F306260026002A80F2F8815A +:103FB00012F0C04940F0F481097B002900F0F08143 +:103FC000022803D02378B34240F0ED81C2F30463AA +:103FD00010462944069302F07F030593FFF7C4FFC0 +:103FE000059B002283464FEA8348002348EA0A489B +:103FF00048EA4668CE78CDE90823F30948EA000884 +:10400000029368D0059B024608A9204600935346B8 +:104010006768B847002800F0C981276A4FB9414650 +:1040200004F10C00FFF700FB074690B96FF00200A7 +:1040300055E03B6998450DD03F68002FF9D14146C6 +:1040400004F10C00FFF7F0FA07460028EED0236ACF +:104050003B60276297F817C006F01F08CCF3840C6A +:10406000ACEB0800A8EB0C031FFA80FE0028B8BFD9 +:104070000EF120001FFA83FEB8BF00B2002B079399 +:10408000B8BF0EF12003D7E90221BCBF1BB20793D2 +:1040900052EA010338D0039B4FF0000CDFF81CE319 +:1040A0009A1A049B63EB010196457CEB01032BD329 +:1040B0006B7B97F81AE0734519D1029B002B78D0DF +:1040C000012821DC7868F8B9DFF8ECC2944570EB80 +:1040D000010316D337E0276A27B96FF00C0013B03D +:1040E000BDE8F08F3B699845B4D03F68F4E7B2482B +:1040F00090427CEB010301D30020F0E7029B002BF0 +:10410000FAD0079B0F2B17DCFA7DB3003946204607 +:1041100002F0030203F07C031343FB75FFF706FB79 +:104120006B7BBB76029B3BB9FB7DC3F38402013200 +:1041300062F38603FB75D0E76A7BBB7E9A42DBD1D4 +:10414000029B002B35D0B309022B32D0039B1422E3 +:1041500000210DA8BB60049BFB60FDF745FC039BA1 +:104160000AA920460A93049BADF83EB00B932B1D81 +:104170008DF840A00C932B7B8DF84180013BDBB286 +:10418000ADF83C30069B8DF84230059B8DF84330EE +:1041900094F82C3083F001038DF84430A3689847DD +:1041A000FB7DC3F38403013303F01F039B02FB82F7 +:1041B000A2E7FB7DC6F34012B2EBD31F40F0F980BB +:1041C000C3F38403434540F0FB80029AB6092B7B7E +:1041D000002A52D016F0010661D1032B40F2F38081 +:1041E000039B394604F10C00BB60049BFB60FB8A17 +:1041F00066F30903AE1DFB8232462B7B033BDBB229 +:10420000FFF7A6FA00280CDA39462046FFF78EFAA7 +:10421000FB7DC3F38403013303F01F039B02FB8286 +:1042200004E7AB88DDE908843B834FF6FF73C9F1EF +:104230002000A9F1200228FA09F109F1080904FA7D +:1042400000F024FA02F2014318461143C9B2FFF705 +:10425000C1F9B9F1400F0346E9D1B88231462A7B52 +:10426000033AD2B2FFF7C6F9FB7DB882DA43C2F354 +:10427000C01262F3C713FB753EE786B92E1D013BE2 +:10428000394604F10C00DBB23246FFF761FA002830 +:10429000BADB2A7B3146B88A013AD2B2E2E7F98A20 +:1042A000013BC1F30901DAB204295BD8281D0023C0 +:1042B00007F11B069A4208D910F801CB013306F822 +:1042C00001C00131DBB20529F4D1039993420A916F +:1042D00038BF043304992CBF002355FA83F30B91A4 +:1042E00007F11B010C9179680E930D91291DFB8A32 +:1042F000ADF83EB0C3F309038DF840A08DF84180BE +:104300001A44069B8DF84230059BADF83C208DF891 +:10431000433094F82C3083F001038DF844300023AF +:10432000B88A7B602A7B013AFFF764F93B8BB8823D +:10433000834203D1A3680AA92046984720460AA9C8 +:10434000FFF7FCFDFB7DBA8AC3F38403013303F05E +:104350001F039B02FB823B8B9A420CBF00206FF035 +:104360001000BCE67B68002BAFD0052001E01C30BC +:1043700033461E68002EFAD1091A2E1D081D184456 +:1043800001EB090C5FFA89F3BCF11B0F9DD89A422F +:104390009BD916F8013B09F1010900F8013BEFE751 +:1043A0006FF009009BE66FF00A0098E66FF00B00D3 +:1043B00095E66FF00D0092E640420F0080841E00EB +:1043C0006FF00E008BE66FF00F0088E6EFF30983C5 +:1043D000054968334A6B22F001024A6383F3098876 +:1043E000002383F31188704700EF00E0302080F352 +:1043F000118862B60D4B0E4AD96821F4E0610904B8 +:10440000090C0A430B49DA60D3F8FC2042F08072B1 +:10441000C3F8FC20084AC2F8B01F116841F001013E +:1044200011602022DA7783F82200704700ED00E067 +:104430000003FA0555CEACC5001000E0302310B5DE +:1044400083F311880E4B5B6813F4006314D0F1EE14 +:10445000103AEFF309844FF08073683CE361094B35 +:10446000DB6B236684F3098800F070FE10B1064B05 +:10447000A36110BD054BFBE783F31188F9E700BF8B +:1044800000ED00E000EF00E03F04000842040008F7 +:1044900008B5074B074A196801F03D019960536858 +:1044A0000BB190689847BDE80840FFF7C7BF00BF51 +:1044B00000000240C463002008B5084B1968890950 +:1044C00001F03D018A019A60054AD3680BB1106979 +:1044D0009847BDE80840FFF7B1BF00BF00000240A9 +:1044E000C463002008B5084B1968090C01F03D01B0 +:1044F0000A049A60054A53690BB190699847BDE870 +:104500000840FFF79BBF00BF00000240C4630020CB +:1045100008B5084B1968890D01F03D018A059A60BC +:10452000054AD3690BB1106A9847BDE80840FFF708 +:1045300085BF00BF00000240C463002008B5074BE0 +:10454000074A596801F03D01D960536A0BB1906A7E +:104550009847BDE80840FFF771BF00BF0000024068 +:10456000C463002008B5084B5968890901F03D0172 +:104570008A01DA60054AD36A0BB1106B9847BDE82F +:104580000840FFF75BBF00BF00000240C46300208B +:1045900008B5084B5968090C01F03D010A04DA60BE +:1045A000054A536B0BB1906B9847BDE80840FFF785 +:1045B00045BF00BF00000240C463002008B5084B9F +:1045C0005968890D01F03D018A05DA60054AD36B0F +:1045D0000BB1106C9847BDE80840FFF72FBF00BF34 +:1045E00000000240C463002008B5074B074A196861 +:1045F00001F03D019960536C0BB1906C9847BDE898 +:104600000840FFF71BBF00BF00040240C463002046 +:1046100008B5084B1968890901F03D018A019A60C3 +:10462000054AD36C0BB1106D9847BDE80840FFF701 +:1046300005BF00BF00040240C463002008B5084B5A +:104640001968090C01F03D010A049A60054A536D8E +:104650000BB1906D9847BDE80840FFF7EFBE00BF73 +:1046600000040240C463002008B5084B1968890D96 +:1046700001F03D018A059A60054AD36D0BB1106EB9 +:104680009847BDE80840FFF7D9BE00BF00040240CC +:10469000C463002008B5074B074A596801F03D0183 +:1046A000D960536E0BB1906E9847BDE80840FFF794 +:1046B000C5BE00BF00040240C463002008B5084B1B +:1046C0005968890901F03D018A01DA60054AD36E13 +:1046D0000BB1106F9847BDE80840FFF7AFBE00BFB1 +:1046E00000040240C463002008B5084B5968090C57 +:1046F00001F03D010A04DA60054A536F0BB1906F77 +:104700009847BDE80840FFF799BE00BF000402408B +:10471000C463002008B5084B5968890D01F03D01BC +:104720008A05DA60054AD36F13B1D2F88000984742 +:10473000BDE80840FFF782BE00040240C4630020C9 +:1047400000230C4910B51A460B4C0B6054F823009B +:10475000026001EB430004334260402BF6D1074A6C +:104760004FF0FF339360D360C2F80834C2F80C34C2 +:1047700010BD00BFC46300209C6800080000024018 +:104780000F28F8B510D9102810D0112811D01228F0 +:1047900008D10F240720DFF8B4E00126DEF800502E +:1047A000A04208D9002649E00446F4E70F2400207F +:1047B000F1E70724FBE706FA00F73D4240D1214C20 +:1047C0004FEA001C3D4304EB00160EEBC000CEF890 +:1047D0000050C0E90123FBB24BB11B48836B43F08F +:1047E00001038363036E43F001030366036E17F452 +:1047F0007F4F09D01448836B43F002038363036E39 +:1048000043F002030366036E54F80C00036823F0C0 +:104810001F030360056815F00105FBD104EB0C03D1 +:104820003D2493F80CC05F6804FA0CF43C6021242A +:104830000560446112B1987B00F00EFA3046F8BD75 +:104840000130ADE79C68000800450258C4630020B1 +:1048500010B5302484F31188FFF792FF002383F30F +:10486000118810BD10B50446807B00F00BFA0123BF +:104870001049627B03FA02F20B6823EA0203DAB200 +:104880000B604AB90C4A916B21F001019163116EE2 +:1048900021F001011166126E13F47F4F09D1064B0E +:1048A0009A6B22F002029A631A6E22F002021A66D2 +:1048B0001B6E10BDC46300200045025808B53023AC +:1048C00083F31188FFF7CEFF002383F3118808BD1F +:1048D0000023054A19460133102BC2E9001102F1E9 +:1048E0000802F8D1704700BF486400202DE9F74F57 +:1048F00002F0030AC2F3C313C2F38009C2F3C10872 +:10490000C2F3411E574600224FF00F0B0193CB0715 +:1049100033D502F00703019C012556009B00BAF134 +:10492000020F05FA02F504FA03FC44680BFA03F3DC +:1049300024EA05046FEA030344EA090444604FF0E3 +:104940000304856804FA06F625EA06056FEA0604FC +:1049500045EA08058560C56825EA060545EA0E05AD +:10496000C5601BD1072A13D8056A2B4043EA0C0304 +:10497000036203681C403C430460490822D04FEAAC +:10498000490901324FEA88084FEA8E0EBF00BEE7A0 +:10499000456A2B4043EA0C034362EAE70568072AAD +:1049A00004EA050444EA0704046005D8046A2340C5 +:1049B00043EA0C030362E0E7446A234043EA0C0342 +:1049C0004362DAE703B0BDE8F08F00000268436895 +:1049D0001143016003B1184770470000024A136891 +:1049E00043F0C0031360704700100140024A13688F +:1049F00043F0C00313607047007C004037B51A4C89 +:104A00001A4D204600F0E8FA04F114000094002347 +:104A10004FF40072164900F0A5F94FF400721549E1 +:104A200004F138000094144B00F01EFA134BC4E953 +:104A30001735134C204600F0CFFA04F11400002380 +:104A40004FF400720F49009400F08CF90E4B4FF4B4 +:104A500000720E4904F13800009400F005FA0C4B86 +:104A6000C4E9173503B030BDC864002000E1F50586 +:104A7000A0650020A0690020DD4900080010014069 +:104A800034650020A0670020ED490008A06B0020DD +:104A9000007C0040037C30B5284C002918BF0C4630 +:104AA000012B0CD1264B984236D1264B1A6D42F081 +:104AB00010021A659A6F42F010029A679B6F226883 +:104AC000036EC16D03EB52038466B3FBF2F36268BD +:104AD000150442BF23F0070503F0070343EA45032B +:104AE000CB60A36843F040034B60E36843F00103ED +:104AF0008B6042F4967343F001030B604FF0FF3379 +:104B00000B62510505D512F0102213D0B2F1805F6F +:104B100012D080F8643030BD0B4B9842CFD1094B96 +:104B20009A6C42F000429A641A6F42F000421A678F +:104B30001B6FC4E77F23ECE73F23EAE79C6900088B +:104B4000C864002000450258346500202DE9F04774 +:104B5000C66D05463768F469210734621AD014F02F +:104B6000080118BF4FF48071E20748BF41F02001EF +:104B7000A3074FF0300348BF41F04001600748BF32 +:104B800041F0800183F31188281DFFF71FFF0023E8 +:104B900083F31188E2050AD5302383F311884FF49B +:104BA0008061281DFFF712FF002383F311884FF067 +:104BB00030094FF0000A14F0200838D13B0616D512 +:104BC0004FF0300905F1380A200610D589F3118815 +:104BD000504600F07DF9002836DA0821281DFFF73D +:104BE000F5FE27F080033360002383F311887906F4 +:104BF00014D5620612D5302383F31188D5E9132327 +:104C00009A4208D12B6C33B127F040071021281DA0 +:104C1000FFF7DCFE3760002383F31188E30618D525 +:104C2000AA6E1369ABB15069BDE8F047184789F324 +:104C30001188736A284695F86410194000F0E6F967 +:104C40008AF31188F469B6E7B06288F31188F469D1 +:104C5000BAE7BDE8F0870000090100F160430122D6 +:104C600003F56143C9B283F8001300F01F039A40B3 +:104C700043099B0003F1604303F56143C3F88021BE +:104C80001A60704700F01F0301229A40430900F1A7 +:104C900060409B0000F5614003F1604303F5614310 +:104CA000C3F88020C3F88021002380F800337047C8 +:104CB000F8B51546826804460B46AA4200D28568BC +:104CC000A1692669761AB5420BD218462A46FCF726 +:104CD00079FEA3692B44A3612846A3685B1BA360EC +:104CE000F8BD0CD9AF1B18463246FCF76BFE3A46AE +:104CF000E1683044FCF766FEE3683B44EBE71846A6 +:104D00002A46FCF75FFEE368E5E70000836893420C +:104D1000F7B50446154600D28568D4E90460361A12 +:104D2000B5420BD22A46FCF74DFE63692B44636102 +:104D30002846A3685B1BA36003B0F0BD0DD93246C3 +:104D4000AF1B0191FCF73EFE01993A46E068314401 +:104D5000FCF738FEE3683B44E9E72A46FCF732FEFD +:104D6000E368E4E710B50A440024C361029B846051 +:104D7000C16002610362C0E90000C0E9051110BD15 +:104D800008B5D0E90532934201D1826882B98268C0 +:104D9000013282605A1C426119700021D0E904324C +:104DA0009A4224BFC368436100F076FA002008BD30 +:104DB0004FF0FF30FBE7000070B5302304460E468D +:104DC00083F31188A568A5B1A368A269013BA3601C +:104DD000531CA36115782269934224BFE368A36141 +:104DE000E3690BB120469847002383F311882846D6 +:104DF00007E03146204600F03FFA0028E2DA85F36A +:104E0000118870BD2DE9F74F04460E4617469846A7 +:104E1000D0F81C904FF0300A8AF311884FF0000B45 +:104E2000154665B12A4631462046FFF741FF034645 +:104E300060B94146204600F01FFA0028F1D0002357 +:104E400083F31188781B03B0BDE8F08FB9F1000F30 +:104E500003D001902046C847019B8BF31188ED1ABF +:104E60001E448AF31188DCE7C160C361009B826045 +:104E70000362C0E905111144C0E9000001617047F7 +:104E8000F8B504460D461646302383F31188A7680B +:104E9000A7B1A368013BA36063695A1C62611D70DE +:104EA000D4E904329A4224BFE3686361E3690BB139 +:104EB00020469847002080F3118807E031462046BD +:104EC00000F0DAF90028E2DA87F31188F8BD000073 +:104ED000D0E9052310B59A4201D182687AB9826877 +:104EE0000021013282605A1C82611C7803699A4257 +:104EF00024BFC368836100F0CFF9204610BD4FF096 +:104F0000FF30FBE72DE9F74F04460E46174698465B +:104F1000D0F81C904FF0300A8AF311884FF0000B44 +:104F2000154665B12A4631462046FFF7EFFE034697 +:104F300060B94146204600F09FF90028F1D00023D7 +:104F400083F31188781B03B0BDE8F08FB9F1000F2F +:104F500003D001902046C847019B8BF31188ED1ABE +:104F60001E448AF31188DCE702684368114301603C +:104F700003B11847704700001430FFF743BF00002B +:104F80004FF0FF331430FFF73DBF00003830FFF71C +:104F9000B9BF00004FF0FF333830FFF7B3BF000058 +:104FA0001430FFF709BF00004FF0FF311430FFF756 +:104FB00003BF00003830FFF763BF00004FF0FF323F +:104FC0003830FFF75DBF0000012914BF6FF01300F8 +:104FD00000207047FFF712BD044B036000234360BD +:104FE000C0E9023301230374704700BFB4690008AD +:104FF00010B53023044683F31188FFF74BFD0223DD +:105000000020237480F3118810BD000038B5C369F7 +:1050100004460D461BB904210844FFF7A5FF2946A5 +:1050200004F11400FFF7ACFE002806DA201D4FF44F +:105030000061BDE83840FFF797BF38BD00238268A4 +:10504000037503691B6899689142FBD25A68036033 +:1050500042601060586070470023826803750369DE +:105060001B6899689142FBD85A68036042601060DF +:105070005860704708B50846302383F311880A7DCD +:105080000023052A06D8DFE802F00B050503120EFF +:10509000826913604FF0FF338361FFF7CFFF002376 +:1050A00083F3118808BD8269936801339360D0E966 +:1050B000003213605A60EDE7FFF7C0BF054BD968B7 +:1050C00008751868026853601A600122D86002757A +:1050D000FBF7A0B9A06D00200C4B30B5DD684B1C70 +:1050E00087B004460FD02B46094A684600F066F99F +:1050F0002046FFF7E3FF009B13B1684600F068F914 +:10510000A86907B030BDFFF7D9FFF9E7A06D00200F +:105110007550000838B50C4D04468161EB68816814 +:105120009A68914203D8BDE83840FFF787BF184618 +:10513000FFF792FF01230146EC6020462375BDE88E +:105140003840FBF767B900BFA06D0020044B1A6818 +:10515000DB6890689B68984294BF002001207047EC +:10516000A06D0020084B10B51C68D86822685360F9 +:105170001A600122DC602275FFF76EFF01462046AF +:10518000BDE81040FBF746B9A06D002038B50123FB +:10519000084C00252370656000F0ACFD00F0D2FDE6 +:1051A0000549064800F0A6FE0223237085F3118806 +:1051B00038BD00BF08700020E0690008A06D002025 +:1051C00008B572B6044B186500F0BEFB00F080FC19 +:1051D000024B03221A70FEE7A06D00200870002029 +:1051E00000F02CB98B600223086108468B8270475F +:1051F0008368A3F1840243F8142C026943F8442C19 +:10520000426943F8402C094A43F8242CC268A3F1B0 +:10521000200043F8182C022203F80C2C002203F87B +:105220000B2C034A43F8102C704700BF2D040008D4 +:10523000A06D002008B5FFF7DBFFBDE80840FFF7D1 +:105240003BBF0000024BDB6898610F20FFF736BFC1 +:10525000A06D0020302383F31188FFF7F3BF000017 +:1052600008B50146302383F311880820FFF734FF87 +:10527000002383F3118808BD064BDB6839B142680F +:1052800018605A60136043600420FFF725BF4FF099 +:10529000FF307047A06D00200368984206D01A685E +:1052A0000260506018469961FFF706BF7047000022 +:1052B000036810B59C68A2420CD85C688A600B60D9 +:1052C0004C602160596099688A1A9A604FF0FF33E8 +:1052D000836010BD121B1B68ECE700000A2938BF71 +:1052E0000A2170B504460D460A26601900F0FCFC40 +:1052F00000F0E4FC041BA54203D8751C04462E46AE +:10530000F3E70A2E04D90120BDE8704000F032BE58 +:1053100070BD0000F8B5144B0D460A2A4FF00A077D +:10532000D96103F11001826038BF0A224160196916 +:105330001446016048601861A81800F0C5FC00F030 +:10534000BDFC431B0646A34206D37C1C28192746F6 +:10535000354600F0C9FCF2E70A2F04D90120BDE868 +:10536000F84000F007BEF8BDA06D0020F8B5064675 +:105370000D4600F0A3FC0F4A134653F8107F9F42DE +:1053800006D12A4601463046BDE8F840FFF7C2BFC5 +:10539000D169BB68441A2C1928BF2C46A34202D9F4 +:1053A0002946FFF79BFF224631460348BDE8F840F7 +:1053B000FFF77EBFA06D0020B06D0020C0E9032381 +:1053C000002310B45DF8044B4361FFF7CFBF00002A +:1053D00010B5194C236998420DD08168D0E900328C +:1053E00013605A609A680A449A60002303604FF081 +:1053F000FF33A36110BD0268234643F8102F5360AA +:105400000022026022699A4203D1BDE8104000F0F8 +:1054100065BC936881680B44936000F04FFC22697F +:10542000E1699268441AA242E4D91144BDE81040EF +:10543000091AFFF753BF00BFA06D00202DE9F04708 +:10544000DFF8BC8008F110072C4ED8F8105000F09F +:1054500035FCD8F81C40AA68031B9A423ED8144475 +:105460004FF00009D5E90032C8F81C4013605A60BB +:10547000C5F80090D8F81030B34201D100F02EFCEE +:1054800089F31188D5E9033128469847302383F3FF +:1054900011886B69002BD8D000F010FC6A69A0EB72 +:1054A000040982464A450DD2022000F063FD002225 +:1054B000D8F81030B34208D151462846BDE8F0472D +:1054C000FFF728BF121A2244F2E712EB0909294616 +:1054D000384638BF4A46FFF7EBFEB5E7D8F810303C +:1054E000B34208D01444C8F81C00211AA960BDE8D2 +:1054F000F047FFF7F3BEBDE8F08700BFB06D0020B6 +:10550000A06D002038B500F0D9FB054AD2E9084566 +:10551000031B181945F10001C2E9080138BD00BF9D +:10552000A06D002000207047FEE7000070470000DB +:105530004FF0FF3070470000BFF34F8F044B1A69E4 +:105540005107FCD1D3F810215207F8D1704700BFA2 +:105550000020005208B50D4B1B78ABB9FFF7ECFFEC +:105560000B4BDA68D10704D50A4A5A6002F1883237 +:105570005A60D3F80C21D20706D5064AC3F8042195 +:1055800002F18832C3F8042108BD00BF107000206A +:10559000002000522301674508B5114B1B78F3B971 +:1055A000104B1A69510703D5DA6842F04002DA60FD +:1055B000D3F81021520705D5D3F80C2142F0400250 +:1055C000C3F80C21FFF7B8FF064BDA6842F001027E +:1055D000DA60D3F80C2142F00102C3F80C2108BDB7 +:1055E00010700020002000520F289ABF00F5806044 +:1055F00040040020704700004FF400307047000066 +:10560000102070470F2808B50BD8FFF7EDFF00F505 +:1056100000330268013204D104308342F9D1012001 +:1056200008BD0020FCE700000F2838B505463FD82C +:10563000FFF782FF1F4CFFF78DFF4FF0FF33072866 +:105640006361C4F814311DD82361FFF775FF0302AD +:1056500043F02403E360E36843F08003E3602369DD +:105660005A07FCD42846FFF767FFFFF7BDFF4FF44A +:10567000003100F009FA2846FFF78EFFBDE83840F8 +:10568000FFF7C0BFC4F81031FFF756FFA0F10803C1 +:105690001B0243F02403C4F80C31D4F80C3143F05E +:1056A0008003C4F80C31D4F810315B07FBD4D9E780 +:1056B000002038BD002000522DE9F84F05460C4669 +:1056C000104645EA0203DE0602D00020BDE8F88F4E +:1056D00020F01F00DFF8BCB0DFF8BCA0FFF73AFFF6 +:1056E00004EB0008444503D10120FFF755FFEDE727 +:1056F00020222946204601F00BF810B9203520342D +:10570000F0E72B4605F120021F68791CDDD1043338 +:105710009A42F9D105F178431B481C4EB3F5801F1E +:105720001B4B38BF184603F1F80332BFD946D146A8 +:105730001E46FFF701FF0760A5EB040C336804F178 +:105740001C0143F002033360231FD9F8007017F0E7 +:105750000507FAD153F8042F8B424CF80320F4D1FB +:10576000BFF34F8FFFF7E8FE4FF0FF3320222146B3 +:1057700003602846336823F00203336000F0C8FF5B +:105780000028BBD03846B0E7142100520C2000524C +:1057900014200052102000521021005210B5084C65 +:1057A000237828B11BB9FFF7D5FE0123237010BD64 +:1057B000002BFCD02070BDE81040FFF7EDBE00BF0D +:1057C000107000202DE9F04F0D4685B0814658B18C +:1057D00011F00D0614BF2022082211F008030193D6 +:1057E00004D0431E03426AD0002435E0002E37D097 +:1057F00009F11F0121F01F094FF00108324F05F098 +:105800000403DFF8D0A005EA080BBBF1000F32D08B +:105810007869C0072FD408F101080C37B8F1060FDA +:10582000F3D19EB9294D4946A819019200F0ACFA6E +:10583000044600283AD11836019A782EF3D1494609 +:1058400000F0A2FA0446002830D1019A49462048C7 +:1058500000F09AFA044668BB204605B0BDE8F08F18 +:105860000029C9D101462846029200F08DFA04466B +:10587000E0B9029AC0E713B178694107CBD5AC070C +:1058800002D578698007C6D5019911B178690107F9 +:10589000C1D51820494600FB08A0CDE9022300F03D +:1058A00073FA0446DDE902230028B4D04A460021F9 +:1058B000204601E04A460021FCF796F8CCE7024674 +:1058C000002E95D198E700BFEC69000844700020D5 +:1058D000147000202C7000200121FFF773BF00001E +:1058E000F8B5144D01241827134E40F2FF32002161 +:1058F0000120FCF779F807FB046001342A6955F8A8 +:105900000C1F00F02DFA062CF5D137254FF4C054AA +:105910002046FFF7E1FF014628B122460748BDE8CF +:10592000F84000F01DBAC4EBC404013D4FEAD404B2 +:10593000EED1F8BDEC6900082C7000201470002036 +:1059400008B100F093BA704738B5054D0024033410 +:10595000696855F80C0B00F0A9F8122CF7D138BD86 +:10596000EC69000838B5EFF311859DB9EFF30584B4 +:10597000C4F30804302334B183F31188FFF7C2FD68 +:1059800085F3118838BD83F31188FFF7BBFD84F3DD +:10599000118838BDBDE83840FFF7B4BD10B5FFF73A +:1059A000E1FF104CC008104A002340EA4170C908CA +:1059B000A0FB04ECA0FB020E1CEB0000A1FB044CBE +:1059C000A1FB02125B41001943EB0C0011EB0E012D +:1059D00042F10002411842F10000090941EA007059 +:1059E00010BD00BFCFF753E3A59BC4200244074B73 +:1059F000D2B210B5904200D110BD441C00B253F891 +:105A0000200041F8040BE0B2F4E700BF504000581A +:105A10000E4B30B51C6F240405D41C6F1C671C6F23 +:105A200044F400441C670A4C02442368D2B243F495 +:105A300080732360074B904200D130BD441C51F865 +:105A4000045B00B243F82050E0B2F4E7004402588F +:105A5000004802585040005807B5012201A9002013 +:105A6000FFF7C4FF019803B05DF804FB13B50446CB +:105A7000FFF7F2FFA04205D0012201A90020019406 +:105A8000FFF7C6FF02B010BD0144BFF34F8F064BB6 +:105A9000884204D3BFF34F8FBFF36F8F7047C3F8B3 +:105AA0005C022030F4E700BF00ED00E00144BFF3EA +:105AB0004F8F064B884204D3BFF34F8FBFF36F8FD6 +:105AC0007047C3F870022030F4E700BF00ED00E03B +:105AD00070470000114BDA6952021ED59A69D0074F +:105AE00004D50F4A9A6002F144329A600B4BDA698E +:105AF000D107FCD41A6A22F480021A629A6942F031 +:105B000002029A61DA69D207FCD49A6942F0010272 +:105B10009A61024AD369DB07FCD470470020005227 +:105B20003B2A1908074B45F255521A6003225A6066 +:105B300040F2FF729A604CF6CC421A600122024B8E +:105B40001A70704700480058C0700020034B1B7843 +:105B50001BB1034B4AF6AA221A607047C07000209E +:105B600000480058034B1A681AB9034AD2F8D024E7 +:105B70001A607047BC70002000400258024B4FF47E +:105B80008032C3F8D02470470040025808B5FFF7B0 +:105B9000E9FF024B1868C0F3806008BDBC700020AC +:105BA00070B5BFF34F8FBFF36F8F1A4A0021C2F851 +:105BB0005012BFF34F8FBFF36F8F536943F400331D +:105BC0005361BFF34F8FBFF36F8FC2F88410BFF3E1 +:105BD0004F8FD2F8803043F6E074C3F3C900C3F3AB +:105BE0004E335B0103EA0406014646EA817501393A +:105BF000C2F86052F9D2203B13F1200FF2D1BFF36B +:105C00004F8F536943F480335361BFF34F8FBFF31A +:105C10006F8F70BD00ED00E0FEE70000214B2248D1 +:105C2000224A70B5904237D3214BC11EDA1C121A9A +:105C300022F003028B4238BF00220021FBF7D4FE82 +:105C40001C4A0023C2F88430BFF34F8FD2F8803053 +:105C500043F6E074C3F3C900C3F34E335B0103EAB8 +:105C60000406014646EA81750139C2F86C52F9D240 +:105C7000203B13F1200FF2D1BFF34F8FBFF36F8F93 +:105C8000BFF34F8FBFF36F8F0023C2F85032BFF3C3 +:105C90004F8FBFF36F8F70BD53F8041B40F8041B88 +:105CA000C0E700BFB46B0008E4700020E47000207F +:105CB000E470002000ED00E000F05ABA014B586A91 +:105CC000704700BF000C0040034B002258631A616C +:105CD0000222DA60704700BF000C0040014B002236 +:105CE000DA607047000C0040014B5863704700BFFA +:105CF000000C0040024B034A1A60034A5A60704786 +:105D0000C4700020E870002000000220074B4942C8 +:105D100010B55C68201A08401968821A8A4203D3B9 +:105D2000A24201D85A6010BD0020FCE7C4700020D8 +:105D300008B5302383F31188FFF7E8FF002383F3CE +:105D4000118808BD04480121044B03600023C0E909 +:105D500001330C3000F016B9CC700020315D000822 +:105D6000CB1D083A23F00703591A521A012110B427 +:105D7000D2080024C0E9004384600C301C605A60E3 +:105D80005DF8044B00F0FEB82DE9F84F364ECD1DFE +:105D90000F46002818BF0646082A4FEAD50538BF27 +:105DA000082206F10C08341D9146404600F006F921 +:105DB00009F10701C9F1000E224624686CB940467A +:105DC00000F006F93368CBB308224946E80098474B +:105DD000044698B340E9026730E004EB010CD4F8C4 +:105DE00004A00CEA0E0C0AF10100ACF1080304EB6C +:105DF000C0009842E0D9A0EB0C0CB5EBEC0F4FEAD9 +:105E0000EC0BD9D89C421CD204F10802AB45A3EBA1 +:105E100002024FEAE202626009D9691CED43206880 +:105E200003EBC1025D44556043F8310022601C461B +:105E30005F60404644F8086B00F0CAF82046BDE8B1 +:105E4000F88FAA45216802D111602346EFE701359A +:105E500004EBC50344F8351003F10801401AC010E3 +:105E600058601360F1E700BFCC700020F8B550F81F +:105E7000043C044650F8085CA0F1080607332F1DC7 +:105E80000C35DB0840F8043C284600F097F83B4608 +:105E90009F421A6801D0B34228D20AB1964225D255 +:105EA00044F8082C54F8042C1E60013254F8081CE5 +:105EB00006EBC200814206D14868024444F8042C33 +:105EC0000A6844F8082C5868411C03EBC1018E4253 +:105ED00007D154F8042C013202445A6054F8082CBB +:105EE0001A602846BDE8F84000F072B81346CFE7C4 +:105EF000FEE7000070B51B4B0025044686B05860D5 +:105F00000E4685620163FEF771FA04F11003A56085 +:105F1000E562C4E904334FF0FF33C4E90044C4E947 +:105F20000635FFF7CBFE2B46024604F1340120462E +:105F3000C4E9082380230C4A2565FFF753F90123A0 +:105F40000A4AE06000920375684672680192B2687E +:105F5000CDE90223064BCDE90435FFF76BF906B016 +:105F600070BD00BF08700020346A0008396A00085C +:105F7000F15E0008024AD36A1843D062704700BF3E +:105F8000A06D0020C0E90000816070478368013B7C +:105F9000002B10B583600CDA074BDC684368A06106 +:105FA000206063601C6044600520FFF787F8A069EB +:105FB00010BD0020FCE700BFA06D002008B5302315 +:105FC00083F31188FFF7E2FF002383F3118808BDF4 +:105FD00008B5302383F3118883680133002B836075 +:105FE00007DC036800211A68026050601846FFF75A +:105FF00091F8002383F3118808BD00004B684360CB +:106000008B688360CB68C3600B6943614B69036233 +:106010008B6943620B6803607047000008B53C4B16 +:1060200040F2FF713B48D3F888200A43C3F8882028 +:10603000D3F8882022F4FF6222F00702C3F88820F8 +:10604000D3F88830344B1A6C0A431A649A6E0A43A8 +:106050009A66324A9B6E1146FFF7D0FF00F58060CA +:1060600002F11C01FFF7CAFF00F5806002F1380160 +:10607000FFF7C4FF00F5806002F15401FFF7BEFF97 +:1060800000F5806002F17001FFF7B8FF00F5806055 +:1060900002F18C01FFF7B2FF00F5806002F1A80168 +:1060A000FFF7ACFF00F5806002F1C401FFF7A6FF27 +:1060B00000F5806002F1E001FFF7A0FF00F58060CD +:1060C00002F1FC01FFF79AFF02F58C7100F5806088 +:1060D000FFF794FF00F00EF9114BD3F8902242F035 +:1060E0000102C3F89022D3F8942242F00102C3F8CF +:1060F00094220522C3F898204FF06052C3F89C20E8 +:10610000084AC3F8A020BDE80840FFF7E3BC00BF81 +:10611000004402580000025800450258406A000836 +:1061200000ED00E01F00080308B500F0CFFAFFF70C +:106130002DF80C4BDA6B42F04002DA635A6E22F013 +:1061400040025A665B6E084B1A6842F008021A60F9 +:106150001A6842F004021A60FFF704FDBDE8084027 +:10616000FFF7BEBB00450258001802487047000008 +:106170000E4B9A6C42F008029A641A6F42F00802C1 +:106180001A670B4A1B6FD36B43F00803D363C72214 +:10619000084B9A624FF0FF32DA6200229A615A632A +:1061A000DA605A6001225A611A607047004502584D +:1061B0000010005C000C0040094A08B51169D36862 +:1061C0000B40D9B29B076FEA0101116107D530235B +:1061D00083F31188FFF704F8002383F3118808BDC7 +:1061E000000C0040044BDA6B0243DA635A6E104332 +:1061F00058665B6E704700BF0045025808B53C4BBF +:106200004FF0FF31D3F8802062F00042C3F88020C5 +:10621000D3F8802002F00042C3F88020D3F8802019 +:10622000D3F88420C3F88410D3F884200022C3F864 +:106230008420D3F88400D86F40F0FF4040F4FF0082 +:1062400040F4DF4040F07F00D867D86F20F0FF4077 +:1062500020F4FF0020F4DF4020F07F00D867D86FE3 +:10626000D3F888006FEA40506FEA5050C3F88800B6 +:10627000D3F88800C0F30A00C3F88800D3F8880078 +:10628000D3F89000C3F89010D3F89000C3F8902092 +:10629000D3F89000D3F89400C3F89410D3F8940086 +:1062A000C3F89420D3F89400D3F89800C3F898105A +:1062B000D3F89800C3F89820D3F89800D3F88C004E +:1062C000C3F88C10D3F88C00C3F88C20D3F88C0062 +:1062D000D3F89C00C3F89C10D3F89C10C3F89C2002 +:1062E000D3F89C30FEF72CFABDE8084000F0BEB9A8 +:1062F0000044025808B50122504BC3F80821504B06 +:106300005A6D42F002025A65DA6F42F00202DA6711 +:106310000422DB6F4B4BDA605A689104FCD54A4A81 +:106320001A6001229A60494ADA6000221A614FF429 +:1063300040429A61434B9A699204FCD51A6842F430 +:1063400080721A60424B1A6F12F4407F04D04FF4EF +:1063500080321A6700221A671A6842F001021A6036 +:106360003B4B1A685007FCD500221A611A6912F0DB +:106370003802FBD1012119604FF0804159605A6702 +:10638000344ADA62344A1A611A6842F480321A6076 +:106390002F4B1A689103FCD51A6842F480521A6098 +:1063A0001A689204FCD52D4A2D499A6200225A633C +:1063B000196301F57C01DA6301F5E77199635A64A9 +:1063C000284A1A64284ADA621A6842F0A8521A6007 +:1063D0001F4B1A6802F02852B2F1285FF9D1482207 +:1063E0009A614FF48862DA6140221A621F4ADA64C5 +:1063F0001F4A1A651F4A5A651F4A9A6532231F4A67 +:106400001360136803F00F03022BFAD1104A1369CB +:1064100043F003031361136903F03803182BFAD117 +:106420004FF00050FFF7DEFE4FF08040FFF7DAFE3E +:106430004FF00040BDE80840FFF7D4BE0080005197 +:10644000004502580048025800C000F00400000156 +:10645000004402580000FF010088900832206000CC +:1064600063020901470E0508DD0BBF012000002073 +:10647000000001100910E00000010110002000528E +:106480004FF0B04208B5D2F8883003F00103C2F8EB +:10649000883023B1044A13680BB150689847BDE8AF +:1064A0000840FDF7CBBF00BF486400204FF0B0426A +:1064B00008B5D2F8883003F00203C2F8883023B15F +:1064C000044A93680BB1D0689847BDE80840FDF7CF +:1064D000B5BF00BF486400204FF0B04208B5D2F805 +:1064E000883003F00403C2F8883023B1044A1369EA +:1064F0000BB150699847BDE80840FDF79FBF00BF4A +:10650000486400204FF0B04208B5D2F8883003F05C +:106510000803C2F8883023B1044A93690BB1D069EB +:106520009847BDE80840FDF789BF00BF48640020D8 +:106530004FF0B04208B5D2F8883003F01003C2F82B +:10654000883023B1044A136A0BB1506A9847BDE8FA +:106550000840FDF773BF00BF486400204FF0B04310 +:1065600010B5D3F8884004F47872C3F88820A306E5 +:1065700004D5124A936A0BB1D06A9847600604D5D5 +:106580000E4A136B0BB1506B9847210604D50B4A8A +:10659000936B0BB1D06B9847E20504D5074A136C97 +:1065A0000BB1506C9847A30504D5044A936C0BB10A +:1065B000D06C9847BDE81040FDF740BF486400200C +:1065C0004FF0B04310B5D3F8884004F47C42C3F8D0 +:1065D0008820620504D5164A136D0BB1506D98479B +:1065E000230504D5124A936D0BB1D06D9847E00492 +:1065F00004D50F4A136E0BB1506E9847A10404D511 +:106600000B4A936E0BB1D06E9847620404D5084ACA +:10661000136F0BB1506F9847230404D5044A936F4E +:106620000BB1D06F9847BDE81040FDF707BF00BF22 +:106630004864002008B50348FEF788FABDE8084022 +:10664000FDF7FCBEC864002008B50348FEF77EFADB +:10665000BDE80840FDF7F2BE3465002008B5FFF73D +:10666000ABFDBDE80840FDF7E9BE0000062108B516 +:106670000846FEF7F1FA06210720FEF7EDFA06219B +:106680000820FEF7E9FA06210920FEF7E5FA0621BF +:106690000A20FEF7E1FA06211720FEF7DDFA0621AF +:1066A0002820FEF7D9FA09217A20FEF7D5FA07212A +:1066B0003220FEF7D1FA0C212520FEF7CDFA0C216D +:1066C0005320BDE80840FEF7C7BA000008B5FFF741 +:1066D00095FDFEF7FDF8FEF77DFCFFF747FDBDE8F1 +:1066E0000840FFF7E9BA00000B460146184600F0E3 +:1066F00001B8000010B5054C13462CB10A460146FE +:106700000220AFF3008010BD2046FCE7000000002F +:1067100010B501390244904201D1002005E0037810 +:1067200011F8014FA34201D0181B10BD0130F2E750 +:106730002DE9F041A3B1C91A17780144044603F1C9 +:10674000FF3C8C42204601D9002009E00578BD427B +:1067500004F10104F5D10CEB0405D618A54201D1D2 +:10676000BDE8F08115F8018D16F801EDF045F5D082 +:10677000E7E70000034611F8012B03F8012B002A7C +:10678000F9D17047636F6D2E6375626570696C6FC8 +:10679000742E6865726534666300000053544D338F +:1067A0003248373F3F3F0053544D333248373378F8 +:1067B0002F3732780053544D3332483734332F3724 +:1067C00035332F373530000001105A0003105900BF +:1067D000012058000320560040A2E4F164689106AD +:1067E0000041A3E5F26569920700000043414E466F +:1067F0004449666163653A204D657373616765203E +:1068000052414D204F766572666C6F772100000013 +:106810004261642043414E496661636520696E644C +:1068200065782E00000100000001FF0000A000407C +:1068300000A400400000000000000000092B000838 +:106840009123000891320008012400080D2400085B +:106850002528000885250008C9230008CD23000845 +:10686000A52300088D230008E1270008B1230008B4 +:10687000F9330008BD230008B527000801040E0500 +:10688000054B02020E05054B04010E05054B0501E3 +:106890000B04044B080106030346000010000240ED +:1068A000080002400008024000000B0028000240DF +:1068B000080002400408024006010C0040000240AB +:1068C000080002400808024010020D005800024073 +:1068D000080002400C08024016030E00700002403F +:1068E0000C0002401008024000040F008800024023 +:1068F0000C0002401408024006051000A0000240EF +:106900000C0002401808024010061100B8000240B6 +:106910000C0002401C08024016072F001004024021 +:106920000804024020080240000838002804024001 +:1069300008040240240802400609390040040240CD +:106940000804024028080240100A3A005804024095 +:10695000080402402C080240160B3B007004024061 +:106960000C04024030080240000C3C008804024045 +:106970000C04024034080240060D4400A00402400A +:106980000C04024038080240100E4500B8040240D2 +:106990000C0402403C080240160F4600009600001E +:1069A00000000000000000000000000000000000E7 +:1069B0000000000000000000954F0008814F000813 +:1069C000BD4F0008A94F0008B54F0008A14F0008AF +:1069D0008D4F0008794F0008C94F00086330000050 +:1069E000DC690008F86D002008700020000100201C +:1069F00000FF010002000000000000300000040061 +:106A0000080000000000002400000800040000004E +:106A10000004000000FC0000020000000000043040 +:106A200000800000080000000000003800000100A5 +:106A3000010000006D61696E0069646C6500000012 +:106A40000000002800000000AAAAAAAA0000002452 +:106A5000FFFF0000000000000000000000A0550A39 +:106A600000000000AAAA9AAA00500000FFF200004D +:106A70000000007700009900000000000000000006 +:106A8000AAAAAAAA00000000FFFF00000000000060 +:106A9000000000005A000000000000009AAAAAAA04 +:106AA00000000000F3FF000099000000000000005B +:106AB0000A00000000000000AAAAAAAA050000001F +:106AC000FFFF000088000000000000000000000040 +:106AD00000000000AAAAAAAA00000000FFFF000010 +:106AE00000000000000000000000000000000000A6 +:106AF000AAAAAAAA00000000FFFF000000000000F0 +:106B0000000000000000000000000000AAAAAAAADD +:106B100000000000FFFF0000000000000000000077 +:106B20000000000000000000AAAAAAAA00000000BD +:106B3000FFFF000000000000000000000000000057 +:106B400000000000AAAAAAAA00000000FFFF00009F +:106B50000000000000000000000000000000000035 +:106B6000AAAAAAAA00000000FFFF0000000000007F +:106B700000000000000000001304000000000000FE +:106B80000000180000000000FE2A0100D2040000EE +:106B9000FF000000C86400203465002000000000F1 +:106BA0009C67000883040000A767000850040000E9 +:046BB000B5670008BD :00000001FF diff --git a/Tools/bootloaders/HolybroF4_PMU_bl.bin b/Tools/bootloaders/HolybroF4_PMU_bl.bin new file mode 100755 index 00000000000000..76803ecc545c87 Binary files /dev/null and b/Tools/bootloaders/HolybroF4_PMU_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_Airspeed_bl.bin b/Tools/bootloaders/HolybroG4_Airspeed_bl.bin new file mode 100755 index 00000000000000..8dc50f4bd83858 Binary files /dev/null and b/Tools/bootloaders/HolybroG4_Airspeed_bl.bin differ diff --git a/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.bin b/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.bin new file mode 100644 index 00000000000000..6437346946a96e Binary files /dev/null and b/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.bin differ diff --git a/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.hex b/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.hex new file mode 100644 index 00000000000000..91d6d80139b732 --- /dev/null +++ b/Tools/bootloaders/IFLIGHT_2RAW_H7_bl.hex @@ -0,0 +1,1102 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200086528000874 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008D13D0008FD3D00086E +:10006000293E0008553E0008813E00087110000836 +:1000700099100008C5100008F11000081D110008B3 +:100080004511000871110008E3020008E3020008AE +:10009000E3020008E3020008E3020008AD3E0008A6 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000113F0008E3020008E3020008E3020008F1 +:1000F000E3020008E3020008E30200089D11000883 +:10010000E3020008E3020008853F0008E30200085C +:10011000E3020008E3020008E3020008E30200082B +:10012000C9110008F11100081D1200084912000849 +:1001300075120008E3020008E3020008E302000869 +:10014000E3020008E3020008E3020008E3020008FB +:100150009D120008C9120008F5120008E302000809 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000851340008E3020008E30200082B +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200083D340008E3020008E3020008DF +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0ECFA88 +:1003500003F0FAFA4FF055301F491B4A91423CBF57 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F004FB03F058FB02 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0ECBA00060020002200207E +:1003D0000000000808ED00E00000002000060020FA +:1003E00060440008002200205C22002060220020DF +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0A4FDFEE701F056 +:1004300033FD00DFFEE7000038B500F02FFC00F0D0 +:10044000ABFD02F0CFF9054602F002FA0446C0B94E +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0C6F90CB100F07A +:1004700075F800F065FD284600F01EF900F06EF8F2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F021FE0023154A4FF4D1 +:1004D0007A71134801F010FE002383F31188124C47 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F088FC322363602B78032B07D16368EB +:100510002BB9022000F07EFC4FF47A73636038BD83 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05DBC022000F050BC024B0022F3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E3FBB14AB8 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F011FD0023AB4A4FF4F0 +:1006F0007A71A94801F000FD002383F31188009B63 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F06BFB24B19C4B1B6860 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F058FB26B10BF03D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F032FA019AFF217F4800F053FA4FEAF3 +:1009F000A803C8F387027C492846019300F052FA05 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F7FA8046E7E7384600F03AF945 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09DF900283AD020228E +:100B7000FF210AA800F08EF9FFF792FC1C4801F053 +:100B8000FFF913B0BDE8F08F002E3FF42BAE0BF051 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0DDF9059800F0E4F946463C462E +:100BD00000F0ACF9A6E506464EE64FF0000901E646 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0A8F98B +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F086FC308028683388834296 +:100CB00008D901F07BFC2B6804440133B4F5C02F44 +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F03EBD00F1006000F5C02000687047E3 +:100CE00000F10060920000F5C02001F0BFBC0000E0 +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F054BC0020704788230020B623002047 +:100D100038B50446074D29B128682044BDE838405D +:100D200001F05CBC2868204401F046FC0028F3D0A8 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C142200207C400008022803D17F +:100DF000024B4FF080729A61704700BF00000258AA +:100E0000022803D1024B4FF480729A61704700BFF1 +:100E100000000258022804D1024A536983F4807307 +:100E2000536170470000025870B504464FF47A765B +:100E30004CB1412C254628BF412506FB05F0641B1B +:100E400001F09EF8F4E770BD002310B5934203D083 +:100E5000CC5CC4540133F9E710BD0000013810B573 +:100E600010F9013F3BB191F900409C4203D11AB106 +:100E70000131013AF4E71AB191F90020981A10BD36 +:100E80001046FCE703460246D01A12F9011B00295E +:100E9000FAD1704702440346934202D003F8011B83 +:100EA000FAE770472DE9F8431F4D14460746884678 +:100EB00095F8242052BBDFF870909CB395F824304D +:100EC0002BB92022FF2148462F62FFF7E3FF95F858 +:100ED00024004146C0F1080205EB8000A24228BF71 +:100EE0002246D6B29200FFF7AFFF95F82430A41B3C +:100EF00017441E449044E4B2F6B2082E85F82460EC +:100F0000DBD1FFF723FF0028D7D108E02B6A03EBE2 +:100F100082038342CFD0FFF719FF0028CBD10020F6 +:100F2000BDE8F8830120FBE78C230020024B1A78F0 +:100F3000024B1A70704700BFB4230020102200201B +:100F400010B5114C114800F06FFB21460F4800F01E +:100F500097FB24684FF47A70D4F89020D2F80438C4 +:100F600043F00203C2F80438FFF75EFF0849204649 +:100F700000F094FCD4F89020D2F8043823F0020357 +:100F8000C2F8043810BD00BF38420008B026002067 +:100F90004042000870470000F0B5A1B071B60023D0 +:100FA0000120002480261A46194600F04BFA4FF41F +:100FB000D067214A3D25136923BBD2F810310BBB02 +:100FC000036804F1006199600368C3F80CD00368FA +:100FD0005E6003681F6001680B6843F001030B60EB +:100FE00001680B6823F01E030B6001680B68DB07C8 +:100FF000FCD4037B8034416805FA03F3B4F5001F89 +:101000000B60D8D100F05EFAB4F5001F11D00024B7 +:101010000A4E0B4D012001F09BFB3388A34205D9FA +:1010200028682044013401F0D9FAF6E7002001F0E5 +:101030008FFB61B621B0F0BD00200052B623002026 +:101040008823002030B50A44084D91420DD011F894 +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:1010700008B5074B074A196801F03D0199605368AC +:101080000BB190689847BDE8084001F023BC00BF51 +:1010900000000240B823002008B5084B19688909F0 +:1010A00001F03D018A019A60054AD3680BB11069CD +:1010B0009847BDE8084001F00DBC00BF00000240A9 +:1010C000B823002008B5084B1968090C01F03D0150 +:1010D0000A049A60054A53690BB190699847BDE8C4 +:1010E000084001F0F7BB00BF00000240B823002019 +:1010F00008B5084B1968890D01F03D018A059A6011 +:10110000054AD3690BB1106A9847BDE8084001F061 +:10111000E1BB00BF00000240B823002008B5074B28 +:10112000074A596801F03D01D960536A0BB1906AD2 +:101130009847BDE8084001F0CDBB00BF0000024069 +:10114000B823002008B5084B5968890901F03D0112 +:101150008A01DA60054AD36A0BB1106B9847BDE883 +:10116000084001F0B7BB00BF00000240B8230020D8 +:1011700008B5084B5968090C01F03D010A04DA6012 +:10118000054A536B0BB1906B9847BDE8084001F0DE +:10119000A1BB00BF00000240B823002008B5084BE7 +:1011A0005968890D01F03D018A05DA60054AD36B63 +:1011B0000BB1106C9847BDE8084001F08BBB00BF35 +:1011C00000000240B823002008B5074B074A196801 +:1011D00001F03D019960536C0BB1906C9847BDE8EC +:1011E000084001F077BB00BF00040240B823002094 +:1011F00008B5084B1968890901F03D018A019A6018 +:10120000054AD36C0BB1106D9847BDE8084001F05A +:1012100061BB00BF00040240B823002008B5084BA2 +:101220001968090C01F03D010A049A60054A536DE2 +:101230000BB1906D9847BDE8084001F04BBB00BF73 +:1012400000040240B823002008B5084B1968890D36 +:1012500001F03D018A059A60054AD36D0BB1106E0D +:101260009847BDE8084001F035BB00BF00040240CC +:10127000B823002008B5074B074A596801F03D0123 +:10128000D960536E0BB1906E9847BDE8084001F0ED +:1012900021BB00BF00040240B823002008B5084B62 +:1012A0005968890901F03D018A01DA60054AD36E67 +:1012B0000BB1106F9847BDE8084001F00BBB00BFB1 +:1012C00000040240B823002008B5084B5968090CF7 +:1012D00001F03D010A04DA60054A536F0BB1906FCB +:1012E0009847BDE8084001F0F5BA00BF000402408D +:1012F000B823002008B5084B5968890D01F03D015D +:101300008A05DA60054AD36F13B1D2F88000984796 +:10131000BDE8084001F0DEBA00040240B823002016 +:1013200000230C4910B51A460B4C0B6054F82300EF +:10133000026001EB430004334260402BF6D1074AC0 +:101340004FF0FF339360D360C2F80834C2F80C3416 +:1013500010BD00BFB82300208C40000800000240F0 +:101360000F28F8B510D9102810D0112811D0122844 +:1013700008D10F240720DFF8C8E00126DEF800506E +:10138000A04208D9002653E00446F4E70F240020C9 +:10139000F1E70724FBE706FA00F73D424AD1264C65 +:1013A0004FEA001C3D4304EB00160EEBC000CEF8E4 +:1013B0000050C0E90123FBB273B12048D0F8D83007 +:1013C00043F00103C0F8D830D0F8003143F00103F6 +:1013D000C0F80031D0F8003117F47F4F0ED0174815 +:1013E000D0F8D83043F00203C0F8D830D0F800313C +:1013F00043F00203C0F80031D0F8003154F80C007B +:10140000036823F01F030360056815F00105FBD195 +:1014100004EB0C033D2493F80CC05F6804FA0CF451 +:101420003C6021240560446112B1987B00F054F8BF +:101430003046F8BD0130A3E78C4000080044025854 +:10144000B823002010B5302484F31188FFF788FFFB +:10145000002383F3118810BD10B50446807B00F093 +:1014600051F801231549627B03FA02F20B6823EA63 +:101470000203DAB20B6072B9114AD2F8D81021F027 +:101480000101C2F8D810D2F8001121F00101C2F810 +:101490000011D2F8002113F47F4F0ED1084BD3F87E +:1014A000D82022F00202C3F8D820D3F8002122F07D +:1014B0000202C3F80021D3F8003110BDB823002088 +:1014C0000044025808B5302383F31188FFF7C4FFA6 +:1014D000002383F3118808BD090100F16043012254 +:1014E00003F56143C9B283F8001300F01F039A406B +:1014F00043099B0003F1604303F56143C3F8802176 +:101500001A60704700F01F0301229A40430900F15E +:1015100060409B0000F5614003F1604303F56143C7 +:10152000C3F88020C3F88021002380F8003370477F +:10153000026843681143016003B118477047000017 +:1015400013B5406B00F58054D4F8A4381A681178AC +:10155000042914D1017C022911D11979012312899E +:101560008B4013420BD101A94C3002F0A3F8D4F800 +:10157000A4480246019B2179206800F0DFF902B0FF +:1015800010BD0000143002F025B800004FF0FF330A +:10159000143002F01FB800004C3002F0F7B8000021 +:1015A0004FF0FF334C3002F0F1B80000143001F07E +:1015B000F3BF00004FF0FF31143001F0EDBF000029 +:1015C0004C3002F0C3B800004FF0FF324C3002F054 +:1015D000BDB800000020704710B500F58054D4F865 +:1015E000A4381A681178042917D1017C022914D172 +:1015F0005979012352898B4013420ED1143001F0E6 +:1016000085FF024648B1D4F8A4484FF4407361798D +:101610002068BDE8104000F07FB910BD406BFFF7B7 +:10162000DBBF0000704700007FB5124B0125042688 +:10163000044603600023057400F1840243602946D8 +:10164000C0E902330C4B0290143001934FF4407305 +:10165000009601F037FF094B04F69442294604F145 +:101660004C000294CDE900634FF4407301F0FEFF9B +:1016700004B070BD8C4100081D160008411500081B +:101680000A68302383F311880B790B3342F8230067 +:101690004B79133342F823008B7913B10B3342F8A3 +:1016A000230000F58053C3F8A4180223037400201C +:1016B00080F311887047000038B5037F044613B1EA +:1016C00090F85430ABB90125201D0221FFF730FFFF +:1016D00004F114006FF00101257700F079FC04F1AA +:1016E0004C0084F854506FF00101BDE8384000F020 +:1016F0006FBC38BD10B5012104460430FFF718FF58 +:101700000023237784F8543010BD000038B5044618 +:101710000025143001F0EEFE04F14C00257701F0B5 +:10172000BDFF201D84F854500121FFF701FF204622 +:10173000BDE83840FFF750BF90F8803003F06003F9 +:10174000202B06D190F881200023212A03D81F2ABC +:1017500006D800207047222AFBD1C0E91D3303E0E0 +:10176000034A426707228267C3670120704700BFB0 +:101770002C22002037B500F58055D5F8A4381A681A +:10178000117804291AD1017C022917D11979012372 +:1017900012898B40134211D100F14C04204602F013 +:1017A0003DF858B101A9204601F084FFD5F8A448BE +:1017B0000246019B2179206800F0C0F803B030BDDB +:1017C00001F10B03F0B550F8236085B004460D46D7 +:1017D000FEB1302383F3118804EB8507301D082107 +:1017E000FFF7A6FEFB6806F14C005B691B681BB1A6 +:1017F000019001F06DFF019803A901F05BFF024623 +:1018000048B1039B2946204600F098F8002383F353 +:10181000118805B0F0BDFB685A691268002AF5D03E +:101820001B8A013B1340F1D104F18002EAE700007A +:10183000133138B550F82140ECB1302383F31188CF +:1018400004F58053D3F8A4281368527903EB82037C +:10185000DB689B695D6845B104216018FFF768FE8D +:10186000294604F1140001F05BFE2046FFF7B4FEA8 +:10187000002383F3118838BD7047000001F028B9B8 +:1018800001234022002110B5044600F8303BFFF749 +:1018900001FB0023C4E9013310BD000010B5302363 +:1018A000044683F311882422416000210C30FFF7A5 +:1018B000F1FA204601F02EF902230020237080F374 +:1018C000118810BD70B500EB8103054650690E46C6 +:1018D0001446DA6018B110220021FFF7DBFAA06984 +:1018E00018B110220021FFF7D5FA31462846BDE88D +:1018F000704001F015BA000083682022002103F037 +:10190000011310B5044683601030FFF7C3FA204678 +:10191000BDE8104001F090BAF0B4012500EB81045D +:1019200047898D40E4683D43A469458123600023D5 +:10193000A2606360F0BC01F0ADBA0000F0B4012514 +:1019400000EB810407898D40E4683D4364690581AB +:1019500023600023A2606360F0BC01F023BB0000A1 +:1019600070B5022300250446242203702946C0F8DE +:1019700088500C3040F8045CFFF78CFA204684F85D +:10198000705001F061F963681B6823B12946204655 +:10199000BDE87040184770BD0378052B10B50446AC +:1019A0000AD080F88C300523037043681B680BB1A4 +:1019B000042198470023A36010BD00000178052989 +:1019C00006D190F88C20436802701B6803B1184759 +:1019D0007047000070B590F87030044613B10023D2 +:1019E00080F8703004F18002204601F049FA636803 +:1019F0009B68B3B994F8803013F0600535D00021AE +:101A0000204601F03BFD0021204601F02BFD6368DC +:101A10001B6813B1062120469847062384F87030CE +:101A200070BD204698470028E4D0B4F88630A26FF5 +:101A30009A4288BFA36794F98030A56F002B4FF0BE +:101A4000300380F20381002D00F0F280092284F837 +:101A5000702083F3118800212046D4E91D23FFF76D +:101A60006DFF002383F31188DAE794F8812003F0F7 +:101A70007F0343EA022340F20232934200F0C58022 +:101A800021D8B3F5807F48D00DD8012B3FD0022B51 +:101A900000F09380002BB2D104F188026267022229 +:101AA000A267E367C1E7B3F5817F00F09B80B3F5E0 +:101AB000407FA4D194F88230012BA0D1B4F88830B3 +:101AC00043F0020332E0B3F5006F4DD017D8B3F501 +:101AD000A06F31D0A3F5C063012B90D86368204676 +:101AE00094F882205E6894F88310B4F88430B0478C +:101AF000002884D0436863670368A3671AE0B3F5DE +:101B0000106F36D040F6024293427FF478AF5C4BC0 +:101B100063670223A3670023C3E794F88230012B95 +:101B20007FF46DAFB4F8883023F00203A4F8883056 +:101B3000C4E91D55E56778E7B4F88030B3F5A06FC8 +:101B40000ED194F88230204684F88A3001F0DAF819 +:101B500063681B6813B10121204698470323237053 +:101B60000023C4E91D339CE704F18B036367012361 +:101B7000C3E72378042B10D1302383F31188204648 +:101B8000FFF7BAFE85F311880321636884F88B5050 +:101B900021701B680BB12046984794F88230002BC7 +:101BA000DED084F88B300423237063681B68002B1D +:101BB000D6D0022120469847D2E794F884302046B8 +:101BC0001D0603F00F010AD501F04CF9012804D0DD +:101BD00002287FF414AF2B4B9AE72B4B98E701F0C8 +:101BE00033F9F3E794F88230002B7FF408AF94F8D0 +:101BF000843013F00F01B3D01A06204602D501F04D +:101C000055FCADE701F046FCAAE794F88230002BC2 +:101C10007FF4F5AE94F8843013F00F01A0D01B06CA +:101C2000204602D501F02AFC9AE701F01BFC97E759 +:101C3000142284F8702083F311882B462A46294603 +:101C40002046FFF769FE85F31188E9E65DB11522AC +:101C500084F8702083F3118800212046D4E91D23E5 +:101C6000FFF75AFEFDE60B2284F8702083F31188FB +:101C70002B462A4629462046FFF760FEE3E700BFD1 +:101C8000BC410008B4410008B841000838B590F8DC +:101C900070300446002B3ED0063BDAB20F2A34D80F +:101CA0000F2B32D8DFE803F03731310822323131DF +:101CB0003131313131313737856FB0F886309D425F +:101CC00014D2C3681B8AB5FBF3F203FB12556DB93E +:101CD000302383F311882B462A462946FFF72EFE30 +:101CE00085F311880A2384F870300EE0142384F8F9 +:101CF0007030302383F31188002320461A4619469A +:101D0000FFF70AFE002383F3118838BDC36F03B1C8 +:101D100098470023E7E70021204601F0AFFB0021B0 +:101D2000204601F09FFB63681B6813B10621204623 +:101D300098470623D7E7000010B590F870300446A6 +:101D4000142B29D017D8062B05D001D81BB110BDF4 +:101D5000093B022BFBD80021204601F08FFB00211C +:101D6000204601F07FFB63681B6813B10621204603 +:101D70009847062319E0152BE9D10B2380F8703022 +:101D8000302383F3118800231A461946FFF7D6FD46 +:101D9000002383F31188DAE7C3689B695B68002B33 +:101DA000D5D1C36F03B19847002384F87030CEE7D4 +:101DB00000238268037503691B6899689142FBD20E +:101DC0005A68036042601060586070470023826860 +:101DD000037503691B6899689142FBD85A680360D0 +:101DE000426010605860704708B50846302383F39E +:101DF00011880B7D032B05D0042B0DD02BB983F359 +:101E0000118808BD8B6900221A604FF0FF3383618F +:101E1000FFF7CEFF0023F2E7D1E9003213605A60EA +:101E2000F3E70000FFF7C4BF054BD96808751868D1 +:101E3000026853601A600122D8600275FEF7E2BAA8 +:101E4000402400200C4B30B5DD684B1C87B00446A5 +:101E50000FD02B46094A684600F04EF92046FFF79E +:101E6000E3FF009B13B1684600F050F9A86907B082 +:101E700030BDFFF7D9FFF9E740240020E91D000835 +:101E8000044B1A68DB6890689B68984294BF0020F6 +:101E90000120704740240020084B10B51C68D8680A +:101EA000226853601A600122DC602275FFF78EFF02 +:101EB00001462046BDE81040FEF7A4BA40240020A9 +:101EC00038B5074C01230025064907482370656093 +:101ED00001F0E2FC0223237085F3118838BD00BFB6 +:101EE000A8260020C44100084024002000F044B986 +:101EF000034A516853685B1A9842FBD8704700BF89 +:101F0000001000E08B600223086108468B82704756 +:101F10008368A3F1840243F8142C026943F8442C2B +:101F2000426943F8402C094A43F8242CC268A3F1C3 +:101F3000200043F8182C022203F80C2C002203F88E +:101F40000B2C034A43F8102C704700BF1D040008F7 +:101F50004024002008B5FFF7DBFFBDE80840FFF78D +:101F600061BF0000024BDB6898610F20FFF75CBF88 +:101F700040240020302383F31188FFF7F3BF0000D3 +:101F800008B50146302383F311880820FFF75AFF74 +:101F9000002383F3118808BD064BDB6839B1426822 +:101FA00018605A60136043600420FFF74BBF4FF086 +:101FB000FF307047402400200368984206D01A681A +:101FC0000260506018469961FFF72CBF704700000F +:101FD00038B504460D462068844200D138BD0368F8 +:101FE00023605C608561FFF71DFFF4E7036810B5AF +:101FF0009C68A2420CD85C688A600B604C602160CF +:10200000596099688A1A9A604FF0FF33836010BD57 +:10201000121B1B68ECE700000A2938BF0A2170B5C3 +:1020200004460D460A26601901F02EFC01F016FC4C +:10203000041BA54203D8751C04462E46F3E70A2E5E +:1020400004D90120BDE8704001F066BC70BD0000FD +:10205000F8B5144B0D460A2A4FF00A07D96103F16F +:102060001001826038BF0A2241601969144601607C +:1020700048601861A81801F0F7FB01F0EFFB431B63 +:102080000646A34206D37C1C28192746354601F094 +:10209000FBFBF2E70A2F04D90120BDE8F84001F06C +:1020A0003BBCF8BD40240020F8B506460D4601F0C3 +:1020B000D5FB0F4A134653F8107F9F4206D12A469C +:1020C00001463046BDE8F840FFF7C2BFD169BB68A2 +:1020D000441A2C1928BF2C46A34202D92946FFF7DF +:1020E0009BFF224631460348BDE8F840FFF77EBF1C +:1020F0004024002050240020C0E90323002310B412 +:102100005DF8044B4361FFF7CFBF000010B5194CD9 +:10211000236998420DD08168D0E9003213605A607B +:102120009A680A449A60002303604FF0FF33A3616A +:1021300010BD0268234643F8102F5360002202604E +:1021400022699A4203D1BDE8104001F097BB936821 +:1021500081680B44936001F081FB2269E169926818 +:10216000441AA242E4D91144BDE81040091AFFF70D +:1021700053BF00BF402400202DE9F047DFF8BC80AA +:1021800008F110072C4ED8F8105001F067FBD8F872 +:102190001C40AA68031B9A423ED814444FF0000921 +:1021A000D5E90032C8F81C4013605A60C5F80090A9 +:1021B000D8F81030B34201D101F060FB89F31188E7 +:1021C000D5E9033128469847302383F311886B699A +:1021D000002BD8D001F042FB6A69A0EB04098246CB +:1021E0004A450DD2022001F097FB0022D8F81030AA +:1021F000B34208D151462846BDE8F047FFF728BF53 +:10220000121A2244F2E712EB09092946384638BF70 +:102210004A46FFF7EBFEB5E7D8F81030B34208D0D6 +:102220001444C8F81C00211AA960BDE8F047FFF764 +:10223000F3BEBDE8F08700BF5024002040240020FA +:1022400000207047FEE70000704700004FF0FF30AD +:102250007047000002290CD0032904D00129074847 +:1022600018BF00207047032A05D8054800EBC200BC +:102270007047044870470020704700BF9C42000828 +:102280003C2200205042000870B59AB0054608462E +:10229000144601A900F0C2F801A8FEF7F3FD431CA3 +:1022A0000022C6B25B001046C5E900342370032348 +:1022B000023404F8013C01ABD1B202348E4201D8A1 +:1022C0001AB070BD13F8011B013204F8010C04F8B8 +:1022D000021CF1E708B5302383F311880348FFF7A8 +:1022E00049FA002383F3118808BD00BFB0260020FF +:1022F00090F8803003F01F02012A07D190F8812066 +:102300000B2A03D10023C0E91D3315E003F060035D +:10231000202B08D1B0F884302BB990F88120212AE5 +:1023200003D81F2A04D8FFF707BA222AEBD0FAE70E +:10233000034A426707228267C3670120704700BFD4 +:102340003322002007B5052917D8DFE801F0191658 +:1023500003191920302383F31188104A01210190B9 +:10236000FFF7B0FA019802210D4AFFF7ABFA0D48CA +:10237000FFF7CCF9002383F3118803B05DF804FB69 +:10238000302383F311880748FFF796F9F2E73023EB +:1023900083F311880348FFF7ADF9EBE7F04100083C +:1023A00014420008B026002038B50C4D0C4C2A46CB +:1023B0000C4904F10800FFF767FF05F1CA0204F1B8 +:1023C00010000949FFF760FF05F5CA7204F1180013 +:1023D0000649BDE83840FFF757BF00BF883F0020DF +:1023E0003C220020D0410008DA410008E541000805 +:1023F00070B5044608460D46FEF744FDC6B22046B9 +:10240000013403780BB9184670BD32462946FEF7F1 +:1024100025FD0028F3D10120F6E700002DE9F84F53 +:1024200005460C46FEF72EFD2A49C6B22846FFF7A0 +:10243000DFFF08B10136F6B227492846FFF7D8FF7B +:1024400008B11036F6B2632E0DD8DFF88890DFF8A9 +:1024500088A0224FDFF88CB0DFF88C802E7846B948 +:102460002670BDE8F88F29462046BDE8F84F01F0F8 +:10247000E7BD252E2AD1072249462846FEF7EEFC65 +:1024800050B9D8F800300735083444F8083CD8F87B +:10249000043044F8043CE1E7082251462846FEF7A0 +:1024A000DDFC98B9A21C0E4B197802320909C95DEE +:1024B00002F8041C13F8011B01F00F015B45C95D14 +:1024C00002F8031CF0D118340835C7E7013504F8C9 +:1024D000016BC3E7BC420008E5410008CD4200089B +:1024E00000E8F11F0CE8F11FC4420008BFF34F8F52 +:1024F000044B1A695107FCD1D3F810215207F8D1C7 +:10250000704700BF0020005208B50D4B1B78ABB9D7 +:10251000FFF7ECFF0B4BDA68D10704D50A4A5A6083 +:1025200002F188325A60D3F80C21D20706D5064A48 +:10253000C3F8042102F18832C3F8042108BD00BFAA +:10254000E6410020002000522301674508B5114BE9 +:102550001B78F3B9104B1A69510703D5DA6842F0BA +:102560004002DA60D3F81021520705D5D3F80C21C8 +:1025700042F04002C3F80C21FFF7B8FF064BDA68BF +:1025800042F00102DA60D3F80C2142F00102C3F8F4 +:102590000C2108BDE6410020002000520F289ABF00 +:1025A00000F5806040040020704700004FF40030C8 +:1025B00070470000102070470F2808B50BD8FFF7B0 +:1025C000EDFF00F500330268013204D1043083428C +:1025D000F9D1012008BD0020FCE700000F2838B524 +:1025E00005463FD8FFF782FF1F4CFFF78DFF4FF0E6 +:1025F000FF3307286361C4F814311DD82361FFF746 +:1026000075FF030243F02403E360E36843F08003B3 +:10261000E36023695A07FCD42846FFF767FFFFF7FA +:10262000BDFF4FF4003100F0F5F82846FFF78EFFAC +:10263000BDE83840FFF7C0BFC4F81031FFF756FFC0 +:10264000A0F108031B0243F02403C4F80C31D4F8B2 +:102650000C3143F08003C4F80C31D4F810315B071F +:10266000FBD4D9E7002038BD002000522DE9F84FF7 +:1026700005460C46104645EA0203DE0602D000205D +:10268000BDE8F88F20F01F00DFF8BCB0DFF8BCA079 +:10269000FFF73AFF04EB0008444503D10120FFF7A0 +:1026A00055FFEDE720222946204601F0B9FC10B97C +:1026B00020352034F0E72B4605F120021F68791CF5 +:1026C000DDD104339A42F9D105F178431B481C4E01 +:1026D000B3F5801F1B4B38BF184603F1F80332BF18 +:1026E000D946D1461E46FFF701FF0760A5EB040C53 +:1026F000336804F11C0143F002033360231FD9F84F +:10270000007017F00507FAD153F8042F8B424CF8EC +:102710000320F4D1BFF34F8FFFF7E8FE4FF0FF33F4 +:102720002022214603602846336823F002033360E9 +:1027300001F076FC0028BBD03846B0E714210052E7 +:102740000C20005214200052102000521021005280 +:1027500010B5084C237828B11BB9FFF7D5FE01232B +:10276000237010BD002BFCD02070BDE81040FFF797 +:10277000EDBE00BFE64100200244074BD2B210B5C7 +:10278000904200D110BD441C00B253F8200041F823 +:10279000040BE0B2F4E700BF504000580E4B30B5D8 +:1027A0001C6F240405D41C6F1C671C6F44F4004488 +:1027B0001C670A4C02442368D2B243F4807323603E +:1027C000074B904200D130BD441C51F8045B00B26D +:1027D00043F82050E0B2F4E70044025800480258A1 +:1027E0005040005807B5012201A90020FFF7C4FF9F +:1027F000019803B05DF804FB13B50446FFF7F2FF40 +:10280000A04205D0012201A900200194FFF7C6FFD4 +:1028100002B010BD0144BFF34F8F064B884204D372 +:10282000BFF34F8FBFF36F8F7047C3F85C02203048 +:10283000F4E700BF00ED00E0034B1A681AB9034A41 +:10284000D2F8D0241A607047E841002000400258B6 +:1028500008B5FFF7F1FF024B1868C0F3806008BDB0 +:10286000E8410020EFF30983054968334A6B22F001 +:1028700001024A6383F30988002383F311887047B8 +:1028800000EF00E0302080F3118862B60D4B0E4A55 +:10289000D96821F4E0610904090C0A430B49DA60A4 +:1028A000D3F8FC2042F08072C3F8FC20084AC2F83A +:1028B000B01F116841F0010111602022DA7783F81E +:1028C0002200704700ED00E00003FA0555CEACC5CC +:1028D000001000E0302310B583F311880E4B5B68C5 +:1028E00013F4006314D0F1EE103AEFF309844FF0C3 +:1028F0008073683CE361094BDB6B236684F30988D2 +:10290000FFF7BEFA10B1064BA36110BD054BFBE704 +:1029100083F31188F9E700BF00ED00E000EF00E06D +:102920002F0400083204000870B5BFF34F8FBFF3C7 +:102930006F8F1A4A0021C2F85012BFF34F8FBFF3B6 +:102940006F8F536943F400335361BFF34F8FBFF36D +:102950006F8FC2F88410BFF34F8FD2F8803043F6E8 +:10296000E074C3F3C900C3F34E335B0103EA04060A +:10297000014646EA81750139C2F86052F9D2203B1E +:1029800013F1200FF2D1BFF34F8F536943F480331B +:102990005361BFF34F8FBFF36F8F70BD00ED00E049 +:1029A000FEE70000214B2248224A70B5904237D3FF +:1029B000214BC11EDA1C121A22F003028B4238BFCF +:1029C00000220021FEF766FA1C4A0023C2F8843078 +:1029D000BFF34F8FD2F8803043F6E074C3F3C900E1 +:1029E000C3F34E335B0103EA0406014646EA8175F0 +:1029F0000139C2F86C52F9D2203B13F1200FF2D109 +:102A0000BFF34F8FBFF36F8FBFF34F8FBFF36F8F46 +:102A10000023C2F85032BFF34F8FBFF36F8F70BDEA +:102A200053F8041B40F8041BC0E700BFBC44000877 +:102A3000BC430020BC430020BC43002000ED00E06C +:102A4000074BD3F8D81021EA0001C3F8D810D3F807 +:102A5000002122EA0002C3F80021D3F800317047B8 +:102A60000044025870B5D0E9244300224FF0FF35EE +:102A70009E6804EB42135101D3F80009002805DADF +:102A8000D3F8000940F08040C3F80009D3F8000BE8 +:102A9000002805DAD3F8000B40F08040C3F8000BA3 +:102AA000013263189642C3F80859C3F8085BE0D2B4 +:102AB0004FF00113C4F81C3870BD0000890141F0CB +:102AC0002001016103699B06FCD41220FFF710BAB4 +:102AD00010B50A4C2046FEF7D3FE094BC4F89030DF +:102AE000084BC4F89430084C2046FEF7C9FE074B4B +:102AF000C4F89030064BC4F8943010BDEC4100206F +:102B00000000084004430008884200200000044000 +:102B10001043000870B503780546012B5CD1434B88 +:102B2000D0F89040984258D1414B0E216520D3F8FF +:102B3000D82042F00062C3F8D820D3F8002142F038 +:102B40000062C3F80021D3F80021D3F8802042F0BE +:102B50000062C3F88020D3F8802022F00062C3F81E +:102B60008020D3F88030FEF7B7FC324BE360324B65 +:102B7000C4F800380023D5F89060C4F8003EC023A4 +:102B800023604FF40413A3633369002BFCDA0123A1 +:102B90000C203361FFF7ACF93369DB07FCD412205A +:102BA000FFF7A6F93369002BFCDA00262846A66059 +:102BB000FFF758FF6B68C4F81068DB68C4F8146846 +:102BC000C4F81C6883BB1D4BA3614FF0FF336361E6 +:102BD000A36843F00103A36070BD194B9842C9D1AB +:102BE000134B4FF08060D3F8D82042F00072C3F846 +:102BF000D820D3F8002142F00072C3F80021D3F8A6 +:102C00000021D3F8802042F00072C3F88020D3F86E +:102C1000802022F00072C3F88020D3F88030FFF7C4 +:102C20000FFF0E214D209EE7064BCDE7EC41002023 +:102C3000004402584014004003002002003C30C011 +:102C400088420020083C30C0F8B5D0F890400546D6 +:102C500000214FF000662046FFF730FFD5F89410B2 +:102C600000234FF001128F684FF0FF30C4F8343862 +:102C7000C4F81C2804EB431201339F42C2F80069D8 +:102C8000C2F8006BC2F80809C2F8080BF2D20B6850 +:102C9000D5F89020C5F89830636210231361166947 +:102CA00016F01006FBD11220FFF722F9D4F80038F5 +:102CB00023F4FE63C4F80038A36943F4402343F0CF +:102CC0001003A3610923C4F81038C4F814380B4B5F +:102CD000EB604FF0C043C4F8103B094BC4F8003B15 +:102CE000C4F81069C4F80039D5F8983003F110021F +:102CF00043F48013C5F89820A362F8BDE0420008B1 +:102D000040800010D0F8902090F88A10D2F8003857 +:102D100023F4FE6343EA0113C2F800387047000051 +:102D20002DE9F84300EB8103D0F890500C46804623 +:102D3000DA680FFA81F94801166806F00306731E77 +:102D4000022B05EB41134FF0000194BFB604384E3F +:102D5000C3F8101B4FF0010104F1100398BF06F1F6 +:102D6000805601FA03F3916998BF06F500460029E1 +:102D70003AD0578A04F15801374349016F50D5F8CA +:102D80001C180B430021C5F81C382B180127C3F869 +:102D90001019A7405369611E9BB3138A928B9B083D +:102DA000012A88BF5343D8F89820981842EA034371 +:102DB00001F140022146C8F89800284605EB82023E +:102DC0005360FFF77BFE08EB8900C3681B8A43EA68 +:102DD000845348341E4364012E51D5F81C381F43D8 +:102DE000C5F81C78BDE8F88305EB4917D7F8001B38 +:102DF00021F40041C7F8001BD5F81C1821EA030391 +:102E0000C0E704F13F030B4A2846214605EB830344 +:102E10005A60FFF753FE05EB4910D0F8003923F450 +:102E20000043C0F80039D5F81C3823EA0707D7E774 +:102E30000080001000040002D0F894201268C0F84E +:102E40009820FFF70FBE00005831D0F890304901AC +:102E50005B5813F4004004D013F4001F0CBF022091 +:102E6000012070474831D0F8903049015B5813F485 +:102E7000004004D013F4001F0CBF02200120704753 +:102E800000EB8101CB68196A0B6813604B685360D3 +:102E90007047000000EB810330B5DD68AA69136854 +:102EA000D36019B9402B84BF402313606B8A146828 +:102EB000D0F890201C4402EB4110013C09B2B4FB55 +:102EC000F3F46343033323F0030343EAC44343F0BF +:102ED000C043C0F8103B2B6803F00303012B0ED155 +:102EE000D2F8083802EB411013F4807FD0F8003B91 +:102EF00014BF43F0805343F00053C0F8003B02EB93 +:102F00004112D2F8003B43F00443C2F8003B30BD0D +:102F10002DE9F041D0F8906005460C4606EB4113D0 +:102F2000D3F8087B3A07C3F8087B08D5D6F81438DD +:102F30001B0704D500EB8103DB685B689847FA0741 +:102F40001FD5D6F81438DB071BD505EB8403D968E9 +:102F5000CCB98B69488A5A68B2FBF0F600FB16229E +:102F60008AB91868DA6890420DD2121AC3E90024AF +:102F7000302383F3118821462846FFF78BFF84F323 +:102F80001188BDE8F081012303FA04F26B8923EA7A +:102F900002036B81CB68002BF3D021462846BDE8A5 +:102FA000F041184700EB81034A0170B5DD68D0F8A5 +:102FB00090306C692668E66056BB1A444FF40020D6 +:102FC000C2F810092A6802F00302012A0AB20ED1DF +:102FD000D3F8080803EB421410F4807FD4F80009FA +:102FE00014BF40F0805040F00050C4F8000903EBDB +:102FF0004212D2F8000940F00440C2F80009012250 +:10300000D3F8340802FA01F10143C3F8341870BD53 +:1030100019B9402E84BF4020206020681A442E8AAF +:103020008419013CB4FBF6F440EAC44040F000507F +:10303000C6E700002DE9F843D0F8906005460C463D +:103040004F0106EB4113D3F8088918F0010FC3F8BC +:1030500008891CD0D6F81038DB0718D500EB81039F +:10306000D3F80CC0DCF81430D3F800E0DA689645E9 +:1030700030D2A2EB0E024FF000091A60C3F80490A0 +:10308000302383F31188FFF78DFF89F3118818F03F +:10309000800F1DD0D6F834380126A640334217D011 +:1030A00005EB84030134D5F89050D3F80CC0E4B29A +:1030B0002F44DCF8142005EB0434D2F800E051680A +:1030C000714514D3D5F8343823EA0606C5F83468B8 +:1030D000BDE8F883012303FA01F2038923EA02031E +:1030E0000381DCF80830002BD1D09847CFE7AEEB56 +:1030F0000103BCF81000834228BF0346D7F8180923 +:1031000080B2B3EB800FE3D89068A0F1040959F8BE +:10311000048FC4F80080A0EB09089844B8F1040FAC +:10312000F5D818440B4490605360C8E72DE9F84F78 +:10313000D0F8905004466E69AB691E4016F4805872 +:103140006E6103D0BDE8F84FFEF70ABC002E12DA1C +:10315000D5F8003E9B0705D0D5F8003E23F00303C9 +:10316000C5F8003ED5F80438204623F00103C5F821 +:103170000438FEF723FC370505D52046FFF772FC1F +:103180002046FEF709FCB0040CD5D5F8083813F03A +:10319000060FEB6823F470530CBF43F4105343F451 +:1031A000A053EB6031071BD56368DB681BB9AB69C3 +:1031B00023F00803AB612378052B0CD1D5F8003E32 +:1031C0009A0705D0D5F8003E23F00303C5F8003E6A +:1031D0002046FEF7F3FB6368DB680BB12046984797 +:1031E000F30200F1BA80B70226D5D4F890900027F8 +:1031F0004FF0010A09EB4712D2F8003B03F44023D9 +:10320000B3F5802F11D1D2F8003B002B0DDA628983 +:103210000AFA07F322EA0303638104EB8703DB68FE +:10322000DB6813B13946204698470137D4F894300B +:10323000FFB29B689F42DDD9F00619D5D4F8900003 +:10324000026AC2F30A1702F00F0302F4F012B2F599 +:10325000802F00F0CA80B2F5402F09D104EB830320 +:10326000002200F58050DB681B6A974240F0B08076 +:103270003003D5F8185835D5E90303D50021204689 +:10328000FFF746FEAA0303D501212046FFF740FEC3 +:103290006B0303D502212046FFF73AFE2F0303D527 +:1032A00003212046FFF734FEE80203D5042120461F +:1032B000FFF72EFEA90203D505212046FFF728FEC1 +:1032C0006A0203D506212046FFF722FE2B0203D512 +:1032D00007212046FFF71CFEEF0103D508212046F9 +:1032E000FFF716FE700340F1A780E90703D5002120 +:1032F0002046FFF79FFEAA0703D501212046FFF7CE +:1033000099FE6B0703D502212046FFF793FE2F0796 +:1033100003D503212046FFF78DFEEE0603D50421D9 +:103320002046FFF787FEA80603D505212046FFF7B4 +:1033300081FE690603D506212046FFF77BFE2A069B +:1033400003D507212046FFF775FEEB0574D520460F +:103350000821BDE8F84FFFF76DBED4F890904FF00C +:10336000000B4FF0010AD4F894305FFA8BF79B689A +:103370009F423FF638AF09EB4713D3F8002902F418 +:103380004022B2F5802F20D1D3F80029002A1CDA80 +:10339000D3F8002942F09042C3F80029D3F800295D +:1033A000002AFBDB3946D4F89000FFF787FB22891F +:1033B0000AFA07F322EA0303238104EB8703DB689D +:1033C0009B6813B13946204698470BF1010BCAE7B9 +:1033D000910701D1D0F80080072A02F101029CBFB9 +:1033E00003F8018B4FEA18283FE704EB830300F54D +:1033F0008050DA68D2F818C0DCF80820DCE9001C3C +:10340000A1EB0C0C00218F4208D1DB689B699A6804 +:103410003A449A605A683A445A6029E711F0030F17 +:1034200001D1D0F800808C4501F1010184BF02F880 +:10343000018B4FEA1828E6E7BDE8F88F08B5034886 +:10344000FFF774FEBDE80840FFF744BAEC410020E6 +:1034500008B50348FFF76AFEBDE80840FFF73ABA2F +:1034600088420020D0F8903003EB4111D1F8003BA6 +:1034700043F40013C1F8003B70470000D0F89030CF +:1034800003EB4111D1F8003943F40013C1F80039BE +:1034900070470000D0F8903003EB4111D1F8003BA9 +:1034A00023F40013C1F8003B70470000D0F89030BF +:1034B00003EB4111D1F8003923F40013C1F80039AE +:1034C0007047000030B50433039C0172002104FBF7 +:1034D0000325C160C0E90653049B0363059BC0E953 +:1034E0000000C0E90422C0E90842C0E90A114363B0 +:1034F00030BD00000022416AC260C0E90411C0E989 +:103500000A226FF00101FEF763BD0000D0E904322A +:10351000934201D1C2680AB9181D70470020704754 +:10352000036919600021C2680132C260C269134494 +:1035300082699342036124BF436A0361FEF73CBD85 +:1035400038B504460D46E3683BB162690020131D9F +:103550001268A3621344E36207E0237A33B9294671 +:103560002046FEF719FD0028EDDA38BD6FF00100A6 +:10357000FBE70000C368C269013BC36043691344B1 +:1035800082699342436124BF436A4361002383629B +:10359000036B03B11847704770B53023044683F3BB +:1035A0001188866A3EB9FFF7CBFF054618B186F34E +:1035B0001188284670BDA36AE26A13F8015B934242 +:1035C000A36202D32046FFF7D5FF002383F31188BF +:1035D000EFE700002DE9F84F04460E4617469846DF +:1035E0004FF0300989F311880025AA46D4F828B095 +:1035F000BBF1000F09D141462046FFF7A1FF20B1E2 +:103600008BF311882846BDE8F88FD4E90A12A7EB9E +:10361000050B521A934528BF9346BBF1400F1BD9A7 +:10362000334601F1400251F8040B914243F8040B78 +:10363000F9D1A36A403640354033A362D4E90A2366 +:103640009A4202D32046FFF795FF8AF31188BD42C4 +:10365000D8D289F31188C9E730465A46FDF7F4FB02 +:10366000A36A5E445D445B44A362E7E710B5029C35 +:103670000433017203FB0421C460C0E90613002374 +:10368000C0E90A33039B0363049BC0E90000C0E95F +:103690000422C0E90842436310BD0000026A6FF0D3 +:1036A0000101C260426AC0E904220022C0E90A2284 +:1036B000FEF78EBCD0E904239A4201D1C26822B938 +:1036C000184650F8043B0B60704700231846FAE791 +:1036D000C3680021C2690133C3604369134482692E +:1036E0009342436124BF436A4361FEF765BC000017 +:1036F00038B504460D46E3683BB1236900201A1D26 +:10370000A262E2691344E36207E0237A33B92946EF +:103710002046FEF741FC0028EDDA38BD6FF00100CD +:10372000FBE7000003691960C268013AC260C26920 +:10373000134482699342036124BF436A03610023F7 +:103740008362036B03B118477047000070B53023E4 +:103750000D460446114683F31188866A2EB9FFF799 +:10376000C7FF10B186F3118870BDA36A1D70A36AEC +:10377000E26A01339342A36204D3E169204604392B +:10378000FFF7D0FF002080F31188EDE72DE9F84F17 +:1037900004460D46904699464FF0300A8AF3118848 +:1037A0000026B346A76A4FB949462046FFF7A0FF57 +:1037B00020B187F311883046BDE8F88FD4E90A07B5 +:1037C0003A1AA8EB0607974228BF1746402F1BD985 +:1037D00005F1400355F8042B9D4240F8042BF9D124 +:1037E000A36A40364033A362D4E90A239A4204D341 +:1037F000E16920460439FFF795FF8BF311884645B0 +:10380000D9D28AF31188CDE729463A46FDF71CFB49 +:10381000A36A3D443E443B44A362E5E7D0E9042368 +:103820009A4217D1C3689BB1836A8BB1043B9B1A40 +:103830000ED01360C368013BC360C3691A44836937 +:103840009A42026124BF436A036100238362012319 +:10385000184670470023FBE700F024B9014B586A73 +:10386000704700BF000C0040034B002258631A61F0 +:103870000222DA60704700BF000C0040014B0022BA +:10388000DA607047000C0040014B5863704700BF7E +:10389000000C0040FEE7000070B51B4B00250446FD +:1038A00086B058600E4685620163FEF7EBFF04F1B7 +:1038B0001003A560E562C4E904334FF0FF33C4E9A7 +:1038C0000044C4E90635FFF7C9FF2B46024604F160 +:1038D00034012046C4E9082380230C4A2565FEF7FD +:1038E00011FB01230A4AE060009203756846726882 +:1038F0000192B268CDE90223064BCDE90435FEF70B +:1039000029FB06B070BD00BFA82600201C4300089C +:103910002143000895380008024AD36A1843D06250 +:10392000704700BF402400204B6843608B68836071 +:10393000CB68C3600B6943614B6903628B69436267 +:103940000B6803607047000008B53C4B40F2FF7104 +:103950003B48D3F888200A43C3F88820D3F888204E +:1039600022F4FF6222F00702C3F88820D3F88820EF +:10397000D3F8E0200A43C3F8E020D3F808210A4333 +:10398000C3F808212F4AD3F808311146FFF7CCFFBE +:1039900000F5806002F11C01FFF7C6FF00F58060B2 +:1039A00002F13801FFF7C0FF00F5806002F1540119 +:1039B000FFF7BAFF00F5806002F17001FFF7B4FF76 +:1039C00000F5806002F18C01FFF7AEFF00F580602A +:1039D00002F1A801FFF7A8FF00F5806002F1C40121 +:1039E000FFF7A2FF00F5806002F1E001FFF79CFF06 +:1039F00000F5806002F1FC01FFF796FF02F58C7183 +:103A000000F58060FFF790FF00F018F90E4BD3F837 +:103A1000902242F00102C3F89022D3F8942242F09F +:103A20000102C3F894220522C3F898204FF0605297 +:103A3000C3F89C20054AC3F8A02008BD00440258E2 +:103A4000000002582843000800ED00E01F000803B2 +:103A500008B500F0C7FAFEF733FA0F4BD3F8DC20B5 +:103A600042F04002C3F8DC20D3F8042122F04002E7 +:103A7000C3F80421D3F80431084B1A6842F0080255 +:103A80001A601A6842F004021A60FEF7D5FEBDE81B +:103A90000840FEF789BC00BF0044025800180248E5 +:103AA00070470000114BD3F8E82042F00802C3F839 +:103AB000E820D3F8102142F00802C3F810210C4A84 +:103AC000D3F81031D36B43F00803D363C722094BFB +:103AD0009A624FF0FF32DA6200229A615A63DA602A +:103AE0005A6001225A611A60704700BF00440258B0 +:103AF0000010005C000C0040094A08B51169D36849 +:103B00000B40D9B29B076FEA0101116107D5302341 +:103B100083F31188FEF7EAF9002383F3118808BDC7 +:103B2000000C0040064BD3F8DC200243C3F8DC2035 +:103B3000D3F804211043C3F80401D3F804317047CB +:103B40000044025808B53C4B4FF0FF31D3F88020B9 +:103B500062F00042C3F88020D3F8802002F00042D7 +:103B6000C3F88020D3F88020D3F88420C3F88410D1 +:103B7000D3F884200022C3F88420D3F88400D86FBF +:103B800040F0FF4040F4FF0040F4DF4040F07F0091 +:103B9000D867D86F20F0FF4020F4FF0020F4DF400A +:103BA00020F07F00D867D86FD3F888006FEA4050C4 +:103BB0006FEA5050C3F88800D3F88800C0F30A00B9 +:103BC000C3F88800D3F88800D3F89000C3F89010A9 +:103BD000D3F89000C3F89020D3F89000D3F8940065 +:103BE000C3F89410D3F89400C3F89420D3F8940049 +:103BF000D3F89800C3F89810D3F89800C3F8982029 +:103C0000D3F89800D3F88C00C3F88C10D3F88C004C +:103C1000C3F88C20D3F88C00D3F89C00C3F89C1018 +:103C2000D3F89C10C3F89C20D3F89C30FDF778FBA8 +:103C3000BDE8084000F0AEB90044025808B50122C2 +:103C4000534BC3F80821534BD3F8F42042F002023F +:103C5000C3F8F420D3F81C2142F00202C3F81C215F +:103C60000222D3F81C314C4BDA605A689104FCD51F +:103C70004A4A1A6001229A60494ADA6000221A61AF +:103C80004FF440429A61444B9A699204FCD51A68F9 +:103C900042F480721A603F4B1A6F12F4407F04D0D6 +:103CA0004FF480321A6700221A671A6842F0010244 +:103CB0001A60384B1A685007FCD500221A611A693D +:103CC00012F03802FBD1012119604FF08041596098 +:103CD0005A67344ADA62344A1A611A6842F4803206 +:103CE0001A602C4B1A689103FCD51A6842F4805272 +:103CF0001A601A689204FCD52C4A2D499A62002257 +:103D00005A63196301F57C01DA6301F2E7119963E3 +:103D10005A64284A1A64284ADA621A6842F0A85299 +:103D20001A601C4B1A6802F02852B2F1285FF9D1D0 +:103D300048229A614FF48862DA6140221A621F4A6F +:103D4000DA641F4A1A651F4A5A651F4A9A65322368 +:103D50001E4A1360136803F00F03022BFAD10D4AB9 +:103D6000136943F003031361136903F03803182B3D +:103D7000FAD14FF00050FFF7D5FE4FF08040FFF72B +:103D8000D1FE4FF00040BDE80840FFF7CBBE00BFBA +:103D900000800051004402580048025800C000F062 +:103DA000020000010000FF010088900812102000AE +:103DB00063020901470E0508DD0BBF01200000204A +:103DC000000001100910E000000101100020005265 +:103DD0004FF0B04208B5D2F8883003F00103C2F8C2 +:103DE000883023B1044A13680BB150689847BDE886 +:103DF0000840FEF76FBD00BF3C4300204FF0B042CB +:103E000008B5D2F8883003F00203C2F8883023B135 +:103E1000044A93680BB1D0689847BDE80840FEF7A4 +:103E200059BD00BF3C4300204FF0B04208B5D2F866 +:103E3000883003F00403C2F8883023B1044A1369C0 +:103E40000BB150699847BDE80840FEF743BD00BF7D +:103E50003C4300204FF0B04208B5D2F8883003F060 +:103E60000803C2F8883023B1044A93690BB1D069C2 +:103E70009847BDE80840FEF72DBD00BF3C43002039 +:103E80004FF0B04208B5D2F8883003F01003C2F802 +:103E9000883023B1044A136A0BB1506A9847BDE8D1 +:103EA0000840FEF717BD00BF3C4300204FF0B04371 +:103EB00010B5D3F8884004F47872C3F88820A306BC +:103EC00004D5124A936A0BB1D06A9847600604D5AC +:103ED0000E4A136B0BB1506B9847210604D50B4A61 +:103EE000936B0BB1D06B9847E20504D5074A136C6E +:103EF0000BB1506C9847A30504D5044A936C0BB1E1 +:103F0000D06C9847BDE81040FEF7E4BC3C4300206D +:103F10004FF0B04310B5D3F8884004F47C42C3F8A6 +:103F20008820620504D5164A136D0BB1506D984771 +:103F3000230504D5124A936D0BB1D06D9847E00468 +:103F400004D50F4A136E0BB1506E9847A10404D5E7 +:103F50000B4A936E0BB1D06E9847620404D5084AA1 +:103F6000136F0BB1506F9847230404D5044A936F25 +:103F70000BB1D06F9847BDE81040FEF7ABBC00BF57 +:103F80003C43002008B5FFF7B7FDBDE80840FEF749 +:103F9000A1BC0000062108B50846FDF79DFA0621E0 +:103FA0000720FDF799FA06210820FDF795FA06216A +:103FB0000920FDF791FA06210A20FDF78DFA062166 +:103FC0001720FDF789FA06212820FDF785FA092137 +:103FD0007A20FDF781FA07213220BDE80840FDF77D +:103FE0007BBA000008B5FFF7ADFD00F00BF8FDF758 +:103FF00045FCFDF717FBFFF753FDBDE80840FFF751 +:104000002BBC00000023054A19460133102BC2E9DE +:10401000001102F10802F8D1704700BF3C430020B4 +:1040200010B501390244904201D1002005E0037827 +:1040300011F8014FA34201D0181B10BD0130F2E767 +:10404000034611F8012B03F8012B002AF9D1704720 +:1040500053544D333248373F3F3F0053544D333272 +:10406000483733782F3732780053544D333248373E +:1040700034332F3735332F373530000001105A00D5 +:104080000310590001205800032056001000024080 +:10409000080002400008024000000B002800024017 +:1040A000080002400408024006010C0040000240E3 +:1040B000080002400808024010020D0058000240AB +:1040C000080002400C08024016030E007000024077 +:1040D0000C0002401008024000040F00880002405B +:1040E0000C0002401408024006051000A000024027 +:1040F0000C0002401808024010061100B8000240EF +:104100000C0002401C08024016072F001004024059 +:104110000804024020080240000838002804024039 +:104120000804024024080240060939004004024005 +:104130000804024028080240100A3A0058040240CD +:10414000080402402C080240160B3B007004024099 +:104150000C04024030080240000C3C00880402407D +:104160000C04024034080240060D4400A004024042 +:104170000C04024038080240100E4500B80402400A +:104180000C0402403C080240160F460000000000EC +:10419000A11500088D150008C9150008B5150008FF +:1041A000C1150008AD15000899150008851500080F +:1041B000D51500080000000001000000000000000C +:1041C00063300000C041000898240020A826002089 +:1041D0004172647550696C6F740025424F415244BE +:1041E000252D424C002553455249414C25000000E5 +:1041F0000200000000000000C1170008311800088C +:1042000040004000583F0020683F002002000000AE +:104210000000000003000000000000007918000802 +:104220000000000010000000783F002000000000A7 +:104230000100000000000000EC410020010102002C +:104240004523000855220008F1220008D522000865 +:10425000430000005842000809024300020100C068 +:1042600032090400000102020100052400100105CA +:10427000240100010424020205240600010705822E +:10428000030800FF09040100020A000000070501FD +:1042900002400000070581024000000012000000FB +:1042A000A442000812011001020000400912415707 +:1042B00000020102030100000403090425424F41EA +:1042C000524425003252415748373433003031329E +:1042D00033343536373839414243444546000000CF +:1042E00000000000D51900088D1C0008391D0008C9 +:1042F000400040002443002024430020010000002F +:10430000344300208000000040010000080000004D +:104310000001000000100000080000006D61696EDF +:104320000069646C650000000000816A0000000004 +:10433000AAAAAAAA00000064FFFE00000000000074 +:1043400000A00A000000000100000000AAAAAAAA1A +:1043500000000001FFFF000000000000000000005E +:104360000000004000000000AAAAAAAA0000004025 +:10437000FFFF0000000000000000000000005000EF +:1043800000000000AAAAAAAA00000000FFF700008F +:10439000000000000000000000000000000000001D +:1043A000AAAAAAAA00000000FFFF00000000000067 +:1043B000000000000000000000000000AAAAAAAA55 +:1043C00000000000FFFF00000000000000000000EF +:1043D0000000000000000000AAAAAAAA0000000035 +:1043E000FFFF0000000000000000000000000000CF +:1043F00000000000AAAAAAAA00000000FFFF000017 +:1044000000000000000000000000000000000000AC +:10441000AAAAAAAA00000000FFFF000000000000F6 +:10442000000000000000000000000000AAAAAAAAE4 +:1044300000000000FFFF000000000000000000007E +:104440000000000000000000AAAAAAAA00000000C4 +:10445000FFFF00000000000000000000000000005E +:10446000950400000000000000001A000000000099 +:10447000FF0000000000000050400008830400001E +:104480005B400008500400006940000800960000EE +:104490000000080096000000000800000400000072 +:1044A000B84200080000000000000000000000000A +:0C44B00000000000000000000000000000 +:00000001FF diff --git a/Tools/bootloaders/JHEMCU-H743HD_bl.bin b/Tools/bootloaders/JHEMCU-H743HD_bl.bin new file mode 100644 index 00000000000000..f784dbeffef99a Binary files /dev/null and b/Tools/bootloaders/JHEMCU-H743HD_bl.bin differ diff --git a/Tools/bootloaders/JHEM_JHEF405_bl.bin b/Tools/bootloaders/JHEM_JHEF405_bl.bin index 89ad64881e8333..66453f2c23beb2 100755 Binary files a/Tools/bootloaders/JHEM_JHEF405_bl.bin and b/Tools/bootloaders/JHEM_JHEF405_bl.bin differ diff --git a/Tools/bootloaders/JHEM_JHEF405_bl.hex b/Tools/bootloaders/JHEM_JHEF405_bl.hex index c5856052cd411d..aaeafa088a23c6 100644 --- a/Tools/bootloaders/JHEM_JHEF405_bl.hex +++ b/Tools/bootloaders/JHEM_JHEF405_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 :1000000000060020E1010008E3010008E301000808 :10001000E3010008E3010008E3010008E301000830 -:10002000E3010008E3010008E30100086D2F000868 +:10002000E3010008E3010008E3010008AD35000822 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008153200083D32000802 -:10006000653200088D320008B5320008E30100084F +:10005000E3010008E3010008553800087D38000876 +:10006000A5380008CD380008F5380008E30100087D :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008DD32000885 +:10009000E3010008E3010008E30100081D3900083E :1000A000E3010008E3010008E3010008E3010008A0 -:1000B000B1330008E3010008E3010008E301000890 +:1000B000053A0008E3010008E3010008E301000835 :1000C000E3010008E3010008E3010008E301000880 :1000D000E3010008E3010008E3010008E301000870 -:1000E00041330008E3010008E3010008E3010008D0 +:1000E00081390008E3010008E3010008E30100088A :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008212700089B -:10015000E3010008E3010008E3010008E3010008EF +:10014000E3010008E3010008E3010008612D000855 +:10015000E3010008E3010008E3010008F1390008A9 :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF :10018000E3010008E3010008E3010008E3010008BF @@ -35,43 +35,43 @@ :100210004F8FBFF36F8F40F20000C0F2F0004EF638 :100220008851CEF200010860BFF34F8FBFF36F8F8C :100230004FF00000E1EE100A4EF63C71CEF20001E4 -:100240000860062080F31488BFF36F8F01F030FF41 -:1002500002F02AFE4FF055301F491B4A91423CBF25 +:100240000860062080F31488BFF36F8F02F050FA25 +:1002500003F04AF94FF055301F491B4A91423CBF09 :1002600041F8040BFAE71D49184A91423CBF41F896 :10027000040BFAE71A491B4A1B4B9A423EBF51F83E :10028000040B42F8040BF8E700201849184A914281 -:100290003CBF41F8040BFAE701F00EFF02F058FEF4 +:100290003CBF41F8040BFAE702F02EFA03F078F9BC :1002A000144C154DAC4203DA54F8041B8847F9E7A7 :1002B00000F042F8114C124DAC4203DA54F8041B22 -:1002C0008847F9E701F0F6BE000600200022002072 +:1002C0008847F9E702F016BA000600200022002055 :1002D0000000000808ED00E00000002000060020FB -:1002E0007837000800220020402200204022002011 -:1002F000602E0020E0010008E0010008E001000895 +:1002E000103E0008002200204C2200205022002056 +:1002F000F0300020E0010008E0010008E001000803 :10030000E00100082DE9F04F2DED108AC1F80CD066 :10031000C3689D46BDEC108ABDE8F08F002383F3CF -:1003200011882846A047002001F072FAFEE701F08C -:1003300001FA00DFFEE7000038B500F0BBFB01F07A -:1003400087FE054601F0AAFE0446C8B90E4B9D4241 +:1003200011882846A047002001F092FDFEE701F069 +:1003300021FD00DFFEE7000038B500F0D1FB02F040 +:10034000A7F9054602F0CAF90446C8B90E4B9D420A :1003500018D001339D4218BF044641F2883504BFCE -:1003600001240025002001F07DFE0CB100F074F89E -:1003700000F000FD284600F0BFF800F06DF8F9E746 +:1003600001240025002002F09DF90CB100F074F882 +:1003700000F016FD284600F0BFF800F06DF8F9E730 :100380000025EFE70546EDE7010007B008B500F0EE -:1003900063FBA0F120035842584108BD07B541F264 -:1003A0001203022101A8ADF8043000F073FB03B082 +:1003900073FBA0F120035842584108BD07B541F254 +:1003A0001203022101A8ADF8043000F083FB03B072 :1003B0005DF804FB38B5302383F3118817480368D0 -:1003C0000BB101F0F1FA164A144800234FF47A7188 -:1003D00001F0E0FA002383F31188124C236813B173 +:1003C0000BB101F011FE164A144800234FF47A7164 +:1003D00001F000FE002383F31188124C236813B14F :1003E0002368013B2360636813B16368013B63606A -:1003F0000D4D2B7833B963687BB9022000F024FCE3 +:1003F0000D4D2B7833B963687BB9022000F03AFCCD :10040000322363602B78032B07D163682BB902205A -:1004100000F01AFC4FF47A73636038BD402200206C -:10042000B50300086023002058220020084B1870F4 +:1004100000F030FC4FF47A73636038BD5022002046 +:10042000B50300087023002068220020084B1870D4 :1004300003280CD8DFE800F008050208022000F0CD -:10044000F9BB022000F0ECBB024B00225A6070475F -:100450005822002060230020234B244A10B51C465C +:100440000FBC022000F002BC024B00225A60704731 +:100450006822002070230020234B244A10B51C463C :10046000196801313FD004339342F9D16268A24246 :1004700039D31F4B9B6803F1006303F540439A4255 -:1004800031D2002000F030FB0220FFF7CFFF194BE4 +:1004800031D2002000F046FB0220FFF7CFFF194BCE :100490001A6C00221A64196E1A66196E596C5A6425 :1004A000596E5A665A6E5A6942F080025A615A6908 :1004B00022F080025A615A691A6942F000521A61A8 @@ -79,15 +79,15 @@ :1004D0003021C3F8084DD4E9003281F311889D46DC :1004E00083F30888104710BD00C0000820C0000832 :1004F00000220020003802402DE9F04F93B0AA4BB3 -:1005000000902022FF210AA89D6800F0DDFBA74A89 +:1005000000902022FF210AA89D6800F0F3FBA74A73 :100510001378A3B9A648012103601170302383F337 -:10052000118803680BB101F03FFAA24AA0480023EA -:100530004FF47A7101F02EFA002383F31188009BA7 +:10052000118803680BB101F05FFDA24AA0480023C7 +:100530004FF47A7101F04EFD002383F31188009B84 :1005400013B19D4B009A1A609C4A009C1378032BB0 :100550001EBF00231370984A4FF0000A18BF536063 -:10056000D3465646D146012000F064FB24B1924B9D -:100570001B68002B00F01182002000F06DFA039040 -:10058000039B002BF2DB012000F04AFB039B213B85 +:10056000D3465646D146012000F07AFB24B1924B87 +:100570001B68002B00F01182002000F07DFA039030 +:10058000039B002BF2DB012000F060FB039B213B6F :10059000162BE8D801A252F823F000BFF905000895 :1005A00021060008B5060008670500086705000871 :1005B000670500083F0700080F0900082908000820 @@ -96,799 +96,905 @@ :1005E00067050008A109000805060008990600082B :1005F000670500088B0800080220FFF7C7FE0028E7 :1006000040F0F581009B0221BAF1000F08BF1C46A3 -:1006100005A841F21233ADF8143000F03BFAA2E71E -:100620004FF47A7000F018FA071EEBDB0220FFF798 +:1006100005A841F21233ADF8143000F04BFAA2E70E +:100620004FF47A7000F028FA071EEBDB0220FFF788 :10063000ADFE0028E6D0013F052F00F2DA81DFE8A9 :1006400007F0030A0D10133605230593042105A8AE -:1006500000F020FA17E054480421F9E75848042133 +:1006500000F030FA17E054480421F9E75848042123 :10066000F6E758480421F3E74FF01C08404600F035 -:100670003DFA08F104080590042105A800F00AFAE3 +:1006700053FA08F104080590042105A800F01AFABD :10068000B8F12C0FF2D1012000FA07F747EA0B0B63 -:100690005FFA8BFB4FF0000900F062FB26B10BF014 +:100690005FFA8BFB4FF0000900F078FB26B10BF0FE :1006A0000B030B2B08BF0024FFF778FE5BE74648DF :1006B0000421CDE7002EA5D00BF00B030B2BA1D10D :1006C0000220FFF763FE074600289BD0012000F0C0 -:1006D0000BFA0220FFF7AAFE00261FFA86F8404612 -:1006E00000F012FA044690B10021404600F01CFAD6 +:1006D00021FA0220FFF7AAFE00261FFA86F84046FC +:1006E00000F028FA044690B10021404600F032FAAA :1006F00001360028F1D1BA46044641F21213022114 -:1007000005A8ADF814303E4600F0C4F92BE70120EF +:1007000005A8ADF814303E4600F0D4F92BE70120DF :10071000FFF78CFE2546244B9B68AB4207D9284641 -:1007200000F0E4F9013040F067810435F3E7234B32 +:1007200000F0FAF9013040F067810435F3E7234B1C :1007300000251D70204BBA465D603E46ACE7002E9A :100740003FF460AF0BF00B030B2B7FF45BAF022089 -:10075000FFF76CFE322000F07FF9B0F10008FFF6E1 +:10075000FFF76CFE322000F08FF9B0F10008FFF6D1 :1007600051AF18F003077FF44DAF0F4A926808EBC2 :10077000050393423FF646AFB8F5807F3FF742AF9F -:10078000124B0193B84523DD4FF47A7000F064F901 +:10078000124B0193B84523DD4FF47A7000F074F9F1 :100790000390039A002AFFF635AF019B039A03F8F2 -:1007A000012B0137EDE700BF002200205C23002071 -:1007B00040220020B50300086023002058220020BA -:1007C00004220020082200200C2200205C220020AD +:1007A000012B0137EDE700BF002200206C23002061 +:1007B00050220020B503000870230020682200208A +:1007C00004220020082200200C2200206C2200209D :1007D000C820FFF7DBFD074600283FF413AF1F2DAD :1007E00011D8C5F1200242450AAB25F0030028BF0D -:1007F000424683490192184400F040FA019A804829 -:10080000FF2100F061FA4FEAA8037D490193C8F384 -:100810008702284600F060FA064600283FF46DAFD4 +:1007F000424683490192184400F056FA019A804813 +:10080000FF2100F077FA4FEAA8037D490193C8F36E +:100810008702284600F076FA064600283FF46DAFBE :10082000019B05EB830537E70220FFF7AFFD0028AA -:100830003FF4E8AE00F0A4F900283FF4E3AE00274F +:100830003FF4E8AE00F0BAF900283FF4E3AE002739 :10084000B846704B9B68BB4218D91F2F11D80A9B22 :1008500001330ED027F0030312AA134453F8203CAF -:1008600005934046042205A900F0AEFA04378046FD -:10087000E7E7384600F03AF90590F2E7CDF8148042 -:10088000042105A800F006F906E70023642104A866 -:10089000049300F0F5F800287FF4B4AE0220FFF7CF -:1008A00075FD00283FF4AEAE049800F051F90590B4 -:1008B000E6E70023642104A8049300F0E1F800288F +:1008600005934046042205A900F0FAFA04378046B1 +:10087000E7E7384600F050F90590F2E7CDF814802C +:10088000042105A800F016F906E70023642104A856 +:10089000049300F005F900287FF4B4AE0220FFF7BE +:1008A00075FD00283FF4AEAE049800F067F905909E +:1008B000E6E70023642104A8049300F0F1F800287F :1008C0007FF4A0AE0220FFF761FD00283FF49AAE4E -:1008D000049800F04DF9EAE70220FFF757FD0028E1 -:1008E0003FF490AE00F05CF9E1E70220FFF74EFD27 -:1008F00000283FF487AE05A9142000F057F9042121 -:100900000746049004A800F0C5F83946B9E732203C -:1009100000F0A2F8071EFFF675AEBB077FF472AEBB +:1008D000049800F063F9EAE70220FFF757FD0028CB +:1008E0003FF490AE00F072F9E1E70220FFF74EFD11 +:1008F00000283FF487AE05A9142000F06DF904210B +:100900000746049004A800F0D5F83946B9E732202C +:1009100000F0B2F8071EFFF675AEBB077FF472AEAB :10092000384A926807EB090393423FF66BAE022008 :10093000FFF72CFD00283FF465AE27F003074F4476 -:10094000B9453FF4A9AE484600F0D0F8042105901F -:1009500005A800F09FF809F10409F1E74FF47A7057 -:10096000FFF714FD00283FF44DAE00F009F9002810 +:10094000B9453FF4A9AE484600F0E6F80421059009 +:1009500005A800F0AFF809F10409F1E74FF47A7047 +:10096000FFF714FD00283FF44DAE00F01FF90028FA :1009700044D00A9B01330BD008220AA9002000F0C2 -:10098000ABF900283AD02022FF210AA800F09CF9F8 -:10099000FFF704FD1C4800F041FF13B0BDE8F08FE5 +:10098000C1F900283AD02022FF210AA800F0B2F9CC +:10099000FFF704FD1C4801F061FA13B0BDE8F08FC9 :1009A000002E3FF42FAE0BF00B030B2B7FF42AAE7F -:1009B0000023642105A8059300F062F8074600288B +:1009B0000023642105A8059300F072F8074600287B :1009C0007FF420AE0220FFF7E1FC804600283FF4D0 -:1009D00019AEFFF7E3FC41F2883000F01FFF0598E5 -:1009E00000F0F0F9464600F0BBF93C46BBE5064690 +:1009D00019AEFFF7E3FC41F2883001F03FFA0598C9 +:1009E00000F01CFA464600F0D1F93C46BBE506464D :1009F00052E64FF0000905E6BA467EE637467CE649 -:100A00005C22002000220020A086010070B50F4B60 -:100A10001B780133DBB2012B0C4611D80C4D296831 -:100A20004FF47A730E6AA2FB03320146224628462F -:100A3000B047844204D1074B00221A70012070BDD8 -:100A40004FF4FA7000F0EAFE0020F8E710220020D0 -:100A5000082600209423002007B500230246012128 -:100A60000DF107008DF80730FFF7D0FF20B19DF89A -:100A7000070003B05DF804FB4FF0FF30F9E700001A -:100A80000A4608B50421FFF7C1FF80F00100C0B29B -:100A9000404208BD30B4054C2368DD69044B0A466A -:100AA000AC460146204630BC604700BF0826002007 -:100AB000A086010070B501F0D1F9094E094D3080D2 -:100AC000002428683388834208D901F0C1F92B68D3 -:100AD00004440133B4F5404F2B60F2D370BD00BF26 -:100AE000962300206823002001F066BA00F1006020 -:100AF00000F540400068704700F10060920000F58A -:100B0000404001F0F1B90000054B1A68054B1B8805 -:100B10009B1A834202D9104401F09AB90020704711 -:100B2000682300209623002038B5084D044629B1DB -:100B300028682044BDE8384001F0AAB9286820445C -:100B400001F08EF90028F3D038BD00BF68230020E3 -:100B500010F003030AD1B0F5047F05D200F1005074 -:100B6000A0F51040D0F80038184670470023FBE786 -:100B700000F10050A0F51040D0F8100A70470000B6 -:100B8000064991F8243033B10023086A81F82430F3 -:100B90000822FFF7B1BF0120704700BF6C2300207F -:100BA000014B1868704700BF002004E070B5194B76 -:100BB0001D68194B0138C5F30B0408442D0C0422A1 -:100BC0001E88A6420BD15C680A46013C824213464D -:100BD0000FD214F9016F4EB102F8016BF6E7013A3A -:100BE00003F10803ECD181420B4602D22C2203F818 -:100BF000012B0A4A05241688AE4204D1984284BFCC -:100C0000967803F8016B013C02F10402F3D1581A03 -:100C100070BD00BF002004E0943400088034000858 -:100C2000022802BF024B4FF000729A61704700BF6A -:100C300000000240022802BF024B4FF400729A618A -:100C4000704700BF00000240022801BF024A5369FA -:100C500083F40073536170470000024070B504468E -:100C60004FF47A764CB1412C254628BF412506FB2E -:100C700005F000F0D3FD641BF4E770BD10B5002350 -:100C8000934203D0CC5CC4540133F9E710BD00009B -:100C900010B5013810F9013F3BB191F900409C4279 -:100CA00003D11AB10131013AF4E71AB191F90020E8 -:100CB000981A10BD1046FCE703460246D01A12F9F6 -:100CC000011B0029FAD1704702440346934202D027 -:100CD00003F8011BFAE770472DE9F8431F4D14464E -:100CE00095F824200746884652BBDFF870909CB3E5 -:100CF00095F824302BB92022FF2148462F62FFF7B8 -:100D0000E3FF95F82400C0F10802A24228BF224662 -:100D1000D6B24146920005EB8000FFF7AFFF95F891 -:100D20002430A41B1E44F6B2082E17449044E4B2AB -:100D300085F82460DBD1FFF723FF0028D7D108E036 -:100D40002B6A03EB82038342CFD0FFF719FF002801 -:100D5000CBD10020BDE8F8830120FBE76C23002005 -:100D6000024B1A78024B1A70704700BF9423002080 -:100D70001022002010B5104C104800F0B5F82146A4 -:100D80000E4800F0DDF82468626DD2F8043843F0B4 -:100D90000203C2F804384FF47A70FFF75FFF084986 -:100DA000204600F0D3F9626DD2F8043823F0020334 -:100DB000C2F8043810BD00BF6035000808260020C6 -:100DC000683500087047000030B5094D0A4491426B -:100DD0000DD011F8013B5840082340F30004013BBB -:100DE0002C4013F0FF0384EA5000F6D1EFE730BD4A -:100DF0002083B8ED026843681143016003B11847CE -:100E00007047000013B5446BD4F894341A68117815 -:100E1000042915D1217C022912D1197912890123C3 -:100E20008B4013420CD101A904F14C0001F0F8FEF3 -:100E3000D4F89444019B21790246206800F0D0F94F -:100E400002B010BD143001F07BBE00004FF0FF3344 -:100E5000143001F075BE00004C3001F04DBF0000B1 -:100E60004FF0FF334C3001F047BF0000143001F069 -:100E700049BE00004FF0FF31143001F043BE0000C6 -:100E80004C3001F019BF00004FF0FF324C3001F040 -:100E900013BF00000020704710B5D0F894341A68D2 -:100EA00011780429044617D1017C022914D15979FB -:100EB000528901238B4013420ED1143001F0DCFD26 -:100EC000024648B1D4F894444FF4807361792068A5 -:100ED000BDE8104000F072B910BD0000406BFFF794 -:100EE000DBBF0000704700007FB5124B036000239A -:100EF0004360C0E90233012502260F4B0574044606 -:100F00000290019300F18402294600964FF4807309 -:100F1000143001F08DFD094B0294CDE9006304F516 -:100F200023724FF48073294604F14C0001F054FE03 -:100F300004B070BDB4340008DD0E0008050E0008D2 -:100F40000B68302282F311880A7903EB82029061E8 -:100F50004A79093243F822008A7912B103EB8203FD -:100F600098610223C0F894140374002080F3118860 -:100F70007047000038B5037F044613B190F8543031 -:100F8000ABB9201D01250221FFF734FF04F1140045 -:100F900025776FF0010100F069FC84F8545004F1EA -:100FA0004C006FF00101BDE8384000F05FBC38BD77 -:100FB00010B5012104460430FFF71CFF00232377FE -:100FC00084F8543010BD000038B5044600251430B4 -:100FD00001F046FD04F14C00257701F015FE201DBF -:100FE00084F854500121FFF705FF2046BDE8384042 -:100FF000FFF752BF90F8443003F06003202B07D175 -:1010000090F84520212A4FF0000303D81F2A06D864 -:1010100000207047222AFBD1C0E90E3303E0034AC7 -:1010200082630722C26303640120704711220020FB -:1010300037B5D0F894341A681178042904461AD1C7 -:10104000017C022917D11979128901238B4013429F -:1010500011D100F14C05284601F096FE58B101A9C6 -:10106000284601F0DDFDD4F89444019B2179024625 -:10107000206800F0B5F803B030BD0000F0B500EB1B -:10108000810385B09E6904460D46FEB1302383F38B -:10109000118804EB8507301D0821FFF7ABFEFB68C4 -:1010A0005B691B6806F14C001BB1019001F0C6FDA5 -:1010B000019803A901F0B4FD024648B1039B2946FB -:1010C000204600F08DF8002383F3118805B0F0BDB1 -:1010D000FB685A691268002AF5D01B8A013B13404D -:1010E000F1D104F14402EAE7093138B550F8214062 -:1010F000DCB1302383F31188D4F894241368527937 -:1011000003EB8203DB689B695D6845B104216018CD -:10111000FFF770FE294604F1140001F0B7FC2046E9 -:10112000FFF7BAFE002383F3118838BD7047000033 -:1011300001F016B8012303700023C0E90133C36135 -:1011400083620362C36243620363704738B5044637 -:10115000302383F311880025C0E90355C0E9055504 -:10116000416001F00DF80223237085F311882846B1 -:1011700038BD000070B500EB810305465069DA60A8 -:101180000E46144618B110220021FFF79DFDA069FC -:1011900018B110220021FFF797FD31462846BDE81F -:1011A000704001F0B7B80000826802F0011282605E -:1011B0000022C0E90422826101F038B9F0B400EBEA -:1011C00081044789E4680125A4698D403D43458138 -:1011D00023600023A2606360F0BC01F053B90000FB -:1011E000F0B400EB81040789E468012564698D404F -:1011F0003D43058123600023A2606360F0BC01F0E1 -:10120000CDB9000070B50223002504460370C0E983 -:101210000255C0E90455C564856180F8345001F079 -:1012200015F863681B6823B129462046BDE8704065 -:10123000184770BD0378052B10B504460AD080F816 -:1012400050300523037043681B680BB10421984795 -:101250000023A36010BD00000178052906D190F895 -:101260005020436802701B6803B1184770470000A4 -:1012700070B590F83430044613B1002380F8343050 -:1012800004F14402204601F0F3F863689B68B3B9A7 -:1012900094F8443013F0600535D00021204601F069 -:1012A00093FB0021204601F085FB63681B6813B1A6 -:1012B000062120469847062384F8343070BD204626 -:1012C00098470028E4D0B4F84A30E26B9A4288BFCD -:1012D000E36394F94430E56B002B4FF0300380F268 -:1012E0000381002D00F0F280092284F8342083F37A -:1012F00011880021D4E90E232046FFF771FF002357 -:1013000083F31188DAE794F8452003F07F0343EA7A -:10131000022340F20232934200F0C58021D8B3F597 -:10132000807F48D00DD8012B3FD0022B00F0938056 -:10133000002BB2D104F14C02A2630222E2632364C7 -:10134000C1E7B3F5817F00F09B80B3F5407FA4D166 -:1013500094F84630012BA0D1B4F84C3043F002038E -:1013600032E0B3F5006F4DD017D8B3F5A06F31D090 -:10137000A3F5C063012B90D8636894F846205E689B -:1013800094F84710B4F848302046B047002884D07D -:101390004368A3630368E3631AE0B3F5106F36D0C4 -:1013A00040F6024293427FF478AF5C4BA363022382 -:1013B000E3630023C3E794F84630012B7FF46DAF5D -:1013C000B4F84C3023F00203C4E90E55A4F84C30B5 -:1013D000256478E7B4F84430B3F5A06F0ED194F8E3 -:1013E000463084F84E30204600F088FF63681B6862 -:1013F00013B1012120469847032323700023C4E939 -:101400000E339CE704F14F03A3630123C3E7237862 -:10141000042B10D1302383F311882046FFF7C4FE3C -:1014200085F311880321636884F84F5021701B688D -:101430000BB12046984794F84630002BDED084F854 -:101440004F300423237063681B68002BD6D0022121 -:1014500020469847D2E794F848301D0603F00F0164 -:1014600020460AD500F0F6FF012804D002287FF4B8 -:1014700014AF2B4B9AE72B4B98E700F0DDFFF3E717 -:1014800094F84630002B7FF408AF94F8483013F0FE -:101490000F01B3D01A06204602D501F0A9FAADE734 -:1014A00001F09CFAAAE794F84630002B7FF4F5AEE1 -:1014B00094F8483013F00F01A0D01B06204602D547 -:1014C00001F082FA9AE701F075FA97E7142284F89E -:1014D000342083F311882B462A4629462046FFF7FD -:1014E0006DFE85F31188E9E65DB1152284F834209C -:1014F00083F311880021D4E90E232046FFF75EFE16 -:10150000FDE60B2284F8342083F311882B462A460B -:1015100029462046FFF764FEE3E700BFE4340008F5 -:10152000DC340008E034000838B590F83430044664 -:10153000002B3ED0063BDAB20F2A34D80F2B32D81C -:10154000DFE803F0373131082232313131313131C6 -:1015500031313737C56BB0F84A309D4214D2C36879 -:101560001B8AB5FBF3F203FB12556DB9302383F3ED -:1015700011882B462A462946FFF732FE85F311884B -:101580000A2384F834300EE0142384F834303023F6 -:1015900083F3118800231A4619462046FFF70EFEF2 -:1015A000002383F3118838BD036C03B198470023EF -:1015B000E7E70021204601F007FA0021204601F06C -:1015C000F9F963681B6813B1062120469847062382 -:1015D000D7E7000010B590F83430142B044629D01A -:1015E00017D8062B05D001D81BB110BD093B022B23 -:1015F000FBD80021204601F0E7F90021204601F048 -:10160000D9F963681B6813B1062120469847062361 -:1016100019E0152BE9D10B2380F83430302383F304 -:10162000118800231A461946FFF7DAFD002383F3D9 -:101630001188DAE7C3689B695B68002BD5D1036C1E -:1016400003B19847002384F83430CEE700230375B4 -:10165000826803691B6899689142FBD25A680360EB -:101660004260106058607047002303758268036908 -:101670001B6899689142FBD85A6803604260106009 -:101680005860704708B50846302383F311880B7DF6 -:10169000032B05D0042B0DD02BB983F3118808BD83 -:1016A0008B6900221A604FF0FF338361FFF7CEFF92 -:1016B0000023F2E7D1E9003213605A60F3E700003B -:1016C000FFF7C4BF054BD9680875186802681A602F -:1016D000536001220275D860FEF714BE98230020E3 -:1016E00030B50C4BDD684B1C87B004460FD02B4641 -:1016F000094A684600F04EF92046FFF7E3FF009BD9 -:1017000013B1684600F050F9A86907B030BDFFF783 -:10171000D9FFF9E79823002085160008044B1A68C2 -:10172000DB6890689B68984294BF00200120704756 -:1017300098230020084B10B51C68D86822681A60EE -:10174000536001222275DC60FFF78EFF01462046C0 -:10175000BDE81040FEF7D6BD9823002038B5074CF1 -:1017600007490848012300252370656001F044FB08 -:101770000223237085F3118838BD00BF00260020A6 -:10178000EC3400089823002000F044B9034A516863 -:1017900053685B1A9842FBD8704700BF001000E006 -:1017A0008B60022308618B82084670478368A3F12F -:1017B000840243F8142C026943F8442C426943F82C -:1017C000402C094A43F8242CC26843F8182C022202 -:1017D00003F80C2C002203F80B2C044A43F8102CBD -:1017E000A3F12000704700BF1D03000898230020CC -:1017F00008B5FFF7DBFFBDE80840FFF761BF000059 -:10180000024BDB6898610F20FFF75CBF9823002034 -:10181000302383F31188FFF7F3BF000008B50146BA -:10182000302383F311880820FFF75AFF002383F346 -:10183000118808BD064BDB6839B1426818605A60F0 -:10184000136043600420FFF74BBF4FF0FF30704739 -:10185000982300200368984206D01A6802605060FE -:1018600099611846FFF72CBF7047000038B5044651 -:101870000D462068844200D138BD036823605C6057 -:101880008561FFF71DFFF4E710B503689C68A2426D -:101890000CD85C688A600B604C6021605960996864 -:1018A0008A1A9A604FF0FF33836010BD1B68121BC9 -:1018B000ECE700000A2938BF0A2170B504460D463E -:1018C0000A26601901F092FA01F07EFA041BA54283 -:1018D00003D8751C2E460446F3E70A2E04D9BDE84A -:1018E0007040012001F0C8BA70BD0000F8B5144B7B -:1018F0000D46D96103F1100141600A2A196982601D -:1019000038BF0A22016048601861A818144601F027 -:101910005FFA0A2701F058FA431BA342064606D392 -:101920007C1C281901F062FA27463546F2E70A2F97 -:1019300004D9BDE8F840012001F09EBAF8BD00BF0F -:1019400098230020F8B506460D4601F03DFA0F4AEF -:10195000134653F8107F9F4206D12A46014630466F -:10196000BDE8F840FFF7C2BFD169BB68441A2C1923 -:1019700028BF2C46A34202D92946FFF79BFF2246E7 -:1019800031460348BDE8F840FFF77EBF98230020AA -:10199000A823002010B4C0E9032300235DF8044B02 -:1019A0004361FFF7CFBF000010B5194C236998427F -:1019B0000DD0D0E90032816813605A609A680A44F9 -:1019C0009A60002303604FF0FF33A36110BD2346EC -:1019D000026843F8102F53600022026022699A4285 -:1019E00003D1BDE8104001F0FBB9936881680B4456 -:1019F000936001F0E9F92269E1699268441AA24210 -:101A0000E4D91144BDE81040091AFFF753BF00BFE5 -:101A1000982300202DE9F047DFF8BC8008F110077B -:101A20002C4ED8F8105001F0CFF9D8F81C40AA6815 -:101A3000031B9A423ED81444D5E900324FF0000906 -:101A4000C8F81C4013605A60C5F80090D8F81030F0 -:101A5000B34201D101F0C4F989F31188D5E903310A -:101A600028469847302383F311886B69002BD8D020 -:101A700001F0AAF96A69A0EB04094A4582460DD231 -:101A8000022001F0F9F90022D8F81030B34208D151 -:101A900051462846BDE8F047FFF728BF121A2244F6 -:101AA000F2E712EB090938BF4A4629463846FFF7E4 -:101AB000EBFEB5E7D8F81030B34208D01444211A31 -:101AC000C8F81C00A960BDE8F047FFF7F3BEBDE809 -:101AD000F08700BFA8230020982300200020704733 -:101AE000FEE70000704700004FF0FF307047000035 -:101AF00002290CD0032904D00129074818BF00206F -:101B00007047032A05D8054800EBC2007047044817 -:101B100070470020704700BFC43500082022002015 -:101B20007835000870B59AB00546084601A91446F4 -:101B300000F0C2F801A8FFF7BFF8431C5B00C5E93D -:101B400000340022237003236370C6B201AB023459 -:101B50001046D1B28E4204F1020401D81AB070BD11 -:101B600013F8011B04F8021C04F8010C0132F0E721 -:101B700008B5302383F311880348FFF759FA00238F -:101B800083F3118808BD00BF0826002090F8443078 -:101B900003F01F02012A07D190F845200B2A03D138 -:101BA0000023C0E90E3315E003F06003202B08D1B9 -:101BB000B0F848302BB990F84520212A03D81F2AC5 -:101BC00004D8FFF717BA222AEBD0FAE7034A826358 -:101BD0000722C26303640120704700BF182200205F -:101BE00007B5052917D8DFE801F0191603191920E0 -:101BF000302383F31188104A01900121FFF7BAFACC -:101C000001980E4A0221FFF7B5FA0D48FFF7DCF9FB -:101C1000002383F3118803B05DF804FB302383F3C2 -:101C200011880748FFF7A6F9F2E7302383F31188FC -:101C30000348FFF7BDF9EBE7183500083C3500080D -:101C40000826002038B50C4D0C4C0D492A4604F1ED -:101C50000800FFF767FF05F1CA0204F11000094907 -:101C6000FFF760FF05F5CA7204F118000649BDE8E8 -:101C70003840FFF757BF00BFD02A002020220020A5 -:101C8000F8340008023500080D35000870B5044628 -:101C900008460D46FFF710F8C6B220460134037817 -:101CA0000BB9184670BD32462946FEF7F1FF0028F1 -:101CB000F3D10120F6E700002DE9F84F05460C4668 -:101CC000FEF7FAFF2B49C6B22846FFF7DFFF08B13F -:101CD0000536F6B228492846FFF7D8FF08B1103676 -:101CE000F6B2632E0DD8DFF88C80DFF88C90234F8E -:101CF000DFF890A0DFF890B02E7846B92670BDE8E6 -:101D0000F88F29462046BDE8F84F01F09BBB252EF1 -:101D10002BD1072241462846FEF7BAFF58B9DBF817 -:101D200000302360DBF804306360DBF80830A36028 -:101D300007350C34E0E7082249462846FEF7A8FF9D -:101D400098B90F4BA21C197809090232C95D02F833 -:101D5000041C13F8011B01F00F015345C95D02F883 -:101D6000031CF0D118340835C6E704F8016B0135BF -:101D7000C2E700BFE43500080D350008F93500085A -:101D8000107AFF1F1C7AFF1FEC350008BFF34F8F3E -:101D9000024AD368DB03FCD4704700BF003C02401A -:101DA00008B5094B1B7873B9FFF7F0FF074B1A69A9 -:101DB000002ABFBF064A5A6002F188325A601A6888 -:101DC00022F480621A6008BD2E2D0020003C0240E3 -:101DD0002301674508B50B4B1B7893B9FFF7D6FF76 -:101DE000094B1A6942F000421A611A6842F48052A3 -:101DF0001A601A6822F480521A601A6842F48062EB -:101E00001A6008BD2E2D0020003C02400B28F0B5C2 -:101E100016D80C4C0C4923787BB90C4D0E460C237C -:101E20004FF0006255F8047B46F8042B013B13F099 -:101E3000FF033A44F6D10123237051F82000F0BD8E -:101E40000020FCE7602D0020302D00200C3600081B -:101E5000014B53F8200070470C3600080C207047E7 -:101E60000B2810B5044601D9002010BDFFF7CEFFA6 -:101E7000064B53F824301844C21A0BB90120F4E77A -:101E800012680132F0D1043BF6E700BF0C360008BF -:101E90000B2810B5044621D8FFF778FFFFF780FF25 -:101EA0000F4AF323D360C300DBB243F4007343F063 -:101EB00002031361136943F480331361FFF766FF74 -:101EC000FFF7A4FF074B53F8241000F0D9F8FFF7F1 -:101ED00081FF2046BDE81040FFF7C2BF002010BDC3 -:101EE000003C02400C360008F8B512F0010314461D -:101EF00042D18218B2F1016F57D82D4B1B6813F0F5 -:101F0000010352D02B4DFFF74BFFF323EB60FFF79C -:101F10003DFF40F20127032C15D824F00104661878 -:101F2000244C401A40F20117B142236900EB01052D -:101F300024D123F001032361FFF74CFF0120F8BDFA -:101F4000043C0430E7E78307E7D12B6923F44073AF -:101F50002B612B693B432B6151F8046B0660BFF387 -:101F60004F8FFFF713FF03689E42E9D02B6923F0E0 -:101F700001032B61FFF72EFF0020E0E723F44073FD -:101F8000236123693B4323610B882B80BFF34F8F71 -:101F9000FFF7FCFE2D8831F8023BADB2AB42C3D057 -:101FA000236923F001032361E4E71846C7E700BF74 -:101FB00000380240003C0240084908B50B7828B1BF -:101FC0001BB9FFF7EDFE01230B7008BD002BFCD001 -:101FD000BDE808400870FFF7FDBE00BF2E2D0020B1 -:101FE00010B50244064BD2B2904200D110BD441C41 -:101FF00000B253F8200041F8040BE0B2F4E700BF50 -:10200000502800400F4B30B51C6F240407D41C6FC0 -:1020100044F400741C671C6F44F400441C670A4CB1 -:10202000236843F4807323600244084BD2B2904289 -:1020300000D130BD441C00B251F8045B43F820507D -:10204000E0B2F4E700380240007000405028004041 -:1020500007B5012201A90020FFF7C2FF019803B0D4 -:102060005DF804FB13B50446FFF7F2FFA04205D06C -:10207000012201A900200194FFF7C4FF02B010BDA6 -:1020800070470000034B1A681AB9034AD2F8742843 -:102090001A607047642D00200030024008B5FFF739 -:1020A000F1FF024B1868C0F3407008BD642D00209A -:1020B00070470000FEE700000A4B0B480B4A9042B5 -:1020C0000BD30B4BDA1C121AC11E22F003028B42F7 -:1020D00038BF00220021FEF7F7BD53F8041B40F87B -:1020E000041BECE7B8370008602E0020602E0020AB -:1020F000602E002070B5D0E915439E6800224FF095 -:10210000FF3504EB42135101D3F800090028BEBF8C -:10211000D3F8000940F08040C3F80009D3F8000B61 -:102120000028BEBFD3F8000B40F08040C3F8000B7E -:10213000013263189642C3F80859C3F8085BE0D22D -:102140004FF00113C4F81C3870BD0000890141F044 -:102150002001016103699B06FCD41220FFF716BB26 -:1021600010B5054C2046FEF7E5FF4FF0A043636530 -:10217000024BA36510BD00BF682D0020603600082B -:1021800070B50378012B054650D12A4B446D984217 -:102190001BD1294B5A6B42F080025A635A6D42F0B0 -:1021A00080025A655A6D5A6942F080025A615A6932 -:1021B00022F080025A610E2143205B6900F022FC6C -:1021C0001E4BE3601E4BC4F800380023C4F8003EE9 -:1021D000C02323606E6D4FF40413A3633369002B97 -:1021E000FCDA012333610C20FFF7D0FA3369DB07F7 -:1021F000FCD41220FFF7CAFA3369002BFCDA002660 -:10220000A6602846FFF776FF6B68C4F81068DB68A5 -:10221000C4F81468C4F81C684BB90A4BA3614FF0AA -:10222000FF336361A36843F00103A36070BD064BF5 -:10223000F4E700BF682D0020003802404014004041 -:1022400003002002003C30C0083C30C0F8B5446DAB -:10225000054600212046FFF779FFA96D00234FF0C6 -:1022600001128F68C4F834384FF00066C4F81C2897 -:102270004FF0FF3004EB431201339F42C2F8006974 -:10228000C2F8006BC2F80809C2F8080BF2D20B685A -:102290006A6DEB65636210231361166916F0100610 -:1022A000FBD11220FFF772FAD4F8003823F4FE6352 -:1022B000C4F80038A36943F4402343F01003A3613A -:1022C0000923C4F81038C4F814380A4BEB604FF0F7 -:1022D000C043C4F8103B084BC4F8003BC4F8106975 -:1022E000C4F80039EB6D03F1100243F48013EA6582 -:1022F000A362F8BD3C36000840800010426D90F8A3 -:102300004E10D2F8003823F4FE6343EA0113C2F8FA -:10231000003870472DE9F84300EB8103456DDA681A -:10232000166806F00306731E022B05EB41130C46DC -:1023300080460FFA81F94FEA41104FF00001C3F8CF -:10234000101B4FF0010104F1100398BFB60401FA0D -:1023500003F391698EBF334E06F1805606F50046B1 -:1023600000293AD0578A04F15801490137436F5088 -:10237000D5F81C180B43C5F81C382B180021C3F8DE -:10238000101953690127611EA7409BB3138A928BD2 -:102390009B08012A88BF5343D8F85C20981842EA6A -:1023A000034301F1400205EB8202C8F85C002146BC -:1023B00053602846FFF7CAFE08EB8900C3681B8AF2 -:1023C00043EA8453483464011E432E51D5F81C3827 -:1023D0001F43C5F81C78BDE8F88305EB4917D7F80B -:1023E000001B21F40041C7F8001BD5F81C1821EA96 -:1023F0000303C0E704F13F0305EB83030A4A5A6075 -:1024000028462146FFF7A2FE05EB4910D0F8003917 -:1024100023F40043C0F80039D5F81C3823EA070735 -:10242000D7E700BF0080001000040002826D126830 -:10243000C265FFF75FBE00005831436D49015B582C -:1024400013F4004004D013F4001F0CBF022001203D -:10245000704700004831436D49015B5813F4004058 -:1024600004D013F4001F0CBF0220012070470000AD -:1024700000EB8101CB68196A0B6813604B685360ED -:102480007047000000EB810330B5DD68AA6913686E -:10249000D36019B9402B84BF402313606B8A146842 -:1024A000426D1C44013CB4FBF3F46343033323F05B -:1024B000030302EB411043EAC44343F0C043C0F8B6 -:1024C000103B2B6803F00303012B09B20ED1D2F8A5 -:1024D000083802EB411013F4807FD0F8003B14BFA2 -:1024E00043F0805343F00053C0F8003B02EB41122D -:1024F000D2F8003B43F00443C2F8003B30BD00007B -:102500002DE9F041244D6E6D06EB40130446D3F8DF -:10251000087BC3F8087B38070AD5D6F814381907A2 -:1025200006D505EB84032146DB6828465B6898479F -:10253000FA071FD5D6F81438DB071BD505EB840343 -:10254000D968CCB98B69488A5A68B2FBF0F600FBAF -:1025500016228AB91868DA6890420DD2121AC3E9B5 -:102560000024302383F311880B482146FFF78AFFAC -:1025700084F31188BDE8F081012303FA04F26B892A -:1025800023EA02036B81CB68002BF3D0214602487B -:10259000BDE8F041184700BF682D002000EB810323 -:1025A00070B5DD68436D6C692668E6604A0156BB0C -:1025B0001A444FF40020C2F810092A6802F00302FE -:1025C000012A0AB20ED1D3F8080803EB421410F422 -:1025D000807FD4F8000914BF40F0805040F00050D4 -:1025E000C4F8000903EB4212D2F8000940F004409D -:1025F000C2F80009D3F83408012202FA01F10143BC -:10260000C3F8341870BD19B9402E84BF4020206033 -:1026100020682E8A8419013CB4FBF6F440EAC440D9 -:1026200040F000501A44C6E72DE9F8433B4D6E6D6B -:1026300006EB40130446D3F80889C3F8088918F05C -:10264000010F4FEA40171AD0D6F81038DB0716D51D -:1026500005EB8003D9684B691868DA68904230D27C -:10266000121A4FF000091A60C3F80490302383F364 -:10267000118821462846FFF791FF89F3118818F049 -:10268000800F1CD0D6F834380126A640334216D02D -:1026900005EB84036D6DD3F80CC0DCF81420013415 -:1026A000E4B2D2F800E005EB04342F4451687145E0 -:1026B00015D3D5F8343823EA0606C5F83468BDE8E2 -:1026C000F883012303FA04F22B8923EA02032B8106 -:1026D0008B68002BD3D0214628469847CFE7BCF81B -:1026E0001000AEEB0103834228BF0346D7F8180958 -:1026F00080B2B3EB800FE2D89068A0F1040959F8DA -:10270000048FC4F80080A0EB09089844B8F1040FC6 -:10271000F5D818440B4490605360C7E7682D00203B -:102720002DE9F74FA24C656D6E69AB691E4016F43A -:1027300080586E6107D02046FEF764FD03B0BDE807 -:10274000F04F00F047BC002E12DAD5F8003E984852 -:102750009B071EBFD5F8003E23F00303C5F8003EDB -:10276000D5F8043823F00103C5F80438FEF774FDEA -:10277000370505D58E48FFF7BDFC8D48FEF75AFD9D -:10278000B0040CD5D5F8083813F0060FEB6823F425 -:1027900070530CBF43F4105343F4A053EB60310764 -:1027A0001BD56368DB681BB9AB6923F00803AB6119 -:1027B0002378052B0CD1D5F8003E7D489A071EBF23 -:1027C000D5F8003E23F00303C5F8003EFEF744FDB4 -:1027D0006368DB680BB176489847F30274D4B7029C -:1027E00027D5D4F85490DFF8C8B100274FF0010A7C -:1027F00009EB4712D2F8003B03F44023B3F5802FD6 -:1028000011D1D2F8003B002B0DDA62890AFA07F3E6 -:1028100022EA0303638104EB8703DB68DB6813B1FF -:10282000394658469847A36D01379B68FFB29F42CF -:10283000DED9F00617D5676D3A6AC2F30A1002F0C6 -:102840000F0302F4F012B2F5802F00F08580B2F58C -:10285000402F08D104EB83030022DB681B6A07F5D5 -:10286000805790426AD13003D5F8184813D5E10358 -:1028700002D50020FFF744FEA20302D50120FFF796 -:102880003FFE630302D50220FFF73AFE270302D57D -:102890000320FFF735FE75037FF550AFE00702D543 -:1028A0000020FFF7C1FEA10702D50120FFF7BCFE03 -:1028B000620702D50220FFF7B7FE23077FF53EAF80 -:1028C0000320FFF7B1FE39E7636DDFF8E4A0019361 -:1028D00000274FF00109A36D9B685FFA87FB9B45BA -:1028E0003FF67DAF019B03EB4B13D3F8001901F4C6 -:1028F0004021B1F5802F1FD1D3F8001900291BDA30 -:10290000D3F8001941F09041C3F80019D3F8001929 -:102910000029FBDB5946606DFFF718FC218909FA95 -:102920000BF321EA0303238104EB8B03DB689B6831 -:1029300013B15946504698470137CCE7910708BF75 -:10294000D7F80080072A98BF03F8018B02F1010233 -:1029500098BF4FEA182884E7023304EB830207F597 -:1029600080575268D2F818C0DCF80820DCE9001C57 -:10297000A1EB0C0C002188420AD104EB83046368AC -:102980009B699A6802449A605A6802445A606AE7EE -:1029900011F0030F08BFD7F800808C4588BF02F8FC -:1029A000018B01F1010188BF4FEA1828E3E700BF5E -:1029B000682D0020436D03EB4111D1F8003B43F437 -:1029C0000013C1F8003B7047436D03EB4111D1F890 -:1029D000003943F40013C1F800397047436D03EB2D -:1029E0004111D1F8003B23F40013C1F8003B7047BC -:1029F000436D03EB4111D1F8003923F40013C1F802 -:102A00000039704700F1604303F561430901C9B221 -:102A100083F80013012200F01F039A4043099B0032 -:102A200003F1604303F56143C3F880211A607047E6 -:102A300030B5039C0172043304FB0325C0E906533F -:102A4000049B03630021059BC160C0E90000C0E94D -:102A50000422C0E90842C0E90A11436330BD000006 -:102A6000416A0022C0E90411C0E90A22C2606FF085 -:102A70000101FEF7FBBE0000D0E90432934201D110 -:102A8000C2680AB9181D70470020704703691960B1 -:102A9000C2680132C260C269134482690361934211 -:102AA00024BF436A03610021FEF7D4BE38B5044653 -:102AB0000D46E3683BB16269131D1268A3621344BB -:102AC000E362002007E0237A33B929462046FEF767 -:102AD000B1FE0028EDDA38BD6FF00100FBE7000021 -:102AE000C368C269013BC36043691344826943619F -:102AF000934224BF436A436100238362036B03B1A3 -:102B00001847704770B53023044683F31188866AEE -:102B10003EB9FFF7CBFF054618B186F3118828466A -:102B200070BDA36AE26A13F8015BA362934202D309 -:102B30002046FFF7D5FF002383F31188EFE700005D -:102B40002DE9F84F04460E46174698464FF03009D7 -:102B500089F311880025AA46D4F828B0BBF1000FEC -:102B600009D141462046FFF7A1FF20B18BF3118820 -:102B70002846BDE8F88FD4E90A12A7EB050B521AD4 -:102B8000934528BF9346BBF1400F1BD9334601F153 -:102B9000400251F8040B43F8040B9142F9D1A36AA7 -:102BA00040334036A3624035D4E90A239A4202D327 -:102BB0002046FFF795FF8AF31188BD42D8D289F3EA -:102BC0001188C9E730465A46FEF758F8A36A5B44B5 -:102BD0005E44A3625D44E7E710B5029C01720433D2 -:102BE00003FB0421C0E906130023C0E90A33039B59 -:102BF0000363049BC460C0E90000C0E90422C0E98B -:102C00000842436310BD0000026AC260426AC0E924 -:102C100004220022C0E90A226FF00101FEF726BE5D -:102C2000D0E904239A4201D1C26822B9184650F86B -:102C3000043B0B60704700231846FAE7C368C2697B -:102C40000133C3604369134482694361934224BFE3 -:102C5000436A43610021FEF7FDBD000038B504461C -:102C60000D46E3683BB123691A1DA262E269134471 -:102C7000E362002007E0237A33B929462046FEF7B5 -:102C8000D9FD0028EDDA38BD6FF00100FBE7000048 -:102C900003691960C268013AC260C269134482695B -:102CA0000361934224BF436A036100238362036B81 -:102CB00003B118477047000070B530230D46044635 -:102CC000114683F31188866A2EB9FFF7C7FF10B14A -:102CD00086F3118870BDA36A1D70A36AE26A01338E -:102CE0009342A36204D3E16920460439FFF7D0FF81 -:102CF000002080F31188EDE72DE9F84F04460D46DA -:102D0000904699464FF0300A8AF311880026B34660 -:102D1000A76A4FB949462046FFF7A0FF20B187F3C5 -:102D200011883046BDE8F88FD4E90A073A1AA8EBB3 -:102D30000607974228BF1746402F1BD905F14003CD -:102D400055F8042B40F8042B9D42F9D1A36A403377 -:102D5000A3624036D4E90A239A4204D3E1692046AB -:102D60000439FFF795FF8BF311884645D9D28AF3D2 -:102D70001188CDE729463A46FDF780FFA36A3B4418 -:102D80003D44A3623E44E5E7D0E904239A4217D1CB -:102D9000C3689BB1836A8BB1043B9B1A0ED013604E -:102DA000C368013BC360C3691A44836902619A42E4 -:102DB00024BF436A036100238362012318467047DE -:102DC0000023FBE700F030B94FF08043586A7047AA -:102DD0004FF08043002258631A610222DA60704784 -:102DE0004FF080430022DA60704700004FF08043CC -:102DF00058637047FEE7000070B51B4B0163002568 -:102E0000044686B0586085620E4600F0BFF804F1B3 -:102E10001003C4E904334FF0FF33C4E90635C4E9B5 -:102E20000044A560E562FFF7CFFF2B460246C4E9E8 -:102E3000082304F134010D4A256580232046FEF75E -:102E4000AFFC0123E0600A4A0375009272680192A8 -:102E5000B268CDE90223074B6846CDE90435FEF799 -:102E6000C7FC06B070BD00BF002600206C3600080D -:102E700071360008F52D0008024AD36A1843D06263 -:102E8000704700BF982300204B6843608B688360C5 -:102E9000CB68C3600B6943614B6903628B69436212 -:102EA0000B6803607047000008B5264B26481A6976 -:102EB00040F2FF110A431A611A6922F4FF7222F0EC -:102EC00001021A611A691A6B0A431A631A6D0A43DE -:102ED0001A651E4A1B6D1146FFF7D6FF02F11C0151 -:102EE00000F58060FFF7D0FF02F1380100F5806047 -:102EF000FFF7CAFF02F1540100F58060FFF7C4FF3D -:102F000002F1700100F58060FFF7BEFF02F18C0155 -:102F100000F58060FFF7B8FF02F1A80100F58060BE -:102F2000FFF7B2FF02F1C40100F58060FFF7ACFFCC -:102F300002F1E00100F58060FFF7A6FFBDE8084060 -:102F400000F0EEB800380240000002407836000879 -:102F500008B500F059FAFEF701FCFFF793F8BDE859 -:102F60000840FEF76FBE000070470000EFF30983D2 -:102F700005494A6B22F001024A63683383F30988EA -:102F8000002383F31188704700EF00E0302080F3C6 -:102F9000118862B60C4B0D4AD96821F4E06109042E -:102FA000090C0A43DA60D3F8FC20094942F0807228 -:102FB000C3F8FC200A6842F001020A602022DA7796 -:102FC00083F82200704700BF00ED00E00003FA051F -:102FD000001000E010B5302383F311880E4B5B68BE -:102FE00013F4006314D0F1EE103AEFF30984683C57 -:102FF0004FF08073E361094BDB6B236684F3098830 -:10300000FEF78CFB10B1064BA36110BD054BFBE72F -:1030100083F31188F9E700BF00ED00E000EF00E066 -:103020002F030008320300080F4B1A6C42F0010214 -:103030001A641A6E42F001021A660C4A1B6E9368FB -:1030400043F0010393604FF0804353229A624FF0A4 -:10305000FF32DA6200229A615A63DA605A60012212 -:103060005A611A60704700BF00380240002004E037 -:103070004FF0804208B51169D3680B40D9B2C943FB -:103080009B07116107D5302383F31188FEF77CFB82 -:10309000002383F3118808BD1F4B1A696FEAC252DF -:1030A0006FEAD2521A611A69C2F308021A614FF02C -:1030B000FF301A695A69586100215A6959615A6981 -:1030C0001A6A62F080521A621A6A02F080521A6218 -:1030D0001A6A5A6A58625A6A59625A6A1A6C42F0F3 -:1030E00080521A641A6E42F080521A661A6E0B4AA7 -:1030F000106840F480701060186F00F44070B0F5F4 -:10310000007F1EBF4FF4803018671967536823F49F -:103110000073536000F054B9003802400070004062 -:10312000334B4FF080521A64324A4FF440411160E1 -:103130001A6842F001021A601A689107FCD59A6871 -:1031400022F003029A602A4B9A6812F00C02FBD11B -:10315000196801F0F90119609A601A6842F4803226 -:103160001A601A689203FCD55A6F42F001025A673E -:103170001F4B5A6F9007FCD51F4A5A601A6842F0DD -:1031800080721A601B4A53685904FCD5184B1A68A0 -:103190009201FCD5194A9A60194B1A68194B9A4248 -:1031A000194B21D1194A1168194A91421CD140F298 -:1031B00005121A60144A136803F00F03052BFAD1A5 -:1031C0000B4B9A6842F002029A609A6802F00C0275 -:1031D000082AFAD15A6C42F480425A645A6E42F478 -:1031E00080425A665B6E704740F20572E1E700BFAD -:1031F00000380240007000400854400700948838AE -:10320000002004E011640020003C024000ED00E0DA -:1032100041C20F41074A08B5536903F001035361E6 -:1032200023B1054A13680BB150689847BDE80840C0 -:10323000FFF7D0BE003C0140E02D0020074A08B552 -:10324000536903F00203536123B1054A93680BB13C -:10325000D0689847BDE80840FFF7BCBE003C01407D -:10326000E02D0020074A08B5536903F004035361B9 -:1032700023B1054A13690BB150699847BDE808406E -:10328000FFF7A8BE003C0140E02D0020074A08B52A -:10329000536903F00803536123B1054A93690BB1E5 -:1032A000D0699847BDE80840FFF794BE003C014054 -:1032B000E02D0020074A08B5536903F0100353615D -:1032C00023B1054A136A0BB1506A9847BDE808401C -:1032D000FFF780BE003C0140E02D0020164B10B5EA -:1032E0005C6904F478725A61A30604D5134A936AA0 -:1032F0000BB1D06A9847600604D5104A136B0BB126 -:10330000506B9847210604D50C4A936B0BB1D06BD8 -:103310009847E20504D5094A136C0BB1506C9847E5 -:10332000A30504D5054A936C0BB1D06C9847BDE852 -:103330001040FFF74FBE00BF003C0140E02D0020D1 -:10334000194B10B55C6904F47C425A61620504D5DE -:10335000164A136D0BB1506D9847230504D5134AD7 -:10336000936D0BB1D06D9847E00404D50F4A136EEE -:103370000BB1506E9847A10404D50C4A936E0BB163 -:10338000D06E9847620404D5084A136F0BB1506F92 -:103390009847230404D5054A936F0BB1D06F984723 -:1033A000BDE81040FFF716BE003C0140E02D0020B4 -:1033B00008B5FFF75DFEBDE80840FFF70BBE000053 -:1033C000062108B50846FFF71DFB06210720FFF779 -:1033D00019FB06210820FFF715FB06210920FFF73E -:1033E00011FB06210A20FFF70DFB06211720FFF72E -:1033F00009FB06212820FFF705FBBDE8084007214F -:103400001C20FFF7FFBA000008B5FFF745FE00F0EB -:103410000BF8FDF78DFEFDF765FDFFF7A5FDBDE897 -:103420000840FFF7CFBC00000023054A19460133CE -:10343000102BC2E9001102F10802F8D1704700BF59 -:10344000E02D0020034611F8012B03F8012B002A80 -:10345000F9D1704753544D3332463F3F3F005354E8 -:103460004D3332463430780053544D333246343283 -:10347000780053544D3332463434365858000000E7 -:10348000012033000010410001105A0003105900C0 -:10349000071031000000000054340008130400003D -:1034A0005E3400081904000068340008210400009C -:1034B0007234000800000000610E00084D0E000884 -:1034C000890E0008750E0008810E00086D0E0008B8 -:1034D000590E0008450E0008950E00080000000077 -:1034E000010000000000000063300000E834000824 -:1034F000F0230020002600204172647550696C6F33 -:10350000740025424F415244252D424C002553451D -:103510005249414C2500000002000000000000005C -:103520007D100008E910000840004000A02A00209B -:10353000B02A00200200000000000000030000008C -:10354000000000002D110008000000001000000025 -:10355000C02A002000000000010000000000000060 -:10356000682D002001010200E11B0008F11A00088B -:103570008D1B0008711B0008430000008035000807 -:1035800009024300020100C03209040000010202E6 -:103590000100052400100105240100010424020299 -:1035A0000524060001070582030800FF0904010045 -:1035B000020A000000070501024000000705810221 -:1035C0004000000012000000CC350008120110017C -:1035D00002000040091241570002010203010000ED -:1035E0000403090425424F41524425004A48454DF1 -:1035F0005F4A484546343035003031323334353651 -:10360000373839414243444546000000004000003D -:1036100000400000004000000040000000000100E9 -:103620000000020000000200000002000000020092 -:103630000000020000000200000002000000000084 -:103640007112000829150008D51500084000400037 -:10365000C82D0020C82D002001000000D82D00201A -:103660008000000040010000030000006D61696EF1 -:103670000069646C650000000000842A00000000FE -:10368000AAAAAAAA00000024FFFD00000000000072 -:1036900000A00A004000001100000000AAAAAAAA87 -:1036A00040000011FFFF00000000000000000000CB -:1036B0000000000000000000AAAAAAAA0000000062 -:1036C000FFFF0000000000000000000000000000FC -:1036D00000000000AAAAAAAA00000000FFFF000044 -:1036E00000000000000000000000000000000000DA -:1036F000AAAAAAAA00000000FFFF00000000000024 -:10370000000000000000000000000000AAAAAAAA11 -:1037100000000000FFFF00000000000000000000AB -:103720000000000000000000AAAAAAAA00000000F1 -:10373000FFFF00000000000000000000000000008B -:10374000000000000A00000000000000030000006C -:103750000000000000000000000000000000000069 -:103760000000000000000000000000000000000059 -:10377000000000000000000039040000000000000C -:1037800000400F0000000000FF009600000000084D -:10379000009600000000080004000000E03500086A -:1037A0000000000000000000000000000000000019 -:0837B000000000000000000011 +:100A00006C22002000220020A08601002DE9F84F72 +:100A10004FF47A73DFF85880DFF8589006460D4699 +:100A200002FB03F7002498F900305A1C5FFA84FA9D +:100A300001D0A34212D159F8240003682A46D3F802 +:100A400020B031463B46D847854207D1074B0120AD +:100A500083F800A0BDE8F88F0124E4E7002CFBD068 +:100A60004FF4FA7001F0FAF90020F3E7B823002000 +:100A7000102200201422002007B500230246012185 +:100A80000DF107008DF80730FFF7C0FF20B19DF88A +:100A9000070003B05DF804FB4FF0FF30F9E70000FA +:100AA0000A4608B50421FFF7B1FF80F00100C0B28B +:100AB000404208BD30B4074B0A461978064B53F83C +:100AC00021402368DD69054B0146AC46204630BC19 +:100AD000604700BFB823002014220020A086010038 +:100AE00070B501F0DBFC094E094D30800024286808 +:100AF0003388834208D901F0CBFC2B6804440133CE +:100B0000B4F5404F2B60F2D370BD00BFBA23002074 +:100B10007823002001F070BD00F1006000F5404036 +:100B20000068704700F10060920000F5404001F05D +:100B3000FBBC0000054B1A68054B1B889B1A8342BF +:100B400002D9104401F0A4BC002070477823002093 +:100B5000BA23002038B5084D044629B1286820443E +:100B6000BDE8384001F0B4BC2868204401F098FC8E +:100B70000028F3D038BD00BF7823002010F0030315 +:100B80000AD1B0F5047F05D200F10050A0F5104065 +:100B9000D0F80038184670470023FBE700F10050FA +:100BA000A0F51040D0F8100A70470000064991F8EF +:100BB000243033B10023086A81F824300822FFF77B +:100BC000B1BF0120704700BF7C230020014B186893 +:100BD000704700BF002004E070B5194B1D68194B29 +:100BE0000138C5F30B0408442D0C04221E88A642CC +:100BF0000BD15C680A46013C824213460FD214F9BD +:100C0000016F4EB102F8016BF6E7013A03F10803F8 +:100C1000ECD181420B4602D22C2203F8012B0A4A66 +:100C200005241688AE4204D1984284BF967803F812 +:100C3000016B013C02F10402F3D1581A70BD00BFF0 +:100C4000002004E0F43A0008E03A0008022802BF5D +:100C5000024B4FF000729A61704700BF00000240E3 +:100C6000022802BF024B4FF400729A61704700BF26 +:100C700000000240022801BF024A536983F4007356 +:100C8000536170470000024070B504464FF47A7615 +:100C90004CB1412C254628BF412506FB05F001F04B +:100CA000DDF8641BF4E770BD10B50023934203D058 +:100CB000CC5CC4540133F9E710BD000010B5013815 +:100CC00010F9013F3BB191F900409C4203D11AB1A8 +:100CD0000131013AF4E71AB191F90020981A10BDD8 +:100CE0001046FCE703460246D01A12F9011B002900 +:100CF000FAD1704702440346934202D003F8011B25 +:100D0000FAE770472DE9F8431F4D144695F8242063 +:100D10000746884652BBDFF870909CB395F82430A4 +:100D20002BB92022FF2148462F62FFF7E3FF95F8F9 +:100D30002400C0F10802A24228BF2246D6B2414692 +:100D4000920005EB8000FFF7AFFF95F82430A41B5D +:100D50001E44F6B2082E17449044E4B285F824608D +:100D6000DBD1FFF723FF0028D7D108E02B6A03EB84 +:100D700082038342CFD0FFF719FF0028CBD1002098 +:100D8000BDE8F8830120FBE77C230020024B1A78A2 +:100D9000024B1A70704700BFB823002010220020B9 +:100DA00038B5194C194D204600F0BEFB29462046A7 +:100DB00000F0E6FB2D686A6DD2F8043843F00203B8 +:100DC000C2F804384FF47A70FFF75EFF10492846E6 +:100DD00000F0DCFC6A6D0F4DD2F8043828680E492B +:100DE00023F00203C2F80438A0424FF4E1330B6051 +:100DF00001D000F0F9FA6868A04204D0BDE838409C +:100E0000054900F0F1BA38BD98280020FC3B0008E5 +:100E1000043C000814220020A423002070B50C4BD1 +:100E20000C4D1E780C4B55F826209A4204460DD0E6 +:100E30000A4B002114221846FFF75CFF04600146AC +:100E400055F82600BDE8704000F0CEBA70BD00BF76 +:100E5000B82300201422002098280020A42300207A +:100E600030B5094D0A4491420DD011F8013B58406C +:100E7000082340F30004013B2C4013F0FF0384EAF5 +:100E80005000F6D1EFE730BD2083B8ED026843682B +:100E90001143016003B1184770470000024AD3684C +:100EA00043F0C003D36070470014014010B5084CF4 +:100EB000084A0021204600F075FA074BC4F85C325E +:100EC00003F1454303F52943C4F8603210BD00BF68 +:100ED000BC2300209D0E000800140140234A037C1F +:100EE000002918BF0A46012B30B5C0F868220CD182 +:100EF0001F4B984209D11F4B596C41F02001596496 +:100F0000596E41F0200159665B6EB2F904501468C5 +:100F1000D0F86032D0F85C12002D03EB5403B3FB21 +:100F2000F4F3BEBF23F0070503F0070343EA4503CC +:100F300094888B60D38843F040030B61138943F09E +:100F400001034B6144F4045343F02C03CB6004F4DD +:100F5000A05400230B60B4F5806F0B684B680CBF86 +:100F60007F23FF2380F8643230BD00BF143B0008AC +:100F7000BC230020003802402DE9F041D0F85C622B +:100F8000F7683368DA0504469DB20DD5302383F344 +:100F900011884FF480610430FFF778FF6FF480739D +:100FA0003360002383F31188302383F3118804F125 +:100FB000040815F02F033AD183F31188380615D5AC +:100FC000290613D5302383F3118804F1380000F08B +:100FD00065F900284EDA0821201DFFF757FF4FF66C +:100FE0007F733B40F360002383F311887A0616D5A4 +:100FF0006B0614D5302383F31188D4E913239A4266 +:101000000AD1236C43B127F040073F041021201D73 +:101010003F0CFFF73BFFF760002383F31188D4F800 +:101020006822D36843B3BDE8F041106918472B0725 +:1010300014D015F0080F0CBF00214FF48071E807A1 +:1010400048BF41F02001AA0748BF41F040016B07AB +:1010500048BF41F080014046FFF718FFAD067368B6 +:1010600005D594F864122046194000F0CBF9356894 +:10107000ADB29EE77060B6E7BDE8F081F8B5154601 +:1010800082680669AA420B46816938BF8568761A6C +:10109000B54204460BD218462A46FFF705FEA3695F +:1010A0002B44A361A3685B1BA3602846F8BD0CD941 +:1010B00018463246FFF7F8FDAF1BE1683A46304468 +:1010C000FFF7F2FDE3683B44EBE718462A46FFF7DB +:1010D000EBFDE368E5E7000083689342F7B515464A +:1010E000044638BF8568D0E90460361AB5420BD291 +:1010F0002A46FFF7D9FD63692B446361A36828463C +:101100005B1BA36003B0F0BD0DD932460191FFF720 +:10111000CBFD0199E068AF1B3A463144FFF7C4FDAF +:10112000E3683B44E9E72A46FFF7BEFDE368E4E7EE +:1011300010B50A440024C361029B8460C0E900002A +:10114000C0E90511C1600261036210BD08B5D0E9B4 +:101150000532934201D1826882B98268013282608D +:101160005A1C42611970D0E904329A4224BFC36804 +:101170004361002100F08EFE002008BD4FF0FF30DB +:10118000FBE7000070B5302304460E4683F3118858 +:10119000A568A5B1A368A269013BA360531CA36124 +:1011A00015782269934224BFE368A361E3690BB118 +:1011B00020469847002383F31188284607E03146EC +:1011C000204600F057FE0028E2DA85F3118870BD52 +:1011D0002DE9F74F04460E4617469846D0F81C9066 +:1011E0004FF0300A8AF311884FF0000B154665B1B5 +:1011F0002A4631462046FFF741FF034660B9414683 +:10120000204600F037FE0028F1D0002383F3118838 +:10121000781B03B0BDE8F08FB9F1000F03D0019047 +:101220002046C847019B8BF31188ED1A1E448AF3B0 +:101230001188DCE7C0E90511C160C3611144009B5E +:101240008260C0E90000016103627047F8B504469E +:101250000D461646302383F31188A768A7B1A3680B +:10126000013BA36063695A1C62611D70D4E90432BA +:101270009A4224BFE3686361E3690BB12046984753 +:10128000002080F3118807E03146204600F0F2FD8F +:101290000028E2DA87F31188F8BD0000D0E90523C1 +:1012A0009A4210B501D182687AB9826801328260AF +:1012B0005A1C82611C7803699A4224BFC368836107 +:1012C000002100F0E7FD204610BD4FF0FF30FBE7A6 +:1012D0002DE9F74F04460E4617469846D0F81C9065 +:1012E0004FF0300A8AF311884FF0000B154665B1B4 +:1012F0002A4631462046FFF7EFFE034660B94146D5 +:10130000204600F0B7FD0028F1D0002383F31188B8 +:10131000781B03B0BDE8F08FB9F1000F03D0019046 +:101320002046C847019B8BF31188ED1A1E448AF3AF +:101330001188DCE7026843681143016003B1184774 +:10134000704700001430FFF743BF00004FF0FF3339 +:101350001430FFF73DBF00003830FFF7B9BF000081 +:101360004FF0FF333830FFF7B3BF00001430FFF702 +:1013700009BF00004FF0FF311430FFF703BF00003A +:101380003830FFF763BF00004FF0FF323830FFF70F +:101390005DBF0000012914BF6FF0130000207047EB +:1013A000FFF784BD37B515460E4A02600022426041 +:1013B000C0E902220122044602740B46009000F1AB +:1013C0005C014FF480721430FFF7B2FE00942B469C +:1013D0004FF4807204F5AE7104F13800FFF72AFF74 +:1013E00003B030BD283B000810B53023044683F31A +:1013F0001188FFF773FD02232374002080F3118806 +:1014000010BD000038B5C36904460D461BB9042160 +:101410000844FFF78FFF294604F11400FFF796FEFA +:10142000002806DA201D4FF40061BDE83840FFF7C0 +:1014300081BF38BD026843681143016003B118479A +:101440007047000013B5446BD4F894341A681178CF +:10145000042915D1217C022912D11979128901237D +:101460008B4013420CD101A904F14C0001F0F8FEAD +:10147000D4F89444019B21790246206800F0D0F909 +:1014800002B010BD143001F07BBE00004FF0FF33FE +:10149000143001F075BE00004C3001F04DBF00006B +:1014A0004FF0FF334C3001F047BF0000143001F023 +:1014B00049BE00004FF0FF31143001F043BE000080 +:1014C0004C3001F019BF00004FF0FF324C3001F0FA +:1014D00013BF00000020704710B5D0F894341A688C +:1014E00011780429044617D1017C022914D15979B5 +:1014F000528901238B4013420ED1143001F0DCFDE0 +:10150000024648B1D4F894444FF48073617920685E +:10151000BDE8104000F072B910BD0000406BFFF74D +:10152000DBBF0000704700007FB5124B0360002353 +:101530004360C0E90233012502260F4B05740446BF +:101540000290019300F18402294600964FF48073C3 +:10155000143001F08DFD094B0294CDE9006304F5D0 +:1015600023724FF48073294604F14C0001F054FEBD +:1015700004B070BD503B00081D150008451400085C +:101580000B68302282F311880A7903EB82029061A2 +:101590004A79093243F822008A7912B103EB8203B7 +:1015A00098610223C0F894140374002080F311881A +:1015B0007047000038B5037F044613B190F85430EB +:1015C000ABB9201D01250221FFF734FF04F11400FF +:1015D00025776FF0010100F069FC84F8545004F1A4 +:1015E0004C006FF00101BDE8384000F05FBC38BD31 +:1015F00010B5012104460430FFF71CFF00232377B8 +:1016000084F8543010BD000038B50446002514306D +:1016100001F046FD04F14C00257701F015FE201D78 +:1016200084F854500121FFF705FF2046BDE83840FB +:10163000FFF752BF90F8443003F06003202B07D12E +:1016400090F84520212A4FF0000303D81F2A06D81E +:1016500000207047222AFBD1C0E90E3303E0034A81 +:1016600082630722C2630364012070471C220020AA +:1016700037B5D0F894341A681178042904461AD181 +:10168000017C022917D11979128901238B40134259 +:1016900011D100F14C05284601F096FE58B101A980 +:1016A000284601F0DDFDD4F89444019B21790246DF +:1016B000206800F0B5F803B030BD0000F0B500EBD5 +:1016C000810385B09E6904460D46FEB1302383F345 +:1016D000118804EB8507301D0821FFF7ABFEFB687E +:1016E0005B691B6806F14C001BB1019001F0C6FD5F +:1016F000019803A901F0B4FD024648B1039B2946B5 +:10170000204600F08DF8002383F3118805B0F0BD6A +:10171000FB685A691268002AF5D01B8A013B134006 +:10172000F1D104F14402EAE7093138B550F821401B +:10173000DCB1302383F31188D4F8942413685279F0 +:1017400003EB8203DB689B695D6845B10421601887 +:10175000FFF770FE294604F1140001F0B7FC2046A3 +:10176000FFF7BAFE002383F3118838BD70470000ED +:1017700001F016B8012303700023C0E90133C361EF +:1017800083620362C36243620363704738B50446F1 +:10179000302383F311880025C0E90355C0E90555BE +:1017A000416001F00DF80223237085F3118828466B +:1017B00038BD000070B500EB810305465069DA6062 +:1017C0000E46144618B110220021FFF793FAA069C3 +:1017D00018B110220021FFF78DFA31462846BDE8E6 +:1017E000704001F0B7B80000826802F00112826018 +:1017F0000022C0E90422826101F038B9F0B400EBA4 +:1018000081044789E4680125A4698D403D434581F1 +:1018100023600023A2606360F0BC01F053B90000B4 +:10182000F0B400EB81040789E468012564698D4008 +:101830003D43058123600023A2606360F0BC01F09A +:10184000CDB9000070B50223002504460370C0E93D +:101850000255C0E90455C564856180F8345001F033 +:1018600015F863681B6823B129462046BDE870401F +:10187000184770BD0378052B10B504460AD080F8D0 +:1018800050300523037043681B680BB1042198474F +:101890000023A36010BD00000178052906D190F84F +:1018A0005020436802701B6803B11847704700005E +:1018B00070B590F83430044613B1002380F834300A +:1018C00004F14402204601F0F3F863689B68B3B961 +:1018D00094F8443013F0600535D00021204601F023 +:1018E00093FB0021204601F085FB63681B6813B160 +:1018F000062120469847062384F8343070BD2046E0 +:1019000098470028E4D0B4F84A30E26B9A4288BF86 +:10191000E36394F94430E56B002B4FF0300380F221 +:101920000381002D00F0F280092284F8342083F333 +:1019300011880021D4E90E232046FFF771FF002310 +:1019400083F31188DAE794F8452003F07F0343EA34 +:10195000022340F20232934200F0C58021D8B3F551 +:10196000807F48D00DD8012B3FD0022B00F0938010 +:10197000002BB2D104F14C02A2630222E263236481 +:10198000C1E7B3F5817F00F09B80B3F5407FA4D120 +:1019900094F84630012BA0D1B4F84C3043F0020348 +:1019A00032E0B3F5006F4DD017D8B3F5A06F31D04A +:1019B000A3F5C063012B90D8636894F846205E6855 +:1019C00094F84710B4F848302046B047002884D037 +:1019D0004368A3630368E3631AE0B3F5106F36D07E +:1019E00040F6024293427FF478AF5C4BA36302233C +:1019F000E3630023C3E794F84630012B7FF46DAF17 +:101A0000B4F84C3023F00203C4E90E55A4F84C306E +:101A1000256478E7B4F84430B3F5A06F0ED194F89C +:101A2000463084F84E30204600F088FF63681B681B +:101A300013B1012120469847032323700023C4E9F2 +:101A40000E339CE704F14F03A3630123C3E723781C +:101A5000042B10D1302383F311882046FFF7C4FEF6 +:101A600085F311880321636884F84F5021701B6847 +:101A70000BB12046984794F84630002BDED084F80E +:101A80004F300423237063681B68002BD6D00221DB +:101A900020469847D2E794F848301D0603F00F011E +:101AA00020460AD500F0F6FF012804D002287FF472 +:101AB00014AF2B4B9AE72B4B98E700F0DDFFF3E7D1 +:101AC00094F84630002B7FF408AF94F8483013F0B8 +:101AD0000F01B3D01A06204602D501F0A9FAADE7EE +:101AE00001F09CFAAAE794F84630002B7FF4F5AE9B +:101AF00094F8483013F00F01A0D01B06204602D501 +:101B000001F082FA9AE701F075FA97E7142284F857 +:101B1000342083F311882B462A4629462046FFF7B6 +:101B20006DFE85F31188E9E65DB1152284F8342055 +:101B300083F311880021D4E90E232046FFF75EFECF +:101B4000FDE60B2284F8342083F311882B462A46C5 +:101B500029462046FFF764FEE3E700BF803B00080C +:101B6000783B00087C3B000838B590F834300446D8 +:101B7000002B3ED0063BDAB20F2A34D80F2B32D8D6 +:101B8000DFE803F037313108223231313131313180 +:101B900031313737C56BB0F84A309D4214D2C36833 +:101BA0001B8AB5FBF3F203FB12556DB9302383F3A7 +:101BB00011882B462A462946FFF732FE85F3118805 +:101BC0000A2384F834300EE0142384F834303023B0 +:101BD00083F3118800231A4619462046FFF70EFEAC +:101BE000002383F3118838BD036C03B198470023A9 +:101BF000E7E70021204601F007FA0021204601F026 +:101C0000F9F963681B6813B106212046984706233B +:101C1000D7E7000010B590F83430142B044629D0D3 +:101C200017D8062B05D001D81BB110BD093B022BDC +:101C3000FBD80021204601F0E7F90021204601F001 +:101C4000D9F963681B6813B106212046984706231B +:101C500019E0152BE9D10B2380F83430302383F3BE +:101C6000118800231A461946FFF7DAFD002383F393 +:101C70001188DAE7C3689B695B68002BD5D1036CD8 +:101C800003B19847002384F83430CEE7002303756E +:101C9000826803691B6899689142FBD25A680360A5 +:101CA00042601060586070470023037582680369C2 +:101CB0001B6899689142FBD85A68036042601060C3 +:101CC0005860704708B50846302383F311880B7DB0 +:101CD000032B05D0042B0DD02BB983F3118808BD3D +:101CE0008B6900221A604FF0FF338361FFF7CEFF4C +:101CF0000023F2E7D1E9003213605A60F3E70000F5 +:101D0000FFF7C4BF054BD9680875186802681A60E8 +:101D1000536001220275D860FEF7F4BA282600202D +:101D200030B50C4BDD684B1C87B004460FD02B46FA +:101D3000094A684600F04EF92046FFF7E3FF009B92 +:101D400013B1684600F050F9A86907B030BDFFF73D +:101D5000D9FFF9E728260020C51C0008044B1A68A3 +:101D6000DB6890689B68984294BF00200120704710 +:101D700028260020084B10B51C68D86822681A6015 +:101D8000536001222275DC60FFF78EFF014620467A +:101D9000BDE81040FEF7B6BA2826002038B5074C3B +:101DA00007490848012300252370656001F044FBC2 +:101DB0000223237085F3118838BD00BF90280020CE +:101DC000883B00082826002000F044B9034A5168E7 +:101DD00053685B1A9842FBD8704700BF001000E0C0 +:101DE0008B60022308618B82084670478368A3F1E9 +:101DF000840243F8142C026943F8442C426943F8E6 +:101E0000402C094A43F8242CC26843F8182C0222BB +:101E100003F80C2C002203F80B2C044A43F8102C76 +:101E2000A3F12000704700BF1D03000828260020F2 +:101E300008B5FFF7DBFFBDE80840FFF761BF000012 +:101E4000024BDB6898610F20FFF75CBF282600205B +:101E5000302383F31188FFF7F3BF000008B5014674 +:101E6000302383F311880820FFF75AFF002383F300 +:101E7000118808BD064BDB6839B1426818605A60AA +:101E8000136043600420FFF74BBF4FF0FF307047F3 +:101E9000282600200368984206D01A680260506025 +:101EA00099611846FFF72CBF7047000038B504460B +:101EB0000D462068844200D138BD036823605C6011 +:101EC0008561FFF71DFFF4E710B503689C68A24227 +:101ED0000CD85C688A600B604C602160596099681E +:101EE0008A1A9A604FF0FF33836010BD1B68121B83 +:101EF000ECE700000A2938BF0A2170B504460D46F8 +:101F00000A26601901F092FA01F07EFA041BA5423C +:101F100003D8751C2E460446F3E70A2E04D9BDE803 +:101F20007040012001F0C8BA70BD0000F8B5144B34 +:101F30000D46D96103F1100141600A2A19698260D6 +:101F400038BF0A22016048601861A818144601F0E1 +:101F50005FFA0A2701F058FA431BA342064606D34C +:101F60007C1C281901F062FA27463546F2E70A2F51 +:101F700004D9BDE8F840012001F09EBAF8BD00BFC9 +:101F800028260020F8B506460D4601F03DFA0F4A16 +:101F9000134653F8107F9F4206D12A460146304629 +:101FA000BDE8F840FFF7C2BFD169BB68441A2C19DD +:101FB00028BF2C46A34202D92946FFF79BFF2246A1 +:101FC00031460348BDE8F840FFF77EBF28260020D1 +:101FD0003826002010B4C0E9032300235DF8044B29 +:101FE0004361FFF7CFBF000010B5194C2369984239 +:101FF0000DD0D0E90032816813605A609A680A44B3 +:102000009A60002303604FF0FF33A36110BD2346A5 +:10201000026843F8102F53600022026022699A423E +:1020200003D1BDE8104001F0FBB9936881680B440F +:10203000936001F0E9F92269E1699268441AA242C9 +:10204000E4D91144BDE81040091AFFF753BF00BF9F +:10205000282600202DE9F047DFF8BC8008F11007A2 +:102060002C4ED8F8105001F0CFF9D8F81C40AA68CF +:10207000031B9A423ED81444D5E900324FF00009C0 +:10208000C8F81C4013605A60C5F80090D8F81030AA +:10209000B34201D101F0C4F989F31188D5E90331C4 +:1020A00028469847302383F311886B69002BD8D0DA +:1020B00001F0AAF96A69A0EB04094A4582460DD2EB +:1020C000022001F0F9F90022D8F81030B34208D10B +:1020D00051462846BDE8F047FFF728BF121A2244B0 +:1020E000F2E712EB090938BF4A4629463846FFF79E +:1020F000EBFEB5E7D8F81030B34208D01444211AEB +:10210000C8F81C00A960BDE8F047FFF7F3BEBDE8C2 +:10211000F08700BF382600202826002000207047C6 +:10212000FEE70000704700004FF0FF3070470000EE +:1021300002290CD0032904D00129074818BF002028 +:102140007047032A05D8054800EBC20070470448D1 +:1021500070470020704700BF603C00082C22002020 +:10216000143C000870B59AB00546084601A914460B +:1021700000F0C2F801A8FEF7B5FD431C5B00C5E9FD +:1021800000340022237003236370C6B201AB023413 +:102190001046D1B28E4204F1020401D81AB070BDCB +:1021A00013F8011B04F8021C04F8010C0132F0E7DB +:1021B00008B5302383F311880348FFF759FA002349 +:1021C00083F3118808BD00BF9828002090F84430A0 +:1021D00003F01F02012A07D190F845200B2A03D1F2 +:1021E0000023C0E90E3315E003F06003202B08D173 +:1021F000B0F848302BB990F84520212A03D81F2A7F +:1022000004D8FFF717BA222AEBD0FAE7034A826311 +:102210000722C26303640120704700BF232200200D +:1022200007B5052917D8DFE801F019160319192099 +:10223000302383F31188104A01900121FFF7BAFA85 +:1022400001980E4A0221FFF7B5FA0D48FFF7DCF9B5 +:10225000002383F3118803B05DF804FB302383F37C +:1022600011880748FFF7A6F9F2E7302383F31188B6 +:102270000348FFF7BDF9EBE7B43B0008D83B000883 +:102280009828002038B50C4D0C4C0D492A4604F115 +:102290000800FFF767FF05F1CA0204F110000949C1 +:1022A000FFF760FF05F5CA7204F118000649BDE8A2 +:1022B0003840FFF757BF00BF602D00202C220020C0 +:1022C000943B00089E3B0008A93B000870B50446FB +:1022D00008460D46FEF706FDC6B2204601340378D7 +:1022E0000BB9184670BD32462946FEF7E7FC0028B8 +:1022F000F3D10120F6E700002DE9F84F05460C4622 +:10230000FEF7F0FC2B49C6B22846FFF7DFFF08B105 +:102310000536F6B228492846FFF7D8FF08B110362F +:10232000F6B2632E0DD8DFF88C80DFF88C90234F47 +:10233000DFF890A0DFF890B02E7846B92670BDE89F +:10234000F88F29462046BDE8F84F01F0ABBB252E9B +:102350002BD1072241462846FEF7B0FC58B9DBF8DE +:1023600000302360DBF804306360DBF80830A360E2 +:1023700007350C34E0E7082249462846FEF79EFC64 +:1023800098B90F4BA21C197809090232C95D02F8ED +:10239000041C13F8011B01F00F015345C95D02F83D +:1023A000031CF0D118340835C6E704F8016B013579 +:1023B000C2E700BF803C0008A93B0008953C00082C +:1023C000107AFF1F1C7AFF1F883C0008BFF34F8F55 +:1023D000024AD368DB03FCD4704700BF003C0240D4 +:1023E00008B5094B1B7873B9FFF7F0FF074B1A6963 +:1023F000002ABFBF064A5A6002F188325A601A6842 +:1024000022F480621A6008BDBE2F0020003C02400A +:102410002301674508B50B4B1B7893B9FFF7D6FF2F +:10242000094B1A6942F000421A611A6842F480525C +:102430001A601A6822F480521A601A6842F48062A4 +:102440001A6008BDBE2F0020003C02400B28F0B5EA +:1024500016D80C4C0C4923787BB90C4D0E460C2336 +:102460004FF0006255F8047B46F8042B013B13F053 +:10247000FF033A44F6D10123237051F82000F0BD48 +:102480000020FCE7F02F0020C02F0020A83C00080F +:10249000014B53F820007047A83C00080C207047FF +:1024A0000B2810B5044601D9002010BDFFF7CEFF60 +:1024B000064B53F824301844C21A0BB90120F4E734 +:1024C00012680132F0D1043BF6E700BFA83C0008D7 +:1024D0000B2810B5044621D8FFF778FFFFF780FFDF +:1024E0000F4AF323D360C300DBB243F4007343F01D +:1024F00002031361136943F480331361FFF766FF2E +:10250000FFF7A4FF074B53F8241000F0D9F8FFF7AA +:1025100081FF2046BDE81040FFF7C2BF002010BD7C +:10252000003C0240A83C0008F8B512F00103144634 +:1025300042D18218B2F1016F57D82D4B1B6813F0AE +:10254000010352D02B4DFFF74BFFF323EB60FFF756 +:102550003DFF40F20127032C15D824F00104661832 +:10256000244C401A40F20117B142236900EB0105E7 +:1025700024D123F001032361FFF74CFF0120F8BDB4 +:10258000043C0430E7E78307E7D12B6923F4407369 +:102590002B612B693B432B6151F8046B0660BFF341 +:1025A0004F8FFFF713FF03689E42E9D02B6923F09A +:1025B00001032B61FFF72EFF0020E0E723F44073B7 +:1025C000236123693B4323610B882B80BFF34F8F2B +:1025D000FFF7FCFE2D8831F8023BADB2AB42C3D011 +:1025E000236923F001032361E4E71846C7E700BF2E +:1025F00000380240003C0240084908B50B7828B179 +:102600001BB9FFF7EDFE01230B7008BD002BFCD0BA +:10261000BDE808400870FFF7FDBE00BFBE2F0020D8 +:1026200010B50244064BD2B2904200D110BD441CFA +:1026300000B253F8200041F8040BE0B2F4E700BF09 +:10264000502800400F4B30B51C6F240407D41C6F7A +:1026500044F400741C671C6F44F400441C670A4C6B +:10266000236843F4807323600244084BD2B2904243 +:1026700000D130BD441C00B251F8045B43F8205037 +:10268000E0B2F4E7003802400070004050280040FB +:1026900007B5012201A90020FFF7C2FF019803B08E +:1026A0005DF804FB13B50446FFF7F2FFA04205D026 +:1026B000012201A900200194FFF7C4FF02B010BD60 +:1026C00070470000034B1A681AB9034AD2F87428FD +:1026D0001A607047F42F00200030024008B5FFF761 +:1026E000F1FF024B1868C0F3407008BDF42F0020C2 +:1026F00070470000FEE700000A4B0B480B4A90426F +:102700000BD30B4BDA1C121AC11E22F003028B42B0 +:1027100038BF00220021FEF7EDBA53F8041B40F841 +:10272000041BECE75C3E0008F0300020F030002095 +:10273000F030002070B5D0E915439E6800224FF0BC +:10274000FF3504EB42135101D3F800090028BEBF46 +:10275000D3F8000940F08040C3F80009D3F8000B1B +:102760000028BEBFD3F8000B40F08040C3F8000B38 +:10277000013263189642C3F80859C3F8085BE0D2E7 +:102780004FF00113C4F81C3870BD0000890141F0FE +:102790002001016103699B06FCD41220FFF716BBE0 +:1027A00010B5054C2046FEF7E5FF4FF0A0436365EA +:1027B000024BA36510BD00BFF82F0020FC3C0008B1 +:1027C00070B50378012B054650D12A4B446D9842D1 +:1027D0001BD1294B5A6B42F080025A635A6D42F06A +:1027E00080025A655A6D5A6942F080025A615A69EC +:1027F00022F080025A610E2143205B6900F022FC26 +:102800001E4BE3601E4BC4F800380023C4F8003EA2 +:10281000C02323606E6D4FF40413A3633369002B50 +:10282000FCDA012333610C20FFF7D0FA3369DB07B0 +:10283000FCD41220FFF7CAFA3369002BFCDA002619 +:10284000A6602846FFF776FF6B68C4F81068DB685F +:10285000C4F81468C4F81C684BB90A4BA3614FF064 +:10286000FF336361A36843F00103A36070BD064BAF +:10287000F4E700BFF82F0020003802404014004069 +:1028800003002002003C30C0083C30C0F8B5446D65 +:10289000054600212046FFF779FFA96D00234FF080 +:1028A00001128F68C4F834384FF00066C4F81C2851 +:1028B0004FF0FF3004EB431201339F42C2F800692E +:1028C000C2F8006BC2F80809C2F8080BF2D20B6814 +:1028D0006A6DEB65636210231361166916F01006CA +:1028E000FBD11220FFF772FAD4F8003823F4FE630C +:1028F000C4F80038A36943F4402343F01003A361F4 +:102900000923C4F81038C4F814380A4BEB604FF0B0 +:10291000C043C4F8103B084BC4F8003BC4F810692E +:10292000C4F80039EB6D03F1100243F48013EA653B +:10293000A362F8BDD83C000840800010426D90F8BA +:102940004E10D2F8003823F4FE6343EA0113C2F8B4 +:10295000003870472DE9F84300EB8103456DDA68D4 +:10296000166806F00306731E022B05EB41130C4696 +:1029700080460FFA81F94FEA41104FF00001C3F889 +:10298000101B4FF0010104F1100398BFB60401FAC7 +:1029900003F391698EBF334E06F1805606F500466B +:1029A00000293AD0578A04F15801490137436F5042 +:1029B000D5F81C180B43C5F81C382B180021C3F898 +:1029C000101953690127611EA7409BB3138A928B8C +:1029D0009B08012A88BF5343D8F85C20981842EA24 +:1029E000034301F1400205EB8202C8F85C00214676 +:1029F00053602846FFF7CAFE08EB8900C3681B8AAC +:102A000043EA8453483464011E432E51D5F81C38E0 +:102A10001F43C5F81C78BDE8F88305EB4917D7F8C4 +:102A2000001B21F40041C7F8001BD5F81C1821EA4F +:102A30000303C0E704F13F0305EB83030A4A5A602E +:102A400028462146FFF7A2FE05EB4910D0F80039D1 +:102A500023F40043C0F80039D5F81C3823EA0707EF +:102A6000D7E700BF0080001000040002826D1268EA +:102A7000C265FFF75FBE00005831436D49015B58E6 +:102A800013F4004004D013F4001F0CBF02200120F7 +:102A9000704700004831436D49015B5813F4004012 +:102AA00004D013F4001F0CBF022001207047000067 +:102AB00000EB8101CB68196A0B6813604B685360A7 +:102AC0007047000000EB810330B5DD68AA69136828 +:102AD000D36019B9402B84BF402313606B8A1468FC +:102AE000426D1C44013CB4FBF3F46343033323F015 +:102AF000030302EB411043EAC44343F0C043C0F870 +:102B0000103B2B6803F00303012B09B20ED1D2F85E +:102B1000083802EB411013F4807FD0F8003B14BF5B +:102B200043F0805343F00053C0F8003B02EB4112E6 +:102B3000D2F8003B43F00443C2F8003B30BD000034 +:102B40002DE9F041244D6E6D06EB40130446D3F899 +:102B5000087BC3F8087B38070AD5D6F8143819075C +:102B600006D505EB84032146DB6828465B68984759 +:102B7000FA071FD5D6F81438DB071BD505EB8403FD +:102B8000D968CCB98B69488A5A68B2FBF0F600FB69 +:102B900016228AB91868DA6890420DD2121AC3E96F +:102BA0000024302383F311880B482146FFF78AFF66 +:102BB00084F31188BDE8F081012303FA04F26B89E4 +:102BC00023EA02036B81CB68002BF3D02146024835 +:102BD000BDE8F041184700BFF82F002000EB81034B +:102BE00070B5DD68436D6C692668E6604A0156BBC6 +:102BF0001A444FF40020C2F810092A6802F00302B8 +:102C0000012A0AB20ED1D3F8080803EB421410F4DB +:102C1000807FD4F8000914BF40F0805040F000508D +:102C2000C4F8000903EB4212D2F8000940F0044056 +:102C3000C2F80009D3F83408012202FA01F1014375 +:102C4000C3F8341870BD19B9402E84BF40202060ED +:102C500020682E8A8419013CB4FBF6F440EAC44093 +:102C600040F000501A44C6E72DE9F8433B4D6E6D25 +:102C700006EB40130446D3F80889C3F8088918F016 +:102C8000010F4FEA40171AD0D6F81038DB0716D5D7 +:102C900005EB8003D9684B691868DA68904230D236 +:102CA000121A4FF000091A60C3F80490302383F31E +:102CB000118821462846FFF791FF89F3118818F003 +:102CC000800F1CD0D6F834380126A640334216D0E7 +:102CD00005EB84036D6DD3F80CC0DCF814200134CF +:102CE000E4B2D2F800E005EB04342F44516871459A +:102CF00015D3D5F8343823EA0606C5F83468BDE89C +:102D0000F883012303FA04F22B8923EA02032B81BF +:102D10008B68002BD3D0214628469847CFE7BCF8D4 +:102D20001000AEEB0103834228BF0346D7F8180911 +:102D300080B2B3EB800FE2D89068A0F1040959F893 +:102D4000048FC4F80080A0EB09089844B8F1040F80 +:102D5000F5D818440B4490605360C7E7F82F002063 +:102D60002DE9F74FA24C656D6E69AB691E4016F4F4 +:102D700080586E6107D02046FEF764FD03B0BDE8C1 +:102D8000F04F00F047BC002E12DAD5F8003E98480C +:102D90009B071EBFD5F8003E23F00303C5F8003E95 +:102DA000D5F8043823F00103C5F80438FEF774FDA4 +:102DB000370505D58E48FFF7BDFC8D48FEF75AFD57 +:102DC000B0040CD5D5F8083813F0060FEB6823F4DF +:102DD00070530CBF43F4105343F4A053EB6031071E +:102DE0001BD56368DB681BB9AB6923F00803AB61D3 +:102DF0002378052B0CD1D5F8003E7D489A071EBFDD +:102E0000D5F8003E23F00303C5F8003EFEF744FD6D +:102E10006368DB680BB176489847F30274D4B70255 +:102E200027D5D4F85490DFF8C8B100274FF0010A35 +:102E300009EB4712D2F8003B03F44023B3F5802F8F +:102E400011D1D2F8003B002B0DDA62890AFA07F3A0 +:102E500022EA0303638104EB8703DB68DB6813B1B9 +:102E6000394658469847A36D01379B68FFB29F4289 +:102E7000DED9F00617D5676D3A6AC2F30A1002F080 +:102E80000F0302F4F012B2F5802F00F08580B2F546 +:102E9000402F08D104EB83030022DB681B6A07F58F +:102EA000805790426AD13003D5F8184813D5E10312 +:102EB00002D50020FFF744FEA20302D50120FFF750 +:102EC0003FFE630302D50220FFF73AFE270302D537 +:102ED0000320FFF735FE75037FF550AFE00702D5FD +:102EE0000020FFF7C1FEA10702D50120FFF7BCFEBD +:102EF000620702D50220FFF7B7FE23077FF53EAF3A +:102F00000320FFF7B1FE39E7636DDFF8E4A001931A +:102F100000274FF00109A36D9B685FFA87FB9B4573 +:102F20003FF67DAF019B03EB4B13D3F8001901F47F +:102F30004021B1F5802F1FD1D3F8001900291BDAE9 +:102F4000D3F8001941F09041C3F80019D3F80019E3 +:102F50000029FBDB5946606DFFF718FC218909FA4F +:102F60000BF321EA0303238104EB8B03DB689B68EB +:102F700013B15946504698470137CCE7910708BF2F +:102F8000D7F80080072A98BF03F8018B02F10102ED +:102F900098BF4FEA182884E7023304EB830207F551 +:102FA00080575268D2F818C0DCF80820DCE9001C11 +:102FB000A1EB0C0C002188420AD104EB8304636866 +:102FC0009B699A6802449A605A6802445A606AE7A8 +:102FD00011F0030F08BFD7F800808C4588BF02F8B6 +:102FE000018B01F1010188BF4FEA1828E3E700BF18 +:102FF000F82F0020436D03EB4111D1F8003B43F45F +:103000000013C1F8003B7047436D03EB4111D1F849 +:10301000003943F40013C1F800397047436D03EBE6 +:103020004111D1F8003B23F40013C1F8003B704775 +:10303000436D03EB4111D1F8003923F40013C1F8BB +:103040000039704700F1604303F561430901C9B2DB +:1030500083F80013012200F01F039A4043099B00EC +:1030600003F1604303F56143C3F880211A607047A0 +:1030700030B5039C0172043304FB0325C0E90653F9 +:10308000049B03630021059BC160C0E90000C0E907 +:103090000422C0E90842C0E90A11436330BD0000C0 +:1030A000416A0022C0E90411C0E90A22C2606FF03F +:1030B0000101FEF7FBBE0000D0E90432934201D1CA +:1030C000C2680AB9181D704700207047036919606B +:1030D000C2680132C260C2691344826903619342CB +:1030E00024BF436A03610021FEF7D4BE38B504460D +:1030F0000D46E3683BB16269131D1268A362134475 +:10310000E362002007E0237A33B929462046FEF720 +:10311000B1FE0028EDDA38BD6FF00100FBE70000DA +:10312000C368C269013BC360436913448269436158 +:10313000934224BF436A436100238362036B03B15C +:103140001847704770B53023044683F31188866AA8 +:103150003EB9FFF7CBFF054618B186F31188284624 +:1031600070BDA36AE26A13F8015BA362934202D3C3 +:103170002046FFF7D5FF002383F31188EFE7000017 +:103180002DE9F84F04460E46174698464FF0300991 +:1031900089F311880025AA46D4F828B0BBF1000FA6 +:1031A00009D141462046FFF7A1FF20B18BF31188DA +:1031B0002846BDE8F88FD4E90A12A7EB050B521A8E +:1031C000934528BF9346BBF1400F1BD9334601F10D +:1031D000400251F8040B43F8040B9142F9D1A36A61 +:1031E00040334036A3624035D4E90A239A4202D3E1 +:1031F0002046FFF795FF8AF31188BD42D8D289F3A4 +:103200001188C9E730465A46FDF74EFDA36A5B4474 +:103210005E44A3625D44E7E710B5029C017204338B +:1032200003FB0421C0E906130023C0E90A33039B12 +:103230000363049BC460C0E90000C0E90422C0E944 +:103240000842436310BD0000026AC260426AC0E9DE +:1032500004220022C0E90A226FF00101FEF726BE17 +:10326000D0E904239A4201D1C26822B9184650F825 +:10327000043B0B60704700231846FAE7C368C26935 +:103280000133C3604369134482694361934224BF9D +:10329000436A43610021FEF7FDBD000038B50446D6 +:1032A0000D46E3683BB123691A1DA262E26913442B +:1032B000E362002007E0237A33B929462046FEF76F +:1032C000D9FD0028EDDA38BD6FF00100FBE7000002 +:1032D00003691960C268013AC260C2691344826915 +:1032E0000361934224BF436A036100238362036B3B +:1032F00003B118477047000070B530230D460446EF +:10330000114683F31188866A2EB9FFF7C7FF10B103 +:1033100086F3118870BDA36A1D70A36AE26A013347 +:103320009342A36204D3E16920460439FFF7D0FF3A +:10333000002080F31188EDE72DE9F84F04460D4693 +:10334000904699464FF0300A8AF311880026B3461A +:10335000A76A4FB949462046FFF7A0FF20B187F37F +:1033600011883046BDE8F88FD4E90A073A1AA8EB6D +:103370000607974228BF1746402F1BD905F1400387 +:1033800055F8042B40F8042B9D42F9D1A36A403331 +:10339000A3624036D4E90A239A4204D3E169204665 +:1033A0000439FFF795FF8BF311884645D9D28AF38C +:1033B0001188CDE729463A46FDF776FCA36A3B44DF +:1033C0003D44A3623E44E5E7D0E904239A4217D185 +:1033D000C3689BB1836A8BB1043B9B1A0ED0136008 +:1033E000C368013BC360C3691A44836902619A429E +:1033F00024BF436A03610023836201231846704798 +:103400000023FBE700F030B94FF08043586A704763 +:103410004FF08043002258631A610222DA6070473D +:103420004FF080430022DA60704700004FF0804385 +:1034300058637047FEE7000070B51B4B0163002521 +:10344000044686B0586085620E4600F0BFF804F16D +:103450001003C4E904334FF0FF33C4E90635C4E96F +:103460000044A560E562FFF7CFFF2B460246C4E9A2 +:10347000082304F134010D4A256580232046FEF718 +:10348000AFFC0123E0600A4A037500927268019262 +:10349000B268CDE90223074B6846CDE90435FEF753 +:1034A000C7FC06B070BD00BF90280020083D000892 +:1034B0000D3D000835340008024AD36A1843D06233 +:1034C000704700BF282600204B6843608B688360EC +:1034D000CB68C3600B6943614B6903628B694362CC +:1034E0000B6803607047000008B5264B26481A6930 +:1034F00040F2FF110A431A611A6922F4FF7222F0A6 +:1035000001021A611A691A6B0A431A631A6D0A4397 +:103510001A651E4A1B6D1146FFF7D6FF02F11C010A +:1035200000F58060FFF7D0FF02F1380100F5806000 +:10353000FFF7CAFF02F1540100F58060FFF7C4FFF6 +:1035400002F1700100F58060FFF7BEFF02F18C010F +:1035500000F58060FFF7B8FF02F1A80100F5806078 +:10356000FFF7B2FF02F1C40100F58060FFF7ACFF86 +:1035700002F1E00100F58060FFF7A6FFBDE808401A +:1035800000F0EEB80038024000000240143D000890 +:1035900008B500F067FAFEF701FCFFF793F8BDE805 +:1035A0000840FEF76FBE000070470000EFF309838C +:1035B00005494A6B22F001024A63683383F30988A4 +:1035C000002383F31188704700EF00E0302080F380 +:1035D000118862B60C4B0D4AD96821F4E0610904E8 +:1035E000090C0A43DA60D3F8FC20094942F08072E2 +:1035F000C3F8FC200A6842F001020A602022DA7750 +:1036000083F82200704700BF00ED00E00003FA05D8 +:10361000001000E010B5302383F311880E4B5B6877 +:1036200013F4006314D0F1EE103AEFF30984683C10 +:103630004FF08073E361094BDB6B236684F30988E9 +:10364000FEF78CFB10B1064BA36110BD054BFBE7E9 +:1036500083F31188F9E700BF00ED00E000EF00E020 +:103660002F030008320300080F4B1A6C42F00102CE +:103670001A641A6E42F001021A660C4A1B6E9368B5 +:1036800043F0010393604FF0804353229A624FF05E +:10369000FF32DA6200229A615A63DA605A600122CC +:1036A0005A611A60704700BF00380240002004E0F1 +:1036B0004FF0804208B51169D3680B40D9B2C943B5 +:1036C0009B07116107D5302383F31188FEF77CFB3C +:1036D000002383F3118808BD1F4B1A696FEAC25299 +:1036E0006FEAD2521A611A69C2F308021A614FF0E6 +:1036F000FF301A695A69586100215A6959615A693B +:103700001A6A62F080521A621A6A02F080521A62D1 +:103710001A6A5A6A58625A6A59625A6A1A6C42F0AC +:1037200080521A641A6E42F080521A661A6E0B4A60 +:10373000106840F480701060186F00F44070B0F5AD +:10374000007F1EBF4FF4803018671967536823F459 +:103750000073536000F05EB9003802400070004012 +:10376000334B4FF080521A64324A4FF4404111609B +:103770001A6842F001021A601A689107FCD59A682B +:1037800022F003029A602A4B9A6812F00C02FBD1D5 +:10379000196801F0F90119609A601A6842F48032E0 +:1037A0001A601A689203FCD55A6F42F001025A67F8 +:1037B0001F4B5A6F9007FCD51F4A5A601A6842F097 +:1037C00080721A601B4A53685904FCD5184B1A685A +:1037D0009201FCD5194A9A60194B1A68194B9A4202 +:1037E000194B21D1194A1168194A91421CD140F252 +:1037F00005121A60144A136803F00F03052BFAD15F +:103800000B4B9A6842F002029A609A6802F00C022E +:10381000082AFAD15A6C42F480425A645A6E42F431 +:1038200080425A665B6E704740F20572E1E700BF66 +:103830000038024000700040085440070094883867 +:10384000002004E011640020003C024000ED00E094 +:1038500041C20F41074A08B5536903F001035361A0 +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7D0BE003C014070300020074A08B579 +:10388000536903F00203536123B1054A93680BB1F6 +:10389000D0689847BDE80840FFF7BCBE003C014037 +:1038A00070300020074A08B5536903F004035361E0 +:1038B00023B1054A13690BB150699847BDE8084028 +:1038C000FFF7A8BE003C014070300020074A08B551 +:1038D000536903F00803536123B1054A93690BB19F +:1038E000D0699847BDE80840FFF794BE003C01400E +:1038F00070300020074A08B5536903F01003536184 +:1039000023B1054A136A0BB1506A9847BDE80840D5 +:10391000FFF780BE003C014070300020164B10B510 +:103920005C6904F478725A61A30604D5134A936A59 +:103930000BB1D06A9847600604D5104A136B0BB1DF +:10394000506B9847210604D50C4A936B0BB1D06B92 +:103950009847E20504D5094A136C0BB1506C98479F +:10396000A30504D5054A936C0BB1D06C9847BDE80C +:103970001040FFF74FBE00BF003C014070300020F8 +:10398000194B10B55C6904F47C425A61620504D598 +:10399000164A136D0BB1506D9847230504D5134A91 +:1039A000936D0BB1D06D9847E00404D50F4A136EA8 +:1039B0000BB1506E9847A10404D50C4A936E0BB11D +:1039C000D06E9847620404D5084A136F0BB1506F4C +:1039D0009847230404D5054A936F0BB1D06F9847DD +:1039E000BDE81040FFF716BE003C014070300020DB +:1039F00008B50348FDF7C0FABDE80840FFF70ABE66 +:103A0000BC23002008B5FFF753FEBDE80840FFF7D0 +:103A100001BE0000062108B50846FFF713FB06218A +:103A20000720FFF70FFB06210820FFF70BFB0621FD +:103A30000920FFF707FB06210A20FFF703FB0621F9 +:103A40001720FFF7FFFA06212820FFF7FBFA0721CE +:103A50001C20FFF7F7FABDE808400C214720FFF7CC +:103A6000F1BA000008B5FFF737FE00F00DF8FDF7DA +:103A700097FCFDF77DFEFDF755FDFFF795FDBDE8D1 +:103A80000840FFF7BFBC00000023054A1946013378 +:103A9000102BC2E9001102F10802F8D1704700BFF3 +:103AA00070300020034611F8012B03F8012B002A87 +:103AB000F9D1704753544D3332463F3F3F00535482 +:103AC0004D3332463430780053544D33324634321D +:103AD000780053544D333246343436585800000081 +:103AE000012033000010410001105A00031059005A +:103AF0000710310000000000B43A00081304000071 +:103B0000BE3A000819040000C83A00082104000069 +:103B1000D23A0008009600000000000000000000FB +:103B20000000000000000000000000006113000819 +:103B30004D1300088913000875130008811300084D +:103B40006D13000859130008451300089513000869 +:103B500000000000A11400088D140008C91400081A +:103B6000B5140008C1140008AD1400089914000829 +:103B700085140008D51400080000000001000000B2 +:103B80000000000063300000843B00088026002015 +:103B9000902800204172647550696C6F7400254252 +:103BA0004F415244252D424C002553455249414C2A +:103BB000250000000200000000000000BD16000803 +:103BC0002917000840004000302D0020402D002023 +:103BD00002000000000000000300000000000000E0 +:103BE0006D1700080000000010000000502D00209C +:103BF000000000000100000000000000F82F00207D +:103C0000010102002122000831210008CD21000815 +:103C1000B1210008430000001C3C000809024300D9 +:103C2000020100C032090400000102020100052463 +:103C300000100105240100010424020205240600ED +:103C400001070582030800FF09040100020A0000C1 +:103C50000007050102400000070581024000000046 +:103C600012000000683C0008120110010200004030 +:103C70000912415700020102030100000403090474 +:103C800025424F41524425004A48454D5F4A484528 +:103C900046343035003031323334353637383941F7 +:103CA0004243444546000000004000000040000040 +:103CB0000040000000400000000001000000020081 +:103CC00000000200000002000000020000000200EC +:103CD000000002000000020000000000B11800080F +:103CE000691B0008151C00084000400058300020E7 +:103CF00058300020010000006830002080000000E3 +:103D000040010000030000006D61696E0069646C91 +:103D1000650000000000842A00000000AAAAAAAAE8 +:103D200000000024FFFD00000000000000A00A00C9 +:103D30004000001100000000AAAAAAAA4000001139 +:103D4000FFFF0000000000000000000000A00000D5 +:103D500000000000AAAAAAAA00500000FFFF00006D +:103D600000000088000000000000000000000000CB +:103D7000AAAAAAAA00000000FFFF0000000000009D +:103D8000000000000000000000000000AAAAAAAA8B +:103D900000000000FFFF0000000000000000000025 +:103DA0000000000000000000AAAAAAAA000000006B +:103DB000FFFF000000000000000000000000000005 +:103DC00000000000AAAAAAAA00000000FFFF00004D +:103DD00000000000000000000000000000000000E3 +:103DE0000A000000000000000300000000000000C6 +:103DF00000000000000000000000000000000000C3 +:103E000000000000000000000000000000000000B2 +:103E1000390400000000000000400F000000000016 +:103E2000FF00000098280020BC230020009600001E +:103E300000000800960000000008000004000000D8 +:103E40007C3C0008000000000000000000000000B2 +:0C3E500000000000000000000000000066 :00000001FF diff --git a/Tools/bootloaders/KakuteF4-Wing_bl.bin b/Tools/bootloaders/KakuteF4-Wing_bl.bin new file mode 100644 index 00000000000000..a3cbae06abadff Binary files /dev/null and b/Tools/bootloaders/KakuteF4-Wing_bl.bin differ diff --git a/Tools/bootloaders/KakuteF4-Wing_bl.hex b/Tools/bootloaders/KakuteF4-Wing_bl.hex new file mode 100644 index 00000000000000..44b4ce6f985194 --- /dev/null +++ b/Tools/bootloaders/KakuteF4-Wing_bl.hex @@ -0,0 +1,893 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008692F00086C +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E301000811320008393200080A +:100060006132000889320008B1320008E30100085B +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008D932000889 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000AD330008E3010008E3010008E301000894 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E0003D330008E3010008E3010008E3010008D4 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100081D2700089F +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F02EFF43 +:1002500002F028FE4FF055301F491B4A91423CBF27 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F00CFF02F056FEF8 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F0F4BE000600200022002074 +:1002D0000000000808ED00E00000002000060020FB +:1002E0007037000800220020402200204022002019 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F070FAFEE701F08E +:10033000FFF900DFFEE7000038B500F0BBFB01F07D +:1003400085FE054601F0A8FE0446C8B90E4B9D4245 +:1003500018D001339D4218BF044641F2883504BFCE +:1003600001240025002001F07BFE0CB100F074F8A0 +:1003700000F0FEFC284600F0BFF800F06DF8F9E749 +:100380000025EFE70546EDE7010007B008B500F0EE +:1003900063FBA0F120035842584108BD07B541F264 +:1003A0001203022101A8ADF8043000F073FB03B082 +:1003B0005DF804FB38B5302383F3118817480368D0 +:1003C0000BB101F0EFFA164A144800234FF47A718A +:1003D00001F0DEFA002383F31188124C236813B175 +:1003E0002368013B2360636813B16368013B63606A +:1003F0000D4D2B7833B963687BB9022000F022FCE5 +:10040000322363602B78032B07D163682BB902205A +:1004100000F018FC4FF47A73636038BD402200206E +:10042000B50300086023002058220020084B1870F4 +:1004300003280CD8DFE800F008050208022000F0CD +:10044000F9BB022000F0ECBB024B00225A6070475F +:100450005822002060230020234B244A10B51C465C +:10046000196801313FD004339342F9D16268A24246 +:1004700039D31F4B9B6803F1006303F540439A4255 +:1004800031D2002000F030FB0220FFF7CFFF194BE4 +:100490001A6C00221A64196E1A66196E596C5A6425 +:1004A000596E5A665A6E5A6942F080025A615A6908 +:1004B00022F080025A615A691A6942F000521A61A8 +:1004C0001A6922F000521A611B6972B64FF0E023DC +:1004D0003021C3F8084DD4E9003281F311889D46DC +:1004E00083F30888104710BD00C0000820C0000832 +:1004F00000220020003802402DE9F04F93B0AA4BB3 +:1005000000902022FF210AA89D6800F0DBFBA74A8B +:100510001378A3B9A648012103601170302383F337 +:10052000118803680BB101F03DFAA24AA0480023EC +:100530004FF47A7101F02CFA002383F31188009BA9 +:1005400013B19D4B009A1A609C4A009C1378032BB0 +:100550001EBF00231370984A4FF0000A18BF536063 +:10056000D3465646D146012000F064FB24B1924B9D +:100570001B68002B00F01182002000F06DFA039040 +:10058000039B002BF2DB012000F04AFB039B213B85 +:10059000162BE8D801A252F823F000BFF905000895 +:1005A00021060008B5060008670500086705000871 +:1005B000670500083F0700080F0900082908000820 +:1005C0008B080008B3080008D90800086705000870 +:1005D000EB080008670500085D0900089906000897 +:1005E00067050008A109000805060008990600082B +:1005F000670500088B0800080220FFF7C7FE0028E7 +:1006000040F0F581009B0221BAF1000F08BF1C46A3 +:1006100005A841F21233ADF8143000F03BFAA2E71E +:100620004FF47A7000F018FA071EEBDB0220FFF798 +:10063000ADFE0028E6D0013F052F00F2DA81DFE8A9 +:1006400007F0030A0D10133605230593042105A8AE +:1006500000F020FA17E054480421F9E75848042133 +:10066000F6E758480421F3E74FF01C08404600F035 +:100670003DFA08F104080590042105A800F00AFAE3 +:10068000B8F12C0FF2D1012000FA07F747EA0B0B63 +:100690005FFA8BFB4FF0000900F060FB26B10BF016 +:1006A0000B030B2B08BF0024FFF778FE5BE74648DF +:1006B0000421CDE7002EA5D00BF00B030B2BA1D10D +:1006C0000220FFF763FE074600289BD0012000F0C0 +:1006D0000BFA0220FFF7AAFE00261FFA86F8404612 +:1006E00000F012FA044690B10021404600F01CFAD6 +:1006F00001360028F1D1BA46044641F21213022114 +:1007000005A8ADF814303E4600F0C4F92BE70120EF +:10071000FFF78CFE2546244B9B68AB4207D9284641 +:1007200000F0E4F9013040F067810435F3E7234B32 +:1007300000251D70204BBA465D603E46ACE7002E9A +:100740003FF460AF0BF00B030B2B7FF45BAF022089 +:10075000FFF76CFE322000F07FF9B0F10008FFF6E1 +:1007600051AF18F003077FF44DAF0F4A926808EBC2 +:10077000050393423FF646AFB8F5807F3FF742AF9F +:10078000124B0193B84523DD4FF47A7000F064F901 +:100790000390039A002AFFF635AF019B039A03F8F2 +:1007A000012B0137EDE700BF002200205C23002071 +:1007B00040220020B50300086023002058220020BA +:1007C00004220020082200200C2200205C220020AD +:1007D000C820FFF7DBFD074600283FF413AF1F2DAD +:1007E00011D8C5F1200242450AAB25F0030028BF0D +:1007F000424683490192184400F03EFA019A80482B +:10080000FF2100F05FFA4FEAA8037D490193C8F386 +:100810008702284600F05EFA064600283FF46DAFD6 +:10082000019B05EB830537E70220FFF7AFFD0028AA +:100830003FF4E8AE00F0A4F900283FF4E3AE00274F +:10084000B846704B9B68BB4218D91F2F11D80A9B22 +:1008500001330ED027F0030312AA134453F8203CAF +:1008600005934046042205A900F0ACFA04378046FF +:10087000E7E7384600F03AF90590F2E7CDF8148042 +:10088000042105A800F006F906E70023642104A866 +:10089000049300F0F5F800287FF4B4AE0220FFF7CF +:1008A00075FD00283FF4AEAE049800F051F90590B4 +:1008B000E6E70023642104A8049300F0E1F800288F +:1008C0007FF4A0AE0220FFF761FD00283FF49AAE4E +:1008D000049800F04DF9EAE70220FFF757FD0028E1 +:1008E0003FF490AE00F05CF9E1E70220FFF74EFD27 +:1008F00000283FF487AE05A9142000F057F9042121 +:100900000746049004A800F0C5F83946B9E732203C +:1009100000F0A2F8071EFFF675AEBB077FF472AEBB +:10092000384A926807EB090393423FF66BAE022008 +:10093000FFF72CFD00283FF465AE27F003074F4476 +:10094000B9453FF4A9AE484600F0D0F8042105901F +:1009500005A800F09FF809F10409F1E74FF47A7057 +:10096000FFF714FD00283FF44DAE00F009F9002810 +:1009700044D00A9B01330BD008220AA9002000F0C2 +:10098000A9F900283AD02022FF210AA800F09AF9FC +:10099000FFF704FD1C4800F03FFF13B0BDE8F08FE7 +:1009A000002E3FF42FAE0BF00B030B2B7FF42AAE7F +:1009B0000023642105A8059300F062F8074600288B +:1009C0007FF420AE0220FFF7E1FC804600283FF4D0 +:1009D00019AEFFF7E3FC41F2883000F01DFF0598E7 +:1009E00000F0EEF9464600F0B9F93C46BBE5064694 +:1009F00052E64FF0000905E6BA467EE637467CE649 +:100A00005C22002000220020A086010070B50F4B60 +:100A10001B780133DBB2012B0C4611D80C4D296831 +:100A20004FF47A730E6AA2FB03320146224628462F +:100A3000B047844204D1074B00221A70012070BDD8 +:100A40004FF4FA7000F0E8FE0020F8E710220020D2 +:100A5000082600209423002007B500230246012128 +:100A60000DF107008DF80730FFF7D0FF20B19DF89A +:100A7000070003B05DF804FB4FF0FF30F9E700001A +:100A80000A4608B50421FFF7C1FF80F00100C0B29B +:100A9000404208BD30B4054C2368DD69044B0A466A +:100AA000AC460146204630BC604700BF0826002007 +:100AB000A086010070B501F0CFF9094E094D3080D4 +:100AC000002428683388834208D901F0BFF92B68D5 +:100AD00004440133B4F5404F2B60F2D370BD00BF26 +:100AE000962300206823002001F064BA00F1006022 +:100AF00000F540400068704700F10060920000F58A +:100B0000404001F0EFB90000054B1A68054B1B8807 +:100B10009B1A834202D9104401F098B90020704713 +:100B2000682300209623002038B5084D044629B1DB +:100B300028682044BDE8384001F0A8B9286820445E +:100B400001F08CF90028F3D038BD00BF68230020E5 +:100B500010F003030AD1B0F5047F05D200F1005074 +:100B6000A0F51040D0F80038184670470023FBE786 +:100B700000F10050A0F51040D0F8100A70470000B6 +:100B8000064991F8243033B10023086A81F82430F3 +:100B90000822FFF7B1BF0120704700BF6C2300207F +:100BA000014B1868704700BF002004E070B5194B76 +:100BB0001D68194B0138C5F30B0408442D0C0422A1 +:100BC0001E88A6420BD15C680A46013C824213464D +:100BD0000FD214F9016F4EB102F8016BF6E7013A3A +:100BE00003F10803ECD181420B4602D22C2203F818 +:100BF000012B0A4A05241688AE4204D1984284BFCC +:100C0000967803F8016B013C02F10402F3D1581A03 +:100C100070BD00BF002004E0903400087C34000860 +:100C2000022802BF024B4FF400329A61704700BFA6 +:100C300000000240022804BF014B9861704700BFCA +:100C400000000240022801BF024A536983F00203F8 +:100C5000536170470000024070B504464FF47A7645 +:100C60004CB1412C254628BF412506FB05F000F07C +:100C7000D3FD641BF4E770BD10B50023934203D08D +:100C8000CC5CC4540133F9E710BD000010B5013845 +:100C900010F9013F3BB191F900409C4203D11AB1D8 +:100CA0000131013AF4E71AB191F90020981A10BD08 +:100CB0001046FCE703460246D01A12F9011B002930 +:100CC000FAD1704702440346934202D003F8011B55 +:100CD000FAE770472DE9F8431F4D144695F8242094 +:100CE0000746884652BBDFF870909CB395F82430D5 +:100CF0002BB92022FF2148462F62FFF7E3FF95F82A +:100D00002400C0F10802A24228BF2246D6B24146C2 +:100D1000920005EB8000FFF7AFFF95F82430A41B8D +:100D20001E44F6B2082E17449044E4B285F82460BD +:100D3000DBD1FFF725FF0028D7D108E02B6A03EBB2 +:100D400082038342CFD0FFF71BFF0028CBD10020C6 +:100D5000BDE8F8830120FBE76C230020024B1A78E2 +:100D6000024B1A70704700BF94230020102200200D +:100D700010B5104C104800F0B5F821460E4800F0B0 +:100D8000DDF82468626DD2F8043843F00203C2F83B +:100D900004384FF47A70FFF75FFF0849204600F0EF +:100DA000D3F9626DD2F8043823F00203C2F8043894 +:100DB00010BD00BF5C35000808260020643500081F +:100DC0007047000030B5094D0A4491420DD011F82A +:100DD000013B5840082340F30004013B2C4013F032 +:100DE000FF0384EA5000F6D1EFE730BD2083B8ED71 +:100DF000026843681143016003B11847704700005F +:100E000013B5446BD4F894341A681178042915D1B9 +:100E1000217C022912D11979128901238B401342B6 +:100E20000CD101A904F14C0001F0F8FED4F894446F +:100E3000019B21790246206800F0D0F902B010BD74 +:100E4000143001F07BBE00004FF0FF33143001F08E +:100E500075BE00004C3001F04DBF00004FF0FF3375 +:100E60004C3001F047BF0000143001F049BE0000D3 +:100E70004FF0FF31143001F043BE00004C3001F060 +:100E800019BF00004FF0FF324C3001F013BF0000DB +:100E90000020704710B5D0F894341A6811780429EE +:100EA000044617D1017C022914D1597952890123B2 +:100EB0008B4013420ED1143001F0DCFD024648B1E4 +:100EC000D4F894444FF4807361792068BDE81040F1 +:100ED00000F072B910BD0000406BFFF7DBBF0000EF +:100EE000704700007FB5124B036000234360C0E9E8 +:100EF0000233012502260F4B05740446029001932C +:100F000000F18402294600964FF48073143001F0FA +:100F10008DFD094B0294CDE9006304F523724FF473 +:100F20008073294604F14C0001F054FE04B070BDFA +:100F3000B0340008D90E0008010E00080B683022FA +:100F400082F311880A7903EB820290614A790932AF +:100F500043F822008A7912B103EB820398610223DD +:100F6000C0F894140374002080F3118870470000C7 +:100F700038B5037F044613B190F85430ABB9201D47 +:100F800001250221FFF734FF04F1140025776FF0EB +:100F9000010100F069FC84F8545004F14C006FF03A +:100FA0000101BDE8384000F05FBC38BD10B501213B +:100FB00004460430FFF71CFF0023237784F85430E5 +:100FC00010BD000038B504460025143001F046FD80 +:100FD00004F14C00257701F015FE201D84F85450D3 +:100FE0000121FFF705FF2046BDE83840FFF752BF5B +:100FF00090F8443003F06003202B07D190F845208F +:10100000212A4FF0000303D81F2A06D8002070477A +:10101000222AFBD1C0E90E3303E0034A8263072290 +:10102000C2630364012070471122002037B5D0F855 +:1010300094341A681178042904461AD1017C0229D3 +:1010400017D11979128901238B40134211D100F174 +:101050004C05284601F096FE58B101A9284601F03A +:10106000DDFDD4F89444019B21790246206800F00C +:10107000B5F803B030BD0000F0B500EB810385B0DA +:101080009E6904460D46FEB1302383F3118804EBBC +:101090008507301D0821FFF7ABFEFB685B691B6805 +:1010A00006F14C001BB1019001F0C6FD019803A9A7 +:1010B00001F0B4FD024648B1039B2946204600F0EA +:1010C0008DF8002383F3118805B0F0BDFB685A69E1 +:1010D0001268002AF5D01B8A013B1340F1D104F1BC +:1010E0004402EAE7093138B550F82140DCB1302339 +:1010F00083F31188D4F894241368527903EB8203A4 +:10110000DB689B695D6845B104216018FFF770FEDC +:10111000294604F1140001F0B7FC2046FFF7BAFE9F +:10112000002383F3118838BD7047000001F016B822 +:10113000012303700023C0E90133C36183620362AA +:10114000C36243620363704738B50446302383F3B8 +:1011500011880025C0E90355C0E90555416001F03B +:101160000DF80223237085F31188284638BD00004E +:1011700070B500EB810305465069DA600E461446EF +:1011800018B110220021FFF79DFDA06918B11022AF +:101190000021FFF797FD31462846BDE8704001F079 +:1011A000B7B80000826802F0011282600022C0E934 +:1011B0000422826101F038B9F0B400EB8104478960 +:1011C000E4680125A4698D403D43458123600023E7 +:1011D000A2606360F0BC01F053B90000F0B400EB12 +:1011E00081040789E468012564698D403D430581D8 +:1011F00023600023A2606360F0BC01F0CDB9000061 +:1012000070B50223002504460370C0E90255C0E909 +:101210000455C564856180F8345001F015F86368A1 +:101220001B6823B129462046BDE87040184770BDB1 +:101230000378052B10B504460AD080F850300523FA +:10124000037043681B680BB1042198470023A36017 +:1012500010BD00000178052906D190F850204368A0 +:1012600002701B6803B118477047000070B590F812 +:101270003430044613B1002380F8343004F14402C2 +:10128000204601F0F3F863689B68B3B994F84430E2 +:1012900013F0600535D00021204601F093FB0021BA +:1012A000204601F085FB63681B6813B106212046C8 +:1012B0009847062384F8343070BD204698470028AC +:1012C000E4D0B4F84A30E26B9A4288BFE36394F901 +:1012D0004430E56B002B4FF0300380F20381002D8A +:1012E00000F0F280092284F8342083F31188002171 +:1012F000D4E90E232046FFF771FF002383F3118802 +:10130000DAE794F8452003F07F0343EA022340F232 +:101310000232934200F0C58021D8B3F5807F48D0D7 +:101320000DD8012B3FD0022B00F09380002BB2D1BF +:1013300004F14C02A2630222E2632364C1E7B3F525 +:10134000817F00F09B80B3F5407FA4D194F84630B4 +:10135000012BA0D1B4F84C3043F0020332E0B3F5D6 +:10136000006F4DD017D8B3F5A06F31D0A3F5C0638F +:10137000012B90D8636894F846205E6894F8471073 +:10138000B4F848302046B047002884D04368A363AF +:101390000368E3631AE0B3F5106F36D040F60242FB +:1013A00093427FF478AF5C4BA3630223E363002393 +:1013B000C3E794F84630012B7FF46DAFB4F84C309E +:1013C00023F00203C4E90E55A4F84C30256478E7F5 +:1013D000B4F84430B3F5A06F0ED194F8463084F8D9 +:1013E0004E30204600F088FF63681B6813B101216E +:1013F00020469847032323700023C4E90E339CE75B +:1014000004F14F03A3630123C3E72378042B10D116 +:10141000302383F311882046FFF7C4FE85F311883B +:101420000321636884F84F5021701B680BB120467C +:10143000984794F84630002BDED084F84F300423D0 +:10144000237063681B68002BD6D002212046984782 +:10145000D2E794F848301D0603F00F0120460AD564 +:1014600000F0F6FF012804D002287FF414AF2B4BC4 +:101470009AE72B4B98E700F0DDFFF3E794F846304E +:10148000002B7FF408AF94F8483013F00F01B3D06D +:101490001A06204602D501F0A9FAADE701F09CFA40 +:1014A000AAE794F84630002B7FF4F5AE94F8483064 +:1014B00013F00F01A0D01B06204602D501F082FADE +:1014C0009AE701F075FA97E7142284F8342083F341 +:1014D00011882B462A4629462046FFF76DFE85F3E4 +:1014E0001188E9E65DB1152284F8342083F3118870 +:1014F0000021D4E90E232046FFF75EFEFDE60B2215 +:1015000084F8342083F311882B462A462946204646 +:10151000FFF764FEE3E700BFE0340008D8340008BA +:10152000DC34000838B590F834300446002B3ED047 +:10153000063BDAB20F2A34D80F2B32D8DFE803F09B +:1015400037313108223231313131313131313737B0 +:10155000C56BB0F84A309D4214D2C3681B8AB5FBF4 +:10156000F3F203FB12556DB9302383F311882B4638 +:101570002A462946FFF732FE85F311880A2384F8AC +:1015800034300EE0142384F83430302383F3118890 +:1015900000231A4619462046FFF70EFE002383F368 +:1015A000118838BD036C03B198470023E7E7002199 +:1015B000204601F007FA0021204601F0F9F963689E +:1015C0001B6813B10621204698470623D7E7000081 +:1015D00010B590F83430142B044629D017D8062BB8 +:1015E00005D001D81BB110BD093B022BFBD800214F +:1015F000204601F0E7F90021204601F0D9F963689F +:101600001B6813B1062120469847062319E0152BC5 +:10161000E9D10B2380F83430302383F31188002381 +:101620001A461946FFF7DAFD002383F31188DAE73B +:10163000C3689B695B68002BD5D1036C03B19847E5 +:10164000002384F83430CEE70023037582680369F1 +:101650001B6899689142FBD25A680360426010602F +:101660005860704700230375826803691B68996896 +:101670009142FBD85A68036042601060586070471E +:1016800008B50846302383F311880B7D032B05D062 +:10169000042B0DD02BB983F3118808BD8B69002270 +:1016A0001A604FF0FF338361FFF7CEFF0023F2E7AC +:1016B000D1E9003213605A60F3E70000FFF7C4BFBE +:1016C000054BD9680875186802681A6053600122D2 +:1016D0000275D860FEF716BE9823002030B50C4B7B +:1016E000DD684B1C87B004460FD02B46094A68467C +:1016F00000F04EF92046FFF7E3FF009B13B1684668 +:1017000000F050F9A86907B030BDFFF7D9FFF9E73D +:101710009823002081160008044B1A68DB68906843 +:101720009B68984294BF00200120704798230020B6 +:10173000084B10B51C68D86822681A6053600122F3 +:101740002275DC60FFF78EFF01462046BDE81040A1 +:10175000FEF7D8BD9823002038B5074C0749084844 +:10176000012300252370656001F044FB02232370F0 +:1017700085F3118838BD00BF00260020E83400083A +:101780009823002000F044B9034A516853685B1A5B +:101790009842FBD8704700BF001000E08B60022326 +:1017A00008618B82084670478368A3F1840243F87E +:1017B000142C026943F8442C426943F8402C094A2E +:1017C00043F8242CC26843F8182C022203F80C2C8E +:1017D000002203F80B2C044A43F8102CA3F120003C +:1017E000704700BF1D0300089823002008B5FFF7CD +:1017F000DBFFBDE80840FFF761BF0000024BDB687C +:1018000098610F20FFF75CBF98230020302383F3FB +:101810001188FFF7F3BF000008B50146302383F3BA +:1018200011880820FFF75AFF002383F3118808BDB1 +:10183000064BDB6839B1426818605A601360436038 +:101840000420FFF74BBF4FF0FF3070479823002074 +:101850000368984206D01A68026050609961184681 +:10186000FFF72CBF7047000038B504460D462068CE +:10187000844200D138BD036823605C608561FFF756 +:101880001DFFF4E710B503689C68A2420CD85C68A1 +:101890008A600B604C602160596099688A1A9A606E +:1018A0004FF0FF33836010BD1B68121BECE7000094 +:1018B0000A2938BF0A2170B504460D460A26601968 +:1018C00001F092FA01F07EFA041BA54203D8751CC0 +:1018D0002E460446F3E70A2E04D9BDE870400120E5 +:1018E00001F0C8BA70BD0000F8B5144B0D46D961BF +:1018F00003F1100141600A2A1969826038BF0A2287 +:10190000016048601861A818144601F05FFA0A27C0 +:1019100001F058FA431BA342064606D37C1C281943 +:1019200001F062FA27463546F2E70A2F04D9BDE8EE +:10193000F840012001F09EBAF8BD00BF98230020B6 +:10194000F8B506460D4601F03DFA0F4A134653F826 +:10195000107F9F4206D12A4601463046BDE8F84036 +:10196000FFF7C2BFD169BB68441A2C1928BF2C46A7 +:10197000A34202D92946FFF79BFF2246314603487E +:10198000BDE8F840FFF77EBF98230020A823002081 +:1019900010B4C0E9032300235DF8044B4361FFF753 +:1019A000CFBF000010B5194C236998420DD0D0E983 +:1019B0000032816813605A609A680A449A60002372 +:1019C00003604FF0FF33A36110BD2346026843F864 +:1019D000102F53600022026022699A4203D1BDE8B1 +:1019E000104001F0FBB9936881680B44936001F0EB +:1019F000E9F92269E1699268441AA242E4D91144E2 +:101A0000BDE81040091AFFF753BF00BF982300201C +:101A10002DE9F047DFF8BC8008F110072C4ED8F80C +:101A2000105001F0CFF9D8F81C40AA68031B9A4265 +:101A30003ED81444D5E900324FF00009C8F81C40E4 +:101A400013605A60C5F80090D8F81030B34201D145 +:101A500001F0C4F989F31188D5E903312846984784 +:101A6000302383F311886B69002BD8D001F0AAF9D9 +:101A70006A69A0EB04094A4582460DD2022001F0B2 +:101A8000F9F90022D8F81030B34208D1514628465F +:101A9000BDE8F047FFF728BF121A2244F2E712EB25 +:101AA000090938BF4A4629463846FFF7EBFEB5E735 +:101AB000D8F81030B34208D01444211AC8F81C00DA +:101AC000A960BDE8F047FFF7F3BEBDE8F08700BFAF +:101AD000A82300209823002000207047FEE7000084 +:101AE000704700004FF0FF307047000002290CD013 +:101AF000032904D00129074818BF00207047032A92 +:101B000005D8054800EBC200704704487047002024 +:101B1000704700BFC035000820220020743500083F +:101B200070B59AB00546084601A9144600F0C2F8FF +:101B300001A8FFF7BFF8431C5B00C5E90034002291 +:101B4000237003236370C6B201AB02341046D1B2D6 +:101B50008E4204F1020401D81AB070BD13F8011BC3 +:101B600004F8021C04F8010C0132F0E708B5302338 +:101B700083F311880348FFF759FA002383F3118890 +:101B800008BD00BF0826002090F8443003F01F0273 +:101B9000012A07D190F845200B2A03D10023C0E980 +:101BA0000E3315E003F06003202B08D1B0F8483065 +:101BB0002BB990F84520212A03D81F2A04D8FFF713 +:101BC00017BA222AEBD0FAE7034A82630722C263DC +:101BD00003640120704700BF1822002007B50529C3 +:101BE00017D8DFE801F0191603191920302383F301 +:101BF0001188104A01900121FFF7BAFA01980E4AA4 +:101C00000221FFF7B5FA0D48FFF7DCF9002383F353 +:101C1000118803B05DF804FB302383F31188074873 +:101C2000FFF7A6F9F2E7302383F311880348FFF7A3 +:101C3000BDF9EBE714350008383500080826002008 +:101C400038B50C4D0C4C0D492A4604F10800FFF73D +:101C500067FF05F1CA0204F110000949FFF760FFB0 +:101C600005F5CA7204F118000649BDE83840FFF7CF +:101C700057BF00BFD02A002020220020F4340008E3 +:101C8000FE3400080935000870B5044608460D46C4 +:101C9000FFF710F8C6B22046013403780BB9184696 +:101CA00070BD32462946FEF7F1FF0028F3D101202E +:101CB000F6E700002DE9F04705460C46FEF7FAFF6F +:101CC0002B49C6B22846FFF7DFFF08B10636F6B249 +:101CD00028492846FFF7D8FF08B11036F6B2632E20 +:101CE0000BD8DFF88C80DFF88C90234FDFF894A0BE +:101CF0002E7846B92670BDE8F08729462046BDE813 +:101D0000F04701F09DBB252E2ED1072241462846E3 +:101D1000FEF7BCFF70B9194B224603F10C0153F8D2 +:101D2000040B42F8040B8B42F9D11B781370073572 +:101D30000D34DDE7082249462846FEF7A7FF98B98B +:101D40000F4BA21C197809090232C95D02F8041C64 +:101D500013F8011B01F00F015345C95D02F8031C84 +:101D6000F0D118340835C3E704F8016B0135BFE73B +:101D7000E035000809350008F6350008E8350008A8 +:101D8000107AFF1F1C7AFF1FBFF34F8F024AD368E0 +:101D9000DB03FCD4704700BF003C024008B5094B90 +:101DA0001B7873B9FFF7F0FF074B1A69002ABFBF12 +:101DB000064A5A6002F188325A601A6822F4806238 +:101DC0001A6008BD2E2D0020003C0240230167450B +:101DD00008B50B4B1B7893B9FFF7D6FF094B1A696F +:101DE00042F000421A611A6842F480521A601A687E +:101DF00022F480521A601A6842F480621A6008BDA8 +:101E00002E2D0020003C02400B28F0B516D80C4CBB +:101E10000C4923787BB90C4D0E460C234FF0006221 +:101E200055F8047B46F8042B013B13F0FF033A44BA +:101E3000F6D10123237051F82000F0BD0020FCE70B +:101E4000602D0020302D002008360008014B53F88B +:101E500020007047083600080C2070470B2810B58A +:101E6000044601D9002010BDFFF7CEFF064B53F802 +:101E700024301844C21A0BB90120F4E71268013269 +:101E8000F0D1043BF6E700BF083600080B2810B578 +:101E9000044621D8FFF778FFFFF780FF0F4AF323AE +:101EA000D360C300DBB243F4007343F00203136159 +:101EB000136943F480331361FFF766FFFFF7A4FF54 +:101EC000074B53F8241000F0D9F8FFF781FF2046A4 +:101ED000BDE81040FFF7C2BF002010BD003C02402B +:101EE00008360008F8B512F00103144642D18218F2 +:101EF000B2F1016F57D82D4B1B6813F0010352D07C +:101F00002B4DFFF74BFFF323EB60FFF73DFF40F254 +:101F10000127032C15D824F001046618244C401A1C +:101F200040F20117B142236900EB010524D123F0EF +:101F300001032361FFF74CFF0120F8BD043C04308E +:101F4000E7E78307E7D12B6923F440732B612B6903 +:101F50003B432B6151F8046B0660BFF34F8FFFF7D3 +:101F600013FF03689E42E9D02B6923F001032B6124 +:101F7000FFF72EFF0020E0E723F44073236123697D +:101F80003B4323610B882B80BFF34F8FFFF7FCFE91 +:101F90002D8831F8023BADB2AB42C3D0236923F0A8 +:101FA00001032361E4E71846C7E700BF0038024099 +:101FB000003C0240084908B50B7828B11BB9FFF76F +:101FC000EDFE01230B7008BD002BFCD0BDE80840DE +:101FD0000870FFF7FDBE00BF2E2D002010B5024493 +:101FE000064BD2B2904200D110BD441C00B253F84F +:101FF000200041F8040BE0B2F4E700BF5028004095 +:102000000F4B30B51C6F240407D41C6F44F40074CC +:102010001C671C6F44F400441C670A4C236843F49B +:10202000807323600244084BD2B2904200D130BD8D +:10203000441C00B251F8045B43F82050E0B2F4E7CE +:1020400000380240007000405028004007B50122CF +:1020500001A90020FFF7C2FF019803B05DF804FB5F +:1020600013B50446FFF7F2FFA04205D0012201A9F3 +:1020700000200194FFF7C4FF02B010BD70470000BC +:10208000034B1A681AB9034AD2F874281A607047C9 +:10209000642D00200030024008B5FFF7F1FF024B2D +:1020A0001868C0F3407008BD642D00207047000020 +:1020B000FEE700000A4B0B480B4A90420BD30B4B38 +:1020C000DA1C121AC11E22F003028B4238BF002212 +:1020D0000021FEF7F7BD53F8041B40F8041BECE7A2 +:1020E000B0370008602E0020602E0020602E0020F7 +:1020F00070B5D0E915439E6800224FF0FF3504EB20 +:1021000042135101D3F800090028BEBFD3F80009DB +:1021100040F08040C3F80009D3F8000B0028BEBF90 +:10212000D3F8000B40F08040C3F8000B0132631875 +:102130009642C3F80859C3F8085BE0D24FF0011388 +:10214000C4F81C3870BD0000890141F02001016114 +:1021500003699B06FCD41220FFF716BB10B5054C93 +:102160002046FEF7E5FF4FF0A0436365024BA365F1 +:1021700010BD00BF682D00205C36000870B50378E4 +:10218000012B054650D12A4B446D98421BD1294B57 +:102190005A6B42F080025A635A6D42F080025A65CF +:1021A0005A6D5A6942F080025A615A6922F08002DF +:1021B0005A610E2143205B6900F022FC1E4BE36054 +:1021C0001E4BC4F800380023C4F8003EC02323602F +:1021D0006E6D4FF40413A3633369002BFCDA012303 +:1021E00033610C20FFF7D0FA3369DB07FCD41220EF +:1021F000FFF7CAFA3369002BFCDA0026A6602846EE +:10220000FFF776FF6B68C4F81068DB68C4F81468E1 +:10221000C4F81C684BB90A4BA3614FF0FF336361EC +:10222000A36843F00103A36070BD064BF4E700BF51 +:10223000682D0020003802404014004003002002B6 +:10224000003C30C0083C30C0F8B5446D0546002164 +:102250002046FFF779FFA96D00234FF001128F6828 +:10226000C4F834384FF00066C4F81C284FF0FF3033 +:1022700004EB431201339F42C2F80069C2F8006BBD +:10228000C2F80809C2F8080BF2D20B686A6DEB6558 +:10229000636210231361166916F01006FBD1122039 +:1022A000FFF772FAD4F8003823F4FE63C4F800385C +:1022B000A36943F4402343F01003A3610923C4F846 +:1022C0001038C4F814380A4BEB604FF0C043C4F820 +:1022D000103B084BC4F8003BC4F81069C4F800393F +:1022E000EB6D03F1100243F48013EA65A362F8BDBD +:1022F0003836000840800010426D90F84E10D2F839 +:10230000003823F4FE6343EA0113C2F80038704733 +:102310002DE9F84300EB8103456DDA68166806F095 +:102320000306731E022B05EB41130C4680460FFA81 +:1023300081F94FEA41104FF00001C3F8101B4FF034 +:10234000010104F1100398BFB60401FA03F3916987 +:102350008EBF334E06F1805606F5004600293AD06E +:10236000578A04F15801490137436F50D5F81C18BA +:102370000B43C5F81C382B180021C3F810195369FA +:102380000127611EA7409BB3138A928B9B08012AE9 +:1023900088BF5343D8F85C20981842EA034301F100 +:1023A000400205EB8202C8F85C00214653602846D3 +:1023B000FFF7CAFE08EB8900C3681B8A43EA84530F +:1023C000483464011E432E51D5F81C381F43C5F80C +:1023D0001C78BDE8F88305EB4917D7F8001B21F4FA +:1023E0000041C7F8001BD5F81C1821EA0303C0E719 +:1023F00004F13F0305EB83030A4A5A60284621464D +:10240000FFF7A2FE05EB4910D0F8003923F4004392 +:10241000C0F80039D5F81C3823EA0707D7E700BF12 +:102420000080001000040002826D1268C265FFF790 +:102430005FBE00005831436D49015B5813F4004002 +:1024400004D013F4001F0CBF0220012070470000CD +:102450004831436D49015B5813F4004004D013F434 +:10246000001F0CBF022001207047000000EB81011B +:10247000CB68196A0B6813604B68536070470000A3 +:1024800000EB810330B5DD68AA691368D36019B920 +:10249000402B84BF402313606B8A1468426D1C4438 +:1024A000013CB4FBF3F46343033323F0030302EB77 +:1024B000411043EAC44343F0C043C0F8103B2B68CB +:1024C00003F00303012B09B20ED1D2F8083802EB56 +:1024D000411013F4807FD0F8003B14BF43F08053C9 +:1024E00043F00053C0F8003B02EB4112D2F8003B2E +:1024F00043F00443C2F8003B30BD00002DE9F04139 +:10250000244D6E6D06EB40130446D3F8087BC3F8E8 +:10251000087B38070AD5D6F81438190706D505EB15 +:1025200084032146DB6828465B689847FA071FD575 +:10253000D6F81438DB071BD505EB8403D968CCB972 +:102540008B69488A5A68B2FBF0F600FB16228AB9FA +:102550001868DA6890420DD2121AC3E900243023B9 +:1025600083F311880B482146FFF78AFF84F3118813 +:10257000BDE8F081012303FA04F26B8923EA020328 +:102580006B81CB68002BF3D021460248BDE8F041B7 +:10259000184700BF682D002000EB810370B5DD688F +:1025A000436D6C692668E6604A0156BB1A444FF4D5 +:1025B0000020C2F810092A6802F00302012A0AB2B8 +:1025C0000ED1D3F8080803EB421410F4807FD4F83E +:1025D000000914BF40F0805040F00050C4F80009DA +:1025E00003EB4212D2F8000940F00440C2F800099F +:1025F000D3F83408012202FA01F10143C3F8341878 +:1026000070BD19B9402E84BF4020206020682E8AFA +:102610008419013CB4FBF6F440EAC44040F0005099 +:102620001A44C6E72DE9F8433B4D6E6D06EB4013A7 +:102630000446D3F80889C3F8088918F0010F4FEA57 +:1026400040171AD0D6F81038DB0716D505EB8003F3 +:10265000D9684B691868DA68904230D2121A4FF084 +:1026600000091A60C3F80490302383F311882146CF +:102670002846FFF791FF89F3118818F0800F1CD0CE +:10268000D6F834380126A640334216D005EB840331 +:102690006D6DD3F80CC0DCF814200134E4B2D2F82C +:1026A00000E005EB04342F445168714515D3D5F88B +:1026B000343823EA0606C5F83468BDE8F8830123F8 +:1026C00003FA04F22B8923EA02032B818B68002B87 +:1026D000D3D0214628469847CFE7BCF81000AEEB90 +:1026E0000103834228BF0346D7F8180980B2B3EB31 +:1026F000800FE2D89068A0F1040959F8048FC4F85B +:102700000080A0EB09089844B8F1040FF5D81844EC +:102710000B4490605360C7E7682D00202DE9F74F08 +:10272000A24C656D6E69AB691E4016F480586E61EF +:1027300007D02046FEF764FD03B0BDE8F04F00F07F +:1027400047BC002E12DAD5F8003E98489B071EBF02 +:10275000D5F8003E23F00303C5F8003ED5F8043851 +:1027600023F00103C5F80438FEF774FD370505D5DD +:102770008E48FFF7BDFC8D48FEF75AFDB0040CD51E +:10278000D5F8083813F0060FEB6823F470530CBF2C +:1027900043F4105343F4A053EB6031071BD5636837 +:1027A000DB681BB9AB6923F00803AB612378052B09 +:1027B0000CD1D5F8003E7D489A071EBFD5F8003EE3 +:1027C00023F00303C5F8003EFEF744FD6368DB68B1 +:1027D0000BB176489847F30274D4B70227D5D4F8E2 +:1027E0005490DFF8C8B100274FF0010A09EB4712F7 +:1027F000D2F8003B03F44023B3F5802F11D1D2F877 +:10280000003B002B0DDA62890AFA07F322EA030380 +:10281000638104EB8703DB68DB6813B139465846F4 +:102820009847A36D01379B68FFB29F42DED9F0063F +:1028300017D5676D3A6AC2F30A1002F00F0302F46B +:10284000F012B2F5802F00F08580B2F5402F08D14C +:1028500004EB83030022DB681B6A07F58057904274 +:102860006AD13003D5F8184813D5E10302D500200A +:10287000FFF744FEA20302D50120FFF73FFE6303EA +:1028800002D50220FFF73AFE270302D50320FFF707 +:1028900035FE75037FF550AFE00702D50020FFF746 +:1028A000C1FEA10702D50120FFF7BCFE620702D5D9 +:1028B0000220FFF7B7FE23077FF53EAF0320FFF7A7 +:1028C000B1FE39E7636DDFF8E4A0019300274FF014 +:1028D0000109A36D9B685FFA87FB9B453FF67DAFBF +:1028E000019B03EB4B13D3F8001901F44021B1F520 +:1028F000802F1FD1D3F8001900291BDAD3F8001953 +:1029000041F09041C3F80019D3F800190029FBDB0E +:102910005946606DFFF718FC218909FA0BF321EA8B +:102920000303238104EB8B03DB689B6813B15946D7 +:10293000504698470137CCE7910708BFD7F8008089 +:10294000072A98BF03F8018B02F1010298BF4FEAF2 +:10295000182884E7023304EB830207F58057526896 +:10296000D2F818C0DCF80820DCE9001CA1EB0C0C44 +:10297000002188420AD104EB830463689B699A684A +:1029800002449A605A6802445A606AE711F0030FE1 +:1029900008BFD7F800808C4588BF02F8018B01F191 +:1029A000010188BF4FEA1828E3E700BF682D002027 +:1029B000436D03EB4111D1F8003B43F40013C1F820 +:1029C000003B7047436D03EB4111D1F8003943F4EC +:1029D0000013C1F800397047436D03EB4111D1F882 +:1029E000003B23F40013C1F8003B7047436D03EB39 +:1029F0004111D1F8003923F40013C1F800397047B0 +:102A000000F1604303F561430901C9B283F8001383 +:102A1000012200F01F039A4043099B0003F1604329 +:102A200003F56143C3F880211A60704730B5039CF9 +:102A30000172043304FB0325C0E90653049B0363BE +:102A40000021059BC160C0E90000C0E90422C0E983 +:102A50000842C0E90A11436330BD0000416A002208 +:102A6000C0E90411C0E90A22C2606FF00101FEF75B +:102A7000FBBE0000D0E90432934201D1C2680AB91A +:102A8000181D70470020704703691960C268013241 +:102A9000C260C269134482690361934224BF436ADE +:102AA00003610021FEF7D4BE38B504460D46E36845 +:102AB0003BB16269131D1268A3621344E3620020F4 +:102AC00007E0237A33B929462046FEF7B1FE0028F5 +:102AD000EDDA38BD6FF00100FBE70000C368C269A2 +:102AE000013BC3604369134482694361934224BF3D +:102AF000436A436100238362036B03B11847704745 +:102B000070B53023044683F31188866A3EB9FFF717 +:102B1000CBFF054618B186F31188284670BDA36A1D +:102B2000E26A13F8015BA362934202D32046FFF7E7 +:102B3000D5FF002383F31188EFE700002DE9F84F5C +:102B400004460E46174698464FF0300989F311881F +:102B50000025AA46D4F828B0BBF1000F09D14146A0 +:102B60002046FFF7A1FF20B18BF311882846BDE86E +:102B7000F88FD4E90A12A7EB050B521A934528BF28 +:102B80009346BBF1400F1BD9334601F1400251F887 +:102B9000040B43F8040B9142F9D1A36A4033403649 +:102BA000A3624035D4E90A239A4202D32046FFF7B4 +:102BB00095FF8AF31188BD42D8D289F31188C9E7FD +:102BC00030465A46FEF758F8A36A5B445E44A36257 +:102BD0005D44E7E710B5029C0172043303FB042156 +:102BE000C0E906130023C0E90A33039B0363049B77 +:102BF000C460C0E90000C0E90422C0E908424363A0 +:102C000010BD0000026AC260426AC0E904220022CC +:102C1000C0E90A226FF00101FEF726BED0E90423C5 +:102C20009A4201D1C26822B9184650F8043B0B60A1 +:102C3000704700231846FAE7C368C2690133C360CE +:102C40004369134482694361934224BF436A4361E9 +:102C50000021FEF7FDBD000038B504460D46E368CF +:102C60003BB123691A1DA262E2691344E3620020AA +:102C700007E0237A33B929462046FEF7D9FD00281C +:102C8000EDDA38BD6FF00100FBE700000369196061 +:102C9000C268013AC260C269134482690361934207 +:102CA00024BF436A036100238362036B03B11847A7 +:102CB0007047000070B530230D460446114683F37B +:102CC0001188866A2EB9FFF7C7FF10B186F3118805 +:102CD00070BDA36A1D70A36AE26A01339342A362C6 +:102CE00004D3E16920460439FFF7D0FF002080F3C8 +:102CF0001188EDE72DE9F84F04460D4690469946B8 +:102D00004FF0300A8AF311880026B346A76A4FB9FC +:102D100049462046FFF7A0FF20B187F311883046CF +:102D2000BDE8F88FD4E90A073A1AA8EB06079742DC +:102D300028BF1746402F1BD905F1400355F8042B37 +:102D400040F8042B9D42F9D1A36A4033A362403678 +:102D5000D4E90A239A4204D3E16920460439FFF7F3 +:102D600095FF8BF311884645D9D28AF31188CDE7B8 +:102D700029463A46FDF780FFA36A3B443D44A362DF +:102D80003E44E5E7D0E904239A4217D1C3689BB1DA +:102D9000836A8BB1043B9B1A0ED01360C368013B5E +:102DA000C360C3691A44836902619A4224BF436ABB +:102DB0000361002383620123184670470023FBE769 +:102DC00000F030B94FF08043586A70474FF08043AD +:102DD000002258631A610222DA6070474FF0804384 +:102DE0000022DA60704700004FF08043586370475C +:102DF000FEE7000070B51B4B01630025044686B05A +:102E0000586085620E4600F0BFF804F11003C4E973 +:102E100004334FF0FF33C4E90635C4E90044A5602C +:102E2000E562FFF7CFFF2B460246C4E9082304F111 +:102E300034010D4A256580232046FEF7AFFC0123AF +:102E4000E0600A4A0375009272680192B268CDE9A7 +:102E50000223074B6846CDE90435FEF7C7FC06B0F0 +:102E600070BD00BF00260020683600086D360008DF +:102E7000F12D0008024AD36A1843D062704700BFA0 +:102E8000982300204B6843608B688360CB68C360E5 +:102E90000B6943614B6903628B6943620B68036092 +:102EA0007047000008B5264B26481A6940F2FF110A +:102EB0000A431A611A6922F4FF7222F001021A61B0 +:102EC0001A691A6B0A431A631A6D0A431A651E4A75 +:102ED0001B6D1146FFF7D6FF02F11C0100F5806063 +:102EE000FFF7D0FF02F1380100F58060FFF7CAFF5D +:102EF00002F1540100F58060FFF7C4FF02F1700198 +:102F000000F58060FFF7BEFF02F18C0100F58060E4 +:102F1000FFF7B8FF02F1A80100F58060FFF7B2FFEC +:102F200002F1C40100F58060FFF7ACFF02F1E0019F +:102F300000F58060FFF7A6FFBDE8084000F0EEB89E +:102F400000380240000002407436000808B500F066 +:102F500059FAFEF701FCFFF793F8BDE80840FEF7C9 +:102F60006FBE000070470000EFF3098305494A6B0C +:102F700022F001024A63683383F30988002383F354 +:102F80001188704700EF00E0302080F3118862B6AE +:102F90000C4B0D4AD96821F4E0610904090C0A437D +:102FA000DA60D3F8FC20094942F08072C3F8FC20B3 +:102FB0000A6842F001020A602022DA7783F82200D0 +:102FC000704700BF00ED00E00003FA05001000E0CC +:102FD00010B5302383F311880E4B5B6813F4006344 +:102FE00014D0F1EE103AEFF30984683C4FF080738F +:102FF000E361094BDB6B236684F30988FEF78CFBE6 +:1030000010B1064BA36110BD054BFBE783F311889C +:10301000F9E700BF00ED00E000EF00E02F0300083B +:10302000320300080F4B1A6C42F001021A641A6E48 +:1030300042F001021A660C4A1B6E936843F00103CA +:1030400093604FF0804353229A624FF0FF32DA626E +:1030500000229A615A63DA605A6001225A611A604A +:10306000704700BF00380240002004E04FF080426B +:1030700008B51169D3680B40D9B2C9439B071161E8 +:1030800007D5302383F31188FEF77CFB002383F3FD +:10309000118808BD1F4B1A696FEAC2526FEAD252FB +:1030A0001A611A69C2F308021A614FF0FF301A69F7 +:1030B0005A69586100215A6959615A691A6A62F05D +:1030C00080521A621A6A02F080521A621A6A5A6AA6 +:1030D00058625A6A59625A6A1A6C42F080521A64EB +:1030E0001A6E42F080521A661A6E0B4A106840F44B +:1030F00080701060186F00F44070B0F5007F1EBF44 +:103100004FF4803018671967536823F400735360D5 +:1031100000F054B90038024000700040334B4FF0CB +:1031200080521A64324A4FF4404111601A6842F0EA +:1031300001021A601A689107FCD59A6822F003020E +:103140009A602A4B9A6812F00C02FBD1196801F0C0 +:10315000F90119609A601A6842F480321A601A689C +:103160009203FCD55A6F42F001025A671F4B5A6F07 +:103170009007FCD51F4A5A601A6842F080721A60A4 +:103180001B4A53685904FCD5184B1A689201FCD5A8 +:10319000194A9A60194B1A68194B9A42194B21D156 +:1031A000194A1168194A91421CD140F205121A605D +:1031B000144A136803F00F03052BFAD10B4B9A68DE +:1031C00042F002029A609A6802F00C02082AFAD1D0 +:1031D0005A6C42F480425A645A6E42F480425A66F3 +:1031E0005B6E704740F20572E1E700BF00380240B5 +:1031F000007000400854400700948838002004E024 +:1032000011640020003C024000ED00E041C20F418B +:10321000074A08B5536903F00103536123B1054A16 +:1032200013680BB150689847BDE80840FFF7D0BE5F +:10323000003C0140E02D0020074A08B5536903F027 +:103240000203536123B1054A93680BB1D0689847D4 +:10325000BDE80840FFF7BCBE003C0140E02D002067 +:10326000074A08B5536903F00403536123B1054AC3 +:1032700013690BB150699847BDE80840FFF7A8BE35 +:10328000003C0140E02D0020074A08B5536903F0D7 +:103290000803536123B1054A93690BB1D06998477C +:1032A000BDE80840FFF794BE003C0140E02D00203F +:1032B000074A08B5536903F01003536123B1054A67 +:1032C000136A0BB1506A9847BDE80840FFF780BE0B +:1032D000003C0140E02D0020164B10B55C6904F461 +:1032E00078725A61A30604D5134A936A0BB1D06A67 +:1032F0009847600604D5104A136B0BB1506B984782 +:10330000210604D50C4A936B0BB1D06B9847E205AC +:1033100004D5094A136C0BB1506C9847A30504D52A +:10332000054A936C0BB1D06C9847BDE81040FFF78D +:103330004FBE00BF003C0140E02D0020194B10B5EE +:103340005C6904F47C425A61620504D5164A136D27 +:103350000BB1506D9847230504D5134A936D0BB1FB +:10336000D06D9847E00404D50F4A136E0BB1506E30 +:103370009847A10404D50C4A936E0BB1D06E9847C0 +:10338000620404D5084A136F0BB1506F98472304A9 +:1033900004D5054A936F0BB1D06F9847BDE8104034 +:1033A000FFF716BE003C0140E02D002008B5FFF7F6 +:1033B0005DFEBDE80840FFF70BBE0000062108B522 +:1033C0000846FFF71DFB06210720FFF719FB062122 +:1033D0000820FFF715FB06210920FFF711FB062146 +:1033E0000A20FFF70DFB06211720FFF709FB062136 +:1033F0002820FFF705FBBDE8084007211C20FFF748 +:10340000FFBA000008B5FFF745FE00F00BF8FDF726 +:103410008DFEFDF765FDFFF7A5FDBDE80840FFF750 +:10342000CFBC00000023054A19460133102BC2E926 +:10343000001102F10802F8D1704700BFE02D002012 +:10344000034611F8012B03F8012B002AF9D170472C +:1034500053544D3332463F3F3F0053544D33324671 +:103460003430780053544D3332463432780053545C +:103470004D333246343436585800000001203300B2 +:103480000010410001105A000310590007103100CC +:103490000000000050340008130400005A340008F3 +:1034A0001904000064340008210400006E34000890 +:1034B000000000005D0E0008490E0008850E00089F +:1034C000710E00087D0E0008690E0008550E0008F8 +:1034D000410E0008910E00080000000001000000ED +:1034E0000000000063300000E4340008F0230020F6 +:1034F000002600204172647550696C6F740025428B +:103500004F415244252D424C002553455249414CD0 +:1035100025000000020000000000000079100008F3 +:10352000E510000840004000A02A0020B02A00203A +:103530000200000000000000030000000000000086 +:10354000291100080000000010000000C02A00201F +:10355000000000000100000000000000682D0020B5 +:1035600001010200DD1B0008ED1A0008891B00089C +:103570006D1B0008430000007C3500080902430071 +:10358000020100C03209040000010202010005240A +:103590000010010524010001042402020524060094 +:1035A00001070582030800FF09040100020A000068 +:1035B00000070501024000000705810240000000ED +:1035C00012000000C835000812011001020000407E +:1035D000091241570002010203010000040309041B +:1035E00025424F41524425004B616B75746546344A +:1035F0002D57696E670030313233343536373839FC +:1036000041424344454600000040000000400000A5 +:103610000040000000400000000001000000020027 +:103620000000020000000200000002000000020092 +:103630000000020000000200000000006D120008FF +:1036400025150008D115000840004000C82D0020B5 +:10365000C82D002001000000D82D002080000000AF +:1036600040010000030000006D61696E0069646C38 +:10367000650000000401802A00000000AAAAAAAA8E +:1036800000010024FDFF00000000000000A00A006F +:103690000000000000000000AAAAAAAA0000000082 +:1036A000FFFF0000000000000000000000000050CC +:1036B00000000000AAAAAAAA00000050FFFF000014 +:1036C00000000000000000000000000000000000FA +:1036D000AAAAAAAA00000000FFFF00000000000044 +:1036E000000000000000000000000000AAAAAAAA32 +:1036F00000000000FFFF00000000000000000000CC +:103700000000000000000000AAAAAAAA0000000011 +:10371000FFFF0000000000000000000000000000AB +:1037200000000000AAAAAAAA00000000FFFF0000F3 +:103730000000000000000000000000000000000089 +:103740000A0000000000000003000000000000006C +:103750000000000000000000000000000000000069 +:103760000000000000000000000000000000000059 +:103770001E1500000000000000400F0000000000C7 +:10378000FF009600000000080096000000000800FE +:1037900004000000DC35000800000000000000000C +:1037A0000000000000000000000000000000000019 +:00000001FF diff --git a/Tools/bootloaders/LongBowF405WING_bl.bin b/Tools/bootloaders/LongBowF405WING_bl.bin new file mode 100755 index 00000000000000..fbecaa9908c16b Binary files /dev/null and b/Tools/bootloaders/LongBowF405WING_bl.bin differ diff --git a/Tools/bootloaders/MFE_POS3_CAN_bl.bin b/Tools/bootloaders/MFE_POS3_CAN_bl.bin new file mode 100644 index 00000000000000..524a52a4c89cfb Binary files /dev/null and b/Tools/bootloaders/MFE_POS3_CAN_bl.bin differ diff --git a/Tools/bootloaders/MFT-SEMA100_bl.bin b/Tools/bootloaders/MFT-SEMA100_bl.bin new file mode 100755 index 00000000000000..5ecc1783617e9b Binary files /dev/null and b/Tools/bootloaders/MFT-SEMA100_bl.bin differ diff --git a/Tools/bootloaders/MUPilot_bl.bin b/Tools/bootloaders/MUPilot_bl.bin new file mode 100755 index 00000000000000..e8813352d60ec6 Binary files /dev/null and b/Tools/bootloaders/MUPilot_bl.bin differ diff --git a/Tools/bootloaders/MatekG474-DShot_bl.bin b/Tools/bootloaders/MatekG474-DShot_bl.bin new file mode 100755 index 00000000000000..84d30793a39581 Binary files /dev/null and b/Tools/bootloaders/MatekG474-DShot_bl.bin differ diff --git a/Tools/bootloaders/MatekG474-DShot_bl.hex b/Tools/bootloaders/MatekG474-DShot_bl.hex new file mode 100644 index 00000000000000..1672d3204c12db --- /dev/null +++ b/Tools/bootloaders/MatekG474-DShot_bl.hex @@ -0,0 +1,1197 @@ +:020000040800F2 +:1000000000070020F101000845270008FD26000830 +:1000100025270008FD2600081D270008F301000819 +:10002000F3010008F3010008F3010008313700086C +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008253A00084D3A0008B2 +:10006000753A00089D3A0008C53A0008F3010008F7 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008AD260008C1260008ED3A00086B +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C13B0008F3010008F3010008F301000848 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000513B0008F3010008F3010008F301000888 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008D5260008E92600084D +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000990F00080000000000000000000000005F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F052F912 +:1002600004F032FA4FF055301F491B4A91423CBF0F +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F030F904F052FACD +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F018B9000700200023002040 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000004A000800230020A4230020A823002097 +:1003000004660020E0010008E4010008E4010008A0 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F080FDFEE703F067 +:1003400009FD00DFFEE70000F8B500F03BFE04F019 +:100350007BF8074604F0CCF80546C0BB294B9F420A +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F058FC2E4642F2107400F06F +:1003800059FC08B10024264601F00EF948B30320B9 +:1003900000F03EF80024264635B11C4B9F4203D0A6 +:1003A00004F09EF800242646002004F057F80EB111 +:1003B00000F044F800F070FC02F0CCF90546C4B936 +:1003C00000F0BEFC4FF47A7003F03EFDF7E72E46D6 +:1003D0000024D4E704460126D1E7064640F6C414BB +:1003E000CDE740F6C4139C4204BF4FF47A74012653 +:1003F000D2E702F0AFF9431BA342E1D900F01EF8A7 +:10040000DAE700BF010007B0000008B0263A09B0E3 +:10041000084B187003280CD8DFE800F00805020824 +:10042000022000F02DBE022000F020BE024B002270 +:100430005A607047A8230020AC23002010B501F0BB +:10044000B3F830B1234B03221A70234B00225A60B9 +:1004500010BD224B224A1C4619680131F8D00433E2 +:100460009342F9D16268A242F2D31E4B9B6803F11A +:10047000006303F510439A42EAD204F003F804F053 +:1004800015F8002000F0B8FD0220FFF7C1FF164B61 +:100490009A6D00229A65996F9A67996FD96DDA659E +:1004A000D96FDA67D96F196E1A66D3F88010C3F85E +:1004B0008020D3F8803072B64FF0E0233021C3F8AB +:1004C000084DD4E9003281F311889D4683F30888F2 +:1004D0001047BDE7A8230020AC23002000900008AF +:1004E000209000080023002000100240094A1368F1 +:1004F00049F2690099B21B0C00FB01331360064BF3 +:10050000186844F2506182B2000C01FB02001860CE +:1005100080B27047142300201023002010B5002162 +:100520001022044600F0C8FD034B03CB206061603D +:100530001868A06010BD00BF9075FF1F2DE9F04145 +:10054000ADF5507D0DF13C086EAC40F275120746DA +:100550000D4610A80021C8F8001000F0ADFD4FF4C2 +:10056000C4720021204600F0A7FD02F0F3F8274BEB +:100570004FF47A72B0FBF2F0186093E807000223A0 +:1005800084E807000DF5ED702382FFF7C7FF49F2FD +:1005900004231F49238407A804F044F91D2384F889 +:1005A00032310DF2EB2207AB0DF1340C1E4603CEB7 +:1005B000664510605160334602F10802F6D130689A +:1005C00010603379137141460122204600F0C0FDCE +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E06A3D3E900232B +:1005F000384602F06DFC0DF5507DBDE8F08100BF7E +:10060000AFF300809E6AC421818A46EEB4230020A5 +:10061000344800082DE9F0412C4C237ADAB08046AA +:100620000D465BBB27A9284600F0B4FE074600280C +:1006300042D19DF89D60C82E3ED801464FF4A66277 +:10064000204600F039FD4FF48073C4F8F8314FF4C0 +:100650000073C4F80C334FF44073C4F820343246AE +:100660000DF19E0104F1090000F014FD26449DF8EF +:100670009C30777223720BB9EB7E237281220021AA +:1006800006AC27A800F018FD0122214627A800F09B +:10069000C7FE00230393AB7E029305F1190380B2DA +:1006A00001932823CDE904400093E97E05A3D3E913 +:1006B0000023404602F00CFC5AB0BDE8F08100BFB8 +:1006C000AFF3008026417272DF25D7B7805D00202E +:1006D000F0B5254E4FF48A7505FB0065F1B096F82C +:1006E000D83085F8DC300024D822214685F8E8404F +:1006F0003AA800F0E1FC06F1090000F0D5FCD5F8BD +:10070000E4308DF8F000C2B206AF06F109010DF138 +:10071000F100CDE93A3400F0BDFC394601223AA897 +:1007200000F0B4FE80B2CDE9047008230127CDE9C2 +:10073000023706F1D803019330230093317A0B4836 +:1007400007A3D3E9002302F0C3FBA04206DD02F0B9 +:1007500001F8C5F8E000384671B0F0BD2046FBE76F +:1007600078F6339F93CACD8D805D0020CC33002076 +:100770002DE9F04F264FDFF8A480264E87B038468B +:1007800002F0D2FB034600283AD00024CDE903440E +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B681C4D43F000430293A146F9 +:1007B000A2462B68D3F810B001F0CEFF10EB080270 +:1007C00041F100032846CDF800A002A9D84704F55E +:1007D000A6640028C8BF49F00109B4F5266F05F5E5 +:1007E000A655E6D1B9F1000F05D0384602F0A0FBBE +:1007F00086F800A0C3E73378072B04D801333370A1 +:1008000007B0BDE8F08F024802F092FBF8E700BFA6 +:10081000CC330020B56200200034002040420F009D +:1008200070B50D4614461E4602F0AEFA50B9022EBF +:1008300010D1012C0ED112A3D3E90023C5E9002366 +:10084000012007E0282C10D005D8012C09D0052C58 +:100850000FD0002070BD302CFBD10BA3D3E90023B7 +:10086000ECE70BA3D3E90023E8E70BA3D3E90023CC +:10087000E4E70BA3D3E90023E0E700BFAFF3008078 +:10088000401DA12026812A0B78F6339F93CACD8D77 +:100890009E6AC421818A46EE26417272DF25D7B74F +:1008A000F017304A39059E5638B505460E4C0021E2 +:1008B000013500F0C3FBA4F82C55B4F82C0500F06A +:1008C000A5FB78B1B4F82C0500F0B0FB014648B99F +:1008D000B4F82C0500F0B2FBB4F82C350133A4F8C1 +:1008E0002C35EAE738BD00BF805D0020F8B50D4C1F +:1008F0000D4F0226A4F5805343F8307C237E3BB98C +:1009000065692DB1284600F0CDFE284603F040FF72 +:10091000204600F0C7FE012EA4F5A65400D1F8BD74 +:100920000126E7E7F0580020944800082DE9F04F31 +:100930008FB000AF05460C4602F026FA002849D1D8 +:10094000237E022B1BD1E38A012B18D101F002FF79 +:100950000646FFF7CBFD03464FF4C870DFF8C482AC +:10096000B3FBF0F206F5167602FB103316FA83F3AA +:10097000C8F80030E37E33B9A34B00221A703C372D +:10098000BD46BDE8F08F07F12401204600F0B6FC1B +:100990000028F4D107F11400FFF7C0FD97F82640B6 +:1009A00007F11401224607F1270003F009FF002890 +:1009B000E2D10F2C08D8944B1C70D8F80030A3F566 +:1009C0001673C8F80030DAE797F82410284602F0CA +:1009D000D3F9D4E7E38A282B2BD010D8012B23D0CE +:1009E000052BCCD1BFF34F8F8849894BCA6802F4DD +:1009F000E0621343CB60BFF34F8F00BFFDE7302BA6 +:100A0000BDD1844EE17E327A9142B8D1607E3146CA +:100A1000002291F8DC50854200F0A5800132042AC2 +:100A200001F58A71F5D1AAE721462846FFF786FD30 +:100A3000A5E721462846FFF7EDFDA0E7B2F8EC5008 +:100A40007B6005F103094FEA99094FEA8902D11D3C +:100A5000C908A8EBC1039D46EB460021584600F0AB +:100A60002BFB04F1EE012A463144584600F012FBFC +:100A70007B6813B9012000F0BFFA96F8D20000F0AD +:100A8000C5FA044630B9307200F0E0FA204600F0B2 +:100A9000B3FAB1E0D6F8D4203AB996F8D200B6F855 +:100AA0002C25824201D8FFF7FFFED6F8D4202A4435 +:100AB000944208D296F8D200B6F82C250130824232 +:100AC00001D8FFF7F1FE70685FFA89F2594600F02D +:100AD000FBFA08B9C54679E0726896F8D2002A4454 +:100AE0007260D6F8D42005EB0209C6F8D49000F065 +:100AF0008DFA814509D396F8D220D6F8D400013278 +:100B0000001B86F8D220C6F8D400FF2D0FD8002491 +:100B1000347200F09BFA204600F06EFA00F044FDBB +:100B20003D4B188108B9FFF789FCC54627E7BB682C +:100B300096F8D9000AFB0362FB68D2F8E41082F849 +:100B4000E83001F58061C2F8E030C2F8E410FFF748 +:100B5000BFFDFFF70DFE96F8D920013202F0030227 +:100B600086F8D920B6E74FF48A7A0AFB02F505F138 +:100B7000EA013144204600F0BBFCF86000287FF415 +:100B8000FEAE3544012285F8E82001F0E3FDD5F8FA +:100B9000E020D6ED007ADFED216A801A192838BFEF +:100BA000192040F6B832904228BF1046B8EE677A56 +:100BB00007EE900AF8EEE77A67EEA67ADFED186A9C +:100BC000E7EE267AFCEEE77AC6ED007A96F8D930A1 +:100BD000BB60BA6873680AFB02F4321992F8E81035 +:100BE00059B1D2F8E4108B42E8463FF427AF002118 +:100BF00082F8E810C2F8E010C5467368064A9B0AFE +:100C000001331381BBE600BFC533002000ED00E0D7 +:100C10000400FA05805D0020B4230020CDCCCC3D3B +:100C20006666663FC8330020014B1870704700BFEE +:100C3000C023002038B54FF00054134B22689A426D +:100C400020D1124B627D12481A70237D03724FF43B +:100C50008073C0F8F8314FF40073C0F80C330025EE +:100C60004FF44073C0F820340A49C0F8E450C92258 +:100C7000093000F00FFAE0222946204600F01CFA65 +:100C8000012038BD0020FCE79AAD44C5C0230020F8 +:100C9000805D00201600002037B500F085FC1F4C59 +:100CA0001F4D2049288102236B71236801225B6854 +:100CB0002046984704F580531A49D3F8C0340122DE +:100CC0005B6804F5A650984700230193164B17491B +:100CD00000931748174B4FF4805202F025F8164B3B +:100CE000197811B1124802F047F801F033FD0446BB +:100CF000FFF7FCFB4FF4C873B0FBF3F202FB1303E6 +:100D000004F5167010FA83F00C4B186003F0F0FB3A +:100D100008B10F232B8103B030BD00BF0034002089 +:100D2000B423002040420F0021080008C423002003 +:100D3000CC3300202D090008C0230020C833002038 +:100D40002DE9F04F2DED028B002493B00DF12C080E +:100D50009FED818BDFF83C92FFF70AFD0A94ADF816 +:100D600034400B94C8F804400026814DDFF804B2EB +:100D7000374601238DF81C302B688DF81D408DED12 +:100D8000008B0DF11D02D3F808A007A90023284607 +:100D9000D0479DF81CA0BAF1000F24D0D9F8143028 +:100DA00083F40053C9F81430102200210EA800F07B +:100DB00083F92B6808AA5F690AA90DF11E0328466A +:100DC000B84798E803000FAB83E803009DF8343080 +:100DD0008DF844300A9B0E930EA9DDE9082358468E +:100DE00002F084FA574606F5A666B6F5266F05F5B5 +:100DF000A655BED1002FB7D15E4801F0C5FF00282F +:100E00003FD15D4E01F0A6FC3368984239D301F022 +:100E1000A1FC0546FFF76AFB4FF4C873B0FBF3F281 +:100E200002FB130305F5167010FA83F03060534E81 +:100E30008DF82870377817B901238DF82830C7F15D +:100E40001005EDB20EA8FFF769FB062D28BF062599 +:100E50000EAB2A46D9190DF1290000F01BF90AAB97 +:100E60000393182302930135454B0193EDB20123FF +:100E70000093404804953AA3D3E9002301F0CAFF48 +:100E8000347001F067FC3F4A3F4D1368C31AB3F555 +:100E90007A7F2FD3106001F05FFC02460B46354885 +:100EA00002F050F8334801F06FFF18B32B7A374E39 +:100EB000002B14BF03230223737101F04BFC0EAF10 +:100EC0004FF47A730122B0FBF3F0394630603046BC +:100ED00000F0ECF9182302932D4B019380B240F2FD +:100EE0005513CDE90370009322481FA3D3E90023D3 +:100EF00001F090FF2B7A93B101F02CFC00260746FD +:100F00004FF48A7895F8D900304400F0030008FBCC +:100F1000005393F8E82072B10136042EF2D1C820B4 +:100F200002F092FF2B7A002B7FF410AF13B0BDECD0 +:100F3000028BBDE8F08FD3F8E02042B12B68FA2B8A +:100F400038BFFA23BA1A0533B2EB430FE4D3FFF7E5 +:100F5000BFFB0028E0D1E2E7000000000000000035 +:100F6000401DA12026812A0BF1C6A7C1D068080F19 +:100F700000340020CC330020C8330020C5330020CB +:100F8000C4330020B0620020805D0020B423002024 +:100F9000B46200200008004810B5074C204600F05D +:100FA000B3FE04F5A65000F0AFFEBDE81040034AC2 +:100FB0000349002003F0E6BB00340020F462002067 +:100FC000ED08000870B503F0DBF8094E094D3080DC +:100FD000002428683388834208D903F0CDF82B68B1 +:100FE00004440133B4F5104F2B60F2D370BD00BF41 +:100FF000E4620020B862002003F07CB900F10060D8 +:10100000920000F5104003F0FFB80000054B1A688D +:10101000054B1B889B1A834202D9104403F0ACB8DD +:1010200000207047B8620020E4620020024B1B6879 +:10103000184403F0A9B800BFB8620020024B1B6837 +:10104000184403F0B3B800BFB8620020064991F815 +:10105000243033B10023086A81F824300822FFF7D6 +:10106000CDBF0120704700BFBC620020022802BF34 +:10107000024B4FF000529A61704700BF00080048D1 +:10108000022802BF024B4FF400529A61704700BF22 +:101090000008004810B50023934203D0CC5CC45430 +:1010A0000133F9E710BD000003460246D01A12F9D9 +:1010B000011B0029FAD1704702440346934202D033 +:1010C00003F8011BFAE770472DE9F8431F4D14465A +:1010D00095F824200746884652BBDFF870909CB3F1 +:1010E00095F824302BB92022FF2148462F62FFF7C4 +:1010F000E3FF95F82400C0F10802A24228BF22466F +:10110000D6B24146920005EB8000FFF7C3FF95F889 +:101110002430A41B1E44F6B2082E17449044E4B2B7 +:1011200085F82460DBD1FFF791FF0028D7D108E0D4 +:101130002B6A03EB82038342CFD0FFF787FF00289F +:10114000CBD10020BDE8F8830120FBE7BC62002082 +:101150002DE9F8430D46044600219046284640F20A +:101160007912FFF7A9FF234620220021284602F02A +:101170005FF8231D02222021284602F059F8631D42 +:1011800003222221284602F053F8A31D0322252121 +:10119000284602F04DF804F10803102228212846C1 +:1011A00002F046F804F1100308223821284602F024 +:1011B0003FF804F1110308224021284602F038F8D4 +:1011C00004F1120308224821284602F031F804F104 +:1011D000140320225021284602F02AF804F11803B3 +:1011E00040227021284602F023F804F1200308224F +:1011F000B021284602F01CF804F121030822B8218E +:10120000284602F015F804F12207C0263B46314675 +:1012100008222846083602F00BF8B6F5A07F07F141 +:101220000107F3D1314604F132030822284601F0C8 +:10123000FFFF94F83260002704F13309F900BE4241 +:1012400001F5A4711FD8F70007F5A476B8F1000FD7 +:1012500008D1314604F599730722284601F0E8FFCA +:1012600007F24F1694F83201502828BF5020074645 +:1012700004EB0009B046A1450DD106EBC7000730CD +:10128000C008BDE8F88309EB07030822284601F0EF +:10129000CFFF0137D2E704F2331341460822284634 +:1012A00001F0C6FF08F108080134E4E713B504466D +:1012B0000846002101602346C0F803102022019057 +:1012C00001F0B6FF0198231D0222202101F0B0FF9A +:1012D0000198631D0322222101F0AAFF0198A31D9A +:1012E0000322252101F0A4FF019804F10803102234 +:1012F000282101F09DFF072002B010BDF7B5047F43 +:1013000005460E462CB1838A122B02D9012003B068 +:10131000F0BD0023194607220096284601F04CFE36 +:10132000731C0093012200230721284601F044FE8C +:10133000D4B9B31C0093052223460821284601F0A6 +:101340003BFE0D24B378102BE0D83746B278BB1B98 +:10135000934210D32B7FA88A0734E408B3B98442A0 +:1013600094BF00200120D2E7AB8ADB00083BDB08FA +:10137000B3700824E6E7FB1C0093214600230822F3 +:10138000284601F019FE08340137DFE7201A18BF9C +:101390000120BCE7F7B5047F05460E462CB1838AD1 +:1013A000CA2B02D9012003B0F0BD002319460096D4 +:1013B0000822284601F000FE731CD4B908220093CD +:1013C00011462346284601F0F7FD10247378C82BF8 +:1013D000E8D8012372785F1C013B934210D32B7F26 +:1013E000A88A0734E408B3B9844294BF00200120DE +:1013F000D9E7AB8ADB00083BDB0873700824E5E71C +:10140000F3190093214600230822284601F0D4FD59 +:1014100008343B46DEE7201A18BF0120C3E700006E +:101420002DE9F8430D460446164600218122284640 +:10143000FFF742FE234608220021284601F0F8FE6D +:10144000C6B9631C07220821284601F0F1FE0F26C9 +:1014500094F901306778002BB8BF7F2704EB0709A8 +:10146000B0464C4508D10736082010FB0760C0087D +:10147000BDE8F8830826EBE7A31C4146082228466E +:1014800001F0D6FE08F108080134EAE72DE9F04141 +:101490000D46044616460021CE222846FFF70CFED4 +:1014A000234628220021284601F0C2FEBEB904F1DD +:1014B000080308222821284601F0BAFE302614F835 +:1014C000080FC82828BFC82080460027B84506EB6B +:1014D000C70106D806EBC800C008BDE8F081282681 +:1014E000EDE70137E3190822284601F0A1FEEDE7F8 +:1014F000F7B5047F05460E4634B1838AB3F5827F83 +:1015000002D9012003B0F0BD009601231022002172 +:10151000284601F051FDDCB9B31C00930922234693 +:101520001021284601F048FD19247388B3F5807F07 +:10153000E7D837467288BB1B934210D32B7FA88A0B +:101540000734E408B3B9844294BF00200120D9E7EE +:10155000AB8ADB00103BDB0873801024E5E73B1D02 +:101560000093214600230822284601F025FD083477 +:101570000137DFE7201A18BF0120C3E730B5094D56 +:101580000A4491420DD011F8013B5840082340F322 +:101590000004013B2C4013F0FF0384EA5000F6D115 +:1015A000EFE730BD2083B8EDF7B5384A10685168D1 +:1015B0006B4603C36A4636493648082303F010F9E0 +:1015C0000446002833D10A25334A106851686B4617 +:1015D00003C36A4631492F48082303F001F9044642 +:1015E000002849D00369B3F5EE2F45D8B0F866104E +:1015F00040F2924291423FD1294A024402F15C01F9 +:101600008B4239D35C3B234900209E1AFFF7B6FF7B +:101610003246074604F164010020FFF7AFFFA368DC +:101620009F4229D1E368984208BF002524E003695E +:10163000B3F5EE2F27D8418B40F29242914220D150 +:10164000174A024402F110018B4218D3103B114992 +:1016500000209D1AFFF792FF2A46064604F1180162 +:101660000020FFF78BFFA3689E4202D1E3689842F7 +:1016700001D00D25A8E70025284603B0F0BD1025B0 +:10168000A2E70C25A0E70B259EE700BF5448000801 +:10169000DC6F0700009000085D480008906F0700AD +:1016A0000870FFF710B5037C044613B9006803F017 +:1016B0007FF8204610BD00000023BFF35B8FC3609E +:1016C000BFF35B8FBFF35B8F8360BFF35B8F7047AC +:1016D000BFF35B8F0068BFF35B8F704770B5054643 +:1016E0000C30FFF7F5FF05F1080604463046FFF71A +:1016F000EFFFA04206D930466D68FFF7E9FF2544A9 +:10170000281A70BD3046FFF7E3FF201AF9E7000002 +:1017100070B50546406898B105F10800FFF7D8FF9D +:1017200005F10C0604463046FFF7D2FF84423046EE +:1017300094BF6D680025FFF7CBFF013C2C44201AB5 +:1017400070BD000038B50C460546FFF7C7FFA04244 +:1017500010D305F10800FFF7BBFF04446868B4FB31 +:10176000F0F100FB1144BFF35B8F0120AC60BFF3CD +:101770005B8F38BD0020FCE72DE9F0411446074699 +:101780000D46FFF7C5FF844228BF0446D4B1B846D2 +:1017900058F80C6B4046FFF79BFF304428604046EA +:1017A0007E68FFF795FF331A9C4203D86C600120D6 +:1017B000BDE8F0816B60A41B3B68AB602044E8602F +:1017C0000220F5E72046F3E738B50C460546FFF75B +:1017D0009FFFA04210D305F10C00FFF779FF0444EE +:1017E0006868B4FBF0F100FB1144BFF35B8F01208C +:1017F000EC60BFF35B8F38BD0020FCE72DE9FF41B3 +:10180000884669460746FFF7B7FF6C4606B204EB09 +:10181000C6060025B44209D06268206808EB0501BD +:10182000FFF738FC636808341D44F3E7294638465F +:10183000FFF7CAFF284604B0BDE8F081F8B50546B9 +:101840000C300F46FFF744FF05F10806044630460A +:10185000FFF73EFFA042304688BF6C68FFF738FFB5 +:10186000201A386020B130462C68FFF731FF204441 +:10187000F8BD000073B5144606460D46FFF72EFF6F +:10188000844228BF04460190DCB101A93046FFF72D +:10189000D5FF019B33B93268C5E90233C5E900249D +:1018A00001200CE09C4238BF0194286001986860D8 +:1018B0008442F5D93368AB60241AEC60022002B090 +:1018C00070BD2046FBE700002DE9FF410F46694649 +:1018D000FFF7D0FF6C4600B204EBC0050026AC4217 +:1018E00009D0D4F8048054F8081BB8194246FFF711 +:1018F000D1FB4644F3E7304604B0BDE8F081000078 +:1019000038B50546FFF7E0FF044601462846FFF7D5 +:1019100019FF204638BD00007047000010B4134680 +:10192000026814680022A4465DF8044B604700007A +:1019300000F5805090F859047047000000F5805081 +:1019400090F852047047000000F5805090F9580458 +:101950007047000050207047302383F3118800F552 +:101960008052D2F89C34D2F898041844D2F89434B7 +:101970001844D2F87C341844D2F88C341844D2F885 +:1019800088341844002383F31188704700F5805091 +:10199000C0F854140120704738B5C26A936923F027 +:1019A00001039361044600F0D5FE0546E36A9B6996 +:1019B000DB0706D500F0CEFE431BFA2BF6D900203C +:1019C00004E004F58054012084F8520438BD00007E +:1019D0002DE9F04F0C4600F5805185B01F4691F877 +:1019E0005234BDF83890054690469BB1D1F8783412 +:1019F0000133C1F878342368980006D4237B082B80 +:101A00000BD9627B0AB10F2B07D9D1F87C34013393 +:101A1000C1F87C344FF0FF3010E0302383F311889D +:101A2000EB6AD3F8C42012F4001B0AD0D1F880343A +:101A30000133C1F88034002080F3118805B0BDE87F +:101A4000F08FD3F8C4302068C3F3014A6B6A482290 +:101A5000002812FB0A33B4BF40F0804080041860B5 +:101A60002268520044BF40F000501860207B4FEACB +:101A70000A6242EA00425A60607B4FEA4A1610B39B +:101A800042F440125A60D1F8B0240132C1F8B024B7 +:101A9000AA1902F58352117B41F020011173207BBA +:101AA000039300F0B3FE039B033080105FFA8BF2C8 +:101AB00082420BF1010B0DDA04EB820103EB82028F +:101AC00049689160F2E7AA1902F58352117B60F32D +:101AD0004511E3E7EB6A012202FA0AF2C3F8CC20CF +:101AE00005EB4A11AB1903F5825301F58251C3E9A5 +:101AF00004871831234604F10C0253F8040B41F813 +:101B0000040B9342F9D11B880B802E4441F26803E9 +:101B100046F803A006F5805609F0030396F86C20FA +:101B200043F0100322F01F02134386F86C300023A9 +:101B300083F31188CDF8009042463B462146284663 +:101B400000F02AFE012079E713B500F580540191D9 +:101B5000606CFFF7DDFD1F280AD90199606C202217 +:101B6000FFF74CFEA0F120035842584102B010BDCF +:101B70000020FBE708B5302383F3118800F580507F +:101B8000406CFFF799FD002383F3118808BD000026 +:101B900000220260828142608260704710B500229C +:101BA0000023C0E900230023044603810C30FFF723 +:101BB000EFFF204610BD00002DE9F0479A4688B09F +:101BC000074688469146302383F3118807F58054F1 +:101BD0006846FFF7E3FF606CFFF780FD1F282DD9F3 +:101BE000606C20226946FFF78BFE202826D194F8EE +:101BF00052341BB303AD444605AB2E4603CE9E4282 +:101C000020606160354604F10804F6D13068206038 +:101C1000B388A380DDE90023C9E90023BDF80830BB +:101C2000AAF80030002383F3118853464A46414600 +:101C3000384608B0BDE8F04700F09CBD002080F3B6 +:101C4000118808B0BDE8F0872DE9F84F002306465B +:101C5000C0E90133294B46F8303B00F58154054675 +:101C600088463746103438462037FFF797FFA7429B +:101C7000F9D105F580544FF4805326630026C4E95A +:101C80000D366764012305F5835705F5A359E6630F +:101C900084F8403084F84830103709F110094FF0CB +:101CA000000A4FF0000B47E908ABA7F11800FFF757 +:101CB0006FFF203747F8286C4F45F4D1B8F1010F7A +:101CC00084F85884A4F85A64A4F85C64A4F85E64A8 +:101CD00084F86064A4F86264A4F86464A4F8666498 +:101CE00084F8686402D9064800F02EFD054B53F8CD +:101CF0002830EB622846BDE8F88F00BF9448000802 +:101D0000684800088448000810B5044B1978044658 +:101D10004A1C1A70FFF798FF204610BDF1620020A0 +:101D20002DE9F84315460C4600295CD0022001F04D +:101D300073FE2E49B0FBF4F78C428CBF0A211121AF +:101D40004B1EB7FBF1F601FB1671DAB221B1022B83 +:101D50001946F5D8002032E0731EB3F5806FF9D232 +:101D6000C2EBC20808F103014FEAE10EC1F3C7015B +:101D7000A2EB010C0EF101094FF47A735FFA8CF7B4 +:101D80000EFB033E59FA8CFCBEFBFCFCBCF5617FEC +:101D900017DC1FFA8CF34A1C57FA82F27243B0FB2D +:101DA000F2F08442D6D14A1E0F2AD3D87A1E072ACF +:101DB000D0D801202B806E8028716971AF71BDE889 +:101DC000F88308F1FF314FEAE10CC1F3C701521A61 +:101DD0000CF1010ED7B20CFB03335EFA82F2B3FBB7 +:101DE000F2F39BB2D7E70846E9E700BF3F420F0096 +:101DF00030B50D4B0D4D05201C786C438C420ED137 +:101E00005978518099785171D978917119791171F6 +:101E10005B7903EB83035B001380012030BD013845 +:101E200003F10603E8D1F9E7D448000840420F0067 +:101E300038B500F58053114A93F85834D55C4FF407 +:101E40005472554305F1804303F5244304460021B1 +:101E50001846FFF731F90A4B60612B44A361094B27 +:101E60002B44E361084B2B442362084B2B446362F1 +:101E7000E36A0022C3F8C02038BD00BF7C480008D8 +:101E800070A40040B0A4004088A5004078A600409F +:101E90002DE9F04F00F580551F4695F85834022B78 +:101EA00089B004468946904604D90026304609B0D8 +:101EB000BDE8F08FA64A52F8231009B942F8230072 +:101EC000A448C4F80C900178277499B9302383F39F +:101ED0001188A14B9A6D42F000729A659A6B42F09C +:101EE00000729A639A6B22F000729A630123037066 +:101EF00081F3118895F85134CBB9302383F31188DD +:101F0000964A95F85834D35C012B2AD0022B2FD057 +:101F10003BB90321152001F093FE0321162001F0A7 +:101F20008FFE012385F85134002383F31188302379 +:101F300083F31188E26A936923F01003936100F040 +:101F400009FC8246E36A9E6916F0080617D000F085 +:101F500001FCA0EB0A03FA2BF4D9002686F31188C2 +:101F6000A4E70321562001F06BFE03215720D6E79A +:101F70000321582001F064FE03215920CFE79A691C +:101F800042F001029A6100F0E5FB8246E36A9A6939 +:101F9000D00706D400F0DEFBA0EB0A03FA2BF5D93C +:101FA000DBE79A6942F002029A61E36A4FF0000AA5 +:101FB000C3F854A08AF31188686CFFF77DFB04F521 +:101FC000825B0BF1100B202200216846FFF774F8AA +:101FD00002A8FFF7DDFDCDF818A06A460BEB06035B +:101FE0000DF1180E9446BCE80300F44518605960E2 +:101FF000624603F10803F5D1DCF8000018602036D2 +:102000009CF804201A71B6F5806FDCD1002304F52A +:10201000A25285F8503485F853341A324946204686 +:10202000FFF77EFE064690B9E26A936923F001034A +:10203000936100F08FFB0546E36A9B69D9077FF542 +:1020400034AF00F087FB431BFA2BF5D92DE795F849 +:102050005E34C5F86C94591E95F85F34E26A013B12 +:102060001B0243EA416395F8601401390B43B5F84C +:102070005C14013943EA0143D361B8F1000F36D053 +:1020800004F5A352023241462046FFF7B1FE90B953 +:10209000E26A936923F00103936100F05BFB05465C +:1020A000E36A9B69DA077FF500AF00F053FB431B3F +:1020B000FA2BF5D9F9E695F86724C5F87084511E16 +:1020C00095F86824E36A013A120142EA012295F880 +:1020D000661401390A43B5F86414013942EA014231 +:1020E00042F40002DA60E36A4FF420629A64204608 +:1020F000FFF79EFE002385F85934E36A6FF04042F3 +:102100001A65E36A164A5A65E36A44229A65E36AE5 +:102110000722C3F8DC20E36A03229742DA653FF422 +:10212000C5AEE26A936923F00103936100F012FBEC +:102130000746E36A9B69DB0705D500F00BFBC31B71 +:10214000FA2BF6D9B1E6012385F85234AEE600BF8A +:10215000E8620020F0620020001002407C48000885 +:102160009B0008002DE9F04F054689B0904699463E +:10217000002741F2680A00F58056EB6AD3F8D430A4 +:10218000FB40D80751D505EB471252444FEA471B95 +:102190001379190749D4D6F884340133C6F8843446 +:1021A00005F5A553C3E9008913799A0648BFD6F807 +:1021B000B43405EB0B0248BF0133524448BFC6F8A4 +:1021C000B434137943F008031371DB0722D596F872 +:1021D0005334FBB105F58254183468465C44FFF76C +:1021E000DDFC03AB04F1080C206861681A4603C2E9 +:1021F000083464451346F7D120681060A2889A809D +:102200000123ADF808302B68CDE90089DB6B694606 +:1022100028469847D6F8A834D6F854040133C6F8AF +:10222000A83410B103681B6998470137202FA4D147 +:1022300009B0BDE8F08F00002DE9F04F8DB00446E5 +:102240000F4600F089FA82468946002F56D1E36A8C +:10225000D3F89020920141BF04F58051D1F8982421 +:102260000132C1F89824D3F89020160703D100203A +:102270000DB0BDE8F08FD3F89050E669C5F30125A5 +:10228000482303FB0566E8464046FFF781FC3268B9 +:1022900051004ABF22F06043C2F38A4343F0004337 +:1022A000920048BF43F080430093736813F4001317 +:1022B0001FBF04F5805201238DF80D30D2F8B834D9 +:1022C0000EBF8DF80D300133C2F8B834F38803F037 +:1022D0000F038DF80C304FF0000B9DF80C0000F050 +:1022E00095FA5FFA8BF3984220D9F2180CA90B44A7 +:1022F000127A03F82C2C0BF1010BEEE7012FB6D16B +:10230000E36AD3F89820950141BF04F58051D1F8D4 +:1023100098240132C1F89824D3F898201007A6D049 +:10232000D3F89850266AC5F30125A9E7EFB9E36A07 +:10233000C3F8945004A8FFF731FC98E80F0007ADEC +:1023400007C52B800023ADF8183023682046CDE95F +:1023500004A9DB6B04A9984704F5805458B1D4F85C +:1023600090340133C4F8903482E7012F04BFE36A4C +:10237000C3F89C50DEE7D4F894340133C4F89434A5 +:10238000012075E72DE9F04105460F4600F5805420 +:10239000012639462846FFF74FFF10B184F85364F1 +:1023A000F7E7D4F8A834D4F854040133C4F8A834B7 +:1023B00020B10368BDE8F0411B691847BDE8F08112 +:1023C000F0B5C36A1A6C12F47F0F2BD000F580545D +:1023D0001B6CC4F8AC3441F26805002347194FF078 +:1023E000010C00EB43122A445E01117911F0020F37 +:1023F00015D0490713D4B959C66AD6F8C8E00CFA03 +:1024000001F111EA0E0F0AD0C6F8D010117941F08F +:1024100004011171D4F88C240132C4F88C240133E6 +:10242000202BDED1F0BD00002B4B70B51E561B5C7F +:10243000012B2FD8294D2A4A55F8233052F826402F +:102440000BB341B3236D1A060FD58023236500F02B +:1024500083F950EA01020B4602D0013861F1000312 +:10246000024655F82600FFF77DFE236D1B032CD591 +:1024700055F826304FF4002203F5805322650122DF +:1024800083F8592421E001232365082323654FF4B1 +:102490008063236570BD236DDA0702D4236D9B072B +:1024A00006D5032355F8260023650021FFF76AFFB0 +:1024B000236D180702D4236DD90606D5182355F8C5 +:1024C000260023650121FFF75DFF55F82600BDE8D2 +:1024D0007040FFF775BF00BF80480008E862002029 +:1024E0008448000808B5302383F31188FFF768FF9C +:1024F000002383F3118808BDC36AD3F8C40080F4B5 +:102500000010C0F34050704708B5302383F31188A2 +:1025100000F58050406CFFF7E1F8002383F3118849 +:1025200043090CBF0120002008BD000000F58053C6 +:1025300093F8592462B1C16A8A6922F001028A6162 +:10254000D3F89C240132C3F89C24002283F8592438 +:10255000704700002DE9F743302181F3118800F521 +:1025600082511031002541F2680E4FF0010800F54C +:10257000805C00EB45147444267977071CD4F6067A +:102580001AD5D0F82C908E69D9F8C87008FA06F6DA +:102590003E4211D04F6801970F689742019F9F41BB +:1025A0000AD2C9F8D060267946F004062671DCF814 +:1025B00088440134CCF888440135202D01F12001F4 +:1025C000D7D1002383F3118803B0BDE8F083000066 +:1025D000F8B51E46002313700F4605461446FFF754 +:1025E00093FF80F0010038701EB12846FFF784FF8A +:1025F0002070F8BD2DE9F04F85B09946DDE90EA3B6 +:102600000D4602931378019391F800B08046164668 +:1026100000F0A2F82B7804460F4613B93378002B4C +:1026200041D022463B464046FFF794FFFFF75AFF52 +:10263000FFF77CFF4B4632462946FFF7C9FF2B7850 +:1026400033B1BBF1000F03D0012005B0BDE8F08F1E +:10265000337813B1019B002BF6D108F58053039317 +:10266000029B544577EB03031DD2039BD3F854041C +:10267000C8B10368AAEB04011B6898474B46324671 +:1026800029464046FFF7A4FF2B7813B1BBF1000F9A +:10269000DAD1337813B1019B002BD5D100F05CF86F +:1026A00004460F46DCE70020CFE7000008B5002114 +:1026B0000846FFF7B9FEBDE8084001F06DB800001C +:1026C00008B501210020FFF7AFFEBDE8084001F08A +:1026D00063B8000008B500210120FFF7A5FEBDE8A2 +:1026E000084001F059B8000008B501210846FFF77D +:1026F0009BFEBDE8084001F04FB8000000B59BB05C +:10270000EFF3098168226846FEF7C4FCEFF3058306 +:10271000014B9B6BFEE700BF00ED00E008B5FFF743 +:10272000EDFF000000B59BB0EFF309816822684619 +:10273000FEF7B0FCEFF30583014B5B6BFEE700BFD8 +:1027400000ED00E0FEE700000FB408B5029801F0CC +:102750002BFBFEE701F014BE01F0F6BD13B56C468D +:1027600084E80600031D94E8030083E805000120C7 +:1027700002B010BD73B58568019155B11B885B0728 +:1027800007D4D0E900369B6B9847019AC1B2304616 +:10279000A847012002B070BDF0B5866889B0054633 +:1027A0000C465EB1BDF838305B070AD4D0E900377B +:1027B0009B6B98472246C1B23846B047012009B00A +:1027C000F0BD00220023CDE900230023ADF808303E +:1027D0000A4603AB01F10806106851681C4603C4A1 +:1027E0000832B2422346F7D1106820609288A28056 +:1027F000FFF7B2FF0423ADF808302B68CDE90001E4 +:10280000DB6B694628469847D8E70000082817D9A7 +:1028100009280CD00A280CD00B280CD00C280CD07E +:102820000D280CD00E2814BF4020302070470C20FB +:1028300070471020704714207047182070472020E0 +:10284000704700002DE9F041456A15B94162BDE8C5 +:10285000F0814B6823F06047C3F38A464FEAD37E8A +:10286000C3F3807816EA230638BF3E46AC462B46B3 +:102870005A68BEEBD27F22F060440AD0002A18DAF0 +:10288000A40CB44217D19D420FD10D60DEE7134670 +:10289000EEE7A74207D102F08044C2F380724245BE +:1028A0000BD054B1EFE708D2EDE7CCF800100B6085 +:1028B000CDE7B44201D0B442E5D81A689C46002A5C +:1028C000E5D11960C3E700002DE9F047089D01F04C +:1028D00007044FEAD508224405F0070500EBD100B4 +:1028E0004FF47F49944201D1BDE8F08704F0070717 +:1028F00005F0070A57453E4638BF5646C6F108065A +:10290000111B8E4228BF0E46E10808EBD50E415C34 +:1029100013F80EC0B94029FA06F721FA0AF1FFB2FE +:102920008CEA010147FA0AF739408CEA010C03F8F6 +:102930000EC034443544D5E780EA0120082341F233 +:10294000210201B24000002980B203F1FF33B8BF79 +:10295000504013F0FF03F4D17047000038B50C4627 +:102960008D18A54200D138BD14F8011BFFF7E4FF14 +:10297000F7E7000042684AB11368436043898189E0 +:1029800001339BB29942438138BF8381104670471F +:1029900070B588B0202204460D4668460021FEF737 +:1029A0008BFB20460495FFF7E5FF024658B16B46C6 +:1029B000054608AE1C4603CCB44228606960234635 +:1029C00005F10805F6D1104608B070BD082817D9E2 +:1029D00009280CD00A280CD00B280CD00C280CD0BD +:1029E0000D280CD00E2814BF4020302070470C203A +:1029F000704710207047142070471820704720201F +:102A000070470000082817D90C280CD910280CD9B9 +:102A100014280CD918280CD920280CD930288CBFA0 +:102A20000F200E207047092070470A2070470B20A6 +:102A300070470C2070470D20704700002DE9F843C7 +:102A4000078C072F04461ED9D0E9029800254FF6BF +:102A5000FF73C5F12006A5F1200029FA05F108FA57 +:102A600006F628FA00F031430143C9B21846FFF7D1 +:102A700063FF0835402D0346EBD1E1693A46BDE8D6 +:102A8000F843FFF76BBF4FF6FF70BDE8F883000017 +:102A900010B54B6823B9CA8A63F30902CA8210BD14 +:102AA00004691A681C600361C38A013BC3824A60DF +:102AB000EFE700002DE9F84F1D46CB8A0F46C3F320 +:102AC00009010529814692460B4630D00020AAB262 +:102AD00007F11A049EB2042E1FFA80F80FD8904511 +:102AE00003F1010306D3FB8A0A4462F30903FB8264 +:102AF00001201AE01AF80060E6540130EAE7904538 +:102B0000F1D2A1F1050B1C237C68BBFBF3F203FBA4 +:102B100012BB1FFA8BF6002C45D14846FFF72AFF5F +:102B2000044638B978606FF00200BDE8F88F4FF0C6 +:102B30000008E6E7002606607860ADB24FF0000BB3 +:102B4000454510D90AEB0803221D13F8011B9155C6 +:102B5000B1B208F101081B291FFA88F82BD04545AE +:102B600006F10106F1D8FB8AC3F30902154465F3A7 +:102B70000903BCE7013292B21C462368002BF9D14D +:102B80006B1F0B441C21B3FBF1F301339BB29A4240 +:102B9000D3D2BBF1000FD0D14846FFF7EBFE20B9EE +:102BA000C4F800B0BFE70122E7E7C0F800B05E4616 +:102BB00020600446C1E74545D5D94846FFF7DAFE0F +:102BC00008B92060AFE7C0F800B0002620600446D6 +:102BD000B6E700002DE9F04F2DED028B1C4683B0C7 +:102BE0005B69019207468846002B00F09A80238C8F +:102BF0002BB1E269002A00F09480072B35D807F149 +:102C00000C00FFF7B7FE054638B96FF002052846FD +:102C100003B0BDEC028BBDE8F08F14220021FEF75B +:102C20004BFA228CE16905F10800FEF733FA208C9B +:102C3000013080B2FFF7E6FEFFF7C8FE013880B230 +:102C40002084013028746369228C1B782A4403F0A5 +:102C50001F0363F03F0348F0004113723846696078 +:102C60002946FFF7EFFD0125D1E700F10C034FF0F6 +:102C7000000908EE103A4FF0800A4E464D4618EE15 +:102C8000100AFFF777FE83460028BED014220021E9 +:102C9000FEF712FA002E3AD1019BABF8083002225F +:102CA0000BF1080E1FFA82FC0CF10100BCF1060FBB +:102CB000218C80B201D88E422BD3FFF7A3FEFFF701 +:102CC00085FE62691278013802F01F028E4208BF49 +:102CD0004FF0400A42EA49121BFA80F14AEA020A1E +:102CE000013048F0004281F808A08BF81000CBF8C2 +:102CF000042059463846FFF7A5FD238C0135B34221 +:102D00002DB289F001094FF0000AB8D17FE7002207 +:102D1000C6E7E169895D0EF802100136B6B20132EC +:102D2000C0E76FF0010572E7F8B515460E46302290 +:102D3000002104461F46FEF7BFF9069B6360B5F508 +:102D4000001F079BA76034BF6A094FF6FF72A3629A +:102D500097B2E66104F1100000239A4206D80023DE +:102D60000360A782E3822383E360F8BD066001333A +:102D700030462036F1E7000003781BB94BB2002B38 +:102D8000C8BF01707047000000787047F8B50C4666 +:102D9000C969074611B9238C002B37D1257E1F2D19 +:102DA00034D8387828BB228C072A2CD8268A36F0CB +:102DB00003032BD14FF6FF70FFF7D0FD20F0010089 +:102DC0003102400441EA0561400C41EA40254FF6DA +:102DD000FF72234629463846FFF7FCFE002807DD30 +:102DE000626913780133DBB21F2B88BF0023137095 +:102DF000F8BD218A2D0645EA012505432046FFF747 +:102E00001DFE0246E5E76FF00300F1E76FF00100F9 +:102E1000EEE7000070B58AB004461646002128226D +:102E200068461D46FEF748F9BDF83830ADF8103059 +:102E30000F9B05939DF840308DF81830119B079338 +:102E40006946BDF84830ADF820302046CDE902652E +:102E5000FFF79CFF0AB070BD2DE9F041D36905462C +:102E60000C4616460BB9138C5BBB377E1F2F28D838 +:102E700095F80080B8F1000F26D03046FFF7DEFD50 +:102E80003378210241EAC33141EA0801338A41EA39 +:102E9000076141EA03410246334641F0800128467A +:102EA000FFF798FE00280ADD3378012B07D17269FD +:102EB00013780133DBB21F2B88BF00231370BDE8EA +:102EC000F0816FF00100FAE76FF00300F7E7000010 +:102ED000F0B58BB004460D461746002128226846FF +:102EE0001E46FEF7E9F89DF84C305A1E53425341F6 +:102EF0008DF800309DF84030ADF81030119B0593EF +:102F00009DF848308DF81830149B07936A46BDF839 +:102F10005430ADF8203029462046CDE90276FFF73F +:102F20009BFF0BB0F0BD0000406A00B10430704759 +:102F3000436A1A68426202691A600361C38A013BEC +:102F4000C38270472DE9F041D0F82080194E144615 +:102F50001D464146002709B9BDE8F081D1E90223A9 +:102F6000A21A65EB0303964277EB03031ED2036AB2 +:102F70008B420DD1FFF78CFD036A1B680362036966 +:102F80000B60C38A0161016A013BC3828846E2E7A4 +:102F9000FFF77EFD0B68C8F8003003690B60C38A39 +:102FA0000161013BC382D8F80010D4E78846096864 +:102FB000D1E700BF80841E002DE9F04F8BB00D4695 +:102FC000DDF8509014469B468046002800F0198199 +:102FD000B9F1000F00F01581531E3F2B00F2118153 +:102FE000012A03D1BBF1000F40F00B810023CDE992 +:102FF0000833B8F81430B5EBC30F4FEAC30703D357 +:1030000000200BB0BDE8F08F2B199F42D8F80C3090 +:103010003ABF7F1BFFB227461BB9D8F81030002BF0 +:103020007AD0272D4ED8C5F12806B7424FF00003BD +:103030002CBFF6B23E4600932946D8F8080008ABEC +:103040003246FFF741FCA7EB060A35445FFA8AFADD +:10305000B8F8143003F10053053BDB000493D8F8B3 +:103060000C3003932821039B13B1BAF1000F2CD12C +:10307000D8F8100040B1BAF1000F05D0009608ABA7 +:103080005246691AFFF720FC38B2002FB8D0660705 +:103090000AD00AAB03EBD401624211F8083C02F0FB +:1030A0000702134101F8083C082C3CD9102C40F2CF +:1030B000B580202C40F2B780BBF1000F00F09C805F +:1030C000082334E0BA460026C2E7049BE02B28BF61 +:1030D000E02306930B44AB42059314D95A1B039883 +:1030E0000096924534BF5246D2B2691A08AB0430FA +:1030F0000792FFF7E9FB079A1644AAEB020A154468 +:10310000F6B25FFA8AFA049B069A05999B1A049311 +:10311000039B1B680393A6E70093D8F8080008AB4D +:103120003A462946AEE7BBF1000F13D00123B4EBBA +:10313000C30F6CD0082C12D89DF82030621E23FAE1 +:1031400002F2D50706D54FF0FF3202FA04F423430A +:103150008DF820309DF8203089F8003051E7102C90 +:1031600012D8BDF82030621E23FA02F2D10706D52C +:103170004FF0FF3202FA04F42343ADF82030BDF8DB +:103180002030A9F800303CE7202C0FD80899631EA6 +:1031900021FA03F3DA0705D54FF0FF3202FA04F4FF +:1031A0000C430894089BC9F800302AE7402C2BD028 +:1031B000DDE90865611EC4F12102A4F1210326FAAC +:1031C00001F105FA02F225FA03F311431943CB0783 +:1031D00012D50122A4F12003C4F1200102FA03F365 +:1031E00022FA01F1A240524243EA010363EB430396 +:1031F00032432B43CDE90823DDE90823C9E9002345 +:10320000FFE66FF00100FCE66FF00800F9E6082C1D +:10321000A0D9102CB3D9202CEED8C3E7BBF1000FF6 +:10322000ADD0022383E7BBF1000FBBD004237EE7C0 +:1032300030B5012A144638BF0124402C85B028BF80 +:1032400040240025012ACDE9025518D81B788DF8B5 +:10325000083063070AD004AB03EBD405624215F8CB +:10326000083C02F00702934005F8083C0091034631 +:103270002246002102A8FFF727FB05B030BD082A2F +:10328000E4D9102A03D81B88ADF80830E1E7202ADA +:103290008DBFD3E900231B680293CDE90223D8E751 +:1032A00010B5CB681BB98B600B618B8210BD0469B4 +:1032B0001A681C600361C38A013BC382CA60F0E7DD +:1032C00003064CBFC0F3C0300220704708B5024669 +:1032D000FFF7F6FF022806D15306C2F30F2001D1F3 +:1032E00000F0030008BDC2F30740FBE72DE9F04FF3 +:1032F00093B0CDE903230A6804461046FFF7E0FFC8 +:10330000022814BFC2F306260026002A0D46824674 +:1033100080F2F78112F0C04940F0F381097B002967 +:1033200000F0EF81022803D02378B34240F0EC8113 +:10333000C2F304630693104602F07F030593FFF780 +:10334000C5FF059B29444FEA834848EA0A4848EAF2 +:103350004668CE7800230022CDE90823F30983468E +:1033600048EA0008029367D0059B0093024667680D +:10337000534608A92046B847002800F0C881276AAC +:103380004FB9414604F10C00FFF702FB074690B924 +:103390006FF0020054E03B6998450DD03F68002F64 +:1033A000F9D1414604F10C00FFF7F2FA0746002874 +:1033B000EED0236A3B60276297F817C006F01F081B +:1033C000CCF3840CACEB08001FFA80FE0028B8BFD9 +:1033D0000EF12000A8EB0C031FFA83FED7E90221AF +:1033E000B8BF00B2002B0793BEBF0EF120031BB283 +:1033F000079352EA010338D0039BDFF824E39A1ABB +:10340000049B4FF0000C63EB010196457CEB01033C +:103410002BD36B7B97F81AE0734519D1029B002BD5 +:1034200078D0012821DC7868F8B9DFF8F0C294453B +:1034300070EB010316D337E0276A27B96FF00C0051 +:1034400013B0BDE8F08F3B699845B5D03F68F4E70D +:10345000B24890427CEB010301D30020F0E7029BCD +:10346000002BFAD0079B0F2B17DCFA7DB30002F07C +:10347000030203F07C031343FB7539462046FFF734 +:1034800007FB6B7BBB76029B3BB9FB7DC3F38402DE +:10349000013262F38603FB75D0E76A7BBB7E9A42FA +:1034A000DBD1029B002B35D0B309022B32D0039B1A +:1034B000BB60049BFB60142200210DA8FDF7FCFDFE +:1034C000039B0A93049B0B932B1D0C932B7BADF852 +:1034D0003EB0013BDBB2ADF83C30069B8DF842308C +:1034E000059B8DF8433094F82C308DF840A083F084 +:1034F00001038DF844308DF84180A3680AA9204665 +:103500009847FB7DC3F38403013303F01F039B0241 +:10351000FB82A2E7FB7DC6F34012B2EBD31F40F063 +:10352000F980C3F38403434540F0FC80029A2B7B6F +:10353000B609002A52D016F0010661D1032B40F2E1 +:10354000F480039BBB60049BFB60FB8A66F309036A +:10355000FB822B7BAE1D033BDBB23246394604F1C6 +:103560000C00FFF7A7FA00280CDA39462046FFF7CF +:103570008FFAFB7DC3F38403013303F01F039B0227 +:10358000FB8205E7DDE90884AB883B834FF6FF73D8 +:10359000C9F12000A9F1200228FA09F104FA00F08B +:1035A000014324FA02F211431846C9B2FFF7C4F9E5 +:1035B00009F10809B9F1400F0346E9D1B8822A7B25 +:1035C000033AD2B23146FFF7C9F9FB7DB882DA433C +:1035D000C2F3C01262F3C713FB753EE786B92E1D16 +:1035E000013BDBB23246394604F10C00FFF762FAC8 +:1035F0000028BADB2A7BB88A013AD2B23146E2E728 +:10360000F98AC1F30901013B0429DAB25BD8281D0C +:10361000002307F11B069A4208D910F801CB06F8DF +:1036200001C0013101330529DBB2F4D103990A91BC +:1036300004990B91934207F11B010C9138BF04339D +:1036400079680D9134BF55FA83F300230E93FB8AFA +:10365000ADF83EB0C3F309031A44069B8DF842301F +:10366000059B8DF8433094F82C30ADF83C2083F066 +:1036700001038DF8443000238DF840A08DF841807F +:103680007B602A7BB88A013A291DFFF767F93B8BDB +:10369000B882834203D1A3680AA9204698472046EE +:1036A0000AA9FFF7FDFDFB7DBA8AC3F3840301334A +:1036B00003F01F039B02FB823B8B9A420CBF00204E +:1036C0006FF01000BCE67B68002BAFD0052001E056 +:1036D0001C3033461E68002EFAD1091A081D2E1D13 +:1036E000184401EB090CBCF11B0F5FFA89F39DD85C +:1036F0009A429BD916F8013B00F8013B09F10109F8 +:10370000EFE76FF009009BE66FF00A0098E66FF0B4 +:103710000B0095E66FF00D0092E600BF40420F00EF +:1037200080841E006FF00E008AE66FF00F0087E6BF +:10373000EFF3098305494A6B22F001024A636833BB +:1037400083F30988002383F31188704700EF00E0BA +:10375000302080F3118862B60C4B0D4AD96821F4F1 +:10376000E0610904090C0A43DA60D3F8FC20094936 +:1037700042F08072C3F8FC200A6842F001020A603D +:103780002022DA7783F82200704700BF00ED00E0C6 +:103790000003FA05001000E010B5302383F3118810 +:1037A0000E4B5B6813F4006314D0F1EE103AEFF3A4 +:1037B0000984683C4FF08073E361094BDB6B23663F +:1037C00084F3098800F0BAFA10B1064BA36110BD6A +:1037D000054BFBE783F31188F9E700BF00ED00E03C +:1037E00000EF00E03F03000842030008434B4FF4A2 +:1037F000007270B51A605A6912F4C06FFBD1404B69 +:103800009A6802F00C02042A20D01A6842F48072EE +:103810001A601A685205FCD501229A609A6802F073 +:103820000C02042AFAD13749374A0A600A6812F0B2 +:103830000F02FBD1C3F8982063221A601A6896031E +:10384000FCD42E4A4FF48071C2F88010C468E5039E +:1038500006D51A6842F480321A601A689103FCD5C2 +:10386000C269D20709D5D3F8982042F00102C3F803 +:103870009820D3F898209607FBD54269DA6044F483 +:1038800080721A6004F0807111B11A689501FBD53D +:10389000996802691B4E22F0030501F003012943D8 +:1038A000996085693560316869400907FBD1134922 +:1038B00005680D6046684E608068C1F880006E043F +:1038C00017D448698505FCD4996802F0030021F0FB +:1038D00003010143996092009968514011F00C0F67 +:1038E000FAD1E2055EBF1A6822F480721A600020E5 +:1038F00070BD48698005FCD5E6E700BF0070004058 +:1039000000100240002002400006040008B500F04C +:1039100083F9BDE8084000F05BB9000010B5394CF0 +:103920003948A36A4FF0FF32A262A36A0023A36260 +:10393000A16AE16A61F07F01E162E16A01F07F0161 +:10394000E162E16A216B2263216B2363216BA16B2E +:10395000A263A16BA363A16BE16BE263E16BE36321 +:10396000E16B216C2264226C2364226C226E42F093 +:1039700001022266D4F8802022F00102C4F88020DF +:10398000D4F88020A26D42F08052A265A26F22F08E +:103990008052A267A26F1D4A4FF400419160D3602C +:1039A000136253629362D362136353639363D3636B +:1039B000136453649364D36413655365116841F4CD +:1039C00080711160D4F8902012F4407F1EBF4FF434 +:1039D0008032C4F89020C4F890300D4A0023A360D0 +:1039E000C4F88820C4F89C30FFF700FF10B10948E4 +:1039F00000F0DAF9D4F8903023F00323C4F89030C3 +:103A000010BD00BF00100240FC48000800700040DC +:103A100055010051F4480008014B53F8200070474D +:103A200018230020074A08B5536903F001035361C6 +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7AABE0004014084650020074A08B5BC +:103A5000536903F00203536123B1054A93680BB124 +:103A6000D0689847BDE80840FFF796BE00040140C3 +:103A700084650020074A08B5536903F004035361C5 +:103A800023B1054A13690BB150699847BDE8084056 +:103A9000FFF782BE0004014084650020074A08B594 +:103AA000536903F00803536123B1054A93690BB1CD +:103AB000D0699847BDE80840FFF76EBE000401409A +:103AC00084650020074A08B5536903F01003536169 +:103AD00023B1054A136A0BB1506A9847BDE8084004 +:103AE000FFF75ABE0004014084650020164B10B554 +:103AF0005C6904F478725A61A30604D5134A936A88 +:103B00000BB1D06A9847600604D5104A136B0BB10D +:103B1000506B9847210604D50C4A936B0BB1D06BC0 +:103B20009847E20504D5094A136C0BB1506C9847CD +:103B3000A30504D5054A936C0BB1D06C9847BDE83A +:103B40001040FFF729BE00BF00040140846500203B +:103B5000194B10B55C6904F47C425A61620504D5C6 +:103B6000164A136D0BB1506D9847230504D5134ABF +:103B7000936D0BB1D06D9847E00404D50F4A136ED6 +:103B80000BB1506E9847A10404D50C4A936E0BB14B +:103B9000D06E9847620404D5084A136F0BB1506F7A +:103BA0009847230404D5054A936F0BB1D06F98470B +:103BB000BDE81040FFF7F0BD00040140846500201F +:103BC00008B500F0FBFCBDE80840FFF7E5BD0000CC +:103BD000062108B5084600F033F80621072000F05A +:103BE0002FF80621082000F02BF80621092000F00C +:103BF00027F806210A2000F023F80621172000F0FC +:103C00001FF80621282000F01BF8BDE80840072116 +:103C10001C2000F015B800004FF0E0230022586887 +:103C20004FF0FF31930003F1604303F5614301322C +:103C30009042C3F88010C3F88011F3D2704700009F +:103C400000F1604303F561430901C9B283F8001331 +:103C5000012200F01F039A4043099B0003F16043D7 +:103C600003F56143C3F880211A6070470023037590 +:103C7000826803691B6899689142FBD25A680360A5 +:103C800042601060586070470023037582680369C2 +:103C90001B6899689142FBD85A68036042601060C3 +:103CA0005860704708B50846302383F311880B7DB0 +:103CB000032B05D0042B0DD02BB983F3118808BD3D +:103CC0008B6900221A604FF0FF338361FFF7CEFF4C +:103CD0000023F2E7D1E9003213605A60F3E70000F5 +:103CE000FFF7C4BF054BD9680875186802681A60E9 +:103CF000536001220275D860FCF70CBBF86200200B +:103D000030B50C4BDD684B1C87B004460FD02B46FA +:103D1000094A684600F02AF92046FFF7E3FF009BB6 +:103D200013B1684600F02CF9A86907B030BDFFF761 +:103D3000D9FFF9E7F8620020A53C0008044B1A6897 +:103D4000DB6890689B68984294BF00200120704710 +:103D5000F8620020084B10B51C68D86822681A6009 +:103D6000536001222275DC60FFF78EFF014620467A +:103D7000BDE81040FCF7CEBAF862002038B5074C19 +:103D800007490848012300252370656000F044FCC2 +:103D90000223237085F3118838BD00BF60650020C1 +:103DA00020490008F862002008B572B6044B186577 +:103DB00000F0B4FA00F064FB024B03221A70FEE735 +:103DC000F86200206065002000F010B98B600223CB +:103DD00008618B82084670478368A3F1840243F828 +:103DE000142C026943F8442C426943F8402C094AD8 +:103DF00043F8242CC26843F8182C022203F80C2C38 +:103E0000002203F80B2C044A43F8102CA3F12000E5 +:103E1000704700BF2D030008F862002008B5FFF7C7 +:103E2000DBFFBDE80840FFF75BBF0000024BDB682B +:103E300098610F20FFF756BFF8620020302383F30C +:103E40001188FFF7F3BF000008B50146302383F364 +:103E500011880820FFF754FF002383F3118808BD61 +:103E600010B503689C68A2420CD85C688A600B603D +:103E70004C602160596099688A1A9A604FF0FF334C +:103E8000836010BD1B68121BECE700000A2938BFD5 +:103E90000A2170B504460D460A26601900F0B6FBEB +:103EA00000F0A2FB041BA54203D8751C2E46044655 +:103EB000F3E70A2E04D9BDE87040012000F0ECBB06 +:103EC00070BD0000F8B5144B0D46D96103F1100127 +:103ED00041600A2A1969826038BF0A22016048607D +:103EE0001861A818144600F083FB0A2700F07CFB39 +:103EF000431BA342064606D37C1C281900F086FB10 +:103F000027463546F2E70A2F04D9BDE8F8400120DC +:103F100000F0C2BBF8BD00BFF8620020F8B506464D +:103F20000D4600F061FB0F4A134653F8107F9F4285 +:103F300006D12A4601463046BDE8F840FFF7C2BF29 +:103F4000D169BB68441A2C1928BF2C46A34202D958 +:103F50002946FFF79BFF224631460348BDE8F8405B +:103F6000FFF77EBFF86200200863002010B4C0E9AC +:103F7000032300235DF8044B4361FFF7CFBF00002C +:103F800010B5194C236998420DD0D0E900328168F0 +:103F900013605A609A680A449A60002303604FF0E5 +:103FA000FF33A36110BD2346026843F8102F53600E +:103FB0000022026022699A4203D1BDE8104000F05D +:103FC0001FBB936881680B44936000F00DFB22696E +:103FD000E1699268441AA242E4D91144BDE8104054 +:103FE000091AFFF753BF00BFF86200202DE9F04720 +:103FF000DFF8BC8008F110072C4ED8F8105000F004 +:10400000F3FAD8F81C40AA68031B9A423ED814441D +:10401000D5E900324FF00009C8F81C4013605A601F +:10402000C5F80090D8F81030B34201D100F0E8FA9A +:1040300089F31188D5E9033128469847302383F363 +:1040400011886B69002BD8D000F0CEFA6A69A0EB1A +:1040500004094A4582460DD2022000F01DFB0022D1 +:10406000D8F81030B34208D151462846BDE8F04791 +:10407000FFF728BF121A2244F2E712EB090938BFF2 +:104080004A4629463846FFF7EBFEB5E7D8F8103028 +:10409000B34208D01444211AC8F81C00A960BDE836 +:1040A000F047FFF7F3BEBDE8F08700BF08630020CC +:1040B000F862002038B500F097FA054AD2E90845C1 +:1040C000031B181945F10001C2E9080138BD00BF02 +:1040D000F862002000207047FEE7000070470000F3 +:1040E0004FF0FF3070470000BFF34F8F024A136953 +:1040F000DB03FCD4704700BF0020024008B5094B29 +:104100001B7873B9FFF7F0FF074B5A69002ABFBF4E +:10411000064A9A6002F188329A601A6822F4806234 +:104120001A6008BD78650020002002402301674521 +:1041300008B50B4B1B7893B9FFF7D6FF094B5A69AB +:1041400042F000425A611A6842F480521A601A68BA +:1041500022F480521A601A6842F480621A6008BD24 +:104160007865002000200240FF289ABF00F58030CB +:10417000C0020020704700004FF40060704700004C +:104180004FF4807070470000FF2808B50BD8FFF788 +:10419000EBFF00F500630268013204D10430834272 +:1041A000F9D1012008BD0020FCE70000FF2838B548 +:1041B000044624D8FFF798FFFFF7A0FF114AF32326 +:1041C000136102235361C3005169C50903F47E736F +:1041D00043EAC5230B435361536943F4803353616E +:1041E000FFF782FF4FF40061FFF7BEFF00F044F9D4 +:1041F000FFF79EFF2046BDE83840FFF7C5BF00200F +:1042000038BD00BF002002402DE9F84340EA020318 +:1042100013F00703144606D0304B40F242321A60C6 +:104220000020BDE8F88385182D4A95420CD92B4A09 +:1042300040F247311160F3E7031D1B684A6893425F +:1042400008D1083C08300831072C14D902680B68E3 +:104250009A42F1D0FFF752FFFFF746FF214E083197 +:104260004FF001084FF00009012CA1F1080706D812 +:10427000FFF75EFF01E0002CECD10120D1E7C6F88A +:104280001480054651F8083C45F8043B51F8043CBD +:104290004360FFF729FF336943F001033361C6F838 +:1042A0001490026851F8083C9A420CD00B4B40F233 +:1042B0006F321A600C4B18600C4B1C600C4B1F606B +:1042C000FFF736FFACE72D6851F8043C9D4201F141 +:1042D0000801EBD1083C0830C6E700BF7465002038 +:1042E000000008080020024068650020706500207A +:1042F0006C650020084908B50B7828B11BB9FFF799 +:10430000FDFE01230B7008BD002BFCD0BDE808406A +:104310000870FFF70DBF00BF7865002008B506499B +:10432000064800F0ABF8BDE808404FF400414FF0FC +:10433000805000F0A3B800BF007F01000001002002 +:10434000084600F035BA000038B5EFF311859DB985 +:10435000EFF30584C4F30804302334B183F31188E8 +:10436000FFF7A8FE85F3118838BD83F31188FFF7A6 +:10437000A1FE84F3118838BDBDE83840FFF79ABE2E +:1043800038B5FFF7E1FF114C114AC00840EA41700F +:10439000A0FB025EC908A0FB040C1CEB050CA1FBF2 +:1043A00004404FF000035B41A1FB02121CEB040C24 +:1043B00043EB000011EB0E0142F10002411842F103 +:1043C0000000090941EA007038BD00BFCFF753E390 +:1043D000A59BC4200244D2B2904200D17047431C36 +:1043E000800000F1804000F51450006841F8040B93 +:1043F000D8B2F1E7124B10B5D3F89040240409D499 +:10440000D3F89040C3F89040D3F8904044F400446F +:10441000C3F890400B4C2368024443F4807323603C +:10442000D2B2904200D110BD431C800000F1804008 +:1044300000F5145051F8044B0460D8B2F1E700BF06 +:10444000001002400070004007B5012201A90020C1 +:10445000FFF7C0FF019803B05DF804FB13B50446F5 +:10446000FFF7F2FFA04205D0012201A9002001942C +:10447000FFF7C0FF02B010BD70470000704700009A +:1044800070470000074B45F255521A6002225A60ED +:1044900040F6FF729A604CF6CC421A60024B012241 +:1044A0001A7070470030004080650020034B1B7875 +:1044B0001BB1034B4AF6AA221A60704780650020A0 +:1044C00000300040054B1A6832B902F1804202F513 +:1044D0000432D2F894201A60704700BF7C65002037 +:1044E000024B4FF40002C3F89420704700100240C2 +:1044F00008B5FFF7E7FF024B1868C0F3407008BD2E +:104500007C65002070470000FEE700000A4B0B4866 +:104510000B4A90420BD30B4BDA1C121AC11E22F02D +:1045200003028B4238BF00220021FCF7C5BD53F8BF +:10453000041B40F8041BECE7A44A000804660020B2 +:1045400004660020046600200023054A1946013352 +:10455000102BC2E9001102F10802F8D1704700BF28 +:104560008465002008B5124B9A6D42F001029A65ED +:104570009A6F42F001029A670E4A9B6F936843F06C +:10458000010393600620FFF747FA0B4BB0FBF3F0F3 +:104590004FF080434FF0FF3201389862DA62002218 +:1045A0009A615A63DA605A6001225A611A6008BD42 +:1045B00000100240002004E040420F004FF0804213 +:1045C00008B51169D3680B40D9B2C9439B07116183 +:1045D00007D5302383F31188FFF7F6FB002383F31D +:1045E000118808BDFFF7BEBF4FF08043586A70477F +:1045F0004FF08043002258631A610222DA6070474C +:104600004FF080430022DA60704700004FF0804393 +:1046100058637047FEE7000070B51B4B016300252F +:10462000044686B0586085620E46FFF791F804F1A3 +:104630001003C4E904334FF0FF33C4E90635C4E97D +:104640000044A560E562FFF7CFFF2B460246C4E9B0 +:10465000082304F134010D4A256580232046FFF725 +:10466000B5FB0123E0600A4A03750092726801926B +:10467000B268CDE90223074B6846CDE90435FFF760 +:10468000CDFB06B070BD00BF606500202C4900085E +:104690003149000815460008024AD36A1843D0621F +:1046A000704700BFF86200204B6843608B688360EE +:1046B000CB68C3600B6943614B6903628B694362DA +:1046C0000B6803607047000008B5204BDA6A42F0BF +:1046D0007F02DA62DA6A22F07F02DA62DA6ADA6C80 +:1046E00042F07F02DA64DA6E42F07F02DA66184A3C +:1046F000DB6E11464FF09040FFF7D6FF02F11C0130 +:1047000000F58060FFF7D0FF02F1380100F580600E +:10471000FFF7CAFF02F1540100F58060FFF7C4FF04 +:1047200002F1700100F58060FFF7BEFF02F18C011D +:1047300000F58060FFF7B8FF02F1A80100F5806086 +:10474000FFF7B2FFBDE80840FFF7E8B800100240ED +:104750003849000808B500F009F8FFF70FFBBDE87D +:104760000840FFF7AFBE00007047000008B5FFF734 +:10477000CDF8FFF7E9FEFFF7F7FFBDE80840FFF7C8 +:1047800031BF00000B460146184600F003B8000098 +:1047900000F00EB810B5054C13462CB10A46014680 +:1047A0000220AFF3008010BD2046FCE700000000AF +:1047B000024B01461868FFF7C3BD00BF402300202D +:1047C00010B501390244904201D1002005E0037880 +:1047D00011F8014FA34201D0181B10BD0130F2E7C0 +:1047E0002DE9F041A3B1C91A17780144044603F139 +:1047F000FF3C8C42204601D9002009E00578BD42EB +:1048000004F10104F5D10CEB0405D618A54201D141 +:10481000BDE8F08115F8018D16F801EDF045F5D0F1 +:10482000E7E70000034611F8012B03F8012B002AEB +:10483000F9D170476F72672E6172647570696C6F21 +:10484000742E4D6174656B473437342D4453686F53 +:104850007400000040A2E4F1646891060041A3E501 +:10486000F2656992070000004261642043414E49AD +:104870006661636520696E6465782E000001000042 +:104880000001FF00006400400068004000000000DC +:1048900000000000911E00081D190008F525000801 +:1048A0008D190008D1190008B91B000899190008D2 +:1048B000551900085919000831190008191900087C +:1048C000751B00083D1900085D27000849190008FC +:1048D000491B000801040E05054B02020E05054B9D +:1048E00004010E05054B05010B04044B08010603EA +:1048F00003460000636C6B737763000000030000E5 +:1049000000000000000100000000010103000000A1 +:104910000328310104070400010000006330000097 +:104920001C49000850630020606500206D61696EBD +:104930000069646C650000000000802A000000002F +:10494000AAAAAAAA00000024FFFF0000000000009D +:10495000009009000028000100000000AAAAAAAAED +:1049600000000001FFFF00000000900900000000AF +:104970000000001400000000AAAAAAAA000000106B +:10498000FFDF000000000000000000000000000049 +:1049900000000000AAAAAAAA00000000FFFF000071 +:1049A0000000000000000000000000000000000007 +:1049B000AAAAAAAA00000000FFFF00000000000051 +:1049C000000000000000000000000000AAAAAAAA3F +:1049D00000000000FFFF00000000000000000000D9 +:1049E0000000000000000000AAAAAAAA000000001F +:1049F000FFFF0000000000000000000000000000B9 +:104A00009204000000000000007007000000000099 +:104A1000FE2A0100D2040000006889096D8BB902EA +:104A200000B4C4040068890900688909006889091C +:104A30000068890900688909006889090000000088 +:104A400044230020000000000000000000000000DF +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:104A80000000000000000000000000000000000026 +:104A90000000000000000000000000000000000016 +:044AA0000000000012 +:00000001FF diff --git a/Tools/bootloaders/MatekG474-Periph_bl.bin b/Tools/bootloaders/MatekG474-Periph_bl.bin new file mode 100755 index 00000000000000..12b8c441141335 Binary files /dev/null and b/Tools/bootloaders/MatekG474-Periph_bl.bin differ diff --git a/Tools/bootloaders/MatekG474-Periph_bl.hex b/Tools/bootloaders/MatekG474-Periph_bl.hex new file mode 100644 index 00000000000000..69a3822bc3524f --- /dev/null +++ b/Tools/bootloaders/MatekG474-Periph_bl.hex @@ -0,0 +1,1197 @@ +:020000040800F2 +:1000000000070020F101000845270008FD26000830 +:1000100025270008FD2600081D270008F301000819 +:10002000F3010008F3010008F3010008313700086C +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008253A00084D3A0008B2 +:10006000753A00089D3A0008C53A0008F3010008F7 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008AD260008C1260008ED3A00086B +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C13B0008F3010008F3010008F301000848 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000513B0008F3010008F3010008F301000888 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008D5260008E92600084D +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000990F00080000000000000000000000005F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F052F912 +:1002600004F032FA4FF055301F491B4A91423CBF0F +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F030F904F052FACD +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F018B9000700200023002040 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000004A000800230020A4230020A823002097 +:1003000004660020E0010008E4010008E4010008A0 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F080FDFEE703F067 +:1003400009FD00DFFEE70000F8B500F03BFE04F019 +:100350007BF8074604F0CCF80546C0BB294B9F420A +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F058FC2E4642F2107400F06F +:1003800059FC08B10024264601F00EF948B30320B9 +:1003900000F03EF80024264635B11C4B9F4203D0A6 +:1003A00004F09EF800242646002004F057F80EB111 +:1003B00000F044F800F070FC02F0CCF90546C4B936 +:1003C00000F0BEFC4FF47A7003F03EFDF7E72E46D6 +:1003D0000024D4E704460126D1E7064640F6C414BB +:1003E000CDE740F6C4139C4204BF4FF47A74012653 +:1003F000D2E702F0AFF9431BA342E1D900F01EF8A7 +:10040000DAE700BF010007B0000008B0263A09B0E3 +:10041000084B187003280CD8DFE800F00805020824 +:10042000022000F02DBE022000F020BE024B002270 +:100430005A607047A8230020AC23002010B501F0BB +:10044000B3F830B1234B03221A70234B00225A60B9 +:1004500010BD224B224A1C4619680131F8D00433E2 +:100460009342F9D16268A242F2D31E4B9B6803F11A +:10047000006303F510439A42EAD204F003F804F053 +:1004800015F8002000F0B8FD0220FFF7C1FF164B61 +:100490009A6D00229A65996F9A67996FD96DDA659E +:1004A000D96FDA67D96F196E1A66D3F88010C3F85E +:1004B0008020D3F8803072B64FF0E0233021C3F8AB +:1004C000084DD4E9003281F311889D4683F30888F2 +:1004D0001047BDE7A8230020AC23002000900008AF +:1004E000209000080023002000100240094A1368F1 +:1004F00049F2690099B21B0C00FB01331360064BF3 +:10050000186844F2506182B2000C01FB02001860CE +:1005100080B27047142300201023002010B5002162 +:100520001022044600F0C8FD034B03CB206061603D +:100530001868A06010BD00BF9075FF1F2DE9F04145 +:10054000ADF5507D0DF13C086EAC40F275120746DA +:100550000D4610A80021C8F8001000F0ADFD4FF4C2 +:10056000C4720021204600F0A7FD02F0F3F8274BEB +:100570004FF47A72B0FBF2F0186093E807000223A0 +:1005800084E807000DF5ED702382FFF7C7FF49F2FD +:1005900004231F49238407A804F044F91E2384F888 +:1005A00032310DF2EB2207AB0DF1340C1E4603CEB7 +:1005B000664510605160334602F10802F6D130689A +:1005C0001060B388938041460122204600F0C0FDB0 +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E06A3D3E900232B +:1005F000384602F06DFC0DF5507DBDE8F08100BF7E +:10060000AFF300809E6AC421818A46EEB4230020A5 +:10061000344800082DE9F0412C4C237ADAB08046AA +:100620000D465BBB27A9284600F0B4FE074600280C +:1006300042D19DF89D60C82E3ED801464FF4A66277 +:10064000204600F039FD4FF48073C4F8F8314FF4C0 +:100650000073C4F80C334FF44073C4F820343246AE +:100660000DF19E0104F1090000F014FD26449DF8EF +:100670009C30777223720BB9EB7E237281220021AA +:1006800006AC27A800F018FD0122214627A800F09B +:10069000C7FE00230393AB7E029305F1190380B2DA +:1006A00001932823CDE904400093E97E05A3D3E913 +:1006B0000023404602F00CFC5AB0BDE8F08100BFB8 +:1006C000AFF3008026417272DF25D7B7805D00202E +:1006D000F0B5254E4FF48A7505FB0065F1B096F82C +:1006E000D83085F8DC300024D822214685F8E8404F +:1006F0003AA800F0E1FC06F1090000F0D5FCD5F8BD +:10070000E4308DF8F000C2B206AF06F109010DF138 +:10071000F100CDE93A3400F0BDFC394601223AA897 +:1007200000F0B4FE80B2CDE9047008230127CDE9C2 +:10073000023706F1D803019330230093317A0B4836 +:1007400007A3D3E9002302F0C3FBA04206DD02F0B9 +:1007500001F8C5F8E000384671B0F0BD2046FBE76F +:1007600078F6339F93CACD8D805D0020CC33002076 +:100770002DE9F04F264FDFF8A480264E87B038468B +:1007800002F0D2FB034600283AD00024CDE903440E +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B681C4D43F000430293A146F9 +:1007B000A2462B68D3F810B001F0CEFF10EB080270 +:1007C00041F100032846CDF800A002A9D84704F55E +:1007D000A6640028C8BF49F00109B4F5266F05F5E5 +:1007E000A655E6D1B9F1000F05D0384602F0A0FBBE +:1007F00086F800A0C3E73378072B04D801333370A1 +:1008000007B0BDE8F08F024802F092FBF8E700BFA6 +:10081000CC330020B56200200034002040420F009D +:1008200070B50D4614461E4602F0AEFA50B9022EBF +:1008300010D1012C0ED112A3D3E90023C5E9002366 +:10084000012007E0282C10D005D8012C09D0052C58 +:100850000FD0002070BD302CFBD10BA3D3E90023B7 +:10086000ECE70BA3D3E90023E8E70BA3D3E90023CC +:10087000E4E70BA3D3E90023E0E700BFAFF3008078 +:10088000401DA12026812A0B78F6339F93CACD8D77 +:100890009E6AC421818A46EE26417272DF25D7B74F +:1008A000F017304A39059E5638B505460E4C0021E2 +:1008B000013500F0C3FBA4F82C55B4F82C0500F06A +:1008C000A5FB78B1B4F82C0500F0B0FB014648B99F +:1008D000B4F82C0500F0B2FBB4F82C350133A4F8C1 +:1008E0002C35EAE738BD00BF805D0020F8B50D4C1F +:1008F0000D4F0226A4F5805343F8307C237E3BB98C +:1009000065692DB1284600F0CDFE284603F040FF72 +:10091000204600F0C7FE012EA4F5A65400D1F8BD74 +:100920000126E7E7F0580020944800082DE9F04F31 +:100930008FB000AF05460C4602F026FA002849D1D8 +:10094000237E022B1BD1E38A012B18D101F002FF79 +:100950000646FFF7CBFD03464FF4C870DFF8C482AC +:10096000B3FBF0F206F5167602FB103316FA83F3AA +:10097000C8F80030E37E33B9A34B00221A703C372D +:10098000BD46BDE8F08F07F12401204600F0B6FC1B +:100990000028F4D107F11400FFF7C0FD97F82640B6 +:1009A00007F11401224607F1270003F009FF002890 +:1009B000E2D10F2C08D8944B1C70D8F80030A3F566 +:1009C0001673C8F80030DAE797F82410284602F0CA +:1009D000D3F9D4E7E38A282B2BD010D8012B23D0CE +:1009E000052BCCD1BFF34F8F8849894BCA6802F4DD +:1009F000E0621343CB60BFF34F8F00BFFDE7302BA6 +:100A0000BDD1844EE17E327A9142B8D1607E3146CA +:100A1000002291F8DC50854200F0A5800132042AC2 +:100A200001F58A71F5D1AAE721462846FFF786FD30 +:100A3000A5E721462846FFF7EDFDA0E7B2F8EC5008 +:100A40007B6005F103094FEA99094FEA8902D11D3C +:100A5000C908A8EBC1039D46EB460021584600F0AB +:100A60002BFB04F1EE012A463144584600F012FBFC +:100A70007B6813B9012000F0BFFA96F8D20000F0AD +:100A8000C5FA044630B9307200F0E0FA204600F0B2 +:100A9000B3FAB1E0D6F8D4203AB996F8D200B6F855 +:100AA0002C25824201D8FFF7FFFED6F8D4202A4435 +:100AB000944208D296F8D200B6F82C250130824232 +:100AC00001D8FFF7F1FE70685FFA89F2594600F02D +:100AD000FBFA08B9C54679E0726896F8D2002A4454 +:100AE0007260D6F8D42005EB0209C6F8D49000F065 +:100AF0008DFA814509D396F8D220D6F8D400013278 +:100B0000001B86F8D220C6F8D400FF2D0FD8002491 +:100B1000347200F09BFA204600F06EFA00F044FDBB +:100B20003D4B188108B9FFF789FCC54627E7BB682C +:100B300096F8D9000AFB0362FB68D2F8E41082F849 +:100B4000E83001F58061C2F8E030C2F8E410FFF748 +:100B5000BFFDFFF70DFE96F8D920013202F0030227 +:100B600086F8D920B6E74FF48A7A0AFB02F505F138 +:100B7000EA013144204600F0BBFCF86000287FF415 +:100B8000FEAE3544012285F8E82001F0E3FDD5F8FA +:100B9000E020D6ED007ADFED216A801A192838BFEF +:100BA000192040F6B832904228BF1046B8EE677A56 +:100BB00007EE900AF8EEE77A67EEA67ADFED186A9C +:100BC000E7EE267AFCEEE77AC6ED007A96F8D930A1 +:100BD000BB60BA6873680AFB02F4321992F8E81035 +:100BE00059B1D2F8E4108B42E8463FF427AF002118 +:100BF00082F8E810C2F8E010C5467368064A9B0AFE +:100C000001331381BBE600BFC533002000ED00E0D7 +:100C10000400FA05805D0020B4230020CDCCCC3D3B +:100C20006666663FC8330020014B1870704700BFEE +:100C3000C023002038B54FF00054134B22689A426D +:100C400020D1124B627D12481A70237D03724FF43B +:100C50008073C0F8F8314FF40073C0F80C330025EE +:100C60004FF44073C0F820340A49C0F8E450C92258 +:100C7000093000F00FFAE0222946204600F01CFA65 +:100C8000012038BD0020FCE79AAD44C5C0230020F8 +:100C9000805D00201600002037B500F085FC1F4C59 +:100CA0001F4D2049288102236B71236801225B6854 +:100CB0002046984704F580531A49D3F8C0340122DE +:100CC0005B6804F5A650984700230193164B17491B +:100CD00000931748174B4FF4805202F025F8164B3B +:100CE000197811B1124802F047F801F033FD0446BB +:100CF000FFF7FCFB4FF4C873B0FBF3F202FB1303E6 +:100D000004F5167010FA83F00C4B186003F0F0FB3A +:100D100008B10F232B8103B030BD00BF0034002089 +:100D2000B423002040420F0021080008C423002003 +:100D3000CC3300202D090008C0230020C833002038 +:100D40002DE9F04F2DED028B002493B00DF12C080E +:100D50009FED818BDFF83C92FFF70AFD0A94ADF816 +:100D600034400B94C8F804400026814DDFF804B2EB +:100D7000374601238DF81C302B688DF81D408DED12 +:100D8000008B0DF11D02D3F808A007A90023284607 +:100D9000D0479DF81CA0BAF1000F24D0D9F8143028 +:100DA00083F40053C9F81430102200210EA800F07B +:100DB00083F92B6808AA5F690AA90DF11E0328466A +:100DC000B84798E803000FAB83E803009DF8343080 +:100DD0008DF844300A9B0E930EA9DDE9082358468E +:100DE00002F084FA574606F5A666B6F5266F05F5B5 +:100DF000A655BED1002FB7D15E4801F0C5FF00282F +:100E00003FD15D4E01F0A6FC3368984239D301F022 +:100E1000A1FC0546FFF76AFB4FF4C873B0FBF3F281 +:100E200002FB130305F5167010FA83F03060534E81 +:100E30008DF82870377817B901238DF82830C7F15D +:100E40001005EDB20EA8FFF769FB062D28BF062599 +:100E50000EAB2A46D9190DF1290000F01BF90AAB97 +:100E60000393182302930135454B0193EDB20123FF +:100E70000093404804953AA3D3E9002301F0CAFF48 +:100E8000347001F067FC3F4A3F4D1368C31AB3F555 +:100E90007A7F2FD3106001F05FFC02460B46354885 +:100EA00002F050F8334801F06FFF18B32B7A374E39 +:100EB000002B14BF03230223737101F04BFC0EAF10 +:100EC0004FF47A730122B0FBF3F0394630603046BC +:100ED00000F0ECF9182302932D4B019380B240F2FD +:100EE0005513CDE90370009322481FA3D3E90023D3 +:100EF00001F090FF2B7A93B101F02CFC00260746FD +:100F00004FF48A7895F8D900304400F0030008FBCC +:100F1000005393F8E82072B10136042EF2D1C820B4 +:100F200002F092FF2B7A002B7FF410AF13B0BDECD0 +:100F3000028BBDE8F08FD3F8E02042B12B68FA2B8A +:100F400038BFFA23BA1A0533B2EB430FE4D3FFF7E5 +:100F5000BFFB0028E0D1E2E7000000000000000035 +:100F6000401DA12026812A0BF1C6A7C1D068080F19 +:100F700000340020CC330020C8330020C5330020CB +:100F8000C4330020B0620020805D0020B423002024 +:100F9000B46200200008004810B5074C204600F05D +:100FA000B3FE04F5A65000F0AFFEBDE81040034AC2 +:100FB0000349002003F0E6BB00340020F462002067 +:100FC000ED08000870B503F0DBF8094E094D3080DC +:100FD000002428683388834208D903F0CDF82B68B1 +:100FE00004440133B4F5104F2B60F2D370BD00BF41 +:100FF000E4620020B862002003F07CB900F10060D8 +:10100000920000F5104003F0FFB80000054B1A688D +:10101000054B1B889B1A834202D9104403F0ACB8DD +:1010200000207047B8620020E4620020024B1B6879 +:10103000184403F0A9B800BFB8620020024B1B6837 +:10104000184403F0B3B800BFB8620020064991F815 +:10105000243033B10023086A81F824300822FFF7D6 +:10106000CDBF0120704700BFBC620020022802BF34 +:10107000024B4FF000529A61704700BF00080048D1 +:10108000022802BF024B4FF400529A61704700BF22 +:101090000008004810B50023934203D0CC5CC45430 +:1010A0000133F9E710BD000003460246D01A12F9D9 +:1010B000011B0029FAD1704702440346934202D033 +:1010C00003F8011BFAE770472DE9F8431F4D14465A +:1010D00095F824200746884652BBDFF870909CB3F1 +:1010E00095F824302BB92022FF2148462F62FFF7C4 +:1010F000E3FF95F82400C0F10802A24228BF22466F +:10110000D6B24146920005EB8000FFF7C3FF95F889 +:101110002430A41B1E44F6B2082E17449044E4B2B7 +:1011200085F82460DBD1FFF791FF0028D7D108E0D4 +:101130002B6A03EB82038342CFD0FFF787FF00289F +:10114000CBD10020BDE8F8830120FBE7BC62002082 +:101150002DE9F8430D46044600219046284640F20A +:101160007912FFF7A9FF234620220021284602F02A +:101170005FF8231D02222021284602F059F8631D42 +:1011800003222221284602F053F8A31D0322252121 +:10119000284602F04DF804F10803102228212846C1 +:1011A00002F046F804F1100308223821284602F024 +:1011B0003FF804F1110308224021284602F038F8D4 +:1011C00004F1120308224821284602F031F804F104 +:1011D000140320225021284602F02AF804F11803B3 +:1011E00040227021284602F023F804F1200308224F +:1011F000B021284602F01CF804F121030822B8218E +:10120000284602F015F804F12207C0263B46314675 +:1012100008222846083602F00BF8B6F5A07F07F141 +:101220000107F3D1314604F132030822284601F0C8 +:10123000FFFF94F83260002704F13309F900BE4241 +:1012400001F5A4711FD8F70007F5A476B8F1000FD7 +:1012500008D1314604F599730722284601F0E8FFCA +:1012600007F24F1694F83201502828BF5020074645 +:1012700004EB0009B046A1450DD106EBC7000730CD +:10128000C008BDE8F88309EB07030822284601F0EF +:10129000CFFF0137D2E704F2331341460822284634 +:1012A00001F0C6FF08F108080134E4E713B504466D +:1012B0000846002101602346C0F803102022019057 +:1012C00001F0B6FF0198231D0222202101F0B0FF9A +:1012D0000198631D0322222101F0AAFF0198A31D9A +:1012E0000322252101F0A4FF019804F10803102234 +:1012F000282101F09DFF072002B010BDF7B5047F43 +:1013000005460E462CB1838A122B02D9012003B068 +:10131000F0BD0023194607220096284601F04CFE36 +:10132000731C0093012200230721284601F044FE8C +:10133000D4B9B31C0093052223460821284601F0A6 +:101340003BFE0D24B378102BE0D83746B278BB1B98 +:10135000934210D32B7FA88A0734E408B3B98442A0 +:1013600094BF00200120D2E7AB8ADB00083BDB08FA +:10137000B3700824E6E7FB1C0093214600230822F3 +:10138000284601F019FE08340137DFE7201A18BF9C +:101390000120BCE7F7B5047F05460E462CB1838AD1 +:1013A000CA2B02D9012003B0F0BD002319460096D4 +:1013B0000822284601F000FE731CD4B908220093CD +:1013C00011462346284601F0F7FD10247378C82BF8 +:1013D000E8D8012372785F1C013B934210D32B7F26 +:1013E000A88A0734E408B3B9844294BF00200120DE +:1013F000D9E7AB8ADB00083BDB0873700824E5E71C +:10140000F3190093214600230822284601F0D4FD59 +:1014100008343B46DEE7201A18BF0120C3E700006E +:101420002DE9F8430D460446164600218122284640 +:10143000FFF742FE234608220021284601F0F8FE6D +:10144000C6B9631C07220821284601F0F1FE0F26C9 +:1014500094F901306778002BB8BF7F2704EB0709A8 +:10146000B0464C4508D10736082010FB0760C0087D +:10147000BDE8F8830826EBE7A31C4146082228466E +:1014800001F0D6FE08F108080134EAE72DE9F04141 +:101490000D46044616460021CE222846FFF70CFED4 +:1014A000234628220021284601F0C2FEBEB904F1DD +:1014B000080308222821284601F0BAFE302614F835 +:1014C000080FC82828BFC82080460027B84506EB6B +:1014D000C70106D806EBC800C008BDE8F081282681 +:1014E000EDE70137E3190822284601F0A1FEEDE7F8 +:1014F000F7B5047F05460E4634B1838AB3F5827F83 +:1015000002D9012003B0F0BD009601231022002172 +:10151000284601F051FDDCB9B31C00930922234693 +:101520001021284601F048FD19247388B3F5807F07 +:10153000E7D837467288BB1B934210D32B7FA88A0B +:101540000734E408B3B9844294BF00200120D9E7EE +:10155000AB8ADB00103BDB0873801024E5E73B1D02 +:101560000093214600230822284601F025FD083477 +:101570000137DFE7201A18BF0120C3E730B5094D56 +:101580000A4491420DD011F8013B5840082340F322 +:101590000004013B2C4013F0FF0384EA5000F6D115 +:1015A000EFE730BD2083B8EDF7B5384A10685168D1 +:1015B0006B4603C36A4636493648082303F010F9E0 +:1015C0000446002833D10A25334A106851686B4617 +:1015D00003C36A4631492F48082303F001F9044642 +:1015E000002849D00369B3F5EE2F45D8B0F866104E +:1015F00040F2924291423FD1294A024402F15C01F9 +:101600008B4239D35C3B234900209E1AFFF7B6FF7B +:101610003246074604F164010020FFF7AFFFA368DC +:101620009F4229D1E368984208BF002524E003695E +:10163000B3F5EE2F27D8418B40F29242914220D150 +:10164000174A024402F110018B4218D3103B114992 +:1016500000209D1AFFF792FF2A46064604F1180162 +:101660000020FFF78BFFA3689E4202D1E3689842F7 +:1016700001D00D25A8E70025284603B0F0BD1025B0 +:10168000A2E70C25A0E70B259EE700BF5448000801 +:10169000DC6F0700009000085D480008906F0700AD +:1016A0000870FFF710B5037C044613B9006803F017 +:1016B0007FF8204610BD00000023BFF35B8FC3609E +:1016C000BFF35B8FBFF35B8F8360BFF35B8F7047AC +:1016D000BFF35B8F0068BFF35B8F704770B5054643 +:1016E0000C30FFF7F5FF05F1080604463046FFF71A +:1016F000EFFFA04206D930466D68FFF7E9FF2544A9 +:10170000281A70BD3046FFF7E3FF201AF9E7000002 +:1017100070B50546406898B105F10800FFF7D8FF9D +:1017200005F10C0604463046FFF7D2FF84423046EE +:1017300094BF6D680025FFF7CBFF013C2C44201AB5 +:1017400070BD000038B50C460546FFF7C7FFA04244 +:1017500010D305F10800FFF7BBFF04446868B4FB31 +:10176000F0F100FB1144BFF35B8F0120AC60BFF3CD +:101770005B8F38BD0020FCE72DE9F0411446074699 +:101780000D46FFF7C5FF844228BF0446D4B1B846D2 +:1017900058F80C6B4046FFF79BFF304428604046EA +:1017A0007E68FFF795FF331A9C4203D86C600120D6 +:1017B000BDE8F0816B60A41B3B68AB602044E8602F +:1017C0000220F5E72046F3E738B50C460546FFF75B +:1017D0009FFFA04210D305F10C00FFF779FF0444EE +:1017E0006868B4FBF0F100FB1144BFF35B8F01208C +:1017F000EC60BFF35B8F38BD0020FCE72DE9FF41B3 +:10180000884669460746FFF7B7FF6C4606B204EB09 +:10181000C6060025B44209D06268206808EB0501BD +:10182000FFF738FC636808341D44F3E7294638465F +:10183000FFF7CAFF284604B0BDE8F081F8B50546B9 +:101840000C300F46FFF744FF05F10806044630460A +:10185000FFF73EFFA042304688BF6C68FFF738FFB5 +:10186000201A386020B130462C68FFF731FF204441 +:10187000F8BD000073B5144606460D46FFF72EFF6F +:10188000844228BF04460190DCB101A93046FFF72D +:10189000D5FF019B33B93268C5E90233C5E900249D +:1018A00001200CE09C4238BF0194286001986860D8 +:1018B0008442F5D93368AB60241AEC60022002B090 +:1018C00070BD2046FBE700002DE9FF410F46694649 +:1018D000FFF7D0FF6C4600B204EBC0050026AC4217 +:1018E00009D0D4F8048054F8081BB8194246FFF711 +:1018F000D1FB4644F3E7304604B0BDE8F081000078 +:1019000038B50546FFF7E0FF044601462846FFF7D5 +:1019100019FF204638BD00007047000010B4134680 +:10192000026814680022A4465DF8044B604700007A +:1019300000F5805090F859047047000000F5805081 +:1019400090F852047047000000F5805090F9580458 +:101950007047000050207047302383F3118800F552 +:101960008052D2F89C34D2F898041844D2F89434B7 +:101970001844D2F87C341844D2F88C341844D2F885 +:1019800088341844002383F31188704700F5805091 +:10199000C0F854140120704738B5C26A936923F027 +:1019A00001039361044600F0D5FE0546E36A9B6996 +:1019B000DB0706D500F0CEFE431BFA2BF6D900203C +:1019C00004E004F58054012084F8520438BD00007E +:1019D0002DE9F04F0C4600F5805185B01F4691F877 +:1019E0005234BDF83890054690469BB1D1F8783412 +:1019F0000133C1F878342368980006D4237B082B80 +:101A00000BD9627B0AB10F2B07D9D1F87C34013393 +:101A1000C1F87C344FF0FF3010E0302383F311889D +:101A2000EB6AD3F8C42012F4001B0AD0D1F880343A +:101A30000133C1F88034002080F3118805B0BDE87F +:101A4000F08FD3F8C4302068C3F3014A6B6A482290 +:101A5000002812FB0A33B4BF40F0804080041860B5 +:101A60002268520044BF40F000501860207B4FEACB +:101A70000A6242EA00425A60607B4FEA4A1610B39B +:101A800042F440125A60D1F8B0240132C1F8B024B7 +:101A9000AA1902F58352117B41F020011173207BBA +:101AA000039300F0B3FE039B033080105FFA8BF2C8 +:101AB00082420BF1010B0DDA04EB820103EB82028F +:101AC00049689160F2E7AA1902F58352117B60F32D +:101AD0004511E3E7EB6A012202FA0AF2C3F8CC20CF +:101AE00005EB4A11AB1903F5825301F58251C3E9A5 +:101AF00004871831234604F10C0253F8040B41F813 +:101B0000040B9342F9D11B880B802E4441F26803E9 +:101B100046F803A006F5805609F0030396F86C20FA +:101B200043F0100322F01F02134386F86C300023A9 +:101B300083F31188CDF8009042463B462146284663 +:101B400000F02AFE012079E713B500F580540191D9 +:101B5000606CFFF7DDFD1F280AD90199606C202217 +:101B6000FFF74CFEA0F120035842584102B010BDCF +:101B70000020FBE708B5302383F3118800F580507F +:101B8000406CFFF799FD002383F3118808BD000026 +:101B900000220260828142608260704710B500229C +:101BA0000023C0E900230023044603810C30FFF723 +:101BB000EFFF204610BD00002DE9F0479A4688B09F +:101BC000074688469146302383F3118807F58054F1 +:101BD0006846FFF7E3FF606CFFF780FD1F282DD9F3 +:101BE000606C20226946FFF78BFE202826D194F8EE +:101BF00052341BB303AD444605AB2E4603CE9E4282 +:101C000020606160354604F10804F6D13068206038 +:101C1000B388A380DDE90023C9E90023BDF80830BB +:101C2000AAF80030002383F3118853464A46414600 +:101C3000384608B0BDE8F04700F09CBD002080F3B6 +:101C4000118808B0BDE8F0872DE9F84F002306465B +:101C5000C0E90133294B46F8303B00F58154054675 +:101C600088463746103438462037FFF797FFA7429B +:101C7000F9D105F580544FF4805326630026C4E95A +:101C80000D366764012305F5835705F5A359E6630F +:101C900084F8403084F84830103709F110094FF0CB +:101CA000000A4FF0000B47E908ABA7F11800FFF757 +:101CB0006FFF203747F8286C4F45F4D1B8F1010F7A +:101CC00084F85884A4F85A64A4F85C64A4F85E64A8 +:101CD00084F86064A4F86264A4F86464A4F8666498 +:101CE00084F8686402D9064800F02EFD054B53F8CD +:101CF0002830EB622846BDE8F88F00BF9448000802 +:101D0000684800088448000810B5044B1978044658 +:101D10004A1C1A70FFF798FF204610BDF1620020A0 +:101D20002DE9F84315460C4600295CD0022001F04D +:101D300073FE2E49B0FBF4F78C428CBF0A211121AF +:101D40004B1EB7FBF1F601FB1671DAB221B1022B83 +:101D50001946F5D8002032E0731EB3F5806FF9D232 +:101D6000C2EBC20808F103014FEAE10EC1F3C7015B +:101D7000A2EB010C0EF101094FF47A735FFA8CF7B4 +:101D80000EFB033E59FA8CFCBEFBFCFCBCF5617FEC +:101D900017DC1FFA8CF34A1C57FA82F27243B0FB2D +:101DA000F2F08442D6D14A1E0F2AD3D87A1E072ACF +:101DB000D0D801202B806E8028716971AF71BDE889 +:101DC000F88308F1FF314FEAE10CC1F3C701521A61 +:101DD0000CF1010ED7B20CFB03335EFA82F2B3FBB7 +:101DE000F2F39BB2D7E70846E9E700BF3F420F0096 +:101DF00030B50D4B0D4D05201C786C438C420ED137 +:101E00005978518099785171D978917119791171F6 +:101E10005B7903EB83035B001380012030BD013845 +:101E200003F10603E8D1F9E7D448000840420F0067 +:101E300038B500F58053114A93F85834D55C4FF407 +:101E40005472554305F1804303F5244304460021B1 +:101E50001846FFF731F90A4B60612B44A361094B27 +:101E60002B44E361084B2B442362084B2B446362F1 +:101E7000E36A0022C3F8C02038BD00BF7C480008D8 +:101E800070A40040B0A4004088A5004078A600409F +:101E90002DE9F04F00F580551F4695F85834022B78 +:101EA00089B004468946904604D90026304609B0D8 +:101EB000BDE8F08FA64A52F8231009B942F8230072 +:101EC000A448C4F80C900178277499B9302383F39F +:101ED0001188A14B9A6D42F000729A659A6B42F09C +:101EE00000729A639A6B22F000729A630123037066 +:101EF00081F3118895F85134CBB9302383F31188DD +:101F0000964A95F85834D35C012B2AD0022B2FD057 +:101F10003BB90321152001F093FE0321162001F0A7 +:101F20008FFE012385F85134002383F31188302379 +:101F300083F31188E26A936923F01003936100F040 +:101F400009FC8246E36A9E6916F0080617D000F085 +:101F500001FCA0EB0A03FA2BF4D9002686F31188C2 +:101F6000A4E70321562001F06BFE03215720D6E79A +:101F70000321582001F064FE03215920CFE79A691C +:101F800042F001029A6100F0E5FB8246E36A9A6939 +:101F9000D00706D400F0DEFBA0EB0A03FA2BF5D93C +:101FA000DBE79A6942F002029A61E36A4FF0000AA5 +:101FB000C3F854A08AF31188686CFFF77DFB04F521 +:101FC000825B0BF1100B202200216846FFF774F8AA +:101FD00002A8FFF7DDFDCDF818A06A460BEB06035B +:101FE0000DF1180E9446BCE80300F44518605960E2 +:101FF000624603F10803F5D1DCF8000018602036D2 +:102000009CF804201A71B6F5806FDCD1002304F52A +:10201000A25285F8503485F853341A324946204686 +:10202000FFF77EFE064690B9E26A936923F001034A +:10203000936100F08FFB0546E36A9B69D9077FF542 +:1020400034AF00F087FB431BFA2BF5D92DE795F849 +:102050005E34C5F86C94591E95F85F34E26A013B12 +:102060001B0243EA416395F8601401390B43B5F84C +:102070005C14013943EA0143D361B8F1000F36D053 +:1020800004F5A352023241462046FFF7B1FE90B953 +:10209000E26A936923F00103936100F05BFB05465C +:1020A000E36A9B69DA077FF500AF00F053FB431B3F +:1020B000FA2BF5D9F9E695F86724C5F87084511E16 +:1020C00095F86824E36A013A120142EA012295F880 +:1020D000661401390A43B5F86414013942EA014231 +:1020E00042F40002DA60E36A4FF420629A64204608 +:1020F000FFF79EFE002385F85934E36A6FF04042F3 +:102100001A65E36A164A5A65E36A44229A65E36AE5 +:102110000722C3F8DC20E36A03229742DA653FF422 +:10212000C5AEE26A936923F00103936100F012FBEC +:102130000746E36A9B69DB0705D500F00BFBC31B71 +:10214000FA2BF6D9B1E6012385F85234AEE600BF8A +:10215000E8620020F0620020001002407C48000885 +:102160009B0008002DE9F04F054689B0904699463E +:10217000002741F2680A00F58056EB6AD3F8D430A4 +:10218000FB40D80751D505EB471252444FEA471B95 +:102190001379190749D4D6F884340133C6F8843446 +:1021A00005F5A553C3E9008913799A0648BFD6F807 +:1021B000B43405EB0B0248BF0133524448BFC6F8A4 +:1021C000B434137943F008031371DB0722D596F872 +:1021D0005334FBB105F58254183468465C44FFF76C +:1021E000DDFC03AB04F1080C206861681A4603C2E9 +:1021F000083464451346F7D120681060A2889A809D +:102200000123ADF808302B68CDE90089DB6B694606 +:1022100028469847D6F8A834D6F854040133C6F8AF +:10222000A83410B103681B6998470137202FA4D147 +:1022300009B0BDE8F08F00002DE9F04F8DB00446E5 +:102240000F4600F089FA82468946002F56D1E36A8C +:10225000D3F89020920141BF04F58051D1F8982421 +:102260000132C1F89824D3F89020160703D100203A +:102270000DB0BDE8F08FD3F89050E669C5F30125A5 +:10228000482303FB0566E8464046FFF781FC3268B9 +:1022900051004ABF22F06043C2F38A4343F0004337 +:1022A000920048BF43F080430093736813F4001317 +:1022B0001FBF04F5805201238DF80D30D2F8B834D9 +:1022C0000EBF8DF80D300133C2F8B834F38803F037 +:1022D0000F038DF80C304FF0000B9DF80C0000F050 +:1022E00095FA5FFA8BF3984220D9F2180CA90B44A7 +:1022F000127A03F82C2C0BF1010BEEE7012FB6D16B +:10230000E36AD3F89820950141BF04F58051D1F8D4 +:1023100098240132C1F89824D3F898201007A6D049 +:10232000D3F89850266AC5F30125A9E7EFB9E36A07 +:10233000C3F8945004A8FFF731FC98E80F0007ADEC +:1023400007C52B800023ADF8183023682046CDE95F +:1023500004A9DB6B04A9984704F5805458B1D4F85C +:1023600090340133C4F8903482E7012F04BFE36A4C +:10237000C3F89C50DEE7D4F894340133C4F89434A5 +:10238000012075E72DE9F04105460F4600F5805420 +:10239000012639462846FFF74FFF10B184F85364F1 +:1023A000F7E7D4F8A834D4F854040133C4F8A834B7 +:1023B00020B10368BDE8F0411B691847BDE8F08112 +:1023C000F0B5C36A1A6C12F47F0F2BD000F580545D +:1023D0001B6CC4F8AC3441F26805002347194FF078 +:1023E000010C00EB43122A445E01117911F0020F37 +:1023F00015D0490713D4B959C66AD6F8C8E00CFA03 +:1024000001F111EA0E0F0AD0C6F8D010117941F08F +:1024100004011171D4F88C240132C4F88C240133E6 +:10242000202BDED1F0BD00002B4B70B51E561B5C7F +:10243000012B2FD8294D2A4A55F8233052F826402F +:102440000BB341B3236D1A060FD58023236500F02B +:1024500083F950EA01020B4602D0013861F1000312 +:10246000024655F82600FFF77DFE236D1B032CD591 +:1024700055F826304FF4002203F5805322650122DF +:1024800083F8592421E001232365082323654FF4B1 +:102490008063236570BD236DDA0702D4236D9B072B +:1024A00006D5032355F8260023650021FFF76AFFB0 +:1024B000236D180702D4236DD90606D5182355F8C5 +:1024C000260023650121FFF75DFF55F82600BDE8D2 +:1024D0007040FFF775BF00BF80480008E862002029 +:1024E0008448000808B5302383F31188FFF768FF9C +:1024F000002383F3118808BDC36AD3F8C40080F4B5 +:102500000010C0F34050704708B5302383F31188A2 +:1025100000F58050406CFFF7E1F8002383F3118849 +:1025200043090CBF0120002008BD000000F58053C6 +:1025300093F8592462B1C16A8A6922F001028A6162 +:10254000D3F89C240132C3F89C24002283F8592438 +:10255000704700002DE9F743302181F3118800F521 +:1025600082511031002541F2680E4FF0010800F54C +:10257000805C00EB45147444267977071CD4F6067A +:102580001AD5D0F82C908E69D9F8C87008FA06F6DA +:102590003E4211D04F6801970F689742019F9F41BB +:1025A0000AD2C9F8D060267946F004062671DCF814 +:1025B00088440134CCF888440135202D01F12001F4 +:1025C000D7D1002383F3118803B0BDE8F083000066 +:1025D000F8B51E46002313700F4605461446FFF754 +:1025E00093FF80F0010038701EB12846FFF784FF8A +:1025F0002070F8BD2DE9F04F85B09946DDE90EA3B6 +:102600000D4602931378019391F800B08046164668 +:1026100000F0A2F82B7804460F4613B93378002B4C +:1026200041D022463B464046FFF794FFFFF75AFF52 +:10263000FFF77CFF4B4632462946FFF7C9FF2B7850 +:1026400033B1BBF1000F03D0012005B0BDE8F08F1E +:10265000337813B1019B002BF6D108F58053039317 +:10266000029B544577EB03031DD2039BD3F854041C +:10267000C8B10368AAEB04011B6898474B46324671 +:1026800029464046FFF7A4FF2B7813B1BBF1000F9A +:10269000DAD1337813B1019B002BD5D100F05CF86F +:1026A00004460F46DCE70020CFE7000008B5002114 +:1026B0000846FFF7B9FEBDE8084001F06DB800001C +:1026C00008B501210020FFF7AFFEBDE8084001F08A +:1026D00063B8000008B500210120FFF7A5FEBDE8A2 +:1026E000084001F059B8000008B501210846FFF77D +:1026F0009BFEBDE8084001F04FB8000000B59BB05C +:10270000EFF3098168226846FEF7C4FCEFF3058306 +:10271000014B9B6BFEE700BF00ED00E008B5FFF743 +:10272000EDFF000000B59BB0EFF309816822684619 +:10273000FEF7B0FCEFF30583014B5B6BFEE700BFD8 +:1027400000ED00E0FEE700000FB408B5029801F0CC +:102750002BFBFEE701F014BE01F0F6BD13B56C468D +:1027600084E80600031D94E8030083E805000120C7 +:1027700002B010BD73B58568019155B11B885B0728 +:1027800007D4D0E900369B6B9847019AC1B2304616 +:10279000A847012002B070BDF0B5866889B0054633 +:1027A0000C465EB1BDF838305B070AD4D0E900377B +:1027B0009B6B98472246C1B23846B047012009B00A +:1027C000F0BD00220023CDE900230023ADF808303E +:1027D0000A4603AB01F10806106851681C4603C4A1 +:1027E0000832B2422346F7D1106820609288A28056 +:1027F000FFF7B2FF0423ADF808302B68CDE90001E4 +:10280000DB6B694628469847D8E70000082817D9A7 +:1028100009280CD00A280CD00B280CD00C280CD07E +:102820000D280CD00E2814BF4020302070470C20FB +:1028300070471020704714207047182070472020E0 +:10284000704700002DE9F041456A15B94162BDE8C5 +:10285000F0814B6823F06047C3F38A464FEAD37E8A +:10286000C3F3807816EA230638BF3E46AC462B46B3 +:102870005A68BEEBD27F22F060440AD0002A18DAF0 +:10288000A40CB44217D19D420FD10D60DEE7134670 +:10289000EEE7A74207D102F08044C2F380724245BE +:1028A0000BD054B1EFE708D2EDE7CCF800100B6085 +:1028B000CDE7B44201D0B442E5D81A689C46002A5C +:1028C000E5D11960C3E700002DE9F047089D01F04C +:1028D00007044FEAD508224405F0070500EBD100B4 +:1028E0004FF47F49944201D1BDE8F08704F0070717 +:1028F00005F0070A57453E4638BF5646C6F108065A +:10290000111B8E4228BF0E46E10808EBD50E415C34 +:1029100013F80EC0B94029FA06F721FA0AF1FFB2FE +:102920008CEA010147FA0AF739408CEA010C03F8F6 +:102930000EC034443544D5E780EA0120082341F233 +:10294000210201B24000002980B203F1FF33B8BF79 +:10295000504013F0FF03F4D17047000038B50C4627 +:102960008D18A54200D138BD14F8011BFFF7E4FF14 +:10297000F7E7000042684AB11368436043898189E0 +:1029800001339BB29942438138BF8381104670471F +:1029900070B588B0202204460D4668460021FEF737 +:1029A0008BFB20460495FFF7E5FF024658B16B46C6 +:1029B000054608AE1C4603CCB44228606960234635 +:1029C00005F10805F6D1104608B070BD082817D9E2 +:1029D00009280CD00A280CD00B280CD00C280CD0BD +:1029E0000D280CD00E2814BF4020302070470C203A +:1029F000704710207047142070471820704720201F +:102A000070470000082817D90C280CD910280CD9B9 +:102A100014280CD918280CD920280CD930288CBFA0 +:102A20000F200E207047092070470A2070470B20A6 +:102A300070470C2070470D20704700002DE9F843C7 +:102A4000078C072F04461ED9D0E9029800254FF6BF +:102A5000FF73C5F12006A5F1200029FA05F108FA57 +:102A600006F628FA00F031430143C9B21846FFF7D1 +:102A700063FF0835402D0346EBD1E1693A46BDE8D6 +:102A8000F843FFF76BBF4FF6FF70BDE8F883000017 +:102A900010B54B6823B9CA8A63F30902CA8210BD14 +:102AA00004691A681C600361C38A013BC3824A60DF +:102AB000EFE700002DE9F84F1D46CB8A0F46C3F320 +:102AC00009010529814692460B4630D00020AAB262 +:102AD00007F11A049EB2042E1FFA80F80FD8904511 +:102AE00003F1010306D3FB8A0A4462F30903FB8264 +:102AF00001201AE01AF80060E6540130EAE7904538 +:102B0000F1D2A1F1050B1C237C68BBFBF3F203FBA4 +:102B100012BB1FFA8BF6002C45D14846FFF72AFF5F +:102B2000044638B978606FF00200BDE8F88F4FF0C6 +:102B30000008E6E7002606607860ADB24FF0000BB3 +:102B4000454510D90AEB0803221D13F8011B9155C6 +:102B5000B1B208F101081B291FFA88F82BD04545AE +:102B600006F10106F1D8FB8AC3F30902154465F3A7 +:102B70000903BCE7013292B21C462368002BF9D14D +:102B80006B1F0B441C21B3FBF1F301339BB29A4240 +:102B9000D3D2BBF1000FD0D14846FFF7EBFE20B9EE +:102BA000C4F800B0BFE70122E7E7C0F800B05E4616 +:102BB00020600446C1E74545D5D94846FFF7DAFE0F +:102BC00008B92060AFE7C0F800B0002620600446D6 +:102BD000B6E700002DE9F04F2DED028B1C4683B0C7 +:102BE0005B69019207468846002B00F09A80238C8F +:102BF0002BB1E269002A00F09480072B35D807F149 +:102C00000C00FFF7B7FE054638B96FF002052846FD +:102C100003B0BDEC028BBDE8F08F14220021FEF75B +:102C20004BFA228CE16905F10800FEF733FA208C9B +:102C3000013080B2FFF7E6FEFFF7C8FE013880B230 +:102C40002084013028746369228C1B782A4403F0A5 +:102C50001F0363F03F0348F0004113723846696078 +:102C60002946FFF7EFFD0125D1E700F10C034FF0F6 +:102C7000000908EE103A4FF0800A4E464D4618EE15 +:102C8000100AFFF777FE83460028BED014220021E9 +:102C9000FEF712FA002E3AD1019BABF8083002225F +:102CA0000BF1080E1FFA82FC0CF10100BCF1060FBB +:102CB000218C80B201D88E422BD3FFF7A3FEFFF701 +:102CC00085FE62691278013802F01F028E4208BF49 +:102CD0004FF0400A42EA49121BFA80F14AEA020A1E +:102CE000013048F0004281F808A08BF81000CBF8C2 +:102CF000042059463846FFF7A5FD238C0135B34221 +:102D00002DB289F001094FF0000AB8D17FE7002207 +:102D1000C6E7E169895D0EF802100136B6B20132EC +:102D2000C0E76FF0010572E7F8B515460E46302290 +:102D3000002104461F46FEF7BFF9069B6360B5F508 +:102D4000001F079BA76034BF6A094FF6FF72A3629A +:102D500097B2E66104F1100000239A4206D80023DE +:102D60000360A782E3822383E360F8BD066001333A +:102D700030462036F1E7000003781BB94BB2002B38 +:102D8000C8BF01707047000000787047F8B50C4666 +:102D9000C969074611B9238C002B37D1257E1F2D19 +:102DA00034D8387828BB228C072A2CD8268A36F0CB +:102DB00003032BD14FF6FF70FFF7D0FD20F0010089 +:102DC0003102400441EA0561400C41EA40254FF6DA +:102DD000FF72234629463846FFF7FCFE002807DD30 +:102DE000626913780133DBB21F2B88BF0023137095 +:102DF000F8BD218A2D0645EA012505432046FFF747 +:102E00001DFE0246E5E76FF00300F1E76FF00100F9 +:102E1000EEE7000070B58AB004461646002128226D +:102E200068461D46FEF748F9BDF83830ADF8103059 +:102E30000F9B05939DF840308DF81830119B079338 +:102E40006946BDF84830ADF820302046CDE902652E +:102E5000FFF79CFF0AB070BD2DE9F041D36905462C +:102E60000C4616460BB9138C5BBB377E1F2F28D838 +:102E700095F80080B8F1000F26D03046FFF7DEFD50 +:102E80003378210241EAC33141EA0801338A41EA39 +:102E9000076141EA03410246334641F0800128467A +:102EA000FFF798FE00280ADD3378012B07D17269FD +:102EB00013780133DBB21F2B88BF00231370BDE8EA +:102EC000F0816FF00100FAE76FF00300F7E7000010 +:102ED000F0B58BB004460D461746002128226846FF +:102EE0001E46FEF7E9F89DF84C305A1E53425341F6 +:102EF0008DF800309DF84030ADF81030119B0593EF +:102F00009DF848308DF81830149B07936A46BDF839 +:102F10005430ADF8203029462046CDE90276FFF73F +:102F20009BFF0BB0F0BD0000406A00B10430704759 +:102F3000436A1A68426202691A600361C38A013BEC +:102F4000C38270472DE9F041D0F82080194E144615 +:102F50001D464146002709B9BDE8F081D1E90223A9 +:102F6000A21A65EB0303964277EB03031ED2036AB2 +:102F70008B420DD1FFF78CFD036A1B680362036966 +:102F80000B60C38A0161016A013BC3828846E2E7A4 +:102F9000FFF77EFD0B68C8F8003003690B60C38A39 +:102FA0000161013BC382D8F80010D4E78846096864 +:102FB000D1E700BF80841E002DE9F04F8BB00D4695 +:102FC000DDF8509014469B468046002800F0198199 +:102FD000B9F1000F00F01581531E3F2B00F2118153 +:102FE000012A03D1BBF1000F40F00B810023CDE992 +:102FF0000833B8F81430B5EBC30F4FEAC30703D357 +:1030000000200BB0BDE8F08F2B199F42D8F80C3090 +:103010003ABF7F1BFFB227461BB9D8F81030002BF0 +:103020007AD0272D4ED8C5F12806B7424FF00003BD +:103030002CBFF6B23E4600932946D8F8080008ABEC +:103040003246FFF741FCA7EB060A35445FFA8AFADD +:10305000B8F8143003F10053053BDB000493D8F8B3 +:103060000C3003932821039B13B1BAF1000F2CD12C +:10307000D8F8100040B1BAF1000F05D0009608ABA7 +:103080005246691AFFF720FC38B2002FB8D0660705 +:103090000AD00AAB03EBD401624211F8083C02F0FB +:1030A0000702134101F8083C082C3CD9102C40F2CF +:1030B000B580202C40F2B780BBF1000F00F09C805F +:1030C000082334E0BA460026C2E7049BE02B28BF61 +:1030D000E02306930B44AB42059314D95A1B039883 +:1030E0000096924534BF5246D2B2691A08AB0430FA +:1030F0000792FFF7E9FB079A1644AAEB020A154468 +:10310000F6B25FFA8AFA049B069A05999B1A049311 +:10311000039B1B680393A6E70093D8F8080008AB4D +:103120003A462946AEE7BBF1000F13D00123B4EBBA +:10313000C30F6CD0082C12D89DF82030621E23FAE1 +:1031400002F2D50706D54FF0FF3202FA04F423430A +:103150008DF820309DF8203089F8003051E7102C90 +:1031600012D8BDF82030621E23FA02F2D10706D52C +:103170004FF0FF3202FA04F42343ADF82030BDF8DB +:103180002030A9F800303CE7202C0FD80899631EA6 +:1031900021FA03F3DA0705D54FF0FF3202FA04F4FF +:1031A0000C430894089BC9F800302AE7402C2BD028 +:1031B000DDE90865611EC4F12102A4F1210326FAAC +:1031C00001F105FA02F225FA03F311431943CB0783 +:1031D00012D50122A4F12003C4F1200102FA03F365 +:1031E00022FA01F1A240524243EA010363EB430396 +:1031F00032432B43CDE90823DDE90823C9E9002345 +:10320000FFE66FF00100FCE66FF00800F9E6082C1D +:10321000A0D9102CB3D9202CEED8C3E7BBF1000FF6 +:10322000ADD0022383E7BBF1000FBBD004237EE7C0 +:1032300030B5012A144638BF0124402C85B028BF80 +:1032400040240025012ACDE9025518D81B788DF8B5 +:10325000083063070AD004AB03EBD405624215F8CB +:10326000083C02F00702934005F8083C0091034631 +:103270002246002102A8FFF727FB05B030BD082A2F +:10328000E4D9102A03D81B88ADF80830E1E7202ADA +:103290008DBFD3E900231B680293CDE90223D8E751 +:1032A00010B5CB681BB98B600B618B8210BD0469B4 +:1032B0001A681C600361C38A013BC382CA60F0E7DD +:1032C00003064CBFC0F3C0300220704708B5024669 +:1032D000FFF7F6FF022806D15306C2F30F2001D1F3 +:1032E00000F0030008BDC2F30740FBE72DE9F04FF3 +:1032F00093B0CDE903230A6804461046FFF7E0FFC8 +:10330000022814BFC2F306260026002A0D46824674 +:1033100080F2F78112F0C04940F0F381097B002967 +:1033200000F0EF81022803D02378B34240F0EC8113 +:10333000C2F304630693104602F07F030593FFF780 +:10334000C5FF059B29444FEA834848EA0A4848EAF2 +:103350004668CE7800230022CDE90823F30983468E +:1033600048EA0008029367D0059B0093024667680D +:10337000534608A92046B847002800F0C881276AAC +:103380004FB9414604F10C00FFF702FB074690B924 +:103390006FF0020054E03B6998450DD03F68002F64 +:1033A000F9D1414604F10C00FFF7F2FA0746002874 +:1033B000EED0236A3B60276297F817C006F01F081B +:1033C000CCF3840CACEB08001FFA80FE0028B8BFD9 +:1033D0000EF12000A8EB0C031FFA83FED7E90221AF +:1033E000B8BF00B2002B0793BEBF0EF120031BB283 +:1033F000079352EA010338D0039BDFF824E39A1ABB +:10340000049B4FF0000C63EB010196457CEB01033C +:103410002BD36B7B97F81AE0734519D1029B002BD5 +:1034200078D0012821DC7868F8B9DFF8F0C294453B +:1034300070EB010316D337E0276A27B96FF00C0051 +:1034400013B0BDE8F08F3B699845B5D03F68F4E70D +:10345000B24890427CEB010301D30020F0E7029BCD +:10346000002BFAD0079B0F2B17DCFA7DB30002F07C +:10347000030203F07C031343FB7539462046FFF734 +:1034800007FB6B7BBB76029B3BB9FB7DC3F38402DE +:10349000013262F38603FB75D0E76A7BBB7E9A42FA +:1034A000DBD1029B002B35D0B309022B32D0039B1A +:1034B000BB60049BFB60142200210DA8FDF7FCFDFE +:1034C000039B0A93049B0B932B1D0C932B7BADF852 +:1034D0003EB0013BDBB2ADF83C30069B8DF842308C +:1034E000059B8DF8433094F82C308DF840A083F084 +:1034F00001038DF844308DF84180A3680AA9204665 +:103500009847FB7DC3F38403013303F01F039B0241 +:10351000FB82A2E7FB7DC6F34012B2EBD31F40F063 +:10352000F980C3F38403434540F0FC80029A2B7B6F +:10353000B609002A52D016F0010661D1032B40F2E1 +:10354000F480039BBB60049BFB60FB8A66F309036A +:10355000FB822B7BAE1D033BDBB23246394604F1C6 +:103560000C00FFF7A7FA00280CDA39462046FFF7CF +:103570008FFAFB7DC3F38403013303F01F039B0227 +:10358000FB8205E7DDE90884AB883B834FF6FF73D8 +:10359000C9F12000A9F1200228FA09F104FA00F08B +:1035A000014324FA02F211431846C9B2FFF7C4F9E5 +:1035B00009F10809B9F1400F0346E9D1B8822A7B25 +:1035C000033AD2B23146FFF7C9F9FB7DB882DA433C +:1035D000C2F3C01262F3C713FB753EE786B92E1D16 +:1035E000013BDBB23246394604F10C00FFF762FAC8 +:1035F0000028BADB2A7BB88A013AD2B23146E2E728 +:10360000F98AC1F30901013B0429DAB25BD8281D0C +:10361000002307F11B069A4208D910F801CB06F8DF +:1036200001C0013101330529DBB2F4D103990A91BC +:1036300004990B91934207F11B010C9138BF04339D +:1036400079680D9134BF55FA83F300230E93FB8AFA +:10365000ADF83EB0C3F309031A44069B8DF842301F +:10366000059B8DF8433094F82C30ADF83C2083F066 +:1036700001038DF8443000238DF840A08DF841807F +:103680007B602A7BB88A013A291DFFF767F93B8BDB +:10369000B882834203D1A3680AA9204698472046EE +:1036A0000AA9FFF7FDFDFB7DBA8AC3F3840301334A +:1036B00003F01F039B02FB823B8B9A420CBF00204E +:1036C0006FF01000BCE67B68002BAFD0052001E056 +:1036D0001C3033461E68002EFAD1091A081D2E1D13 +:1036E000184401EB090CBCF11B0F5FFA89F39DD85C +:1036F0009A429BD916F8013B00F8013B09F10109F8 +:10370000EFE76FF009009BE66FF00A0098E66FF0B4 +:103710000B0095E66FF00D0092E600BF40420F00EF +:1037200080841E006FF00E008AE66FF00F0087E6BF +:10373000EFF3098305494A6B22F001024A636833BB +:1037400083F30988002383F31188704700EF00E0BA +:10375000302080F3118862B60C4B0D4AD96821F4F1 +:10376000E0610904090C0A43DA60D3F8FC20094936 +:1037700042F08072C3F8FC200A6842F001020A603D +:103780002022DA7783F82200704700BF00ED00E0C6 +:103790000003FA05001000E010B5302383F3118810 +:1037A0000E4B5B6813F4006314D0F1EE103AEFF3A4 +:1037B0000984683C4FF08073E361094BDB6B23663F +:1037C00084F3098800F0BAFA10B1064BA36110BD6A +:1037D000054BFBE783F31188F9E700BF00ED00E03C +:1037E00000EF00E03F03000842030008434B4FF4A2 +:1037F000007270B51A605A6912F4C06FFBD1404B69 +:103800009A6802F00C02042A20D01A6842F48072EE +:103810001A601A685205FCD501229A609A6802F073 +:103820000C02042AFAD13749374A0A600A6812F0B2 +:103830000F02FBD1C3F8982063221A601A6896031E +:10384000FCD42E4A4FF48071C2F88010C468E5039E +:1038500006D51A6842F480321A601A689103FCD5C2 +:10386000C269D20709D5D3F8982042F00102C3F803 +:103870009820D3F898209607FBD54269DA6044F483 +:1038800080721A6004F0807111B11A689501FBD53D +:10389000996802691B4E22F0030501F003012943D8 +:1038A000996085693560316869400907FBD1134922 +:1038B00005680D6046684E608068C1F880006E043F +:1038C00017D448698505FCD4996802F0030021F0FB +:1038D00003010143996092009968514011F00C0F67 +:1038E000FAD1E2055EBF1A6822F480721A600020E5 +:1038F00070BD48698005FCD5E6E700BF0070004058 +:1039000000100240002002400006040008B500F04C +:1039100083F9BDE8084000F05BB9000010B5394CF0 +:103920003948A36A4FF0FF32A262A36A0023A36260 +:10393000A16AE16A61F07F01E162E16A01F07F0161 +:10394000E162E16A216B2263216B2363216BA16B2E +:10395000A263A16BA363A16BE16BE263E16BE36321 +:10396000E16B216C2264226C2364226C226E42F093 +:1039700001022266D4F8802022F00102C4F88020DF +:10398000D4F88020A26D42F08052A265A26F22F08E +:103990008052A267A26F1D4A4FF400419160D3602C +:1039A000136253629362D362136353639363D3636B +:1039B000136453649364D36413655365116841F4CD +:1039C00080711160D4F8902012F4407F1EBF4FF434 +:1039D0008032C4F89020C4F890300D4A0023A360D0 +:1039E000C4F88820C4F89C30FFF700FF10B10948E4 +:1039F00000F0DAF9D4F8903023F00323C4F89030C3 +:103A000010BD00BF00100240FC48000800700040DC +:103A100055010051F4480008014B53F8200070474D +:103A200018230020074A08B5536903F001035361C6 +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7AABE0004014084650020074A08B5BC +:103A5000536903F00203536123B1054A93680BB124 +:103A6000D0689847BDE80840FFF796BE00040140C3 +:103A700084650020074A08B5536903F004035361C5 +:103A800023B1054A13690BB150699847BDE8084056 +:103A9000FFF782BE0004014084650020074A08B594 +:103AA000536903F00803536123B1054A93690BB1CD +:103AB000D0699847BDE80840FFF76EBE000401409A +:103AC00084650020074A08B5536903F01003536169 +:103AD00023B1054A136A0BB1506A9847BDE8084004 +:103AE000FFF75ABE0004014084650020164B10B554 +:103AF0005C6904F478725A61A30604D5134A936A88 +:103B00000BB1D06A9847600604D5104A136B0BB10D +:103B1000506B9847210604D50C4A936B0BB1D06BC0 +:103B20009847E20504D5094A136C0BB1506C9847CD +:103B3000A30504D5054A936C0BB1D06C9847BDE83A +:103B40001040FFF729BE00BF00040140846500203B +:103B5000194B10B55C6904F47C425A61620504D5C6 +:103B6000164A136D0BB1506D9847230504D5134ABF +:103B7000936D0BB1D06D9847E00404D50F4A136ED6 +:103B80000BB1506E9847A10404D50C4A936E0BB14B +:103B9000D06E9847620404D5084A136F0BB1506F7A +:103BA0009847230404D5054A936F0BB1D06F98470B +:103BB000BDE81040FFF7F0BD00040140846500201F +:103BC00008B500F0FBFCBDE80840FFF7E5BD0000CC +:103BD000062108B5084600F033F80621072000F05A +:103BE0002FF80621082000F02BF80621092000F00C +:103BF00027F806210A2000F023F80621172000F0FC +:103C00001FF80621282000F01BF8BDE80840072116 +:103C10001C2000F015B800004FF0E0230022586887 +:103C20004FF0FF31930003F1604303F5614301322C +:103C30009042C3F88010C3F88011F3D2704700009F +:103C400000F1604303F561430901C9B283F8001331 +:103C5000012200F01F039A4043099B0003F16043D7 +:103C600003F56143C3F880211A6070470023037590 +:103C7000826803691B6899689142FBD25A680360A5 +:103C800042601060586070470023037582680369C2 +:103C90001B6899689142FBD85A68036042601060C3 +:103CA0005860704708B50846302383F311880B7DB0 +:103CB000032B05D0042B0DD02BB983F3118808BD3D +:103CC0008B6900221A604FF0FF338361FFF7CEFF4C +:103CD0000023F2E7D1E9003213605A60F3E70000F5 +:103CE000FFF7C4BF054BD9680875186802681A60E9 +:103CF000536001220275D860FCF70CBBF86200200B +:103D000030B50C4BDD684B1C87B004460FD02B46FA +:103D1000094A684600F02AF92046FFF7E3FF009BB6 +:103D200013B1684600F02CF9A86907B030BDFFF761 +:103D3000D9FFF9E7F8620020A53C0008044B1A6897 +:103D4000DB6890689B68984294BF00200120704710 +:103D5000F8620020084B10B51C68D86822681A6009 +:103D6000536001222275DC60FFF78EFF014620467A +:103D7000BDE81040FCF7CEBAF862002038B5074C19 +:103D800007490848012300252370656000F044FCC2 +:103D90000223237085F3118838BD00BF60650020C1 +:103DA00020490008F862002008B572B6044B186577 +:103DB00000F0B4FA00F064FB024B03221A70FEE735 +:103DC000F86200206065002000F010B98B600223CB +:103DD00008618B82084670478368A3F1840243F828 +:103DE000142C026943F8442C426943F8402C094AD8 +:103DF00043F8242CC26843F8182C022203F80C2C38 +:103E0000002203F80B2C044A43F8102CA3F12000E5 +:103E1000704700BF2D030008F862002008B5FFF7C7 +:103E2000DBFFBDE80840FFF75BBF0000024BDB682B +:103E300098610F20FFF756BFF8620020302383F30C +:103E40001188FFF7F3BF000008B50146302383F364 +:103E500011880820FFF754FF002383F3118808BD61 +:103E600010B503689C68A2420CD85C688A600B603D +:103E70004C602160596099688A1A9A604FF0FF334C +:103E8000836010BD1B68121BECE700000A2938BFD5 +:103E90000A2170B504460D460A26601900F0B6FBEB +:103EA00000F0A2FB041BA54203D8751C2E46044655 +:103EB000F3E70A2E04D9BDE87040012000F0ECBB06 +:103EC00070BD0000F8B5144B0D46D96103F1100127 +:103ED00041600A2A1969826038BF0A22016048607D +:103EE0001861A818144600F083FB0A2700F07CFB39 +:103EF000431BA342064606D37C1C281900F086FB10 +:103F000027463546F2E70A2F04D9BDE8F8400120DC +:103F100000F0C2BBF8BD00BFF8620020F8B506464D +:103F20000D4600F061FB0F4A134653F8107F9F4285 +:103F300006D12A4601463046BDE8F840FFF7C2BF29 +:103F4000D169BB68441A2C1928BF2C46A34202D958 +:103F50002946FFF79BFF224631460348BDE8F8405B +:103F6000FFF77EBFF86200200863002010B4C0E9AC +:103F7000032300235DF8044B4361FFF7CFBF00002C +:103F800010B5194C236998420DD0D0E900328168F0 +:103F900013605A609A680A449A60002303604FF0E5 +:103FA000FF33A36110BD2346026843F8102F53600E +:103FB0000022026022699A4203D1BDE8104000F05D +:103FC0001FBB936881680B44936000F00DFB22696E +:103FD000E1699268441AA242E4D91144BDE8104054 +:103FE000091AFFF753BF00BFF86200202DE9F04720 +:103FF000DFF8BC8008F110072C4ED8F8105000F004 +:10400000F3FAD8F81C40AA68031B9A423ED814441D +:10401000D5E900324FF00009C8F81C4013605A601F +:10402000C5F80090D8F81030B34201D100F0E8FA9A +:1040300089F31188D5E9033128469847302383F363 +:1040400011886B69002BD8D000F0CEFA6A69A0EB1A +:1040500004094A4582460DD2022000F01DFB0022D1 +:10406000D8F81030B34208D151462846BDE8F04791 +:10407000FFF728BF121A2244F2E712EB090938BFF2 +:104080004A4629463846FFF7EBFEB5E7D8F8103028 +:10409000B34208D01444211AC8F81C00A960BDE836 +:1040A000F047FFF7F3BEBDE8F08700BF08630020CC +:1040B000F862002038B500F097FA054AD2E90845C1 +:1040C000031B181945F10001C2E9080138BD00BF02 +:1040D000F862002000207047FEE7000070470000F3 +:1040E0004FF0FF3070470000BFF34F8F024A136953 +:1040F000DB03FCD4704700BF0020024008B5094B29 +:104100001B7873B9FFF7F0FF074B5A69002ABFBF4E +:10411000064A9A6002F188329A601A6822F4806234 +:104120001A6008BD78650020002002402301674521 +:1041300008B50B4B1B7893B9FFF7D6FF094B5A69AB +:1041400042F000425A611A6842F480521A601A68BA +:1041500022F480521A601A6842F480621A6008BD24 +:104160007865002000200240FF289ABF00F58030CB +:10417000C0020020704700004FF40060704700004C +:104180004FF4807070470000FF2808B50BD8FFF788 +:10419000EBFF00F500630268013204D10430834272 +:1041A000F9D1012008BD0020FCE70000FF2838B548 +:1041B000044624D8FFF798FFFFF7A0FF114AF32326 +:1041C000136102235361C3005169C50903F47E736F +:1041D00043EAC5230B435361536943F4803353616E +:1041E000FFF782FF4FF40061FFF7BEFF00F044F9D4 +:1041F000FFF79EFF2046BDE83840FFF7C5BF00200F +:1042000038BD00BF002002402DE9F84340EA020318 +:1042100013F00703144606D0304B40F247321A60C1 +:104220000020BDE8F88385182D4A95420CD92B4A09 +:104230004FF453711160F3E7031D1B684A68934202 +:1042400008D1083C08300831072C14D902680B68E3 +:104250009A42F1D0FFF752FFFFF746FF214E083197 +:104260004FF001084FF00009012CA1F1080706D812 +:10427000FFF75EFF01E0002CECD10120D1E7C6F88A +:104280001480054651F8083C45F8043B51F8043CBD +:104290004360FFF729FF336943F001033361C6F838 +:1042A0001490026851F8083C9A420CD00B4B4FF422 +:1042B0005D721A600C4B18600C4B1C600C4B1F603D +:1042C000FFF736FFACE72D6851F8043C9D4201F141 +:1042D0000801EBD1083C0830C6E700BF7465002038 +:1042E000000008080020024068650020706500207A +:1042F0006C650020084908B50B7828B11BB9FFF799 +:10430000FDFE01230B7008BD002BFCD0BDE808406A +:104310000870FFF70DBF00BF7865002008B506499B +:10432000064800F0ABF8BDE808404FF400414FF0FC +:10433000805000F0A3B800BF007F01000001002002 +:10434000084600F035BA000038B5EFF311859DB985 +:10435000EFF30584C4F30804302334B183F31188E8 +:10436000FFF7A8FE85F3118838BD83F31188FFF7A6 +:10437000A1FE84F3118838BDBDE83840FFF79ABE2E +:1043800038B5FFF7E1FF114C114AC00840EA41700F +:10439000A0FB025EC908A0FB040C1CEB050CA1FBF2 +:1043A00004404FF000035B41A1FB02121CEB040C24 +:1043B00043EB000011EB0E0142F10002411842F103 +:1043C0000000090941EA007038BD00BFCFF753E390 +:1043D000A59BC4200244D2B2904200D17047431C36 +:1043E000800000F1804000F51450006841F8040B93 +:1043F000D8B2F1E7124B10B5D3F89040240409D499 +:10440000D3F89040C3F89040D3F8904044F400446F +:10441000C3F890400B4C2368024443F4807323603C +:10442000D2B2904200D110BD431C800000F1804008 +:1044300000F5145051F8044B0460D8B2F1E700BF06 +:10444000001002400070004007B5012201A90020C1 +:10445000FFF7C0FF019803B05DF804FB13B50446F5 +:10446000FFF7F2FFA04205D0012201A9002001942C +:10447000FFF7C0FF02B010BD70470000704700009A +:1044800070470000074B45F255521A6002225A60ED +:1044900040F6FF729A604CF6CC421A60024B012241 +:1044A0001A7070470030004080650020034B1B7875 +:1044B0001BB1034B4AF6AA221A60704780650020A0 +:1044C00000300040054B1A6832B902F1804202F513 +:1044D0000432D2F894201A60704700BF7C65002037 +:1044E000024B4FF40002C3F89420704700100240C2 +:1044F00008B5FFF7E7FF024B1868C0F3407008BD2E +:104500007C65002070470000FEE700000A4B0B4866 +:104510000B4A90420BD30B4BDA1C121AC11E22F02D +:1045200003028B4238BF00220021FCF7C5BD53F8BF +:10453000041B40F8041BECE7A44A000804660020B2 +:1045400004660020046600200023054A1946013352 +:10455000102BC2E9001102F10802F8D1704700BF28 +:104560008465002008B5124B9A6D42F001029A65ED +:104570009A6F42F001029A670E4A9B6F936843F06C +:10458000010393600620FFF747FA0B4BB0FBF3F0F3 +:104590004FF080434FF0FF3201389862DA62002218 +:1045A0009A615A63DA605A6001225A611A6008BD42 +:1045B00000100240002004E040420F004FF0804213 +:1045C00008B51169D3680B40D9B2C9439B07116183 +:1045D00007D5302383F31188FFF7F6FB002383F31D +:1045E000118808BDFFF7BEBF4FF08043586A70477F +:1045F0004FF08043002258631A610222DA6070474C +:104600004FF080430022DA60704700004FF0804393 +:1046100058637047FEE7000070B51B4B016300252F +:10462000044686B0586085620E46FFF791F804F1A3 +:104630001003C4E904334FF0FF33C4E90635C4E97D +:104640000044A560E562FFF7CFFF2B460246C4E9B0 +:10465000082304F134010D4A256580232046FFF725 +:10466000B5FB0123E0600A4A03750092726801926B +:10467000B268CDE90223074B6846CDE90435FFF760 +:10468000CDFB06B070BD00BF606500202C4900085E +:104690003149000815460008024AD36A1843D0621F +:1046A000704700BFF86200204B6843608B688360EE +:1046B000CB68C3600B6943614B6903628B694362DA +:1046C0000B6803607047000008B5204BDA6A42F0BF +:1046D0007F02DA62DA6A22F07F02DA62DA6ADA6C80 +:1046E00042F07F02DA64DA6E42F07F02DA66184A3C +:1046F000DB6E11464FF09040FFF7D6FF02F11C0130 +:1047000000F58060FFF7D0FF02F1380100F580600E +:10471000FFF7CAFF02F1540100F58060FFF7C4FF04 +:1047200002F1700100F58060FFF7BEFF02F18C011D +:1047300000F58060FFF7B8FF02F1A80100F5806086 +:10474000FFF7B2FFBDE80840FFF7E8B800100240ED +:104750003849000808B500F009F8FFF70FFBBDE87D +:104760000840FFF7AFBE00007047000008B5FFF734 +:10477000CDF8FFF7E9FEFFF7F7FFBDE80840FFF7C8 +:1047800031BF00000B460146184600F003B8000098 +:1047900000F00EB810B5054C13462CB10A46014680 +:1047A0000220AFF3008010BD2046FCE700000000AF +:1047B000024B01461868FFF7C3BD00BF402300202D +:1047C00010B501390244904201D1002005E0037880 +:1047D00011F8014FA34201D0181B10BD0130F2E7C0 +:1047E0002DE9F041A3B1C91A17780144044603F139 +:1047F000FF3C8C42204601D9002009E00578BD42EB +:1048000004F10104F5D10CEB0405D618A54201D141 +:10481000BDE8F08115F8018D16F801EDF045F5D0F1 +:10482000E7E70000034611F8012B03F8012B002AEB +:10483000F9D170476F72672E6172647570696C6F21 +:10484000742E4D6174656B473437342D5065726931 +:104850007068000040A2E4F1646891060041A3E59D +:10486000F2656992070000004261642043414E49AD +:104870006661636520696E6465782E000001000042 +:104880000001FF00006400400068004000000000DC +:1048900000000000911E00081D190008F525000801 +:1048A0008D190008D1190008B91B000899190008D2 +:1048B000551900085919000831190008191900087C +:1048C000751B00083D1900085D27000849190008FC +:1048D000491B000801040E05054B02020E05054B9D +:1048E00004010E05054B05010B04044B08010603EA +:1048F00003460000636C6B737763000000030000E5 +:1049000000000000000100000000010103000000A1 +:104910000328310104070400010000006330000097 +:104920001C49000850630020606500206D61696EBD +:104930000069646C650000000000802A000000002F +:10494000AAAAAAAA00000024FFFF0000000000009D +:10495000009009000028000100000000AAAAAAAAED +:1049600000000001FFFF00000000900900000000AF +:104970000000001400000000AAAAAAAA000000106B +:10498000FFDF000000000000000000000000000049 +:1049900000000000AAAAAAAA00000000FFFF000071 +:1049A0000000000000000000000000000000000007 +:1049B000AAAAAAAA00000000FFFF00000000000051 +:1049C000000000000000000000000000AAAAAAAA3F +:1049D00000000000FFFF00000000000000000000D9 +:1049E0000000000000000000AAAAAAAA000000001F +:1049F000FFFF0000000000000000000000000000B9 +:104A00009204000000000000007007000000000099 +:104A1000FE2A0100D2040000006889096D8BB902EA +:104A200000B4C4040068890900688909006889091C +:104A30000068890900688909006889090000000088 +:104A400044230020000000000000000000000000DF +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:104A80000000000000000000000000000000000026 +:104A90000000000000000000000000000000000016 +:044AA0000000000012 +:00000001FF diff --git a/Tools/bootloaders/MatekH7A3_bl.bin b/Tools/bootloaders/MatekH7A3_bl.bin index 81a83e580b27cd..6b2d6edac88491 100755 Binary files a/Tools/bootloaders/MatekH7A3_bl.bin and b/Tools/bootloaders/MatekH7A3_bl.bin differ diff --git a/Tools/bootloaders/MatekH7A3_bl.hex b/Tools/bootloaders/MatekH7A3_bl.hex index e36bf98ed9b647..ce600d6df1f5d4 100644 --- a/Tools/bootloaders/MatekH7A3_bl.hex +++ b/Tools/bootloaders/MatekH7A3_bl.hex @@ -1064,7 +1064,7 @@ :10426000C3F83C21D3F8642142F08042C3F86421B2 :10427000D3F86431704700BF0080005100440258F9 :104280000048025800C000F0020000010000FF01D9 -:1042900000828402424040001703010163020103CF +:10429000008284028280800017030101630201030F :1042A0005505FF01000001200210F000004101202F :1042B000002000524FF0B04208B5D2F8883003F029 :1042C0000103C2F8883023B1044A13680BB1506867 diff --git a/Tools/bootloaders/MatekL431-APDTelem_bl.bin b/Tools/bootloaders/MatekL431-APDTelem_bl.bin new file mode 100755 index 00000000000000..293ca93fee8251 Binary files /dev/null and b/Tools/bootloaders/MatekL431-APDTelem_bl.bin differ diff --git a/Tools/bootloaders/MicoAir405Mini_bl.bin b/Tools/bootloaders/MicoAir405Mini_bl.bin new file mode 100644 index 00000000000000..72e6d8b15a6fe7 Binary files /dev/null and b/Tools/bootloaders/MicoAir405Mini_bl.bin differ diff --git a/Tools/bootloaders/MicoAir405Mini_bl.hex b/Tools/bootloaders/MicoAir405Mini_bl.hex new file mode 100644 index 00000000000000..d5f5b127dfe20f --- /dev/null +++ b/Tools/bootloaders/MicoAir405Mini_bl.hex @@ -0,0 +1,892 @@ +:020000040800F2 +:1000000000060020E1010008390E0008F10D00088B +:10001000190E0008F10D0008110E0008E301000898 +:10002000E3010008E3010008E30100080D210008D6 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008D5310008013200087F +:100060002D3200085932000885320008E3010008EB +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008B1320008B1 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B00049300008E3010008E3010008E3010008FB +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00019330008E3010008E3010008E3010008F8 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100084528000876 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B +:10020000086040F20000CCF200004EF63471CEF2ED +:1002100000010860BFF34F8FBFF36F8F40F2000003 +:10022000C0F2F0004EF68851CEF200010860BFF334 +:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 +:100240003C71CEF200010860062080F31488BFF3F1 +:100250006F8F01F0DBFF01F0B7FF02F059FE4FF0A6 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F095FF02F087FE144C144DAC42C2 +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D0007DBF000000060020002200200000000872 +:1002E00000000020000600205837000800220020EF +:1002F0004022002040220020A82D0020E00100081C +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F0F8FAFEE701F073FA00DFFEE70000D3 +:1003400038B501F0B3FE054601F0D6FE0446D8B933 +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F0A9FE0CB14E +:1003700000F076F800F012FD00F0A0FB284600F037 +:10038000BFF800F06DF8F9E70025EDE70546EBE76B +:10039000010007B008B500F063FBA0F1200358424C +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F073FB03B05DF804FB38B5202374 +:1003C00083F311881748C3680BB101F031FB164A5B +:1003D000144800234FF47A7101F0EEFA002383F3FE +:1003E0001188124C236813B12368013B23606368B2 +:1003F00013B16368013B63600D4D2B7833B96368BB +:100400007BB9022000F03AFC322363602B78032B87 +:1004100007D163682BB9022000F030FC4FF47A73E7 +:10042000636038BD40220020BD0300085C2300202B +:1004300054220020084B187003280CD8DFE800F085 +:1004400008050208022000F009BC022000F0F4BBFD +:10045000024B00225A607047542200205C23002087 +:10046000234B244A10B51C46196801313FD0043390 +:100470009342F9D16268A24239D31F4B9B6803F1C2 +:10048000006303F540439A4231D2002000F030FB74 +:100490000220FFF7CFFF194B1A6C00221A64196E65 +:1004A0001A66196E596C5A64596E5A665A6E5A69B0 +:1004B00042F080025A615A6922F080025A615A69F8 +:1004C0001A6942F000521A611A6922F000521A6148 +:1004D0001B6972B64FF0E0232021C3F8084DD4E920 +:1004E000003281F311889D4683F30888104710BDC0 +:1004F00000C0000820C00008002200200038024090 +:100500002DE9F04F93B0AA4B00902022FF210AA8BA +:100510009D6800F0EDFBA74A1378A3B9A648012116 +:10052000C3601170202383F31188C3680BB101F0FD +:100530007FFAA24AA04800234FF47A7101F03CFAF6 +:10054000002383F31188009B13B19D4B009A1A601E +:100550009C4A009C1378032B1EBF00231370984AFB +:100560004FF0000A18BF5360D3465646D1460120CB +:1005700000F074FB24B1924B1B68002B00F0118239 +:10058000002000F06DFA0390039B002BF2DB0120AA +:1005900000F052FB039B213B162BE8D801A252F836 +:1005A00023F000BF0106000829060008BD06000868 +:1005B0006F0500086F0500086F0500084707000871 +:1005C000170900083108000893080008BB08000854 +:1005D000E10800086F050008F30800086F0500082F +:1005E00065090008A10600086F050008A9090008B0 +:1005F0000D060008A10600086F0500089308000812 +:100600000220FFF7C7FE002840F0F581009B022181 +:10061000BAF1000F08BF1C4605A841F21233ADF82D +:10062000143000F03BFAA2E74FF47A7000F018FAA9 +:10063000071EEBDB0220FFF7ADFE0028E6D0013FEE +:10064000052F00F2DA81DFE807F0030A0D101336F8 +:1006500005230593042105A800F020FA17E054486B +:100660000421F9E758480421F6E758480421F3E744 +:100670004FF01C08404600F03DFA08F104080590D0 +:10068000042105A800F00AFAB8F12C0FF2D10120DC +:1006900000FA07F747EA0B0B5FFA8BFB4FF00009F4 +:1006A00000F072FB26B10BF00B030B2B08BF0024EC +:1006B000FFF778FE5BE746480421CDE7002EA5D082 +:1006C0000BF00B030B2BA1D10220FFF763FE0746B3 +:1006D00000289BD0012000F00BFA0220FFF7AAFEB1 +:1006E00000265FFA86F8404600F012FA044690B100 +:1006F0000021404600F01CFA01360028F1D1BA462C +:10070000044641F21213022105A8ADF814303E460A +:1007100000F0C4F92BE70120FFF78CFE2546244B9F +:100720009B68AB4207D9284600F0E4F9013040F05D +:1007300067810435F3E7234B00251D70204BBA4633 +:100740005D603E46ACE7002E3FF460AF0BF00B035C +:100750000B2B7FF45BAF0220FFF76CFE322000F022 +:100760007FF9B0F10008FFF651AF18F003077FF4EE +:100770004DAF0F4A926808EB050393423FF646AF30 +:10078000B8F5807F3FF742AF124B0193B84523DDA8 +:100790004FF47A7000F064F90390039A002AFFF690 +:1007A00035AF019B039A03F8012B0137EDE700BF3A +:1007B000002200205823002040220020BD03000812 +:1007C0005C23002054220020042200200822002064 +:1007D0000C22002058220020C820FFF7DBFD07462E +:1007E00000283FF413AF1F2D11D8C5F12002424558 +:1007F0000AAB25F0030028BF424683490192184402 +:1008000000F050FA019A8048FF2100F071FA4FEA97 +:10081000A8037D490193C8F38702284600F070FAC7 +:10082000064600283FF46DAF019B05EB830537E7D3 +:100830000220FFF7AFFD00283FF4E8AE00F0A4F976 +:1008400000283FF4E3AE0027B846704B9B68BB42DC +:1008500018D91F2F11D80A9B01330ED027F003039C +:1008600012AA134453F8203C05934046042205A9DC +:1008700000F0E4FA04378046E7E7384600F03AF93A +:100880000590F2E7CDF81480042105A800F006F9E0 +:1008900006E70023642104A8049300F0F5F800287B +:1008A0007FF4B4AE0220FFF775FD00283FF4AEAE32 +:1008B000049800F051F90590E6E70023642104A8AC +:1008C000049300F0E1F800287FF4A0AE0220FFF7C7 +:1008D00061FD00283FF49AAE049800F04DF9EAE774 +:1008E0000220FFF757FD00283FF490AE00F05CF9BE +:1008F000E1E70220FFF74EFD00283FF487AE05A98F +:10090000142000F057F904210746049004A800F0D1 +:10091000C5F83946B9E7322000F0A2F8071EFFF605 +:1009200075AEBB077FF472AE384A926807EB0903D5 +:1009300093423FF66BAE0220FFF72CFD00283FF4F8 +:1009400065AE27F003074F44B9453FF4A9AE4846CA +:1009500000F0D0F80421059005A800F09FF809F1F7 +:100960000409F1E74FF47A70FFF714FD00283FF413 +:100970004DAE00F009F9002844D00A9B01330BD09A +:1009800008220AA9002000F0BBF900283AD0202252 +:10099000FF210AA800F0ACF9FFF704FD1C4800F0A5 +:1009A000C7FF13B0BDE8F08F002E3FF42FAE0BF061 +:1009B0000B030B2B7FF42AAE0023642105A80593BB +:1009C00000F062F8074600287FF420AE0220FFF70F +:1009D000E1FC804600283FF419AEFFF7E3FC41F24A +:1009E000883000F0A5FF059800F000FA464600F0B8 +:1009F000CBF93C46BBE5064652E64FF0000905E65A +:100A0000BA467EE637467CE65822002000220020C7 +:100A1000A086010070B50F4B1B780133DBB2012BB0 +:100A20000C4611D80C4D29684FF47A730E6AA2FB5C +:100A30000332014622462846B047844204D1074B80 +:100A400000221A70012070BD4FF4FA7000F070FFA0 +:100A50000020F8E7102200205025002090230020DD +:100A600007B50023024601210DF107008DF807307C +:100A7000FFF7D0FF20B19DF8070003B05DF804FB3D +:100A80004FF0FF30F9E700000A4608B50421FFF7F0 +:100A9000C1FF80F00100C0B2404208BD30B4054C37 +:100AA0002368DD69044B0A46AC460146204630BC4B +:100AB000604700BF50250020A086010070B501F0FE +:100AC000E7F9094E094D30800024286833888342B5 +:100AD00008D901F0D7F92B6804440133B4F5404F2D +:100AE0002B60F2D370BD00BF92230020642300204E +:100AF00001F090BA00F1006000F5404000687047D6 +:100B000000F10060920000F5404001F00FBA0000D3 +:100B1000054B1A68054B1B889B1A834202D9104467 +:100B200001F0B0B900207047642300209223002018 +:100B300038B5084D044629B128682044BDE838403E +:100B400001F0C0B92868204401F0A4F90028F3D0CE +:100B500038BD00BF6423002010F003030AD1B0F5B4 +:100B6000047F05D200F10050A0F51040D0F8003805 +:100B7000184670470023FBE700F10050A0F5104035 +:100B8000D0F8100A70470000064991F8243033B1BC +:100B90000023086A81F824300822FFF7B1BF012042 +:100BA000704700BF68230020014B1868704700BFE2 +:100BB000002004E0F0B51C4B024618681B4BC0F344 +:100BC0000B050424000C1E88AE421BD15C6893F90F +:100BD0000850174B05261F88874208BF93F902501B +:100BE000013E03F10403F6D1013A0A44013C0B46ED +:100BF00093420ED214F9016F581C66B100F8016CD3 +:100C00000346F5E7013C03F10C03DCD1094C3F2519 +:100C1000DFE7184605E02C2490421C7001D2981C96 +:100C20005D70401AF0BD00BF002004E05834000899 +:100C30004434000818340008022804D1054B4FF052 +:100C400080729A6170470128FCD1034B4FF48012E7 +:100C5000F7E700BF0000024000080240022804D16C +:100C6000044B4FF480729A6170470128FCD1024B0B +:100C70001022F8E70000024000080240022805D1D7 +:100C8000064A536983F48073536170470128FCD18D +:100C9000034A536983F01003F6E700BF00000240E7 +:100CA0000008024010B50023934203D0CC5CC4542A +:100CB0000133F9E710BD000010B5013810F9013F0C +:100CC0003BB191F900409C4203D11AB10131013A84 +:100CD000F4E71AB191F90020981A10BD1046FCE70C +:100CE00003460246D01A12F9011B0029FAD17047B7 +:100CF00002440346934202D003F8011BFAE770470F +:100D00002DE9F8431F4D144695F8242007468846E0 +:100D100052BBDFF870909CB395F824302BB9202299 +:100D2000FF2148462F62FFF7E3FF95F82400C0F14A +:100D30000802A24228BF2246D6B24146920005EBE5 +:100D40008000FFF7AFFF95F82430A41B1E44F6B2D5 +:100D5000082E17449044E4B285F82460DBD1FFF7F5 +:100D600013FF0028D7D108E02B6A03EB82038342EC +:100D7000CFD0FFF709FF0028CBD10020BDE8F883D2 +:100D80000120FBE768230020024B1A78024B1A70FF +:100D9000704700BF902300201022002010B50F4C98 +:100DA0000F4800F0DBF821460D4800F003F92468F5 +:100DB0000C48626DD2F8043843F00203C2F80438DC +:100DC00000F0B6FD0849204600F0FAF9626DD2F84D +:100DD000043823F00203C2F8043810BD4C35000873 +:100DE0005025002040420F00543500087047000095 +:100DF00000B59BB0EFF3098168226846FFF752FF08 +:100E0000EFF30583014B9B6BFEE700BF00ED00E0B5 +:100E100008B5FFF7EDFF000000B59BB0EFF30981C7 +:100E200068226846FFF73EFFEFF30583014B5B6BDB +:100E3000FEE700BF00ED00E0FEE7000030B5094D21 +:100E40000A4491420DD011F8013B5840082340F369 +:100E50000004013B2C4013F0FF0384EA5000F6D15C +:100E6000EFE730BD2083B8ED0268436811430160AD +:100E700003B118477047000013B5446BD4F894349D +:100E80001A681178042915D1217C022912D1197907 +:100E9000128901238B4013420CD101A904F14C00AB +:100EA00001F03CFFD4F89444019B2179024620686C +:100EB00000F0CEF902B010BD143001F0BFBE00004A +:100EC0004FF0FF33143001F0B9BE00004C3001F098 +:100ED00091BF00004FF0FF334C3001F08BBF00009A +:100EE000143001F08DBE00004FF0FF31143001F0DE +:100EF00087BE00004C3001F05DBF00004FF0FF32B4 +:100F00004C3001F057BF00000020704710B5D0F8FA +:100F100094341A6811780429044617D1017C0229F7 +:100F200014D15979528901238B4013420ED11430C8 +:100F300001F020FE024648B1D4F894444FF4807387 +:100F400061792068BDE8104000F070B910BD000064 +:100F5000406BFFF7DBBF0000704700007FB5124B0E +:100F6000036000234360C0E90233012502260F4BD2 +:100F7000057404460290019300F18402294600960C +:100F80004FF48073143001F0D1FD094B0294CDE988 +:100F9000006304F523724FF48073294604F14C007A +:100FA00001F098FE04B070BD88340008510F0008AD +:100FB000790E00080B68202282F311880A7903EB6E +:100FC000820290614A79093243F822008A7912B18B +:100FD00003EB8203986102230374C0F89414002386 +:100FE00083F311887047000038B5037F044613B1BE +:100FF00090F85430ABB9201D01250221FFF734FFD2 +:1010000004F1140025776FF0010100F0B9FC84F8B9 +:10101000545004F14C006FF00101BDE8384000F07D +:10102000AFBC38BD10B5012104460430FFF71CFFEA +:101030000023237784F8543010BD000038B50446EF +:101040000025143001F08AFD04F14C00257701F0F1 +:1010500059FE201D84F854500121FFF705FF20465A +:10106000BDE83840FFF752BF90F8443003F060030A +:10107000202B07D190F84520212A4FF0000303D8F8 +:101080001F2A06D800207047222AFBD1C0E90E3360 +:1010900003E0034A82630722C263036401207047AE +:1010A0001122002037B5D0F894341A681178042939 +:1010B00004461AD1017C022917D11979128901231A +:1010C0008B40134211D100F14C05284601F0DAFEA5 +:1010D00058B101A9284601F021FED4F89444019B9F +:1010E00021790246206800F0B3F803B030BD00005B +:1010F000F0B500EB810385B09E6904460D46FEB154 +:10110000202383F3118804EB8507301D0821FFF7A6 +:10111000ABFEFB685B691B6806F14C001BB10190DC +:1011200001F00AFE019803A901F0F8FD024648B15A +:10113000039B2946204600F08BF8002383F3118897 +:1011400005B0F0BDFB685A691268002AF5D01B8A09 +:10115000013B1340F1D104F14402EAE7093138B50B +:1011600050F82140DCB1202383F31188D4F8942473 +:101170001368527903EB8203DB689B695D6845B1B4 +:1011800004216018FFF770FE294604F1140001F0F5 +:10119000FBFC2046FFF7BAFE002383F3118838BD1D +:1011A0007047000001F0A8B8012303700023C0E9D4 +:1011B0000133C36183620362C362436203637047A6 +:1011C00038B50446202383F311880025C0E9035570 +:1011D000C0E90555416001F09FF80223237085F3B3 +:1011E000118838BD70B500EB810305465069DA609F +:1011F0000E46144618B110220021FFF779FDA069B0 +:1012000018B110220021FFF773FD31462846BDE8D2 +:10121000704001F04BB90000826802F00112826058 +:101220000022C0E90422826101F0CCB9F0B400EBE5 +:1012300081044789E4680125A4698D403D434581C7 +:1012400023600023A2606360F0BC01F0E7B90000F6 +:10125000F0B400EB81040789E468012564698D40DE +:101260003D43058123600023A2606360F0BC01F070 +:1012700061BA000070B50223002504460370C0E97E +:101280000255C0E90455C564856180F8345001F009 +:10129000A9F863681B6823B129462046BDE8704061 +:1012A000184770BD037880F85030052303704368F9 +:1012B0001B6810B504460BB1042198470023A360B6 +:1012C00010BD000090F85020436802701B680BB1FD +:1012D000052118477047000070B590F83430044677 +:1012E00013B1002380F8343004F14402204601F0A9 +:1012F0008BF963689B68B3B994F8443013F06005C8 +:1013000035D00021204601F0DDFB0021204601F010 +:10131000CFFB63681B6813B106212046984706235C +:1013200084F8343070BD204698470028E4D0B4F8E3 +:101330004A30E26B9A4288BFE36394F94430E56B2C +:10134000002B4FF0200380F20381002D00F0F2808B +:10135000092284F8342083F311880021D4E90E2374 +:101360002046FFF775FF002383F31188DAE794F82E +:10137000452003F07F0343EA022340F20232934206 +:1013800000F0C58021D8B3F5807F48D00DD8012B5F +:101390003FD0022B00F09380002BB2D104F14C021D +:1013A000A2630222E2632364C1E7B3F5817F00F008 +:1013B0009B80B3F5407FA4D194F84630012BA0D197 +:1013C000B4F84C3043F0020332E0B3F5006F4DD077 +:1013D00017D8B3F5A06F31D0A3F5C063012B90D817 +:1013E000636894F846205E6894F84710B4F8483073 +:1013F0002046B047002884D04368A3630368E363B2 +:101400001AE0B3F5106F36D040F6024293427FF4F3 +:1014100078AF5C4BA3630223E3630023C3E794F834 +:101420004630012B7FF46DAFB4F84C3023F002034B +:10143000C4E90E55A4F84C30256478E7B4F844307C +:10144000B3F5A06F0ED194F8463084F84E302046A4 +:1014500001F020F863681B6813B10121204698470A +:10146000032323700023C4E90E339CE704F14F03E8 +:10147000A3630123C3E72378042B10D1202383F334 +:1014800011882046FFF7C8FE85F3118803216368A1 +:1014900084F84F5021701B680BB12046984794F890 +:1014A0004630002BDED084F84F300423237063686D +:1014B0001B68002BD6D0022120469847D2E794F82B +:1014C00048301D0603F00F0120460AD501F08EF8C2 +:1014D000012804D002287FF414AF2B4B9AE72B4B42 +:1014E00098E701F075F8F3E794F84630002B7FF4A5 +:1014F00008AF94F8483013F00F01B3D01A06204615 +:1015000002D501F0F3FAADE701F0E6FAAAE794F8A4 +:101510004630002B7FF4F5AE94F8483013F00F01FD +:10152000A0D01B06204602D501F0CCFA9AE701F0C4 +:10153000BFFA97E7142284F8342083F311882B46EE +:101540002A4629462046FFF771FE85F31188E9E611 +:101550005DB1152284F8342083F311880021D4E989 +:101560000E232046FFF762FEFDE60B2284F83420AE +:1015700083F311882B462A4629462046FFF768FE4A +:10158000E3E700BFB8340008B0340008B434000802 +:1015900038B590F834300446002B3ED0063BDAB222 +:1015A0000F2A34D80F2B32D8DFE803F03731310857 +:1015B000223231313131313131313737C56BB0F809 +:1015C0004A309D4214D2C3681B8AB5FBF3F203FB79 +:1015D00012556DB9202383F311882B462A462946DC +:1015E000FFF736FE85F311880A2384F834300EE0C5 +:1015F000142384F83430202383F3118800231A46FF +:1016000019462046FFF712FE002383F3118838BDE8 +:10161000036C03B198470023E7E70021204601F05F +:1016200051FA0021204601F043FA63681B6813B1A8 +:101630000621204698470623D7E7000010B590F80A +:101640003430142B044629D017D8062B05D001D8E6 +:101650001BB110BD093B022BFBD80021204601F035 +:1016600031FA0021204601F023FA63681B6813B1A8 +:10167000062120469847062319E0152BE9D10B23B4 +:1016800080F83430202383F3118800231A4619464A +:10169000FFF7DEFD002383F31188DAE7C3689B6957 +:1016A0005B68002BD5D1036C03B19847002384F805 +:1016B0003430CEE7024B0022C3E900339A60704712 +:1016C00094230020002303748268054B1B689968EB +:1016D0009142FBD25A6803604260106058607047C4 +:1016E0009423002008B5202383F31188037C032B67 +:1016F00005D0042B0DD02BB983F3118808BD4369A5 +:1017000000221A604FF0FF334361FFF7DBFF002335 +:10171000F2E7D0E9003213605A60F3E70023037464 +:101720008268054B1B6899689142FBD85A68036030 +:10173000426010605860704794230020054B19697F +:101740000874186802681A605360186101230374F2 +:10175000FEF7DCBD9423002030B54B1C0B4D87B049 +:10176000044610D02B690A4A01A800F025F920464A +:10177000FFF7E4FF049B13B101A800F059F92B69AE +:10178000586907B030BDFFF7D9FFF8E79423002070 +:10179000E516000838B50C4D41612B6981689A68DF +:1017A0009142044603D8BDE83840FFF78BBF184686 +:1017B000FFF7B4FF01232C61014623742046BDE8E6 +:1017C0003840FEF7A3BD00BF94230020044B1A68E5 +:1017D0001B6990689B68984294BF00200120704765 +:1017E0009423002010B5084C236820691A682260F1 +:1017F0005460012223611A74FFF790FF01462069AB +:10180000BDE81040FEF782BD9423002008B5FFF725 +:10181000DDFF18B1BDE80840FFF7E4BF08BD0000D8 +:10182000FFF7E0BFFEE7000010B50C4CFFF742FFEA +:1018300000F0B4F80A498022204600F03BF801236A +:1018400044F8180C037400F071FC002383F3118832 +:1018500062B60448BDE8104000F04CB8BC2300203C +:10186000BC340008CC34000800F01CB9EFF3118040 +:1018700020B9EFF30583202282F31188704700001E +:1018800010B530B9EFF30584C4F3080414B180F344 +:10189000118810BDFFF7BAFF84F31188F9E7000043 +:1018A000034A516853685B1A9842FBD8704700BFDF +:1018B000001000E082600222028270478368A3F178 +:1018C0007C0243F80C2C026943F83C2C426943F833 +:1018D000382C074A43F81C2CC26843F8102C02220B +:1018E00003F8082C002203F8072CA3F11800704716 +:1018F0002503000810B5202383F31188FFF7DEFFCE +:1019000000210446FFF746FF002383F31188204699 +:1019100010BD0000024B1B6958610F20FFF70EBF7E +:1019200094230020202383F31188FFF7F3BF0000E6 +:1019300008B50146202383F311880820FFF70CFF28 +:10194000002383F3118808BD49B1064B42681B6927 +:1019500018605A60136043600420FFF7FDBE4FF02B +:10196000FF307047942300200368984206D01A681D +:101970000260506059611846FFF7A4BE704700002E +:1019800038B504460D462068844200D138BD03684E +:1019900023605C604561FFF795FEF4E7054B03F1BA +:1019A0001402C3E905224FF0FF310022C3E90712F8 +:1019B000704700BF9423002070B51C4EC0E903237C +:1019C00005460C4601F090FA334653F8142F9A421C +:1019D0000DD13062C5E901242A600A2C2CBF001900 +:1019E0000A30C6E90555BDE8704001F06BBA316AAE +:1019F000431AE31838BF1C469368A34202D908195A +:101A000001F06EFA73699A6894420CD85A68AC6017 +:101A10002B606A6015609A685D60121B9A604FF0D7 +:101A2000FF33F36170BD1B68A41AECE79423002018 +:101A300038B51B4C636998420DD0D0E90032136071 +:101A40005A6000228168C2609A680A449A604FF026 +:101A5000FF33E36138BD2246036842F8143F00219A +:101A600093425A60C16003D1BDE8384001F032BAF8 +:101A70009A688168256A0A449A6001F035FA6369B8 +:101A80009A68411B8A42E5D9AB181D1A092D206AB4 +:101A900098BF01F10A02BDE83840104401F020BAB5 +:101AA000942300202DE9F041184C002704F114067E +:101AB000656901F019FA236AAA68C11A8A4215D821 +:101AC00013442362D5E9003213605A606369D5F884 +:101AD0000C80EF60B34201D101F0FCF987F311886B +:101AE0002869C047202383F31188E1E76169B14287 +:101AF00009D013441B1ABDE8F0410A2B2CBFC018B3 +:101B00000A3001F0EDB9BDE8F08100BF9423002058 +:101B100000207047FEE70000704700004FF0FF30E4 +:101B20007047000002290CD0032904D0012907487E +:101B300018BF00207047032A05D8054800EBC200F3 +:101B40007047044870470020704700BFB035000858 +:101B5000202200206435000870B59AB0054608467A +:101B600001A9144600F0C2F801A8FFF7B9F8431C18 +:101B70005B00C5E900340022237003236370C6B202 +:101B800001AB02341046D1B28E4204F1020401D8F6 +:101B90001AB070BD13F8011B04F8021C04F8010C04 +:101BA0000132F0E708B5202383F311880348FFF7DB +:101BB00079FA002383F3118808BD00BF5025002067 +:101BC00090F8443003F01F02012A07D190F8452015 +:101BD0000B2A03D10023C0E90E3315E003F06003A4 +:101BE000202B08D1B0F848302BB990F84520212A95 +:101BF00003D81F2A04D8FFF737BA222AEBD0FAE716 +:101C0000034A82630722C26303640120704700BF56 +:101C10001822002007B5052917D8DFE801F01916AA +:101C200003191920202383F31188104A0190012100 +:101C3000FFF7D8FA01980E4A0221FFF7D3FA0D48B0 +:101C4000FFF7FCF9002383F3118803B05DF804FB70 +:101C5000202383F311880748FFF7C6F9F2E7202312 +:101C600083F311880348FFF7DDF9EBE7043500083B +:101C7000283500085025002038B50C4D0C4C0D4976 +:101C80002A4604F10800FFF767FF05F1CA0204F1D4 +:101C900010000949FFF760FF05F5CA7204F118004A +:101CA0000649BDE83840FFF757BF00BF182A00209B +:101CB00020220020E4340008EE340008F934000843 +:101CC00070B5044608460D46FFF70AF8C6B220462E +:101CD000013403780BB9184670BD32462946FEF729 +:101CE000EBFF0028F3D10120F6E700002DE9F047D3 +:101CF00005460C46FEF7F4FF2B49C6B22846FFF70F +:101D0000DFFF08B10736F6B228492846FFF7D8FFAB +:101D100008B11036F6B2632E0BD8DFF88C80DFF8EE +:101D20008C90234FDFF894A02E7846B92670BDE83A +:101D3000F08729462046BDE8F04701F065BB252E17 +:101D40002ED1072241462846FEF7B6FF70B9194B3F +:101D5000224603F10C0153F8040B42F8040B8B42AA +:101D6000F9D11B88138007350E34DDE70822494678 +:101D70002846FEF7A1FF98B90F4BA21C1978090954 +:101D80000232C95D02F8041C13F8011B01F00F01B7 +:101D90005345C95D02F8031CF0D118340835C3E778 +:101DA00004F8016B0135BFE7D0350008F9340008AD +:101DB000E7350008D8350008107AFF1F1C7AFF1F8E +:101DC000BFF34F8F024AD368DB03FCD4704700BFD8 +:101DD000003C024008B5094B1B7873B9FFF7F0FFD0 +:101DE000074B1A69002ABFBF064A5A6002F18832BF +:101DF0005A601A6822F480621A6008BD762C0020AE +:101E0000003C02402301674508B50B4B1B7893B992 +:101E1000FFF7D6FF094B1A6942F000421A611A68AF +:101E200042F480521A601A6822F480521A601A68CA +:101E300042F480621A6008BD762C0020003C02400B +:101E40000B28F0B516D80C4C0C4923787BB90C4DF7 +:101E50000E460C234FF0006255F8047B46F8042B25 +:101E6000013B13F0FF033A44F6D10123237051F8EC +:101E70002000F0BD0020FCE7A82C0020782C0020DA +:101E8000F8350008014B53F820007047F83500087A +:101E90000C2070470B2810B5044601D9002010BD56 +:101EA000FFF7CEFF064B53F824301844C21A0BB983 +:101EB0000120F4E712680132F0D1043BF6E700BFDD +:101EC000F83500080B2838B5044628D8FFF7CEFCB3 +:101ED000FFF776FFFFF77EFF124AF323D360E3009C +:101EE000DBB243F4007343F002031361136943F45C +:101EF0008033136105462046FFF762FFFFF7A0FF1E +:101F0000094B53F8241000F0E9F82846FFF77CFF4E +:101F1000FFF7B6FC2046BDE83840FFF7BBBF002006 +:101F200038BD00BF003C0240F835000812F0010344 +:101F30002DE9F04105460E4614464BD18218B2F108 +:101F4000016F61D8314B1B6813F001035CD0304F37 +:101F5000FFF78CFCFFF73EFFF323FB60FFF730FF3A +:101F6000314640F20128032C18D824F00104284EF1 +:101F70000C446D1A40F20118A142336905EB0107C8 +:101F80002AD123F001033361FFF73EFFFFF778FC0E +:101F90000120BDE8F081043C0435E4E7AB07E4D15F +:101FA0003B6923F440733B613B6943EA08033B61AF +:101FB00051F8046B2E60BFF34F8FFFF701FF2B68C2 +:101FC0009E42E8D03B6923F001033B61FFF71CFF11 +:101FD000FFF756FC0020DCE723F4407333613369DC +:101FE00043EA080333610B883B80BFF34F8FFFF751 +:101FF000E7FE3F8831F8023BBFB2BB42BCD0336939 +:1020000023F001033361E1E71846C2E700380240DC +:10201000003C0240084908B50B7828B11BB9FFF70E +:10202000D9FE01230B7008BD002BFCD0BDE8084091 +:102030000870FFF7E9BE00BF762C002010B50244FF +:10204000064BD2B2904200D110BD441C00B253F8EE +:10205000200041F8040BE0B2F4E700BF5028004034 +:102060000F4B30B51C6F240407D41C6F44F400746C +:102070001C671C6F44F400441C670A4C236843F43B +:10208000807323600244084BD2B2904200D130BD2D +:10209000441C00B251F8045B43F82050E0B2F4E76E +:1020A00000380240007000405028004007B501226F +:1020B00001A90020FFF7C2FF019803B05DF804FBFF +:1020C00013B50446FFF7F2FFA04205D0012201A993 +:1020D00000200194FFF7C4FF02B010BD704700005C +:1020E000034B1A681AB9034AD2F874281A60704769 +:1020F000AC2C00200030024008B5FFF7F1FF024B86 +:102100001868C0F3407008BDAC2C0020EFF30983C1 +:1021100005494A6B22F001024A63683383F3098858 +:10212000002383F31188704700EF00E0202080F344 +:10213000118862B60C4B0D4AD96821F4E06109049C +:10214000090C0A43DA60D3F8FC20094942F0807296 +:10215000C3F8FC200A6842F001020A601022DA7714 +:1021600083F82200704700BF00ED00E00003FA058D +:10217000001000E010B5202383F311880E4B5B683C +:1021800013F4006314D0F1EE103AEFF30984683CC5 +:102190004FF08073E361094BDB6B236684F309889E +:1021A000FFF714FB10B1064BA36110BD054BFBE715 +:1021B00083F31188F9E700BF00ED00E000EF00E0D5 +:1021C000370300083A03000870470000FEE70000EC +:1021D0000A4B0B480B4A90420BD30B4BDA1C121ADA +:1021E000C11E22F003028B4238BF00220021FEF7FD +:1021F0007FBD53F8041B40F8041BECE79837000838 +:10220000A82D0020A82D0020A82D00207047000038 +:1022100070B5D0E915439E6800224FF0FF3504EBFE +:1022200042135101D3F800090028BEBFD3F80009BA +:1022300040F08040C3F80009D3F8000B0028BEBF6F +:10224000D3F8000B40F08040C3F8000B0132631854 +:102250009642C3F80859C3F8085BE0D24FF0011367 +:10226000C4F81C3870BD00001D4B03EB80022DE943 +:10227000F043D2F80CC05D6DDCF81420461CD2F897 +:1022800000E005EB063605EB4018516871450AD3AE +:10229000D5F83438012202FA00F023EA0000C5F82C +:1022A0003408BDE8F083BCF81040AEEB0103A34254 +:1022B00028BF2346D8F81849A4B2B3EB840FF0D84E +:1022C0009468A4F1040959F8047F3760A4EB090766 +:1022D0001F44042FF7D81C440B4494605360D4E788 +:1022E000B02C0020890141F02001016103699B06A7 +:1022F000FCD41220FFF7D4BA10B5054C2046FEF7E7 +:1023000053FF4FF0A0436365024BA36510BD00BFB0 +:10231000B02C00204C36000870B50378012B054620 +:1023200050D12A4B446D98421BD1294B5A6B42F035 +:1023300080025A635A6D42F080025A655A6D5A699A +:1023400042F080025A615A6922F080025A610E21DD +:1023500043205B6900F0D4FB1E4BE3601E4BC4F8C6 +:1023600000380023C4F8003EC02323606E6D4FF494 +:102370000413A3633369002BFCDA012333610C20BF +:10238000FFF78EFA3369DB07FCD41220FFF788FAD7 +:102390003369002BFCDA0026A6602846FFF738FFD9 +:1023A0006B68C4F81068DB68C4F81468C4F81C686B +:1023B0004BB90A4BA3614FF0FF336361A36843F04D +:1023C0000103A36070BD064BF4E700BFB02C0020F2 +:1023D000003802404014004003002002003C30C09E +:1023E000083C30C0F8B5446D054600212046FFF793 +:1023F00079FFA96D00234FF001128F68C4F83438BB +:102400004FF00066C4F81C284FF0FF3004EB431275 +:1024100001339F42C2F80069C2F8006BC2F8080994 +:10242000C2F8080BF2D20B686A6DEB656362102389 +:102430001361166916F01006FBD11220FFF730FA6F +:10244000D4F8003823F4FE63C4F80038A36943F4D9 +:10245000402343F01003A3610923C4F81038C4F8E3 +:1024600014380A4BEB604FF0C043C4F8103B084BE4 +:10247000C4F8003BC4F81069C4F80039EB6D03F1EF +:10248000100243F48013EA65A362F8BD2836000801 +:1024900040800010426D90F84E10D2F8003823F4BE +:1024A000FE6343EA0113C2F8003870472DE9F84390 +:1024B00000EB8103456DDA68166806F00306731EAB +:1024C000022B05EB41130C4680460FFA81F94FEAC7 +:1024D00041104FF00001C3F8101B4FF0010104F14F +:1024E000100398BFB60401FA03F391698EBF334E0F +:1024F00006F1805606F5004600293AD0578A04F1C5 +:102500005801490137436F50D5F81C180B43C5F8E3 +:102510001C382B180021C3F8101953690127611EBC +:10252000A7409BB3138A928B9B08012A88BF534311 +:10253000D8F85C20981842EA034301F1400205EB09 +:102540008202C8F85C00214653602846FFF7CAFEA5 +:1025500008EB8900C3681B8A43EA8453483464014A +:102560001E432E51D5F81C381F43C5F81C78BDE812 +:10257000F88305EB4917D7F8001B21F40041C7F891 +:10258000001BD5F81C1821EA0303C0E704F13F0340 +:1025900005EB83030A4A5A6028462146FFF7A2FE4C +:1025A00005EB4910D0F8003923F40043C0F8003996 +:1025B000D5F81C3823EA0707D7E700BF00800010D2 +:1025C00000040002826D1268C265FFF721BE0000A0 +:1025D0005831436D49015B5813F4004004D013F4A3 +:1025E000001F0CBF02200120704700004831436DDE +:1025F00049015B5813F4004004D013F4001F0CBFD2 +:10260000022001207047000000EB8101CB68196AAD +:102610000B6813604B6853607047000000EB810348 +:1026200030B5DD68AA691368D36019B9402B84BF3F +:10263000402313606B8A1468426D1C44013CB4FB58 +:10264000F3F46343033323F0030302EB411043EA43 +:10265000C44343F0C043C0F8103B2B6803F00303AE +:10266000012B09B20ED1D2F8083802EB411013F455 +:10267000807FD0F8003B14BF43F0805343F00053F9 +:10268000C0F8003B02EB4112D2F8003B43F0044398 +:10269000C2F8003B30BD00002DE9F041244D6E6DC5 +:1026A00006EB40130446D3F8087BC3F8087B3807D1 +:1026B0000AD5D6F81438190706D505EB8403214648 +:1026C000DB6828465B689847FA071FD5D6F81438A8 +:1026D000DB071BD505EB8403D968CCB98B69488A25 +:1026E0005A68B2FBF0F600FB16228AB91868DA685D +:1026F00090420DD2121AC3E90024202383F31188DB +:102700000B482146FFF78AFF84F31188BDE8F0816A +:10271000012303FA04F26B8923EA02036B81CB687D +:10272000002BF3D021460248BDE8F041184700BF16 +:10273000B02C002000EB810370B5DD68436D6C693F +:102740002668E6604A0156BB1A444FF40020C2F8DE +:1027500010092A6802F00302012A0AB20ED1D3F846 +:10276000080803EB421410F4807FD4F8000914BF6A +:1027700040F0805040F00050C4F8000903EB4212D2 +:10278000D2F8000940F00440C2F80009D3F8340838 +:10279000012202FA01F10143C3F8341870BD19B9DE +:1027A000402E84BF4020206020682E8A8419013C7E +:1027B000B4FBF6F440EAC44040F000501A44C6E7C7 +:1027C000F8B504461E48456D05EB4413D3F8086977 +:1027D000C3F80869F10717D5D5F81038DA0713D50B +:1027E00000EB8403D9684B691F68DA68974218D2F6 +:1027F000D21B00271A605F60202383F311882146D3 +:10280000FFF798FF87F31188330617D5D5F83428DA +:102810000123A340134211D02046BDE8F840FFF742 +:1028200023BD012303FA04F2038923EA020303818F +:102830008B68002BE8D021469847E5E7F8BD00BF3C +:10284000B02C00202DE9F74F984C666D7569B3697F +:102850001D4015F48058756107D02046FEF70AFD2B +:1028600003B0BDE8F04FFFF785BC002D12DAD6F8B3 +:10287000003E8E489F071EBFD6F8003E23F003039C +:10288000C6F8003ED6F8043823F00103C6F8043831 +:10289000FEF718FD280505D58448FFF7B9FC8348E5 +:1028A000FEF700FDA9040CD5D6F8083813F0060F82 +:1028B000F36823F470530CBF43F4105343F4A05354 +:1028C000F3602A0704D56368DB680BB17748984743 +:1028D000EB0274D4AF0227D5D4F85490DFF8CCB112 +:1028E00000274FF0010A09EB4712D2F8003B03F42E +:1028F0004023B3F5802F11D1D2F8003B002B0DDA25 +:1029000062890AFA07F322EA0303638104EB87036F +:10291000DB68DB6813B1394658469847A36D013729 +:102920009B68FFB29F42DED9E80617D5676D3A6A09 +:10293000C2F30A1002F00F0302F4F012B2F5802F76 +:1029400000F08880B2F5402F08D104EB8303002209 +:10295000DB681B6A07F5805790426DD12903D6F8D2 +:10296000184813D5E20302D50020FFF795FEA30314 +:1029700002D50120FFF790FE670302D50220FFF782 +:102980008BFE260302D50320FFF786FE6D037FF53D +:1029900067AFE00702D50020FFF712FFA10702D5BD +:1029A0000120FFF70DFF620702D50220FFF708FFA5 +:1029B00023077FF555AF0320FFF702FF50E7636D54 +:1029C000DFF8E8B0019300274FF0010AA36D9B6880 +:1029D0005FFA87F999453FF67DAF019B03EB4913F9 +:1029E000D3F8002902F44022B2F5802F22D1D3F887 +:1029F0000029002A1EDAD3F8002942F09042C3F8D9 +:102A00000029D3F80029002AFBDB606D4946FFF757 +:102A100069FC22890AFA09F322EA0303238104EB01 +:102A20008903DB689B6813B1494658469847484676 +:102A3000FFF71AFC0137C9E7910708BFD7F80080F4 +:102A4000072A98BF03F8018B02F1010298BF4FEAF1 +:102A5000182881E7023304EB830207F58057526898 +:102A6000D2F818C0DCF80820DCE9001CA1EB0C0C43 +:102A7000002188420AD104EB830463689B699A6849 +:102A800002449A605A6802445A6067E711F0030FE3 +:102A900008BFD7F800808C4588BF02F8018B01F190 +:102AA000010188BF4FEA1828E3E700BFB02C0020DF +:102AB000436D03EB4111D1F8003B43F40013C1F81F +:102AC000003B7047436D03EB4111D1F8003943F4EB +:102AD0000013C1F800397047436D03EB4111D1F881 +:102AE000003B23F40013C1F8003B7047436D03EB38 +:102AF0004111D1F8003923F40013C1F800397047AF +:102B000000F1604303F561430901C9B283F8001382 +:102B1000012200F01F039A4043099B0003F1604328 +:102B200003F56143C3F880211A60704730B5039CF8 +:102B30000172043304FB0325C0E90653049B0363BD +:102B40000021059BC160C0E90000C0E90422C0E982 +:102B50000842C0E90A11436330BD0000416A002207 +:102B6000C0E90411C0E90A22C2606FF00101FEF75A +:102B700007BF0000D0E90432934201D1C2680AB90C +:102B8000181D70470020704703691960C268013240 +:102B9000C260C269134482690361934224BF436ADD +:102BA00003610021FEF7E0BE38B504460D46E36838 +:102BB0003BB16269131D1268A3621344E3620020F3 +:102BC00007E0237A33B929462046FEF7BDFE0028E8 +:102BD000EDDA38BD6FF00100FBE70000C368C269A1 +:102BE000013BC3604369134482694361934224BF3C +:102BF000436A436100238362036B03B11847704744 +:102C000070B52023044683F31188866A3EB9FFF726 +:102C1000CBFF054618B186F31188284670BDA36A1C +:102C2000E26A13F8015BA362934202D32046FFF7E6 +:102C3000D5FF002383F31188EFE700002DE9F84F5B +:102C400004460E46174698464FF0200989F311882E +:102C50000025AA46D4F828B0BBF1000F09D141469F +:102C60002046FFF7A1FF20B18BF311882846BDE86D +:102C7000F88FD4E90A12A7EB050B521A934528BF27 +:102C80009346BBF1400F1BD9334601F1400251F886 +:102C9000040B43F8040B9142F9D1A36A4033403648 +:102CA000A3624035D4E90A239A4202D32046FFF7B3 +:102CB00095FF8AF31188BD42D8D289F31188C9E7FC +:102CC00030465A46FDF7EEFFA36A5B445E44A362BA +:102CD0005D44E7E710B5029C0172043304FB032155 +:102CE000C0E906130023C0E90A33039B0363049B76 +:102CF000C460C0E90000C0E90422C0E9084243639F +:102D000010BD0000026AC260426AC0E904220022CB +:102D1000C0E90A226FF00101FEF732BED0E90423B8 +:102D20009A4201D1C26822B9184650F8043B0B60A0 +:102D30007047002070470000C368C2690133C36058 +:102D40004369134482694361934224BF436A4361E8 +:102D50000021FEF709BE000038B504460D46E368C1 +:102D60003BB123691A1DA262E2691344E3620020A9 +:102D700007E0237A33B929462046FEF7E5FD00280F +:102D8000EDDA38BD6FF00100FBE700000369196060 +:102D9000C268013AC260C269134482690361934206 +:102DA00024BF436A036100238362036B03B11847A6 +:102DB0007047000070B520230D460446114683F38A +:102DC0001188866A2EB9FFF7C7FF10B186F3118804 +:102DD00070BDA36A1D70A36AE26A01339342A362C5 +:102DE00004D3E16920460439FFF7D0FF002080F3C7 +:102DF0001188EDE72DE9F84F04460D4690469946B7 +:102E00004FF0200A8AF311880026B346A76A4FB90B +:102E100049462046FFF7A0FF20B187F311883046CE +:102E2000BDE8F88FD4E90A073A1AA8EB06079742DB +:102E300028BF1746402F1BD905F1400355F8042B36 +:102E400040F8042B9D42F9D1A36A4033A362403677 +:102E5000D4E90A239A4204D3E16920460439FFF7F2 +:102E600095FF8BF311884645D9D28AF31188CDE7B7 +:102E700029463A46FDF716FFA36A3B443D44A36248 +:102E80003E44E5E7D0E904239A4217D1C3689BB1D9 +:102E9000836A8BB1043B9B1A0ED01360C368013B5D +:102EA000C360C3691A44836902619A4224BF436ABA +:102EB0000361002383620123184670470023FBE768 +:102EC00000F088B84FF08043002258631A61022254 +:102ED000DA6070474FF080430022DA6070470000EC +:102EE0004FF08043586370474FF08043586A7047F3 +:102EF0004B6843608B688360CB68C3600B69436138 +:102F00004B6903628B6943620B6803607047000082 +:102F100008B5264B26481A6940F2FF110A431A6188 +:102F20001A6922F4FF7222F001021A611A691A6BFF +:102F30000A431A631A6D0A431A651E4A1B6D11462D +:102F4000FFF7D6FF02F11C0100F58060FFF7D0FF0C +:102F500002F1380100F58060FFF7CAFF02F1540169 +:102F600000F58060FFF7C4FF02F1700100F580609A +:102F7000FFF7BEFF02F18C0100F58060FFF7B8FF9C +:102F800002F1A80100F58060FFF7B2FF02F1C40171 +:102F900000F58060FFF7ACFF02F1E00100F5806012 +:102FA000FFF7A6FFBDE8084000F09AB800380240DD +:102FB000000002405836000808B500F007FAFEF796 +:102FC00033FCFFF78DF8BDE80840FEF755BE000062 +:102FD00070470000104B1A6C42F001021A641A6E1E +:102FE00042F001021A660D4A1B6E936843F001031A +:102FF00093604FF0804353229A624FF0FF32DA62BF +:1030000000229A615A63DA605A6001225A610821EB +:103010001A601C20FFF774BD00380240002004E055 +:103020004FF0804208B51169D3680B40D9B2C9434B +:103030009B07116107D5202383F31188FEF714FC49 +:10304000002383F3118808BD08B5FFF7E9FFBDE849 +:103050000840FFF78FB800001F4B1A696FEAC25291 +:103060006FEAD2521A611A69C2F308021A614FF06C +:10307000FF301A695A69586100215A6959615A69C1 +:103080001A6A62F080521A621A6A02F080521A6258 +:103090001A6A5A6A58625A6A59625A6A1A6C42F033 +:1030A00080521A641A6E42F080521A661A6E0B4AE7 +:1030B000106840F480701060186F00F44070B0F534 +:1030C000007F1EBF4FF4803018671967536823F4E0 +:1030D0000073536000F05AB900380240007000409D +:1030E000334B4FF080521A64324A4FF44041116022 +:1030F0001A6842F001021A601A689107FCD59A68B2 +:1031000022F003029A602A4B9A6812F00C02FBD15B +:10311000196801F0F90119609A601A6842F4803266 +:103120001A601A689203FCD55A6F42F001025A677E +:103130001F4B5A6F9007FCD51F4A5A601A6842F01D +:1031400080721A601B4A53685904FCD5184B1A68E0 +:103150009201FCD5194A9A60194B1A68194B9A4288 +:10316000194B21D1194A1168194A91421CD140F2D8 +:1031700005121A60144A136803F00F03052BFAD1E5 +:103180000B4B9A6842F002029A609A6802F00C02B5 +:10319000082AFAD15A6C42F480425A645A6E42F4B8 +:1031A00080425A665B6E704740F20572E1E700BFED +:1031B00000380240007000400854400700948838EE +:1031C000002004E011640020003C024000ED00E01B +:1031D00041C20F41084A08B5516913680B4003F01A +:1031E0000103536123B1054A13680BB15068984736 +:1031F000BDE80840FEF7BEBF003C0140282D00207E +:10320000084A08B5516913680B4003F00203536183 +:1032100023B1054A93680BB1D0689847BDE80840D0 +:10322000FEF7A8BF003C0140282D0020084A08B541 +:10323000516913680B4003F00403536123B1054A3D +:1032400013690BB150699847BDE80840FEF792BF7B +:10325000003C0140282D0020084A08B55169136838 +:103260000B4003F00803536123B1054A93690BB186 +:10327000D0699847BDE80840FEF77CBF003C01409C +:10328000282D0020084A08B5516913680B4003F047 +:103290001003536123B1054A136A0BB1506A984772 +:1032A000BDE80840FEF766BF003C0140282D002025 +:1032B000174B10B55A691C68144004F478725A61AF +:1032C000A30604D5134A936A0BB1D06A98476006E7 +:1032D00004D5104A136B0BB1506B9847210604D5E7 +:1032E0000C4A936B0BB1D06B9847E20504D5094AA1 +:1032F000136C0BB1506C9847A30504D5054A936C29 +:103300000BB1D06C9847BDE81040FEF733BF00BF4B +:10331000003C0140282D00201A4B10B55A691C684A +:10332000144004F47C425A61620504D5164A136DB8 +:103330000BB1506D9847230504D5134A936D0BB11B +:10334000D06D9847E00404D50F4A136E0BB1506E50 +:103350009847A10404D50C4A936E0BB1D06E9847E0 +:10336000620404D5084A136F0BB1506F98472304C9 +:1033700004D5054A936F0BB1D06F9847BDE8104054 +:10338000FEF7F8BE003C0140282D0020062108B5BC +:103390000846FFF7B5FB06210720FFF7B1FB062122 +:1033A0000820FFF7ADFB06210920FFF7A9FB062146 +:1033B0000A20FFF7A5FB06211720FFF7A1FBBDE8B8 +:1033C000084006212820FFF79BBB000008B5FFF747 +:1033D00043FE00F00BF8FDF7E5FEFDF7BDFDFFF73E +:1033E000F7FDBDE80840FFF76BBD00000023054A6C +:1033F00019460133102BC2E9001102F10802F8D17D +:10340000704700BF282D0020034611F8012B03F858 +:10341000012B002AF9D1704753544D3332463F3FB8 +:103420003F00000053544D3332463430780053543B +:103430004D3332463432780053544D3332463434AF +:1034400036585800012033000010410001105A0086 +:103450000310590007103100000000001834000864 +:103460003F00000013040000243400083F00000067 +:10347000190400002E3400083F0000002104000061 +:10348000383400083F00000000000000D50E00089E +:10349000C10E0008FD0E0008E90E0008F50E000838 +:1034A000E10E0008CD0E0008B90E0008090F000853 +:1034B0000000000001000000000000006D61696E66 +:1034C0000000000069646C6500000000C43400085E +:1034D000D8230020502500200100000025180008F6 +:1034E000000000004172647550696C6F74002542E1 +:1034F0004F415244252D424C002553455249414CE1 +:10350000250000000200000000000000F11000088B +:103510005D11000840004000E8290020F829002043 +:103520000200000000000000030000000000000096 +:10353000A11100080000000010000000082A00206F +:10354000000000000100000000000000B02C00207E +:1035500001010200151C0008251B0008C11B000802 +:10356000A51B0008430000006C3500080902430059 +:10357000020100C03209040000010202010005241A +:1035800000100105240100010424020205240600A4 +:1035900001070582030800FF09040100020A000078 +:1035A00000070501024000000705810240000000FD +:1035B00012000000B835000812011001020000409E +:1035C000091241570002010203010000040309042B +:1035D00025424F41524425004D69636F4169723461 +:1035E00030354D696E690030313233343536373815 +:1035F000394142434445460000400000004000007D +:103600000040000000400000000001000000020037 +:1036100000000200000002000000020000000200A2 +:10362000000002000000020000000000D9120008A3 +:10363000911500083D16000840004000102D0020A4 +:10364000102D002001000000202D0020800000002F +:1036500040010000030000000000810200000000A3 +:10366000AAAAAAAA00000000FFFE000000000000B5 +:1036700000A00A000000000100000000AAAAAAAAF7 +:1036800000000001FFFF000000000000000000003B +:103690000001041400000000AAAAAAAA0000041451 +:1036A000EFFF00000000000000000000000000002C +:1036B00000000000AAAAAAAA00000000FFFF000064 +:1036C00000000000000000000000000000000000FA +:1036D000AAAAAAAA00000000FFFF00000000000044 +:1036E000000000000000000000000000AAAAAAAA32 +:1036F00000000000FFFF00000000000000000000CC +:103700000000000000000000AAAAAAAA0000000011 +:10371000FFFF0000000000000000000000000000AB +:10372000000000000A00000000000000030000008C +:103730000000000000000000000000000000000089 +:103740000000000000000000000000000000000079 +:1037500000000000000000008904000000000000DC +:1037600000400F0000000000FF009600000000086D +:10377000009600000000080004000000CC3500089E +:103780000000000000000000000000000000000039 +:08379000000000000000000031 +:00000001FF diff --git a/Tools/bootloaders/MicoAir743_bl.bin b/Tools/bootloaders/MicoAir743_bl.bin new file mode 100644 index 00000000000000..e4880f850cd331 Binary files /dev/null and b/Tools/bootloaders/MicoAir743_bl.bin differ diff --git a/Tools/bootloaders/MicoAir743_bl.hex b/Tools/bootloaders/MicoAir743_bl.hex new file mode 100644 index 00000000000000..36b22e6b3a83c8 --- /dev/null +++ b/Tools/bootloaders/MicoAir743_bl.hex @@ -0,0 +1,1213 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008F12E0008E2 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E30200085D4400088944000848 +:10006000B5440008E14400080D45000845110008AA +:100070006D11000899110008C5110008F111000860 +:100080001912000845120008E3020008E302000804 +:10009000E3020008E3020008E30200083945000813 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E302000811460008E3020008E3020008FA +:1000E0009D450008E3020008E3020008E30200085F +:1000F000E3020008E3020008E302000871120008AE +:10010000E3020008E302000825460008E3020008B5 +:10011000E3020008E3020008E3020008E30200082B +:100120009D120008C5120008F11200081D130008F6 +:1001300049130008E3020008E3020008E302000894 +:10014000E3020008E3020008E3020008E3020008FB +:10015000711300089D130008C9130008E30200088A +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008DD3A0008E3020008E302000899 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008C93A0008E3020008E30200084D +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F032FE3E +:1003500003F040FE4FF055301F491B4A91423CBF0D +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F04AFE03F09EFE70 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F032BE000600200022002034 +:1003D0000000000808ED00E00000002000060020FA +:1003E000484B0008002200206422002068220020E0 +:1003F00044480020E0020008E0020008E002000893 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002002F0E6F8FEE702F017 +:1004300075F800DFFEE7000038B500F045FC00F07D +:1004400015FE02F015FD054602F048FD0446C0B950 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F00CFD0CB100F030 +:1004700075F800F099FD284600F01EF900F06EF8BE +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0E5FBA0F120035842584108BD23 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000F5FB03B05DF804FB38B5302383F31188F6 +:1004C000174803680BB102F063F90023154A4FF493 +:1004D0007A71134802F052F9002383F31188124C09 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0B4FC322363602B78032B07D16368BF +:100510002BB9022000F0AAFC4FF47A73636038BD57 +:1005200068220020B90400088823002080220020CF +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F085BC022000F072BC024B0022A9 +:100550005A6070478022002088230020F8B5504B55 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0C0FB0220FFF7CBFF454B0021D3F852 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F017FCB14A83 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB102F053F80023AB4A4FF4B2 +:1006F0007A71A94802F042F8002383F31188009B25 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F093FB24B19C4B1B6838 +:10073000002B00F02682002000F092FA0390039B29 +:10074000002BF2DB012000F073FB039B213B1F2BEE +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F04FFA91E785 +:100800004FF47A7000F02CFA071EEBDB0220FFF7A2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F034FA17E004215548F9E704215A483A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F061FA0421059005A800F01EFAD2 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F08CFB26B10BF009 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F030FA0220FFF73BFE1FFA86F84046B0 +:1008C00000F038FA0446B0B1039940460136A1F170 +:1008D00040025142514100F03DFA0028EDD1BA46A4 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0D4F916E725460120FFF719FE244B36 +:100900009B68AB4207D9284600F006FA013040F058 +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940008FF9B0F10008FFF64DAF18F003077FF400 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F074F90390039A002AFFF69E +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200208423002068220020B9040008DF +:1009A000882300208022002004220020082200202A +:1009B0000C22002084220020C820FFF769FD074692 +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F066FA019AFF217F4800F087FA4FEA8B +:1009F000A803C8F387027C492846019300F086FAD1 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0B8F9F6 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F061FB8046E7E7384600F05CF9B8 +:100A60000590F2E7CDF81480042105A800F016F9EE +:100A700002E70023642104A8049300F005F900288C +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F073F90590E6E70023642104A8A8 +:100AA000049300F0F1F800287FF49CAE0220FFF7D9 +:100AB000EFFC00283FF496AE049800F061F9EAE7F5 +:100AC0000220FFF7E5FC00283FF48CAE00F070F93F +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F06BF907460421049004A800F0DC +:100AF000D5F83946B9E7322000F0B2F8071EFFF604 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0F0F80421059005A800F07F +:100B4000ADF8F1E74FF47A70FFF7A2FC00283FF40C +:100B500049AE00F01DF9002844D00A9B01330BD0A8 +:100B600008220AA9002000F0D1F900283AD020225A +:100B7000FF210AA800F0C2F9FFF792FC1C4801F01F +:100B800041FD13B0BDE8F08F002E3FF42BAE0BF00B +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F072F8074600287FF41CAE0220FFF721 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F01FFD059800F02EFA46463C469D +:100BD00000F0E0F9A6E506464EE64FF0000901E612 +:100BE000BA467EE637467CE68422002000220020BA +:100BF000A08601002DE9F84F4FF47A7306460D46A2 +:100C0000002402FB03F7DFF85080DFF8509098F9DA +:100C100000305FFA84FA5A1C01D0A34212D159F86D +:100C200024002A4631460368D3F820B03B46D84713 +:100C3000854207D1074B012083F800A0BDE8F88F5B +:100C40000124E4E7002CFBD04FF4FA7001F0DAFC49 +:100C50000020F3E7D42300201022002014220020DB +:100C6000002307B5024601210DF107008DF807307A +:100C7000FFF7C0FF20B19DF8070003B05DF804FB4B +:100C80004FF0FF30F9E700000A46042108B5FFF7EE +:100C9000B1FF80F00100C0B2404208BD074B0A46D8 +:100CA00030B41978064B53F821400146236820469A +:100CB000DD69044BAC4630BC604700BFD423002044 +:100CC00014220020A086010070B5104C0025104EA3 +:100CD00001F0B6FF20803068238883420CD80025BD +:100CE0002088013801F0A8FF23880544013BB5F5B1 +:100CF000802F2380F4D370BD01F09EFF336805443C +:100D00000133B5F5003F3360E5D3E8E7D623002093 +:100D10009023002002F062B800F1006000F500307E +:100D20000068704700F10060920000F5003001F0AB +:100D3000E3BF0000054B1A68054B1B889B1A8342D2 +:100D400002D9104401F078BF0020704790230020A2 +:100D5000D623002038B50446074D29B12868204421 +:100D6000BDE8384001F080BF2868204401F06AFFE8 +:100D70000028F3D038BD00BF90230020002070472A +:100D800000F1FF5000F58F10D0F800087047000008 +:100D9000064991F8243033B100230822086A81F80B +:100DA0002430FFF7BFBF0120704700BF942300200D +:100DB000014B1868704700BF0010005C194B0138E8 +:100DC0000322084470B51D68174BC5F30B042D0CA6 +:100DD0001E88A6420BD15C680A46013C824213463B +:100DE0000FD214F9016F4EB102F8016BF6E7013A28 +:100DF00003F10803ECD181420B4602D22C2203F806 +:100E0000012B0424094A1688AE4204D1984284BFBB +:100E1000967803F8016B013C02F10402F3D1581AF1 +:100E200070BD00BF0010005C1C2200202847000895 +:100E3000022804D1054B4FF480129A6170470128B3 +:100E4000FCD1024B4FF48002F7E700BF00100258BC +:100E5000022803D1044B10229A6170470128FCD16B +:100E6000014B4022F8E700BF00100258022805D1CC +:100E7000064A536983F01003536170470128FCD17F +:100E8000024A536983F04003F6E700BF001002589E +:100E900070B504464FF47A764CB1412C254628BFF4 +:100EA000412506FB05F0641B01F0ACFBF4E770BDC7 +:100EB000002310B5934203D0CC5CC4540133F9E74E +:100EC00010BD0000013810B510F9013F3BB191F998 +:100ED00000409C4203D11AB10131013AF4E71AB142 +:100EE00091F90020981A10BD1046FCE7034602460F +:100EF000D01A12F9011B0029FAD1704702440346A7 +:100F0000934202D003F8011BFAE770472DE9F8433A +:100F10001F4D14460746884695F8242052BBDFF83B +:100F200070909CB395F824302BB92022FF214846BD +:100F30002F62FFF7E3FF95F824004146C0F1080255 +:100F400005EB8000A24228BF2246D6B29200FFF7EE +:100F5000AFFF95F82430A41B17441E449044E4B21C +:100F6000F6B2082E85F82460DBD1FFF711FF0028C8 +:100F7000D7D108E02B6A03EB82038342CFD0FFF77F +:100F800007FF0028CBD10020BDE8F8830120FBE754 +:100F900094230020024B1A78024B1A70704700BF4E +:100FA000D42300201022002038B51A4C1A4D2046B8 +:100FB00000F07CFE2946204600F0A4FE2D684FF488 +:100FC0007A70D5F89020D2F8043843F00203C2F8C2 +:100FD0000438FFF75DFF1149284600F0A1FFD5F85E +:100FE00090200F4DD2F80438286823F002030D49F1 +:100FF000A042C2F804384FF4E1330B6001D000F096 +:10100000B3FD6868A04204D00649BDE8384000F04E +:10101000ABBD38BD382B0020244900082C490008FE +:1010200014220020BC2300200C4B70B50C4D04464C +:101030001E780C4B55F826209A420DD00A4B002101 +:1010400018221846FFF75AFF0460014655F826009B +:10105000BDE8704000F088BD70BD00BFD423002003 +:1010600014220020382B0020BC230020F0B5A1B0B2 +:1010700071B600230120002480261A46194600F08C +:101080004BFA4FF4D067214A3D25136923BBD2F8B0 +:1010900010310BBB036804F1006199600368C3F869 +:1010A0000CD003685E6003681F6001680B6843F042 +:1010B00001030B6001680B6823F01E030B600168DD +:1010C0000B68DB07FCD4037B8034416805FA03F32B +:1010D000B4F5001F0B60D8D100F05EFAB4F5001F24 +:1010E00011D000240A4E0B4D012001F077FE338809 +:1010F000A34205D928682044013401F0B5FDF6E784 +:10110000002001F06BFE61B621B0F0BD002000525E +:10111000D62300209023002030B50A44084D914288 +:101120000DD011F8013B5840082340F30004013B67 +:101130002C4013F0FF0384EA5000F6D1EFE730BDF6 +:101140002083B8ED08B5074B074A196801F03D0147 +:10115000996053680BB190689847BDE8084001F06A +:10116000FFBE00BF00000240D823002008B5084B96 +:101170001968890901F03D018A019A60054AD3681E +:101180000BB110699847BDE8084001F0E9BE00BF07 +:1011900000000240D823002008B5084B1968090C4C +:1011A00001F03D010A049A60054A53690BB1906948 +:1011B0009847BDE8084001F0D3BE00BF00000240E0 +:1011C000D823002008B5084B1968890D01F03D01AE +:1011D0008A059A60054AD3690BB1106A9847BDE841 +:1011E000084001F0BDBE00BF00000240D82300202F +:1011F00008B5074B074A596801F03D01D960536AA9 +:101200000BB1906A9847BDE8084001F0A9BE00BF45 +:1012100000000240D823002008B5084B596889090E +:1012200001F03D018A01DA60054AD36A0BB1106B07 +:101230009847BDE8084001F093BE00BF000002409F +:10124000D823002008B5084B5968090C01F03D016E +:101250000A04DA60054A536B0BB1906B9847BDE8FE +:10126000084001F07DBE00BF00000240D8230020EE +:1012700008B5084B5968890D01F03D018A05DA600F +:10128000054AD36B0BB1106C9847BDE8084001F0DC +:1012900067BE00BF00000240D823002008B5074BFE +:1012A000074A196801F03D019960536C0BB1906CCD +:1012B0009847BDE8084001F053BE00BF000402405B +:1012C000D823002008B5084B1968890901F03D01B1 +:1012D0008A019A60054AD36C0BB1106D9847BDE83E +:1012E000084001F03DBE00BF00040240D8230020AA +:1012F00008B5084B1968090C01F03D010A049A6011 +:10130000054A536D0BB1906D9847BDE8084001F058 +:1013100027BE00BF00040240D823002008B5084BB8 +:101320001968890D01F03D018A059A60054AD36D5F +:101330000BB1106E9847BDE8084001F011BE00BF28 +:1013400000040240D823002008B5074B074A59681B +:1013500001F03D01D960536E0BB1906E9847BDE826 +:10136000084001F0FDBD00BF00040240D82300206A +:1013700008B5084B5968890901F03D018A01DA6016 +:10138000054AD36E0BB1106F9847BDE8084001F0D5 +:10139000E7BD00BF00040240D823002008B5084B79 +:1013A0005968090C01F03D010A04DA60054A536FDF +:1013B0000BB1906F9847BDE8084001F0D1BD00BF68 +:1013C00000040240D823002008B5084B5968890D55 +:1013D00001F03D018A05DA60054AD36F13B1D2F8F6 +:1013E00080009847BDE8084001F0BABD0004024003 +:1013F000D823002000230C4910B51A460B4C0B6073 +:1014000054F82300026001EB430004334260402B98 +:10141000F6D1074A4FF0FF339360D360C2F8083427 +:10142000C2F80C3410BD00BFD82300203847000894 +:10143000000002400F28F8B510D9102810D011284C +:1014400011D0122808D10F240720DFF8C8E00126A8 +:10145000DEF80050A04208D9002653E00446F4E725 +:101460000F240020F1E70724FBE706FA00F73D42CE +:101470004AD1264C4FEA001C3D4304EB00160EEB0C +:10148000C000CEF80050C0E90123FBB273B1204880 +:10149000D0F8D83043F00103C0F8D830D0F800318C +:1014A00043F00103C0F80031D0F8003117F47F4F4A +:1014B0000ED01748D0F8D83043F00203C0F8D83027 +:1014C000D0F8003143F00203C0F80031D0F8003109 +:1014D00054F80C00036823F01F030360056815F03F +:1014E0000105FBD104EB0C033D2493F80CC05F68AD +:1014F00004FA0CF43C6021240560446112B1987B2D +:1015000000F066F93046F8BD0130A3E7384700081F +:1015100000440258D823002010B5302484F31188E9 +:10152000FFF788FF002383F3118810BD10B5044630 +:10153000807B00F063F901231549627B03FA02F214 +:101540000B6823EA0203DAB20B6072B9114AD2F8CF +:10155000D81021F00101C2F8D810D2F8001121F002 +:101560000101C2F80011D2F8002113F47F4F0ED10F +:10157000084BD3F8D82022F00202C3F8D820D3F8C1 +:10158000002122F00202C3F80021D3F8003110BD7F +:10159000D82300200044025808B5302383F3118873 +:1015A000FFF7C4FF002383F3118808BD0268436876 +:1015B0001143016003B1184770470000024A1368E5 +:1015C00043F0C003136070470010014013B50E4C88 +:1015D000204600F0BDFA04F1140000234FF400721D +:1015E0000A49009400F07AF9094B4FF40072094956 +:1015F00004F13800009400F0F3F9074A074BC4E9FE +:10160000172302B010BD00BF5C240020C8240020B6 +:10161000BD150008C82600200010014000E1F505B6 +:10162000037C30B5244C002918BF0C46012B11D186 +:10163000224B98420ED1224BD3F8F02042F01002F8 +:10164000C3F8F020D3F8182142F01002C3F8182193 +:10165000D3F818312268036EC16D03EB5203846620 +:10166000B3FBF2F36268150442BF23F0070503F0F1 +:10167000070343EA4503CB60A36843F040034B6094 +:10168000E36843F001038B6042F4967343F0010377 +:101690000B604FF0FF330B62510505D512F010229D +:1016A00005D0B2F1805F04D080F8643030BD7F2374 +:1016B000FAE73F23F8E700BF384800085C24002021 +:1016C000004402582DE9F047C66D05463768F469B5 +:1016D000210734621AD014F0080118BF4FF480714A +:1016E000E20748BF41F02001A3074FF0300348BF95 +:1016F00041F04001600748BF41F0800183F3118849 +:10170000281DFFF753FF002383F31188E2050AD554 +:10171000302383F311884FF48061281DFFF746FFC3 +:10172000002383F311884FF030094FF0000A14F0C2 +:10173000200838D13B0616D54FF0300905F1380A9C +:10174000200610D589F31188504600F07DF9002855 +:1017500036DA0821281DFFF729FF27F080033360C0 +:10176000002383F31188790614D5620612D530233D +:1017700083F31188D5E913239A4208D12B6C33B136 +:1017800027F040071021281DFFF710FF37600023C6 +:1017900083F31188E30618D5AA6E1369ABB15069BB +:1017A000BDE8F047184789F31188736A284695F811 +:1017B0006410194000F0E6F98AF31188F469B6E77D +:1017C000B06288F31188F469BAE7BDE8F0870000D9 +:1017D000090100F16043012203F56143C9B283F8B6 +:1017E000001300F01F039A4043099B0003F160437C +:1017F00003F56143C3F880211A60704700F01F03AE +:1018000001229A40430900F160409B0000F56140CD +:1018100003F1604303F56143C3F88020C3F88021DE +:10182000002380F800337047F8B5154682680446F7 +:101830000B46AA4200D28568A1692669761AB5428C +:101840000BD218462A46FFF733FBA3692B44A3614A +:101850002846A3685B1BA360F8BD0CD9AF1B1846D4 +:101860003246FFF725FB3A46E1683044FFF720FB9C +:10187000E3683B44EBE718462A46FFF719FBE368A9 +:10188000E5E7000083689342F7B50446154600D2A9 +:101890008568D4E90460361AB5420BD22A46FFF7B0 +:1018A00007FB63692B4463612846A3685B1BA36045 +:1018B00003B0F0BD0DD93246AF1B0191FFF7F8FA26 +:1018C00001993A46E0683144FFF7F2FAE3683B4495 +:1018D000E9E72A46FFF7ECFAE368E4E710B50A44C3 +:1018E0000024C361029B8460C16002610362C0E99D +:1018F0000000C0E9051110BD08B5D0E905329342DA +:1019000001D1826882B98268013282605A1C4261C8 +:1019100019700021D0E904329A4224BFC3684361A0 +:1019200000F08CFE002008BD4FF0FF30FBE7000008 +:1019300070B5302304460E4683F31188A568A5B11F +:10194000A368A269013BA360531CA36115782269B7 +:10195000934224BFE368A361E3690BB12046984733 +:10196000002383F31188284607E03146204600F023 +:1019700055FE0028E2DA85F3118870BD2DE9F74F96 +:1019800004460E4617469846D0F81C904FF0300A91 +:101990008AF311884FF0000B154665B12A4631468F +:1019A0002046FFF741FF034660B94146204600F05C +:1019B00035FE0028F1D0002383F31188781B03B093 +:1019C000BDE8F08FB9F1000F03D001902046C84761 +:1019D000019B8BF31188ED1A1E448AF31188DCE712 +:1019E000C160C361009B82600362C0E905111144BC +:1019F000C0E9000001617047F8B504460D4616467F +:101A0000302383F31188A768A7B1A368013BA360C3 +:101A100063695A1C62611D70D4E904329A4224BF82 +:101A2000E3686361E3690BB120469847002080F3C7 +:101A3000118807E03146204600F0F0FD0028E2DA88 +:101A400087F31188F8BD0000D0E9052310B59A424C +:101A500001D182687AB982680021013282605A1C01 +:101A600082611C7803699A4224BFC368836100F0D5 +:101A7000E5FD204610BD4FF0FF30FBE72DE9F74FA5 +:101A800004460E4617469846D0F81C904FF0300A90 +:101A90008AF311884FF0000B154665B12A4631468E +:101AA0002046FFF7EFFE034660B94146204600F0AE +:101AB000B5FD0028F1D0002383F31188781B03B013 +:101AC000BDE8F08FB9F1000F03D001902046C84760 +:101AD000019B8BF31188ED1A1E448AF31188DCE711 +:101AE000026843681143016003B118477047000062 +:101AF0001430FFF743BF00004FF0FF331430FFF7FF +:101B00003DBF00003830FFF7B9BF00004FF0FF3392 +:101B10003830FFF7B3BF00001430FFF709BF0000F3 +:101B20004FF0FF311430FFF703BF00003830FFF7EC +:101B300063BF00004FF0FF323830FFF75DBF000099 +:101B4000012914BF6FF0130000207047FFF73EBD5E +:101B5000044B036000234360C0E902330123037494 +:101B6000704700BF5048000810B53023044683F387 +:101B70001188FFF755FD02230020237480F311889C +:101B800010BD000038B5C36904460D461BB90421D9 +:101B90000844FFF7A5FF294604F11400FFF7ACFE47 +:101BA000002806DA201D4FF40061BDE83840FFF739 +:101BB00097BF38BD026843681143016003B11847FD +:101BC0007047000013B5406B00F58054D4F8A4387A +:101BD0001A681178042914D1017C022911D11979CC +:101BE000012312898B4013420BD101A94C3002F022 +:101BF000A7F8D4F8A4480246019B2179206800F098 +:101C0000DFF902B010BD0000143002F029B8000066 +:101C10004FF0FF33143002F023B800004C3002F0D4 +:101C2000FBB800004FF0FF334C3002F0F5B8000075 +:101C3000143001F0F7BF00004FF0FF31143001F015 +:101C4000F1BF00004C3002F0C7B800004FF0FF3287 +:101C50004C3002F0C1B800000020704710B500F50C +:101C60008054D4F8A4381A681178042917D1017C5B +:101C7000022914D15979012352898B4013420ED184 +:101C8000143001F089FF024648B1D4F8A4484FF45B +:101C9000407361792068BDE8104000F07FB910BD45 +:101CA000406BFFF7DBBF0000704700007FB5124BB1 +:101CB00001250426044603600023057400F1840214 +:101CC00043602946C0E902330C4B02901430019363 +:101CD0004FF44073009601F03BFF094B04F6944229 +:101CE000294604F14C000294CDE900634FF440739F +:101CF00002F002F804B070BD78480008A11C00088A +:101D0000C51B00080A68302383F311880B790B3355 +:101D100042F823004B79133342F823008B7913B137 +:101D20000B3342F8230000F58053C3F8A4180223B4 +:101D30000374002080F311887047000038B5037FDA +:101D4000044613B190F85430ABB90125201D02218F +:101D5000FFF730FF04F114006FF00101257700F068 +:101D600079FC04F14C0084F854506FF00101BDE897 +:101D7000384000F06FBC38BD10B501210446043076 +:101D8000FFF718FF0023237784F8543010BD0000BC +:101D900038B504460025143001F0F2FE04F14C0081 +:101DA000257701F0C1FF201D84F854500121FFF771 +:101DB00001FF2046BDE83840FFF750BF90F8803063 +:101DC00003F06003202B06D190F881200023212A04 +:101DD00003D81F2A06D800207047222AFBD1C0E969 +:101DE0001D3303E0034A426707228267C36701206D +:101DF000704700BF3422002037B500F58055D5F874 +:101E0000A4381A68117804291AD1017C022917D143 +:101E10001979012312898B40134211D100F14C042E +:101E2000204602F041F858B101A9204601F088FF90 +:101E3000D5F8A4480246019B2179206800F0C0F83B +:101E400003B030BD01F10B03F0B550F8236085B04D +:101E500004460D46FEB1302383F3118804EB850759 +:101E6000301D0821FFF7A6FEFB6806F14C005B69F8 +:101E70001B681BB1019001F071FF019803A901F0EB +:101E80005FFF024648B1039B2946204600F098F8C0 +:101E9000002383F3118805B0F0BDFB685A6912680E +:101EA000002AF5D01B8A013B1340F1D104F18002D6 +:101EB000EAE70000133138B550F82140ECB1302387 +:101EC00083F3118804F58053D3F8A428136852795A +:101ED00003EB8203DB689B695D6845B104216018F0 +:101EE000FFF768FE294604F1140001F05FFE20466A +:101EF000FFF7B4FE002383F3118838BD704700005C +:101F000001F02CB901234022002110B5044600F84D +:101F1000303BFEF7F3FF0023C4E9013310BD00009E +:101F200010B53023044683F3118824224160002138 +:101F30000C30FEF7E3FF204601F032F902230020C7 +:101F4000237080F3118810BD70B500EB8103054646 +:101F500050690E461446DA6018B110220021FEF7CF +:101F6000CDFFA06918B110220021FEF7C7FF31464E +:101F70002846BDE8704001F019BA000083682022AD +:101F8000002103F0011310B5044683601030FEF702 +:101F9000B5FF2046BDE8104001F094BAF0B4012529 +:101FA00000EB810447898D40E4683D43A469458185 +:101FB00023600023A2606360F0BC01F0B1BA0000AE +:101FC000F0B4012500EB810407898D40E4683D43AE +:101FD0006469058123600023A2606360F0BC01F0A6 +:101FE00027BB000070B5022300250446242203709D +:101FF0002946C0F888500C3040F8045CFEF77EFF9C +:10200000204684F8705001F065F963681B6823B1BD +:1020100029462046BDE87040184770BD0378052B5F +:1020200010B504460AD080F88C300523037043684D +:102030001B680BB1042198470023A36010BD00006A +:102040000178052906D190F88C20436802701B683E +:1020500003B118477047000070B590F8703004461F +:1020600013B1002380F8703004F18002204601F0A3 +:102070004DFA63689B68B3B994F8803013F060053B +:1020800035D00021204601F03FFD0021204601F01F +:102090002FFD63681B6813B106212046984706236D +:1020A00084F8703070BD204698470028E4D0B4F81A +:1020B0008630A26F9A4288BFA36794F98030A56FDB +:1020C000002B4FF0300380F20381002D00F0F280EE +:1020D000092284F8702083F3118800212046D4E976 +:1020E0001D23FFF76DFF002383F31188DAE794F8CF +:1020F000812003F07F0343EA022340F2023293423D +:1021000000F0C58021D8B3F5807F48D00DD8012BD1 +:102110003FD0022B00F09380002BB2D104F1880253 +:1021200062670222A267E367C1E7B3F5817F00F02F +:102130009B80B3F5407FA4D194F88230012BA0D1CD +:10214000B4F8883043F0020332E0B3F5006F4DD0AD +:1021500017D8B3F5A06F31D0A3F5C063012B90D889 +:102160006368204694F882205E6894F88310B4F87F +:102170008430B047002884D0436863670368A3674E +:102180001AE0B3F5106F36D040F6024293427FF466 +:1021900078AF5C4B63670223A3670023C3E794F81F +:1021A0008230012B7FF46DAFB4F8883023F0020346 +:1021B000A4F88830C4E91D55E56778E7B4F88030A5 +:1021C000B3F5A06F0ED194F88230204684F88A309F +:1021D00001F0DEF863681B6813B1012120469847BF +:1021E000032323700023C4E91D339CE704F18B0310 +:1021F00063670123C3E72378042B10D1302383F3D3 +:1022000011882046FFF7BAFE85F311880321636821 +:1022100084F88B5021701B680BB12046984794F8C6 +:102220008230002BDED084F88B3004232370636867 +:102230001B68002BD6D0022120469847D2E794F89D +:10224000843020461D0603F00F010AD501F050F935 +:10225000012804D002287FF414AF2B4B9AE72B4BB4 +:1022600098E701F037F9F3E794F88230002B7FF418 +:1022700008AF94F8843013F00F01B3D01A0620464B +:1022800002D501F059FCADE701F04AFCAAE794F849 +:102290008230002B7FF4F5AE94F8843013F00F01F8 +:1022A000A0D01B06204602D501F02EFC9AE701F0D3 +:1022B0001FFC97E7142284F8702083F311882B46C3 +:1022C0002A4629462046FFF769FE85F31188E9E68C +:1022D0005DB1152284F8702083F311880021204617 +:1022E000D4E91D23FFF75AFEFDE60B2284F8702087 +:1022F00083F311882B462A4629462046FFF760FEC5 +:10230000E3E700BFA8480008A0480008A448000868 +:1023100038B590F870300446002B3ED0063BDAB258 +:102320000F2A34D80F2B32D8DFE803F037313108C9 +:10233000223231313131313131313737856FB0F8B7 +:1023400086309D4214D2C3681B8AB5FBF3F203FBAF +:1023500012556DB9302383F311882B462A4629463E +:10236000FFF72EFE85F311880A2384F870300EE003 +:10237000142384F87030302383F31188002320461F +:102380001A461946FFF70AFE002383F3118838BD69 +:10239000C36F03B198470023E7E70021204601F00F +:1023A000B3FB0021204601F0A3FB63681B6813B157 +:1023B0000621204698470623D7E7000010B590F87D +:1023C00070300446142B29D017D8062B05D001D81D +:1023D0001BB110BD093B022BFBD80021204601F0A8 +:1023E00093FB0021204601F083FB63681B6813B157 +:1023F000062120469847062319E0152BE9D10B2327 +:1024000080F87030302383F3118800231A46194670 +:10241000FFF7D6FD002383F31188DAE7C3689B69D1 +:102420005B68002BD5D1C36F03B19847002384F8B4 +:102430007030CEE700238268037503691B689968D2 +:102440009142FBD25A680360426010605860704746 +:1024500000238268037503691B6899689142FBD861 +:102460005A680360426010605860704708B50846BB +:10247000302383F311880B7D032B05D0042B0DD063 +:102480002BB983F3118808BD8B6900221A604FF0C5 +:10249000FF338361FFF7CEFF0023F2E7D1E900327B +:1024A00013605A60F3E70000FFF7C4BF054BD9681B +:1024B00008751868026853601A600122D8600275B6 +:1024C000FDF7A0BFC82800200C4B30B5DD684B1CC1 +:1024D00087B004460FD02B46094A684600F04EF9F3 +:1024E0002046FFF7E3FF009B13B1684600F050F968 +:1024F000A86907B030BDFFF7D9FFF9E7C828002069 +:102500006D240008044B1A68DB6890689B68984249 +:1025100094BF002001207047C8280020084B10B548 +:102520001C68D868226853601A600122DC6022753A +:10253000FFF78EFF01462046BDE81040FDF762BF61 +:10254000C828002038B5074C012300250649074854 +:102550002370656001F0E6FC0223237085F3118887 +:1025600038BD00BF302B0020B0480008C82800202C +:1025700000F044B9034A516853685B1A9842FBD88B +:10258000704700BF001000E08B600223086108461E +:102590008B8270478368A3F1840243F8142C02698C +:1025A00043F8442C426943F8402C094A43F8242C50 +:1025B000C268A3F1200043F8182C022203F80C2C67 +:1025C000002203F80B2C034A43F8102C704700BF7D +:1025D0001D040008C828002008B5FFF7DBFFBDE890 +:1025E0000840FFF761BF0000024BDB6898610F20D5 +:1025F000FFF75CBFC8280020302383F31188FFF762 +:10260000F3BF000008B50146302383F3118808208A +:10261000FFF75AFF002383F3118808BD064BDB68E0 +:1026200039B1426818605A60136043600420FFF7B4 +:102630004BBF4FF0FF307047C82800200368984216 +:1026400006D01A680260506018469961FFF72CBFE7 +:102650007047000038B504460D462068844200D11A +:1026600038BD036823605C608561FFF71DFFF4E7F8 +:10267000036810B59C68A2420CD85C688A600B6045 +:102680004C602160596099688A1A9A604FF0FF3354 +:10269000836010BD121B1B68ECE700000A2938BFDD +:1026A0000A2170B504460D460A26601901F032FC75 +:1026B00001F01AFC041BA54203D8751C04462E46E3 +:1026C000F3E70A2E04D90120BDE8704001F06ABC8E +:1026D00070BD0000F8B5144B0D460A2A4FF00A07EA +:1026E000D96103F11001826038BF0A224160196983 +:1026F0001446016048601861A81801F0FBFB01F066 +:10270000F3FB431B0646A34206D37C1C281927462D +:10271000354601F0FFFBF2E70A2F04D90120BDE89E +:10272000F84001F03FBCF8BDC8280020F8B50646C7 +:102730000D4601F0D9FB0F4A134653F8107F9F4214 +:1027400006D12A4601463046BDE8F840FFF7C2BF31 +:10275000D169BB68441A2C1928BF2C46A34202D960 +:102760002946FFF79BFF224631460348BDE8F84063 +:10277000FFF77EBFC8280020D8280020C0E9032327 +:10278000002310B45DF8044B4361FFF7CFBF000096 +:1027900010B5194C236998420DD08168D0E90032F8 +:1027A00013605A609A680A449A60002303604FF0ED +:1027B000FF33A36110BD0268234643F8102F536016 +:1027C0000022026022699A4203D1BDE8104001F064 +:1027D0009BBB936881680B44936001F085FB226981 +:1027E000E1699268441AA242E4D91144BDE810405C +:1027F000091AFFF753BF00BFC82800202DE9F04792 +:10280000DFF8BC8008F110072C4ED8F8105001F00A +:102810006BFBD8F81C40AA68031B9A423ED81444AC +:102820004FF00009D5E90032C8F81C4013605A6027 +:10283000C5F80090D8F81030B34201D101F064FB24 +:1028400089F31188D5E9033128469847302383F36B +:1028500011886B69002BD8D001F046FB6A69A0EBA8 +:10286000040982464A450DD2022001F09BFB00225A +:10287000D8F81030B34208D151462846BDE8F04799 +:10288000FFF728BF121A2244F2E712EB0909294682 +:10289000384638BF4A46FFF7EBFEB5E7D8F81030A8 +:1028A000B34208D01444C8F81C00211AA960BDE83E +:1028B000F047FFF7F3BEBDE8F08700BFD82800203F +:1028C000C828002000207047FEE700007047000085 +:1028D0004FF0FF307047000002290CD0032904D0CC +:1028E0000129074818BF00207047032A05D805486A +:1028F00000EBC2007047044870470020704700BFDB +:1029000088490008442200203C49000870B59AB06C +:1029100005460846144601A900F0C2F801A8FEF7D2 +:10292000E5FA431C0022C6B25B001046C5E900343C +:1029300023700323023404F8013C01ABD1B202340A +:102940008E4201D81AB070BD13F8011B013204F891 +:10295000010C04F8021CF1E708B5302383F3118859 +:102960000348FFF749FA002383F3118808BD00BF2D +:10297000382B002090F8803003F01F02012A07D185 +:1029800090F881200B2A03D10023C0E91D3315E004 +:1029900003F06003202B08D1B0F884302BB990F8F5 +:1029A0008120212A03D81F2A04D8FFF707BA222A38 +:1029B000EBD0FAE7034A426707228267C367012028 +:1029C000704700BF3B22002007B5052917D8DFE874 +:1029D00001F0191603191920302383F31188104AC6 +:1029E00001210190FFF7B0FA019802210D4AFFF78B +:1029F000ABFA0D48FFF7CCF9002383F3118803B03D +:102A00005DF804FB302383F311880748FFF796F93C +:102A1000F2E7302383F311880348FFF7ADF9EBE7C2 +:102A2000DC48000800490008382B002038B50C4D60 +:102A30000C4C2A460C4904F10800FFF767FF05F12A +:102A4000CA0204F110000949FFF760FF05F5CA72D8 +:102A500004F118000649BDE83840FFF757BF00BF32 +:102A60001044002044220020BC480008C64800084A +:102A7000D148000870B5044608460D46FEF736FA00 +:102A8000C6B22046013403780BB9184670BD3246F1 +:102A90002946FEF717FA0028F3D10120F6E70000D7 +:102AA0002DE9F84F05460C46FEF720FA2C49C6B230 +:102AB0002846FFF7DFFF08B10336F6B2294928465A +:102AC000FFF7D8FF08B11036F6B2632E0DD8DFF845 +:102AD0009080DFF89090244FDFF894A0DFF894B056 +:102AE0002E7846B92670BDE8F88F29462046BDE805 +:102AF000F84F01F0FBBD252E2ED107224146284676 +:102B0000FEF7E0F970B9DBF8003007350A3444F815 +:102B10000A3CDBF8043044F8063CBBF8083024F8E3 +:102B2000023CDDE7082249462846FEF7CBF998B972 +:102B3000A21C0E4B197802320909C95D02F8041C67 +:102B400013F8011B01F00F015345C95D02F8031C86 +:102B5000F0D118340835C3E7013504F8016BBFE73D +:102B6000A8490008D1480008BB49000800E8F11F47 +:102B70000CE8F11FB0490008BFF34F8F044B1A69EE +:102B80005107FCD1D3F810215207F8D1704700BF8C +:102B90000020005208B50D4B1B78ABB9FFF7ECFFD6 +:102BA0000B4BDA68D10704D50A4A5A6002F1883221 +:102BB0005A60D3F80C21D20706D5064AC3F804217F +:102BC00002F18832C3F8042108BD00BF6E46002020 +:102BD000002000522301674508B5114B1B78F3B95B +:102BE000104B1A69510703D5DA6842F04002DA60E7 +:102BF000D3F81021520705D5D3F80C2142F040023A +:102C0000C3F80C21FFF7B8FF064BDA6842F0010267 +:102C1000DA60D3F80C2142F00102C3F80C2108BDA0 +:102C20006E460020002000520F289ABF00F58060F9 +:102C300040040020704700004FF40030704700004F +:102C4000102070470F2808B50BD8FFF7EDFF00F5EF +:102C500000330268013204D104308342F9D10120EB +:102C600008BD0020FCE700000F2838B505463FD816 +:102C7000FFF782FF1F4CFFF78DFF4FF0FF33072850 +:102C80006361C4F814311DD82361FFF775FF030297 +:102C900043F02403E360E36843F08003E3602369C7 +:102CA0005A07FCD42846FFF767FFFFF7BDFF4FF434 +:102CB000003100F0F5F82846FFF78EFFBDE83840F8 +:102CC000FFF7C0BFC4F81031FFF756FFA0F10803AB +:102CD0001B0243F02403C4F80C31D4F80C3143F048 +:102CE0008003C4F80C31D4F810315B07FBD4D9E76A +:102CF000002038BD002000522DE9F84F05460C4653 +:102D0000104645EA0203DE0602D00020BDE8F88F37 +:102D100020F01F00DFF8BCB0DFF8BCA0FFF73AFFDF +:102D200004EB0008444503D10120FFF755FFEDE710 +:102D300020222946204601F0C9FC10B92035203454 +:102D4000F0E72B4605F120021F68791CDDD1043322 +:102D50009A42F9D105F178431B481C4EB3F5801F08 +:102D60001B4B38BF184603F1F80332BFD946D14692 +:102D70001E46FFF701FF0760A5EB040C336804F162 +:102D80001C0143F002033360231FD9F8007017F0D1 +:102D90000507FAD153F8042F8B424CF80320F4D1E5 +:102DA000BFF34F8FFFF7E8FE4FF0FF33202221469D +:102DB00003602846336823F00203336001F086FC89 +:102DC0000028BBD03846B0E7142100520C20005236 +:102DD00014200052102000521021005210B5084C4F +:102DE000237828B11BB9FFF7D5FE0123237010BD4E +:102DF000002BFCD02070BDE81040FFF7EDBE00BFF7 +:102E00006E4600200244074BD2B210B5904200D16A +:102E100010BD441C00B253F8200041F8040BE0B28E +:102E2000F4E700BF504000580E4B30B51C6F24042F +:102E300005D41C6F1C671C6F44F400441C670A4CCB +:102E400002442368D2B243F480732360074B90425C +:102E500000D130BD441C51F8045B00B243F820504F +:102E6000E0B2F4E7004402580048025850400058CD +:102E700007B5012201A90020FFF7C4FF019803B0A4 +:102E80005DF804FB13B50446FFF7F2FFA04205D03E +:102E9000012201A900200194FFF7C6FF02B010BD76 +:102EA0000144BFF34F8F064B884204D3BFF34F8FCB +:102EB000BFF36F8F7047C3F85C022030F4E700BFA8 +:102EC00000ED00E0034B1A681AB9034AD2F8D02487 +:102ED0001A607047704600200040025808B5FFF79E +:102EE000F1FF024B1868C0F3806008BD70460020F7 +:102EF000EFF30983054968334A6B22F001024A6304 +:102F000083F30988002383F31188704700EF00E002 +:102F1000302080F3118862B60D4B0E4AD96821F437 +:102F2000E0610904090C0A430B49DA60D3F8FC207C +:102F300042F08072C3F8FC20084AC2F8B01F116842 +:102F400041F0010111602022DA7783F822007047F6 +:102F500000ED00E00003FA0555CEACC5001000E01E +:102F6000302310B583F311880E4B5B6813F40063B4 +:102F700014D0F1EE103AEFF309844FF08073683CFF +:102F8000E361094BDB6B236684F30988FFF7BAFA28 +:102F900010B1064BA36110BD054BFBE783F311880D +:102FA000F9E700BF00ED00E000EF00E02F040008AB +:102FB0003204000870B5BFF34F8FBFF36F8F1A4A0A +:102FC0000021C2F85012BFF34F8FBFF36F8F5369C8 +:102FD00043F400335361BFF34F8FBFF36F8FC2F8D9 +:102FE0008410BFF34F8FD2F8803043F6E074C3F300 +:102FF000C900C3F34E335B0103EA0406014646EA07 +:1030000081750139C2F86052F9D2203B13F1200FCB +:10301000F2D1BFF34F8F536943F480335361BFF351 +:103020004F8FBFF36F8F70BD00ED00E0FEE7000033 +:10303000214B2248224A70B5904237D3214BC11E02 +:10304000DA1C121A22F003028B4238BF0022002140 +:10305000FDF754FF1C4A0023C2F88430BFF34F8FA2 +:10306000D2F8803043F6E074C3F3C900C3F34E33A3 +:103070005B0103EA0406014646EA81750139C2F89C +:103080006C52F9D2203B13F1200FF2D1BFF34F8FD6 +:10309000BFF36F8FBFF34F8FBFF36F8F0023C2F863 +:1030A0005032BFF34F8FBFF36F8F70BD53F8041BC7 +:1030B00040F8041BC0E700BFAC4B000844480020A8 +:1030C000444800204448002000ED00E0074BD3F8BE +:1030D000D81021EA0001C3F8D810D3F8002122EA61 +:1030E0000002C3F80021D3F80031704700440258B1 +:1030F00070B5D0E9244300224FF0FF359E6804EB01 +:1031000042135101D3F80009002805DAD3F8000969 +:1031100040F08040C3F80009D3F8000B002805DA1E +:10312000D3F8000B40F08040C3F8000B0132631865 +:103130009642C3F80859C3F8085BE0D24FF0011378 +:10314000C4F81C3870BD0000890141F02001016104 +:1031500003699B06FCD41220FFF70CBA10B50A4C89 +:103160002046FEF7CFFE094BC4F89030084BC4F858 +:103170009430084C2046FEF7C5FE074BC4F890304B +:10318000064BC4F8943010BD74460020000008407F +:10319000F04900081047002000000440FC490008E6 +:1031A00070B503780546012B5CD1434BD0F89040B5 +:1031B000984258D1414B0E216520D3F8D82042F0D7 +:1031C0000062C3F8D820D3F8002142F00062C3F8AF +:1031D0000021D3F80021D3F8802042F00062C3F828 +:1031E0008020D3F8802022F00062C3F88020D3F83A +:1031F0008030FEF7EDFA324BE360324BC4F8003812 +:103200000023D5F89060C4F8003EC02323604FF43B +:103210000413A3633369002BFCDA01230C20336110 +:10322000FFF7A8F93369DB07FCD41220FFF7A2F9F6 +:103230003369002BFCDA00262846A660FFF758FF0A +:103240006B68C4F81068DB68C4F81468C4F81C68BC +:1032500083BB1D4BA3614FF0FF336361A36843F051 +:103260000103A36070BD194B9842C9D1134B4FF0B5 +:103270008060D3F8D82042F00072C3F8D820D3F889 +:10328000002142F00072C3F80021D3F80021D3F8E6 +:10329000802042F00072C3F88020D3F8802022F012 +:1032A0000072C3F88020D3F88030FFF70FFF0E21A3 +:1032B0004D209EE7064BCDE774460020004402589F +:1032C0004014004003002002003C30C010470020A2 +:1032D000083C30C0F8B5D0F89040054600214FF0CA +:1032E00000662046FFF730FFD5F8941000234FF01A +:1032F00001128F684FF0FF30C4F83438C4F81C282E +:1033000004EB431201339F42C2F80069C2F8006B1C +:10331000C2F80809C2F8080BF2D20B68D5F8902061 +:10332000C5F89830636210231361166916F0100611 +:10333000FBD11220FFF71EF9D4F8003823F4FE6306 +:10334000C4F80038A36943F4402343F01003A36199 +:103350000923C4F81038C4F814380B4BEB604FF055 +:10336000C043C4F8103B094BC4F8003BC4F81069D3 +:10337000C4F80039D5F8983003F1100243F48013F3 +:10338000C5F89820A362F8BDCC4900084080001021 +:10339000D0F8902090F88A10D2F8003823F4FE6319 +:1033A00043EA0113C2F80038704700002DE9F843E2 +:1033B00000EB8103D0F890500C468046DA680FFA93 +:1033C00081F94801166806F00306731E022B05EB0F +:1033D00041134FF0000194BFB604384EC3F8101BE0 +:1033E0004FF0010104F1100398BF06F1805601FA75 +:1033F00003F3916998BF06F5004600293AD0578A31 +:1034000004F15801374349016F50D5F81C180B439C +:103410000021C5F81C382B180127C3F81019A74044 +:103420005369611E9BB3138A928B9B08012A88BF44 +:103430005343D8F89820981842EA034301F1400218 +:103440002146C8F89800284605EB82025360FFF732 +:103450007BFE08EB8900C3681B8A43EA8453483427 +:103460001E4364012E51D5F81C381F43C5F81C7843 +:10347000BDE8F88305EB4917D7F8001B21F400419C +:10348000C7F8001BD5F81C1821EA0303C0E704F1B4 +:103490003F030B4A2846214605EB83035A60FFF79A +:1034A00053FE05EB4910D0F8003923F40043C0F86F +:1034B0000039D5F81C3823EA0707D7E70080001049 +:1034C00000040002D0F894201268C0F89820FFF79A +:1034D0000FBE00005831D0F8903049015B5813F40A +:1034E000004004D013F4001F0CBF022001207047DD +:1034F0004831D0F8903049015B5813F4004004D0B3 +:1035000013F4001F0CBF02200120704700EB810163 +:10351000CB68196A0B6813604B68536070470000F2 +:1035200000EB810330B5DD68AA691368D36019B96F +:10353000402B84BF402313606B8A1468D0F890201E +:103540001C4402EB4110013C09B2B4FBF3F46343A9 +:10355000033323F0030343EAC44343F0C043C0F8FA +:10356000103B2B6803F00303012B0ED1D2F808386F +:1035700002EB411013F4807FD0F8003B14BF43F0FE +:10358000805343F00053C0F8003B02EB4112D2F8E5 +:10359000003B43F00443C2F8003B30BD2DE9F0414D +:1035A000D0F8906005460C4606EB4113D3F8087B33 +:1035B0003A07C3F8087B08D5D6F814381B0704D59A +:1035C00000EB8103DB685B689847FA071FD5D6F8E4 +:1035D0001438DB071BD505EB8403D968CCB98B699C +:1035E000488A5A68B2FBF0F600FB16228AB91868BE +:1035F000DA6890420DD2121AC3E90024302383F313 +:10360000118821462846FFF78BFF84F31188BDE817 +:10361000F081012303FA04F26B8923EA02036B8130 +:10362000CB68002BF3D021462846BDE8F04118476F +:1036300000EB81034A0170B5DD68D0F890306C6909 +:103640002668E66056BB1A444FF40020C2F8100901 +:103650002A6802F00302012A0AB20ED1D3F8080840 +:1036600003EB421410F4807FD4F8000914BF40F03B +:10367000805040F00050C4F8000903EB4212D2F829 +:10368000000940F00440C2F800090122D3F83408D0 +:1036900002FA01F10143C3F8341870BD19B9402E84 +:1036A00084BF4020206020681A442E8A8419013C7F +:1036B000B4FBF6F440EAC44040F00050C6E7000016 +:1036C0002DE9F843D0F8906005460C464F0106EB13 +:1036D0004113D3F8088918F0010FC3F808891CD0EA +:1036E000D6F81038DB0718D500EB8103D3F80CC0EF +:1036F000DCF81430D3F800E0DA68964530D2A2EB5B +:103700000E024FF000091A60C3F80490302383F3CF +:103710001188FFF78DFF89F3118818F0800F1DD0F5 +:10372000D6F834380126A640334217D005EB84037F +:103730000134D5F89050D3F80CC0E4B22F44DCF833 +:10374000142005EB0434D2F800E05168714514D31D +:10375000D5F8343823EA0606C5F83468BDE8F8839E +:10376000012303FA01F2038923EA02030381DCF84F +:103770000830002BD1D09847CFE7AEEB0103BCF85F +:103780001000834228BF0346D7F8180980B2B3EB74 +:10379000800FE3D89068A0F1040959F8048FC4F8A9 +:1037A0000080A0EB09089844B8F1040FF5D818443C +:1037B0000B4490605360C8E72DE9F84FD0F8905063 +:1037C00004466E69AB691E4016F480586E6103D0E2 +:1037D000BDE8F84FFEF706BC002E12DAD5F8003E21 +:1037E0009B0705D0D5F8003E23F00303C5F8003E43 +:1037F000D5F80438204623F00103C5F80438FEF755 +:103800001FFC370505D52046FFF772FC2046FEF762 +:1038100005FCB0040CD5D5F8083813F0060FEB689A +:1038200023F470530CBF43F4105343F4A053EB60E4 +:1038300031071BD56368DB681BB9AB6923F008034C +:10384000AB612378052B0CD1D5F8003E9A0705D043 +:10385000D5F8003E23F00303C5F8003E2046FEF7EE +:10386000EFFB6368DB680BB120469847F30200F179 +:10387000BA80B70226D5D4F8909000274FF0010AFD +:1038800009EB4712D2F8003B03F44023B3F5802F35 +:1038900011D1D2F8003B002B0DDA62890AFA07F346 +:1038A00022EA0303638104EB8703DB68DB6813B15F +:1038B0003946204698470137D4F89430FFB29B68C8 +:1038C0009F42DDD9F00619D5D4F89000026AC2F300 +:1038D0000A1702F00F0302F4F012B2F5802F00F085 +:1038E000CA80B2F5402F09D104EB8303002200F512 +:1038F0008050DB681B6A974240F0B0803003D5F8F7 +:10390000185835D5E90303D500212046FFF746FEB8 +:10391000AA0303D501212046FFF740FE6B0303D520 +:1039200002212046FFF73AFE2F0303D5032120464C +:10393000FFF734FEE80203D504212046FFF72EFEF0 +:10394000A90203D505212046FFF728FE6A0203D508 +:1039500006212046FFF722FE2B0203D50721204631 +:10396000FFF71CFEEF0103D508212046FFF716FEE6 +:10397000700340F1A780E90703D500212046FFF737 +:103980009FFEAA0703D501212046FFF799FE6B078A +:1039900003D502212046FFF793FE2F0703D503210D +:1039A0002046FFF78DFEEE0603D504212046FFF7E3 +:1039B00087FEA80603D505212046FFF781FE69068C +:1039C00003D506212046FFF77BFE2A0603D50721F3 +:1039D0002046FFF775FEEB0574D520460821BDE8AB +:1039E000F84FFFF76DBED4F890904FF0000B4FF0FA +:1039F000010AD4F894305FFA8BF79B689F423FF638 +:103A000038AF09EB4713D3F8002902F44022B2F58E +:103A1000802F20D1D3F80029002A1CDAD3F80029FE +:103A200042F09042C3F80029D3F80029002AFBDBBA +:103A30003946D4F89000FFF787FB22890AFA07F38A +:103A400022EA0303238104EB8703DB689B6813B13D +:103A50003946204698470BF1010BCAE7910701D17F +:103A6000D0F80080072A02F101029CBF03F8018B05 +:103A70004FEA18283FE704EB830300F58050DA682B +:103A8000D2F818C0DCF80820DCE9001CA1EB0C0C13 +:103A900000218F4208D1DB689B699A683A449A609A +:103AA0005A683A445A6029E711F0030F01D1D0F85F +:103AB00000808C4501F1010184BF02F8018B4FEABF +:103AC0001828E6E7BDE8F88F08B50348FFF774FE4D +:103AD000BDE80840FFF744BA7446002008B5034823 +:103AE000FFF76AFEBDE80840FFF73ABA104700202A +:103AF000D0F8903003EB4111D1F8003B43F40013B0 +:103B0000C1F8003B70470000D0F8903003EB411142 +:103B1000D1F8003943F40013C1F8003970470000B0 +:103B2000D0F8903003EB4111D1F8003B23F400139F +:103B3000C1F8003B70470000D0F8903003EB411112 +:103B4000D1F8003923F40013C1F8003970470000A0 +:103B500030B50433039C0172002104FB0325C160CE +:103B6000C0E90653049B0363059BC0E90000C0E95C +:103B70000422C0E90842C0E90A11436330BD0000D5 +:103B80000022416AC260C0E90411C0E90A226FF054 +:103B90000101FEF75FBD0000D0E90432934201D17C +:103BA000C2680AB9181D7047002070470369196080 +:103BB0000021C2680132C260C26913448269934223 +:103BC000036124BF436A0361FEF738BD38B504467C +:103BD0000D46E3683BB162690020131D1268A362C1 +:103BE0001344E36207E0237A33B929462046FEF7FF +:103BF00015FD0028EDDA38BD6FF00100FBE700008D +:103C0000C368C269013BC36043691344826993423C +:103C1000436124BF436A436100238362036B03B1A2 +:103C20001847704770B53023044683F31188866ABD +:103C30003EB9FFF7CBFF054618B186F31188284639 +:103C400070BDA36AE26A13F8015B9342A36202D3D8 +:103C50002046FFF7D5FF002383F31188EFE700002C +:103C60002DE9F84F04460E46174698464FF03009A6 +:103C700089F311880025AA46D4F828B0BBF1000FBB +:103C800009D141462046FFF7A1FF20B18BF31188EF +:103C90002846BDE8F88FD4E90A12A7EB050B521AA3 +:103CA000934528BF9346BBF1400F1BD9334601F122 +:103CB000400251F8040B914243F8040BF9D1A36A76 +:103CC000403640354033A362D4E90A239A4202D3F6 +:103CD0002046FFF795FF8AF31188BD42D8D289F3B9 +:103CE0001188C9E730465A46FDF7E2F8A36A5E44F8 +:103CF0005D445B44A362E7E710B5029C04330172A4 +:103D000003FB0421C460C0E906130023C0E90A33A1 +:103D1000039B0363049BC0E90000C0E90422C0E9DF +:103D20000842436310BD0000026A6FF00101C260E7 +:103D3000426AC0E904220022C0E90A22FEF78ABCD6 +:103D4000D0E904239A4201D1C26822B9184650F83A +:103D5000043B0B60704700231846FAE7C368002154 +:103D6000C2690133C360436913448269934243616A +:103D700024BF436A4361FEF761BC000038B50446C6 +:103D80000D46E3683BB1236900201A1DA262E26977 +:103D90001344E36207E0237A33B929462046FEF74D +:103DA0003DFC0028EDDA38BD6FF00100FBE70000B4 +:103DB00003691960C268013AC260C269134482692A +:103DC0009342036124BF436A036100238362036B50 +:103DD00003B118477047000070B530230D46044604 +:103DE000114683F31188866A2EB9FFF7C7FF10B119 +:103DF00086F3118870BDA36A1D70A36AE26A01335D +:103E00009342A36204D3E16920460439FFF7D0FF4F +:103E1000002080F31188EDE72DE9F84F04460D46A8 +:103E2000904699464FF0300A8AF311880026B3462F +:103E3000A76A4FB949462046FFF7A0FF20B187F394 +:103E400011883046BDE8F88FD4E90A073A1AA8EB82 +:103E50000607974228BF1746402F1BD905F140039C +:103E600055F8042B9D4240F8042BF9D1A36A403643 +:103E70004033A362D4E90A239A4204D3E16920467D +:103E80000439FFF795FF8BF311884645D9D28AF3A1 +:103E90001188CDE729463A46FDF70AF8A36A3D4462 +:103EA0003E443B44A362E5E7D0E904239A4217D19C +:103EB000C3689BB1836A8BB1043B9B1A0ED013601D +:103EC000C368013BC360C3691A4483699A420261B3 +:103ED00024BF436A036100238362012318467047AD +:103EE0000023FBE700F024B9014B586A704700BF7C +:103EF000000C0040034B002258631A610222DA6072 +:103F0000704700BF000C0040014B0022DA60704790 +:103F1000000C0040014B5863704700BF000C00408C +:103F2000FEE7000070B51B4B0025044686B05860C4 +:103F30000E4685620163FEF7EBFF04F11003A560F6 +:103F4000E562C4E904334FF0FF33C4E90044C4E937 +:103F50000635FFF7C9FF2B46024604F1340120461F +:103F6000C4E9082380230C4A2565FEF70DFB0123D5 +:103F70000A4AE06000920375684672680192B2686E +:103F8000CDE90223064BCDE90435FEF725FB06B04B +:103F900070BD00BF302B0020084A00080D4A000801 +:103FA000213F0008024AD36A1843D062704700BF1D +:103FB000C82800204B6843608B688360CB68C3606F +:103FC0000B6943614B6903628B6943620B68036051 +:103FD0007047000008B53C4B40F2FF713B48D3F8F6 +:103FE00088200A43C3F88820D3F8882022F4FF628F +:103FF00022F00702C3F88820D3F88820D3F8E02005 +:104000000A43C3F8E020D3F808210A43C3F8082183 +:104010002F4AD3F808311146FFF7CCFF00F5806036 +:1040200002F11C01FFF7C6FF00F5806002F13801C4 +:10403000FFF7C0FF00F5806002F15401FFF7BAFFFF +:1040400000F5806002F17001FFF7B4FF00F58060B9 +:1040500002F18C01FFF7AEFF00F5806002F1A801CC +:10406000FFF7A8FF00F5806002F1C401FFF7A2FF8F +:1040700000F5806002F1E001FFF79CFF00F5806031 +:1040800002F1FC01FFF796FF02F58C7100F58060EC +:10409000FFF790FF00F018F90E4BD3F8902242F092 +:1040A0000102C3F89022D3F8942242F00102C3F82F +:1040B00094220522C3F898204FF06052C3F89C2048 +:1040C000054AC3F8A02008BD004402580000025869 +:1040D000144A000800ED00E01F00080308B500F0D6 +:1040E000D5FAFEF72FFA0F4BD3F8DC2042F040024E +:1040F000C3F8DC20D3F8042122F04002C3F80421E5 +:10410000D3F80431084B1A6842F008021A601A68A2 +:1041100042F004021A60FEF7D5FEBDE80840FEF743 +:1041200085BC00BF004402580018024870470000D8 +:10413000114BD3F8E82042F00802C3F8E820D3F886 +:10414000102142F00802C3F810210C4AD3F81031B4 +:10415000D36B43F00803D363C722094B9A624FF035 +:10416000FF32DA6200229A615A63DA605A600122F1 +:104170005A611A60704700BF004402580010005C8A +:10418000000C0040094A08B51169D3680B40D9B248 +:104190009B076FEA0101116107D5302383F3118872 +:1041A000FEF7E6F9002383F3118808BD000C0040F8 +:1041B000064BD3F8DC200243C3F8DC20D3F80421FB +:1041C0001043C3F80401D3F8043170470044025887 +:1041D00008B53C4B4FF0FF31D3F8802062F000422D +:1041E000C3F88020D3F8802002F00042C3F880207A +:1041F000D3F88020D3F88420C3F88410D3F8842027 +:104200000022C3F88420D3F88400D86F40F0FF4028 +:1042100040F4FF0040F4DF4040F07F00D867D86FE3 +:1042200020F0FF4020F4FF0020F4DF4020F07F006A +:10423000D867D86FD3F888006FEA40506FEA5050C3 +:10424000C3F88800D3F88800C0F30A00C3F88800D8 +:10425000D3F88800D3F89000C3F89010D3F89000FA +:10426000C3F89020D3F89000D3F89400C3F89410CA +:10427000D3F89400C3F89420D3F89400D3F89800AE +:10428000C3F89810D3F89800C3F89820D3F8980092 +:10429000D3F88C00C3F88C10D3F88C00C3F88C20B2 +:1042A000D3F88C00D3F89C00C3F89C10D3F89C1072 +:1042B000C3F89C20D3F89C30FDF79CF8BDE808407B +:1042C00000F0B8B90044025808B50122534BC3F8B6 +:1042D0000821534BD3F8F42042F00202C3F8F42033 +:1042E000D3F81C2142F00202C3F81C210222D3F8A9 +:1042F0001C314C4BDA605A689104FCD54A4A1A606A +:1043000001229A60494ADA6000221A614FF4404261 +:104310009A61444B9A699204FCD51A6842F48072FF +:104320001A603F4B1A6F12F4407F04D04FF4803272 +:104330001A6700221A671A6842F001021A60384BA5 +:104340001A685007FCD500221A611A6912F0380267 +:10435000FBD1012119604FF0804159605A67344AFE +:10436000DA62344A1A611A6842F480321A602C4BBD +:104370001A689103FCD51A6842F480521A601A68D0 +:104380009204FCD52C4A2D499A6200225A63196383 +:1043900001F57C01DA6301F2E71199635A64284A56 +:1043A0001A64284ADA621A6842F0A8521A601C4B52 +:1043B0001A6802F02852B2F1285FF9D148229A61B6 +:1043C0004FF48862DA6140221A621F4ADA641F4A97 +:1043D0001A651F4A5A651F4A9A6532231E4A13609E +:1043E000136803F00F03022BFAD10D4A136943F04F +:1043F00003031361136903F03803182BFAD14FF04C +:104400000050FFF7D5FE4FF08040FFF7D1FE4FF090 +:104410000040BDE80840FFF7CBBE00BF0080005160 +:10442000004402580048025800C000F00200000199 +:104430000000FF01008890081210200063020901AB +:10444000470E0508DD0BBF01200000200000011011 +:104450000910E00000010110002000524FF0B042AE +:1044600008B5D2F8883003F00103C2F8883023B1D0 +:10447000044A13680BB150689847BDE80840FEF73E +:104480006FBD00BFC44700204FF0B04208B5D2F85E +:10449000883003F00203C2F8883023B1044A9368DD +:1044A0000BB1D0689847BDE80840FEF759BD00BF82 +:1044B000C44700204FF0B04208B5D2F8883003F06E +:1044C0000403C2F8883023B1044A13690BB1506960 +:1044D0009847BDE80840FEF743BD00BFC447002031 +:1044E0004FF0B04208B5D2F8883003F00803C2F8A4 +:1044F000883023B1044A93690BB1D0699847BDE86D +:104500000840FEF72DBD00BFC44700204FF0B04269 +:1045100008B5D2F8883003F01003C2F8883023B110 +:10452000044A136A0BB1506A9847BDE80840FEF789 +:1045300017BD00BFC44700204FF0B04310B5D3F8FB +:10454000884004F47872C3F88820A30604D5124A80 +:10455000936A0BB1D06A9847600604D50E4A136B74 +:104560000BB1506B9847210604D50B4A936B0BB1E6 +:10457000D06B9847E20504D5074A136C0BB1506C19 +:104580009847A30504D5044A936C0BB1D06C9847A7 +:10459000BDE81040FEF7E4BCC44700204FF0B04334 +:1045A00010B5D3F8884004F47C42C3F88820620533 +:1045B00004D5164A136D0BB1506D9847230504D5E9 +:1045C000124A936D0BB1D06D9847E00404D50F4AA1 +:1045D000136E0BB1506E9847A10404D50B4A936E2D +:1045E0000BB1D06E9847620404D5084A136F0BB123 +:1045F000506F9847230404D5044A936F0BB1D06FD2 +:104600009847BDE81040FEF7ABBC00BFC447002090 +:1046100008B50348FDF756F8BDE80840FEF7A0BC12 +:104620005C24002008B5FFF7ADFDBDE80840FEF7AB +:1046300097BC0000062108B50846FDF7C9F8062119 +:104640000720FDF7C5F806210820FDF7C1F806216F +:104650000920FDF7BDF806210A20FDF7B9F806216B +:104660001720FDF7B5F806212820FDF7B1F809213C +:104670007A20FDF7ADF807213220FDF7A9F80C21CB +:104680002520BDE80840FDF7A3B8000008B5FFF7F6 +:104690009FFD00F00DF8FDF759FAFDF731FCFDF72D +:1046A00003FBFFF743FDBDE80840FFF71BBC00001C +:1046B0000023054A19460133102BC2E9001102F10B +:1046C0000802F8D1704700BFC447002010B5013977 +:1046D0000244904201D1002005E0037811F8014F17 +:1046E000A34201D0181B10BD0130F2E7034611F8B8 +:1046F000012B03F8012B002AF9D1704753544D3395 +:104700003248373F3F3F0053544D333248373378B8 +:104710002F3732780053544D3332483734332F37E4 +:1047200035332F373530000001105A00031059007F +:1047300001205800032056001000024008000240EB +:104740000008024000000B00280002400800024060 +:104750000408024006010C0040000240080002402C +:104760000808024010020D005800024008000240F4 +:104770000C08024016030E00700002400C000240BC +:104780001008024000040F00880002400C000240A4 +:104790001408024006051000A00002400C00024070 +:1047A0001808024010061100B80002400C00024038 +:1047B0001C08024016072F001004024008040240A3 +:1047C0002008024000083800280402400804024083 +:1047D000240802400609390040040240080402404F +:1047E00028080240100A3A00580402400804024017 +:1047F0002C080240160B3B00700402400C040240DF +:1048000030080240000C3C00880402400C040240C6 +:1048100034080240060D4400A00402400C0402408B +:1048200038080240100E4500B80402400C04024053 +:104830003C080240160F46000096000000000000F1 +:104840000000000000000000000000000000000068 +:10485000000000000D1B0008F91A0008351B0008B5 +:10486000211B00082D1B0008191B0008051B000850 +:10487000F11A0008411B000800000000251C000878 +:10488000111C00084D1C0008391C0008451C0008BC +:10489000311C00081D1C0008091C0008591C0008D8 +:1048A0000000000001000000000000006330000074 +:1048B000AC48000820290020302B0020417264758C +:1048C00050696C6F740025424F415244252D424C73 +:1048D000002553455249414C2500000002000000CC +:1048E00000000000451E0008B51E00084000400002 +:1048F000E0430020F0430020020000000000000020 +:104900000300000000000000FD1E00080000000081 +:104910001000000000440020000000000100000022 +:10492000000000007446002001010200C9290008AF +:10493000D9280008752900085929000843000000FB +:104940004449000809024300020100C03209040082 +:1049500000010202010005240010010524010001EC +:10496000042402020524060001070582030800FF53 +:1049700009040100020A00000007050102400000CE +:104980000705810240000000120000009049000865 +:1049900012011001020000400912415700020102F9 +:1049A000030100000403090425424F41524425003D +:1049B0004D69636F416972373433003031323334BB +:1049C000353637383941424344454600000000003F +:1049D0005920000811230008BD23000840004000B2 +:1049E000AC470020AC47002001000000BC4700207D +:1049F00080000000400100000800000000010000ED +:104A000000100000080000006D61696E0069646CB0 +:104A1000650000000000A86A00000000AAAAAAAA77 +:104A200000001464FFFF00000000000070A70A00EF +:104A30000000000100000000AAAAAAAA00000001CC +:104A4000FFFF000000000000000000000000000068 +:104A500000000000AAAAAAAA00000000FFFF0000B0 +:104A60000000000000000000000500000000000041 +:104A7000AAAAAAAA00050000FFFF0000000000008B +:104A8000000000000011000000000000AAAAAAAA6D +:104A900000000000AFFF0000000000000000000068 +:104AA0000000000000000000AAAAAAAA000000005E +:104AB000FFFF0000000000000000000000000000F8 +:104AC00000000000AAAAAAAA00000000FFFF000040 +:104AD00000000000000000000000000000000000D6 +:104AE000AAAAAAAA00000000FFFF00000000000020 +:104AF000000000000000000000000000AAAAAAAA0E +:104B000000000000FFFF00000000000000000000A7 +:104B10000000000000000000AAAAAAAA00000000ED +:104B2000FFFF000000000000000000000000000087 +:104B300000000000AAAAAAAA00000000FFFF0000CF +:104B400000000000000000008E04000000000000D3 +:104B500000001A0000000000FF000000382B0020B9 +:104B60005C24002000000000FC46000883040000D4 +:104B70000747000850040000154700080096000091 +:104B8000000008009600000000080000040000007B +:104B9000A449000800000000000000000000000020 +:0C4BA00000000000000000000000000009 +:00000001FF diff --git a/Tools/bootloaders/Nucleo-L496_bl.bin b/Tools/bootloaders/Nucleo-L496_bl.bin new file mode 100755 index 00000000000000..c4139d494231dd Binary files /dev/null and b/Tools/bootloaders/Nucleo-L496_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-L496_bl.hex b/Tools/bootloaders/Nucleo-L496_bl.hex new file mode 100644 index 00000000000000..62113d995c8c01 --- /dev/null +++ b/Tools/bootloaders/Nucleo-L496_bl.hex @@ -0,0 +1,1764 @@ +:020000040800F2 +:1000000000090020D5040008C12800084128000884 +:1000100099280008412800086D280008D704000826 +:10002000D7040008D7040008D7040008613A000884 +:10003000D7040008D7040008D7040008D704000834 +:10004000D7040008D7040008D7040008D704000824 +:10005000D7040008D704000885640008AD640008D0 +:10006000D5640008FD64000825650008D704000871 +:10007000D7040008D7040008D7040008D7040008F4 +:10008000D7040008D7040008D70400088524000816 +:10009000B1240008C1240008D70400084D650008F9 +:1000A000D7040008D7040008D7040008D7040008C4 +:1000B00035660008D7040008D7040008D7040008F4 +:1000C000D7040008D7040008D7040008D7040008A4 +:1000D000D704000821660008D7040008D7040008E8 +:1000E000B1650008D7040008D7040008D704000849 +:1000F000D7040008D7040008D7040008D704000874 +:10010000D7040008D7040008D7040008D704000863 +:10011000D7040008D7040008D7040008D704000853 +:10012000D7040008D7040008D7040008D704000843 +:10013000D7040008D7040008D7040008D704000833 +:10014000D7040008D7040008D7040008E55A0008BF +:10015000D7040008D7040008D7040008D704000813 +:10016000D7040008D7040008D7040008D704000803 +:10017000D7040008D7040008D7040008D7040008F3 +:10018000D7040008D7040008D7040008D7040008E3 +:10019000D7040008D7040008D7040008D7040008D3 +:1001A000D7040008D7040008D7040008D7040008C3 +:1001B000D7040008D7040008D7040008D7040008B3 +:1001C0005D160008000000000000000000000000B4 +:1001D00053B94AB9002908BF00281CBF4FF0FF31AE +:1001E0004FF0FF3000F074B9ADF1080C6DE904CEAA +:1001F00000F006F8DDF804E0DDE9022304B0704702 +:100200002DE9F047089D04468E46002B4DD18A42C9 +:10021000944669D9B2FA82F252B101FA02F3C2F1FC +:10022000200120FA01F10CFA02FC41EA030E94408D +:100230004FEA1C48210CBEFBF8F61FFA8CF708FBAE +:1002400016E341EA034306FB07F199420AD91CEB86 +:10025000030306F1FF3080F01F81994240F21C81B8 +:10026000023E63445B1AA4B2B3FBF8F008FB103300 +:1002700044EA034400FB07F7A7420AD91CEB040435 +:1002800000F1FF3380F00A81A74240F20781644405 +:10029000023840EA0640E41B00261DB1D44000238A +:1002A000C5E900433146BDE8F0878B4209D9002DEE +:1002B00000F0EF800026C5E9000130463146BDE878 +:1002C000F087B3FA83F6002E4AD18B4202D38242E2 +:1002D00000F2F980841A61EB030301209E46002D91 +:1002E000E0D0C5E9004EDDE702B9FFDEB2FA82F2E6 +:1002F000002A40F09280A1EB0C014FEA1C471FFA44 +:100300008CFE0126200CB1FBF7F307FB131140EA2A +:1003100001410EFB03F0884208D91CEB010103F1F7 +:10032000FF3802D2884200F2CB804346091AA4B2B9 +:10033000B1FBF7F007FB101144EA01440EFB00FE8D +:10034000A64508D91CEB040400F1FF3102D2A645F2 +:1003500000F2BB800846A4EB0E0440EA03409CE791 +:10036000C6F12007B34022FA07FC4CEA030C20FA3E +:1003700007F401FA06F31C43F9404FEA1C4900FA5E +:1003800006F3B1FBF9F8200C1FFA8CFE09FB1811DB +:1003900040EA014108FB0EF0884202FA06F20BD94E +:1003A0001CEB010108F1FF3A80F08880884240F29E +:1003B0008580A8F102086144091AA4B2B1FBF9F0E2 +:1003C00009FB101144EA014100FB0EFE8E4508D9DD +:1003D0001CEB010100F1FF346CD28E456AD9023862 +:1003E000614440EA0840A0FB0294A1EB0E01A14247 +:1003F000C846A64656D353D05DB1B3EB080261EBB5 +:100400000E0101FA07F722FA06F3F1401F43C5E98E +:10041000007100263146BDE8F087C2F12003D840C4 +:100420000CFA02FC21FA03F3914001434FEA1C4706 +:100430001FFA8CFEB3FBF7F007FB10360B0C43EAF8 +:10044000064300FB0EF69E4204FA02F408D91CEBA8 +:10045000030300F1FF382FD29E422DD902386344A6 +:100460009B1B89B2B3FBF7F607FB163341EA034146 +:1004700006FB0EF38B4208D91CEB010106F1FF3895 +:1004800016D28B4214D9023E6144C91A46EA00468C +:1004900038E72E46284605E70646E3E61846F8E61E +:1004A0004B45A9D2B9EB020864EB0C0E0138A3E767 +:1004B0004646EAE7204694E74046D1E7D0467BE748 +:1004C000023B614432E7304609E76444023842E7C0 +:1004D000704700BF02E000F000F8FEE772B63A484D +:1004E00080F30888394880F3098839484EF6085166 +:1004F000CEF20001086040F20000CCF200004EF69F +:100500003471CEF200010860BFF34F8FBFF36F8FDD +:1005100040F20000C0F2F0004EF68851CEF2000129 +:100520000860BFF34F8FBFF36F8F4FF00000E1EE15 +:10053000100A4EF63C71CEF200010860062080F3EE +:100540001488BFF36F8F04F0B1FF04F08DFF05F046 +:100550002FFE4FF055301F491B4A91423CBF41F8D6 +:10056000040BFAE71C49194A91423CBF41F8040BBD +:10057000FAE71A491A4A1B4B9A423EBF51F8040B3C +:1005800042F8040BF8E700201749184A91423CBF93 +:1005900041F8040BFAE704F06BFF05F055FE144C2C +:1005A000144DAC4203DA54F8041B8847F9E700F015 +:1005B00041F8114C114DAC4203DA54F8041B884742 +:1005C000F9E704F053BF00000009002000110020EB +:1005D000000000080001002000090020506D000804 +:1005E00000110020C4110020C8110020D43F0020B9 +:1005F000C0010008C4010008C4010008C4010008CB +:100600002DE9F04F2DED108AC1F80CD0C3689D463E +:10061000BDEC108ABDE8F08F002383F311882846D3 +:10062000A047002004F0D0FAFEE704F03FFA00DF14 +:10063000FEE70000F8B504F0CDFE074604F00AFF1F +:100640000546B8BB204B9F4234D001339F4234D083 +:100650001E4B27F0FF029A4232D1F8B200F050FE52 +:100660002E4642F2107400F051FE08B100242646D6 +:1006700002F044FA20B1032000F07CF80024264662 +:1006800035B1134B9F4203D004F0DCFE0024264614 +:10069000002004F0A9FE0EB100F082F801F080F90C +:1006A00000F058FE01F056F8204600F0D9F800F0AE +:1006B00077F8F9E72E460024D5E704460126D2E76D +:1006C00006464FF47A74CEE7010007B0000008B088 +:1006D000263A09B008B501F009F8A0F12003584204 +:1006E000584108BD07B541F21203022101A8ADF837 +:1006F000043001F019F803B05DF804FB38B520238D +:1007000083F311881748C3680BB104F0E3FA164A63 +:10071000144800234FF47A7104F0A0FA002383F305 +:100720001188124C236813B12368013B236063686E +:1007300013B16368013B63600D4D2B7833B9636877 +:100740007BB9022001F0A6F8322363602B78032BDB +:1007500007D163682BB9022001F09CF84FF47A733B +:10076000636038BDC8110020FD060008E4120020B7 +:10077000DC110020084B187003280CD8DFE800F0CB +:1007800008050208022001F07BB8022001F070B8D1 +:10079000024B00225A607047DC110020E412002056 +:1007A00010B502F0ABF930B1274B03221A70274B7A +:1007B00000225A6010BD264B264A1C46196801319A +:1007C000F8D004339342F9D16268A242F2D3224BAB +:1007D0009B6803F1006303F520439A42EAD204F0D8 +:1007E00017FE002000F0D0FF0220FFF7C3FF1B4BD5 +:1007F0009A6D00229A65996F9A67996FD96DDA653B +:10080000D96FDA67D96F196E1A66D3F88010C3F8FA +:100810008020D3F88020DA6A42F48052DA62DA6A01 +:1008200022F48052DA62DB6A72B64FF0E0232021B4 +:10083000C3F8084DD4E9003281F311889D4683F353 +:1008400008881047B6E700BFDC110020E412002042 +:1008500000A0000820A000080011002000100240A5 +:100860002DE9F04F93B0AC4B00902022FF210AA855 +:100870009D6801F03FF8A94A1378A3B9A84801215F +:10088000C3601170202383F31188C3680BB104F097 +:1008900021FAA44AA24800234FF47A7104F0DEF949 +:1008A000002383F31188009B13B19F4B009A1A60B9 +:1008B0009E4A009C1378032B1EBF002313709A4A94 +:1008C0004FF0000A18BF5360D3465646D146012068 +:1008D00000F0D6FF24B1944B1B68002B00F015826A +:1008E000002000F003FF0390039B002B01DA00F0CF +:1008F00079FD039B002BEDDB012000F0B9FF039B8A +:10090000213B162BE3D801A252F823F06909000815 +:1009100091090008250A0008CF080008CF08000840 +:10092000CF080008AF0A00087F0C0008990B0008E8 +:10093000FB0B0008230C0008490C0008CF08000836 +:100940005B0C0008CF080008CD0C0008090A00085D +:10095000CF080008110D000875090008090A0008F1 +:10096000CF080008FB0B00080220FFF7B3FE0028A9 +:1009700040F0F581009B0221BAF1000F08BF1C4630 +:1009800005A841F21233ADF8143000F0CDFE9EE719 +:100990004FF47A7000F0AAFE071EEBDB0220FFF78F +:1009A00099FE0028E6D0013F052F00F2DA81DFE84A +:1009B00007F0030A0D10133605230593042105A83B +:1009C00000F0B2FE17E054480421F9E7584804212A +:1009D000F6E758480421F3E74FF01C08404600F0C2 +:1009E000D5FE08F104080590042105A800F09CFE3E +:1009F000B8F12C0FF2D1012000FA07F747EA0B0BF0 +:100A00005FFA8BFB4FF0000900F0C0FF26B10BF03E +:100A10000B030B2B08BF0024FFF764FE57E7464883 +:100A20000421CDE7002EA5D00BF00B030B2BA1D199 +:100A30000220FFF74FFE074600289BD0012000F060 +:100A4000A3FE0220FFF796FE00265FFA86F84046D6 +:100A500000F0AAFE044690B10021404600F0B4FE2A +:100A600001360028F1D1BA46044641F212130221A0 +:100A700005A8ADF814303E4600F056FE27E70120E9 +:100A8000FFF778FE2546244B9B68AB4207D92846E2 +:100A900000F07CFE013040F067810435F3E7234B22 +:100AA00000251D70204BBA465D603E46ACE7002E27 +:100AB0003FF460AF0BF00B030B2B7FF45BAF022016 +:100AC000FFF758FE322000F011FEB0F10008FFF6EB +:100AD00051AF18F003077FF44DAF0F4A926808EB4F +:100AE000050393423FF646AFB8F5807F3FF742AF2C +:100AF000124B0193B84523DD4FF47A7000F0F6FDF8 +:100B00000390039A002AFFF635AF019B039A03F87E +:100B1000012B0137EDE700BF00110020E01200209B +:100B2000C8110020FD060008E4120020DC1100209E +:100B300004110020081100200C110020E0110020F9 +:100B4000C820FFF7C7FD074600283FF413AF1F2D4D +:100B500011D8C5F1200242450AAB25F0030028BF99 +:100B6000424683490192184400F09EFE019A804853 +:100B7000FF2100F0BFFE4FEAA8037D490193C8F3AF +:100B80008702284600F0BEFE064600283FF46DAFFF +:100B9000019B05EB830537E70220FFF79BFD00284B +:100BA0003FF4E8AE00F02EFE00283FF4E3AE00274D +:100BB000B846704B9B68BB4218D91F2F11D80A9BAF +:100BC00001330ED027F0030312AA134453F8203C3C +:100BD00005934046042205A901F07AFF04378046B8 +:100BE000E7E7384600F0D2FD0590F2E7CDF8148033 +:100BF000042105A800F098FD06E70023642104A85D +:100C0000049300F087FD00287FF4B4AE0220FFF7C4 +:100C100061FD00283FF4AEAE049800F0E9FD0590B8 +:100C2000E6E70023642104A8049300F073FD002884 +:100C30007FF4A0AE0220FFF74DFD00283FF49AAEEE +:100C4000049800F0D7FDEAE70220FFF743FD0028F3 +:100C50003FF490AE00F0E6FDE1E70220FFF73AFD39 +:100C600000283FF487AE05A9142000F0E1FD04211F +:100C70000746049004A800F057FD3946B9E7322032 +:100C800000F034FD071EFFF675AEBB077FF472AEB1 +:100C9000384A926807EB090393423FF66BAE022095 +:100CA000FFF718FD00283FF465AE27F003074F4417 +:100CB000B9453FF4A9AE484600F068FD042105900F +:100CC00005A800F031FD09F10409F1E74FF47A704D +:100CD000FFF700FD00283FF44DAE00F093FD002823 +:100CE00044D00A9B01330BD008220AA9002000F04F +:100CF00009FE00283AD02022FF210AA800F0FAFDC0 +:100D0000FFF7F0FC1C4803F065FF13B0BDE8F08F5F +:100D1000002E3FF42FAE0BF00B030B2B7FF42AAE0B +:100D20000023642105A8059300F0F4FC0746002881 +:100D30007FF420AE0220FFF7CDFC804600283FF470 +:100D400019AEFFF7CFFC41F2883003F043FF05985E +:100D500000F066FE464600F019FE3C46B7E5064642 +:100D600052E64FF0000905E6BA467EE637467CE6D5 +:100D7000E011002000110020A0860100094A13683C +:100D800049F2690099B21B0C00FB01331360064B5A +:100D9000186844F2506182B2000C01FB0200186036 +:100DA00080B27047141100201011002010B50021EE +:100DB0001022044600F09EFD034B03CB20606160CF +:100DC0001868A06010BD00BF9075FF1F2DE9F041AD +:100DD000ADF54E7D0DF134086CAC40F2751207464E +:100DE0000D460EA80021C8F8001000F083FD4FF456 +:100DF000C4720021204600F07DFD01F069FD254B05 +:100E00004FF47A72B0FBF2F0186093E80700012308 +:100E100084E807000DF5E9702382FFF7C7FF41F270 +:100E200004731D49238406A805F0C8FD192384F81E +:100E300032310DF2E32206AB0DF1300C1E4603CE2B +:100E4000664510605160334602F10802F6D13378EE +:100E5000137041460122204601F040FD0023039318 +:100E6000AB7E029305F11903019380B20123CDE912 +:100E700004800093E97E05A3D3E90023384602F0FD +:100E800095F90DF54E7DBDE8F08100BF9E6AC42145 +:100E9000818A46EEEC120020EC6900082DE9F0434F +:100EA000224DBBB001F014FDAB6840F2ED22C31A35 +:100EB000934232D906AFA8602B462822002138463B +:100EC00002F05CFB05F10E0000F00CFD002604466C +:100ED0005FFA80F905F10E08F3B2F100994501F1CE +:100EE000280107D908EB06030822384602F046FB22 +:100EF0000136F1E708230122CDE9023205340C4B1B +:100F00000193A4B230230093CDE9047405A3D3E97F +:100F10000023297B074802F049F93BB0BDE8F08384 +:100F2000AFF3008078F6339F93CACD8D0034002054 +:100F30000D34002004230020F0B58B8A013B9BB2C6 +:100F4000C92BC9B006460C4647D8274D2F7B27BB77 +:100F500005F10C03009308223B463946204602F077 +:100F6000D1F97B1CFAB2D9001F46A38A013B9A42F1 +:100F700005DA0E322A44009200230822EEE700230D +:100F80000022C5E900230023AB6085F8D730C5F8FF +:100F9000D8302B7B0BB9E37E2B738122002106AD69 +:100FA00027A800F0A7FC0122294627A801F064FD2C +:100FB00000230393A37E029304F1190380B20193EB +:100FC0002823CDE90450E17E0093304604A3D3E901 +:100FD000002302F0EBF8FFF761FF49B0F0BD00BF5E +:100FE00026417272DF25D7B70034002070B50D4658 +:100FF00014461E4602F070F850B9022E10D1012C92 +:101000000ED112A3D3E90023C5E90023012007E094 +:10101000282C10D005D8012C09D0052C0FD0002089 +:1010200070BD302CFBD10BA3D3E90023ECE70BA35D +:10103000D3E90023E8E70BA3D3E90023E4E70BA3FC +:10104000D3E90023E0E700BFAFF30080401DA120FB +:1010500026812A0B78F6339F93CACD8D9E6AC421D0 +:10106000818A46EE26417272DF25D7B7F017304AE3 +:1010700039059E562DE9F04F8DB002AF80460D46E2 +:1010800002F02AF8044600285CD12B7E022B1BD1EB +:10109000EB8A012B18D101F01BFC0646FFF76EFE10 +:1010A00003464FF4C870DFF81C92B3FBF0F206F56C +:1010B000167602FB103316FA83F3C9F80030EB7E84 +:1010C00033B97B4B00221A702C37BD46BDE8F08F38 +:1010D000AB8AE6B2013BB34204F101040CD907F13B +:1010E00008031E44E10000960023082201F0F801E5 +:1010F000284602F007F9EBE707F11800FFF756FE64 +:10110000324607F1180107F1080005F02BFB002813 +:10111000D7D10F2E08D8664B1E70D9F80030A3F532 +:101120001673C9F80030CFE7FB1DF8710146009334 +:1011300007220346284602F0E5F8F979404601F017 +:10114000C3FFC1E7EB8A282B26D010D8012B1ED075 +:10115000052BB9D1BFF34F8F5649574BCA6802F4DC +:10116000E0621343CB60BFF34F8F00BFFDE7302B2E +:10117000AAD16B7E514C0133627BDBB29342E946CC +:1011800003D1EA7E237B9A420BD0CD469CE72946C9 +:101190004046FFF71BFE97E729464046FFF7CCFE87 +:1011A00092E74FF0000807F11803A7F81880102203 +:1011B000009341460123284602F0A4F8AE8A023E7D +:1011C000B6B2F31C9B109B000733DB08A9EBC303EB +:1011D0009D460DF1080A1FFA88F34FEAC8019E42A6 +:1011E00001F110010AD90AEB080300930822002339 +:1011F000284602F087F808F10108ECE794F8D700D8 +:1012000000F0D2FAD4F8D810054619B994F8D700EE +:1012100000F0DAFAD4F8D83033449D4205D294F87D +:10122000D7000021013000F0CFFA4FEA960B4FF0C3 +:1012300000081FFA88F18B45D4E9003209D90AEB7E +:10124000880103EB8800012200F05CFB08F1010833 +:10125000EFE7F31842F10002C4E90032D4F8D830C5 +:1012600094F8D70006EB0308C4F8D88000F09CFA85 +:10127000804509D394F8D730D4F8D8000133401B07 +:1012800084F8D730C4F8D800FF2E0D4D09D80023BC +:10129000237300F0B7FA01F031FC288108B9FFF799 +:1012A0007FFA23689B0A01332B810023A3606CE73C +:1012B000FD22002000ED00E00400FA0500340020CB +:1012C000EC1200200023002010B50A4B0A4A1A60D5 +:1012D00003F5805393F860203AB9DC6D2CB12046B9 +:1012E00001F074F9204605F0FBF9BDE81040034811 +:1012F00001F06CB9302300203C6A000878330020EC +:10130000014B1870704700BFF812002010B54FF065 +:1013100000540C4B22689A4211D10B4B627D1A701B +:101320000A48237D03730A49C9220E3000F0BCFA33 +:10133000E0220021204600F0DDFA012010BD00204F +:10134000FCE700BF9AAD44C5F8120020003400202D +:101350001600002037B501F0D1FB194D194928813D +:101360000223012218486B7100F07CFF00230193D7 +:10137000164B174900931748174B4FF4805201F052 +:101380007DFE164B197811B1124801F09DFE01F057 +:101390009FFA0446FFF7F2FC4FF4C873B0FBF3F278 +:1013A00002FB130304F5167010FA83F00C4B18605F +:1013B00004F050F808B10F232B8103B030BD00BFFB +:1013C000EC12002040420F0030230020ED0F0008F7 +:1013D000FC1200200423002075100008F8120020E1 +:1013E000002300202DE9F04F2DED028B0FF25C2938 +:1013F000D9E900898B4C93B08B4E8C4F204601F07D +:1014000039FF034660B30025CDE90F550E95ADF8C1 +:101410004450027B8DF8442099684068DFF834A27C +:101420000FAA03C21B6843F000430E9301F052FA67 +:10143000821941F1000300950EA9384600F040FBE7 +:10144000A84205DD204601F019FF8AF80050D5E7D3 +:101450009AF80030072B00F2B58001338AF800308B +:101460000BAE9FED6C8B0023704FDFF8ECA10A935D +:10147000ADF834300B9373604FF0000B5B468DED8D +:10148000008B01250DF11D0207A938468DF81C506F +:101490008DF81DB000F096FE9DF81C30002B40F03A +:1014A0009580204601F018FE0646002845D1604F81 +:1014B00001F00EFA3B6898423FD301F009FA8246E8 +:1014C000FFF75CFC4FF4C8730AF5167AB0FBF3F231 +:1014D00002FB13031AFA83F33B60564F97F800B0F0 +:1014E000CBF1100ABBF1000F14BF33462B465FFA55 +:1014F0008AFA0EA88DF82830FFF758FCBAF1060FCB +:1015000028BF4FF0060A0EAB03EB0B0152460DF15C +:10151000290000F0C9F90AAB0393182302930AF1DA +:101520000102454BD2B2CDE90053049220463BA3C1 +:10153000D3E9002301F0D2FD3E7001F0C9F93F4A22 +:101540003F4D1368C31AB3F57A7F2ED3106001F0B4 +:10155000C1F902460B46204601F09AFE204601F0F2 +:10156000BBFD10B32B7B374E002B14BF032302238C +:10157000737101F0ADF90EAF4FF47A730122B0FB35 +:10158000F3F039463060304601F04EFA18230293EA +:101590002D4B019380B240F25513CDE903700093B7 +:1015A00042464B46204601F099FD2B7B2BB1FFF7BD +:1015B00075FC2B7B002B7FF41FAF13B0BDEC028BAF +:1015C000BDE8F08F204601F059FE49E7DAF8143003 +:1015D00083F08003CAF81430594610220EA800F098 +:1015E00089F90DF11E0308AA0AA9384600F066FB26 +:1015F00096E803000FAB83E803009DF834308DF8C4 +:1016000044300A9B0E930EA9DDE90823204601F021 +:10161000FDFF31E70000000000000000401DA12098 +:1016200026812A0B0423002040420F003023002093 +:1016300000230020FD220020FC220020E0340020B6 +:1016400000340020EC120020E4340020F1C6A7C1D1 +:10165000D068080FE53400200004004808B50548AC +:1016600000F0C6FBBDE80840034A0449002005F02D +:1016700031B800BF3023002038350020C9120008DF +:101680002DE9F84F4FF47A73DFF85880DFF858905F +:1016900006460D4602FB03F7002498F900305A1C59 +:1016A0005FFA84FA01D0A34212D159F824000368EA +:1016B0002A46D3F820B031463B46D847854207D169 +:1016C000074B012083F800A0BDE8F88F0124E4E770 +:1016D000002CFBD04FF4FA7003F07CFA0020F3E703 +:1016E0002C350020181100201C11002007B5002304 +:1016F000024601210DF107008DF80730FFF7C0FF0A +:1017000020B19DF8070003B05DF804FB4FF0FF30F7 +:10171000F9E700000A4608B50421FFF7B1FF80F0A1 +:101720000100C0B2404208BD30B4074B0A461978E8 +:10173000064B53F821402368DD69054B0146AC4652 +:10174000204630BC604700BF2C3500201C11002013 +:10175000A086010070B503F0D7FC094E094D30801A +:10176000002428683388834208D903F0C9FC2B6819 +:1017700004440133B4F5204F2B60F2D370BD00BF99 +:101780002E350020E834002003F07EBD00F100601B +:1017900000F520400068704700F10060920000F5FD +:1017A000204003F0F5BC0000054B1A68054B1B8870 +:1017B0009B1A834202D9104403F0A2BC0020704758 +:1017C000E83400202E35002038B5084D044629B1F4 +:1017D00028682044BDE8384003F0AABC28682044AB +:1017E00003F094FC0028F3D038BD00BFE83400209B +:1017F0000020704700F10050A0F51040D0F890058F +:1018000070470000064991F8243033B10023086A7C +:1018100081F824300822FFF7BFBF0120704700BFC6 +:10182000EC340020014B1868704700BF002004E032 +:1018300070B50E4B5C6893F90860421E0A44013C87 +:101840000B46934207D214F9015F581C2DB100F8E2 +:10185000015C0346F5E7184605E02C2482421C7023 +:1018600001D9981C5E70401A70BD00BF2411002081 +:10187000022802BF014B80229A6170470004004891 +:10188000022802BF024B4FF400029A61704700BF6A +:1018900000040048022801BF024A536983F0800314 +:1018A000536170470004004810B50023934203D0F1 +:1018B000CC5CC4540133F9E710BD000010B5013809 +:1018C00010F9013F3BB191F900409C4203D11AB19C +:1018D0000131013AF4E71AB191F90020981A10BDCC +:1018E0001046FCE703460246D01A12F9011B0029F4 +:1018F000FAD1704702440346934202D003F8011B19 +:10190000FAE770472DE9F8431F4D144695F8242057 +:101910000746884652BBDFF870909CB395F8243098 +:101920002BB92022FF2148462F62FFF7E3FF95F8ED +:101930002400C0F10802A24228BF2246D6B2414686 +:10194000920005EB8000FFF7AFFF95F82430A41B51 +:101950001E44F6B2082E17449044E4B285F8246081 +:10196000DBD1FFF74FFF0028D7D108E02B6A03EB4C +:1019700082038342CFD0FFF745FF0028CBD1002060 +:10198000BDE8F8830120FBE7EC340020024B1A7815 +:10199000024B1A70704700BF2C3500201811002030 +:1019A00038B5194C194D204602F016FC2946204640 +:1019B00002F03EFC2D681648EA6ED2F8043843F077 +:1019C0000203C2F8043803F005F92846114902F071 +:1019D00037FDEA6E104DD2F8043828680F4923F01D +:1019E0000203C2F80438A0424FF461430B6001D0F7 +:1019F00002F052FB6868A04204D0BDE838400749B5 +:101A000002F04ABB38BD00BF60370020946B00086D +:101A100040420F009C6B00081C1100201435002070 +:101A200070B50C4B0C4D1E780C4B55F826209A4285 +:101A300004460DD00A4B002118221846FFF75AFF22 +:101A40000460014655F82600BDE8704002F024BB52 +:101A500070BD00BF2C3500201C1100206037002015 +:101A600014350020202383F3118862B670470000EC +:101A7000002383F3118862B67047000010B4026837 +:101A800054681A4623465DF8044B184701207047F6 +:101A9000002070470020704770470000002070470A +:101AA0000E20704700F5805090F8C800C0F3400049 +:101AB0007047000000F5805090F9C90070470000A1 +:101AC0002DE9F0410C68BDF8187014F000541E4662 +:101AD0006FD10B7B082B6CD8FFF7C4FF4569AB684F +:101AE0005B010CD4AB681B0108D4AC6814F08054C3 +:101AF0005DD1FFF7BDFF2046BDE8F08101240B68F2 +:101B000004F1180C002BB8BFDB004FEA0C1CB4BF6B +:101B100043F004035B0545F80C300B680FFA84FCB6 +:101B200013F0804F18BF05EB0C1E05EB0C1C1EBFFD +:101B3000DEF8803143F00203CEF880310B7BCCF825 +:101B4000843105EB04158B68C5F88C314B68C5F8FA +:101B50008831DCF8803143F00103CCF8803100EBB0 +:101B6000441541F268031D4403EB44130344C5E9E3 +:101B7000002608330D4601F10C0C55F804EB43F830 +:101B800004EB6545F9D184342D881D8000EB4414A5 +:101B900007F00303257925F00B052B432371FFF78D +:101BA00067FF06973346BDE8F04100F0AFBC022462 +:101BB000A5E74FF0FF309FE713B500F58054019182 +:101BC000E06D00F039FD1F280AD90199E06D20224F +:101BD00000F0A8FDA0F120035842584102B010BD0A +:101BE0000020FBE708B500F58050FFF73BFFC06D14 +:101BF00000F0F6FCBDE80840FFF73ABF00220260A3 +:101C0000828142608260704710B500220023C0E9E3 +:101C100000230023044603810C30FFF7EFFF20462A +:101C200010BD0000F0B5054600F580500C4690F858 +:101C3000C83013F0040FC3F3800108BF114661F3ED +:101C4000820304F1840680F8C83005EB461389B09E +:101C50001B79D8072ED57AB319072DD46846FFF71C +:101C6000D3FF05EB441303F5835303F1180703AACD +:101C7000103318685968144603C40833BB4222461F +:101C8000F7D1186820609B88A380DDE90E23CDE999 +:101C900000230123ADF808302B686946DB6B28462A +:101CA000984705EB46152B791A075CBF43F00803EC +:101CB0002B7101E0002AF4D109B0F0BD2DE9F04705 +:101CC000074688B007F5805468469A468846FFF76D +:101CD000C9FE9146FFF798FFE06D00F093FC1F28C6 +:101CE00029D9E06D2022694600F09EFD202822D1EE +:101CF00003AD444605AB2E4603CE9E422060616094 +:101D0000354604F10804F6D130682060B388A3801A +:101D1000DDE90023C9E90023BDF80830AAF8003046 +:101D2000FFF7A6FE4A4653464146384608B0BDE88E +:101D3000F04700F0D9BBFFF79BFE002008B0BDE8DC +:101D4000F08700002DE9F84F0023C0E90133254B4F +:101D5000044640F8183B0F46FFF750FF04F12800F7 +:101D6000FFF752FF04F1480804F58255464608354E +:101D700030462036FFF748FFAE42F9D104F58055D2 +:101D80004FF480534FF00009C5E91339C5F8488076 +:101D90000123EE6504F5875804F58456C5F8549080 +:101DA00085F8583085F86030083608F108084FF09B +:101DB000000A4FF0000B46E908ABA6F11800FFF748 +:101DC0001DFF203646F8289C4645F4D185F8C97099 +:101DD00017B1054800F076FD044B63612046BDE86D +:101DE000F88F00BF3C6A0008146A000800640040D5 +:101DF00010B5044B197804464A1C1A70FFF7A2FF6D +:101E0000204610BD343500202DE9F047002950D080 +:101E1000294B2A4FB7FBF1F599428CBF0A231123B6 +:101E2000581EB5FBF3FC03FB1C53C4B22BB10228B4 +:101E30000346F5D80020BDE8F0870CF1FF36B6F573 +:101E4000806FF7D2C4EBC40E0EF103034FEAE3092F +:101E5000C3F3C703A4EB030809F1010A4FF47A7531 +:101E60005FFA88F009FB05555AFA88F8B5FBF8F5D2 +:101E7000B5F5617FC1BF0EF1FF33C3F3C703E01AAD +:101E8000C0B25C1C50FA84F40CFB04F4B7FBF4F40D +:101E9000A142CFD1013BDBB20F2BCBD80138C0B26E +:101EA0000728C7D80021107116809170D3700120C7 +:101EB000C1E70846BFE700BF3F420F0000B4C404BB +:101EC00070B505460E464FF47A746B695B6803F093 +:101ED0000103B34207D04FF47A7002F07BFE013C5D +:101EE000F3D1204670BD0120FCE7000030B5426907 +:101EF000936913F0700F16D000230B4C936103F11C +:101F0000840200EB421211794D0709D5890707D5E4 +:101F1000416954F823508D60117941F00401117129 +:101F20000133032BEBD130BD286A000873B51D4681 +:101F3000436916469A68D207044609D59A68012172 +:101F40009960C2F34002CDE900650021FFF76AFE07 +:101F500063699A68D1050BD59A684FF480719960CE +:101F6000C2F34022CDE9006501212046FFF75AFE69 +:101F700063699A68D2030BD59A684FF480319960EF +:101F8000C2F34042CDE9006502212046FFF74AFE38 +:101F9000204602B0BDE87040FFF7A8BFF8B5044680 +:101FA000466900296CD106F10C07386880076AD0B1 +:101FB00006EB01153868D5F8B00110F0040FD5F81C +:101FC000B0011ABFC00840F00040400DA061D5F834 +:101FD000B0C11CF0020F1CBF40F08040A061D5F8DA +:101FE000B40106EB011100F00F0084F82400D1F8D1 +:101FF000B8012077D1F8B801000A6077D1F8B801AC +:10200000000CA077D1F8B801000EE077D1F8BC0140 +:1020100084F82000D1F8BC01000A84F82100D1F82E +:10202000BC01000C84F82200D1F8BC11090E84F820 +:1020300023103821396004F1340004F1180104F14F +:10204000240551F8046B40F8046BA942F9D10988C2 +:102050000180C4E90A2321460023238651F8283B46 +:102060002046DB6B984704F58052204692F8C83032 +:1020700043F0040382F8C830BDE8F840FFF736BFEC +:1020800006F1100791E7F8BD10B5044600F022FCF8 +:1020900002460B4652EA030102D0013A63F1000303 +:1020A0000449086820B12146BDE81040FFF776BF1B +:1020B00010BD00BF30350020F8B500F583511E4635 +:1020C000FFF7D0FCDFF844C00831002404F1840598 +:1020D00000EB45152B795F070ED4DB060CD5D1E953 +:1020E00000739742B34107D243695CF824709F6044 +:1020F0002B7943F004032B710134032C01F12001EF +:10210000E4D1BDE8F840FFF7B3BC00BF286A00087F +:1021100008B5FFF7A7FCFFF7E9FEBDE80840FFF7A9 +:10212000A7BC0000F8B543690546986800F0E05088 +:10213000B0F1E05F0F461FD0E8B1FFF793FC05F563 +:1021400083541034002606F1840305EB43131B79F6 +:102150001A0706D50136032E04F12004F3D101201D +:1021600007E05B07F6D42146384600F009FA00285C +:10217000F0D1FFF77DFCF8BD0120FCE700F58050B1 +:1021800008B5FFF76FFCC06D00F03CFAFFF770FC7C +:1021900043090CBF0120002008BD0000F8B51D4612 +:1021A000002313700F4606461446FFF7E7FF80F042 +:1021B0000100387025B129463046FFF7B3FF207083 +:1021C000F8BD00002DE9B8410C4615461F46804673 +:1021D00000F080FB0B462178024609B9287850B1FF +:1021E0004046FFF769FFFFF793FF3B462A4621462B +:1021F000FFF7D4FF0120BDE8B881000010B5FFF75C +:1022000031FC174B9A6D42F000729A659A6B42F05E +:1022100000729A639A6B00F5805422F000729A6300 +:10222000FFF726FC94F8C830DB0718D4B9B10221B7 +:102230001320FFF717FC01F07DFD0221142001F0AF +:1022400079FD0221152001F075FD94F8C83043F0A6 +:10225000010384F8C830BDE81040FFF709BC10BD89 +:10226000001002402DE9F04700F5805588B095F840 +:10227000C930012B0446884616467FD8804F57F850 +:1022800023200AB947F82300D7F800A0C4F80C802F +:102290002674BAF1000F63D095F8C930012B6FD0C6 +:1022A00001212046FFF7AAFFFFF7DCFB62691368F4 +:1022B00023F0020313606269136843F001031360A3 +:1022C000636900275F6101212046FFF7D1FBFFF71B +:1022D000F7FD002800F09580E86D00F081F904F525 +:1022E0008359BA4609F10809202200216846FFF700 +:1022F00001FB02A8FFF782FCCDF818A06A4609EBA3 +:1023000007030DF1180E9446BCE80300F44518606D +:102310005960624603F10803F5D1DCF8000018604B +:1023200020379CF804201A71602FDDD195F8C83051 +:102330006FF38203002785F8C8306A46414620467D +:10234000ADF80070ADF802708DF80470FFF75CFD19 +:10235000636948BB4FF400421A6008B0BDE8F087DB +:1023600041F2D00004F0BEF9814610B15146FFF7AA +:10237000E9FCC7F80090B9F1000F8DD10020ECE71F +:10238000386803681B6B98470146002888D1386875 +:10239000FFF734FF3868036832465B684146984768 +:1023A00000287FF47DAFE9E761221A609DF80230D2 +:1023B0009DF803201B06120402F4702203F0407300 +:1023C0001343BDF80020C2F3090213439DF8042013 +:1023D0001205022E02F4E0020CBF4FF00041002172 +:1023E000134362690B43D361636913225A616269C3 +:1023F000136823F00103136039462046FFF760FDA0 +:1024000008B96369A6E795F8C93093BB6169D1F84B +:10241000002242F00102C1F800226169D1F80022D5 +:1024200022F47C5222F00E02C1F800226169D1F838 +:10243000002242F46062C1F800226269C2F81432DC +:102440006269C2F80432626941F6FF71C2F80C1287 +:102450006269C2F840326269C2F84432636901229B +:10246000C3F81C226269D2F8003223F00103C2F8DB +:10247000003295F8C83043F0020385F8C8306CE7A5 +:102480003035002008B500F025FA50EA0103024675 +:1024900002D0421E61F10001044B186810B10B46D6 +:1024A000FFF744FDBDE8084001F00EBB30350020C9 +:1024B00008B50020FFF7E8FDBDE8084001F004BBC7 +:1024C00008B50120FFF7E0FDBDE8084001F0FCBAC7 +:1024D00013B56C4684E80600031D94E8030083E806 +:1024E0000500012002B010BD73B58568019155B19A +:1024F0001B885B0707D4D0E900369B6B9847019A8D +:10250000C1B23046A847012002B070BDF0B5866860 +:1025100089B005460C465EB1BDF838305B070AD479 +:10252000D0E900379B6B98472246C1B23846B04786 +:10253000012009B0F0BD00220023CDE900230023D3 +:10254000ADF808300A4603AB01F10806106851687F +:102550001C4603C40832B2422346F7D110682060FB +:102560009288A28000F0B8F90423ADF808302B68F7 +:10257000CDE90001DB6B694628469847D8E70000A3 +:1025800030B503680968DD0FB5EBD17F23F06044F7 +:1025900021F060424FEAD1700BD0002BB8BFA40CE1 +:1025A0000029B8BF920C944202D034BF0120002011 +:1025B00030BD944205D1C1F38070C3F38073834270 +:1025C000F6D194422CBF00200120F1E710B5037C26 +:1025D000044613B9006804F0BDF8204610BD0000A1 +:1025E0000023BFF35B8FC360BFF35B8FBFF35B8FD1 +:1025F0008360BFF35B8F7047BFF35B8F0068BFF3EF +:102600005B8F704770B505460C30FFF7F5FF05F19D +:10261000080604463046FFF7EFFFA04206D93046D1 +:102620006D68FFF7E9FF2544281A70BD3046FFF7B3 +:10263000E3FF201AF9E7000070B50546406898B13D +:1026400005F10800FFF7D8FF05F10C0604463046F7 +:10265000FFF7D2FF8442304694BF6D680025FFF734 +:10266000CBFF013C2C44201A70BD000038B50C464D +:102670000546FFF7C7FFA04210D305F10800FFF79A +:10268000BBFF04446868B4FBF0F100FB1144BFF3E6 +:102690005B8F0120AC60BFF35B8F38BD0020FCE78F +:1026A0002DE9F041144607460D46FFF7C5FF844269 +:1026B00028BF0446D4B1B84658F80C6B4046FFF723 +:1026C0009BFF3044286040467E68FFF795FF331A31 +:1026D0009C4203D86C600120BDE8F0816B60A41BB4 +:1026E0003B68AB602044E8600220F5E72046F3E752 +:1026F00038B50C460546FFF79FFFA04210D305F101 +:102700000C00FFF779FF04446868B4FBF0F100FBAC +:102710001144BFF35B8F0120EC60BFF35B8F38BDCA +:102720000020FCE72DE9FF41884669460746FFF790 +:10273000B7FF6C4606B204EBC6060025B44209D0CA +:102740006268206808EB0501FFF7AEF8636808349B +:102750001D44F3E729463846FFF7CAFF284604B070 +:10276000BDE8F081F8B505460C300F46FFF744FF91 +:1027700005F1080604463046FFF73EFFA04230460A +:1027800088BF6C68FFF738FF201A386020B13046E8 +:102790002C68FFF731FF2044F8BD000073B51446E4 +:1027A00006460D46FFF72EFF844228BF04460190DF +:1027B000DCB101A93046FFF7D5FF019B33B9326880 +:1027C000C5E90233C5E9002401200CE09C4238BF72 +:1027D00001942860019868608442F5D93368AB6041 +:1027E000241AEC60022002B070BD2046FBE7000016 +:1027F0002DE9FF410F466946FFF7D0FF6C4600B256 +:1028000004EBC0050026AC4209D0D4F8048054F88B +:10281000081BB8194246FFF747F84644F3E730462D +:1028200004B0BDE8F081000038B50546FFF7E0FFD1 +:10283000044601462846FFF719FF204638BD000030 +:1028400000B59BB0EFF3098168226846FFF72CF8CA +:10285000EFF30583044B9A6BDA6A9A6A9A6A9A6A6A +:102860009A6A9A6A9B6AFEE700ED00E000B59BB0A9 +:10287000EFF3098168226846FFF716F8EFF3058346 +:10288000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ADB +:10289000FEE700BF00ED00E000B59BB0EFF309815B +:1028A00068226846FFF700F8EFF30583034B5A6B85 +:1028B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E051 +:1028C000FEE700000FB408B5029802F013F9FEE726 +:1028D00002F01ABD02F0F2BC02F0F0BC2DE9F047A4 +:1028E0000D46044600219046284640F27912FFF733 +:1028F00001F8234620220021284600F03FFE231D38 +:1029000002222021284600F039FE631D03222221E5 +:10291000284600F033FEA31D03222521284600F09F +:102920002DFE04F1080310222821284600F026FE7F +:1029300004F1100308223821284600F01FFE04F19C +:10294000110308224021284600F018FE04F112036A +:1029500008224821284600F011FE04F11403202229 +:102960005021284600F00AFE04F11803402270218D +:10297000284600F003FE04F120030822B021284677 +:1029800000F0FCFD04F121030822B821284600F0E4 +:10299000F5FD04F12207C0263B46314608222846B1 +:1029A000083600F0EBFDB6F5A07F07F10107F3D183 +:1029B00004F1320308223146284600F0DFFD0027EB +:1029C00004F1330A94F832304FEAC7099F4209F5FF +:1029D000A47615D3B8F1000F08D1314604F59973E8 +:1029E0000722284600F0CAFD09F24F16274694F840 +:1029F00032213B1B93420CD3F01DC008BDE8F08789 +:102A00000AEB070308223146284600F0B7FD0137DC +:102A1000D8E707F2331331460822284600F0AEFD0E +:102A200008360137E3E7000013B5044608460021E5 +:102A300001602346C0F803102022019000F09EFDA3 +:102A40000198231D0222202100F098FD0198631DAA +:102A50000322222100F092FD0198A31D03222521CB +:102A600000F08CFD019804F108031022282100F0E9 +:102A700085FD072002B010BDF8B50E460546144688 +:102A8000002181223046FEF735FF2B460822002127 +:102A9000304600F073FD7CB96B1C072208213046DC +:102AA00000F06CFD0F2401236A785F1C013B934208 +:102AB00004D3E01DC008F8BD0824F4E7EB19214653 +:102AC0000822304600F05AFD08343B46ECE700008F +:102AD00030B5094D0A4491420DD011F8013B5840E0 +:102AE000082340F30004013B2C4013F0FF0384EA69 +:102AF0005000F6D1EFE730BD2083B8ED73B5384A0A +:102B0000106851686B4603C36A4636493648082345 +:102B100003F038FE044670B9344A106851686B46B9 +:102B200003C36A4632493048082303F02BFE0446AB +:102B300030BB0A2022E00369B3F5583FECD8418B43 +:102B400040F217429142E7D12A4A024402F11001B1 +:102B50008B42E1D3103B244900209D1AFFF7B8FFB8 +:102B60002A46064604F118010020FFF7B1FFA368CA +:102B70009E42D1D1E3689842CED1002002B070BD10 +:102B80000369B3F5583F22D8B0F8661040F21742F7 +:102B900091421ED1174A024402F15C018B421AD3C2 +:102BA0005C3B114900209D1AFFF792FF2A4606461A +:102BB00004F164010020FFF78BFFA26896420346F0 +:102BC0000BD1E068834214BF0D200020D6E70B2014 +:102BD000D4E70C20D2E71020D0E70D20CEE700BFCD +:102BE0007C6A0008DC5F030000A00008856A00081A +:102BF000905F03000860FFF72DE9F041C56915B942 +:102C0000C161BDE8F0814B6823F06047C3F38A4699 +:102C10004FEAD37EC3F3807816EA230638BF3E46D8 +:102C2000AC462B465A68BEEBD27F22F060440AD0F5 +:102C3000002A18DAA40CB44217D19D420FD10D60BE +:102C4000DEE71346EEE7A74207D102F08044C2F365 +:102C5000807242450BD054B1EFE708D2EDE7CCF8D3 +:102C600000100B60CDE7B44201D0B442E5D81A6839 +:102C70009C46002AE5D11960C3E700002DE9F04722 +:102C8000089D01F007044FEAD508224405F0070526 +:102C900000EBD1004FF47F49944201D1BDE8F087A9 +:102CA00004F0070705F0070A57453E4638BF564669 +:102CB000C6F10806111B8E4228BF0E46E10808EB3C +:102CC000D50E415C13F80EC0B94029FA06F721FA77 +:102CD0000AF1FFB28CEA010147FA0AF739408CEA9F +:102CE000010C03F80EC034443544D5E780EA0120D6 +:102CF000082341F2210201B24000002980B203F111 +:102D0000FF33B8BF504013F0FF03F4D17047000009 +:102D100038B50C468D18A54200D138BD14F8011BFA +:102D2000FFF7E4FFF7E7000002684AB113680360A9 +:102D3000C388018901339BB29942C38038BF0381A4 +:102D40001046704770B588B0202204460D4668468C +:102D50000021FEF7CFFD20460495FFF7E5FF024670 +:102D600058B16B46054608AE1C4603CCB4422860F9 +:102D70006960234605F10805F6D1104608B070BD1C +:102D8000082817D909280CD00A280CD00B280CD0F9 +:102D90000C280CD00D280CD00E2814BF4020302059 +:102DA00070470C207047102070471420704718207F +:102DB0007047202070470000082817D90C280CD92C +:102DC00010280CD914280CD918280CD920280CD973 +:102DD00030288CBF0F200E207047092070470A2032 +:102DE00070470B2070470C2070470D207047000083 +:102DF00010B54B6823B9CA8A63F30902CA8210BDB1 +:102E0000C4681A681C60C360438A013B43824A60FD +:102E1000EFE700002DE9F84F1D46CB8A0F46C3F3BC +:102E200009010529814692460B4630D00020AAB2FE +:102E300007F11A049EB2042E1FFA80F80FD89045AD +:102E400003F1010306D3FB8A0A4462F30903FB8200 +:102E500001201AE01AF80060E6540130EAE79045D4 +:102E6000F1D2A1F1050B1C237C68BBFBF3F203FB41 +:102E700012BB1FFA8BF6002C45D14846FFF754FFD2 +:102E8000044638B978606FF00200BDE8F88F4FF063 +:102E90000008E6E7002606607860ADB24FF0000B50 +:102EA000454510D90AEB0803221D13F8011B915563 +:102EB000B1B208F101081B291FFA88F82BD045454B +:102EC00006F10106F1D8FB8AC3F30902154465F344 +:102ED0000903BCE7013292B21C462368002BF9D1EA +:102EE0006B1F0B441C21B3FBF1F301339BB29A42DD +:102EF000D3D2BBF1000FD0D14846FFF715FF20B960 +:102F0000C4F800B0BFE70122E7E7C0F800B05E46B2 +:102F100020600446C1E74545D5D94846FFF704FF80 +:102F200008B92060AFE7C0F800B000262060044672 +:102F3000B6E700002DE9F04F2DED028B83B0CDE90F +:102F40000013BDF83C5007469146002A00F09280DD +:102F50002DB10E9B002B00F08D80072D32D807F18C +:102F60000C00FFF7E1FE044638B96FF0020420467A +:102F700003B0BDEC028BBDE8F08F14220021FEF7F8 +:102F8000B9FC0E992A4604F10800FEF78DFC681C76 +:102F9000C0B2FFF711FFFFF7F3FE207499F800307D +:102FA000013814FA80F003F01F0363F03F0303724B +:102FB000009B43F00041616038462146FFF71CFE4C +:102FC0000124D4E700F10C034FF0000808EE103A9A +:102FD0004FF0800A4646444618EE100AFFF7A4FE5A +:102FE00083460028C1D014220021FEF783FCC6BB13 +:102FF000019BABF8083002200E9B00F108029919E2 +:103000005BFA82F20130C0B2082801D0AE422AD366 +:10301000FFF7D2FEFFF7B4FE99F80020009B411E97 +:1030200002F01F0242EA4812AE4208BF4FF0400AC7 +:103030005BFA81F14AEA020A43F0004281F808A0F3 +:103040008BF81000CBF8042059463846FFF7D4FD22 +:103050000134AE4224B288F001084FF0000ABBD11F +:1030600085E70020C8E711F801CB02F801CB013653 +:10307000B6B2C7E76FF0010479E70000F8B515466E +:103080000E462822002104461F46FEF733FC069B0D +:103090006360B5F5001F079BA76034BF6A094FF650 +:1030A000FF72236204F10C0097B200239A4205D804 +:1030B0000023036027826382A382F8BD0660013388 +:1030C00030462036F2E7000003781BB94BB2002BE4 +:1030D000C8BF017070470000007870472DE9F74FB6 +:1030E000DDF83C90BDF830500D9E9DF83840BDF89D +:1030F0004070804692469B46B9F1000F01D1002FE7 +:1031000051D11F2C4FD898F80000B0B9072F47D8DD +:1031100035F0030347D13A4649464FF6FF70FFF7B3 +:10312000F7FD20F001002D02400445EA0464400C44 +:1031300044EA40244FF6FF7321E040EA0520072FC0 +:1031400040EA0464F6D900254FF6FF73C5F120006C +:10315000A5F120022AFA05F10BFA00F001432BFA3F +:1031600002F211431846C9B2FFF7C0FD0835402DE1 +:103170000346EBD13A464946FFF7CAFD0346CDE97F +:103180000097324621464046FFF7D4FE337801339C +:10319000DBB21F2B88BF0023337003B0BDE8F08F74 +:1031A0006FF00300F9E76FF00100F6E72DE9F04F4B +:1031B00085B09246DDF848800F9D9DF840209DF82F +:1031C0004490BDF84C7006469B46B8F1000F01D103 +:1031D000002F48D11F2A46D83378002B46D00C0246 +:1031E00044EA02649DF8381044EAC93444EA0144D0 +:1031F0001C43072F44F0800432D900234FF6FF729E +:10320000C3F1200CA3F120002AFA03F10BFA0CFC05 +:1032100041EA0C012BFA00F00143C9B210460393B6 +:10322000FFF764FD039B0833402B0246E8D13A4682 +:103230004146FFF76DFD0346CDE900872A4621464A +:103240003046FFF777FEB9F1010F06D12B78013335 +:10325000DBB21F2B88BF00232B7005B0BDE8F08FB9 +:103260004FF6FF73E8E76FF00100F6E76FF0030039 +:10327000F3E70000C06900B104307047C3691A6801 +:10328000C261C2681A60C360438A013B43827047CF +:103290002DE9F041D0F81880194E14461D464146DC +:1032A000002709B9BDE8F081D1E90223A21A65EB34 +:1032B0000303964277EB03031ED283698B420DD141 +:1032C000FFF796FD83691B688361C3680B60438ABF +:1032D000C1608169013B43828846E2E7FFF788FDD0 +:1032E0000B68C8F80030C3680B60438AC160013BBB +:1032F0004382D8F80010D4E788460968D1E700BFB8 +:1033000080841E002DE9F04F8BB00D46DDF8509003 +:1033100014469B468046002800F01981B9F1000F41 +:1033200000F01581531E3F2B00F21181012A03D1B9 +:10333000BBF1000F40F00B810023CDE90833B8F852 +:103340001430B5EBC30F4FEAC30703D300200BB013 +:10335000BDE8F08F2B199F42D8F80C303ABF7F1B85 +:10336000FFB227461BB9D8F81030002B7AD0272D92 +:103370004ED8C5F12806B7424FF000032CBFF6B275 +:103380003E4600932946D8F8080008AB3246FFF7BE +:1033900075FCA7EB060A35445FFA8AFAB8F81430D0 +:1033A00003F10053053BDB000493D8F80C30039382 +:1033B0002821039B13B1BAF1000F2CD1D8F81000CB +:1033C00040B1BAF1000F05D0009608AB5246691A19 +:1033D000FFF754FC38B2002FB8D066070AD00AAB0A +:1033E00003EBD401624211F8083C02F007021341DA +:1033F00001F8083C082C3CD9102C40F2B580202C58 +:1034000040F2B780BBF1000F00F09C80082334E04D +:10341000BA460026C2E7049BE02B28BFE0230693B0 +:103420000B44AB42059314D95A1B0398009692455E +:1034300034BF5246D2B2691A08AB04300792FFF784 +:103440001DFC079A1644AAEB020A1544F6B25FFA6D +:103450008AFA049B069A05999B1A0493039B1B689E +:103460000393A6E70093D8F8080008AB3A4629462C +:10347000AEE7BBF1000F13D00123B4EBC30F6CD048 +:10348000082C12D89DF82030621E23FA02F2D507CC +:1034900006D54FF0FF3202FA04F423438DF82030B2 +:1034A0009DF8203089F8003051E7102C12D8BDF873 +:1034B0002030621E23FA02F2D10706D54FF0FF3208 +:1034C00002FA04F42343ADF82030BDF82030A9F807 +:1034D00000303CE7202C0FD80899631E21FA03F333 +:1034E000DA0705D54FF0FF3202FA04F40C430894D2 +:1034F000089BC9F800302AE7402C2BD0DDE908658D +:10350000611EC4F12102A4F1210326FA01F105FA9A +:1035100002F225FA03F311431943CB0712D5012216 +:10352000A4F12003C4F1200102FA03F322FA01F10D +:10353000A240524243EA010363EB430332432B436D +:10354000CDE90823DDE90823C9E90023FFE66FF090 +:103550000100FCE66FF00800F9E6082CA0D9102C59 +:10356000B3D9202CEED8C3E7BBF1000FADD00223B6 +:1035700083E7BBF1000FBBD004237EE730B5012AFF +:10358000144638BF0124402C85B028BF40240025B4 +:10359000012ACDE9025518D81B788DF80830630749 +:1035A0000AD004AB03EBD405624215F8083C02F0E4 +:1035B0000702934005F8083C00910346224600218B +:1035C00002A8FFF75BFB05B030BD082AE4D9102A3A +:1035D00003D81B88ADF80830E1E7202A8DBFD3E976 +:1035E00000231B680293CDE90223D8E710B5CB680E +:1035F0001BB98B600B618B8210BDC4681A681C609C +:10360000C360438A013B4382CA60F0E72DE9F04F73 +:1036100095B0CDE904230B6804460D461806C3F3A4 +:10362000C01147BFC3F3C03BC3F306264FF0020BE4 +:103630000E46002B80F2018213F0C04940F0FD815C +:103640002A7B002A00F0F981BBF1020F03D0207819 +:10365000B04240F0F581C3F30460089003F07F00AE +:10366000069059B3C3F3074A2A44069B92F8038095 +:10367000760646EA0B4646EA834600220023CDE959 +:103680000A235FEAD81346EA0A0603936AD0069B28 +:10369000009367685B4652460AA92046B84700284F +:1036A00000F0D181A76987B9314604F10C00FFF71A +:1036B00049FB0746C8B96FF0020057E0C3F30F2A71 +:1036C000590608BF0AF0030ACEE73B699E420DD0B7 +:1036D0003F68002FF9D1314604F10C00FFF732FBAF +:1036E00007460028E7D0A3693B60A761FE7D08F08C +:1036F0001F03C6F38406F01A1FFA80FC0028B8BF27 +:103700000CF120000793A3EB06031FFA83FCD7E913 +:103710000221B8BF00B2002B0993BEBF0CF12003F9 +:103720001BB2099352EA010335D0049EDFF8D4C2DC +:10373000B21A059E66EB01010026944576EB010363 +:1037400029D395F80DE097F81AC0E64516D1039BEA +:10375000002B78D001281EDCA948904276EB0103AB +:1037600016D338E0A76927B96FF00C0015B0BDE893 +:10377000F08F3B699E42B9D03F68F4E7A048904281 +:1037800076EB010301D30020F0E7039B002BFAD076 +:10379000099B0F2B18DCFA7D4FEA880302F0030225 +:1037A00003F07C031343FB7539462046FFF720FBEB +:1037B0006B7BBB76039B3BB9FB7DC3F38402013279 +:1037C00062F38603FB75CFE76A7BBB7E9A42DAD150 +:1037D000039B002B37D04FEA9813022B33D0049B66 +:1037E000BB60059BFB60142200210FA8FEF782F846 +:1037F000049B0C93059B0D932B1D0E932B7BADF817 +:1038000046A0013BDBB2ADF84430079B8DF8493050 +:10381000089B8DF84A30069B8DF84B3094F8243085 +:103820008DF848B083F001038DF84C300CA9A368E3 +:1038300020469847FB7DC3F38403013303F01F0345 +:103840009B02FB829FE7FB7DC8F34012B2EBD31FC4 +:1038500040F0FC80079AC3F38403934240F0F98060 +:1038600003992B7B4FEA981200294DD0D2075DD4E3 +:10387000032B40F2F180049BBB60059BFB602B7B1C +:10388000AE1D033BDBB23246394604F10C00FFF7B4 +:10389000C1FA00280CDA39462046FFF7A9FAFB7D69 +:1038A000C3F38403013303F01F039B02FB8202E78F +:1038B000DDE90A84AB883B834FF6FF73C9F1200032 +:1038C000A9F1200228FA09F104FA00F0014324FAD0 +:1038D00002F211431846C9B2FFF708FA09F10809C4 +:1038E000B9F1400F0346E9D1B8822A7B033AD2B23C +:1038F0003146FFF70DFAFB7DB882DA43C2F3C012FE +:1039000062F3C713FB753EE782B92E1D013BDBB2A4 +:103910003246394604F10C00FFF77CFA0028BADB86 +:103920002A7BB88A013AD2B23146E2E7F98AC1F37A +:103930000901013B0429DAB25CD8281D002307F1F4 +:103940001B069A4208D910F801CB06F801C00131D4 +:1039500001330529DBB2F4D104990C9105990D913D +:10396000934207F11B010E9138BF043379680F9120 +:1039700034BF55FA83F300231093FB8AADF846A0B9 +:10398000C3F309031A44079B8DF84930089B8DF84F +:103990004A30069B8DF84B3094F82430ADF8442023 +:1039A00083F001038DF84C3000238DF848B07B6024 +:1039B0002A7BB88A013A291DFFF7AAF93B8BB88206 +:1039C000834203D1A3680CA92046984720460CA93E +:1039D000FFF70CFEFB7DBA8AC3F38403013303F0C7 +:1039E0001F039B02FB823B8B9A420CBF00206FF0AF +:1039F0001000BBE67B68002BAED0052006E000BFC0 +:103A000040420F0080841E001C3033461E68002E8A +:103A1000FAD1091A081D2E1D184401EB090CBCF13E +:103A20001B0F5FFA89F397D89A4295D916F8013B94 +:103A300000F8013B09F10109EFE76FF0090095E695 +:103A40006FF00A0092E66FF00B008FE66FF00D004A +:103A50008CE66FF00E0089E66FF00F0086E600BF7F +:103A6000EFF3098305494A6B22F001024A63683388 +:103A700083F30988002383F31188704700EF00E087 +:103A8000202080F3118862B60C4B0D4AD96821F4CE +:103A9000E0610904090C0A43DA60D3F8FC20094903 +:103AA00042F08072C3F8FC200A6842F001020A600A +:103AB0001022DA7783F82200704700BF00ED00E0A3 +:103AC0000003FA05001000E010B5202383F31188ED +:103AD0000E4B5B6813F4006314D0F1EE103AEFF371 +:103AE0000984683C4FF08073E361094BDB6B23660C +:103AF00084F3098800F0B0FF10B1064BA36110BD3C +:103B0000054BFBE783F31188F9E700BF00ED00E008 +:103B100000EF00E02B0600082E060008026843684C +:103B20001143016003B1184770470000024A13684F +:103B300043F0C003136070470038014013B50D4CCB +:103B4000204600F09DFA04F114000B490094002374 +:103B5000202200F05FF9094B09490094202204F16A +:103B6000380000F0D9F9074A074BC4E9172302B01F +:103B700010BD00BF3C350020A83500202D3B0008BB +:103B8000C83500200038014000B4C40430B5037CBF +:103B9000234C002918BF0C46012B0FD1214B984212 +:103BA0000CD1214B1A6E42F480421A66D3F8802061 +:103BB00042F48042C3F88020D3F880302268036E3C +:103BC000C16D846603EB5203B3FBF2F36268150424 +:103BD00042BF23F0070503F0070343EA4503CB6028 +:103BE000A36843F040034B60E36843F001038B603C +:103BF00042F4967343F001030B604FF0FF330B6206 +:103C0000510505D512F0102205D0B2F1805F04D025 +:103C100080F8643030BD7F23FAE73F23F8E700BF28 +:103C2000906A00083C350020001002402DE9F04762 +:103C3000C66D3768F46934622107054618D014F060 +:103C4000080118BF8021E20748BF41F02001A30707 +:103C500048BF41F04001600748BF41F48071202314 +:103C600083F31188281DFFF759FF002383F3118880 +:103C7000E2050AD5202383F311884FF40071281D33 +:103C8000FFF74CFF002383F311884FF020094FF01A +:103C9000000A14F0200838D13B0616D54FF0200951 +:103CA00005F1380A200610D589F31188504600F036 +:103CB00067F9002836DA0821281DFFF72FFF27F0C3 +:103CC00080033360002383F31188790614D56206DC +:103CD00012D5202383F31188D5E913239A4208D102 +:103CE0002B6C33B11021281D27F04007FFF716FF7A +:103CF0003760002383F31188E30619D5AA6E136990 +:103D0000B3B1BDE8F0475069184789F31188B38C07 +:103D100095F864102846194000F0CCF98AF3118810 +:103D2000F469B6E780B2308588F31188F469B9E7A1 +:103D3000BDE8F08700F1604303F561430901C9B2B2 +:103D400083F80013012200F01F039A4043099B00EF +:103D500003F1604303F56143C3F880211A607047A3 +:103D6000F8B5154682680669AA420B46816938BFD4 +:103D70008568761AB54204460BD218462A46FDF7E6 +:103D800093FDA3692B44A361A3685B1BA360284632 +:103D9000F8BD0CD918463246FDF786FDAF1BE16829 +:103DA0003A463044FDF780FDE3683B44EBE71846B4 +:103DB0002A46FDF779FDE368E5E700008368934252 +:103DC000F7B51546044638BF8568D0E90460361A51 +:103DD000B5420BD22A46FDF767FD63692B44636148 +:103DE000A36828465B1BA36003B0F0BD0DD9324623 +:103DF0000191FDF759FD0199E068AF1B3A46314446 +:103E0000FDF752FDE3683B44E9E72A46FDF74CFD28 +:103E1000E368E4E710B50A440024C361029B8460B0 +:103E2000C0E90000C0E90511C1600261036210BD74 +:103E300008B5D0E90532934201D1826882B982681F +:103E4000013282605A1C42611970D0E904329A42F0 +:103E500024BFC3684361002100F0D8FE002008BDE4 +:103E60004FF0FF30FBE7000070B5202304460E46FC +:103E700083F31188A568A5B1A368A269013BA3607B +:103E8000531CA36115782269934224BFE368A361A0 +:103E9000E3690BB120469847002383F31188284635 +:103EA00007E03146204600F0A1FE0028E2DA85F363 +:103EB000118870BD2DE9F74F04460E461746984607 +:103EC000D0F81C904FF0200A8AF311884FF0000BB5 +:103ED000154665B12A4631462046FFF741FF0346A5 +:103EE00060B94146204600F081FE0028F1D0002351 +:103EF00083F31188781B03B0BDE8F08FB9F1000F90 +:103F000003D001902046C847019B8BF31188ED1A1E +:103F10001E448AF31188DCE7C0E90511C160C36162 +:103F20001144009B8260C0E9000001610362704798 +:103F3000F8B504460D461646202383F31188A7687A +:103F4000A7B1A368013BA36063695A1C62611D703D +:103F5000D4E904329A4224BFE3686361E3690BB198 +:103F600020469847002080F3118807E0314620461C +:103F700000F03CFE0028E2DA87F31188F8BD00006B +:103F8000D0E905239A4210B501D182687AB98268D6 +:103F9000013282605A1C82611C7803699A4224BFF4 +:103FA000C3688361002100F031FE204610BD4FF050 +:103FB000FF30FBE72DE9F74F04460E4617469846BB +:103FC000D0F81C904FF0200A8AF311884FF0000BB4 +:103FD000154665B12A4631462046FFF7EFFE0346F7 +:103FE00060B94146204600F001FE0028F1D00023D0 +:103FF00083F31188781B03B0BDE8F08FB9F1000F8F +:1040000003D001902046C847019B8BF31188ED1A1D +:104010001E448AF31188DCE702684368114301609B +:1040200003B11847704700001430FFF743BF00008A +:104030004FF0FF331430FFF73DBF00003830FFF77B +:10404000B9BF00004FF0FF333830FFF7B3BF0000B7 +:104050001430FFF709BF00004FF0FF311430FFF7B5 +:1040600003BF00003830FFF763BF00004FF0FF329E +:104070003830FFF75DBF000000207047FFF75EBDDE +:10408000044B03600023C0E902334360012303743F +:10409000704700BFA86A000810B52023044683F3C8 +:1040A0001188FFF773FD02232374002383F3118823 +:1040B00010BD000038B5C36904460D461BB9042184 +:1040C0000844FFF7A9FF294604F11400FFF7B0FEEA +:1040D000002806DA201D4FF48061BDE83840FFF764 +:1040E0009BBF38BD026843681143016003B11847A4 +:1040F0007047000013B5446BD4F894341A681178F3 +:10410000042915D1217C022912D1197912890123A0 +:104110008B4013420CD101A904F14C0001F04EFF79 +:10412000D4F89444019B21790246206800F0D4F928 +:1041300002B010BD143001F0D1BE00004FF0FF33CB +:10414000143001F0CBBE00004C3001F0A3BF0000E2 +:104150004FF0FF334C3001F09DBF0000143001F0F0 +:104160009FBE00004FF0FF31143001F099BE0000F7 +:104170004C3001F06FBF00004FF0FF324C3001F0C7 +:1041800069BF00000020704710B5D0F894341A6859 +:1041900011780429044617D1017C022914D15979D8 +:1041A000528901238B4013420ED1143001F032FEAC +:1041B000024648B1D4F894444FF480736179206882 +:1041C000BDE8104000F076B910BD0000406BFFF76D +:1041D000DBBF0000704700007FB5124B0360002377 +:1041E0004360C0E90233012502260F4B05740446E3 +:1041F0000290019300F18402294600964FF48073E7 +:10420000143001F0E3FD094B0294CDE9006304F59D +:1042100023724FF48073294604F14C0001F0AAFE8A +:1042200004B070BDD06A0008CD410008F540000818 +:104230000B68202282F311880A7903EB8202106254 +:104240004A790D3243F822008A7912B103EB8203D6 +:10425000186202230374C0F89414002383F31188B6 +:104260007047000038B5037F044613B190F854300E +:10427000ABB9201D01250221FFF734FF04F1140022 +:1042800025776FF0010100F0CDFC84F8545004F163 +:104290004C006FF00101BDE8384000F0C3BC38BDF0 +:1042A00010B5012104460430FFF71CFF00232377DB +:1042B00084F8543010BD000038B504460025143091 +:1042C00001F09CFD04F14C00257701F06BFE201DF0 +:1042D00084F854500121FFF705FF2046BDE838401F +:1042E000FFF752BF90F85C3003F06003202B07D13A +:1042F00090F85D20212A4FF0000303D81F2A06D82A +:1043000000207047222AFBD1C0E9143303E0034A9E +:104310000265072242658365012070473011002045 +:1043200037B5D0F894341A681178042904461AD1A4 +:10433000017C022917D11979128901238B4013427C +:1043400011D100F14C05284601F0ECFE58B101A94D +:10435000284601F033FED4F89444019B21790246AB +:10436000206800F0B9F803B030BD0000F0B500EBF4 +:10437000810385B01E6A04460D46FEB1202383F3F7 +:10438000118804EB8507301D0821FFF7ABFEFB68A1 +:104390005B691B6806F14C001BB1019001F01CFE2B +:1043A000019803A901F00AFE024648B1039B294681 +:1043B000204600F091F8002383F3118805B0F0BD8A +:1043C000FB685A691268002AF5D01B8A013B13402A +:1043D000F1D104F15C02EAE70D3138B550F8214023 +:1043E000DCB1202383F31188D4F894241368527924 +:1043F00003EB8203DB689B695D6845B104216018AB +:10440000FFF770FE294604F1140001F00DFD20466F +:10441000FFF7BAFE002383F3118838BD7047000010 +:1044200001F0BAB810B501230446282200F8243B55 +:104430000021FDF75FFA0023C4E9013310BD00003D +:1044400038B50446202383F311880025C0E90355BD +:10445000C0E90555C0E90755416001F0ADF80223F8 +:10446000237085F3118838BD70B500EB81030546D4 +:104470005069DA600E46144618B110220021FDF78B +:1044800039FAA06918B110220021FDF733FA31463C +:104490002846BDE8704001F059B90000826802F07A +:1044A000011282600022C0E90422C0E906220262F1 +:1044B00001F0D8B9F0B400EB81044789E468012524 +:1044C000A4698D403D43458123600023A260636061 +:1044D000F0BC01F0F3B90000F0B400EB81040789EF +:1044E000E468012564698D403D4305812360002314 +:1044F000A2606360F0BC01F06DBA000070B50223E9 +:10450000002504460370C0E90255C0E90455C0E91E +:1045100006554566056280F84C5001F0B3F86368B3 +:104520001B6823B129462046BDE87040184770BD7E +:10453000037880F868300523037043681B6810B562 +:1045400004460BB1042198470023A36010BD00006E +:1045500090F86820436802701B680BB1052118476A +:104560007047000070B590F84C30044613B100233A +:1045700080F84C3004F15C02204601F095F9636844 +:104580009B68B3B994F85C3013F0600535D0002116 +:10459000204601F0FDFB0021204601F0EFFB63689F +:1045A0001B6813B1062120469847062384F84C3037 +:1045B00070BD204698470028E4D0B4F86230626DA0 +:1045C0009A4288BF636594F95C30656D002B4FF0AB +:1045D000200380F20381002D00F0F280092284F88C +:1045E0004C2083F311880021D4E914232046FFF7DF +:1045F00073FF002383F31188DAE794F85D2003F05A +:104600007F0343EA022340F20232934200F0C58066 +:1046100021D8B3F5807F48D00DD8012B3FD0022B95 +:1046200000F09380002BB2D104F1640222650222D3 +:104630006265A365C1E7B3F5817F00F09B80B3F5A8 +:10464000407FA4D194F85E30012BA0D1B4F864303F +:1046500043F0020332E0B3F5006F4DD017D8B3F545 +:10466000A06F31D0A3F5C063012B90D8636894F894 +:104670005E205E6894F85F10B4F860302046B04762 +:10468000002884D043682365036863651AE0B3F5A6 +:10469000106F36D040F6024293427FF478AF5C4B05 +:1046A0002365022363650023C3E794F85E30012B82 +:1046B0007FF46DAFB4F8643023F00203C4E91455FD +:1046C000A4F86430A56578E7B4F85C30B3F5A06F62 +:1046D0000ED194F85E3084F86630204601F02AF856 +:1046E00063681B6813B10121204698470323237098 +:1046F0000023C4E914339CE704F167032365012315 +:10470000C3E72378042B10D1202383F3118820469C +:10471000FFF7C4FE85F311880321636884F86750AE +:1047200021701B680BB12046984794F85E30002B2F +:10473000DED084F867300423237063681B68002B85 +:10474000D6D0022120469847D2E794F860301D0663 +:1047500003F00F0120460AD501F098F8012804D093 +:1047600002287FF414AF2B4B9AE72B4B98E701F00C +:104770007FF8F3E794F85E30002B7FF408AF94F8ED +:10478000603013F00F01B3D01A06204602D501F0B5 +:1047900013FBADE701F006FBAAE794F85E30002BAF +:1047A0007FF4F5AE94F8603013F00F01A0D01B0633 +:1047B000204602D501F0ECFA9AE701F0DFFA97E71C +:1047C000142284F84C2083F311882B462A4629466C +:1047D0002046FFF76FFE85F31188E9E65DB11522EB +:1047E00084F84C2083F311880021D4E91423204657 +:1047F000FFF760FEFDE60B2284F84C2083F311885E +:104800002B462A4629462046FFF766FEE3E700BF0F +:10481000006B0008F86A0008FC6A000838B590F8D8 +:104820004C300446002B3ED0063BDAB20F2A34D877 +:104830000F2B32D8DFE803F0373131082232313123 +:104840003131313131313737456DB0F862309D4209 +:1048500014D2C3681B8AB5FBF3F203FB12556DB982 +:10486000202383F311882B462A462946FFF734FE7E +:1048700085F311880A2384F84C300EE0142384F861 +:104880004C30202383F3118800231A461946204612 +:10489000FFF710FE002383F3118838BD836D03B149 +:1048A00098470023E7E70021204601F071FA002134 +:1048B000204601F063FA63681B6813B106212046A5 +:1048C00098470623D7E7000010B590F84C30142B1A +:1048D000044629D017D8062B05D001D81BB110BD2E +:1048E000093B022BFBD80021204601F051FA0021A0 +:1048F000204601F043FA63681B6813B10621204685 +:104900009847062319E0152BE9D10B2380F84C308A +:10491000202383F3118800231A461946FFF7DCFD94 +:10492000002383F31188DAE7C3689B695B68002B77 +:10493000D5D1836D03B19847002384F84C30CEE77E +:10494000024B0022C3E900339A607047E83500202B +:10495000002303748268054B1B6899689142FBD25F +:104960005A6803604260106058607047E835002064 +:1049700008B5202383F31188037C032B05D0042B77 +:104980000DD02BB983F3118808BD436900221A604A +:104990004FF0FF334361FFF7DBFF0023F2E7D0E97D +:1049A000003213605A60F3E7002303748268054BFA +:1049B0001B6899689142FBD85A6803604260106096 +:1049C00058607047E8350020054B1969087418686D +:1049D00002681A605360186101230374FBF710BE6C +:1049E000E835002030B54B1C0B4D87B0044610D085 +:1049F0002B690A4A01A800F031F92046FFF7E4FFCD +:104A0000049B13B101A800F065F92B69586907B040 +:104A100030BDFFF7D9FFF8E7E835002071490008FD +:104A200038B50C4D41612B6981689A689142044602 +:104A300003D8BDE83840FFF78BBF1846FFF7B4FF37 +:104A400001232C61014623742046BDE83840FBF762 +:104A5000D7BD00BFE8350020044B1A681B69906879 +:104A60009B68984294BF002001207047E8350020E1 +:104A700010B5084C236820691A682260546001222E +:104A800023611A74FFF790FF01462069BDE81040CA +:104A9000FBF7B6BDE835002008B5FFF7DDFF18B11C +:104AA000BDE80840FFF7E4BF08BD0000FFF7E0BF26 +:104AB000FEE7000010B50C4CFFF742FF00F0C0F815 +:104AC0000A498022204600F047F8012344F8180CD8 +:104AD0000374FEF7D5FF002383F3118862B6044800 +:104AE000BDE8104000F058B810360020046B0008F4 +:104AF000146B000808B572B6034B586200F0D8FB7F +:104B000000F084FCFEE700BFE835002000F01CB98F +:104B1000EFF3118020B9EFF30583202282F311888F +:104B20007047000010B530B9EFF30584C4F30804F2 +:104B300014B180F3118810BDFFF7AEFF84F3118824 +:104B4000F9E70000034A516853685B1A9842FBD8A2 +:104B5000704700BF001000E08260022202827047AE +:104B60008368A3F17C0243F80C2C026943F83C2CC7 +:104B7000426943F8382C074A43F81C2CC26843F8B2 +:104B8000102C022203F8082C002203F8072CA3F1B2 +:104B9000180070471906000810B5202383F3118808 +:104BA000FFF7DEFF00210446FFF73AFF002383F3FF +:104BB0001188204610BD0000024B1B6958610F2070 +:104BC000FFF702BFE8350020202383F31188FFF7A9 +:104BD000F3BF000008B50146202383F311880820A5 +:104BE000FFF700FF002383F3118808BD49B1064B8E +:104BF00042681B6918605A60136043600420FFF725 +:104C0000F1BE4FF0FF307047E8350020036898424E +:104C100006D01A680260506059611846FFF798BEC6 +:104C20007047000038B504460D462068844200D124 +:104C300038BD036823605C604561FFF789FEF4E7D7 +:104C4000054B03F11402C3E905224FF0FF310022A6 +:104C5000C3E90712704700BFE835002070B51C4E4D +:104C6000C0E9032305460C4601F08EFA334653F89B +:104C7000142F9A420DD13062C5E901242A600A2C12 +:104C80002CBF00190A30C6E90555BDE8704001F097 +:104C900069BA316A431AE31838BF1C469368A342C5 +:104CA00002D9081901F06CFA73699A6894420CD819 +:104CB0005A68AC602B606A6015609A685D60121B70 +:104CC0009A604FF0FF33F36170BD1B68A41AECE7E4 +:104CD000E835002038B51B4C636998420DD0D0E907 +:104CE000003213605A6000228168C2609A680A44E8 +:104CF0009A604FF0FF33E36138BD2246036842F803 +:104D0000143F002193425A60C16003D1BDE838408E +:104D100001F030BA9A688168256A0A449A6001F005 +:104D200033FA63699A68411B8A42E5D9AB181D1AA8 +:104D3000092D206A98BF01F10A02BDE838401044ED +:104D400001F01EBAE83500202DE9F041184C00278B +:104D500004F11406656901F017FA236AAA68C11AFA +:104D60008A4215D813442362D5E9003213605A6091 +:104D70006369D5F80C80EF60B34201D101F0FAF914 +:104D800087F311882869C047202383F31188E1E75E +:104D90006169B14209D013441B1ABDE8F0410A2BE6 +:104DA0002CBFC0180A3001F0EBB9BDE8F08100BF9C +:104DB000E83500200C2303604FF0FF3070470000FF +:104DC00000207047FEE70000704700004FF0FF3002 +:104DD0007047000002290CD0032904D0012907489C +:104DE00018BF00207047032A05D8054800EBC20011 +:104DF0007047044870470020704700BFF86B0008F8 +:104E000040110020AC6B000870B59AB0054608460A +:104E100001A9144600F0C2F801A8FCF763FD431C89 +:104E20005B00C5E900340022237003236370C6B21F +:104E300001AB02341046D1B28E4204F1020401D813 +:104E40001AB070BD13F8011B04F8021C04F8010C21 +:104E50000132F0E708B5202383F311880348FFF7F8 +:104E60005FFA002383F3118808BD00BF603700207C +:104E700090F85C3003F01F02012A07D190F85D2002 +:104E80000B2A03D10023C0E9143315E003F06003BB +:104E9000202B08D1B0F860302BB990F85D20212A82 +:104EA00003D81F2A04D8FFF71DBA222AEBD0FAE74D +:104EB000034A02650722426583650120704700BFEF +:104EC0003711002007B5052917D8DFE801F01916BA +:104ED00003191920202383F31188104A019001211E +:104EE000FFF7C2FA01980E4A0221FFF7BDFA0D48FA +:104EF000FFF7E2F9002383F3118803B05DF804FBA8 +:104F0000202383F311880748FFF7ACF9F2E7202349 +:104F100083F311880348FFF7C3F9EBE74C6B0008F4 +:104F2000706B00086037002038B50C4D0C4C0D49F3 +:104F30002A4604F10800FFF767FF05F1CA0204F1F1 +:104F400010000949FFF760FF05F5CA7204F1180067 +:104F50000649BDE83840FFF757BF00BF283C002096 +:104F6000401100202C6B0008366B0008416B0008D4 +:104F700070B5044608460D46FCF7B4FCC6B22046A0 +:104F8000013403780BB9184670BD32462946FCF748 +:104F900095FC0028F3D10120F6E700002DE9F84F39 +:104FA00005460C46FCF79EFC2B49C6B22846FFF787 +:104FB000DFFF08B10436F6B228492846FFF7D8FFCC +:104FC00008B11036F6B2632E0DD8DFF88C90DFF8FA +:104FD0008CA0DFF89480DFF894B0214F2E7846B98A +:104FE0002670BDE8F88F29462046BDE8F84F01F04D +:104FF000E5BC252E2CD1072249462846FCF75EFC4D +:1050000050B93B6823607B6863603B892381BB7A2E +:10501000A37207350B34E1E7082251462846FCF716 +:105020004DFCA8B90F4BA21C19780909023211F8DE +:10503000081002F8041C13F8011B01F00F015B4576 +:1050400011F8081002F8031CEED118340835C5E732 +:1050500004F8016B0135C1E7186C0008416B0008CA +:10506000FA6900089075FF1F206C00089C75FF1FEF +:10507000BFF34F8F024A1369DB03FCD4704700BFB4 +:105080000020024008B5094B1B7873B9FFF7F0FF09 +:10509000074B5A69002ABFBF064A9A6002F188325C +:1050A0009A601A6822F480621A6008BD983E002057 +:1050B000002002402301674508B50B4B1B7893B9CC +:1050C000FFF7D6FF094B5A6942F000425A611A684D +:1050D00042F480521A601A6822F480521A601A68E8 +:1050E00042F480621A6008BD983E00200020024011 +:1050F0007F289ABF00F58030C00200207047000072 +:105100004FF4006070470000802070477F2808B58A +:105110000BD8FFF7EDFF00F500630268013204D100 +:1051200004308342F9D1012008BD0020FCE70000D3 +:105130007F2838B5044626D8FFF7EAFCFFF798FF2A +:10514000FFF7A0FF114BF3221A6102225A615A693C +:1051500042EAC4025A615A6942F480325A610546F1 +:105160002046FFF785FF4FF40061FFF7C1FF00F015 +:1051700049F92846FFF7A0FFFFF7D4FC2046BDE819 +:105180003840FFF7C3BF002038BD00BF00200240F9 +:1051900040EA020313F007032DE9F04705460C46E9 +:1051A000164606D0324B40F2FB221A600020BDE8C2 +:1051B000F08781182F4A91420CD92D4A4FF4407143 +:1051C0001160F3E72B1D1B686268934208D1083E0B +:1051D00008350834072E19D92A6823689A42F1D075 +:1051E000FFF796FCFFF74EFFFFF742FF04F10801BF +:1051F000214C4FF001084FF00009012EA1F10807E2 +:1052000008D8FFF759FFFFF78DFC01E0002EE7D12A +:105210000120CCE7C4F81480AA4651F8083C4AF8AB +:10522000043B51F8043C6B60FFF722FFC4F8149074 +:105230002A6851F8083C9A420ED00D4B40F22632B3 +:105240001A600E4B1D600E4B1E600E4B1F60FFF769 +:1052500033FFFFF767FCA9E7DAF800A051F8043C38 +:105260009A4501F10801E8D1083E0835C5E700BFBD +:10527000943E00200000040800200240883E0020E8 +:10528000903E00208C3E0020084908B50B7828B1DC +:105290001BB9FFF7F7FE01230B7008BD002BFCD0F4 +:1052A000BDE808400870FFF707BF00BF983E002028 +:1052B0004FF4A0214FF0005000F0A6B870B582B0B6 +:1052C000FFF726FC0E4E054600F05EFF3268904266 +:1052D00037BF0C4A0B49516814682EBFD1E9004111 +:1052E000013151600419034641F100012846019142 +:1052F0003360FFF717FC0199204602B070BD00BF74 +:105300009C3E0020A03E002070B582B0FFF700FC5C +:10531000104E054600F038FF3268904237BF0E4A03 +:105320000D49516814682EBFD1E900410131516027 +:10533000041941F100010346284601913360FFF74B +:10534000F1FB01994FF47A7200232046FAF740FFEF +:1053500002B070BD9C3E0020A03E002010B502446B +:10536000064BD2B2904200D110BD441C00B253F89B +:10537000200041F8040BE0B2F4E700BF50280040E1 +:10538000114B30B5D3F89040240409D4D3F89040A1 +:10539000C3F89040D3F8904044F40044C3F89040E0 +:1053A0000A4C236843F4807323600244084BD2B252 +:1053B000904200D130BD441C00B251F8045B43F868 +:1053C0002050E0B2F4E700BF00100240007000403F +:1053D0005028004007B5012201A90020FFF7BEFFB9 +:1053E000019803B05DF804FB13B50446FFF7F2FF24 +:1053F000A04205D0012201A900200194FFF7C0FFBF +:1054000002B010BD704700007047000070470000F8 +:10541000034B1B781BB1034B4AF6AA221A60704754 +:10542000AC3E002000300040054B1A6832B902F152 +:10543000804202F50432D2F894201A60704700BF0F +:10544000A83E0020024B4FF40002C3F8942070479E +:105450000010024008B5FFF7E7FF024B1868C0F3E1 +:10546000407008BDA83E002070470000FEE7000025 +:105470000A4B0B480B4A90420BD30B4BDA1C121A07 +:10548000C11E22F003028B4238BF00220021FCF72C +:1054900031BA53F8041B40F8041BECE7146E000803 +:1054A000D43F0020D43F0020D43F002070470000AC +:1054B00070B5D0E91B439E6800224FF0FF3504EB26 +:1054C00042135101D3F800090028BEBFD3F80009E8 +:1054D00040F08040C3F80009D3F8000B0028BEBF9D +:1054E000D3F8000B40F08040C3F8000B0132631882 +:1054F0009642C3F80859C3F8085BE0D24FF0011395 +:10550000C4F81C3870BD00001D4B03EB80022DE970 +:10551000F043D2F80CC0DD6EDCF81420461CD2F843 +:1055200000E005EB063605EB4018516871450AD3DB +:10553000D5F83438012202FA00F023EA0000C5F859 +:105540003408BDE8F083BCF81040AEEB0103A34281 +:1055500028BF2346D8F81849A4B2B3EB840FF0D87B +:105560009468A4F1040959F8047F3760A4EB090793 +:105570001F44042FF7D81C440B4494605360D4E7B5 +:10558000B03E0020890141F02001016103699B06C2 +:10559000FCD41220FFF7D6BA10B5054C2046FEF712 +:1055A00041FF4FF0A043E366024B236710BD00BFED +:1055B000B03E0020586C000870B50378012B0546FA +:1055C00050D12A4BC46E98421BD1294BDA6C42F45D +:1055D0008052DA64DA6E42F48052DA66DA6EDA6A9F +:1055E00042F48052DA62DA6A22F48052DA620E21E0 +:1055F0004320DB6AFEF79EFB1E4BE3601E4BC4F8A4 +:1056000000380023C4F8003EC0232360EE6E4FF440 +:105610000413A3633369002BFCDA012333610C20EC +:10562000FFF790FA3369DB07FCD41220FFF78AFA00 +:105630003369002BFCDA0026A6602846FFF738FF06 +:105640006B68C4F81068DB68C4F81468C4F81C6898 +:105650004BB90A4BA3614FF0FF336361A36843F07A +:105660000103A36070BD064BF4E700BFB03E00200D +:10567000001002404014004003002002003C30C0F3 +:10568000083C30C0F8B5C46E054600212046FFF73F +:1056900079FF296F00234FF001128F68C4F8343866 +:1056A0004FF00066C4F81C284FF0FF3004EB4312A3 +:1056B00001339F42C2F80069C2F8006BC2F80809C2 +:1056C000C2F8080BF2D20B68EA6E6B6763621023B4 +:1056D0001361166916F01006FBD11220FFF732FA9B +:1056E000D4F8003823F4FE63C4F80038A36943F407 +:1056F000402343F01003A3610923C4F81038C4F811 +:1057000014380A4BEB604FF0C043C4F8103B084B11 +:10571000C4F8003BC4F81069C4F800396B6F03F19A +:10572000100243F480136A67A362F8BD346C00086A +:1057300040800010C26E90F86610D2F8003823F452 +:10574000FE6343EA0113C2F8003870472DE9F843BD +:1057500000EB8103C56EDA68166806F00306731E57 +:10576000022B05EB41130C4680460FFA81F94FEAF4 +:1057700041104FF00001C3F8101B4FF0010104F17C +:10578000100398BFB60401FA03F391698EBF334E3C +:1057900006F1805606F5004600293AD0578A04F1F2 +:1057A0005801490137436F50D5F81C180B43C5F811 +:1057B0001C382B180021C3F8101953690127611EEA +:1057C000A7409BB3138A928B9B08012A88BF53433F +:1057D000D8F87420981842EA034301F1400205EB1F +:1057E0008202C8F87400214653602846FFF7CAFEBB +:1057F00008EB8900C3681B8A43EA84534834640178 +:105800001E432E51D5F81C381F43C5F81C78BDE83F +:10581000F88305EB4917D7F8001B21F40041C7F8BE +:10582000001BD5F81C1821EA0303C0E704F13F036D +:1058300005EB83030A4A5A6028462146FFF7A2FE79 +:1058400005EB4910D0F8003923F40043C0F80039C3 +:10585000D5F81C3823EA0707D7E700BF00800010FF +:1058600000040002026F12684267FFF721BE0000C9 +:105870005831C36E49015B5813F4004004D013F44F +:10588000001F0CBF02200120704700004831C36E8A +:1058900049015B5813F4004004D013F4001F0CBFFF +:1058A000022001207047000000EB8101CB68196ADB +:1058B0000B6813604B6853607047000000EB810376 +:1058C00030B5DD68AA691368D36019B9402B84BF6D +:1058D000402313606B8A1468C26E1C44013CB4FB05 +:1058E000F3F46343033323F0030302EB411043EA71 +:1058F000C44343F0C043C0F8103B2B6803F00303DC +:10590000012B09B20ED1D2F8083802EB411013F482 +:10591000807FD0F8003B14BF43F0805343F0005326 +:10592000C0F8003B02EB4112D2F8003B43F00443C5 +:10593000C2F8003B30BD00002DE9F041244DEE6E71 +:1059400006EB40130446D3F8087BC3F8087B3807FE +:105950000AD5D6F81438190706D505EB8403214675 +:10596000DB6828465B689847FA071FD5D6F81438D5 +:10597000DB071BD505EB8403D968CCB98B69488A52 +:105980005A68B2FBF0F600FB16228AB91868DA688A +:1059900090420DD2121AC3E90024202383F3118808 +:1059A0000B482146FFF78AFF84F31188BDE8F08198 +:1059B000012303FA04F26B8923EA02036B81CB68AB +:1059C000002BF3D021460248BDE8F041184700BF44 +:1059D000B03E002000EB810370B5DD68C36E6C69DA +:1059E0002668E6604A0156BB1A444FF40020C2F80C +:1059F00010092A6802F00302012A0AB20ED1D3F874 +:105A0000080803EB421410F4807FD4F8000914BF97 +:105A100040F0805040F00050C4F8000903EB4212FF +:105A2000D2F8000940F00440C2F80009D3F8340865 +:105A3000012202FA01F10143C3F8341870BD19B90B +:105A4000402E84BF4020206020682E8A8419013CAB +:105A5000B4FBF6F440EAC44040F000501A44C6E7F4 +:105A6000F8B504461E48C56E05EB4413D3F8086923 +:105A7000C3F80869F10717D5D5F81038DA0713D538 +:105A800000EB8403D9684B691F68DA68974218D223 +:105A9000D21B00271A605F60202383F31188214600 +:105AA000FFF798FF87F31188330617D5D5F8342808 +:105AB0000123A340134211D02046BDE8F840FFF770 +:105AC00023BD012303FA04F2038923EA02030381BD +:105AD0008B68002BE8D021469847E5E7F8BD00BF6A +:105AE000B03E00202DE9F74FA34CE66E7569B3690F +:105AF0001D4015F48058756107D02046FEF7FEFC66 +:105B000003B0BDE8F04FFDF7DFBF002D12DAD6F885 +:105B1000003E99489F071EBFD6F8003E23F00303BE +:105B2000C6F8003ED6F8043823F00103C6F804385E +:105B3000FEF70EFD280505D58F48FFF7B9FC8E4806 +:105B4000FEF7F6FCA9040CD5D6F8083813F0060FBA +:105B5000F36823F470530CBF43F4105343F4A05381 +:105B6000F3602A0704D56368DB680BB18248984765 +:105B7000EB0200F18A80AF0227D5D4F86C90DFF8F1 +:105B8000F8B100274FF0010A09EB4712D2F8003BA9 +:105B900003F44023B3F5802F11D1D2F8003B002B42 +:105BA0000DDA62890AFA07F322EA0303638104EB40 +:105BB0008703DB68DB6813B1394658469847236F83 +:105BC00001379B68FFB29F42DED9E80618D5E76E21 +:105BD0003A6AC2F30A1002F00F0302F4F012B2F5AF +:105BE000802F00F09D80B2F5402F09D104EB830394 +:105BF0000022DB681B6A07F58057904240F08280E4 +:105C00002B03D6F818481DD5E70302D50020FFF76F +:105C100093FEA60302D50120FFF78EFE600302D596 +:105C20000220FFF789FE210302D50320FFF784FE3F +:105C3000E20202D50420FFF77FFEA30202D5052071 +:105C4000FFF77AFE6F037FF55BAFE60702D5002012 +:105C5000FFF706FFA50702D50120FFF701FF600748 +:105C600002D50220FFF7FCFE210702D50320FFF733 +:105C7000F7FEE20602D50420FFF7F2FEA3067FF549 +:105C80003FAF0520FFF7ECFE3AE7E36EDFF8E8B040 +:105C9000019300274FF0010A236F9B685FFA87F991 +:105CA00099453FF668AF019B03EB4913D3F80029F0 +:105CB00002F44022B2F5802F22D1D3F80029002A25 +:105CC0001EDAD3F8002942F09042C3F80029D3F835 +:105CD0000029002AFBDBE06E4946FFF753FC2289CE +:105CE0000AFA09F322EA0303238104EB8903DB6840 +:105CF0009B6813B14946584698474846FFF704FC4D +:105D00000137C9E7910708BFD7F80080072A98BF75 +:105D100003F8018B02F1010298BF4FEA18286CE7E3 +:105D2000023304EB830207F580575268D2F818C09B +:105D3000DCF80820DCE9001CA1EB0C0C00218842F7 +:105D40000AD104EB830463689B699A6802449A60F1 +:105D50005A6802445A6053E711F0030F08BFD7F89E +:105D600000808C4588BF02F8018B01F1010188BFDA +:105D70004FEA1828E3E700BFB03E0020C36E03EBF4 +:105D80004111D1F8003B43F40013C1F8003B7047C8 +:105D9000C36E03EB4111D1F8003943F40013C1F88D +:105DA00000397047C36E03EB4111D1F8003B23F477 +:105DB0000013C1F8003B7047C36E03EB4111D1F8EB +:105DC000003923F40013C1F80039704730B5039C43 +:105DD0000172043304FB0325C0E90653049B0363EB +:105DE0000021059BC160C0E90000C0E90422C0E9B0 +:105DF0000842C0E90A11436330BD0000416A002235 +:105E0000C0E90411C0E90A22C2606FF00101FEF787 +:105E100009BF0000D0E90432934201D1C2680AB937 +:105E2000181D70470020704703691960C26801326D +:105E3000C260C269134482690361934224BF436A0A +:105E400003610021FEF7E2BE38B504460D46E36863 +:105E50003BB16269131D1268A3621344E362002020 +:105E600007E0237A33B929462046FEF7BFFE002813 +:105E7000EDDA38BD6FF00100FBE70000C368C269CE +:105E8000013BC3604369134482694361934224BF69 +:105E9000436A436100238362036B03B11847704771 +:105EA00070B52023044683F31188866A3EB9FFF754 +:105EB000CBFF054618B186F31188284670BDA36A4A +:105EC000E26A13F8015BA362934202D32046FFF714 +:105ED000D5FF002383F31188EFE700002DE9F84F89 +:105EE00004460E46174698464FF0200989F311885C +:105EF0000025AA46D4F828B0BBF1000F09D14146CD +:105F00002046FFF7A1FF20B18BF311882846BDE89A +:105F1000F88FD4E90A12A7EB050B521A934528BF54 +:105F20009346BBF1400F1BD9334601F1400251F8B3 +:105F3000040B43F8040B9142F9D1A36A4033403675 +:105F4000A3624035D4E90A239A4202D32046FFF7E0 +:105F500095FF8AF31188BD42D8D289F31188C9E729 +:105F600030465A46FBF7A0FCA36A5B445E44A3623A +:105F70005D44E7E710B5029C0172043304FB032182 +:105F8000C0E906130023C0E90A33039B0363049BA3 +:105F9000C460C0E90000C0E90422C0E908424363CC +:105FA00010BD0000026AC260426AC0E904220022F9 +:105FB000C0E90A226FF00101FEF734BED0E90423E4 +:105FC0009A4201D1C26822B9184650F8043B0B60CE +:105FD0007047002070470000C368C2690133C36086 +:105FE0004369134482694361934224BF436A436116 +:105FF0000021FEF70BBE000038B504460D46E368ED +:106000003BB123691A1DA262E2691344E3620020D6 +:1060100007E0237A33B929462046FEF7E7FD00283A +:10602000EDDA38BD6FF00100FBE70000036919608D +:10603000C268013AC260C269134482690361934233 +:1060400024BF436A036100238362036B03B11847D3 +:106050007047000070B520230D460446114683F3B7 +:106060001188866A2EB9FFF7C7FF10B186F3118831 +:1060700070BDA36A1D70A36AE26A01339342A362F2 +:1060800004D3E16920460439FFF7D0FF002080F3F4 +:106090001188EDE72DE9F84F04460D4690469946E4 +:1060A0004FF0200A8AF311880026B346A76A4FB939 +:1060B00049462046FFF7A0FF20B187F311883046FC +:1060C000BDE8F88FD4E90A073A1AA8EB0607974209 +:1060D00028BF1746402F1BD905F1400355F8042B64 +:1060E00040F8042B9D42F9D1A36A4033A3624036A5 +:1060F000D4E90A239A4204D3E16920460439FFF720 +:1061000095FF8BF311884645D9D28AF31188CDE7E4 +:1061100029463A46FBF7C8FBA36A3B443D44A362C9 +:106120003E44E5E7D0E904239A4217D1C3689BB106 +:10613000836A8BB1043B9B1A0ED01360C368013B8A +:10614000C360C3691A44836902619A4224BF436AE7 +:106150000361002383620123184670470023FBE795 +:1061600000F080B84FF08043002258631A61022289 +:10617000DA6070474FF080430022DA607047000019 +:106180004FF08043586370474FF08043586A704720 +:106190004B6843608B688360CB68C3600B69436165 +:1061A0004B6903628B6943620B68036070470000B0 +:1061B00008B5234BDA6A42F0FF02DA62DA6A22F0AB +:1061C000FF02DA62DA6ADA6C42F0FF02DA64DA6E4F +:1061D00042F0FF02DA661B4ADB6E11464FF0904038 +:1061E000FFF7D6FF02F11C0100F58060FFF7D0FF3A +:1061F00002F1380100F58060FFF7CAFF02F1540197 +:1062000000F58060FFF7C4FF02F1700100F58060C7 +:10621000FFF7BEFF02F18C0100F58060FFF7B8FFC9 +:1062200002F1A80100F58060FFF7B2FF02F1C4019E +:1062300000F58060FFF7ACFFBDE8084000F09EB8B5 +:1062400000100240646C000808B500F023FAFEF765 +:1062500031FCFFF7E9F8BDE80840FEF765BE000035 +:10626000704700000F4B9A6D42F001029A659A6FD9 +:1062700042F001029A670C4A9B6F936843F0010356 +:1062800093604FF080434F229A624FF0FF32DA6200 +:1062900000229A615A63DA605A6001225A611A60D8 +:1062A000704700BF00100240002004E04FF0804221 +:1062B00008B51169D3680B40D9B2C9439B07116176 +:1062C00007D5202383F31188FEF720FC002383F3F6 +:1062D000118808BD08B5274B4FF0FF319A6A9962C3 +:1062E0009A6A00229A62986AD86A60F0FF00D862BF +:1062F000D86AC0B2D862D86A186B1963186B1A636F +:10630000186B986B60F080509863986B00F0805029 +:106310009863986BD86BD963D86BDA63D86B186CB9 +:106320001964196C1A64196C996D41F08051996562 +:10633000996F41F080519967996FD3F8901011F4DB +:10634000407F1EBF4FF48031C3F89010C3F89020F7 +:10635000D3F89020C3F8902000F074F9064B002287 +:106360005A605A6842F480625A605A6842F4007275 +:106370005A6008BD00100240007000403A4B3B4A92 +:106380009A6501221A601A689007FCD500229A606B +:106390009A6812F00C0FFBD1354A4FF4007111606E +:1063A00051694905FCD41A6842F480721A601A686F +:1063B0005205FCD52E490A6842F480720A602D4AC3 +:1063C0004FF4E06111601A6842F060021A601A68C6 +:1063D00042F008021A601A689007FCD59A6812F019 +:1063E0000C0FFBD1D3F8942042F4C062C3F8942080 +:1063F000214ADA601A6842F080721A601A689101C4 +:10640000FCD51E4A1A611A6842F080621A601A6846 +:106410001201FCD500229A60194AC3F88820154958 +:106420000122C3F89C200A6822F0070242F004020D +:106430000A600A6802F00702042AFAD19A6842F058 +:1064400003029A609A6802F00C020C2AFAD11A6EC2 +:1064500042F001021A66D3F8802042F00102C3F82C +:106460008020D3F8803070470010024000040010F4 +:10647000007000400020024012140001000C1000C7 +:1064800055550134074A08B5536903F001035361B8 +:1064900023B1054A13680BB150689847BDE808401E +:1064A000FDF712BB00040140403F0020074A08B539 +:1064B000536903F00203536123B1054A93680BB19A +:1064C000D0689847BDE80840FDF7FEBA00040140D7 +:1064D000403F0020074A08B5536903F004035361A5 +:1064E00023B1054A13690BB150699847BDE80840CC +:1064F000FDF7EABA00040140403F0020074A08B512 +:10650000536903F00803536123B1054A93690BB142 +:10651000D0699847BDE80840FDF7D6BA00040140AD +:10652000403F0020074A08B5536903F01003536148 +:1065300023B1054A136A0BB1506A9847BDE8084079 +:10654000FDF7C2BA00040140403F0020164B10B5D1 +:106550005C6904F478725A61A30604D5134A936AFD +:106560000BB1D06A9847600604D5104A136B0BB183 +:10657000506B9847210604D50C4A936B0BB1D06B36 +:106580009847E20504D5094A136C0BB1506C984743 +:10659000A30504D5054A936C0BB1D06C9847BDE8B0 +:1065A0001040FDF791BA00BF00040140403F0020B9 +:1065B000194B10B55C6904F47C425A61620504D53C +:1065C000164A136D0BB1506D9847230504D5134A35 +:1065D000936D0BB1D06D9847E00404D50F4A136E4C +:1065E0000BB1506E9847A10404D50C4A936E0BB1C1 +:1065F000D06E9847620404D5084A136F0BB1506FF0 +:106600009847230404D5054A936F0BB1D06F984780 +:10661000BDE81040FDF758BA00040140403F00209B +:1066200008B50348FDF702FBBDE80840FDF74CBA8A +:106630003C35002008B5FFF739FEBDE80840FDF7FE +:1066400043BA0000062108B50846FDF773FB062192 +:106650000720FDF76FFB06210820FDF76BFB0621E5 +:106660000920FDF767FB06210A20FDF763FB0621E1 +:106670001720FDF75FFB06212820FDF75BFB0721B4 +:106680001C20FDF757FBBDE808400C212520FDF735 +:1066900051BB000008B5FFF71DFE00F00DF8FDF737 +:1066A000EDFCFDF7BDFEFDF795FDFFF7D9FDBDE85B +:1066B0000840FFF755BD00000023054A1946013385 +:1066C000102BC2E9001102F10802F8D1704700BF97 +:1066D000403F00200B460146184600F025B8000058 +:1066E00000F038B8012838BF012010B50446204614 +:1066F00000F028F830B900F007F808B900F00CF8FD +:106700008047F4E710BD0000024B1868BFF35B8FB1 +:10671000704700BFC03F002008B5062000F032F9E6 +:106720000120FEF74FFB000010B5054C13462CB1BD +:106730000A4601460220AFF3008010BD2046FCE768 +:1067400000000000024B0146186800F089B800BF45 +:1067500060110020024B0146186800F035B800BFF8 +:106760006011002010B501390244904201D100208F +:1067700005E0037811F8014FA34201D0181B10BDAA +:106780000130F2E72DE9F041A3B1C91A17780144AD +:10679000044603F1FF3C8C42204601D9002009E069 +:1067A0000578BD4204F10104F5D10CEB0405D618BF +:1067B000A54201D1BDE8F08115F8018D16F801ED73 +:1067C000F045F5D0E7E7000037B5002944D051F88F +:1067D000043C0190002BA1F10404B8BFE41800F0C0 +:1067E000F5F81E4A0198136833B96360146003B06A +:1067F000BDE8304000F0F0B8A34208D9256861191F +:106800008B4201BF19685B6849192160EDE71A46A0 +:106810005B680BB1A342FAD911685518A5420BD198 +:10682000246821445418A3421160E0D11C685B68BD +:10683000536021441160DAE702D90C230360D6E7E4 +:10684000256861198B4204BF19685B68636004BFE7 +:10685000491921605460CAE703B030BDC43F00202D +:10686000F8B5CD1C25F0030508350C2D38BF0C25D7 +:10687000002D064601DBA94203D90C23336000201A +:10688000F8BD00F0A3F821490A6814469CB9204FCE +:106890003B6823B92146304600F03CF83860294671 +:1068A000304600F037F8431C23D10C2333603046C8 +:1068B00000F092F8E3E723685B1B17D40B2B03D996 +:1068C00023601C44256004E06368A2420CBF0B6097 +:1068D0005360304600F080F804F10B00231D20F0D7 +:1068E0000700C21ACCD01B1AA350C9E7224664681D +:1068F000CCE7C41C24F00304A042E3D0211A3046A4 +:1069000000F008F80130DDD1CFE700BFC43F002020 +:10691000C83F002038B5064D0023044608462B60CA +:10692000FEF748FA431C02D12B6803B1236038BD3F +:10693000CC3F00201F2938B504460D4604D9162344 +:1069400003604FF0FF3038BD426C12B152F8213075 +:106950004BB9204600F030F82A4601462046BDE8F3 +:10696000384000F017B8012B0AD0591C03D1162368 +:1069700003600120E7E7002442F8254028469847B5 +:106980000020E0E7024B01461868FFF7D3BF00BFC5 +:106990006011002038B5074D002304460846114613 +:1069A0002B60FEF713FA431C02D12B6803B123605E +:1069B00038BD00BFCC3F0020FEF702BA034611F8F5 +:1069C000012B03F8012B002AF9D17047014800F090 +:1069D00009B800BFD03F0020014800F005B800BF53 +:1069E000D03F002070470000704700006F72672E94 +:1069F0006172647570696C6F742E4E75636C656F2F +:106A00002D4C34393600000053544D33324C343F52 +:106A10003F0000004261642043414E496661636566 +:106A200020696E6465782E00800000000080000000 +:106A30000000800000000000000000007D1A000837 +:106A400065220008C52100088D1A0008C11A000837 +:106A5000BD1C0008911A0008A11A0008951A000828 +:106A60009D1A0008991A0008E51B0008A51A0008DD +:106A7000D1240008B51A0008B91B000840A2E4F1AF +:106A8000646891060041A3E5F26569920700000081 +:106A90000096000000000000000000000000000060 +:106AA0000000000000000000000000004540000859 +:106AB000314000086D40000859400008654000085A +:106AC000514000083D400008294000087940000876 +:106AD00000000000514100083D41000879410008D4 +:106AE00065410008714100085D4100084941000806 +:106AF0003541000885410008000000000100000049 +:106B0000000000006D61696E0000000069646C6542 +:106B1000000000000C6B00082836002060370020C1 +:106B200001000000B14A00080000000041726475D5 +:106B300050696C6F740025424F415244252D424CE0 +:106B4000002553455249414C250000000200000039 +:106B5000000000006D430008D943000840004000D9 +:106B6000F83B0020083C002002000000000000006C +:106B700003000000000000001D44000800000000A9 +:106B800010000000183C0020000000000100000080 +:106B900000000000B03E002001010200C54E0008C8 +:106BA000D54D0008714E0008554E00084300000006 +:106BB000B46B000809024300020100C0320904005E +:106BC000000102020100052400100105240100015A +:106BD000042402020524060001070582030800FFC1 +:106BE00009040100020A000000070501024000003C +:106BF000070581024000000012000000006C000840 +:106C00001201100102000040091241570002010266 +:106C1000030100000403090425424F4152442500AA +:106C200030313233343536373839414243444546C2 +:106C30000000000000000000654500081D48000835 +:106C4000C948000840004000283F0020283F00209D +:106C500001000000383F00208000000040010000DB +:106C6000050000000000A82A00000000AAAABEAA91 +:106C700000001424FFFF00000000000070A70A00BD +:106C80000040001000000000AAAAAAAA000000000C +:106C90007FBF0000000000000000000000000000B6 +:106CA00000000000AAAAAAAA00000000FFFF00003E +:106CB00000000000000000000A00000000000000CA +:106CC000AAAAAAAA00000000FFFF00009900000085 +:106CD000000000000000000000000000AAAAAAAA0C +:106CE00000000000FFFF00000000000000000000A6 +:106CF0000000000000000000AAAAAAAA00000000EC +:106D0000FFFF000000000000000000000000000085 +:106D100000000000AAAAAAAA00000000FFFF0000CD +:106D20000000000000000000000000000000000063 +:106D3000AAAAAAAA00000000FFFF000000000000AD +:106D400000000000BC94FF7F010000000000000074 +:106D500017040000000000000060030000000000B5 +:106D6000FE2A0100D2040000FF000000603700206E +:106D70003C35002000000000086A00083F000000C9 +:106D800000960000000008009600000000080000C7 +:106D900004000000146C0008000000000000000067 +:106DA00000000000000000000000000000000000E3 +:106DB000641100200000000000000000000000003E +:106DC00000000000000000000000000000000000C3 +:106DD00000000000000000000000000000000000B3 +:106DE00000000000000000000000000000000000A3 +:106DF0000000000000000000000000000000000093 +:106E00000000000000000000000000000000000082 +:046E1000000000007E +:00000001FF diff --git a/Tools/bootloaders/NxtPX4v2_bl.bin b/Tools/bootloaders/NxtPX4v2_bl.bin new file mode 100644 index 00000000000000..07c2d5d2d93a1d Binary files /dev/null and b/Tools/bootloaders/NxtPX4v2_bl.bin differ diff --git a/Tools/bootloaders/NxtPX4v2_bl.hex b/Tools/bootloaders/NxtPX4v2_bl.hex new file mode 100644 index 00000000000000..b9dbf29471ba99 --- /dev/null +++ b/Tools/bootloaders/NxtPX4v2_bl.hex @@ -0,0 +1,1107 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008B128000828 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E30200081D3E0008493E0008D4 +:10006000753E0008A13E0008CD3E0008BD10000806 +:10007000E5100008111100083D1100086911000881 +:1000800091110008BD110008E3020008E302000816 +:10009000E3020008E3020008E3020008F93E00085A +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E0005D3F0008E3020008E3020008E3020008A5 +:1000F000E3020008E3020008E3020008E911000837 +:10010000E3020008E3020008D13F0008E302000810 +:10011000E3020008E3020008E3020008E30200082B +:10012000151200083D120008691200089512000817 +:10013000C1120008E3020008E3020008E30200081D +:10014000E3020008E3020008E3020008E3020008FB +:10015000E91200081513000841130008E302000823 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E30200089D340008E3020008E3020008DF +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000889340008E3020008E302000893 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F012FB61 +:1003500003F020FB4FF055301F491B4A91423CBF30 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F02AFB03F07EFBB6 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F012BB000600200022002057 +:1003D0000000000808ED00E00000002000060020FA +:1003E000A8440008002200205C2200206022002097 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0CAFDFEE701F030 +:1004300059FD00DFFEE7000038B500F02FFC00F0AA +:10044000D1FD02F0F5F9054602F028FA0446C0B9DC +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0ECF90CB100F054 +:1004700075F800F08BFD284600F01EF900F06EF8CC +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F047FE0023154A4FF4AB +:1004D0007A71134801F036FE002383F31188124C21 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0A4FC322363602B78032B07D16368CF +:100510002BB9022000F09AFC4FF47A73636038BD67 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F071BC022000F05CBC024B0022D3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0AAFB0220FFF7CBFF454B0021D3F868 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F009FCB14A91 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F037FD0023AB4A4FF4CA +:1006F0007A71A94801F026FD002383F31188009B3D +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F07FFB24B19C4B1B684C +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F05DFB039B213B1F2B04 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F04BFA0421059005A800F00EFAF8 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F07EFB26B10BF017 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F01AFA0220FFF73BFE1FFA86F84046C6 +:1008C00000F022FA0446B0B1039940460136A1F186 +:1008D00040025142514100F027FA0028EDD1BA46BA +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0F0F9013040F06F +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F058FA019AFF217F4800F079FA4FEAA7 +:1009F000A803C8F387027C492846019300F078FADF +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0A2F90C +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F01DFB8046E7E7384600F046F912 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F05DF90590E6E70023642104A8BE +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F04BF9EAE70B +:100AC0000220FFF7E5FC00283FF48CAE00F05AF955 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F055F907460421049004A800F0F2 +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0DAF80421059005A800F095 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F007F9002844D00A9B01330BD0BE +:100B600008220AA9002000F0C3F900283AD0202268 +:100B7000FF210AA800F0B4F9FFF792FC1C4801F02D +:100B800025FA13B0BDE8F08F002E3FF42BAE0BF02A +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F003FA059800F00AFA46463C46E0 +:100BD00000F0D2F9A6E506464EE64FF0000901E620 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0CEF965 +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B5104C50 +:100CA0000025104E01F0ACFC208030682388834280 +:100CB0000CD800252088013801F09EFC23880544CB +:100CC000013BB5F5802F2380F4D370BD01F094FC77 +:100CD000336805440133B5F5003F3360E5D3E8E7F9 +:100CE000B62300208823002001F058BD00F10060E9 +:100CF00000F500300068704700F10060920000F5D8 +:100D0000003001F0D9BC0000054B1A68054B1B8868 +:100D10009B1A834202D9104401F06EBC0020704738 +:100D200088230020B623002038B50446074D29B19A +:100D300028682044BDE8384001F076BC286820448B +:100D400001F060FC0028F3D038BD00BF88230020EC +:100D50000020704700F1FF5000F58F10D0F8000818 +:100D600070470000064991F8243033B1002308226F +:100D7000086A81F82430FFF7BFBF0120704700BF29 +:100D80008C230020014B1868704700BF0010005CE6 +:100D9000194B01380322084470B51D68174BC5F381 +:100DA0000B042D0C1E88A6420BD15C680A46013C40 +:100DB000824213460FD214F9016F4EB102F8016B53 +:100DC000F6E7013A03F10803ECD181420B4602D267 +:100DD0002C2203F8012B0424094A1688AE4204D1C0 +:100DE000984284BF967803F8016B013C02F104023B +:100DF000F3D1581A70BD00BF0010005C142200200F +:100E0000C8400008022804D1054B4FF400429A6103 +:100E100070470128FCD1034B4FF40062F7E700BF95 +:100E200000040258000C0258022804D1054B4FF070 +:100E300000429A6170470128FCD1034B4FF00062D9 +:100E4000F7E700BF00040258000C0258022805D141 +:100E5000064A536983F40043536170470128FCD16B +:100E6000034A536983F40063F6E700BF00040258A5 +:100E7000000C025870B504464FF47A764CB1412C00 +:100E8000254628BF412506FB05F0641B01F09EF8AE +:100E9000F4E770BD002310B5934203D0CC5CC4547A +:100EA0000133F9E710BD0000013810B510F9013F1A +:100EB0003BB191F900409C4203D11AB10131013A92 +:100EC000F4E71AB191F90020981A10BD1046FCE71A +:100ED00003460246D01A12F9011B0029FAD17047C5 +:100EE00002440346934202D003F8011BFAE770471D +:100EF0002DE9F8431F4D14460746884695F82420EF +:100F000052BBDFF870909CB395F824302BB92022A7 +:100F1000FF2148462F62FFF7E3FF95F82400414682 +:100F2000C0F1080205EB8000A24228BF2246D6B2DB +:100F30009200FFF7AFFF95F82430A41B17441E441E +:100F40009044E4B2F6B2082E85F82460DBD1FFF7B6 +:100F500009FF0028D7D108E02B6A03EB8203834204 +:100F6000CFD0FFF7FFFE0028CBD10020BDE8F883EB +:100F70000120FBE78C230020024B1A78024B1A70E9 +:100F8000704700BFB42300201022002010B5114C80 +:100F9000114800F06FFB21460F4800F097FB2468D2 +:100FA0004FF47A70D4F89020D2F8043843F002035A +:100FB000C2F80438FFF75EFF0849204600F094FCB1 +:100FC000D4F89020D2F8043823F00203C2F8043891 +:100FD00010BD00BF84420008B02600208C420008EB +:100FE00070470000F0B5A1B071B6002301200024C5 +:100FF00080261A46194600F04BFA4FF4D067214A72 +:101000003D25136923BBD2F810310BBB036804F1F3 +:10101000006199600368C3F80CD003685E600368E0 +:101020001F6001680B6843F001030B6001680B68E7 +:1010300023F01E030B6001680B68DB07FCD4037B05 +:101040008034416805FA03F3B4F5001F0B60D8D172 +:1010500000F05EFAB4F5001F11D000240A4E0B4DCB +:10106000012001F09BFB3388A34205D92868204466 +:10107000013401F0D9FAF6E7002001F08FFB61B6E8 +:1010800021B0F0BD00200052B623002088230020AC +:1010900030B50A44084D91420DD011F8013B58403B +:1010A000082340F30004013B2C4013F0FF0384EAC3 +:1010B0005000F6D1EFE730BD2083B8ED08B5074BFF +:1010C000074A196801F03D01996053680BB19068B7 +:1010D0009847BDE8084001F023BC00BF0000024073 +:1010E000B823002008B5084B1968890901F03D01B3 +:1010F0008A019A60054AD3680BB110699847BDE828 +:10110000084001F00DBC00BF00000240B8230020E1 +:1011100008B5084B1968090C01F03D010A049A60F2 +:10112000054A53690BB190699847BDE8084001F042 +:10113000F7BB00BF00000240B823002008B5084BF1 +:101140001968890D01F03D018A059A60054AD36945 +:101150000BB1106A9847BDE8084001F0E1BB00BF41 +:1011600000000240B823002008B5074B074A596821 +:1011700001F03D01D960536A0BB1906A9847BDE810 +:10118000084001F0CDBB00BF00000240B8230020A2 +:1011900008B5084B5968890901F03D018A01DA60F8 +:1011A000054AD36A0BB1106B9847BDE8084001F0BF +:1011B000B7BB00BF00000240B823002008B5084BB1 +:1011C0005968090C01F03D010A04DA60054A536BC5 +:1011D0000BB1906B9847BDE8084001F0A1BB00BF80 +:1011E00000000240B823002008B5084B5968890D5B +:1011F00001F03D018A05DA60054AD36B0BB1106C32 +:101200009847BDE8084001F08BBB00BF00000240DA +:10121000B823002008B5074B074A196801F03D01C3 +:101220009960536C0BB1906C9847BDE8084001F091 +:1012300077BB00BF00040240B823002008B5084B6C +:101240001968890901F03D018A019A60054AD36C49 +:101250000BB1106D9847BDE8084001F061BB00BFBD +:1012600000040240B823002008B5084B1968090C97 +:1012700001F03D010A049A60054A536D0BB1906D6F +:101280009847BDE8084001F04BBB00BF0004024096 +:10129000B823002008B5084B1968890D01F03D01FD +:1012A0008A059A60054AD36D0BB1106E9847BDE868 +:1012B000084001F035BB00BF00040240B823002005 +:1012C00008B5074B074A596801F03D01D960536ED4 +:1012D0000BB1906E9847BDE8084001F021BB00BFFC +:1012E00000040240B823002008B5084B596889095A +:1012F00001F03D018A01DA60054AD36E0BB1106F2F +:101300009847BDE8084001F00BBB00BF0004024055 +:10131000B823002008B5084B5968090C01F03D01BD +:101320000A04DA60054A536F0BB1906F9847BDE825 +:10133000084001F0F5BA00BF00040240B8230020C5 +:1013400008B5084B5968890D01F03D018A05DA603E +:10135000054AD36F13B1D2F880009847BDE8084022 +:1013600001F0DEBA00040240B823002000230C493B +:1013700010B51A460B4C0B6054F82300026001EBC9 +:10138000430004334260402BF6D1074A4FF0FF334D +:101390009360D360C2F80834C2F80C3410BD00BFAB +:1013A000B8230020D8400008000002400F28F8B5FC +:1013B00010D9102810D0112811D0122808D10F24CC +:1013C0000720DFF8C8E00126DEF80050A04208D967 +:1013D000002653E00446F4E70F240020F1E7072439 +:1013E000FBE706FA00F73D424AD1264C4FEA001CC3 +:1013F0003D4304EB00160EEBC000CEF80050C0E9F0 +:101400000123FBB273B12048D0F8D83043F0010378 +:10141000C0F8D830D0F8003143F00103C0F80031F3 +:10142000D0F8003117F47F4F0ED01748D0F8D830DD +:1014300043F00203C0F8D830D0F8003143F0020383 +:10144000C0F80031D0F8003154F80C00036823F0E4 +:101450001F030360056815F00105FBD104EB0C03C5 +:101460003D2493F80CC05F6804FA0CF43C6021241E +:101470000560446112B1987B00F054F83046F8BD25 +:101480000130A3E7D840000800440258B8230020E8 +:1014900010B5302484F31188FFF788FF002383F30D +:1014A000118810BD10B50446807B00F051F801236F +:1014B0001549627B03FA02F20B6823EA0203DAB2EF +:1014C0000B6072B9114AD2F8D81021F00101C2F8AC +:1014D000D810D2F8001121F00101C2F80011D2F8A1 +:1014E000002113F47F4F0ED1084BD3F8D82022F0FF +:1014F0000202C3F8D820D3F8002122F00202C3F878 +:101500000021D3F8003110BDB82300200044025858 +:1015100008B5302383F31188FFF7C4FF002383F35A +:10152000118808BD090100F16043012203F5614300 +:10153000C9B283F8001300F01F039A4043099B00CF +:1015400003F1604303F56143C3F880211A607047DB +:1015500000F01F0301229A40430900F160409B0004 +:1015600000F5614003F1604303F56143C3F8802057 +:10157000C3F88021002380F8003370470268436875 +:101580001143016003B118477047000013B5406B69 +:1015900000F58054D4F8A4381A681178042914D1BD +:1015A000017C022911D11979012312898B40134240 +:1015B0000BD101A94C3002F0A3F8D4F8A44802469C +:1015C000019B2179206800F0DFF902B010BD000016 +:1015D000143002F025B800004FF0FF33143002F051 +:1015E0001FB800004C3002F0F7B800004FF0FF3396 +:1015F0004C3002F0F1B80000143001F0F3BF0000ED +:101600004FF0FF31143001F0EDBF00004C3002F01C +:10161000C3B800004FF0FF324C3002F0BDB80000FC +:101620000020704710B500F58054D4F8A4381A682B +:101630001178042917D1017C022914D15979012389 +:1016400052898B4013420ED1143001F085FF0246BF +:1016500048B1D4F8A4484FF4407361792068BDE8DC +:10166000104000F07FB910BD406BFFF7DBBF0000FA +:10167000704700007FB5124B012504260446036025 +:101680000023057400F1840243602946C0E9023357 +:101690000C4B0290143001934FF44073009601F00C +:1016A00037FF094B04F69442294604F14C0002949A +:1016B000CDE900634FF4407301F0FEFF04B070BD4C +:1016C000D8410008691600088D1500080A68302303 +:1016D00083F311880B790B3342F823004B791333D2 +:1016E00042F823008B7913B10B3342F8230000F545 +:1016F0008053C3F8A41802230374002080F31188D8 +:101700007047000038B5037F044613B190F8543099 +:10171000ABB90125201D0221FFF730FF04F11400B1 +:101720006FF00101257700F079FC04F14C0084F89A +:1017300054506FF00101BDE8384000F06FBC38BD77 +:1017400010B5012104460430FFF718FF002323776A +:1017500084F8543010BD000038B50446002514301C +:1017600001F0EEFE04F14C00257701F0BDFF201DD5 +:1017700084F854500121FFF701FF2046BDE83840AE +:10178000FFF750BF90F8803003F06003202B06D1A4 +:1017900090F881200023212A03D81F2A06D8002090 +:1017A0007047222AFBD1C0E91D3303E0034A426798 +:1017B00007228267C3670120704700BF2C220020E8 +:1017C00037B500F58055D5F8A4381A681178042982 +:1017D0001AD1017C022917D11979012312898B4072 +:1017E000134211D100F14C04204602F03DF858B1EB +:1017F00001A9204601F084FFD5F8A4480246019BC8 +:101800002179206800F0C0F803B030BD01F10B036E +:10181000F0B550F8236085B004460D46FEB1302384 +:1018200083F3118804EB8507301D0821FFF7A6FE1E +:10183000FB6806F14C005B691B681BB1019001F06D +:101840006DFF019803A901F05BFF024648B1039BBD +:101850002946204600F098F8002383F3118805B04C +:10186000F0BDFB685A691268002AF5D01B8A013B5B +:101870001340F1D104F18002EAE70000133138B5DA +:1018800050F82140ECB1302383F3118804F58053E4 +:10189000D3F8A4281368527903EB8203DB689B69B1 +:1018A0005D6845B104216018FFF768FE294604F120 +:1018B000140001F05BFE2046FFF7B4FE002383F323 +:1018C000118838BD7047000001F028B9012340227B +:1018D000002110B5044600F8303BFFF701FB002360 +:1018E000C4E9013310BD000010B53023044683F372 +:1018F00011882422416000210C30FFF7F1FA2046C4 +:1019000001F02EF902230020237080F3118810BD0E +:1019100070B500EB8103054650690E461446DA6047 +:1019200018B110220021FFF7DBFAA06918B11022CC +:101930000021FFF7D5FA31462846BDE8704001F096 +:1019400015BA000083682022002103F0011310B5AE +:10195000044683601030FFF7C3FA2046BDE810400C +:1019600001F090BAF0B4012500EB810447898D4065 +:10197000E4683D43A469458123600023A26063605D +:10198000F0BC01F0ADBA0000F0B4012500EB810419 +:1019900007898D40E4683D43646905812360002325 +:1019A000A2606360F0BC01F023BB000070B50223AD +:1019B00000250446242203702946C0F888500C30C4 +:1019C00040F8045CFFF78CFA204684F8705001F070 +:1019D00061F963681B6823B129462046BDE8704061 +:1019E000184770BD0378052B10B504460AD080F85F +:1019F0008C300523037043681B680BB104219847A2 +:101A00000023A36010BD00000178052906D190F8DD +:101A10008C20436802701B6803B1184770470000B0 +:101A200070B590F87030044613B1002380F8703020 +:101A300004F18002204601F049FA63689B68B3B95B +:101A400094F8803013F0600535D00021204601F075 +:101A50003BFD0021204601F02BFD63681B6813B19C +:101A6000062120469847062384F8703070BD204632 +:101A700098470028E4D0B4F88630A26F9A4288BF15 +:101A8000A36794F98030A56F002B4FF0300380F2EC +:101A90000381002D00F0F280092284F8702083F386 +:101AA000118800212046D4E91D23FFF76DFF002394 +:101AB00083F31188DAE794F8812003F07F0343EA87 +:101AC000022340F20232934200F0C58021D8B3F5E0 +:101AD000807F48D00DD8012B3FD0022B00F093809F +:101AE000002BB2D104F1880262670222A267E36789 +:101AF000C1E7B3F5817F00F09B80B3F5407FA4D1AF +:101B000094F88230012BA0D1B4F8883043F002035E +:101B100032E0B3F5006F4DD017D8B3F5A06F31D0D8 +:101B2000A3F5C063012B90D86368204694F8822007 +:101B30005E6894F88310B4F88430B047002884D0ED +:101B4000436863670368A3671AE0B3F5106F36D084 +:101B500040F6024293427FF478AF5C4B6367022306 +:101B6000A3670023C3E794F88230012B7FF46DAFA5 +:101B7000B4F8883023F00203A4F88830C4E91D5576 +:101B8000E56778E7B4F88030B3F5A06F0ED194F82C +:101B90008230204684F88A3001F0DAF863681B68E6 +:101BA00013B1012120469847032323700023C4E981 +:101BB0001D339CE704F18B0363670123C3E723789C +:101BC000042B10D1302383F311882046FFF7BAFE8F +:101BD00085F311880321636884F88B5021701B689A +:101BE0000BB12046984794F88230002BDED084F861 +:101BF0008B300423237063681B68002BD6D002212E +:101C000020469847D2E794F8843020461D0603F01A +:101C10000F010AD501F04CF9012804D002287FF405 +:101C200014AF2B4B9AE72B4B98E701F033F9F3E70E +:101C300094F88230002B7FF408AF94F8843013F0CE +:101C40000F01B3D01A06204602D501F055FCADE7CE +:101C500001F046FCAAE794F88230002B7FF4F5AE41 +:101C600094F8843013F00F01A0D01B06204602D553 +:101C700001F02AFC9AE701F01BFC97E7142284F894 +:101C8000702083F311882B462A4629462046FFF709 +:101C900069FE85F31188E9E65DB1152284F87020AC +:101CA00083F3118800212046D4E91D23FFF75AFE53 +:101CB000FDE60B2284F8702083F311882B462A4618 +:101CC00029462046FFF760FEE3E700BF0842000810 +:101CD000004200080442000838B590F8703004460D +:101CE000002B3ED0063BDAB20F2A34D80F2B32D865 +:101CF000DFE803F03731310822323131313131310F +:101D000031313737856FB0F886309D4214D2C368C1 +:101D10001B8AB5FBF3F203FB12556DB9302383F335 +:101D200011882B462A462946FFF72EFE85F3118897 +:101D30000A2384F870300EE0142384F870303023C6 +:101D400083F31188002320461A461946FFF70AFE3E +:101D5000002383F3118838BDC36F03B19847002374 +:101D6000E7E70021204601F0AFFB0021204601F00B +:101D70009FFB63681B6813B1062120469847062322 +:101D8000D7E7000010B590F870300446142B29D026 +:101D900017D8062B05D001D81BB110BD093B022B6B +:101DA000FBD80021204601F08FFB0021204601F0E6 +:101DB0007FFB63681B6813B1062120469847062302 +:101DC00019E0152BE9D10B2380F87030302383F311 +:101DD000118800231A461946FFF7D6FD002383F326 +:101DE0001188DAE7C3689B695B68002BD5D1C36FA4 +:101DF00003B19847002384F87030CEE7002382684F +:101E0000037503691B6899689142FBD25A680360A5 +:101E10004260106058607047002382680375036950 +:101E20001B6899689142FBD85A6803604260106051 +:101E30005860704708B50846302383F311880B7D3E +:101E4000032B05D0042B0DD02BB983F3118808BDCB +:101E50008B6900221A604FF0FF338361FFF7CEFFDA +:101E60000023F2E7D1E9003213605A60F3E7000083 +:101E7000FFF7C4BF054BD96808751868026853603E +:101E80001A600122D8600275FEF7BCBA4024002017 +:101E90000C4B30B5DD684B1C87B004460FD02B4689 +:101EA000094A684600F04EF92046FFF7E3FF009B21 +:101EB00013B1684600F050F9A86907B030BDFFF7CC +:101EC000D9FFF9E740240020351E0008044B1A68AA +:101ED000DB6890689B68984294BF0020012070479F +:101EE00040240020084B10B51C68D8682268536055 +:101EF0001A600122DC602275FFF78EFF0146204642 +:101F0000BDE81040FEF77EBA4024002038B5074CEB +:101F100001230025064907482370656001F0E2FCB3 +:101F20000223237085F3118838BD00BFA826002046 +:101F3000104200084024002000F044B9034A5168D0 +:101F400053685B1A9842FBD8704700BF001000E04E +:101F50008B600223086108468B8270478368A3F177 +:101F6000840243F8142C026943F8442C426943F874 +:101F7000402C094A43F8242CC268A3F1200043F8FE +:101F8000182C022203F80C2C002203F80B2C034A15 +:101F900043F8102C704700BF1D04000840240020A7 +:101FA00008B5FFF7DBFFBDE80840FFF761BF0000A1 +:101FB000024BDB6898610F20FFF75CBF40240020D4 +:101FC000302383F31188FFF7F3BF000008B5014603 +:101FD000302383F311880820FFF75AFF002383F38F +:101FE000118808BD064BDB6839B1426818605A6039 +:101FF000136043600420FFF74BBF4FF0FF30704782 +:10200000402400200368984206D01A68026050609D +:1020100018469961FFF72CBF7047000038B5044699 +:102020000D462068844200D138BD036823605C609F +:102030008561FFF71DFFF4E7036810B59C68A242B5 +:102040000CD85C688A600B604C60216059609968AC +:102050008A1A9A604FF0FF33836010BD121B1B6811 +:10206000ECE700000A2938BF0A2170B504460D4686 +:102070000A26601901F02EFC01F016FC041BA54293 +:1020800003D8751C04462E46F3E70A2E04D9012016 +:10209000BDE8704001F066BC70BD0000F8B5144B9F +:1020A0000D460A2A4FF00A07D96103F11001826038 +:1020B00038BF0A22416019691446016048601861FE +:1020C000A81801F0F7FB01F0EFFB431B0646A34203 +:1020D00006D37C1C28192746354601F0FBFBF2E7A6 +:1020E0000A2F04D90120BDE8F84001F03BBCF8BD3F +:1020F00040240020F8B506460D4601F0D5FB0F4AF6 +:10210000134653F8107F9F4206D12A4601463046B7 +:10211000BDE8F840FFF7C2BFD169BB68441A2C196B +:1021200028BF2C46A34202D92946FFF79BFF22462F +:1021300031460348BDE8F840FFF77EBF4024002049 +:1021400050240020C0E90323002310B45DF8044BA1 +:102150004361FFF7CFBF000010B5194C23699842C7 +:102160000DD08168D0E9003213605A609A680A4441 +:102170009A60002303604FF0FF33A36110BD026833 +:10218000234643F8102F53600022026022699A42CE +:1021900003D1BDE8104001F097BB936881680B4400 +:1021A000936001F081FB2269E1699268441AA242BE +:1021B000E4D91144BDE81040091AFFF753BF00BF2E +:1021C000402400202DE9F047DFF8BC8008F110071B +:1021D0002C4ED8F8105001F067FBD8F81C40AA68C4 +:1021E000031B9A423ED814444FF00009D5E900324F +:1021F000C8F81C4013605A60C5F80090D8F8103039 +:10220000B34201D101F060FB89F31188D5E90331B4 +:1022100028469847302383F311886B69002BD8D068 +:1022200001F042FB6A69A0EB040982464A450DD2DF +:10223000022001F097FB0022D8F81030B34208D1F9 +:1022400051462846BDE8F047FFF728BF121A22443E +:10225000F2E712EB09092946384638BF4A46FFF72C +:10226000EBFEB5E7D8F81030B34208D01444C8F8F4 +:102270001C00211AA960BDE8F047FFF7F3BEBDE8D6 +:10228000F08700BF50240020402400200020704729 +:10229000FEE70000704700004FF0FF30704700007D +:1022A00002290CD0032904D00129074818BF0020B7 +:1022B0007047032A05D8054800EBC2007047044860 +:1022C00070470020704700BFE84200083C22002011 +:1022D0009C42000870B59AB005460846144601A90C +:1022E00000F0C2F801A8FEF7F3FD431C0022C6B2BD +:1022F0005B001046C5E9003423700323023404F860 +:10230000013C01ABD1B202348E4201D81AB070BD8B +:1023100013F8011B013204F8010C04F8021CF1E768 +:1023200008B5302383F311880348FFF749FA0023E7 +:1023300083F3118808BD00BFB026002090F88030DC +:1023400003F01F02012A07D190F881200B2A03D144 +:102350000023C0E91D3315E003F06003202B08D1F2 +:10236000B0F884302BB990F88120212A03D81F2A95 +:1023700004D8FFF707BA222AEBD0FAE7034A4267EC +:1023800007228267C3670120704700BF3322002005 +:1023900007B5052917D8DFE801F019160319192028 +:1023A000302383F31188104A01210190FFF7B0FA1E +:1023B000019802210D4AFFF7ABFA0D48FFF7CCF95F +:1023C000002383F3118803B05DF804FB302383F30B +:1023D00011880748FFF796F9F2E7302383F3118855 +:1023E0000348FFF7ADF9EBE73C4200086042000804 +:1023F000B026002038B50C4D0C4C2A460C4904F18F +:102400000800FFF767FF05F1CA0204F1100009494F +:10241000FFF760FF05F5CA7204F118000649BDE830 +:102420003840FFF757BF00BF883F00203C22002004 +:102430001C420008264200083142000870B50446DC +:1024400008460D46FEF744FDC6B220460134037827 +:102450000BB9184670BD32462946FEF725FD002807 +:10246000F3D10120F6E700002DE9F84F05460C46B0 +:10247000FEF72EFD2A49C6B22846FFF7DFFF08B156 +:102480000136F6B227492846FFF7D8FF08B11036C3 +:10249000F6B2632E0DD8DFF88890DFF888A0224FBF +:1024A000DFF88CB0DFF88C802E7846B92670BDE856 +:1024B000F88F29462046BDE8F84F01F0E7BD252EEC +:1024C0002AD1072249462846FEF7EEFC50B9D8F833 +:1024D00000300735083444F8083CD8F8043044F894 +:1024E000043CE1E7082251462846FEF7DDFC98B996 +:1024F000A21C0E4B197802320909C95D02F8041CAE +:1025000013F8011B01F00F015B45C95D02F8031CC4 +:10251000F0D118340835C7E7013504F8016BC3E77B +:1025200008430008314200081943000800E8F11F81 +:102530000CE8F11F10430008BFF34F8F044B1A69DA +:102540005107FCD1D3F810215207F8D1704700BFD2 +:102550000020005208B50D4B1B78ABB9FFF7ECFF1C +:102560000B4BDA68D10704D50A4A5A6002F1883267 +:102570005A60D3F80C21D20706D5064AC3F80421C5 +:1025800002F18832C3F8042108BD00BFE6410020F3 +:10259000002000522301674508B5114B1B78F3B9A1 +:1025A000104B1A69510703D5DA6842F04002DA602D +:1025B000D3F81021520705D5D3F80C2142F0400280 +:1025C000C3F80C21FFF7B8FF064BDA6842F00102AE +:1025D000DA60D3F80C2142F00102C3F80C2108BDE7 +:1025E000E6410020002000520F289ABF00F58060CD +:1025F00040040020704700004FF400307047000096 +:10260000102070470F2808B50BD8FFF7EDFF00F535 +:1026100000330268013204D104308342F9D1012031 +:1026200008BD0020FCE700000F2838B505463FD85C +:10263000FFF782FF1F4CFFF78DFF4FF0FF33072896 +:102640006361C4F814311DD82361FFF775FF0302DD +:1026500043F02403E360E36843F08003E36023690D +:102660005A07FCD42846FFF767FFFFF7BDFF4FF47A +:10267000003100F0F5F82846FFF78EFFBDE838403E +:10268000FFF7C0BFC4F81031FFF756FFA0F10803F1 +:102690001B0243F02403C4F80C31D4F80C3143F08E +:1026A0008003C4F80C31D4F810315B07FBD4D9E7B0 +:1026B000002038BD002000522DE9F84F05460C4699 +:1026C000104645EA0203DE0602D00020BDE8F88F7E +:1026D00020F01F00DFF8BCB0DFF8BCA0FFF73AFF26 +:1026E00004EB0008444503D10120FFF755FFEDE757 +:1026F00020222946204601F0B9FC10B920352034AB +:10270000F0E72B4605F120021F68791CDDD1043368 +:102710009A42F9D105F178431B481C4EB3F5801F4E +:102720001B4B38BF184603F1F80332BFD946D146D8 +:102730001E46FFF701FF0760A5EB040C336804F1A8 +:102740001C0143F002033360231FD9F8007017F017 +:102750000507FAD153F8042F8B424CF80320F4D12B +:10276000BFF34F8FFFF7E8FE4FF0FF3320222146E3 +:1027700003602846336823F00203336001F076FCDF +:102780000028BBD03846B0E7142100520C2000527C +:1027900014200052102000521021005210B5084C95 +:1027A000237828B11BB9FFF7D5FE0123237010BD94 +:1027B000002BFCD02070BDE81040FFF7EDBE00BF3D +:1027C000E64100200244074BD2B210B5904200D13E +:1027D00010BD441C00B253F8200041F8040BE0B2D5 +:1027E000F4E700BF504000580E4B30B51C6F240476 +:1027F00005D41C6F1C671C6F44F400441C670A4C12 +:1028000002442368D2B243F480732360074B9042A2 +:1028100000D130BD441C51F8045B00B243F8205095 +:10282000E0B2F4E700440258004802585040005813 +:1028300007B5012201A90020FFF7C4FF019803B0EA +:102840005DF804FB13B50446FFF7F2FFA04205D084 +:10285000012201A900200194FFF7C6FF02B010BDBC +:102860000144BFF34F8F064B884204D3BFF34F8F11 +:10287000BFF36F8F7047C3F85C022030F4E700BFEE +:1028800000ED00E0034B1A681AB9034AD2F8D024CD +:102890001A607047E84100200040025808B5FFF771 +:1028A000F1FF024B1868C0F3806008BDE8410020CA +:1028B000EFF30983054968334A6B22F001024A634A +:1028C00083F30988002383F31188704700EF00E049 +:1028D000302080F3118862B60D4B0E4AD96821F47E +:1028E000E0610904090C0A430B49DA60D3F8FC20C3 +:1028F00042F08072C3F8FC20084AC2F8B01F116889 +:1029000041F0010111602022DA7783F8220070473C +:1029100000ED00E00003FA0555CEACC5001000E064 +:10292000302310B583F311880E4B5B6813F40063FA +:1029300014D0F1EE103AEFF309844FF08073683C45 +:10294000E361094BDB6B236684F30988FFF7BEFA6A +:1029500010B1064BA36110BD054BFBE783F3118853 +:10296000F9E700BF00ED00E000EF00E02F040008F1 +:102970003204000870B5BFF34F8FBFF36F8F1A4A50 +:102980000021C2F85012BFF34F8FBFF36F8F53690E +:1029900043F400335361BFF34F8FBFF36F8FC2F81F +:1029A0008410BFF34F8FD2F8803043F6E074C3F346 +:1029B000C900C3F34E335B0103EA0406014646EA4D +:1029C00081750139C2F86052F9D2203B13F1200F12 +:1029D000F2D1BFF34F8F536943F480335361BFF398 +:1029E0004F8FBFF36F8F70BD00ED00E0FEE700007A +:1029F000214B2248224A70B5904237D3214BC11E49 +:102A0000DA1C121A22F003028B4238BF0022002186 +:102A1000FEF766FA1C4A0023C2F88430BFF34F8FDA +:102A2000D2F8803043F6E074C3F3C900C3F34E33E9 +:102A30005B0103EA0406014646EA81750139C2F8E2 +:102A40006C52F9D2203B13F1200FF2D1BFF34F8F1C +:102A5000BFF36F8FBFF34F8FBFF36F8F0023C2F8A9 +:102A60005032BFF34F8FBFF36F8F70BD53F8041B0D +:102A700040F8041BC0E700BF04450008BC43002029 +:102A8000BC430020BC43002000ED00E0074BD3F81E +:102A9000D81021EA0001C3F8D810D3F8002122EAA7 +:102AA0000002C3F80021D3F80031704700440258F7 +:102AB00070B5D0E9244300224FF0FF359E6804EB47 +:102AC00042135101D3F80009002805DAD3F80009B0 +:102AD00040F08040C3F80009D3F8000B002805DA65 +:102AE000D3F8000B40F08040C3F8000B01326318AC +:102AF0009642C3F80859C3F8085BE0D24FF00113BF +:102B0000C4F81C3870BD0000890141F0200101614A +:102B100003699B06FCD41220FFF710BA10B50A4CCB +:102B20002046FEF7D3FE094BC4F89030084BC4F89A +:102B30009430084C2046FEF7C9FE074BC4F890308D +:102B4000064BC4F8943010BDEC4100200000084052 +:102B50005043000888420020000004405C43000805 +:102B600070B503780546012B5CD1434BD0F89040FB +:102B7000984258D1414B0E216520D3F8D82042F01D +:102B80000062C3F8D820D3F8002142F00062C3F8F5 +:102B90000021D3F80021D3F8802042F00062C3F86E +:102BA0008020D3F8802022F00062C3F88020D3F880 +:102BB0008030FEF7B7FC324BE360324BC4F800388C +:102BC0000023D5F89060C4F8003EC02323604FF482 +:102BD0000413A3633369002BFCDA01230C20336157 +:102BE000FFF7ACF93369DB07FCD41220FFF7A6F935 +:102BF0003369002BFCDA00262846A660FFF758FF51 +:102C00006B68C4F81068DB68C4F81468C4F81C6802 +:102C100083BB1D4BA3614FF0FF336361A36843F097 +:102C20000103A36070BD194B9842C9D1134B4FF0FB +:102C30008060D3F8D82042F00072C3F8D820D3F8CF +:102C4000002142F00072C3F80021D3F80021D3F82C +:102C5000802042F00072C3F88020D3F8802022F058 +:102C60000072C3F88020D3F88030FFF70FFF0E21E9 +:102C70004D209EE7064BCDE7EC4100200044025872 +:102C80004014004003002002003C30C08842002075 +:102C9000083C30C0F8B5D0F89040054600214FF010 +:102CA00000662046FFF730FFD5F8941000234FF060 +:102CB00001128F684FF0FF30C4F83438C4F81C2874 +:102CC00004EB431201339F42C2F80069C2F8006B63 +:102CD000C2F80809C2F8080BF2D20B68D5F89020A8 +:102CE000C5F89830636210231361166916F0100658 +:102CF000FBD11220FFF722F9D4F8003823F4FE6349 +:102D0000C4F80038A36943F4402343F01003A361DF +:102D10000923C4F81038C4F814380B4BEB604FF09B +:102D2000C043C4F8103B094BC4F8003BC4F8106919 +:102D3000C4F80039D5F8983003F1100243F4801339 +:102D4000C5F89820A362F8BD2C430008408000100D +:102D5000D0F8902090F88A10D2F8003823F4FE635F +:102D600043EA0113C2F80038704700002DE9F84328 +:102D700000EB8103D0F890500C468046DA680FFAD9 +:102D800081F94801166806F00306731E022B05EB55 +:102D900041134FF0000194BFB604384EC3F8101B26 +:102DA0004FF0010104F1100398BF06F1805601FABB +:102DB00003F3916998BF06F5004600293AD0578A77 +:102DC00004F15801374349016F50D5F81C180B43E3 +:102DD0000021C5F81C382B180127C3F81019A7408B +:102DE0005369611E9BB3138A928B9B08012A88BF8B +:102DF0005343D8F89820981842EA034301F140025F +:102E00002146C8F89800284605EB82025360FFF778 +:102E10007BFE08EB8900C3681B8A43EA845348346D +:102E20001E4364012E51D5F81C381F43C5F81C7889 +:102E3000BDE8F88305EB4917D7F8001B21F40041E2 +:102E4000C7F8001BD5F81C1821EA0303C0E704F1FA +:102E50003F030B4A2846214605EB83035A60FFF7E0 +:102E600053FE05EB4910D0F8003923F40043C0F8B5 +:102E70000039D5F81C3823EA0707D7E7008000108F +:102E800000040002D0F894201268C0F89820FFF7E0 +:102E90000FBE00005831D0F8903049015B5813F450 +:102EA000004004D013F4001F0CBF02200120704723 +:102EB0004831D0F8903049015B5813F4004004D0F9 +:102EC00013F4001F0CBF02200120704700EB8101AA +:102ED000CB68196A0B6813604B6853607047000039 +:102EE00000EB810330B5DD68AA691368D36019B9B6 +:102EF000402B84BF402313606B8A1468D0F8902065 +:102F00001C4402EB4110013C09B2B4FBF3F46343EF +:102F1000033323F0030343EAC44343F0C043C0F840 +:102F2000103B2B6803F00303012B0ED1D2F80838B5 +:102F300002EB411013F4807FD0F8003B14BF43F044 +:102F4000805343F00053C0F8003B02EB4112D2F82B +:102F5000003B43F00443C2F8003B30BD2DE9F04193 +:102F6000D0F8906005460C4606EB4113D3F8087B79 +:102F70003A07C3F8087B08D5D6F814381B0704D5E0 +:102F800000EB8103DB685B689847FA071FD5D6F82A +:102F90001438DB071BD505EB8403D968CCB98B69E2 +:102FA000488A5A68B2FBF0F600FB16228AB9186804 +:102FB000DA6890420DD2121AC3E90024302383F359 +:102FC000118821462846FFF78BFF84F31188BDE85E +:102FD000F081012303FA04F26B8923EA02036B8177 +:102FE000CB68002BF3D021462846BDE8F0411847B6 +:102FF00000EB81034A0170B5DD68D0F890306C6950 +:103000002668E66056BB1A444FF40020C2F8100947 +:103010002A6802F00302012A0AB20ED1D3F8080886 +:1030200003EB421410F4807FD4F8000914BF40F081 +:10303000805040F00050C4F8000903EB4212D2F86F +:10304000000940F00440C2F800090122D3F8340816 +:1030500002FA01F10143C3F8341870BD19B9402ECA +:1030600084BF4020206020681A442E8A8419013CC5 +:10307000B4FBF6F440EAC44040F00050C6E700005C +:103080002DE9F843D0F8906005460C464F0106EB59 +:103090004113D3F8088918F0010FC3F808891CD030 +:1030A000D6F81038DB0718D500EB8103D3F80CC035 +:1030B000DCF81430D3F800E0DA68964530D2A2EBA1 +:1030C0000E024FF000091A60C3F80490302383F316 +:1030D0001188FFF78DFF89F3118818F0800F1DD03C +:1030E000D6F834380126A640334217D005EB8403C6 +:1030F0000134D5F89050D3F80CC0E4B22F44DCF87A +:10310000142005EB0434D2F800E05168714514D363 +:10311000D5F8343823EA0606C5F83468BDE8F883E4 +:10312000012303FA01F2038923EA02030381DCF895 +:103130000830002BD1D09847CFE7AEEB0103BCF8A5 +:103140001000834228BF0346D7F8180980B2B3EBBA +:10315000800FE3D89068A0F1040959F8048FC4F8EF +:103160000080A0EB09089844B8F1040FF5D8184482 +:103170000B4490605360C8E72DE9F84FD0F89050A9 +:1031800004466E69AB691E4016F480586E6103D028 +:10319000BDE8F84FFEF70ABC002E12DAD5F8003E63 +:1031A0009B0705D0D5F8003E23F00303C5F8003E89 +:1031B000D5F80438204623F00103C5F80438FEF79B +:1031C00023FC370505D52046FFF772FC2046FEF7A5 +:1031D00009FCB0040CD5D5F8083813F0060FEB68DD +:1031E00023F470530CBF43F4105343F4A053EB602B +:1031F00031071BD56368DB681BB9AB6923F0080393 +:10320000AB612378052B0CD1D5F8003E9A0705D089 +:10321000D5F8003E23F00303C5F8003E2046FEF734 +:10322000F3FB6368DB680BB120469847F30200F1BB +:10323000BA80B70226D5D4F8909000274FF0010A43 +:1032400009EB4712D2F8003B03F44023B3F5802F7B +:1032500011D1D2F8003B002B0DDA62890AFA07F38C +:1032600022EA0303638104EB8703DB68DB6813B1A5 +:103270003946204698470137D4F89430FFB29B680E +:103280009F42DDD9F00619D5D4F89000026AC2F346 +:103290000A1702F00F0302F4F012B2F5802F00F0CB +:1032A000CA80B2F5402F09D104EB8303002200F558 +:1032B0008050DB681B6A974240F0B0803003D5F83D +:1032C000185835D5E90303D500212046FFF746FEFF +:1032D000AA0303D501212046FFF740FE6B0303D567 +:1032E00002212046FFF73AFE2F0303D50321204693 +:1032F000FFF734FEE80203D504212046FFF72EFE37 +:10330000A90203D505212046FFF728FE6A0203D54E +:1033100006212046FFF722FE2B0203D50721204677 +:10332000FFF71CFEEF0103D508212046FFF716FE2C +:10333000700340F1A780E90703D500212046FFF77D +:103340009FFEAA0703D501212046FFF799FE6B07D0 +:1033500003D502212046FFF793FE2F0703D5032153 +:103360002046FFF78DFEEE0603D504212046FFF729 +:1033700087FEA80603D505212046FFF781FE6906D2 +:1033800003D506212046FFF77BFE2A0603D5072139 +:103390002046FFF775FEEB0574D520460821BDE8F1 +:1033A000F84FFFF76DBED4F890904FF0000B4FF040 +:1033B000010AD4F894305FFA8BF79B689F423FF67E +:1033C00038AF09EB4713D3F8002902F44022B2F5D5 +:1033D000802F20D1D3F80029002A1CDAD3F8002945 +:1033E00042F09042C3F80029D3F80029002AFBDB01 +:1033F0003946D4F89000FFF787FB22890AFA07F3D1 +:1034000022EA0303238104EB8703DB689B6813B183 +:103410003946204698470BF1010BCAE7910701D1C5 +:10342000D0F80080072A02F101029CBF03F8018B4B +:103430004FEA18283FE704EB830300F58050DA6871 +:10344000D2F818C0DCF80820DCE9001CA1EB0C0C59 +:1034500000218F4208D1DB689B699A683A449A60E0 +:103460005A683A445A6029E711F0030F01D1D0F8A5 +:1034700000808C4501F1010184BF02F8018B4FEA05 +:103480001828E6E7BDE8F88F08B50348FFF774FE93 +:10349000BDE80840FFF744BAEC41002008B50348F6 +:1034A000FFF76AFEBDE80840FFF73ABA88420020FD +:1034B000D0F8903003EB4111D1F8003B43F40013F6 +:1034C000C1F8003B70470000D0F8903003EB411189 +:1034D000D1F8003943F40013C1F8003970470000F7 +:1034E000D0F8903003EB4111D1F8003B23F40013E6 +:1034F000C1F8003B70470000D0F8903003EB411159 +:10350000D1F8003923F40013C1F8003970470000E6 +:1035100030B50433039C0172002104FB0325C16014 +:10352000C0E90653049B0363059BC0E90000C0E9A2 +:103530000422C0E90842C0E90A11436330BD00001B +:103540000022416AC260C0E90411C0E90A226FF09A +:103550000101FEF763BD0000D0E90432934201D1BE +:10356000C2680AB9181D70470020704703691960C6 +:103570000021C2680132C260C26913448269934269 +:10358000036124BF436A0361FEF73CBD38B50446BE +:103590000D46E3683BB162690020131D1268A36207 +:1035A0001344E36207E0237A33B929462046FEF745 +:1035B00019FD0028EDDA38BD6FF00100FBE70000CF +:1035C000C368C269013BC360436913448269934283 +:1035D000436124BF436A436100238362036B03B1E9 +:1035E0001847704770B53023044683F31188866A04 +:1035F0003EB9FFF7CBFF054618B186F31188284680 +:1036000070BDA36AE26A13F8015B9342A36202D31E +:103610002046FFF7D5FF002383F31188EFE7000072 +:103620002DE9F84F04460E46174698464FF03009EC +:1036300089F311880025AA46D4F828B0BBF1000F01 +:1036400009D141462046FFF7A1FF20B18BF3118835 +:103650002846BDE8F88FD4E90A12A7EB050B521AE9 +:10366000934528BF9346BBF1400F1BD9334601F168 +:10367000400251F8040B914243F8040BF9D1A36ABC +:10368000403640354033A362D4E90A239A4202D33C +:103690002046FFF795FF8AF31188BD42D8D289F3FF +:1036A0001188C9E730465A46FDF7F4FBA36A5E4429 +:1036B0005D445B44A362E7E710B5029C04330172EA +:1036C00003FB0421C460C0E906130023C0E90A33E8 +:1036D000039B0363049BC0E90000C0E90422C0E926 +:1036E0000842436310BD0000026A6FF00101C2602E +:1036F000426AC0E904220022C0E90A22FEF78EBC19 +:10370000D0E904239A4201D1C26822B9184650F880 +:10371000043B0B60704700231846FAE7C36800219A +:10372000C2690133C36043691344826993424361B0 +:1037300024BF436A4361FEF765BC000038B5044608 +:103740000D46E3683BB1236900201A1DA262E269BD +:103750001344E36207E0237A33B929462046FEF793 +:1037600041FC0028EDDA38BD6FF00100FBE70000F6 +:1037700003691960C268013AC260C2691344826970 +:103780009342036124BF436A036100238362036B96 +:1037900003B118477047000070B530230D4604464A +:1037A000114683F31188866A2EB9FFF7C7FF10B15F +:1037B00086F3118870BDA36A1D70A36AE26A0133A3 +:1037C0009342A36204D3E16920460439FFF7D0FF96 +:1037D000002080F31188EDE72DE9F84F04460D46EF +:1037E000904699464FF0300A8AF311880026B34676 +:1037F000A76A4FB949462046FFF7A0FF20B187F3DB +:1038000011883046BDE8F88FD4E90A073A1AA8EBC8 +:103810000607974228BF1746402F1BD905F14003E2 +:1038200055F8042B9D4240F8042BF9D1A36A403689 +:103830004033A362D4E90A239A4204D3E1692046C3 +:103840000439FFF795FF8BF311884645D9D28AF3E7 +:103850001188CDE729463A46FDF71CFBA36A3D4493 +:103860003E443B44A362E5E7D0E904239A4217D1E2 +:10387000C3689BB1836A8BB1043B9B1A0ED0136063 +:10388000C368013BC360C3691A4483699A420261F9 +:1038900024BF436A036100238362012318467047F3 +:1038A0000023FBE700F024B9014B586A704700BFC2 +:1038B000000C0040034B002258631A610222DA60B8 +:1038C000704700BF000C0040014B0022DA607047D7 +:1038D000000C0040014B5863704700BF000C0040D3 +:1038E000FEE7000070B51B4B0025044686B058600B +:1038F0000E4685620163FEF7EBFF04F11003A5603D +:10390000E562C4E904334FF0FF33C4E90044C4E97D +:103910000635FFF7C9FF2B46024604F13401204665 +:10392000C4E9082380230C4A2565FEF711FB012317 +:103930000A4AE06000920375684672680192B268B4 +:10394000CDE90223064BCDE90435FEF729FB06B08D +:1039500070BD00BFA8260020684300086D43000822 +:10396000E1380008024AD36A1843D062704700BFAA +:10397000402400204B6843608B688360CB68C36041 +:103980000B6943614B6903628B6943620B68036097 +:103990007047000008B53C4B40F2FF713B48D3F83C +:1039A00088200A43C3F88820D3F8882022F4FF62D5 +:1039B00022F00702C3F88820D3F88820D3F8E0204B +:1039C0000A43C3F8E020D3F808210A43C3F80821CA +:1039D0002F4AD3F808311146FFF7CCFF00F580607D +:1039E00002F11C01FFF7C6FF00F5806002F138010B +:1039F000FFF7C0FF00F5806002F15401FFF7BAFF46 +:103A000000F5806002F17001FFF7B4FF00F58060FF +:103A100002F18C01FFF7AEFF00F5806002F1A80112 +:103A2000FFF7A8FF00F5806002F1C401FFF7A2FFD5 +:103A300000F5806002F1E001FFF79CFF00F5806077 +:103A400002F1FC01FFF796FF02F58C7100F5806032 +:103A5000FFF790FF00F018F90E4BD3F8902242F0D8 +:103A60000102C3F89022D3F8942242F00102C3F875 +:103A700094220522C3F898204FF06052C3F89C208E +:103A8000054AC3F8A02008BD0044025800000258AF +:103A90007443000800ED00E01F00080308B500F0C3 +:103AA000C7FAFEF733FA0F4BD3F8DC2042F040029E +:103AB000C3F8DC20D3F8042122F04002C3F804212B +:103AC000D3F80431084B1A6842F008021A601A68E9 +:103AD00042F004021A60FEF7D5FEBDE80840FEF78A +:103AE00089BC00BF0044025800180248704700001B +:103AF000114BD3F8E82042F00802C3F8E820D3F8CD +:103B0000102142F00802C3F810210C4AD3F81031FA +:103B1000D36B43F00803D363C722094B9A624FF07B +:103B2000FF32DA6200229A615A63DA605A60012237 +:103B30005A611A60704700BF004402580010005CD0 +:103B4000000C0040094A08B51169D3680B40D9B28E +:103B50009B076FEA0101116107D5302383F31188B8 +:103B6000FEF7EAF9002383F3118808BD000C00403A +:103B7000064BD3F8DC200243C3F8DC20D3F8042141 +:103B80001043C3F80401D3F80431704700440258CD +:103B900008B53C4B4FF0FF31D3F8802062F0004273 +:103BA000C3F88020D3F8802002F00042C3F88020C0 +:103BB000D3F88020D3F88420C3F88410D3F884206D +:103BC0000022C3F88420D3F88400D86F40F0FF406F +:103BD00040F4FF0040F4DF4040F07F00D867D86F2A +:103BE00020F0FF4020F4FF0020F4DF4020F07F00B1 +:103BF000D867D86FD3F888006FEA40506FEA50500A +:103C0000C3F88800D3F88800C0F30A00C3F888001E +:103C1000D3F88800D3F89000C3F89010D3F8900040 +:103C2000C3F89020D3F89000D3F89400C3F8941010 +:103C3000D3F89400C3F89420D3F89400D3F89800F4 +:103C4000C3F89810D3F89800C3F89820D3F89800D8 +:103C5000D3F88C00C3F88C10D3F88C00C3F88C20F8 +:103C6000D3F88C00D3F89C00C3F89C10D3F89C10B8 +:103C7000C3F89C20D3F89C30FDF778FBBDE80840E2 +:103C800000F0AEB90044025808B50122534BC3F806 +:103C90000821534BD3F8F42042F00202C3F8F42079 +:103CA000D3F81C2142F00202C3F81C210222D3F8EF +:103CB0001C314C4BDA605A689104FCD54A4A1A60B0 +:103CC00001229A60494ADA6000221A614FF44042A8 +:103CD0009A61444B9A699204FCD51A6842F4807246 +:103CE0001A603F4B1A6F12F4407F04D04FF48032B9 +:103CF0001A6700221A671A6842F001021A60384BEC +:103D00001A685007FCD500221A611A6912F03802AD +:103D1000FBD1012119604FF0804159605A67344A44 +:103D2000DA62344A1A611A6842F480321A602C4B03 +:103D30001A689103FCD51A6842F480521A601A6816 +:103D40009204FCD52C4A2D499A6200225A631963C9 +:103D500001F57C01DA6301F2E71199635A64284A9C +:103D60001A64284ADA621A6842F0A8521A601C4B98 +:103D70001A6802F02852B2F1285FF9D148229A61FC +:103D80004FF48862DA6140221A621F4ADA641F4ADD +:103D90001A651F4A5A651F4A9A6532231E4A1360E4 +:103DA000136803F00F03022BFAD10D4A136943F095 +:103DB00003031361136903F03803182BFAD14FF092 +:103DC0000050FFF7D5FE4FF08040FFF7D1FE4FF0D7 +:103DD0000040BDE80840FFF7CBBE00BF00800051A7 +:103DE000004402580048025800C000F002000001E0 +:103DF0000000FF01008890082220400063020901B2 +:103E0000470E0508DD0BBF01200000200000011057 +:103E10000910E00000010110002000524FF0B042F4 +:103E200008B5D2F8883003F00103C2F8883023B116 +:103E3000044A13680BB150689847BDE80840FEF784 +:103E40006FBD00BF3C4300204FF0B04208B5D2F830 +:103E5000883003F00203C2F8883023B1044A936823 +:103E60000BB1D0689847BDE80840FEF759BD00BFC8 +:103E70003C4300204FF0B04208B5D2F8883003F040 +:103E80000403C2F8883023B1044A13690BB15069A6 +:103E90009847BDE80840FEF743BD00BF3C43002003 +:103EA0004FF0B04208B5D2F8883003F00803C2F8EA +:103EB000883023B1044A93690BB1D0699847BDE8B3 +:103EC0000840FEF72DBD00BF3C4300204FF0B0423C +:103ED00008B5D2F8883003F01003C2F8883023B157 +:103EE000044A136A0BB1506A9847BDE80840FEF7D0 +:103EF00017BD00BF3C4300204FF0B04310B5D3F8CE +:103F0000884004F47872C3F88820A30604D5124AC6 +:103F1000936A0BB1D06A9847600604D50E4A136BBA +:103F20000BB1506B9847210604D50B4A936B0BB12C +:103F3000D06B9847E20504D5074A136C0BB1506C5F +:103F40009847A30504D5044A936C0BB1D06C9847ED +:103F5000BDE81040FEF7E4BC3C4300204FF0B04306 +:103F600010B5D3F8884004F47C42C3F88820620579 +:103F700004D5164A136D0BB1506D9847230504D52F +:103F8000124A936D0BB1D06D9847E00404D50F4AE7 +:103F9000136E0BB1506E9847A10404D50B4A936E73 +:103FA0000BB1D06E9847620404D5084A136F0BB169 +:103FB000506F9847230404D5044A936F0BB1D06F18 +:103FC0009847BDE81040FEF7ABBC00BF3C43002063 +:103FD00008B5FFF7B7FDBDE80840FEF7A1BC00003B +:103FE000062108B50846FDF79DFA06210720FDF7D2 +:103FF00099FA06210820FDF795FA06210920FDF718 +:1040000091FA06210A20FDF78DFA06211720FDF707 +:1040100089FA06212820FDF785FA09217A20FDF783 +:1040200081FA07213220BDE80840FDF77BBA000085 +:1040300008B5FFF7ADFD00F00BF8FDF745FCFDF707 +:1040400017FBFFF753FDBDE80840FFF72BBC00004E +:104050000023054A19460133102BC2E9001102F171 +:104060000802F8D1704700BF3C43002010B5013969 +:104070000244904201D1002005E0037811F8014F7D +:10408000A34201D0181B10BD0130F2E7034611F81E +:10409000012B03F8012B002AF9D1704753544D33FB +:1040A0003248373F3F3F0053544D3332483733781F +:1040B0002F3732780053544D3332483734332F374B +:1040C00035332F373530000001105A0003105900E6 +:1040D0000120580003205600100002400800024052 +:1040E0000008024000000B002800024008000240C7 +:1040F0000408024006010C00400002400800024093 +:104100000808024010020D0058000240080002405A +:104110000C08024016030E00700002400C00024022 +:104120001008024000040F00880002400C0002400A +:104130001408024006051000A00002400C000240D6 +:104140001808024010061100B80002400C0002409E +:104150001C08024016072F00100402400804024009 +:1041600020080240000838002804024008040240E9 +:1041700024080240060939004004024008040240B5 +:1041800028080240100A3A0058040240080402407D +:104190002C080240160B3B00700402400C04024045 +:1041A00030080240000C3C00880402400C0402402D +:1041B00034080240060D4400A00402400C040240F2 +:1041C00038080240100E4500B80402400C040240BA +:1041D0003C080240160F460000000000ED150008E4 +:1041E000D915000815160008011600080D1600085C +:1041F000F9150008E5150008D1150008211600087A +:10420000000000000100000000000000633000001A +:104210000C42000898240020A826002041726475F2 +:1042200050696C6F740025424F415244252D424C19 +:10423000002553455249414C250000000200000072 +:10424000000000000D1800087D1800084000400024 +:10425000583F0020683F00200200000000000000DE +:104260000300000000000000C51800080000000066 +:1042700010000000783F0020000000000100000056 +:1042800000000000EC410020010102009123000821 +:10429000A12200083D23000821230008430000005C +:1042A000A442000809024300020100C032090400D0 +:1042B0000001020201000524001001052401000193 +:1042C000042402020524060001070582030800FFFA +:1042D00009040100020A0000000705010240000075 +:1042E000070581024000000012000000F0420008B3 +:1042F00012011001020000400912415700020102A0 +:10430000030100000403090425424F4152442500E3 +:104310004E7874505834763200303132333435367A +:104320003738394142434445460000000000000050 +:10433000211A0008D91C0008851D00084000400013 +:1043400024430020244300200100000034430020C7 +:104350008000000040010000080000000001000093 +:1043600000100000080000006D61696E0069646C57 +:10437000650000005000802A00000000AAAAAAAA36 +:1043800050000024FFFF00000000000000A00A0011 +:104390000000004000000000AAAAAAAA0000000035 +:1043A000FFFF0000000000000000000010000004FB +:1043B00000000000AAAAAAAA10000004FFFF000043 +:1043C00000000000000000000000400000000000AD +:1043D000AAAAAAAA00000000FFFF00000000000037 +:1043E000000000000000000000000000AAAAAAAA25 +:1043F00000000000FFFF00000000000000000000BF +:104400000000000000000000AAAAAAAA0000000004 +:10441000FFFF00000000000000000000000000009E +:1044200000000000AAAAAAAA00000000FFFF0000E6 +:10443000000000000000000000000000000000007C +:10444000AAAAAAAA00000000FFFF000000000000C6 +:10445000000000000000000000000000AAAAAAAAB4 +:1044600000000000FFFF000000000000000000004E +:104470000000000000000000AAAAAAAA0000000094 +:10448000FFFF00000000000000000000000000002E +:1044900000000000AAAAAAAA00000000FFFF000076 +:1044A0000000000000000000870400000000000081 +:1044B00000001A0000000000FF00000000000000E3 +:1044C0009C40000883040000A7400008500400003E +:1044D000B5400008009600000000080096000000AB +:1044E0000008000004000000044300080000000071 +:1044F00000000000000000000000000000000000BC +:0445000000000000B7 +:00000001FF diff --git a/Tools/bootloaders/PixPilot-V6PRO_bl.bin b/Tools/bootloaders/PixPilot-V6PRO_bl.bin new file mode 100644 index 00000000000000..97647e212e6347 Binary files /dev/null and b/Tools/bootloaders/PixPilot-V6PRO_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin b/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin index 1275617bf45113..44d0703b4d9178 100755 Binary files a/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin and b/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin differ diff --git a/Tools/bootloaders/SDMODELH7V2_bl.bin b/Tools/bootloaders/SDMODELH7V2_bl.bin new file mode 100644 index 00000000000000..7746ebe826e789 Binary files /dev/null and b/Tools/bootloaders/SDMODELH7V2_bl.bin differ diff --git a/Tools/bootloaders/SDMODELH7V2_bl.hex b/Tools/bootloaders/SDMODELH7V2_bl.hex new file mode 100644 index 00000000000000..f74bb98df819fe --- /dev/null +++ b/Tools/bootloaders/SDMODELH7V2_bl.hex @@ -0,0 +1,1104 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200088528000854 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008F13D00081D3E00082D +:10006000493E0008753E0008A13E000885100008C2 +:10007000AD100008D9100008051100083111000862 +:100080005911000885110008E3020008E302000886 +:10009000E3020008E3020008E3020008CD3E000886 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000313F0008E3020008E3020008E3020008D1 +:1000F000E3020008E3020008E3020008B11100086F +:10010000E3020008E3020008A53F0008E30200083C +:10011000E3020008E3020008E3020008E30200082B +:10012000DD11000805120008311200085D120008F8 +:1001300089120008E3020008E3020008E302000855 +:10014000E3020008E3020008E3020008E3020008FB +:10015000B1120008DD12000809130008E3020008CC +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000871340008E3020008E30200080B +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200085D340008E3020008E3020008BF +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0FCFA78 +:1003500003F00AFB4FF055301F491B4A91423CBF46 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F014FB03F068FBE2 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0FCBA00060020002200206E +:1003D0000000000808ED00E00000002000060020FA +:1003E00080440008002200205C22002060220020BF +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0AEFDFEE701F04C +:100430003DFD00DFFEE7000038B500F02FFC00F0C6 +:10044000B5FD02F0DFF9054602F012FA0446C0B924 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0D6F90CB100F06A +:1004700075F800F06FFD284600F01EF900F06EF8E8 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F02BFE0023154A4FF4C7 +:1004D0007A71134801F01AFE002383F31188124C3D +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F092FC322363602B78032B07D16368E1 +:100510002BB9022000F088FC4FF47A73636038BD79 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F067BC022000F05CBC024B0022DD +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0AAFB0220FFF7CBFF454B0021D3F868 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0EDFBB14AAE +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F01BFD0023AB4A4FF4E6 +:1006F0007A71A94801F00AFD002383F31188009B59 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F075FB24B19C4B1B6856 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F05DFB039B213B1F2B04 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F04BFA0421059005A800F00EFAF8 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F062FB26B10BF033 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F01AFA0220FFF73BFE1FFA86F84046C6 +:1008C00000F022FA0446B0B1039940460136A1F186 +:1008D00040025142514100F027FA0028EDD1BA46BA +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0F0F9013040F06F +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F03CFA019AFF217F4800F05DFA4FEADF +:1009F000A803C8F387027C492846019300F05CFAFB +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0A2F90C +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F001FB8046E7E7384600F046F92E +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F05DF90590E6E70023642104A8BE +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F04BF9EAE70B +:100AC0000220FFF7E5FC00283FF48CAE00F05AF955 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F055F907460421049004A800F0F2 +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0DAF80421059005A800F095 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F007F9002844D00A9B01330BD0BE +:100B600008220AA9002000F0A7F900283AD0202284 +:100B7000FF210AA800F098F9FFF792FC1C4801F049 +:100B800009FA13B0BDE8F08F002E3FF42BAE0BF046 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0E7F9059800F0EEF946463C461A +:100BD00000F0B6F9A6E506464EE64FF0000901E63C +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0B2F981 +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B5104C50 +:100CA0000025104E01F096FC208030682388834296 +:100CB0000CD800252088013801F088FC23880544E1 +:100CC000013BB5F5802F2380F4D370BD01F07EFC8D +:100CD000336805440133B5F5003F3360E5D3E8E7F9 +:100CE000B62300208823002001F042BD00F10060FF +:100CF00000F500300068704700F10060920000F5D8 +:100D0000003001F0C3BC0000054B1A68054B1B887E +:100D10009B1A834202D9104401F058BC002070474E +:100D200088230020B623002038B50446074D29B19A +:100D300028682044BDE8384001F060BC28682044A1 +:100D400001F04AFC0028F3D038BD00BF8823002002 +:100D50000020704700F1FF5000F58F10D0F8000818 +:100D600070470000064991F8243033B1002308226F +:100D7000086A81F82430FFF7BFBF0120704700BF29 +:100D80008C230020014B1868704700BF0010005CE6 +:100D9000194B01380322084470B51D68174BC5F381 +:100DA0000B042D0C1E88A6420BD15C680A46013C40 +:100DB000824213460FD214F9016F4EB102F8016B53 +:100DC000F6E7013A03F10803ECD181420B4602D267 +:100DD0002C2203F8012B0424094A1688AE4204D1C0 +:100DE000984284BF967803F8016B013C02F104023B +:100DF000F3D1581A70BD00BF0010005C142200200F +:100E00009C400008022802D1014B04229A617047DD +:100E100000080258022803D1024B4FF480229A6145 +:100E2000704700BF00080258022804D1024A5369E3 +:100E300083F00403536170470008025870B50446FC +:100E40004FF47A764CB1412C254628BF412506FB4C +:100E500005F0641B01F09EF8F4E770BD002310B5A7 +:100E6000934203D0CC5CC4540133F9E710BD0000B9 +:100E7000013810B510F9013F3BB191F900409C4297 +:100E800003D11AB10131013AF4E71AB191F9002006 +:100E9000981A10BD1046FCE703460246D01A12F914 +:100EA000011B0029FAD1704702440346934202D045 +:100EB00003F8011BFAE770472DE9F8431F4D14466C +:100EC0000746884695F8242052BBDFF870909CB303 +:100ED00095F824302BB92022FF2148462F62FFF7D6 +:100EE000E3FF95F824004146C0F1080205EB8000BD +:100EF000A24228BF2246D6B29200FFF7AFFF95F874 +:100F00002430A41B17441E449044E4B2F6B2082EC9 +:100F100085F82460DBD1FFF725FF0028D7D108E052 +:100F20002B6A03EB82038342CFD0FFF71BFF00281D +:100F3000CBD10020BDE8F8830120FBE78C23002003 +:100F4000024B1A78024B1A70704700BFB42300207E +:100F50001022002010B5114C114800F06FFB214603 +:100F60000F4800F097FB24684FF47A70D4F8902073 +:100F7000D2F8043843F00203C2F80438FFF75EFFEA +:100F80000849204600F094FCD4F89020D2F80438A8 +:100F900023F00203C2F8043810BD00BF5842000815 +:100FA000B02600206042000870470000F0B5A1B0F4 +:100FB00071B600230120002480261A46194600F04D +:100FC0004BFA4FF4D067214A3D25136923BBD2F871 +:100FD00010310BBB036804F1006199600368C3F82A +:100FE0000CD003685E6003681F6001680B6843F003 +:100FF00001030B6001680B6823F01E030B6001689E +:101000000B68DB07FCD4037B8034416805FA03F3EB +:10101000B4F5001F0B60D8D100F05EFAB4F5001FE4 +:1010200011D000240A4E0B4D012001F0A1FB3388A2 +:10103000A34205D928682044013401F0DFFAF6E71D +:10104000002001F095FB61B621B0F0BD00200052F8 +:10105000B62300208823002030B50A44084D914271 +:101060000DD011F8013B5840082340F30004013B28 +:101070002C4013F0FF0384EA5000F6D1EFE730BDB7 +:101080002083B8ED08B5074B074A196801F03D0108 +:10109000996053680BB190689847BDE8084001F02B +:1010A00029BC00BF00000240B823002008B5084B4F +:1010B0001968890901F03D018A019A60054AD368DF +:1010C0000BB110699847BDE8084001F013BC00BFA0 +:1010D00000000240B823002008B5084B1968090C2D +:1010E00001F03D010A049A60054A53690BB1906909 +:1010F0009847BDE8084001F0FDBB00BF000002407A +:10110000B823002008B5084B1968890D01F03D018E +:101110008A059A60054AD3690BB1106A9847BDE801 +:10112000084001F0E7BB00BF00000240B8230020E8 +:1011300008B5074B074A596801F03D01D960536A69 +:101140000BB1906A9847BDE8084001F0D3BB00BFDF +:1011500000000240B823002008B5084B59688909EF +:1011600001F03D018A01DA60054AD36A0BB1106BC8 +:101170009847BDE8084001F0BDBB00BF0000024039 +:10118000B823002008B5084B5968090C01F03D014F +:101190000A04DA60054A536B0BB1906B9847BDE8BF +:1011A000084001F0A7BB00BF00000240B8230020A8 +:1011B00008B5084B5968890D01F03D018A05DA60D0 +:1011C000054AD36B0BB1106C9847BDE8084001F09D +:1011D00091BB00BF00000240B823002008B5074BB8 +:1011E000074A196801F03D019960536C0BB1906C8E +:1011F0009847BDE8084001F07DBB00BF00040240F5 +:10120000B823002008B5084B1968890901F03D0191 +:101210008A019A60054AD36C0BB1106D9847BDE8FE +:10122000084001F067BB00BF00040240B823002063 +:1012300008B5084B1968090C01F03D010A049A60D1 +:10124000054A536D0BB1906D9847BDE8084001F019 +:1012500051BB00BF00040240B823002008B5084B72 +:101260001968890D01F03D018A059A60054AD36D20 +:101270000BB1106E9847BDE8084001F03BBB00BFC2 +:1012800000040240B823002008B5074B074A5968FC +:1012900001F03D01D960536E0BB1906E9847BDE8E7 +:1012A000084001F027BB00BF00040240B823002023 +:1012B00008B5084B5968890901F03D018A01DA60D7 +:1012C000054AD36E0BB1106F9847BDE8084001F096 +:1012D00011BB00BF00040240B823002008B5084B32 +:1012E0005968090C01F03D010A04DA60054A536FA0 +:1012F0000BB1906F9847BDE8084001F0FBBA00BF02 +:1013000000040240B823002008B5084B5968890D35 +:1013100001F03D018A05DA60054AD36F13B1D2F8B6 +:1013200080009847BDE8084001F0E4BA000402409C +:10133000B823002000230C4910B51A460B4C0B6053 +:1013400054F82300026001EB430004334260402B59 +:10135000F6D1074A4FF0FF339360D360C2F80834E8 +:10136000C2F80C3410BD00BFB8230020AC40000808 +:10137000000002400F28F8B510D9102810D011280D +:1013800011D0122808D10F240720DFF8C8E0012669 +:10139000DEF80050A04208D9002653E00446F4E7E6 +:1013A0000F240020F1E70724FBE706FA00F73D428F +:1013B0004AD1264C4FEA001C3D4304EB00160EEBCD +:1013C000C000CEF80050C0E90123FBB273B1204841 +:1013D000D0F8D83043F00103C0F8D830D0F800314D +:1013E00043F00103C0F80031D0F8003117F47F4F0B +:1013F0000ED01748D0F8D83043F00203C0F8D830E8 +:10140000D0F8003143F00203C0F80031D0F80031C9 +:1014100054F80C00036823F01F030360056815F0FF +:101420000105FBD104EB0C033D2493F80CC05F686D +:1014300004FA0CF43C6021240560446112B1987BED +:1014400000F054F83046F8BD0130A3E7AC40000886 +:1014500000440258B823002010B5302484F31188CA +:10146000FFF788FF002383F3118810BD10B50446F1 +:10147000807B00F051F801231549627B03FA02F2E8 +:101480000B6823EA0203DAB20B6072B9114AD2F890 +:10149000D81021F00101C2F8D810D2F8001121F0C3 +:1014A0000101C2F80011D2F8002113F47F4F0ED1D0 +:1014B000084BD3F8D82022F00202C3F8D820D3F882 +:1014C000002122F00202C3F80021D3F8003110BD40 +:1014D000B82300200044025808B5302383F3118854 +:1014E000FFF7C4FF002383F3118808BD090100F151 +:1014F0006043012203F56143C9B283F8001300F091 +:101500001F039A4043099B0003F1604303F56143C5 +:10151000C3F880211A60704700F01F0301229A402F +:10152000430900F160409B0000F5614003F1604316 +:1015300003F56143C3F88020C3F88021002380F8BD +:1015400000337047026843681143016003B11847D4 +:101550007047000013B5406B00F58054D4F8A438F0 +:101560001A681178042914D1017C022911D1197942 +:10157000012312898B4013420BD101A94C3002F098 +:10158000A9F8D4F8A4480246019B2179206800F00C +:10159000DFF902B010BD0000143002F02BB80000DB +:1015A0004FF0FF33143002F025B800004C3002F049 +:1015B000FDB800004FF0FF334C3002F0F7B80000E8 +:1015C000143001F0F9BF00004FF0FF31143001F08A +:1015D000F3BF00004C3002F0C9B800004FF0FF32FA +:1015E0004C3002F0C3B800000020704710B500F581 +:1015F0008054D4F8A4381A681178042917D1017CD2 +:10160000022914D15979012352898B4013420ED1FA +:10161000143001F08BFF024648B1D4F8A4484FF4CF +:10162000407361792068BDE8104000F07FB910BDBB +:10163000406BFFF7DBBF0000704700007FB5124B27 +:1016400001250426044603600023057400F184028A +:1016500043602946C0E902330C4B029014300193D9 +:101660004FF44073009601F03DFF094B04F694429D +:10167000294604F14C000294CDE900634FF4407315 +:1016800002F004F804B070BDAC4100083116000847 +:10169000551500080A68302383F311880B790B3342 +:1016A00042F823004B79133342F823008B7913B1AE +:1016B0000B3342F8230000F58053C3F8A41802232B +:1016C0000374002080F311887047000038B5037F51 +:1016D000044613B190F85430ABB90125201D022106 +:1016E000FFF730FF04F114006FF00101257700F0DF +:1016F00079FC04F14C0084F854506FF00101BDE80E +:10170000384000F06FBC38BD10B5012104460430EC +:10171000FFF718FF0023237784F8543010BD000032 +:1017200038B504460025143001F0F4FE04F14C00F5 +:10173000257701F0C3FF201D84F854500121FFF7E5 +:1017400001FF2046BDE83840FFF750BF90F88030D9 +:1017500003F06003202B06D190F881200023212A7A +:1017600003D81F2A06D800207047222AFBD1C0E9DF +:101770001D3303E0034A426707228267C3670120E3 +:10178000704700BF2C22002037B500F58055D5F8F2 +:10179000A4381A68117804291AD1017C022917D1BA +:1017A0001979012312898B40134211D100F14C04A5 +:1017B000204602F043F858B101A9204601F08AFF03 +:1017C000D5F8A4480246019B2179206800F0C0F8B2 +:1017D00003B030BD01F10B03F0B550F8236085B0C4 +:1017E00004460D46FEB1302383F3118804EB8507D0 +:1017F000301D0821FFF7A6FEFB6806F14C005B696F +:101800001B681BB1019001F073FF019803A901F05F +:1018100061FF024648B1039B2946204600F098F834 +:10182000002383F3118805B0F0BDFB685A69126884 +:10183000002AF5D01B8A013B1340F1D104F180024C +:10184000EAE70000133138B550F82140ECB13023FD +:1018500083F3118804F58053D3F8A42813685279D0 +:1018600003EB8203DB689B695D6845B10421601866 +:10187000FFF768FE294604F1140001F061FE2046DE +:10188000FFF7B4FE002383F3118838BD70470000D2 +:1018900001F02EB901234022002110B5044600F8C2 +:1018A000303BFFF701FB0023C4E9013310BD00000A +:1018B00010B53023044683F31188242241600021AF +:1018C0000C30FFF7F1FA204601F034F90223002032 +:1018D000237080F3118810BD70B500EB81030546BD +:1018E00050690E461446DA6018B110220021FFF745 +:1018F000DBFAA06918B110220021FFF7D5FA3146B2 +:101900002846BDE8704001F01BBA00008368202221 +:10191000002103F0011310B5044683601030FFF777 +:10192000C3FA2046BDE8104001F096BAF0B4012594 +:1019300000EB810447898D40E4683D43A4694581FB +:1019400023600023A2606360F0BC01F0B3BA000022 +:10195000F0B4012500EB810407898D40E4683D4324 +:101960006469058123600023A2606360F0BC01F01C +:1019700029BB000070B50223002504462422037011 +:101980002946C0F888500C3040F8045CFFF78CFA08 +:10199000204684F8705001F067F963681B6823B132 +:1019A00029462046BDE87040184770BD0378052BD6 +:1019B00010B504460AD080F88C30052303704368C4 +:1019C0001B680BB1042198470023A36010BD0000E1 +:1019D0000178052906D190F88C20436802701B68B5 +:1019E00003B118477047000070B590F87030044696 +:1019F00013B1002380F8703004F18002204601F01A +:101A00004FFA63689B68B3B994F8803013F06005AF +:101A100035D00021204601F041FD0021204601F093 +:101A200031FD63681B6813B10621204698470623E1 +:101A300084F8703070BD204698470028E4D0B4F890 +:101A40008630A26F9A4288BFA36794F98030A56F51 +:101A5000002B4FF0300380F20381002D00F0F28064 +:101A6000092284F8702083F3118800212046D4E9EC +:101A70001D23FFF76DFF002383F31188DAE794F845 +:101A8000812003F07F0343EA022340F202329342B3 +:101A900000F0C58021D8B3F5807F48D00DD8012B48 +:101AA0003FD0022B00F09380002BB2D104F18802CA +:101AB00062670222A267E367C1E7B3F5817F00F0A6 +:101AC0009B80B3F5407FA4D194F88230012BA0D144 +:101AD000B4F8883043F0020332E0B3F5006F4DD024 +:101AE00017D8B3F5A06F31D0A3F5C063012B90D800 +:101AF0006368204694F882205E6894F88310B4F8F6 +:101B00008430B047002884D0436863670368A367C4 +:101B10001AE0B3F5106F36D040F6024293427FF4DC +:101B200078AF5C4B63670223A3670023C3E794F895 +:101B30008230012B7FF46DAFB4F8883023F00203BC +:101B4000A4F88830C4E91D55E56778E7B4F880301B +:101B5000B3F5A06F0ED194F88230204684F88A3015 +:101B600001F0E0F863681B6813B101212046984733 +:101B7000032323700023C4E91D339CE704F18B0386 +:101B800063670123C3E72378042B10D1302383F349 +:101B900011882046FFF7BAFE85F311880321636898 +:101BA00084F88B5021701B680BB12046984794F83D +:101BB0008230002BDED084F88B30042323706368DE +:101BC0001B68002BD6D0022120469847D2E794F814 +:101BD000843020461D0603F00F010AD501F052F9AA +:101BE000012804D002287FF414AF2B4B9AE72B4B2B +:101BF00098E701F039F9F3E794F88230002B7FF48D +:101C000008AF94F8843013F00F01B3D01A062046C1 +:101C100002D501F05BFCADE701F04CFCAAE794F8BB +:101C20008230002B7FF4F5AE94F8843013F00F016E +:101C3000A0D01B06204602D501F030FC9AE701F047 +:101C400021FC97E7142284F8702083F311882B4637 +:101C50002A4629462046FFF769FE85F31188E9E602 +:101C60005DB1152284F8702083F31188002120468D +:101C7000D4E91D23FFF75AFEFDE60B2284F87020FD +:101C800083F311882B462A4629462046FFF760FE3B +:101C9000E3E700BFDC410008D4410008D841000858 +:101CA00038B590F870300446002B3ED0063BDAB2CF +:101CB0000F2A34D80F2B32D8DFE803F03731310840 +:101CC000223231313131313131313737856FB0F82E +:101CD00086309D4214D2C3681B8AB5FBF3F203FB26 +:101CE00012556DB9302383F311882B462A462946B5 +:101CF000FFF72EFE85F311880A2384F870300EE07A +:101D0000142384F87030302383F311880023204695 +:101D10001A461946FFF70AFE002383F3118838BDDF +:101D2000C36F03B198470023E7E70021204601F085 +:101D3000B5FB0021204601F0A5FB63681B6813B1C9 +:101D40000621204698470623D7E7000010B590F8F3 +:101D500070300446142B29D017D8062B05D001D893 +:101D60001BB110BD093B022BFBD80021204601F01E +:101D700095FB0021204601F085FB63681B6813B1C9 +:101D8000062120469847062319E0152BE9D10B239D +:101D900080F87030302383F3118800231A461946E7 +:101DA000FFF7D6FD002383F31188DAE7C3689B6948 +:101DB0005B68002BD5D1C36F03B19847002384F82B +:101DC0007030CEE700238268037503691B68996849 +:101DD0009142FBD25A6803604260106058607047BD +:101DE00000238268037503691B6899689142FBD8D8 +:101DF0005A680360426010605860704708B5084632 +:101E0000302383F311880B7D032B05D0042B0DD0D9 +:101E10002BB983F3118808BD8B6900221A604FF03B +:101E2000FF338361FFF7CEFF0023F2E7D1E90032F1 +:101E300013605A60F3E70000FFF7C4BF054BD96891 +:101E400008751868026853601A600122D86002752C +:101E5000FEF7D8BA402400200C4B30B5DD684B1C8F +:101E600087B004460FD02B46094A684600F04EF969 +:101E70002046FFF7E3FF009B13B1684600F050F9DE +:101E8000A86907B030BDFFF7D9FFF9E7402400206B +:101E9000FD1D0008044B1A68DB6890689B68984237 +:101EA00094BF00200120704740240020084B10B54B +:101EB0001C68D868226853601A600122DC602275B1 +:101EC000FFF78EFF01462046BDE81040FEF79ABAA4 +:101ED0004024002038B5074C012300250649074857 +:101EE0002370656001F0E8FC0223237085F31188FC +:101EF00038BD00BFA8260020E4410008402400208F +:101F000000F044B9034A516853685B1A9842FBD801 +:101F1000704700BF001000E08B6002230861084694 +:101F20008B8270478368A3F1840243F8142C026902 +:101F300043F8442C426943F8402C094A43F8242CC6 +:101F4000C268A3F1200043F8182C022203F80C2CDD +:101F5000002203F80B2C034A43F8102C704700BFF3 +:101F60001D0400084024002008B5FFF7DBFFBDE892 +:101F70000840FFF761BF0000024BDB6898610F204B +:101F8000FFF75CBF40240020302383F31188FFF764 +:101F9000F3BF000008B50146302383F31188082001 +:101FA000FFF75AFF002383F3118808BD064BDB6857 +:101FB00039B1426818605A60136043600420FFF72B +:101FC0004BBF4FF0FF307047402400200368984219 +:101FD00006D01A680260506018469961FFF72CBF5E +:101FE0007047000038B504460D462068844200D191 +:101FF00038BD036823605C608561FFF71DFFF4E76F +:10200000036810B59C68A2420CD85C688A600B60BB +:102010004C602160596099688A1A9A604FF0FF33CA +:10202000836010BD121B1B68ECE700000A2938BF53 +:102030000A2170B504460D460A26601901F034FCE9 +:1020400001F01CFC041BA54203D8751C04462E4657 +:10205000F3E70A2E04D90120BDE8704001F06CBC02 +:1020600070BD0000F8B5144B0D460A2A4FF00A0760 +:10207000D96103F11001826038BF0A2241601969F9 +:102080001446016048601861A81801F0FDFB01F0DA +:10209000F5FB431B0646A34206D37C1C28192746A2 +:1020A000354601F001FCF2E70A2F04D90120BDE812 +:1020B000F84001F041BCF8BD40240020F8B50646C8 +:1020C0000D4601F0DBFB0F4A134653F8107F9F4289 +:1020D00006D12A4601463046BDE8F840FFF7C2BFA8 +:1020E000D169BB68441A2C1928BF2C46A34202D9D7 +:1020F0002946FFF79BFF224631460348BDE8F840DA +:10210000FFF77EBF4024002050240020C0E90323B5 +:10211000002310B45DF8044B4361FFF7CFBF00000C +:1021200010B5194C236998420DD08168D0E900326E +:1021300013605A609A680A449A60002303604FF063 +:10214000FF33A36110BD0268234643F8102F53608C +:102150000022026022699A4203D1BDE8104001F0DA +:102160009DBB936881680B44936001F087FB2269F3 +:10217000E1699268441AA242E4D91144BDE81040D2 +:10218000091AFFF753BF00BF402400202DE9F04794 +:10219000DFF8BC8008F110072C4ED8F8105001F081 +:1021A0006DFBD8F81C40AA68031B9A423ED8144421 +:1021B0004FF00009D5E90032C8F81C4013605A609E +:1021C000C5F80090D8F81030B34201D101F066FB99 +:1021D00089F31188D5E9033128469847302383F3E2 +:1021E00011886B69002BD8D001F048FB6A69A0EB1D +:1021F000040982464A450DD2022001F09DFB0022CF +:10220000D8F81030B34208D151462846BDE8F0470F +:10221000FFF728BF121A2244F2E712EB09092946F8 +:10222000384638BF4A46FFF7EBFEB5E7D8F810301E +:10223000B34208D01444C8F81C00211AA960BDE8B4 +:10224000F047FFF7F3BEBDE8F08700BF5024002041 +:102250004024002000207047FEE700007047000087 +:102260004FF0FF307047000002290CD0032904D042 +:102270000129074818BF00207047032A05D80548E0 +:1022800000EBC2007047044870470020704700BF51 +:10229000BC4200083C2200207042000870B59AB091 +:1022A00005460846144601A900F0C2F801A8FEF749 +:1022B000F3FD431C0022C6B25B001046C5E90034A2 +:1022C00023700323023404F8013C01ABD1B2023481 +:1022D0008E4201D81AB070BD13F8011B013204F808 +:1022E000010C04F8021CF1E708B5302383F31188D0 +:1022F0000348FFF749FA002383F3118808BD00BFA4 +:10230000B026002090F8803003F01F02012A07D188 +:1023100090F881200B2A03D10023C0E91D3315E07A +:1023200003F06003202B08D1B0F884302BB990F86B +:102330008120212A03D81F2A04D8FFF707BA222AAE +:10234000EBD0FAE7034A426707228267C36701209E +:10235000704700BF3322002007B5052917D8DFE8F2 +:1023600001F0191603191920302383F31188104A3C +:1023700001210190FFF7B0FA019802210D4AFFF701 +:10238000ABFA0D48FFF7CCF9002383F3118803B0B3 +:102390005DF804FB302383F311880748FFF796F9B3 +:1023A000F2E7302383F311880348FFF7ADF9EBE739 +:1023B0001042000834420008B026002038B50C4D09 +:1023C0000C4C2A460C4904F10800FFF767FF05F1A1 +:1023D000CA0204F110000949FFF760FF05F5CA724F +:1023E00004F118000649BDE83840FFF757BF00BFA9 +:1023F000883F00203C220020F0410008FA410008FC +:102400000542000870B5044608460D46FEF744FD37 +:10241000C6B22046013403780BB9184670BD324667 +:102420002946FEF725FD0028F3D10120F6E700003C +:102430002DE9F84F05460C46FEF72EFD2D49C6B294 +:102440002846FFF7DFFF08B10436F6B22A492846CE +:10245000FFF7D8FF08B11036F6B2632E0DD8DFF8BB +:102460009490DFF894A0DFF89C80DFF89CB0234FB5 +:102470002E7846B92670BDE8F88F29462046BDE87B +:10248000F84F01F0EDBD252E30D1072249462846F0 +:10249000FEF7EEFC70B93B6807350B3444F80B3C93 +:1024A0007B6844F8073C3B8924F8033CBB7A04F87A +:1024B000013CDDE7082251462846FEF7D9FCA8B9C1 +:1024C000A21C0F4B19780232090911F8081002F802 +:1024D000041C13F8011B01F00F015B4511F80810F3 +:1024E00002F8031CEED118340835C1E7013504F8B1 +:1024F000016BBDE7DC42000805420008E442000829 +:1025000000E8F11FF04200080CE8F11FBFF34F8F05 +:10251000044B1A695107FCD1D3F810215207F8D1A6 +:10252000704700BF0020005208B50D4B1B78ABB9B7 +:10253000FFF7ECFF0B4BDA68D10704D50A4A5A6063 +:1025400002F188325A60D3F80C21D20706D5064A28 +:10255000C3F8042102F18832C3F8042108BD00BF8A +:10256000E6410020002000522301674508B5114BC9 +:102570001B78F3B9104B1A69510703D5DA6842F09A +:102580004002DA60D3F81021520705D5D3F80C21A8 +:1025900042F04002C3F80C21FFF7B8FF064BDA689F +:1025A00042F00102DA60D3F80C2142F00102C3F8D4 +:1025B0000C2108BDE6410020002000520F289ABFE0 +:1025C00000F5806040040020704700004FF40030A8 +:1025D00070470000102070470F2808B50BD8FFF790 +:1025E000EDFF00F500330268013204D1043083426C +:1025F000F9D1012008BD0020FCE700000F2838B504 +:1026000005463FD8FFF782FF1F4CFFF78DFF4FF0C5 +:10261000FF3307286361C4F814311DD82361FFF725 +:1026200075FF030243F02403E360E36843F0800393 +:10263000E36023695A07FCD42846FFF767FFFFF7DA +:10264000BDFF4FF4003100F0F5F82846FFF78EFF8C +:10265000BDE83840FFF7C0BFC4F81031FFF756FFA0 +:10266000A0F108031B0243F02403C4F80C31D4F892 +:102670000C3143F08003C4F80C31D4F810315B07FF +:10268000FBD4D9E7002038BD002000522DE9F84FD7 +:1026900005460C46104645EA0203DE0602D000203D +:1026A000BDE8F88F20F01F00DFF8BCB0DFF8BCA059 +:1026B000FFF73AFF04EB0008444503D10120FFF780 +:1026C00055FFEDE720222946204601F0B9FC10B95C +:1026D00020352034F0E72B4605F120021F68791CD5 +:1026E000DDD104339A42F9D105F178431B481C4EE1 +:1026F000B3F5801F1B4B38BF184603F1F80332BFF8 +:10270000D946D1461E46FFF701FF0760A5EB040C32 +:10271000336804F11C0143F002033360231FD9F82E +:10272000007017F00507FAD153F8042F8B424CF8CC +:102730000320F4D1BFF34F8FFFF7E8FE4FF0FF33D4 +:102740002022214603602846336823F002033360C9 +:1027500001F076FC0028BBD03846B0E714210052C7 +:102760000C20005214200052102000521021005260 +:1027700010B5084C237828B11BB9FFF7D5FE01230B +:10278000237010BD002BFCD02070BDE81040FFF777 +:10279000EDBE00BFE64100200244074BD2B210B5A7 +:1027A000904200D110BD441C00B253F8200041F803 +:1027B000040BE0B2F4E700BF504000580E4B30B5B8 +:1027C0001C6F240405D41C6F1C671C6F44F4004468 +:1027D0001C670A4C02442368D2B243F4807323601E +:1027E000074B904200D130BD441C51F8045B00B24D +:1027F00043F82050E0B2F4E7004402580048025881 +:102800005040005807B5012201A90020FFF7C4FF7E +:10281000019803B05DF804FB13B50446FFF7F2FF1F +:10282000A04205D0012201A900200194FFF7C6FFB4 +:1028300002B010BD0144BFF34F8F064B884204D352 +:10284000BFF34F8FBFF36F8F7047C3F85C02203028 +:10285000F4E700BF00ED00E0034B1A681AB9034A21 +:10286000D2F8D0241A607047E84100200040025896 +:1028700008B5FFF7F1FF024B1868C0F3806008BD90 +:10288000E8410020EFF30983054968334A6B22F0E1 +:1028900001024A6383F30988002383F31188704798 +:1028A00000EF00E0302080F3118862B60D4B0E4A35 +:1028B000D96821F4E0610904090C0A430B49DA6084 +:1028C000D3F8FC2042F08072C3F8FC20084AC2F81A +:1028D000B01F116841F0010111602022DA7783F8FE +:1028E0002200704700ED00E00003FA0555CEACC5AC +:1028F000001000E0302310B583F311880E4B5B68A5 +:1029000013F4006314D0F1EE103AEFF309844FF0A2 +:102910008073683CE361094BDB6B236684F30988B1 +:10292000FFF7B8FA10B1064BA36110BD054BFBE7EA +:1029300083F31188F9E700BF00ED00E000EF00E04D +:102940002F0400083204000870B5BFF34F8FBFF3A7 +:102950006F8F1A4A0021C2F85012BFF34F8FBFF396 +:102960006F8F536943F400335361BFF34F8FBFF34D +:102970006F8FC2F88410BFF34F8FD2F8803043F6C8 +:10298000E074C3F3C900C3F34E335B0103EA0406EA +:10299000014646EA81750139C2F86052F9D2203BFE +:1029A00013F1200FF2D1BFF34F8F536943F48033FB +:1029B0005361BFF34F8FBFF36F8F70BD00ED00E029 +:1029C000FEE70000214B2248224A70B5904237D3DF +:1029D000214BC11EDA1C121A22F003028B4238BFAF +:1029E00000220021FEF760FA1C4A0023C2F884305E +:1029F000BFF34F8FD2F8803043F6E074C3F3C900C1 +:102A0000C3F34E335B0103EA0406014646EA8175CF +:102A10000139C2F86C52F9D2203B13F1200FF2D1E8 +:102A2000BFF34F8FBFF36F8FBFF34F8FBFF36F8F26 +:102A30000023C2F85032BFF34F8FBFF36F8F70BDCA +:102A400053F8041B40F8041BC0E700BFDC44000837 +:102A5000BC430020BC430020BC43002000ED00E04C +:102A6000074BD3F8D81021EA0001C3F8D810D3F8E7 +:102A7000002122EA0002C3F80021D3F80031704798 +:102A80000044025870B5D0E9244300224FF0FF35CE +:102A90009E6804EB42135101D3F80009002805DABF +:102AA000D3F8000940F08040C3F80009D3F8000BC8 +:102AB000002805DAD3F8000B40F08040C3F8000B83 +:102AC000013263189642C3F80859C3F8085BE0D294 +:102AD0004FF00113C4F81C3870BD0000890141F0AB +:102AE0002001016103699B06FCD41220FFF70ABA9A +:102AF00010B50A4C2046FEF7CDFE094BC4F89030C5 +:102B0000084BC4F89430084C2046FEF7C3FE074B30 +:102B1000C4F89030064BC4F8943010BDEC4100204E +:102B200000000840284300088842002000000440BC +:102B30003443000870B503780546012B5CD1434B44 +:102B4000D0F89040984258D1414B0E216520D3F8DF +:102B5000D82042F00062C3F8D820D3F8002142F018 +:102B60000062C3F80021D3F80021D3F8802042F09E +:102B70000062C3F88020D3F8802022F00062C3F8FE +:102B80008020D3F88030FEF7B1FC324BE360324B4B +:102B9000C4F800380023D5F89060C4F8003EC02384 +:102BA00023604FF40413A3633369002BFCDA012381 +:102BB0000C203361FFF7A6F93369DB07FCD4122040 +:102BC000FFF7A0F93369002BFCDA00262846A6603F +:102BD000FFF758FF6B68C4F81068DB68C4F8146826 +:102BE000C4F81C6883BB1D4BA3614FF0FF336361C6 +:102BF000A36843F00103A36070BD194B9842C9D18B +:102C0000134B4FF08060D3F8D82042F00072C3F825 +:102C1000D820D3F8002142F00072C3F80021D3F885 +:102C20000021D3F8802042F00072C3F88020D3F84E +:102C3000802022F00072C3F88020D3F88030FFF7A4 +:102C40000FFF0E214D209EE7064BCDE7EC41002003 +:102C5000004402584014004003002002003C30C0F1 +:102C600088420020083C30C0F8B5D0F890400546B6 +:102C700000214FF000662046FFF730FFD5F8941092 +:102C800000234FF001128F684FF0FF30C4F8343842 +:102C9000C4F81C2804EB431201339F42C2F80069B8 +:102CA000C2F8006BC2F80809C2F8080BF2D20B6830 +:102CB000D5F89020C5F89830636210231361166927 +:102CC00016F01006FBD11220FFF71CF9D4F80038DB +:102CD00023F4FE63C4F80038A36943F4402343F0AF +:102CE0001003A3610923C4F81038C4F814380B4B3F +:102CF000EB604FF0C043C4F8103B094BC4F8003BF5 +:102D0000C4F81069C4F80039D5F8983003F11002FE +:102D100043F48013C5F89820A362F8BD044300086B +:102D200040800010D0F8902090F88A10D2F8003837 +:102D300023F4FE6343EA0113C2F800387047000031 +:102D40002DE9F84300EB8103D0F890500C46804603 +:102D5000DA680FFA81F94801166806F00306731E57 +:102D6000022B05EB41134FF0000194BFB604384E1F +:102D7000C3F8101B4FF0010104F1100398BF06F1D6 +:102D8000805601FA03F3916998BF06F500460029C1 +:102D90003AD0578A04F15801374349016F50D5F8AA +:102DA0001C180B430021C5F81C382B180127C3F849 +:102DB0001019A7405369611E9BB3138A928B9B081D +:102DC000012A88BF5343D8F89820981842EA034351 +:102DD00001F140022146C8F89800284605EB82021E +:102DE0005360FFF77BFE08EB8900C3681B8A43EA48 +:102DF000845348341E4364012E51D5F81C381F43B8 +:102E0000C5F81C78BDE8F88305EB4917D7F8001B17 +:102E100021F40041C7F8001BD5F81C1821EA030370 +:102E2000C0E704F13F030B4A2846214605EB830324 +:102E30005A60FFF753FE05EB4910D0F8003923F430 +:102E40000043C0F80039D5F81C3823EA0707D7E754 +:102E50000080001000040002D0F894201268C0F82E +:102E60009820FFF70FBE00005831D0F8903049018C +:102E70005B5813F4004004D013F4001F0CBF022071 +:102E8000012070474831D0F8903049015B5813F465 +:102E9000004004D013F4001F0CBF02200120704733 +:102EA00000EB8101CB68196A0B6813604B685360B3 +:102EB0007047000000EB810330B5DD68AA69136834 +:102EC000D36019B9402B84BF402313606B8A146808 +:102ED000D0F890201C4402EB4110013C09B2B4FB35 +:102EE000F3F46343033323F0030343EAC44343F09F +:102EF000C043C0F8103B2B6803F00303012B0ED135 +:102F0000D2F8083802EB411013F4807FD0F8003B70 +:102F100014BF43F0805343F00053C0F8003B02EB72 +:102F20004112D2F8003B43F00443C2F8003B30BDED +:102F30002DE9F041D0F8906005460C4606EB4113B0 +:102F4000D3F8087B3A07C3F8087B08D5D6F81438BD +:102F50001B0704D500EB8103DB685B689847FA0721 +:102F60001FD5D6F81438DB071BD505EB8403D968C9 +:102F7000CCB98B69488A5A68B2FBF0F600FB16227E +:102F80008AB91868DA6890420DD2121AC3E900248F +:102F9000302383F3118821462846FFF78BFF84F303 +:102FA0001188BDE8F081012303FA04F26B8923EA5A +:102FB00002036B81CB68002BF3D021462846BDE885 +:102FC000F041184700EB81034A0170B5DD68D0F885 +:102FD00090306C692668E66056BB1A444FF40020B6 +:102FE000C2F810092A6802F00302012A0AB20ED1BF +:102FF000D3F8080803EB421410F4807FD4F80009DA +:1030000014BF40F0805040F00050C4F8000903EBBA +:103010004212D2F8000940F00440C2F8000901222F +:10302000D3F8340802FA01F10143C3F8341870BD33 +:1030300019B9402E84BF4020206020681A442E8A8F +:103040008419013CB4FBF6F440EAC44040F000505F +:10305000C6E700002DE9F843D0F8906005460C461D +:103060004F0106EB4113D3F8088918F0010FC3F89C +:1030700008891CD0D6F81038DB0718D500EB81037F +:10308000D3F80CC0DCF81430D3F800E0DA689645C9 +:1030900030D2A2EB0E024FF000091A60C3F8049080 +:1030A000302383F31188FFF78DFF89F3118818F01F +:1030B000800F1DD0D6F834380126A640334217D0F1 +:1030C00005EB84030134D5F89050D3F80CC0E4B27A +:1030D0002F44DCF8142005EB0434D2F800E05168EA +:1030E000714514D3D5F8343823EA0606C5F8346898 +:1030F000BDE8F883012303FA01F2038923EA0203FE +:103100000381DCF80830002BD1D09847CFE7AEEB35 +:103110000103BCF81000834228BF0346D7F8180902 +:1031200080B2B3EB800FE3D89068A0F1040959F89E +:10313000048FC4F80080A0EB09089844B8F1040F8C +:10314000F5D818440B4490605360C8E72DE9F84F58 +:10315000D0F8905004466E69AB691E4016F4805852 +:103160006E6103D0BDE8F84FFEF704BC002E12DA02 +:10317000D5F8003E9B0705D0D5F8003E23F00303A9 +:10318000C5F8003ED5F80438204623F00103C5F801 +:103190000438FEF71DFC370505D52046FFF772FC05 +:1031A0002046FEF703FCB0040CD5D5F8083813F020 +:1031B000060FEB6823F470530CBF43F4105343F431 +:1031C000A053EB6031071BD56368DB681BB9AB69A3 +:1031D00023F00803AB612378052B0CD1D5F8003E12 +:1031E0009A0705D0D5F8003E23F00303C5F8003E4A +:1031F0002046FEF7EDFB6368DB680BB1204698477D +:10320000F30200F1BA80B70226D5D4F890900027D7 +:103210004FF0010A09EB4712D2F8003B03F44023B8 +:10322000B3F5802F11D1D2F8003B002B0DDA628963 +:103230000AFA07F322EA0303638104EB8703DB68DE +:10324000DB6813B13946204698470137D4F89430EB +:10325000FFB29B689F42DDD9F00619D5D4F89000E3 +:10326000026AC2F30A1702F00F0302F4F012B2F579 +:10327000802F00F0CA80B2F5402F09D104EB830300 +:10328000002200F58050DB681B6A974240F0B08056 +:103290003003D5F8185835D5E90303D50021204669 +:1032A000FFF746FEAA0303D501212046FFF740FEA3 +:1032B0006B0303D502212046FFF73AFE2F0303D507 +:1032C00003212046FFF734FEE80203D504212046FF +:1032D000FFF72EFEA90203D505212046FFF728FEA1 +:1032E0006A0203D506212046FFF722FE2B0203D5F2 +:1032F00007212046FFF71CFEEF0103D508212046D9 +:10330000FFF716FE700340F1A780E90703D50021FF +:103310002046FFF79FFEAA0703D501212046FFF7AD +:1033200099FE6B0703D502212046FFF793FE2F0776 +:1033300003D503212046FFF78DFEEE0603D50421B9 +:103340002046FFF787FEA80603D505212046FFF794 +:1033500081FE690603D506212046FFF77BFE2A067B +:1033600003D507212046FFF775FEEB0574D52046EF +:103370000821BDE8F84FFFF76DBED4F890904FF0EC +:10338000000B4FF0010AD4F894305FFA8BF79B687A +:103390009F423FF638AF09EB4713D3F8002902F4F8 +:1033A0004022B2F5802F20D1D3F80029002A1CDA60 +:1033B000D3F8002942F09042C3F80029D3F800293D +:1033C000002AFBDB3946D4F89000FFF787FB2289FF +:1033D0000AFA07F322EA0303238104EB8703DB687D +:1033E0009B6813B13946204698470BF1010BCAE799 +:1033F000910701D1D0F80080072A02F101029CBF99 +:1034000003F8018B4FEA18283FE704EB830300F52C +:103410008050DA68D2F818C0DCF80820DCE9001C1B +:10342000A1EB0C0C00218F4208D1DB689B699A68E4 +:103430003A449A605A683A445A6029E711F0030FF7 +:1034400001D1D0F800808C4501F1010184BF02F860 +:10345000018B4FEA1828E6E7BDE8F88F08B5034866 +:10346000FFF774FEBDE80840FFF744BAEC410020C6 +:1034700008B50348FFF76AFEBDE80840FFF73ABA0F +:1034800088420020D0F8903003EB4111D1F8003B86 +:1034900043F40013C1F8003B70470000D0F89030AF +:1034A00003EB4111D1F8003943F40013C1F800399E +:1034B00070470000D0F8903003EB4111D1F8003B89 +:1034C00023F40013C1F8003B70470000D0F890309F +:1034D00003EB4111D1F8003923F40013C1F800398E +:1034E0007047000030B50433039C0172002104FBD7 +:1034F0000325C160C0E90653049B0363059BC0E933 +:103500000000C0E90422C0E90842C0E90A1143638F +:1035100030BD00000022416AC260C0E90411C0E968 +:103520000A226FF00101FEF75DBD0000D0E9043210 +:10353000934201D1C2680AB9181D70470020704734 +:10354000036919600021C2680132C260C269134474 +:1035500082699342036124BF436A0361FEF736BD6B +:1035600038B504460D46E3683BB162690020131D7F +:103570001268A3621344E36207E0237A33B9294651 +:103580002046FEF713FD0028EDDA38BD6FF001008C +:10359000FBE70000C368C269013BC3604369134491 +:1035A00082699342436124BF436A4361002383627B +:1035B000036B03B11847704770B53023044683F39B +:1035C0001188866A3EB9FFF7CBFF054618B186F32E +:1035D0001188284670BDA36AE26A13F8015B934222 +:1035E000A36202D32046FFF7D5FF002383F311889F +:1035F000EFE700002DE9F84F04460E4617469846BF +:103600004FF0300989F311880025AA46D4F828B074 +:10361000BBF1000F09D141462046FFF7A1FF20B1C1 +:103620008BF311882846BDE8F88FD4E90A12A7EB7E +:10363000050B521A934528BF9346BBF1400F1BD987 +:10364000334601F1400251F8040B914243F8040B58 +:10365000F9D1A36A403640354033A362D4E90A2346 +:103660009A4202D32046FFF795FF8AF31188BD42A4 +:10367000D8D289F31188C9E730465A46FDF7EEFBE8 +:10368000A36A5E445D445B44A362E7E710B5029C15 +:103690000433017203FB0421C460C0E90613002354 +:1036A000C0E90A33039B0363049BC0E90000C0E93F +:1036B0000422C0E90842436310BD0000026A6FF0B3 +:1036C0000101C260426AC0E904220022C0E90A2264 +:1036D000FEF788BCD0E904239A4201D1C26822B91E +:1036E000184650F8043B0B60704700231846FAE771 +:1036F000C3680021C2690133C3604369134482690E +:103700009342436124BF436A4361FEF75FBC0000FC +:1037100038B504460D46E3683BB1236900201A1D05 +:10372000A262E2691344E36207E0237A33B92946CF +:103730002046FEF73BFC0028EDDA38BD6FF00100B3 +:10374000FBE7000003691960C268013AC260C26900 +:10375000134482699342036124BF436A03610023D7 +:103760008362036B03B118477047000070B53023C4 +:103770000D460446114683F31188866A2EB9FFF779 +:10378000C7FF10B186F3118870BDA36A1D70A36ACC +:10379000E26A01339342A36204D3E169204604390B +:1037A000FFF7D0FF002080F31188EDE72DE9F84FF7 +:1037B00004460D46904699464FF0300A8AF3118828 +:1037C0000026B346A76A4FB949462046FFF7A0FF37 +:1037D00020B187F311883046BDE8F88FD4E90A0795 +:1037E0003A1AA8EB0607974228BF1746402F1BD965 +:1037F00005F1400355F8042B9D4240F8042BF9D104 +:10380000A36A40364033A362D4E90A239A4204D320 +:10381000E16920460439FFF795FF8BF3118846458F +:10382000D9D28AF31188CDE729463A46FDF716FB2F +:10383000A36A3D443E443B44A362E5E7D0E9042348 +:103840009A4217D1C3689BB1836A8BB1043B9B1A20 +:103850000ED01360C368013BC360C3691A44836917 +:103860009A42026124BF436A0361002383620123F9 +:10387000184670470023FBE700F024B9014B586A53 +:10388000704700BF000C0040034B002258631A61D0 +:103890000222DA60704700BF000C0040014B00229A +:1038A000DA607047000C0040014B5863704700BF5E +:1038B000000C0040FEE7000070B51B4B00250446DD +:1038C00086B058600E4685620163FEF7EBFF04F197 +:1038D0001003A560E562C4E904334FF0FF33C4E987 +:1038E0000044C4E90635FFF7C9FF2B46024604F140 +:1038F00034012046C4E9082380230C4A2565FEF7DD +:103900000BFB01230A4AE060009203756846726867 +:103910000192B268CDE90223064BCDE90435FEF7EA +:1039200023FB06B070BD00BFA8260020404300085E +:1039300045430008B5380008024AD36A1843D062EC +:10394000704700BF402400204B6843608B68836051 +:10395000CB68C3600B6943614B6903628B69436247 +:103960000B6803607047000008B53C4B40F2FF71E4 +:103970003B48D3F888200A43C3F88820D3F888202E +:1039800022F4FF6222F00702C3F88820D3F88820CF +:10399000D3F8E0200A43C3F8E020D3F808210A4313 +:1039A000C3F808212F4AD3F808311146FFF7CCFF9E +:1039B00000F5806002F11C01FFF7C6FF00F5806092 +:1039C00002F13801FFF7C0FF00F5806002F15401F9 +:1039D000FFF7BAFF00F5806002F17001FFF7B4FF56 +:1039E00000F5806002F18C01FFF7AEFF00F580600A +:1039F00002F1A801FFF7A8FF00F5806002F1C40101 +:103A0000FFF7A2FF00F5806002F1E001FFF79CFFE5 +:103A100000F5806002F1FC01FFF796FF02F58C7162 +:103A200000F58060FFF790FF00F018F90E4BD3F817 +:103A3000902242F00102C3F89022D3F8942242F07F +:103A40000102C3F894220522C3F898204FF0605277 +:103A5000C3F89C20054AC3F8A02008BD00440258C2 +:103A6000000002584C43000800ED00E01F0008036E +:103A700008B500F0C7FAFEF72DFA0F4BD3F8DC209B +:103A800042F04002C3F8DC20D3F8042122F04002C7 +:103A9000C3F80421D3F80431084B1A6842F0080235 +:103AA0001A601A6842F004021A60FEF7D5FEBDE8FB +:103AB0000840FEF783BC00BF0044025800180248CB +:103AC00070470000114BD3F8E82042F00802C3F819 +:103AD000E820D3F8102142F00802C3F810210C4A64 +:103AE000D3F81031D36B43F00803D363C722094BDB +:103AF0009A624FF0FF32DA6200229A615A63DA600A +:103B00005A6001225A611A60704700BF004402588F +:103B10000010005C000C0040094A08B51169D36828 +:103B20000B40D9B29B076FEA0101116107D5302321 +:103B300083F31188FEF7E4F9002383F3118808BDAD +:103B4000000C0040064BD3F8DC200243C3F8DC2015 +:103B5000D3F804211043C3F80401D3F804317047AB +:103B60000044025808B53C4B4FF0FF31D3F8802099 +:103B700062F00042C3F88020D3F8802002F00042B7 +:103B8000C3F88020D3F88020D3F88420C3F88410B1 +:103B9000D3F884200022C3F88420D3F88400D86F9F +:103BA00040F0FF4040F4FF0040F4DF4040F07F0071 +:103BB000D867D86F20F0FF4020F4FF0020F4DF40EA +:103BC00020F07F00D867D86FD3F888006FEA4050A4 +:103BD0006FEA5050C3F88800D3F88800C0F30A0099 +:103BE000C3F88800D3F88800D3F89000C3F8901089 +:103BF000D3F89000C3F89020D3F89000D3F8940045 +:103C0000C3F89410D3F89400C3F89420D3F8940028 +:103C1000D3F89800C3F89810D3F89800C3F8982008 +:103C2000D3F89800D3F88C00C3F88C10D3F88C002C +:103C3000C3F88C20D3F88C00D3F89C00C3F89C10F8 +:103C4000D3F89C10C3F89C20D3F89C30FDF772FB8E +:103C5000BDE8084000F0AEB90044025808B50122A2 +:103C6000534BC3F80821534BD3F8F42042F002021F +:103C7000C3F8F420D3F81C2142F00202C3F81C213F +:103C80000222D3F81C314C4BDA605A689104FCD5FF +:103C90004A4A1A6001229A60494ADA6000221A618F +:103CA0004FF440429A61444B9A699204FCD51A68D9 +:103CB00042F480721A603F4B1A6F12F4407F04D0B6 +:103CC0004FF480321A6700221A671A6842F0010224 +:103CD0001A60384B1A685007FCD500221A611A691D +:103CE00012F03802FBD1012119604FF08041596078 +:103CF0005A67344ADA62344A1A611A6842F48032E6 +:103D00001A602C4B1A689103FCD51A6842F4805251 +:103D10001A601A689204FCD52C4A2D499A62002236 +:103D20005A63196301F57C01DA6301F2E7119963C3 +:103D30005A64284A1A64284ADA621A6842F0A85279 +:103D40001A601C4B1A6802F02852B2F1285FF9D1B0 +:103D500048229A614FF48862DA6140221A621F4A4F +:103D6000DA641F4A1A651F4A5A651F4A9A65322348 +:103D70001E4A1360136803F00F03022BFAD10D4A99 +:103D8000136943F003031361136903F03803182B1D +:103D9000FAD14FF00050FFF7D5FE4FF08040FFF70B +:103DA000D1FE4FF00040BDE80840FFF7CBBE00BF9A +:103DB00000800051004402580048025800C000F042 +:103DC000020000010000FF0100889008121020008E +:103DD00063020901470E0508DD0BBF01200000202A +:103DE000000001100910E000000101100020005245 +:103DF0004FF0B04208B5D2F8883003F00103C2F8A2 +:103E0000883023B1044A13680BB150689847BDE865 +:103E10000840FEF76FBD00BF3C4300204FF0B042AA +:103E200008B5D2F8883003F00203C2F8883023B115 +:103E3000044A93680BB1D0689847BDE80840FEF784 +:103E400059BD00BF3C4300204FF0B04208B5D2F846 +:103E5000883003F00403C2F8883023B1044A1369A0 +:103E60000BB150699847BDE80840FEF743BD00BF5D +:103E70003C4300204FF0B04208B5D2F8883003F040 +:103E80000803C2F8883023B1044A93690BB1D069A2 +:103E90009847BDE80840FEF72DBD00BF3C43002019 +:103EA0004FF0B04208B5D2F8883003F01003C2F8E2 +:103EB000883023B1044A136A0BB1506A9847BDE8B1 +:103EC0000840FEF717BD00BF3C4300204FF0B04351 +:103ED00010B5D3F8884004F47872C3F88820A3069C +:103EE00004D5124A936A0BB1D06A9847600604D58C +:103EF0000E4A136B0BB1506B9847210604D50B4A41 +:103F0000936B0BB1D06B9847E20504D5074A136C4D +:103F10000BB1506C9847A30504D5044A936C0BB1C0 +:103F2000D06C9847BDE81040FEF7E4BC3C4300204D +:103F30004FF0B04310B5D3F8884004F47C42C3F886 +:103F40008820620504D5164A136D0BB1506D984751 +:103F5000230504D5124A936D0BB1D06D9847E00448 +:103F600004D50F4A136E0BB1506E9847A10404D5C7 +:103F70000B4A936E0BB1D06E9847620404D5084A81 +:103F8000136F0BB1506F9847230404D5044A936F05 +:103F90000BB1D06F9847BDE81040FEF7ABBC00BF37 +:103FA0003C43002008B5FFF7B7FDBDE80840FEF729 +:103FB000A1BC0000062108B50846FDF797FA0621C6 +:103FC0000720FDF793FA06210820FDF78FFA062156 +:103FD0000920FDF78BFA06210A20FDF787FA062152 +:103FE0001720FDF783FA06212820FDF77FFA092123 +:103FF0007A20FDF77BFA07213220BDE80840FDF763 +:1040000075BA000008B5FFF7ADFD00F00BF8FDF73D +:104010003FFCFDF711FBFFF753FDBDE80840FFF73C +:104020002BBC00000023054A19460133102BC2E9BE +:10403000001102F10802F8D1704700BF3C43002094 +:1040400010B501390244904201D1002005E0037807 +:1040500011F8014FA34201D0181B10BD0130F2E747 +:10406000034611F8012B03F8012B002AF9D1704700 +:1040700053544D333248373F3F3F0053544D333252 +:10408000483733782F3732780053544D333248371E +:1040900034332F3735332F373530000001105A00B5 +:1040A0000310590001205800032056001000024060 +:1040B000080002400008024000000B0028000240F7 +:1040C000080002400408024006010C0040000240C3 +:1040D000080002400808024010020D00580002408B +:1040E000080002400C08024016030E007000024057 +:1040F0000C0002401008024000040F00880002403B +:104100000C0002401408024006051000A000024006 +:104110000C0002401808024010061100B8000240CE +:104120000C0002401C08024016072F001004024039 +:104130000804024020080240000838002804024019 +:1041400008040240240802400609390040040240E5 +:104150000804024028080240100A3A0058040240AD +:10416000080402402C080240160B3B007004024079 +:104170000C04024030080240000C3C00880402405D +:104180000C04024034080240060D4400A004024022 +:104190000C04024038080240100E4500B8040240EA +:1041A0000C0402403C080240160F460000000000CC +:1041B000B5150008A1150008DD150008C91500088F +:1041C000D5150008C1150008AD150008991500089F +:1041D000E9150008000000000100000000000000D8 +:1041E00063300000E041000898240020A826002049 +:1041F0004172647550696C6F740025424F4152449E +:10420000252D424C002553455249414C25000000C4 +:104210000200000000000000D51700084518000843 +:1042200040004000583F0020683F0020020000008E +:104230000000000003000000000000008D180008CE +:104240000000000010000000783F00200000000087 +:104250000100000000000000EC410020010102000C +:10426000592300086922000805230008E9220008F4 +:10427000430000007842000809024300020100C028 +:1042800032090400000102020100052400100105AA +:10429000240100010424020205240600010705820E +:1042A000030800FF09040100020A000000070501DD +:1042B00002400000070581024000000012000000DB +:1042C000C4420008120110010200004009124157C7 +:1042D00000020102030100000403090425424F41CA +:1042E0005244250053444D4F44454C483756320004 +:1042F000303132333435363738394142434445461C +:104300000000000000000000E9190008A11C0008DE +:104310004D1D00084000400024430020244300209D +:104320000100000034430020800000004001000034 +:10433000080000000001000000100000080000005C +:104340006D61696E0069646C650000000001802A7F +:1043500000000000AAAAAAAA00010024FFFF000092 +:104360000000000000A00A00000040010000000062 +:10437000AAAAAAAA00000001FFFF00000000000096 +:10438000000000001000000400000000AAAAAAAA71 +:1043900000000008FBDF000000000000000000003B +:1043A0000000000000000000AAAAAAAA0000000065 +:1043B000FFFF0000000000000000000000010000FE +:1043C00000000000AAAAAAAA00010000FFFF000046 +:1043D00000000000000000000000000000000000DD +:1043E000AAAAAAAA00000000FFFF00000000000027 +:1043F000000000000000000000000000AAAAAAAA15 +:1044000000000000FFFF00000000000000000000AE +:104410000000000000000000AAAAAAAA00000000F4 +:10442000FFFF00000000000000000000000000008E +:1044300000000000AAAAAAAA00000000FFFF0000D6 +:10444000000000000000000000000000000000006C +:10445000AAAAAAAA00000000FFFF000000000000B6 +:10446000000000000000000000000000AAAAAAAAA4 +:1044700000000000FFFF000000000000000000003E +:104480008F0400000000000000001A00000000007F +:10449000FF000000000000007040000883040000DE +:1044A0007B4000085004000089400008009600008E +:1044B0000000080096000000000800000400000052 +:1044C000D8420008000000000000000000000000CA +:0C44D000000000000000000000000000E0 +:00000001FF diff --git a/Tools/bootloaders/SkySakuraH743_bl.bin b/Tools/bootloaders/SkySakuraH743_bl.bin new file mode 100644 index 00000000000000..05f6dd77050531 Binary files /dev/null and b/Tools/bootloaders/SkySakuraH743_bl.bin differ diff --git a/Tools/bootloaders/TBS_LUCID_H7_bl.bin b/Tools/bootloaders/TBS_LUCID_H7_bl.bin new file mode 100644 index 00000000000000..4214b3b6f178cc Binary files /dev/null and b/Tools/bootloaders/TBS_LUCID_H7_bl.bin differ diff --git a/Tools/bootloaders/TBS_LUCID_H7_bl.hex b/Tools/bootloaders/TBS_LUCID_H7_bl.hex new file mode 100644 index 00000000000000..cd01f403d659a1 --- /dev/null +++ b/Tools/bootloaders/TBS_LUCID_H7_bl.hex @@ -0,0 +1,2496 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008FD7500088F +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E302000809850008358500086E +:10006000618500088D850008B985000821460008D3 +:100070004946000875460008A1460008CD4600081C +:10008000F546000821470008E3020008E3020008E3 +:10009000E3020008E3020008E3020008E585000827 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E00049860008E3020008E3020008E302000872 +:1000F000E3020008E3020008E30200084D4700089D +:10010000E3020008BD860008E5860008E302000857 +:10011000E3020008E3020008E3020008E30200082B +:1001200079470008A1470008CD470008F9470008B3 +:1001300025480008E3020008E3020008E302000883 +:10014000E3020008E3020008E3020008E3020008FB +:100150004D48000879480008A5480008E302000857 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008E9810008E3020008E302000846 +:10018000E3020008E3020008D1860008E302000849 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008D5810008E3020008E3020008FA +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F0B8F9B8 +:1003500006F046FB4FF055301F491B4A91423CBF07 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F0D0F906F0A4FBE4 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E707F0B8B90006002000220020AE +:1003D0000000000808ED00E00000002000060020FA +:1003E000709B0008002200206C2200207022002058 +:1003F000545E0020E0020008E0020008E00200086D +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F0BCF8FEE706F039 +:1004300015F800DFFEE7000053B94AB9002908BFEC +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF38B501F06A +:10074000FFF901F0BBFB06F063FE054606F04CFF27 +:100750000446D0B90F4B9D4219D001339D4241F25E +:10076000883504BF01240025002006F05BFE0CB193 +:1007700000F078F801F040FB00F026FD08B100F031 +:1007800071F8284600F01CF9F9E70025ECE705466A +:10079000EAE700BF010007B008B501F09DF9A0F13C +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0ADF903B05DF804FB19 +:1007C00038B5302383F31188174803680BB105F05F +:1007D000CDFF0023154A4FF47A71134805F0BCFF92 +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F060FA3223636078 +:100810002B78032B07D163682BB9022001F056FA1D +:100820004FF47A73636038BD70220020C10700085E +:100830009023002088220020084B187003280CD831 +:10084000DFE800F008050208022001F037BA0220B4 +:1008500001F02ABA024B00225A6070478822002019 +:1008600090230020F8B5504B504A1C4619680131BE +:1008700000F0998004339342F8D162684C4B9A425D +:1008800040F291804B4B9B6803F1006303F500330A +:100890009A4280F08880002001F078F90220FFF76A +:1008A000CBFF454B0021D3F8E820C3F8E810D3F87C +:1008B0001021C3F81011D3F81021D3F8EC20C3F89D +:1008C000EC10D3F81421C3F81411D3F81421D3F881 +:1008D000F020C3F8F010D3F81821C3F81811D3F89A +:1008E0001821D3F8802042F00062C3F88020D3F8AA +:1008F000802022F00062C3F88020D3F88020D3F853 +:10090000802042F00072C3F88020D3F8802022F0CB +:100910000072C3F88020D3F8803072B64FF0E02325 +:10092000C3F8084DD4E90004BFF34F8FBFF36F8FB6 +:10093000224AC2F88410BFF34F8F536923F48033E7 +:100940005361BFF34F8FD2F8803043F6E076C3F3A4 +:10095000C905C3F34E335B0103EA060C29464CEA92 +:1009600081770139C2F87472F9D2203B13F1200F5C +:10097000F2D1BFF34F8FBFF36F8FBFF34F8FBFF332 +:100980006F8F536923F4003353610023C2F8503250 +:10099000BFF34F8FBFF36F8F302383F311888546EA +:1009A00080F308882047F8BD0000020820000208F4 +:1009B000FFFF0108002200200044025800ED00E083 +:1009C0002DE9F04F93B0B44B2022FF2100900AA8EC +:1009D0009D6801F0BBF9B14A1378A3B90121B04871 +:1009E00011700360302383F3118803680BB105F0A5 +:1009F000BDFE0023AB4A4FF47A71A94805F0ACFE66 +:100A0000002383F31188009B13B1A74B009A1A604F +:100A1000A64A1378032B03D000231370A24A536015 +:100A20004FF0000A009CD3465646D146012001F003 +:100A300045F924B19C4B1B68002B00F02682002056 +:100A400001F04AF80390039B002BF2DB012001F038 +:100A50002BF9039B213B1F2BE8D801A252F823F06E +:100A6000E10A0008090B00089D0B00082D0A000888 +:100A70002D0A00082D0A00082F0C0008FF0D0008A1 +:100A8000190D00087B0D0008A30D0008C90D000812 +:100A90002D0A0008DB0D00082D0A00084D0E000885 +:100AA000810B00082D0A0008910E0008ED0A0008CD +:100AB000810B00082D0A00087B0D00082D0A000894 +:100AC0002D0A00082D0A00082D0A00082D0A00082A +:100AD0002D0A00082D0A00082D0A00089D0B0008A9 +:100AE0000220FFF759FE002840F0F981009B022107 +:100AF00005A8BAF1000F08BF1C4641F21233ADF849 +:100B0000143001F007F891E74FF47A7000F0E4FF39 +:100B1000071EEBDB0220FFF73FFE0028E6D0013F77 +:100B2000052F00F2DE81DFE807F0030A0D1013360F +:100B30000523042105A8059300F0ECFF17E004212C +:100B40005548F9E704215A48F6E704215948F3E7E4 +:100B50004FF01C08404608F1040801F019F8042180 +:100B6000059005A800F0D6FFB8F12C0FF2D10120B6 +:100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F +:100B800001F030F926B10BF00B030B2B08BF00244A +:100B9000FFF70AFE4AE704214748CDE7002EA5D01B +:100BA0000BF00B030B2BA1D10220FFF7F5FD07463D +:100BB00000289BD00120002600F0E8FF0220FFF76C +:100BC0003BFE1FFA86F8404600F0F0FF0446B0B145 +:100BD000039940460136A1F140025142514100F0D3 +:100BE000F5FF0028EDD1BA46044641F21213022166 +:100BF00005A83E46ADF8143000F08CFF16E72546F8 +:100C00000120FFF719FE244B9B68AB4207D9284609 +:100C100000F0BEFF013040F067810435F3E70025A6 +:100C2000224BBA463E461D701F4B5D60A8E7002E62 +:100C30003FF45CAF0BF00B030B2B7FF457AF02209C +:100C4000FFF7FAFD322000F047FFB0F10008FFF691 +:100C50004DAF18F003077FF449AF0F4A08EB0503C7 +:100C6000926893423FF642AFB8F5807F3FF73EAFC0 +:100C7000124BB845019323DD4FF47A7000F02CFF3E +:100C80000390039A002AFFF631AF039A0137019BC4 +:100C900003F8012BEDE700BF002200208C23002089 +:100CA00070220020C1070008902300208822002025 +:100CB00004220020082200200C2200208C22002088 +:100CC000C820FFF769FD074600283FF40FAF1F2D2E +:100CD00011D8C5F120020AAB25F003008449424532 +:100CE000184428BF4246019201F00AF8019AFF21F8 +:100CF0007F4801F02BF84FEAA803C8F387027C492C +:100D00002846019301F02AF8064600283FF46DAF0B +:100D1000019B05EB830533E70220FFF73DFD00282B +:100D20003FF4E4AE00F070FF00283FF4DFAE002790 +:100D3000B846704B9B68BB4218D91F2F11D80A9B2D +:100D400001330ED027F0030312AA134453F8203CBA +:100D500005934046042205A9043701F00FF98046A7 +:100D6000E7E7384600F014FF0590F2E7CDF814806D +:100D7000042105A800F0CEFE02E70023642104A8A8 +:100D8000049300F0BDFE00287FF4B0AE0220FFF710 +:100D900003FD00283FF4AAAE049800F02BFF059055 +:100DA000E6E70023642104A8049300F0A9FE0028CC +:100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 +:100DC000049800F019FFEAE70220FFF7E5FC00288D +:100DD0003FF48CAE00F028FFE1E70220FFF7DCFCD7 +:100DE00000283FF483AE05A9142000F023FF074636 +:100DF0000421049004A800F08DFE3946B9E73220A2 +:100E000000F06AFE071EFFF671AEBB077FF46EAE00 +:100E1000384A07EB0903926893423FF667AE022017 +:100E2000FFF7BAFC00283FF461AE27F003074F44F8 +:100E3000B9453FF4A5AE484609F1040900F0A8FE03 +:100E40000421059005A800F065FEF1E74FF47A70E3 +:100E5000FFF7A2FC00283FF449AE00F0D5FE0028C1 +:100E600044D00A9B01330BD008220AA9002000F0CD +:100E700075FF00283AD02022FF210AA800F066FF63 +:100E8000FFF792FC1C4805F093FB13B0BDE8F08F10 +:100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 +:100EA0000023642105A8059300F02AFE07460028C8 +:100EB0007FF41CAE0220FFF76FFC804600283FF451 +:100EC00015AEFFF771FC41F2883005F071FB059813 +:100ED00000F0D2FF46463C4600F084FFA6E50646F9 +:100EE0004EE64FF0000901E6BA467EE637467CE65C +:100EF0008C22002000220020A08601007047000004 +:100F000070470000704700002DE9F04100F5803780 +:100F1000044616463B7C5BB9C0681030204400F0A4 +:100F2000EFFEE5683544B5F5004FE56002D816B12F +:100F3000BDE8F081DEB905F07F0605F11000002163 +:100F4000C6F180062044F6B232462E4400F0FEFE82 +:100F5000A06804F11008324600F10060414600F537 +:100F6000003006F001F830B901233B74E0E74FF49C +:100F700000463546ECE7A26805F1100140463244D0 +:100F80002144A260E268521BE26000F0B9FE022038 +:100F9000BDE8F04100F09ABE183000F0E9BC000056 +:100FA00010B5044601F006F8204610BD10B5044601 +:100FB00001F000F8204610BDC0B2A0F14103052B9E +:100FC00002D83738C0B27047A0F16103052B94BF37 +:100FD00057383038F6E7000070B504461546084625 +:100FE00003220C4900F096FE014688B908346E1CB5 +:100FF00015F91100FFF7E0FF024616F91100013163 +:10100000FFF7DAFF102940EA021004F8010BEFD1D4 +:1010100070BD00BF289100082DE9F04FADF53F7D70 +:101020000746416801222AA802F0A6FE002840F0E7 +:1010300087800646824681461125DFF80C81DFF85D +:101040000CB101AB4FF4805241462AA802F0F4FFE4 +:10105000002875D1019AB2F5805F71D8002A65D059 +:101060000446019A9442ECD2282D0FD008DC132DAF +:101070002DD01E2D39D0112D13D00134A4B2F0E79C +:10108000322D2DD0372D2FD02D2DF6D13B68121BB0 +:1010900008EB040138461B692D259847BDF804402C +:1010A000EBE7121B022A09D9594608EB040000F0AD +:1010B00031FE18B902342825A4B2DEE718F804304E +:1010C0003A2B3DD00A2B1CBFA1461325D5E718F8B3 +:1010D00004300A2B34D03A2B04BFA2463225CCE789 +:1010E00018F80430202BC8D0264618F804300A2BF4 +:1010F0001AD1AAEB090208EB090102A811254F2A0F +:1011000028BF4F2207F0FCFFA21B08EB060116A820 +:101110004F2A28BF4F2207F0F3FF3B6816AA02A907 +:10112000DB6838469847A8E71E25A6E73B6838469F +:1011300004491B69984701200DF53F7DBDE8F08FFC +:101140000020F9E72A920008982300202C9100083B +:1011500000F1180110B5044686B00846019100F070 +:10116000F1FB2046FFF758FF60B1019902A800F09B +:1011700049FC102204F1080102A807F081FFB0FA2F +:1011800080F0400906B010BD70B504460025EEB2EF +:10119000304600F00BFD58B100213046013500F01B +:1011A00015FD08B9002070BD022000F08FFDEEE7AC +:1011B0002046FFF731FF0028F4D004F58034207C6E +:1011C00080F00100EFE70000F0B5C9B006F038F993 +:1011D00000F00CFF18B90025284649B0F0BD69465B +:1011E0002A4802F0EBFF00284BD1294C204603F09F +:1011F00015F8284803F012F8274803F00FF82146A5 +:10120000224803F087F80028E5D1702000F0CCFEDA +:10121000064610B1214B44600360336830469B683A +:101220009847054600282ED01A4F1948394603F032 +:1012300071F805460028CED1194800F0B5FE0446E5 +:1012400038B1184B4760036000F58033C0E90255A0 +:101250001D74236820469B689847054628B10E49AF +:101260000C4803F057F80028B5D1336830465B6866 +:1012700098471CB1236820465B68984700F09EFEA3 +:10128000AAE70025FAE70446EFE700BF309100081F +:1012900040910008579100086D9100089091000856 +:1012A00014000100AC9100082DE9F04FD44A8DB034 +:1012B0000B68D0F804A001931A440368D14E1A4475 +:1012C000D1F81C90DFF8B4C3DFF8B4B3D0E902342E +:1012D000634003EA0A03634013444A6802920AEB3C +:1012E0007363029CC84A2244C468224484688AEA20 +:1012F00004051D40654015448A68039203EB35558B +:10130000039CC24A2244846822448AEA03042C4093 +:1013100084EA0A041444CA6805EBF43404921644BF +:1013200083EA0502224056445A4032440E6905962B +:1013300004EBB222059FB64E3E441E4485EA0403E8 +:1013400013406B4033444E69069602EB7363069F6D +:10135000B04E3E442E4484EA02051D4065403544AB +:101360008E69079603EB3555079FAB4E3E442644E6 +:1013700082EA03042C4054403444A84E4E4405EB0A +:10138000F434164483EA050222405A4032440E6A7D +:10139000089604EBB222089FA14E3E441E4485EA03 +:1013A000040313406B4033444E6A099602EB7363A7 +:1013B000099F9C4ED1F830E03E44D1F83880F34488 +:1013C0002E4484EA02051D40654035448E6AA6F528 +:1013D000244703EB35550A964F3F274482EA03041E +:1013E0002C4054403C44CF6A0B9705EBF4340B9EE1 +:1013F0008D4F3744029E174483EA050222405A402B +:101400003A448A4F774404EBB2221F4485EA04032E +:1014100013406B403B444F6BBC4402EB7363654429 +:1014200084EA020C0CEA030C8CEA040C6544DFF835 +:1014300054C2C44403EB3555A44482EA03042C404F +:1014400054406444D1F83CC0794905EBF43461441C +:10145000114483EA050222405A400A44754904EBCC +:10146000B2223144079E194484EA02032B406340B0 +:101470000B44714902EBF36331440B9E0D4482EA45 +:1014800003012140514029446C4D03EBF151354497 +:10149000019E254483EA010414405C402C44684DBD +:1014A00001EBB4443544069E154481EA04021A4017 +:1014B0004A402A44634D04EB323235440A9E1D44AF +:1014C00084EA02030B4063402B445F4D02EBF3635D +:1014D0003544059E0D4482EA0301214051402944D0 +:1014E0005A4D03EBF1516544254483EA010414404D +:1014F0005C402C44564D01EBB4443544099E1544E0 +:1015000081EA04021A404A402A44524D04EB323226 +:101510003544049E1D4484EA02030B4063402B447F +:101520004D4D02EBF36345440D4482EA0301214033 +:1015300051402944494D03EBF1513544089E2C4458 +:1015400083EA010515405D402C44454D01EBB44450 +:101550003544039E2A4481EA04051D404D402A4437 +:10156000404D04EB32323D442B4484EA020593445F +:101570000D4065402B443C4D02EBF3633544069E21 +:10158000294482EA0305254055402944374D03EBA1 +:10159000F1514D442C4483EA010515405D4025443A +:1015A00001EBB54581EA050404EA03024A405A44C6 +:1015B000A6F5B82B089E05EB3232ABF2BE6B544059 +:1015C0005B4423442A4C344402EB33730B9E0C449B +:1015D00085EA020159402144264C344403EB715101 +:1015E000029E254482EA03044C402544224C444494 +:1015F00001EB3545144483EA01026A40224443E08A +:1016000078A46AD7EECEBDC156B7C7E8DB702024F8 +:10161000AF0F7CF52AC68747134630A8019546FDD3 +:10162000D8988069AFF7448BBED75C892211906B44 +:101630002108B44962251EF640B340C0515A5E26C7 +:10164000AAC7B6E95D102FD65314440281E6A1D88B +:10165000C8FBD3E7E6CDE121D60737C3870DD5F424 +:10166000ED145A4505E9E3A9F8A3EFFCD9026F6729 +:1016700081F6718722619D6D0C38E5FD937198FDAF +:101680008A4C2A8D8E4379A6934C344405EB722202 +:10169000059E1C4481EA0503534023448F4C344487 +:1016A00002EB33730A9E0C4485EA0201594021443F +:1016B0008B4C4C4403EB7151254482EA03044C40AB +:1016C0002C44884D354401EB3444019E154483EA93 +:1016D000010262402A44844D3D4404EB72221D44C1 +:1016E00081EA040353402B44804D354402EB3373AD +:1016F000049E294484EA02055D4029447C4D35441A +:1017000003EB7151079E254482EA03044C402C44AC +:10171000784D354401EB3444099E2A4483EA01059F +:1017200065401544744A324404EB7525039E134406 +:1017300081EA04026A401A44704B734405EB32722A +:101740000B4484EA0501514019446D4B634402EB9C +:1017500071511C4485EA02034B401C44694B3344DD +:1017600001EB3444019E1D4482EA010363402B4493 +:10177000654D04EB73233544069E154463EA01026C +:1017800062402A44614D03EBB2624D4462EA0409AF +:1017900029445F4D89EA0309454449442C445D4D81 +:1017A00002EBB1513544049E61EA03081D4488EA06 +:1017B0000208444401EB744464EA02034B402B44A6 +:1017C000554D04EBF323754463EA010E15448EEA8C +:1017D000040E0EEB0502514D03EBB262354462EA92 +:1017E000040E29440A9D8EEA030EA5F580164C4D81 +:1017F0007144A6F6833602EBB151264461EA030434 +:1018000054403444029E01EB7444354464EA0206B9 +:101810001D444E407319089E424D04EBF32335449A +:1018200063EA01061544664072193F4D03EBB2624C +:10183000654462EA040629443C4D5E403144079EFB +:1018400002EBB151354461EA03062C44384D564051 +:101850003D443444059E1D4401EB744464EA020394 +:101860004B402B44334D04EBF32335440B9E15447E +:1018700063EA010262402A442F4D03EBB262354411 +:10188000039E0D4462EA0401594029442B4D02EBAA +:10189000B15135442A4E254461EA030454402C4496 +:1018A000099D01EB74442E4464EA02051E4485EA56 +:1018B00001039D1903681A440AEB040303EBF523A3 +:1018C0000260436083681C44C36819448460C1603B +:1018D0000DB0BDE8F08F00BF44EABEA4A9CFDE4B37 +:1018E000604BBBF670BCBFBEC67E9B28FA27A1EA40 +:1018F0008530EFD4051D880439D0D4D9E599DBE6CD +:10190000F87CA21F6556ACC4442229F497FF2A43F1 +:10191000A72394AB39A093FCC3595B6592CC0C8F81 +:10192000D15D84854F7EA86FE0E62CFE144301A3B1 +:10193000A111084E827E53F735F23ABDBBD2D72AA9 +:1019400091D386EB094B036003F18833436003F1C5 +:101950002943A3F59613A3F68B638360A3F1883321 +:10196000C3600023C0E90433704700BF012345670B +:101970002DE9F8431446026905460E46E300C2F31A +:10198000C50800F118079B18036122BF43690133A2 +:10199000436112F4FC7F436903EB5473436114D039 +:1019A000C8F1400907EB08004C4504D22246BDE8C7 +:1019B000F84307F075BB403C4A464E4407F070FBC5 +:1019C000444439462846FFF76FFCA04606EB04095D +:1019D000B8F13F0FA9EB08010AD94022384607F0B9 +:1019E0005FFB39462846A8F14008FFF75DFCEFE7AA +:1019F000A1096FF03F02384602FB014206EB81115C +:101A0000D5E7000070B50B6901F1180506460C46D4 +:101A1000C3F3C503EA18501C8022EA54C3F13F0205 +:101A2000072A1FD8002100F091F929462046FFF728 +:101A30003BFC38220021284600F088F9236929461A +:101A40002046236563696365FFF72EFC214610225B +:101A5000304607F025FB204658220021BDE87040A3 +:101A600000F074B9C3F137020021E5E72DE9F84F22 +:101A70004FF47A7306460D46002402FB03F7DFF8A5 +:101A80005080DFF8509098F900305FFA84FA5A1CC1 +:101A900001D0A34212D159F824002A4631460368E6 +:101AA000D3F820B03B46D847854207D1074B0120E9 +:101AB00083F800A0BDE8F88F0124E4E7002CFBD0F8 +:101AC0004FF4FA7004F074FD0020F3E7DC330020DB +:101AD0001022002014220020002307B50246012115 +:101AE0000DF107008DF80730FFF7C0FF20B19DF81A +:101AF000070003B05DF804FB4FF0FF30F9E700008A +:101B00000A46042108B5FFF7B1FF80F00100C0B21A +:101B1000404208BD074B0A4630B41978064B53F8CB +:101B20002140014623682046DD69044BAC4630BCA9 +:101B3000604700BFDC33002014220020A086010093 +:101B400070B5104C0025104E05F0B2F920803068B9 +:101B5000238883420CD800252088013805F0A4F999 +:101B600023880544013BB5F5802F2380F4D370BD55 +:101B700005F09AF9336805440133B5F5003F336049 +:101B8000E5D3E8E7DE3300209833002005F05EBAA5 +:101B900000F1006000F500300068704700F100605F +:101BA000920000F5003005F0DFB90000054B1A681F +:101BB000054B1B889B1A834202D9104405F074B967 +:101BC0000020704798330020DE33002038B50446EB +:101BD000074D29B128682044BDE8384005F07CB99C +:101BE0002868204405F066F90028F3D038BD00BF0E +:101BF000983300200020704700F1FF5000F58F104F +:101C0000D0F8000870470000064991F8243033B13D +:101C100000230822086A81F82430FFF7BFBF0120A3 +:101C2000704700BF9C330020014B1868704700BF0D +:101C30000010005C194B01380322084470B51D6880 +:101C4000174BC5F30B042D0C1E88A6420BD15C6804 +:101C50000A46013C824213460FD214F9016F4EB17D +:101C600002F8016BF6E7013A03F10803ECD1814277 +:101C70000B4602D22C2203F8012B0424094A1688B1 +:101C8000AE4204D1984284BF967803F8016B013CC0 +:101C900002F10402F3D1581A70BD00BF0010005CBD +:101CA0001C220020EC910008022803D1024B4FF4C3 +:101CB00000229A61704700BF00100258022802D12A +:101CC000014B08229A61704700100258022804D183 +:101CD000024A536983F008035361704700100258A9 +:101CE00070B504464FF47A764CB1412C254628BF96 +:101CF000412506FB05F0641B04F05AFCF4E770BDB7 +:101D0000002310B5934203D0CC5CC4540133F9E7EF +:101D100010BD0000013810B510F9013F3BB191F939 +:101D200000409C4203D11AB10131013AF4E71AB1E3 +:101D300091F90020981A10BD1046FCE703460246B0 +:101D4000D01A12F9011B0029FAD170470244034648 +:101D5000934202D003F8011BFAE770472DE9F843DC +:101D60001F4D14460746884695F8242052BBDFF8DD +:101D700070909CB395F824302BB92022FF2148465F +:101D80002F62FFF7E3FF95F824004146C0F10802F7 +:101D900005EB8000A24228BF2246D6B29200FFF790 +:101DA000AFFF95F82430A41B17441E449044E4B2BE +:101DB000F6B2082E85F82460DBD1FFF725FF002856 +:101DC000D7D108E02B6A03EB82038342CFD0FFF721 +:101DD0001BFF0028CBD10020BDE8F8830120FBE7E2 +:101DE0009C330020024B1A78024B1A70704700BFD8 +:101DF000DC3300201022002038B51A4C1A4D204642 +:101E000003F0DEFE2946204603F006FF2D684FF45E +:101E10007A70D5F89020D2F8043843F00203C2F863 +:101E20000438FFF75DFF1149284604F003F8D5F8A0 +:101E300090200F4DD2F80438286823F002030D4992 +:101E4000A042C2F804384FF4E1330B6001D003F034 +:101E500015FE6868A04204D00649BDE8384003F08A +:101E60000DBE38BD38400020E8990008F099000800 +:101E700014220020C43300200C4B70B50C4D0446D6 +:101E80001E780C4B55F826209A420DD00A4B0021A3 +:101E900018221846FFF75AFF0460014655F826003D +:101EA000BDE8704003F0EABD70BD00BFDC33002028 +:101EB0001422002038400020C4330020F8B571B649 +:101EC000002301201A46194602F094FD04468020A2 +:101ED00005F05CF9002849D00025254A80274FF4F9 +:101EE000D06C3D26136913F0C06F26D1D2F81031A3 +:101EF00013F0C06F21D1236805F100619960236858 +:101F0000D86023685F602368C3F800C021680B684D +:101F100043F001030B6021680B6823F01E030B6084 +:101F200021680B68DB07FCD4237B8035616806FAE7 +:101F300003F3B5F5001F0B60D4D1204602F09AFDE3 +:101F4000B5F5001F11D000240A4E0B4D012005F0FD +:101F50007DF83388A34205D928682044013404F071 +:101F6000BBFFF6E7002005F071F861B6F8BD00BFD1 +:101F700000200052DE3300209833002030B50A44A0 +:101F8000084D91420DD011F8013B5840082340F311 +:101F90000004013B2C4013F0FF0384EA5000F6D10B +:101FA000EFE730BD2083B8ED0121884238BF0846F5 +:101FB00005F024B908B105F025B9704710B5084CF3 +:101FC00001220849002001F0B3FE23783BB1064806 +:101FD00003F0CCFC044803F0FFFC0023237010BD89 +:101FE000E0330020FC910008C03600201D482DE998 +:101FF000F041036D2BB901224FF48051503005F0B0 +:1020000045FA194E33780BB1FFF7D8FF0324174F69 +:102010004FF00008134D15492846C7F8048003F017 +:10202000CDFC284603F006FB48B1013C284603F0EE +:10203000D3FC14F0FF04EED1204634700FE00C49BD +:1020400001220C4801F074FE014618B1284603F045 +:102050008DFCEAE7084800F011F801203070BDE877 +:10206000F08100BFC0360020E03300203422002081 +:10207000FC910008E4330020009200080FB4002017 +:1020800004B070470068704703460068596870479D +:102090000B0A017043700B0C090E8370C1707047FE +:1020A000110A027003714170110C120E8170C2701E +:1020B0001A0A42711A0C1B0E8271C371704700001C +:1020C000C36A0239023B8B4283BF4389006C01FB28 +:1020D0000300002070470000C2F307238A76CB7606 +:1020E0000378032B01BF120C0A75120A4A75704758 +:1020F00000F10B010022D30143EA520310F8012B37 +:1021000052FA83F38842DAB2F5D1104670470000E4 +:1021100010B5417804460020013102464901022AE7 +:1021200016BFA35C032203EBC03302F101021EBF02 +:102130009BB203EB500398B29142F0D810BD00005F +:1021400002684AB1134613F8011B1F290DD93A2919 +:10215000F9D1911C8B4202D04FF0FF3070471278BA +:10216000302AF9D1036000207047014B187870477E +:102170003036002038B50D46044618B90920002332 +:102180002B6038BD0368002BF8D01A78002AF5D0F0 +:102190008188DA889142F1D1587804F0A5FB10F0DB +:1021A0000100EBD12368EBE738B50D4640F2523120 +:1021B000144602F0B9F9FF2807D9012C0BD9030AFC +:1021C000022468702B70204638BD30B1002CFAD044 +:1021D00001242870F7E70024F5E70446F3E7000040 +:1021E0002DE9F8430026D0F8008005460C468E768F +:1021F000836B002B4AD098F80030042B4BD1334628 +:102200003546402720E0B7F5187F80F0C480F906F6 +:1022100006F1010608BF0237D05B02372BB900F583 +:10222000205292B2B2F5006F0DD305F11A01C5F13B +:10223000FF0240EA03402144FFF7B6FF002800F008 +:10224000AA80054400200346D8F8102092F82310F5 +:10225000B142D8D8002B40F09E80002D00F09B802A +:1022600000232544AB766373D8F81020137903F06C +:102270003701DB0621730BD402F13800FFF704FFAE +:10228000C4E9000193896381D3892381BDE8F88380 +:1022900000200146F4E7C36C01335ED1EA6B0023F2 +:1022A0002E26551E184615F8011F013020290CD086 +:1022B000052908BFE521092804D10B2B9EBFE7188B +:1022C00001337E73E718013379730B28EBD1E118E2 +:1022D00000204873A17E00294BD1002B40D06FF025 +:1022E0000C0604F10D000825361B331810F8011BED +:1022F000002938D02E298BB24AD0A3F141011929E7 +:1023000003D8117B0D4200D020330373EDE7B9F100 +:10231000000F05D100F520539BB2B3F5006F0BD32E +:1023200007F11A01C7F1FF0240EA09402144FFF713 +:102330003BFF48B10744002002368146D8F80C30F4 +:10234000985B0028E3D13846B9F1000F4FF0000246 +:1023500018BF002023189A76A0E7B1463746EDE76C +:102360003F23A3760123234400219976137B03B9ED +:102370006373D37A02F11C0003F03F03237300233D +:10238000FFF780FE20606360D38A6381138B7CE754 +:1023900010250B46B9E73F230125A37660E700002F +:1023A00038B50546002435F8020B08B9204638BD7B +:1023B00002F0EEF86308C2B203EBC43312FA83F3FF +:1023C0009AB2C0F3072303EB520303EBC2339CB270 +:1023D000E9E7000037B5C37804461BB90025284655 +:1023E00003B030BD00F14C01826C012340780191B3 +:1023F00004F0A0FA054680B9A36BE070A06C226BD4 +:10240000C31A9342EAD2A3780199022BE6D102447F +:102410000123607804F08EFAE1E70125DFE7000090 +:1024200038B5836C05460C468B4210D0FFF7D2FFBF +:1024300060B92246012305F14C01687804F056FA90 +:1024400000281CBF4FF0FF340120AC6438BD0020D1 +:10245000FCE7000038B500230446C3704FF0FF339B +:102460008364FFF7DDFF00284BD1B4F84A524AF6E7 +:1024700055239D4207D10B22254904F14C0006F05B +:10248000FFFD00283FD094F84C30EB2B03D01833DD +:10249000DBB2012B2ED84AF655239D4206D10822E5 +:1024A0001C4904F19E0006F0EBFD48B3B4F8573028 +:1024B000B3F5007F1ED194F85930DBB15A1E1A4291 +:1024C00018D1B4F85A30ABB194F85C30013B012B11 +:1024D00010D8B4F85D306BB1B4F85F307F2B06D8FC +:1024E00004F16C00FFF7CEFDB0F5803F02D3B4F8E5 +:1024F000623053B94AF6552085420CBF02200320B2 +:1025000038BD0420FCE70120FAE70020F8E700BF0F +:102510002C9200083892000802392DE9F04701F0AA +:1025200007044FF0010A466C05460AFA04F4174600 +:10253000984606EB1136C1F3C809E4B23146284685 +:102540000136FFF76DFF18B10120BDE8F08799460D +:1025500005EB090292F84C30234214BF01210021FF +:10256000414513D06340013F82F84C3085F803A009 +:10257000EBD0640014F0FF04EAD109F10103012457 +:102580004FF00009B3F5007FE1D1D7E70220DCE787 +:1025900001290246F8B50C4640F28C800668F36AC1 +:1025A0008B4240F287803378013B032B00F282801C +:1025B000DFE803F00229384B04EB5405B16B3046D9 +:1025C00001EB5521FFF72CFF10B14FF0FF30F8BDA4 +:1025D0006F1CC5F30805B16B3046354401EB57213C +:1025E00095F84C50FFF71CFF0028EED1C7F3080701 +:1025F000E3073E4496F84C0045EA00204CBF000932 +:10260000C0F30B00E3E7B16B304601EB1421FFF799 +:1026100007FF0028D9D1640004F4FF742644B6F8FB +:102620004C00D4E7B16B304601EBD411FFF7F8FE54 +:102630000028CAD1A40006F14C0004F4FE74204422 +:10264000FFF720FD20F07040C1E7D0E90430D579D4 +:1026500053EA000101D0916801B95DBB9168022D78 +:10266000A4EB01010DD1013B728940F1FF305B0AFF +:1026700043EAC053B3FBF2F399421BD81CD0601C51 +:10268000A5E7032D02D193698B42F8D8D3699BB992 +:10269000B16B304601EBD411FFF7C2FE002894D194 +:1026A000A0004C3600F4FE703044FFF7EBFC20F045 +:1026B00000408CE701208AE76FF0004087E70000C8 +:1026C000F8B5066804460D463378042B0CBF4FF06E +:1026D00080524FF400128A4201D80220F8BDCA0687 +:1026E000FBD182680163D2B9022B13D83389B3EBD3 +:1026F000551FF2D9F36BA363A36B6263002BECD07D +:1027000003EB55234C36C5F308050020A36335447D +:10271000E563E3E7F36BC271002BE7D01A467789D4 +:102720007F02BD42114604D23046FFF7C9FCA063C8 +:10273000E2E72046FFF72CFF431C024606D00128A3 +:10274000CBD9F36A8342C8D9ED1BEAE70120C5E77C +:1027500001292DE9F04706460C46174608D9C36AF9 +:102760008B4205D90378022B62D003D8012B22D0EB +:10277000022552E0033B012BFAD8816B01EBD41107 +:10278000FFF74EFE0546002847D1A40006F14C0392 +:1027900004F4FE741C443378042B07D0204627F041 +:1027A0007047FFF76FFC00F0704007433946204642 +:1027B000FFF76EFC2FE001EB5108816B01EB582114 +:1027C000FFF72EFE054640BB14F0010406F14C094C +:1027D00008F1010AC8F3080808BFFBB230461FBF62 +:1027E00019F8083003F00F023B0103F0F00318BFA3 +:1027F000134309F808300123B16BF37001EB5A2140 +:10280000FFF70EFE054640B9CAF3080A44B1C7F304 +:10281000071709F80A700123F3702846BDE8F0870E +:1028200019F80A30C7F3032723F00F031F43F0E71B +:10283000816B01EB1421FFF7F3FD05460028ECD175 +:10284000640006F14C0304F4FF741F551919C7F313 +:1028500007274F70DFE70000F8B504460E4617461D +:10286000E3690BB91846F8BD012BA6EB03052068F8 +:1028700014BFAA1C3A46691CFFF76AFF0028F2D170 +:10288000E369013BE361EBE701292DE9F8430646E3 +:102890000C461746056802D80220BDE8F883EB6AAB +:1028A0008B42F9D97AB9A14621463046A046FFF7B6 +:1028B0006FFE0446B0B92B78042B02D1002F43D110 +:1028C000F7710020E9E72B78042B02D1C379022BA2 +:1028D000E9D04FF0FF3239462846FFF739FF00288C +:1028E000E1D0DAE70128D7D0421C01D10120D4E79A +:1028F0002B78042B19D1EA6AAB69023A93421CD3B4 +:1029000008F10102A2420CD02B78042B08D100233D +:10291000A2EB090249462846FFF7FEFD0028BCD17C +:10292000A146EB6AA342BFD8C5E70022414628462C +:10293000FFF70EFF0028DED0AFE70133AB612B7944 +:1029400043F001032B71DBE7F3798BB9B468BC4228 +:1029500002D10223F371B4E721463046FFF718FE97 +:10296000012899D9431CC1D001348442EFD0A8E793 +:10297000032BA6D1B368BB42A3D8B2691344BB42B0 +:102980009FD3E6E770B5C3790446032B06D181686F +:102990008369CD18A94203D10023E371002070BDE3 +:1029A0004E1C20683246FFF7D3FE0028F7D131468F +:1029B000F0E700002DE9F74305460191FFF70AFD16 +:1029C0000446002849D105F14C09019928464FF4E5 +:1029D0000072FFF775FB2146A86407464846FFF7DB +:1029E000B5F96C896402B4F5004F28BF4FF4004478 +:1029F000B4F5007F2FD9204604F008FC804630B1A2 +:102A000022460021640A0026FFF7A0F909E06408C5 +:102A1000EEE72346BA194146687803F08BFF18B9F0 +:102A200026446B899E42F4D3404604F0FFFB68893C +:102A3000801B18BF012003B0BDE8F08301366B890D +:102A40009E42F4D20123BA194946687803F072FF16 +:102A50000028F3D0EBE70026F1E70120EBE70000C8 +:102A6000F8B50446FFF7B6FC0546002842D12378A6 +:102A7000032B37D12779012F34D104F14C060146BD +:102A80004FF400723046FFF761F95523412272215D +:102A900084F84A32AA2304F50D7084F84F2084F894 +:102AA0004B32522384F8301284F84C3084F84D3085 +:102AB000612384F8311284F84E3084F83332A169EE +:102AC00084F83222FFF7E4FA616904F50E70FFF72B +:102AD000DFFA626B3B46314601326078A26403F054 +:102AE00029FF257100226078114603F047FF003866 +:102AF00018BF0120F8BD000000232DE9F0430B6052 +:102B000085B00F461546FFF71BFB061EC0F2B281CB +:102B1000804B53F82640002C00F0AE813C6005F05D +:102B2000FE0523786BB1607803F0DEFEC70708D49A +:102B30001DB110F0040500D00A25284605B0BDE8F7 +:102B4000F0830023F0B22370607003F0B9FEC10778 +:102B500000F194810DB14207EED400212046FFF729 +:102B600079FC022840F099806E4604F2122304F2A8 +:102B70005221324618461033FFF784FA42F8040B0C +:102B80008B42F7D1002556F8041B00297DD0204642 +:102B9000FFF760FC012879D80128A26C40F0C080C2 +:102BA00004F1570304F18C0113F8015B002D7BD174 +:102BB0008B42F9D1B4F8B430B3F5807F74D194F876 +:102BC000B830092B70D104F19400FFF75DFA4FF093 +:102BD000FF33171841F10001BB4275EB010363D3CA +:102BE00004F1A000FFF74EFA94F8BA302063012BED +:102BF000A37059D194F8B99003FA09F91FFA89F32F +:102C00006381002B50D0444B04F1A800FFF73AFA3F +:102C10000646984248D8831C626304F1A400E3622C +:102C2000FFF730FA00EB020804F19C00C4F8408082 +:102C3000FFF728FA10441FFA89F2A06306FB02F39B +:102C400013EB080345EB05029F4271EB02032BD304 +:102C50002E4604F1AC00FFF715FAE06365B963890D +:102C6000B34221D9E16B2046FFF72AFA81192046A9 +:102C7000FFF7D6FB98B90136631993F84C30812BD6 +:102C800014D02035C5F30805E8E703200135042DED +:102C90007FF479AF042807D101E0042801D1012590 +:102CA0004BE701287FF678AF0D2546E705F11400C4 +:102CB00004F14C063044FFF7E5F901280546F3D945 +:102CC000E36A8342F0D96189821E236C02FB0133DF +:102CD0006364A16B204601EBD511FFF7A1FB00282F +:102CE000DDD105F07F0006EB8000FFF7CBF9431C38 +:102CF00003D00135A842ECD0D6E70425C4E905008D +:102D0000064A257000251388E56101339BB21380C4 +:102D1000E38012E734360020FDFFFF7F38360020C5 +:102D2000B4F85730B3F5007FBED1B4F8626026B96D +:102D300004F17000FFF7A6F9064694F85C302663AC +:102D4000591EA3700129AFD894F859506581002D00 +:102D5000AAD0691E2942A7D1B4F85D8018F00F0FE0 +:102D6000A4F80880A0D1B4F85F0018B904F16C0091 +:102D7000FFF788F9B4F85A10002995D006FB03FE36 +:102D800001EB181CF44460458ED3A0EB0C00A84264 +:102D9000B0FBF5F388D33E48834285D84FF6F570F3 +:102DA00083426DD903259F1C114402EB0C03032DB4 +:102DB000E7626263A16323644CD1B4F8763053EACE +:102DC00008037FF471AFBB0004F17800FFF75AF9F4 +:102DD000E06303F2FF13B6EB532FFFF465AF4FF040 +:102DE000FF33032DC4E905334FF08003237187D1EE +:102DF000B4F87C30012B83D1511C2046FFF710FB27 +:102E000000287FF47DAFB4F84A224AF6552320719A +:102E10009A427FF475AF1F4B04F14C00FFF732F973 +:102E200098427FF46DAF03F1FF5304F50C70FFF788 +:102E300029F903F50053203398427FF461AF04F57C +:102E40000D70FFF71FF9A06104F50E70FFF71AF976 +:102E5000606155E7B8F1000F3FF426AF7144022DD1 +:102E60004FEA4703E1631EBFD91907F0010303EBE3 +:102E70005103AEE70B2560E60C255EE603255CE614 +:102E800040F6F575AB428CBF022501258BE700BFEC +:102E9000F5FFFF0F525261412DE9F84F07460568D3 +:102EA000884649B96E69C6B1EB6AB34298BF01263C +:102EB000AB69A3B9002405E0FFF76AFB01280446CB +:102EC00003D801242046BDE8F88F421C00F0D280D0 +:102ED000EB6A8342F6D84646EAE70126E8E72A7815 +:102EE000EB6A042A40F08380A6F1020A023B4FF00D +:102EF000010B9A4528BF4FF0000AD146696C28465D +:102F000001EB1931FFF78CFA00283BD109F00703D8 +:102F1000EA6AC9F3C8010BFA03F3901EDBB26A1820 +:102F20004C4609F1010992F84C20814502EA03025E +:102F300033BF5B0000234FF40071DBB228BF99461A +:102F4000B2B90234631E0333BCD80123214628469C +:102F50001A46FFF7E1FA0228B3D0012800F08A8070 +:102F6000B8F1000F13D10223FB710028A9D130E082 +:102F7000CA450AD0002BD2D10131B1F5007FBDD2B4 +:102F80000123CCE74FF0FF34DCE70024DAE7FB79DC +:102F9000022B07D1731CA342E7D0BB68F31ABB61B5 +:102FA0000323FB7108F10102FB69A24205D113B1B1 +:102FB0000133FB61D9E70223FBE70BB90123FB6176 +:102FC000224641463846FFF747FC00284FD10123EF +:102FD000FB61EA6AAB69023A6C6193429CBF03F100 +:102FE000FF33AB612B7943F001032B716AE7464550 +:102FF00014D1741C3846A34298BF02242146FFF71F +:10300000C7FA01283FF45DAF431C33D0E0B16B69D0 +:10301000012B03D9EA6A934238BF1E463446013475 +:10302000EB6AA34203D8012E7FF644AF0224214667 +:103030003846FFF7ADFA48B101283FF442AF0130FE +:1030400018D0B442EBD135E7002CE7D04FF0FF3277 +:1030500021462846FFF77CFB48B9B8F1000FB8D0ED +:10306000224641462846FFF773FB0028B1D00128CD +:103070007FF427AF4FF0FF3424E700002DE9F84339 +:1030800006680446076B894633782037042B0CBF4B +:103090004FF080534FF40013BB429CBF0023836367 +:1030A000836B73B1C7F30808B8F1000F3CD101334B +:1030B000416B836339B93389B3EB571F34D800238D +:1030C000A36304200AE07389013B13EA57232BD141 +:1030D000FFF75EFA0128054602D80220BDE8F88312 +:1030E000421C01D10120F9E7F36A834216D8B9F1F5 +:1030F000000FE4D0616B2046FFF7CEFE0546C8B155 +:103100000128EAD0431CEDD001463046FFF752FCBF +:103110000028E7D1E37943F00403E3712946304600 +:103120006563FEF7CDFFA0634C360020276346445D +:10313000E663D3E70720D1E7F8B50E460021044641 +:103140000768FFF7BDFA98B90546A16B3846FFF747 +:1031500067F968B93A78E36B042A1B780CD11B062F +:103160000ED5054601212046FFF788FF0028ECD048 +:10317000042808BF072006E0E52B01D0002BF0D182 +:103180000135B542EED1F8BDC16C4B1C2DE9F041C3 +:1031900004460568066B1FD1E5274FF00108A16BB7 +:1031A0002846FFF73DF998B92A78E36B042A09BF4E +:1031B0001A781F7002F07F021A7085F80380236B63 +:1031C000B3420DD200212046FFF758FF0028E6D079 +:1031D000042808BF022003E0FFF772FA0028DBD0C2 +:1031E000BDE8F0812DE9F04105460068A96B06694C +:1031F000FFF716F9044620B9EB6B1A78852A03D03D +:1032000002242046BDE8F081324603F1200153F844 +:10321000040B8B4242F8040BF9D1777801377F0118 +:10322000A7F16003B3F5007FEAD800212846FFF735 +:1032300025FF04280446E3D00028E2D1A96B2868C2 +:10324000FFF7EEF804460028DBD1EB6B1A78C02AB2 +:10325000D6D106F1200203F1200153F8040B8B4272 +:1032600042F8040BF9D196F823300F222C33B3FB2C +:10327000F2F3B7EB431FC3D34FF0400800212846B9 +:10328000FFF7FCFE04280446BAD00028B9D1A96B88 +:103290002868FFF7C5F804460028B2D1EB6B1A780E +:1032A000C12AADD1B8F5187F09D206EB080203F1A7 +:1032B000200153F8040B8B4242F8040BF9D108F1BA +:1032C00020084745DAD8B8F5187F9AD83046FEF777 +:1032D0001FFF7388834294D092E700000B6800229E +:1032E00010B5036004460B6A83604B6AC261C37108 +:1032F00023F0FF03896AC0E90432C164FFF7E0F9F3 +:1033000020B92046BDE81040FFF76CBF10BD00009B +:10331000F8B50368054601271C692046FEF7F8FE4C +:10332000A070000A6678E0702846E96CFFF7C8F9DB +:1033300020B1022828BF0220C0B2F8BDA96B2868BE +:10334000FFF76EF80028F4D1EB6B04F1200254F87B +:10335000041B944243F8041BF9D12B68DF70002E44 +:10336000E7D000212846013EFFF788FEE0E7000095 +:103370002DE9F8434FF0FF08064607680424454648 +:103380004FF6FF79B16B11B9002C73D063E038466A +:10339000FFF746F8044600285DD1F06B0378002B58 +:1033A0006ED03A78042A11D1852B4DD1336B30463B +:1033B000F364FFF717FF044600284CD13B691B79E3 +:1033C00003F03F03B3712046BDE8F883C27AE52BD2 +:1033D00002F03F02B27143D02E2B41D022F02001E7 +:1033E00008293DD00F2A40D1590637D503F0BF0533 +:1033F000336B90F80D80F364437B434530D1428BAF +:1034000072BB03780D21FC6823F04003DFF874E001 +:10341000013B4B4301211EF801CB30F80CC009B32E +:10342000FF2B1DD824F813C06146013301320D2A49 +:10343000F1D10278520605D521B1FF2B10D8002218 +:1034400024F81320013DEDB200213046FFF716FEAF +:103450000446002896D00023B363B4E7AB42CBD038 +:10346000FF25F1E7CC45E1D0FAE72DB9FEF740FEA4 +:10347000404501D10024A6E74FF0FF33F364A2E7F3 +:103480000424E8E7D49200082DE9F04F002187B02A +:103490000446D0F80090FFF713F9804670B999F808 +:1034A0000030042B33D1D9F80C00FEF779FF074622 +:1034B0002046FFF75DFF054620B18046404607B035 +:1034C000BDE8F08FD9F810309A8CBA42F0D193F859 +:1034D00023B040265D4506D1D9F80C3033F81530BD +:1034E000002BE5D1EAE7F106D9F8103008BF023623 +:1034F000985B01F04DF8D9F80C30824633F815008E +:1035000001F046F88245D3D102360135E2E74FF0AB +:10351000FF0A4FF0FF3B5546C4F84CB0A16B48463C +:10352000FEF77EFF00285CD1E66B3778002F77D05E +:10353000F27AE52F02F03F03A37103D0120704D5FE +:103540000F2B04D0C4F84CB04FE00F2B54D194F89B +:103550004B3058063FD4790645D5236B07F0BF079B +:1035600096F80DA0E364737B53453ED1738B002B1B +:103570003BD135780121D9F80C3005F03F05019396 +:103580000D23013D5D43284B13F8012BB25A71B353 +:10359000FF2D059329D81046049200F0F9FF6B1C0B +:1035A00003900293019B33F8150000F0F1FF03999B +:1035B00081421AD1049A029D1146059B1B4A9342EF +:1035C000E2D133785A0604D519B1019B33F815308E +:1035D0005BB97D1EEDB200212046FFF74FFD0028AC +:1035E0009CD080466AE7BD42BDD0FF25F3E74FF689 +:1035F000FF708242E2D0F8E72DB93046FEF778FD41 +:1036000050453FF45BAF94F84B30DB079AD40B2264 +:1036100004F14001304605F033FD002892D14DE71A +:103620004FF004084AE700BFD4920008E192000876 +:103630002DE9F04F90F84BB099B004461BF0A0056F +:1036400040F068810668F26832F81530002B4AD1E4 +:103650003378042B40F087800F230E352046B5FBCE +:10366000F3F5A91CFFF768FD8146002877D1236B8D +:103670000135A3EB4515E3795A07E56435D523F009 +:1036800004032046E371FFF77DF950BB4FF0FF3292 +:10369000616B2046FFF7E0F818BBA3682BB3214607 +:1036A00004A8FFF71BFEE0B970894FF40071D4E95C +:1036B0000423E0FB01233069C4E904233830FEF71A +:1036C000EFFC3069D4E904232830FEF7E9FCE37904 +:1036D000326904A843F0010382F82130FFF718FE95 +:1036E00018B181463BE00135AEE7D6E903544022EC +:1036F00000212046FEF72AFB85230121402223706A +:10370000C0234FF0C10C04EB010884F820300023E3 +:103710001E469E46571C04F802C0F0B2023204F85E +:1037200007E021B135F8131009B10133DBB20F0AFC +:10373000A15408F802700232D706F2D135F813709E +:103740000136002FE6D184F82330831C28466370AD +:10375000FEF726FE84F82400000A84F82500484677 +:1037600019B0BDE8F08F04F140070DF1100A1BF00D +:10377000010F97E807008AE8070000F0D380402394 +:103780004FF0010884F84B30BC46F368B8F1050FE0 +:103790009AE80700ACE803002CF8022B4FEA12422B +:1037A0008CF8002059D9981E424630F8021F002993 +:1037B00042D10DF10F0C072102F00F0E91461209B4 +:1037C0000EF13000392888BF0EF1370001390CF8AE +:1037D000010902D0B9F10F0FEED818AB7E205A18AC +:1037E00002F8580C38460022914206D010F801CB5E +:1037F00002F1010EBCF1200F31D104F13F0C072979 +:1038000002F1010297BF18AB20205818013198BF70 +:1038100010F8580C072A0CF80200F0D92046FFF7E0 +:1038200033FE8146002878D108F10108B8F1640F11 +:10383000AAD14FF0070992E74FF0100C01F0010EEA +:1038400049080EEB4202D30344BF82F4883282F06F +:103850002102BCF1010CF1D1A7E74246A9E772466B +:10386000C2E7216B2046A1EB4511FEF729FF8146F7 +:1038700000287FF474AF4FF6FF783846FEF738FC27 +:103880000190A16B3046FEF7CBFD814600287FF406 +:1038900066AFE36BE9B2019A4FF00D0CD6F80CE07D +:1038A0005A734FF00F02DFF8E0A0DA724A1E187365 +:1038B0000CFB02F284469876D87640451AF8019BB4 +:1038C0000CF1010C18BF3EF8120003EB090B18BFF6 +:1038D000013203F809004FEA1029002808BF4046CA +:1038E000BCF10D0F8BF80190E7D1404502D03EF8B6 +:1038F00012200AB941F0400119700123002120462D +:10390000F370FFF7BBFB814600287FF428AF013D31 +:10391000B7D11BE04FF0060921E704287FF41FAF61 +:1039200084F84BB01BF0020F20461BBF0C350D2155 +:103930000125B5FBF1F518BF01352946FFF7FCFB62 +:10394000814600287FF40BAF013D8AD1A16B304640 +:10395000FEF766FD814600287FF401AF0146202274 +:10396000E06BFEF7F3F9E36B03CF18605960BA78A8 +:1039700039889A72198194F84B30E26B03F018037E +:1039800013730123F370EAE6D492000810B50446DD +:103990000A463430FEF776FB886004F13800FEF703 +:1039A00073FBC2E9040194F8213003F00203D371E0 +:1039B0000023D36110BD000003284B8B04BF8A8A0B +:1039C00043EA0243184670472DE9F04F0B7899B04F +:1039D000044689462F2BD0F800B001D05C2B09D1CA +:1039E0004A461378914601322F2BFAD05C2BF8D03F +:1039F000002301E0DBF81C30A3600023E3619BF8A7 +:103A00000030042B1ED1A368E3B1DBF8203021463F +:103A100004A82362DBF824306362DBF82830A36259 +:103A2000FFF75CFC0346002854D1DBF8102002F1BC +:103A30003800FEF727FBC4E9040392F8213003F0B5 +:103A40000203E37199F800301F2B00F235818023C7 +:103A50000021204684F84B3019B0BDE8F04FFEF746 +:103A60002FBE49460B78894601312F2BFAD05C2BAB +:103A7000F8D01F2B8CBF00250425012F2FD11388D0 +:103A80002E2B31D1002322F8173004F140029F423F +:103A90008CBF2E21202101330B2B02F8011BF6D104 +:103AA00045F02005204684F84B50FFF7EDFC94F8D4 +:103AB0004B30002800F0E78004280BD1990603F072 +:103AC000040240F1DC80002A00F0F6808023002010 +:103AD00084F84B3019B0BDE8F08F0425CDE7022FF4 +:103AE00002D153882E2BCAD0911E87BB002322F807 +:103AF0001730002F00F0118132F8130019460133FE +:103B00002028F9D009B92E2801D145F00305901ECF +:103B100030F817302E2B01D0013FF9D14FF0203370 +:103B20004FF0000A6364D0462364C4F8473008238A +:103B3000481C32F811600090F6B1202E03D02E2ED2 +:103B40000DD1B84210D045F003050099F0E731F8E7 +:103B50001730202B01D02E2BC8D1013FC5E79A4545 +:103B600005D20099B9423BD10B2B30D101E00B2B90 +:103B700027D145F003050B2394F84020E52A04BF24 +:103B8000052284F84020082B04BF4FEA88085FFA1A +:103B900088F808F00C030C2B03D008F00303032B68 +:103BA00001D145F00205A8073FF57CAF18F0010FE1 +:103BB00018BF45F0100518F0040F18BF45F00805B0 +:103BC00070E70099B94202D045F00305D4D84FEA16 +:103BD00088080B234FF0080A00975FFA88F8B4E7CB +:103BE0007F2E15D9304640F25231CDE9022345F0FF +:103BF0000203019300F098FC10F0800F0646DDE907 +:103C0000022316D000F07F0646498E5D019D46B323 +:103C100031464548CDE9012305F05CFADDE9012391 +:103C2000F8B9A6F1410189B219291ED848F0020855 +:103C300010E0FF28EAD9591E8A4503D345F0030551 +:103C40009A4682E704EB0A01000A0AF1010A019D83 +:103C500081F8400004EB0A010AF1010A81F8406092 +:103C600073E745F003055F26F4E7A6F1610189B229 +:103C700019299EBF203E48F00108B6B2EAE7002AA3 +:103C800008BF052026E75A073FF524AFA379DB06D6 +:103C900045D59BF80000042835D1A3682146E27978 +:103CA00023622369DBF8100023F0FF0313436362F0 +:103CB000E36CA362FFF76AFE23680027DA6819F84D +:103CC000010B00283FF409AF40F25231009200F09E +:103CD0004BFC054608B31F28009A7FF6FEAE2F283E +:103CE0003FF4BFAE5C283FF4BCAE7F2805D8014648 +:103CF0000E4805F0EFF9009A78B9FF2F0DD022F8A1 +:103D000017500137DBE7216B0BF14C03C1F30801BE +:103D10001944FFF751FEA060CEE70620DAE6052041 +:103D2000D8E600BF549200084D9200084492000863 +:103D30001FB5CDE9001003A814460391FEF700FA61 +:103D4000002815DB0B4A52F820300BB10021197006 +:103D5000019B0BB10021197042F820302CB10022D8 +:103D600001A96846FEF7C8FE0446204604B010BD0F +:103D70000B24FAE7343600202DE9F04798B090463E +:103D800005460191002800F0528102F03F0603A988 +:103D900001A83246FEF7B0FE002840F04681039BA2 +:103DA0004FF48C60049303F031FA0746002800F0CA +:103DB0004081039B00F500720199D86004A81A6144 +:103DC000FFF702FE044620B99DF95B30002BB8BF17 +:103DD000062418F01C0F00F0CD80002C4CD0042CD1 +:103DE00040D104A8FFF724FC044600283AD146F04D +:103DF0000806039B1A78042A40F083801869294634 +:103E00002B60FFF7C3FD039B1E22002118690230BF +:103E1000FDF79CFF039C00211A2220692630FDF744 +:103E200095FF236920221A71246903F029FA0146BB +:103E3000012208342046FEF72BF9039B04A81B69D6 +:103E400083F82120FFF764FA044658B9A96801B342 +:103E500002462846FEF718FDAB68039A0446013B6C +:103E60005361B4B1384603F0E1F90CB100232B6083 +:103E7000204618B0BDE8F0879DF8163013F0110FFA +:103E800040F0848018F0040F40F0C98018F0080F4B +:103E9000AFD1039A31071399936C48BF46F040069F +:103EA000E964AB641078042872D1069B9DF8171062 +:103EB0002B62089B106923F0FF030B4329466B62BA +:103EC000179BAB62FFF762FDDDF80CA00024002217 +:103ED00005F15008BAF8063021464046C5F800A062 +:103EE000AB80002385F8306085F831406C64C5E90B +:103EF0000E234FF40072FDF729FFB20653D40024BD +:103F0000B0E703F0BDF90146009013980E30FEF7BC +:103F1000BFF8139800991630FEF7BAF8039C13996E +:103F20002078FFF749FD202300228046CB722046EF +:103F30001399FEF7D1F8139B002201211A775A77C3 +:103F40009A77DA77039BD970B8F1000FA1D0414678 +:103F500004A8D3F84890FEF797FC0446002881D1C6 +:103F600049460398FEF75CFA039B044608F1FF30CC +:103F7000586176E7002C7FF475AF9DF81630DC06AB +:103F80004FD418F0020F84D0D80782D5072469E7F0 +:103F9000FFF712FD0023A86001F11C00FEF772F884 +:103FA0006B61286190E7D5E9046956EA0903A6D058 +:103FB000BAF80AA0A9684FEA4A2AC5E90E69B245CB +:103FC00074EB09031BD300242964002C7FF44AAF4F +:103FD000C6F30803002B92D0039C2046FEF770F82E +:103FE00008B3760A0123414646EAC95682196A6433 +:103FF000607802F07BFC041E18BF012432E72846DB +:10400000FEF7C6FAB6EB0A06014669F10009012877 +:1040100003D9431CD3D10124D6E70224D4E70824D2 +:1040200020E704241EE702241CE704461EE70924B7 +:104030001EE711241CE700002DE9F04F994685B0DA +:104040000023884603A90446C9F800301646FEF747 +:1040500091F8054680BB94F831506DBB94F8303030 +:1040600013F00103009300F0A68004F1500AD4E994 +:104070000432D4E90E011B1A62EB0102B34272F161 +:10408000000238BF1E46BEB1D4E90E10C1F30803CA +:10409000002B40F08280039B5A894B0A013A43EA85 +:1040A000C0531A401BD151EA000309D1A06801286E +:1040B0000DD8022584F83150284605B0BDE8F08FB0 +:1040C000216C20460192FEF763FA019AEFE7431C48 +:1040D00004D10123009D84F83130EDE72064DDF840 +:1040E0000CB0216C5846FDF7EBFF0028E1D0B6F587 +:1040F000007F02EB000731D3BBF80A1002EB562019 +:10410000730A88429BF8010088BF8B1A3A464146E1 +:10411000019302F0EBFB0028DBD194F93020019BE6 +:10412000002A0BDA606CC01B984207D24FF4007271 +:10413000514608EB4020FDF7E3FD019B5F02D9F8F3 +:104140000030F61BB8443B44C9F80030D4E90E32C5 +:10415000DB1942F10002C4E90E3294E7626CBA4204 +:104160001AD094F93030002B0DDA012351469BF818 +:10417000010002F0DFFB0028ABD194F8303003F0EF +:104180007F0384F83030039801233A465146407843 +:1041900002F0ACFB00289CD16764A16B4046C1F3E0 +:1041A0000801C1F500775144B74228BF37463A4667 +:1041B000FDF7A6FDC3E707257EE7000070B596B0C2 +:1041C0000E460022019002A901A8FEF795FC0446C4 +:1041D000E0B94FF48C6003F019F80546D8B1029BA2 +:1041E00000F500720199D86002A81A61FFF7ECFB94 +:1041F000044640B99DF95330002B0ADB1EB131460D +:1042000002A8FDF7EDFF284603F010F8204616B08F +:1042100070BD0624F7E71124F8E7000070B5B8B0C8 +:104220000222019003A901A8FEF766FC044608BB20 +:10423000039B4FF48C60109302F0E8FF05460028C2 +:1042400066D0039B00F500720199D86010A81A612E +:10425000FFF7BAFB044650B99DF88B30980655D449 +:10426000190653D49DF84630DA0706D507242846A8 +:1042700002F0DCFF204638B070BD039B0493187831 +:10428000042814D104A91869FFF780FB069E9DF845 +:104290004630DB0610D410A8FEF776FF044600284F +:1042A000E5D156BB0398FEF7DBFB0446DFE71F9919 +:1042B000FFF782FB0646EAE7039BDA69B242D5D0F4 +:1042C00024930021269624A81B78042B01BFDDE946 +:1042D0000823CDE928239DF817308DF89730FEF795 +:1042E000EFF904460028C2D124A8FFF741F804469C +:1042F0000028BBD00428BAD1CDE70246314604A835 +:10430000FEF7C2FA04460028B1D1CBE70624AEE797 +:104310001124AFE7F0B5BDB0CDE900106846FDF758 +:104320000FFF022203A901A8FEF7E6FB04460028BE +:1043300041D1039B4FF48C60149302F067FF054654 +:10434000002800F0EE80039B00F5007214AE019986 +:10435000D8601A613046FFF737FB044640BB9DF832 +:104360009B3013F0A00F40F0D880039B009F1A7879 +:10437000042A68D11B6904AC03F1400C18680833A7 +:1043800053F8041C2246634503C21446F6D150225A +:10439000314628A8FDF7B4FC394628A8FFF714FBDE +:1043A000044600284CD12A9A169B9A4206D008242B +:1043B000284602F03BFF20463DB0F0BD349A209BDA +:1043C0009A42F4D128A8FFF733F904460028EFD128 +:1043D000039B04AF1B6993F801E093F823C09C8C06 +:1043E0003A46083303CAB24243F8080C43F8041CA7 +:1043F0001746F5D1039B28A81B6983F801E0039BAE +:104400001A6982F823C01A6982F82440240A82F8C3 +:1044100025401A691379D9065CBF43F02003137154 +:10442000FEF776FF04460028C2D13046FEF7ACFE08 +:1044300004460028BCD10398FEF712FB0446B7E7F8 +:104440000428B5D1BEE7239A04AB02F1200C106812 +:10445000083252F8041C1C46624503C42346F6D1B8 +:104460005022314628A8FDF74BFC394628A8FFF713 +:10447000ABFA044600284CD12A9A169B9A4296D150 +:10448000349A209B9A4292D128A8FFF7D1F804468B +:1044900000288DD137990DF11D030DF12D0001F18B +:1044A0000D0253F8044B834242F8044BF9D11888AB +:1044B000012710809B7893709DF81B30039CDA06CF +:1044C00058BF43F02003CB72E770CB7ADB06ACD544 +:1044D000169A2A9B9A42A8D02078FFF76DFA0146D7 +:1044E0002046FDF7EDFD0146C8B12046FDF798FFD7 +:1044F000044600287FF45CAF039890F86D302E2BB3 +:1045000093D12A9A00F16C01FDF7E6FD039BDF7061 +:104510008BE704287FF44CAFB6E7062448E7022473 +:1045200046E7112447E700007F2810B501D880B284 +:1045300010BDB0F5803F13D240F2523399420FD1F3 +:104540000849002231F8024B93B2844203D103F1AF +:104550008000C0B2ECE70132802AF3D11346F6E7BF +:104560000020E5E7949500087F280DD940F25233EA +:10457000994208D1FF2806D800F10040034B80384B +:1045800033F8100070470020704700BF9495000872 +:10459000B0F5803FF0B522D21F4A83B21F49B0F573 +:1045A000805F28BF0A46141D34F8042C2146AAB1A6 +:1045B000934213D334F8025C2E0AEFB252FA85F517 +:1045C000A84222DA082E09D8DFE806F0050A101200 +:1045D0001416181A1C00801A34F810301846F0BD52 +:1045E000981A00F001001B1A9BB2F7E7103BFBE79B +:1045F000203BF9E7303BF7E71A3BF5E70833F3E7F1 +:10460000503BF1E7A3F5E353EEE70434002ECBD1A2 +:1046100001EB4702C7E700BFE4920008D894000806 +:1046200008B5074B074A196801F03D0199605368C6 +:104630000BB190689847BDE8084003F017B800BF79 +:10464000000002403C36002008B5084B1968890973 +:1046500001F03D018A019A60054AD3680BB11069E7 +:104660009847BDE8084003F001B800BF00000240D1 +:104670003C36002008B5084B1968090C01F03D01D3 +:104680000A049A60054A53690BB190699847BDE8DE +:10469000084002F0EBBF00BF000002403C360020A3 +:1046A00008B5084B1968890D01F03D018A059A602B +:1046B000054AD3690BB1106A9847BDE8084002F07B +:1046C000D5BF00BF000002403C36002008B5074BB4 +:1046D000074A596801F03D01D960536A0BB1906AED +:1046E0009847BDE8084002F0C1BF00BF000002408B +:1046F0003C36002008B5084B5968890901F03D0196 +:104700008A01DA60054AD36A0BB1106B9847BDE89D +:10471000084002F0ABBF00BF000002403C36002062 +:1047200008B5084B5968090C01F03D010A04DA602C +:10473000054A536B0BB1906B9847BDE8084002F0F7 +:1047400095BF00BF000002403C36002008B5084B72 +:104750005968890D01F03D018A05DA60054AD36B7D +:104760000BB1106C9847BDE8084002F07FBF00BF56 +:10477000000002403C36002008B5074B074A196884 +:1047800001F03D019960536C0BB1906C9847BDE806 +:10479000084002F06BBF00BF000402403C3600201E +:1047A00008B5084B1968890901F03D018A019A6032 +:1047B000054AD36C0BB1106D9847BDE8084002F074 +:1047C00055BF00BF000402403C36002008B5084B2E +:1047D0001968090C01F03D010A049A60054A536DFD +:1047E0000BB1906D9847BDE8084002F03FBF00BF95 +:1047F000000402403C36002008B5084B1968890DBA +:1048000001F03D018A059A60054AD36D0BB1106E27 +:104810009847BDE8084002F029BF00BF00040240ED +:104820003C36002008B5074B074A596801F03D01A6 +:10483000D960536E0BB1906E9847BDE8084002F006 +:1048400015BF00BF000402403C36002008B5084BED +:104850005968890901F03D018A01DA60054AD36E81 +:104860000BB1106F9847BDE8084002F0FFBE00BFD3 +:10487000000402403C36002008B5084B5968090C7A +:1048800001F03D010A04DA60054A536F0BB1906FE5 +:104890009847BDE8084002F0E9BE00BF00040240AE +:1048A0003C36002008B5084B5968890D01F03D01E0 +:1048B0008A05DA60054AD36F13B1D2F880009847B1 +:1048C000BDE8084002F0D2BE000402403C360020A1 +:1048D00000230C4910B51A460B4C0B6054F823000A +:1048E000026001EB430004334260402BF6D1074ADB +:1048F0004FF0FF339360D360C2F80834C2F80C3431 +:1049000010BD00BF3C360020949600080000024015 +:104910000F28F8B510D9102810D0112811D012285E +:1049200008D10F240720DFF8C8E00126DEF8005088 +:10493000A04208D9002653E00446F4E70F240020E3 +:10494000F1E70724FBE706FA00F73D424AD1264C7F +:104950004FEA001C3D4304EB00160EEBC000CEF8FE +:104960000050C0E90123FBB273B12048D0F8D83021 +:1049700043F00103C0F8D830D0F8003143F0010310 +:10498000C0F80031D0F8003117F47F4F0ED017482F +:10499000D0F8D83043F00203C0F8D830D0F8003156 +:1049A00043F00203C0F80031D0F8003154F80C0095 +:1049B000036823F01F030360056815F00105FBD1B0 +:1049C00004EB0C033D2493F80CC05F6804FA0CF46C +:1049D0003C6021240560446112B1987B00F060FCCA +:1049E0003046F8BD0130A3E7949600080044025811 +:1049F0003C36002010B5302484F31188FFF788FF7F +:104A0000002383F3118810BD10B50446807B00F0AD +:104A10005DFC01231549627B03FA02F20B6823EA6D +:104A20000203DAB20B6072B9114AD2F8D81021F041 +:104A30000101C2F8D810D2F8001121F00101C2F82A +:104A40000011D2F8002113F47F4F0ED1084BD3F898 +:104A5000D82022F00202C3F8D820D3F8002122F097 +:104A60000202C3F80021D3F8003110BD3C3600200B +:104A70000044025808B5302383F31188FFF7C4FFC0 +:104A8000002383F3118808BD836CC26A8B4250688F +:104A900010B506D95A1E4C0002EB4103B3FBF4F3E8 +:104AA000184410BD01F001038A0748BF43F0020318 +:104AB0004A0748BF43F008030A0748BF43F004030E +:104AC000CA0648BF43F010038A06426B48BF43F052 +:104AD000200313434363704710B5074C204600F092 +:104AE00061FF064B0022C4E91023054BA364054B6C +:104AF000E363054BE36410BDC03600200070005234 +:104B000000B4C4041437002014390020C36A0BB960 +:104B1000104BC3620379012B11D10F4B98420ED178 +:104B20000E4BD3F8D42042F48032C3F8D420D3F80B +:104B3000FC2042F48032C3F8FC20D3F8FC30436CF4 +:104B400000221A65DA621A605A605A624FF0FF3228 +:104B50009A63704794970008C036002000440258BA +:104B60000379012B1BD0436C00221A65DA621A60AC +:104B70005A605A624FF0FF329A63094B98420ED145 +:104B8000084BD3F8D42022F48032C3F8D420D3F8D1 +:104B9000FC2022F48032C3F8FC20D3F8FC307047AC +:104BA000C03600200044025810B5446C0649FFF797 +:104BB0006BFF6060236842F2107043F003032360D0 +:104BC000BDE8104001F0F4BC801A06000129F8B5D8 +:104BD000466C0B4F09D175680A493D40FFF754FFF9 +:104BE000054345F480557560F8BD746806493C403E +:104BF000FFF74AFF044344F480547460F4E700BFB5 +:104C000000ECFFFF80F0FA0240787D01436C002247 +:104C10005A601A6070470000426C0129536823F4FF +:104C2000404304D0022905D001B95360704743F4D2 +:104C30008043FAE743F40043F7E70000436C41F494 +:104C400080519A60D9605A6B1206FCD580229A6313 +:104C50007047000010B541F48851446CA260E160D7 +:104C6000616B11F04502FBD0A26311F0040203D086 +:104C7000FFF718FF012010BD616910461960FAE7BF +:104C800010B541F48851446CA260E160616B11F091 +:104C90004502FBD0A26311F0050203D0FFF702FF2B +:104CA000012010BD616910461960FAE773B513461B +:104CB00004460E46302282F31188426CD26B32B128 +:104CC0004FF0FF314030019301F07EFC019B606C9E +:104CD00000220265C263C262456B15F4807504D17F +:104CE00085F31188012002B070BD4FF0FF31816360 +:104CF00082F31188012E06D90C21204602B0BDE8AE +:104D00007040FFF7BDBF1046EDE7000073B5446C7F +:104D10000E4600250192616BA1632565E562FFF7F0 +:104D2000C1FE012E07D9019B2A460C2102B0BDE825 +:104D30007040FFF7A5BF02B070BD000010B541F490 +:104D40009851446CA260E160616B11F04502FBD0A8 +:104D5000A26311F03F0203D0FFF7A4FE012010BDB3 +:104D6000216A10461960E1695960A1699960616919 +:104D7000D960F4E72DE9F74304460191006D01A9DC +:104D80001746984602F09AFB064600284AD0626C05 +:104D90002046DDF804905568C5F3090501356B0020 +:104DA000A56CB5FBF3F54FF47A73B5FBF3F55D43F2 +:104DB000556200F0BDFD50BB636C4FF0FF32012522 +:104DC0004146C3F8589020461D659A634FF495728A +:104DD000DA6342F207029F62DA62E36C0A9AFFF733 +:104DE0004FFFA0B9E26C104B11680B407BB929460C +:104DF0002046FFF75BFF054648B92E463A46019923 +:104E0000206D02F093FB304603B0BDE8F0833A46D4 +:104E10000199206D02F08AFBE26C01212046FFF728 +:104E200075FFF0E70126EEE708E0FFFD2DE9F74307 +:104E30001F46436C01924FF47A725D6804468846BF +:104E4000C5F3090501356E00856CB5FBF6F5B5FBBC +:104E5000F2F555435D6200F06BFD20B10125284657 +:104E600003B0BDE8F0837E0201A9206D324602F056 +:104E700025FB05460028F1D0636C019AD4F84C90CC +:104E80009A6501221A654FF0FF329A634FF49572CA +:104E9000DA639E62236BDB064B4658BF4FEA482815 +:104EA000012F42461BD912212046FFF7E9FEC0B967 +:104EB000D9F80020104B13409BB9636C42F2930267 +:104EC00039462046DA62E26CFFF7F0FE804640B9D0 +:104ED00032460199206D454602F028FBBFE71121BB +:104EE000E2E732460199206D02F020FBE26C394680 +:104EF0002046FFF70BFFB2E708E0FFFD2DE9F34185 +:104F00001F46436C01924FF47A725D6804468846EE +:104F1000C5F3090501356E00856CB5FBF6F5B5FBEB +:104F2000F2F555435D6200F003FD20B101252846EE +:104F300002B0BDE8F0817E0201A9206D324602F088 +:104F400003FB05460028F1D0636C019A9A650122A3 +:104F50001A654FF0FF329A634FF48D72DA639E62E6 +:104F6000236BE66CDB06334658BF4FEA4828012F17 +:104F7000424619D919212046FFF782FEB0B932689E +:104F80000F4B134093B9636C42F2910239462046AD +:104F9000DA62E26CFFF78AFE064638B901993546B7 +:104FA000206D02F00DFBC2E71821E4E70199206DA6 +:104FB00002F006FBE26C39462046FFF7A7FEB6E793 +:104FC00008E0FFFD12F0030F2DE9F04107460C4603 +:104FD00015461E4617D00E44B44202D10020BDE84B +:104FE000F0810123FA6B21463846FFF71FFF0028A6 +:104FF000F5D128464FF40072F96B05F500750134C0 +:10500000FCF77EFEE8E7BDE8F041FFF70FBF0000C8 +:1050100012F0030F2DE9F04107460C4615461E46D7 +:1050200017D00E44B44202D10020BDE8F0812946D9 +:105030004FF40072F86B05F50075FCF761FE012373 +:10504000FA6B21463846FFF759FF0028EDD10134AD +:10505000E8E7BDE8F041FFF751BF000000207047CE +:10506000302310B583F311880024436C403021466F +:10507000DC6301F0B7FA84F3118810BD026843685D +:105080001143016003B1184770470000024A1368DA +:1050900043F0C003136070470078004013B50E4C16 +:1050A000204600F0DFFC04F1140000234FF40072EE +:1050B0000A49009400F07AF9094B4FF4007209494B +:1050C00004F13800009400F0F3F9074A074BC4E9F3 +:1050D000172302B010BD00BF18390020843900200A +:1050E0008D500008843B00200078004000E1F50569 +:1050F000037C30B5244C002918BF0C46012B11D17C +:10510000224B98420ED1224BD3F8E82042F0804245 +:10511000C3F8E820D3F8102142F08042C3F81021F0 +:10512000D3F810312268036EC16D03EB520384661D +:10513000B3FBF2F36268150442BF23F0070503F0E6 +:10514000070343EA4503CB60A36843F040034B6089 +:10515000E36843F001038B6042F4967343F001036C +:105160000B604FF0FF330B62510505D512F0102292 +:1051700005D0B2F1805F04D080F8643030BD7F2369 +:10518000FAE73F23F8E700BF9C9700081839002092 +:10519000004402582DE9F047C66D05463768F469AA +:1051A000210734621AD014F0080118BF4FF480713F +:1051B000E20748BF41F02001A3074FF0300348BF8A +:1051C00041F04001600748BF41F0800183F311883E +:1051D000281DFFF753FF002383F31188E2050AD54A +:1051E000302383F311884FF48061281DFFF746FFB9 +:1051F000002383F311884FF030094FF0000A14F0B8 +:10520000200838D13B0616D54FF0300905F1380A91 +:10521000200610D589F31188504600F07DF900284A +:1052200036DA0821281DFFF729FF27F080033360B5 +:10523000002383F31188790614D5620612D5302332 +:1052400083F31188D5E913239A4208D12B6C33B12B +:1052500027F040071021281DFFF710FF37600023BB +:1052600083F31188E30618D5AA6E1369ABB15069B0 +:10527000BDE8F047184789F31188736A284695F806 +:105280006410194000F008FC8AF31188F469B6E74D +:10529000B06288F31188F469BAE7BDE8F0870000CE +:1052A000090100F16043012203F56143C9B283F8AB +:1052B000001300F01F039A4043099B0003F1604371 +:1052C00003F56143C3F880211A60704700F01F03A3 +:1052D00001229A40430900F160409B0000F56140C3 +:1052E00003F1604303F56143C3F88020C3F88021D4 +:1052F000002380F800337047F8B5154682680446ED +:105300000B46AA4200D28568A1692669761AB54281 +:105310000BD218462A46FCF7F3FCA3692B44A36181 +:105320002846A3685B1BA360F8BD0CD9AF1B1846C9 +:105330003246FCF7E5FC3A46E1683044FCF7E0FC15 +:10534000E3683B44EBE718462A46FCF7D9FCE368E0 +:10535000E5E7000083689342F7B50446154600D29E +:105360008568D4E90460361AB5420BD22A46FCF7A8 +:10537000C7FC63692B4463612846A3685B1BA36079 +:1053800003B0F0BD0DD93246AF1B0191FCF7B8FC5C +:1053900001993A46E0683144FCF7B2FCE3683B44CB +:1053A000E9E72A46FCF7ACFCE368E4E710B50A44F9 +:1053B0000024C361029B8460C16002610362C0E992 +:1053C0000000C0E9051110BD08B5D0E905329342CF +:1053D00001D1826882B98268013282605A1C4261BE +:1053E00019700021D0E904329A4224BFC368436196 +:1053F00001F012F9002008BD4FF0FF30FBE700007C +:1054000070B5302304460E4683F31188A568A5B114 +:10541000A368A269013BA360531CA36115782269AC +:10542000934224BFE368A361E3690BB12046984728 +:10543000002383F31188284607E03146204601F017 +:10544000DBF80028E2DA85F3118870BD2DE9F74F0B +:1054500004460E4617469846D0F81C904FF0300A86 +:105460008AF311884FF0000B154665B12A46314684 +:105470002046FFF741FF034660B94146204601F050 +:10548000BBF80028F1D0002383F31188781B03B008 +:10549000BDE8F08FB9F1000F03D001902046C84756 +:1054A000019B8BF31188ED1A1E448AF31188DCE707 +:1054B000C160C361009B82600362C0E905111144B1 +:1054C000C0E9000001617047F8B504460D46164674 +:1054D000302383F31188A768A7B1A368013BA360B9 +:1054E00063695A1C62611D70D4E904329A4224BF78 +:1054F000E3686361E3690BB120469847002080F3BD +:10550000118807E03146204601F076F80028E2DAFB +:1055100087F31188F8BD0000D0E9052310B59A4241 +:1055200001D182687AB982680021013282605A1CF6 +:1055300082611C7803699A4224BFC368836101F0C9 +:105540006BF8204610BD4FF0FF30FBE72DE9F74F19 +:1055500004460E4617469846D0F81C904FF0300A85 +:105560008AF311884FF0000B154665B12A46314683 +:105570002046FFF7EFFE034660B94146204601F0A2 +:105580003BF80028F1D0002383F31188781B03B087 +:10559000BDE8F08FB9F1000F03D001902046C84755 +:1055A000019B8BF31188ED1A1E448AF31188DCE706 +:1055B0000379052B05BF836A002001204B6004BFDF +:1055C0004FF400730B60704770B55D1E866A044629 +:1055D0000D44B54205D9436B43F08003436301207A +:1055E00070BD06250571FFF7EDFC05232371F7E774 +:1055F00070B55D1E866A04460D44B54205D9436BFD +:1056000043F080034363012070BD07250571FFF758 +:10561000FFFC05232371F7E738B505790446052D0E +:1056200005D108230371FFF719FD257138BD01204D +:10563000FCE700000323F0B5037185B00446FFF7D3 +:10564000B3FA002220461146FFF7F8FA4FF4D5725C +:1056500003AB08212046FFF713FB0246B8B901232C +:105660002363039BC3F30323012B09D103AB37212E +:105670002046FFF705FB18B9A44B039A1340ABB1C2 +:1056800020460125FFF7C2FA0223237137E103AB5D +:10569000002237212046FFF7F3FA28B99B4A039BE3 +:1056A0001A40002A00F0A78002232363236B03F033 +:1056B0000F03022B40F0A9806425954E42F2107032 +:1056C00000F076FF03AB324601212046FFF7C2FA15 +:1056D0000028D5D1039B002B80F293805A0003D57C +:1056E000236B43F010032363002204F1080302211B +:1056F0002046FFF723FB02460028C1D104F13803FE +:1057000003212046FFF7BCFA0028B9D104F118059F +:10571000A26B092120462B46FFF710FB0028AFD1D2 +:1057200002ABA26B07212046FFF7AAFA0646002823 +:10573000A6D1236B03F00F03022B40F08F807E2253 +:105740007F21284603F0E4F9012840F28780E76BC7 +:1057500042F2107000F02CFF08234FF4007239461B +:1057600020460096FFF706FB002889D1384603F053 +:105770001DFA236BA06203F00F03022B72D103AB5F +:10578000644A06212046FFF77BFA002871D15F4961 +:10579000039B1940B1FA81F149092046FFF716FA37 +:1057A00002AB4FF4007210212046FFF769FA05465C +:1057B00000287FF465AF554E029B33427FF460AF03 +:1057C000236B13F00E0F03F00F0273D0022A7FF445 +:1057D00057AFE36A1978012900F09480022900F09C +:1057E0009380002900F089804B4F2046FFF714FA80 +:1057F00003AB3A4676E0114620462263FFF71EFAD5 +:1058000054E7013D7FF45AAF3AE7444D6426444AD9 +:105810003E4F012B18BF154603AB0022372120460F +:10582000FFF72EFA00287FF42BAF039B3B427FF457 +:1058300027AF03AB2A4629212046FFF70BFA0028A1 +:105840007FF41EAF039B002BFFF648AF013E3FF4F1 +:1058500017AF42F2107000F0ABFEDDE7284603F010 +:1058600079F986E77E227F212846E66B03F050F91E +:1058700008B9002191E700234022314620460093D9 +:105880000623FFF777FA0028F3D1B3895BBA9B07A9 +:10589000EFD5244B40223146204600930623FFF7E4 +:1058A00069FA0028E5D1317C01F00F010F3918BFEA +:1058B000012172E7E36A1978F9B101297FF4E0AEBA +:1058C0002046FFF7A9F903ABA26B37212046FFF76B +:1058D000D7F900287FF4D4AE039B33427FF4D0AED7 +:1058E00003AB022206212046FFF7CAF900287FF405 +:1058F000C7AE039B33427FF4C3AE05232371284612 +:1059000005B0F0BD084F70E7084F6EE708E0FFFDF7 +:105910000080FFC00001B9030000B7030080FF5002 +:1059200000001080F1FFFF800001B7030002B70301 +:1059300037B504460C4D01ABA26B0D212046FFF795 +:105940009FF978B9019B2B420BD1C3F34323042B5E +:1059500008D0053B022B04D84FF47A7000F028FEE3 +:10596000E9E7012003B030BD08E0FFFD70B530234A +:10597000054683F3118803790024022B03D184F3B5 +:105980001188204670BD0423037184F31188022618 +:10599000FFF7CEFF04462846FFF738F92E71F0E7EF +:1059A000FFF79AB8044B036001230371002343639C +:1059B000C0E90A33704700BFB497000810B5302320 +:1059C000044683F31188C162FFF7A0F80223002088 +:1059D000237180F3118810BD10B53023044683F382 +:1059E0001188FFF7BDF800230122E362227183F3DF +:1059F000118810BD026843681143016003B1184764 +:105A0000704700001430FFF721BD00004FF0FF3356 +:105A10001430FFF71BBD00003830FFF797BD0000C2 +:105A20004FF0FF333830FFF791BD00001430FFF71F +:105A3000E7BC00004FF0FF311430FFF7E1BC00007D +:105A40003830FFF741BD00004FF0FF323830FFF72C +:105A50003BBD0000012914BF6FF013000020704708 +:105A6000FFF71CBB044B036000234360C0E9023313 +:105A700001230374704700BFD897000810B5302386 +:105A8000044683F31188FFF733FB022300202374BD +:105A900080F3118810BD000038B5C36904460D4677 +:105AA0001BB904210844FFF7A5FF294604F114009F +:105AB000FFF78AFC002806DA201D4FF40061BDE8DC +:105AC0003840FFF797BF38BD026843681143016053 +:105AD00003B118477047000013B5406B00F58054C0 +:105AE000D4F8A4381A681178042914D1017C022949 +:105AF00011D11979012312898B4013420BD101A9CD +:105B00004C3002F033FFD4F8A4480246019B2179BF +:105B1000206800F0DFF902B010BD0000143002F080 +:105B2000B5BE00004FF0FF33143002F0AFBE0000EE +:105B30004C3002F087BF00004FF0FF334C3002F0D2 +:105B400081BF0000143002F083BE00004FF0FF312F +:105B5000143002F07DBE00004C3002F053BF000054 +:105B60004FF0FF324C3002F04DBF00000020704774 +:105B700010B500F58054D4F8A4381A6811780429B7 +:105B800017D1017C022914D15979012352898B4004 +:105B900013420ED1143002F015FE024648B1D4F87B +:105BA000A4484FF4407361792068BDE8104000F0CC +:105BB0007FB910BD406BFFF7DBBF000070470000EE +:105BC0007FB5124B012504260446036000230574AB +:105BD00000F1840243602946C0E902330C4B029075 +:105BE000143001934FF44073009602F0C7FD094B47 +:105BF00004F69442294604F14C000294CDE9006376 +:105C00004FF4407302F08EFE04B070BD009800089F +:105C1000B55B0008D95A00080A68302383F311885D +:105C20000B790B3342F823004B79133342F82300EE +:105C30008B7913B10B3342F8230000F58053C3F87E +:105C4000A41802230374002080F311887047000019 +:105C500038B5037F044613B190F85430ABB9012531 +:105C6000201D0221FFF730FF04F114006FF0010145 +:105C7000257700F0DDFC04F14C0084F854506FF0FF +:105C80000101BDE8384000F0D3BC38BD10B501219A +:105C900004460430FFF718FF0023237784F85430BC +:105CA00010BD000038B504460025143002F07EFD1A +:105CB00004F14C00257702F04DFE201D84F854506D +:105CC0000121FFF701FF2046BDE83840FFF750BF34 +:105CD00090F8803003F06003202B06D190F88120EB +:105CE0000023212A03D81F2A06D800207047222A21 +:105CF000FBD1C0E91D3303E0034A426707228267F4 +:105D0000C3670120704700BF3C22002037B500F573 +:105D10008055D5F8A4381A68117804291AD1017C65 +:105D2000022917D11979012312898B40134211D10D +:105D300000F14C04204602F0CDFE58B101A92046E6 +:105D400002F014FED5F8A4480246019B2179206890 +:105D500000F0C0F803B030BD01F10B03F0B550F80E +:105D6000236085B004460D46FEB1302383F31188CD +:105D700004EB8507301D0821FFF7A6FEFB6806F13E +:105D80004C005B691B681BB1019002F0FDFD01989E +:105D900003A902F0EBFD024648B1039B29462046C9 +:105DA00000F098F8002383F3118805B0F0BDFB687C +:105DB0005A691268002AF5D01B8A013B1340F1D1C1 +:105DC00004F18002EAE70000133138B550F82140B1 +:105DD000ECB1302383F3118804F58053D3F8A42861 +:105DE0001368527903EB8203DB689B695D6845B1F8 +:105DF00004216018FFF768FE294604F1140002F040 +:105E0000EBFC2046FFF7B4FE002383F3118838BD76 +:105E10007047000001F028BD01234022002110B589 +:105E2000044600F8303BFBF791FF0023C4E901333F +:105E300010BD000010B53023044683F311882422DE +:105E4000416000210C30FBF781FF204601F02EFD60 +:105E500002230020237080F3118810BD70B500EB81 +:105E60008103054650690E461446DA6018B11022C7 +:105E70000021FBF76BFFA06918B110220021FBF78E +:105E800065FF31462846BDE8704001F015BE0000B0 +:105E900083682022002103F0011310B504468360BB +:105EA0001030FBF753FF2046BDE8104001F090BED4 +:105EB000F0B4012500EB810447898D40E4683D433F +:105EC000A469458123600023A2606360F0BC01F0F7 +:105ED000ADBE0000F0B4012500EB810407898D40C0 +:105EE000E4683D436469058123600023A260636028 +:105EF000F0BC01F023BF000070B50223002504466A +:105F0000242203702946C0F888500C3040F8045C05 +:105F1000FBF71CFF204684F8705001F061FD6368B8 +:105F20001B6823B129462046BDE87040184770BD64 +:105F30000378052B10B504460AD080F88C30052371 +:105F4000037043681B680BB1042198470023A360CA +:105F500010BD00000178052906D190F88C20436817 +:105F600002701B6803B118477047000070B590F8C5 +:105F70007030044613B1002380F8703004F18002C1 +:105F8000204601F049FE63689B68B3B994F88030FD +:105F900013F0600535D00021204602F03BF90021C6 +:105FA000204602F02BF963681B6813B106212046D6 +:105FB0009847062384F8703070BD20469847002823 +:105FC000E4D0B4F88630A26F9A4288BFA36794F9F0 +:105FD0008030A56F002B4FF0300380F20381002D3D +:105FE00000F0F280092284F8702083F311880021E8 +:105FF0002046D4E91D23FFF76DFF002383F31188AA +:10600000DAE794F8812003F07F0343EA022340F2A9 +:106010000232934200F0C58021D8B3F5807F48D08A +:106020000DD8012B3FD0022B00F09380002BB2D172 +:1060300004F1880262670222A267E367C1E7B3F551 +:10604000817F00F09B80B3F5407FA4D194F882302B +:10605000012BA0D1B4F8883043F0020332E0B3F54D +:10606000006F4DD017D8B3F5A06F31D0A3F5C06342 +:10607000012B90D86368204694F882205E6894F8DB +:106080008310B4F88430B047002884D04368636735 +:106090000368A3671AE0B3F5106F36D040F60242EA +:1060A00093427FF478AF5C4B63670223A3670023BE +:1060B000C3E794F88230012B7FF46DAFB4F88830D9 +:1060C00023F00203A4F88830C4E91D55E56778E79A +:1060D000B4F88030B3F5A06F0ED194F8823020462A +:1060E00084F88A3001F0DAFC63681B6813B101217F +:1060F00020469847032323700023C4E91D339CE7FF +:1061000004F18B0363670123C3E72378042B10D1C9 +:10611000302383F311882046FFF7BAFE85F31188F8 +:106120000321636884F88B5021701B680BB12046F3 +:10613000984794F88230002BDED084F88B3004230B +:10614000237063681B68002BD6D002212046984735 +:10615000D2E794F8843020461D0603F00F010AD5DB +:1061600001F04CFD012804D002287FF414AF2B4B22 +:106170009AE72B4B98E701F033FDF3E794F8823070 +:10618000002B7FF408AF94F8843013F00F01B3D0E4 +:106190001A06204602D502F055F8ADE702F046F89F +:1061A000AAE794F88230002B7FF4F5AE94F884309F +:1061B00013F00F01A0D01B06204602D502F02AF8EA +:1061C0009AE702F01BF897E7142284F8702083F313 +:1061D00011882B462A4629462046FFF769FE85F39B +:1061E0001188E9E65DB1152284F8702083F31188E7 +:1061F00000212046D4E91D23FFF75AFEFDE60B22BD +:1062000084F8702083F311882B462A4629462046BD +:10621000FFF760FEE3E700BF309800082898000809 +:106220002C98000838B590F870300446002B3ED00A +:10623000063BDAB20F2A34D80F2B32D8DFE803F04E +:106240003731310822323131313131313131373763 +:10625000856FB0F886309D4214D2C3681B8AB5FBA7 +:10626000F3F203FB12556DB9302383F311882B46EB +:106270002A462946FFF72EFE85F311880A2384F863 +:1062800070300EE0142384F87030302383F31188CB +:10629000002320461A461946FFF70AFE002383F31F +:1062A000118838BDC36F03B198470023E7E7002189 +:1062B000204601F0AFFF0021204601F09FFF6368F8 +:1062C0001B6813B10621204698470623D7E7000034 +:1062D00010B590F870300446142B29D017D8062B2F +:1062E00005D001D81BB110BD093B022BFBD8002102 +:1062F000204601F08FFF0021204601F07FFF6368F8 +:106300001B6813B1062120469847062319E0152B78 +:10631000E9D10B2380F87030302383F311880023F8 +:106320001A461946FFF7D6FD002383F31188DAE7F2 +:10633000C3689B695B68002BD5D1C36F03B19847D5 +:10634000002384F87030CEE70023826880F8243080 +:1063500083691B6899689142FBD25A680360426066 +:1063600010605860704700000023826880F8243075 +:1063700083691B6899689142FBD85A680360426040 +:10638000106058607047000008B50846302383F35A +:10639000118891F82430032B05D0042B0DD02BB994 +:1063A00083F3118808BD8B6A00221A604FF0FF3317 +:1063B0008362FFF7C9FF0023F2E7D1E900321360DF +:1063C0005A60F3E7034610B51B68984203D09C68F7 +:1063D0008A689442F8D25A680B604A60116059602A +:1063E00010BD0000FFF7B0BF064BD96881F824004C +:1063F0001868026853601A600122D86080F824206F +:10640000FAF700B8883D00200C4B30B5DD684B1C16 +:1064100087B004460FD02B46094A684600F09CF925 +:106420002046FFF7E1FF009B13B1684600F09EF99C +:10643000A86A07B030BDFFF7D7FFF9E7883D002015 +:1064400089630008044B1A68DB6890689B6898426F +:1064500094BF002001207047883D0020094B10B5F3 +:106460001C68D868226853601A600122DC6084F8D6 +:106470002420FFF779FF01462046BDE81040F9F7D8 +:10648000C1BF00BF883D0020044B1A68DB689268DA +:106490009B689A4201D9FFF7E1BF7047883D002011 +:1064A00038B50123084C00252370656002F0ACFB71 +:1064B00002F0D2FB0549064802F0A8FC0223237033 +:1064C00085F3118838BD00BF30400020389800089F +:1064D000883D002000F080B9034A516853685B1A78 +:1064E0009842FBD8704700BF001000E08B604B6300 +:1064F0000023CA6100F128020B6302230A618B8426 +:106500000123886181F8263001F11003C26A4A61D3 +:106510001360C36201F12C030846CB627047000090 +:10652000D0E90131026841F8183CA1F19C033839E7 +:10653000CB60036941F8243C436941F8203C034B9C +:1065400041F8043CC3680248FFF7D0BF1D040008AF +:10655000883D002008B5FFF7E3FFBDE80840FFF7DE +:1065600041BF000038B50E4BDC6804F12C05A06279 +:10657000E06AA8420FD194F826303BB994F8253050 +:106580009B0702BFD4E9043213605A600F20BDE8B4 +:106590003840FFF729BF0368E362FFF723FFE7E70F +:1065A000883D0020302383F31188FFF7DBBF000014 +:1065B00008B50146302383F311880820FFF724FF34 +:1065C000002383F3118808BD054BDB6821B103600C +:1065D00098620320FFF718BF4FF0FF30704700BFED +:1065E000883D002003682BB10022026018469962A2 +:1065F000FFF7F8BE70470000064BDB6839B1426810 +:1066000018605A60136043600420FFF7FDBE4FF02E +:10661000FF307047883D00200368984206D01A6812 +:106620000260506018469962FFF7DCBE70470000B8 +:1066300038B504460D462068844200D138BD036851 +:1066400023605C608562FFF7CDFEF4E7036810B558 +:106650009C68A2420CD85C688A600B604C60216028 +:10666000596099688A1A9A604FF0FF33836010BDB1 +:10667000121B1B68ECE700000A2938BF0A2170B51D +:1066800004460D460A26601902F0B8FA02F0A0FA94 +:10669000041BA54203D8751C04462E46F3E70A2EB8 +:1066A00004D90120BDE8704002F078BC70BD000044 +:1066B000F8B5144B0D460A2A4FF00A07D96103F1C9 +:1066C0001001826038BF0A224160196914460160D6 +:1066D00048601861A81802F081FA02F079FA431BA9 +:1066E0000646A34206D37C1C28192746354602F0ED +:1066F00085FAF2E70A2F04D90120BDE8F84002F03C +:106700004DBCF8BD883D0020F8B506460D4602F0A8 +:106710005FFA0F4A134653F8107F9F4206D12A466C +:1067200001463046BDE8F840FFF7C2BFD169BB68FB +:10673000441A2C1928BF2C46A34202D92946FFF738 +:106740009BFF224631460348BDE8F840FFF77EBF75 +:10675000883D0020983D0020C0E90323002310B4A9 +:106760005DF8044B4361FFF7CFBF000010B5194C33 +:10677000236998420DD08168D0E9003213605A60D5 +:106780009A680A449A60002303604FF0FF33A361C4 +:1067900010BD0268234643F8102F536000220260A8 +:1067A00022699A4203D1BDE8104002F021BA9368F1 +:1067B00081680B44936002F00BFA2269E1699268E8 +:1067C000441AA242E4D91144BDE81040091AFFF767 +:1067D00053BF00BF883D00202DE9F047DFF8BC80A3 +:1067E00008F110072C4ED8F8105002F0F1F9D8F843 +:1067F0001C40AA68031B9A423ED814444FF000097B +:10680000D5E90032C8F81C4013605A60C5F8009002 +:10681000D8F81030B34201D102F0EAF989F31188B7 +:10682000D5E9033128469847302383F311886B69F3 +:10683000002BD8D002F0CCF96A69A0EB040982469B +:106840004A450DD2022002F0A9FB0022D8F81030F0 +:10685000B34208D151462846BDE8F047FFF728BFAC +:10686000121A2244F2E712EB09092946384638BFCA +:106870004A46FFF7EBFEB5E7D8F81030B34208D030 +:106880001444C8F81C00211AA960BDE8F047FFF7BE +:10689000F3BEBDE8F08700BF983D0020883D002092 +:1068A00038B502F095F9054AD2E90845031B1819D5 +:1068B00045F10001C2E9080138BD00BF883D002054 +:1068C00010B560B9074804790368053C9B6818BF98 +:1068D0000124984708B144F00404204610BD012467 +:1068E000FBE700BFC0360020FFF7EABF2DE9F04705 +:1068F000884617469A460446B0B90D4E3579052D9F +:1069000005D003240DE0013D15F0FF050ED03268DF +:10691000534639463046D2F814904246C8470028BC +:10692000F1D12046BDE8F0870424FAE70124F8E716 +:10693000C03600202DE9F047884617469A4604469F +:10694000B0B90D4E3579052D05D003240DE0013D7C +:1069500015F0FF050ED03268534639463046D2F85E +:1069600018904246C8470028F1D12046BDE8F0877C +:106970000424FAE70124F8E7C036002037B50C46B6 +:10698000154670B951B101290BD107486946036812 +:106990001B6A984710B9019B04462B60204603B040 +:1069A00030BD0424FAE700BFC03600200020704745 +:1069B000FEE70000704700004FF0FF307047000016 +:1069C0004B6843608B688360CB68C3600B6943612D +:1069D0004B6903628B6943620B6803607047000078 +:1069E00008B53C4B40F2FF713B48D3F888200A437E +:1069F000C3F88820D3F8882022F4FF6222F007022F +:106A0000C3F88820D3F88820D3F8E0200A43C3F8DD +:106A1000E020D3F808210A43C3F808212F4AD3F80D +:106A200008311146FFF7CCFF00F5806002F11C0130 +:106A3000FFF7C6FF00F5806002F13801FFF7C0FFE5 +:106A400000F5806002F15401FFF7BAFF00F58060A5 +:106A500002F17001FFF7B4FF00F5806002F18C01D4 +:106A6000FFF7AEFF00F5806002F1A801FFF7A8FF75 +:106A700000F5806002F1C401FFF7A2FF00F580601D +:106A800002F1E001FFF79CFF00F5806002F1FC01DC +:106A9000FFF796FF02F58C7100F58060FFF790FF1D +:106AA00001F068FC0E4BD3F8902242F00102C3F8CB +:106AB0009022D3F8942242F00102C3F894220522D6 +:106AC000C3F898204FF06052C3F89C20054AC3F8E1 +:106AD000A02008BD00440258000002584C9800084D +:106AE00000ED00E01F00080308B501F033FEFFF7DA +:106AF000D7FC104BD3F8DC2042F04002C3F8DC2076 +:106B0000D3F8042122F04002C3F80421D3F8043161 +:106B1000094B1A6842F008021A601A6842F004022F +:106B20001A6000F055FD00F035FBBDE8084000F0AC +:106B3000B5B800BF00440258001802480120704751 +:106B4000002070477047000002290CD0032904D0B0 +:106B50000129074818BF00207047032A05D80548B7 +:106B600000EBC2007047044870470020704700BF28 +:106B70004C9A00084C220020009A000870B59AB088 +:106B800005460846144601A900F0C2F801A8FBF723 +:106B9000D5F8431C0022C6B25B001046C5E900349C +:106BA00023700323023404F8013C01ABD1B2023458 +:106BB0008E4201D81AB070BD13F8011B013204F8DF +:106BC000010C04F8021CF1E708B5302383F31188A7 +:106BD0000348FFF79BF8002383F3118808BD00BF2B +:106BE0003840002090F8803003F01F02012A07D1BE +:106BF00090F881200B2A03D10023C0E91D3315E052 +:106C000003F06003202B08D1B0F884302BB990F842 +:106C10008120212A03D81F2A04D8FFF759B8222A35 +:106C2000EBD0FAE7034A426707228267C367012075 +:106C3000704700BF4322002007B5052917D8DFE8B9 +:106C400001F0191603191920302383F31188104A13 +:106C500001210190FFF702F9019802210D4AFFF787 +:106C6000FDF80D48FFF71EF8002383F3118803B0E9 +:106C70005DF804FB302383F311880748FEF7E8FF33 +:106C8000F2E7302383F311880348FEF7FFFFEBE7B9 +:106C9000A0990008C49900083840002038B50C4D70 +:106CA0000C4C2A460C4904F10800FFF767FF05F178 +:106CB000CA0204F110000949FFF760FF05F5CA7226 +:106CC00004F118000649BDE83840FFF757BF00BF80 +:106CD000105900204C220020809900088A99000851 +:106CE0009599000870B5044608460D46FBF726F84E +:106CF000C6B22046013403780BB9184670BD32463F +:106D00002946FBF707F80028F3D10120F6E7000039 +:106D10002DE9F84F05460C46FBF710F82C49C6B292 +:106D20002846FFF7DFFF08B10536F6B229492846A5 +:106D3000FFF7D8FF08B11036F6B2632E0DD8DFF892 +:106D40009080DFF89090244FDFF894A0DFF894B0A3 +:106D50002E7846B92670BDE8F88F29462046BDE852 +:106D6000F84F02F0C5B9252E2ED1072241462846FC +:106D7000FAF7D0FF70B9DBF8003007350C3444F86F +:106D80000C3CDBF8043044F8083CDBF8083044F8ED +:106D9000043CDDE7082249462846FAF7BBFF98B9CC +:106DA000A21C0E4B197802320909C95D02F8041CB5 +:106DB00013F8011B01F00F015345C95D02F8031CD4 +:106DC000F0D118340835C3E7013504F8016BBFE78B +:106DD0006C9A000895990008819A000800E8F11F54 +:106DE0000CE8F11F749A0008BFF34F8F044B1A6927 +:106DF0005107FCD1D3F810215207F8D1704700BFDA +:106E00000020005208B50D4B1B78ABB9FFF7ECFF23 +:106E10000B4BDA68D10704D50A4A5A6002F188326E +:106E20005A60D3F80C21D20706D5064AC3F80421CC +:106E300002F18832C3F8042108BD00BF6E5B002058 +:106E4000002000522301674508B5114B1B78F3B9A8 +:106E5000104B1A69510703D5DA6842F04002DA6034 +:106E6000D3F81021520705D5D3F80C2142F0400287 +:106E7000C3F80C21FFF7B8FF064BDA6842F00102B5 +:106E8000DA60D3F80C2142F00102C3F80C2108BDEE +:106E90006E5B0020002000520F289ABF00F5806032 +:106EA00040040020704700004FF40030704700009D +:106EB000102070470F2808B50BD8FFF7EDFF00F53D +:106EC00000330268013204D104308342F9D1012039 +:106ED00008BD0020FCE700000F2838B505463FD864 +:106EE000FFF782FF1F4CFFF78DFF4FF0FF3307289E +:106EF0006361C4F814311DD82361FFF775FF0302E5 +:106F000043F02403E360E36843F08003E360236914 +:106F10005A07FCD42846FFF767FFFFF7BDFF4FF481 +:106F2000003100F08FFA2846FFF78EFFBDE83840A9 +:106F3000FFF7C0BFC4F81031FFF756FFA0F10803F8 +:106F40001B0243F02403C4F80C31D4F80C3143F095 +:106F50008003C4F80C31D4F810315B07FBD4D9E7B7 +:106F6000002038BD002000522DE9F84F05460C46A0 +:106F7000104645EA0203DE0602D00020BDE8F88F85 +:106F800020F01F00DFF8BCB0DFF8BCA0FFF73AFF2D +:106F900004EB0008444503D10120FFF755FFEDE75E +:106FA00020222946204602F06BF810B92035203403 +:106FB000F0E72B4605F120021F68791CDDD1043370 +:106FC0009A42F9D105F178431B481C4EB3F5801F56 +:106FD0001B4B38BF184603F1F80332BFD946D146E0 +:106FE0001E46FFF701FF0760A5EB040C336804F1B0 +:106FF0001C0143F002033360231FD9F8007017F01F +:107000000507FAD153F8042F8B424CF80320F4D132 +:10701000BFF34F8FFFF7E8FE4FF0FF3320222146EA +:1070200003602846336823F00203336002F028F837 +:107030000028BBD03846B0E7142100520C20005283 +:1070400014200052102000521021005210B5084C9C +:10705000237828B11BB9FFF7D5FE0123237010BD9B +:10706000002BFCD02070BDE81040FFF7EDBE00BF44 +:107070006E5B00202DE9F04F0D4685B0814658B17A +:1070800011F00D0614BF2022082211F0080301930D +:1070900004D0431E034269D0002435E0002E37D0CF +:1070A00009F11F0121F01F094FF00108314F05F0D0 +:1070B0000403DFF8CCA005EA080BBBF1000F32D0C7 +:1070C0007869C0072FD408F101080C37B8F1060F12 +:1070D000F3D19EB9284D4946A819019201F0DEFD71 +:1070E0000446002839D12036019AA02EF3D1494612 +:1070F00001F0D4FD044600282FD1019A49461F48CB +:1071000001F0CCFD044660BB204605B0BDE8F08F21 +:107110000029C9D101462846029201F0BFFD04466C +:10712000D8B9029AC0E713B178694107CBD5AC074B +:1071300002D578698007C6D5019911B17869010730 +:10714000C1D549460AEB4810CDE9022301F0A6FD5E +:107150000446DDE902230028B5D04A460021204636 +:1071600001E04A460021FAF7F1FDCDE70246002E84 +:1071700096D199E7949A0008B05B0020705B0020DC +:10718000905B00200021FFF775BF00000121FFF791 +:1071900071BF000070B5144D0124144E40F2FF324F +:1071A00000210120FAF7D2FD06EB441001342A69D0 +:1071B00055F80C1F01F05EFD062CF5D137254FF474 +:1071C000C0542046FFF7E2FF014628B12246084896 +:1071D000BDE8704001F04EBDC4EBC404013D4FEA70 +:1071E000D404EED170BD00BF949A0008905B0020DB +:1071F000705B00200421FFF73DBF00004843FFF70C +:10720000C1BF000008B101F0BBBD7047B0F5805FA1 +:1072100010B5044607D8FFF7EDFF28B92046BDE8B2 +:107220001040FFF7AFBF002010BD0000FFF7EABF1E +:1072300070B5AAB140EA010313F01F030FD1094C46 +:107240000144A5686D0706D52568A84203D3666882 +:107250003544A94204D903330C34122BF1D1002256 +:10726000104670BD949A000808B501F09FFE034ACD +:10727000D2E90032C01842EB010108BD505C002089 +:10728000434BD3E900232DE9F34113437CD0FFF7AF +:10729000EBFF404A00230027F9F7CEF806460D46DB +:1072A0003D4A0023F9F7C8F8002314463046294622 +:1072B000394AF9F7C1F84FF461613C23ADF8017028 +:1072C000B4FBF1F5B4FBF3F601FB154103FB1646E5 +:1072D0004624B1FBF3F1314BF6B28DF800409842F1 +:1072E0003CD84FF0640C4FF4C87EA30704F26C72D4 +:1072F00025D1B2FBFCF30CFB132313BBB2FBFEF353 +:107300000EFB1322B2FA82F35B0903F26D18621CC2 +:107310008045D2B217D90FB18DF800400022204C21 +:107320004FF00C0C17460CFB0343D4B2013213F898 +:1073300004C084450CD8A0EB0C000127F5E700231E +:10734000E3E70123E1E7A0EB080014460127CCE7BF +:107350000FB18DF80140431C8DF802309DF80100FB +:10736000431C9DF800005038400640EA43509DF809 +:10737000023040EA034040EA560040EAC52040EAB5 +:10738000411002B0BDE8F0814FF40410F9E700BFEE +:10739000505C002040420F008051010090230B0000 +:1073A000DC9A00080244074BD2B210B5904200D1DB +:1073B00010BD441C00B253F8200041F8040BE0B2A9 +:1073C000F4E700BF504000580E4B30B51C6F24044A +:1073D00005D41C6F1C671C6F44F400441C670A4CE6 +:1073E00002442368D2B243F480732360074B904277 +:1073F00000D130BD441C51F8045B00B243F820506A +:10740000E0B2F4E7004402580048025850400058E7 +:1074100007B5012201A90020FFF7C4FF019803B0BE +:107420005DF804FB13B50446FFF7F2FFA04205D058 +:10743000012201A900200194FFF7C6FF02B010BD90 +:10744000704700000144BFF34F8F064B884204D3BE +:10745000BFF34F8FBFF36F8F7047C3F85C022030CC +:10746000F4E700BF00ED00E00144BFF34F8F064B8F +:10747000884204D3BFF34F8FBFF36F8F7047C3F8B9 +:1074800070022030F4E700BF00ED00E070B5054663 +:1074900016460C4601201021FFF7B0FE2860467307 +:1074A0003CB1204636B1FFF7A5FE2B68186000B14D +:1074B0009C6070BDFFF76AFEF7E70000F8B50F4665 +:1074C0001546044648B905F11F010126386821F028 +:1074D0001F01FFF7B7FF3046F8BD427B29463868E9 +:1074E000FFF7A6FE06460028EDD13B686360A3685F +:1074F000AB4210D213B12068FFF784FE637B2846AD +:107500002BB1FFF777FE206020B9A060E3E7FFF71B +:107510003DFEF8E7A560206805F11F01012621F076 +:107520001F013860FFF78EFF2673D4E710B50446BD +:1075300040B10068884205D1606808B1FAF7E0FB05 +:107540000023237310BD0000F8B50F46144605460E +:1075500048B904F11F010126386821F01F01FFF727 +:1075600083FF3046F8BD427B21463868FFF760FE56 +:1075700006460028EDD1AB68A34210D213B12868AB +:10758000FFF740FE6B7B20462BB1FFF733FE2860F0 +:1075900020B9A860E5E7FFF7F9FDF8E7AC603968C6 +:1075A00019B122462868FAF7ABFB286804F11F01DD +:1075B000012621F01F013860FFF756FF2E73D0E738 +:1075C00020B103688B4204BF00230373704700009F +:1075D000034B1A681AB9034AD2F8D0241A607047CC +:1075E000585C00200040025808B5FFF7F1FF024B3D +:1075F0001868C0F3806008BD585C0020EFF3098371 +:10760000054968334A6B22F001024A6383F3098813 +:10761000002383F31188704700EF00E0302080F3EF +:10762000118862B60D4B0E4AD96821F4E061090455 +:10763000090C0A430B49DA60D3F8FC2042F080724F +:10764000C3F8FC20084AC2F8B01F116841F00101DC +:1076500011602022DA7783F82200704700ED00E005 +:107660000003FA0555CEACC5001000E0302310B57C +:1076700083F311880E4B5B6813F4006314D0F1EEB2 +:10768000103AEFF309844FF08073683CE361094BD3 +:10769000DB6B236684F30988FEF7D4FE10B1064B3A +:1076A000A36110BD054BFBE783F31188F9E700BF29 +:1076B00000ED00E000EF00E02F04000832040008B5 +:1076C00070B5BFF34F8FBFF36F8F1A4A0021C2F816 +:1076D0005012BFF34F8FBFF36F8F536943F40033E2 +:1076E0005361BFF34F8FBFF36F8FC2F88410BFF3A6 +:1076F0004F8FD2F8803043F6E074C3F3C900C3F370 +:107700004E335B0103EA0406014646EA81750139FE +:10771000C2F86052F9D2203B13F1200FF2D1BFF32F +:107720004F8F536943F480335361BFF34F8FBFF3DF +:107730006F8F70BD00ED00E0FEE70000214B224896 +:10774000224A70B5904237D3214BC11EDA1C121A5F +:1077500022F003028B4238BF00220021FAF7F6FA2A +:107760001C4A0023C2F88430BFF34F8FD2F8803018 +:1077700043F6E074C3F3C900C3F34E335B0103EA7D +:107780000406014646EA81750139C2F86C52F9D205 +:10779000203B13F1200FF2D1BFF34F8FBFF36F8F58 +:1077A000BFF34F8FBFF36F8F0023C2F85032BFF388 +:1077B0004F8FBFF36F8F70BD53F8041B40F8041B4D +:1077C000C0E700BFDC9B0008545E0020545E002030 +:1077D000545E002000ED00E0074BD3F8D81021EAFA +:1077E0000001C3F8D810D3F8002122EA0002C3F840 +:1077F0000021D3F8003170470044025870B5D0E939 +:10780000244300224FF0FF359E6804EB42135101E0 +:10781000D3F80009002805DAD3F8000940F08040C9 +:10782000C3F80009D3F8000B002805DAD3F8000BE1 +:1078300040F08040C3F8000B013263189642C3F851 +:107840000859C3F8085BE0D24FF00113C4F81C38A4 +:1078500070BD0000890141F02001016103699B06B0 +:10786000FCD41220FEF738BE10B50A4C2046FEF7B5 +:10787000D3FA094BC4F89030084BC4F89430084C44 +:107880002046FEF7C9FA074BC4F89030064BC4F8FF +:10789000943010BD5C5C002000000840189B00087C +:1078A000F85C002000000440249B000870B50378B9 +:1078B0000546012B5CD1434BD0F89040984258D1FB +:1078C000414B0E216520D3F8D82042F00062C3F866 +:1078D000D820D3F8002142F00062C3F80021D3F889 +:1078E0000021D3F8802042F00062C3F88020D3F852 +:1078F000802022F00062C3F88020D3F88030FDF7AA +:10790000CFFC324BE360324BC4F800380023D5F88B +:107910009060C4F8003EC02323604FF40413A363B7 +:107920003369002BFCDA01230C203361FEF7D4FD10 +:107930003369DB07FCD41220FEF7CEFD3369002B40 +:10794000FCDA00262846A660FFF758FF6B68C4F8EB +:107950001068DB68C4F81468C4F81C6883BB1D4B4E +:10796000A3614FF0FF336361A36843F00103A36099 +:1079700070BD194B9842C9D1134B4FF08060D3F8BA +:10798000D82042F00072C3F8D820D3F8002142F08A +:107990000072C3F80021D3F80021D3F8802042F010 +:1079A0000072C3F88020D3F8802022F00072C3F860 +:1079B0008020D3F88030FFF70FFF0E214D209EE787 +:1079C000064BCDE75C5C00200044025840140040A8 +:1079D00003002002003C30C0F85C0020083C30C0AE +:1079E000F8B5D0F89040054600214FF000662046DB +:1079F000FFF730FFD5F8941000234FF001128F6885 +:107A00004FF0FF30C4F83438C4F81C2804EB43129C +:107A100001339F42C2F80069C2F8006BC2F808093E +:107A2000C2F8080BF2D20B68D5F89020C5F8983050 +:107A3000636210231361166916F01006FBD1122041 +:107A4000FEF74AFDD4F8003823F4FE63C4F800388A +:107A5000A36943F4402343F01003A3610923C4F84E +:107A60001038C4F814380B4BEB604FF0C043C4F827 +:107A7000103B094BC4F8003BC4F81069C4F8003946 +:107A8000D5F8983003F1100243F48013C5F898201C +:107A9000A362F8BDF49A000840800010D0F890204E +:107AA00090F88A10D2F8003823F4FE6343EA0113F9 +:107AB000C2F80038704700002DE9F84300EB81035D +:107AC000D0F890500C468046DA680FFA81F94801E8 +:107AD000166806F00306731E022B05EB41134FF0E8 +:107AE000000194BFB604384EC3F8101B4FF00101DB +:107AF00004F1100398BF06F1805601FA03F391696F +:107B000098BF06F5004600293AD0578A04F158017B +:107B1000374349016F50D5F81C180B430021C5F8B5 +:107B20001C382B180127C3F81019A7405369611E90 +:107B30009BB3138A928B9B08012A88BF5343D8F8C2 +:107B40009820981842EA034301F140022146C8F800 +:107B50009800284605EB82025360FFF77BFE08EB96 +:107B60008900C3681B8A43EA845348341E43640176 +:107B70002E51D5F81C381F43C5F81C78BDE8F88392 +:107B800005EB4917D7F8001B21F40041C7F8001B8B +:107B9000D5F81C1821EA0303C0E704F13F030B4AA0 +:107BA0002846214605EB83035A60FFF753FE05EB99 +:107BB0004910D0F8003923F40043C0F80039D5F853 +:107BC0001C3823EA0707D7E70080001000040002F2 +:107BD000D0F894201268C0F89820FFF70FBE00007C +:107BE0005831D0F8903049015B5813F4004004D06C +:107BF00013F4001F0CBF0220012070474831D0F859 +:107C0000903049015B5813F4004004D013F4001F76 +:107C10000CBF02200120704700EB8101CB68196A7C +:107C20000B6813604B6853607047000000EB8103E2 +:107C300030B5DD68AA691368D36019B9402B84BFD9 +:107C4000402313606B8A1468D0F890201C4402EB28 +:107C50004110013C09B2B4FBF3F46343033323F056 +:107C6000030343EAC44343F0C043C0F8103B2B680E +:107C700003F00303012B0ED1D2F8083802EB4110B8 +:107C800013F4807FD0F8003B14BF43F0805343F0DF +:107C90000053C0F8003B02EB4112D2F8003B43F026 +:107CA0000443C2F8003B30BD2DE9F041D0F89060AC +:107CB00005460C4606EB4113D3F8087B3A07C3F898 +:107CC000087B08D5D6F814381B0704D500EB8103D0 +:107CD000DB685B689847FA071FD5D6F81438DB07CE +:107CE0001BD505EB8403D968CCB98B69488A5A68DF +:107CF000B2FBF0F600FB16228AB91868DA689042E7 +:107D00000DD2121AC3E90024302383F311882146CF +:107D10002846FFF78BFF84F31188BDE8F08101232B +:107D200003FA04F26B8923EA02036B81CB68002B10 +:107D3000F3D021462846BDE8F041184700EB810307 +:107D40004A0170B5DD68D0F890306C692668E6604D +:107D500056BB1A444FF40020C2F810092A6802F0FA +:107D60000302012A0AB20ED1D3F8080803EB421429 +:107D700010F4807FD4F8000914BF40F0805040F028 +:107D80000050C4F8000903EB4212D2F8000940F099 +:107D90000440C2F800090122D3F8340802FA01F1C4 +:107DA0000143C3F8341870BD19B9402E84BF402078 +:107DB000206020681A442E8A8419013CB4FBF6F432 +:107DC00040EAC44040F00050C6E700002DE9F84307 +:107DD000D0F8906005460C464F0106EB4113D3F8EE +:107DE000088918F0010FC3F808891CD0D6F810389C +:107DF000DB0718D500EB8103D3F80CC0DCF8143096 +:107E0000D3F800E0DA68964530D2A2EB0E024FF0CC +:107E100000091A60C3F80490302383F31188FFF738 +:107E20008DFF89F3118818F0800F1DD0D6F83438F3 +:107E30000126A640334217D005EB84030134D5F860 +:107E40009050D3F80CC0E4B22F44DCF8142005EBBA +:107E50000434D2F800E05168714514D3D5F83438B1 +:107E600023EA0606C5F83468BDE8F883012303FA5F +:107E700001F2038923EA02030381DCF80830002BB6 +:107E8000D1D09847CFE7AEEB0103BCF81000834296 +:107E900028BF0346D7F8180980B2B3EB800FE3D8A8 +:107EA0009068A0F1040959F8048FC4F80080A0EB91 +:107EB00009089844B8F1040FF5D818440B449060B1 +:107EC0005360C8E72DE9F84FD0F8905004466E692A +:107ED000AB691E4016F480586E6103D0BDE8F84FC0 +:107EE000FEF70AB8002E12DAD5F8003E9B0705D03F +:107EF000D5F8003E23F00303C5F8003ED5F804385A +:107F0000204623F00103C5F80438FEF723F83705AF +:107F100005D52046FFF772FC2046FEF709F8B004AD +:107F20000CD5D5F8083813F0060FEB6823F470531E +:107F30000CBF43F4105343F4A053EB6031071BD53F +:107F40006368DB681BB9AB6923F00803AB61237876 +:107F5000052B0CD1D5F8003E9A0705D0D5F8003E88 +:107F600023F00303C5F8003E2046FDF7F3FF6368E6 +:107F7000DB680BB120469847F30200F1BA80B702E4 +:107F800026D5D4F8909000274FF0010A09EB47124C +:107F9000D2F8003B03F44023B3F5802F11D1D2F87F +:107FA000003B002B0DDA62890AFA07F322EA030389 +:107FB000638104EB8703DB68DB6813B13946204635 +:107FC00098470137D4F89430FFB29B689F42DDD9BF +:107FD000F00619D5D4F89000026AC2F30A1702F02D +:107FE0000F0302F4F012B2F5802F00F0CA80B2F550 +:107FF000402F09D104EB8303002200F58050DB6899 +:108000001B6A974240F0B0803003D5F8185835D538 +:10801000E90303D500212046FFF746FEAA0303D556 +:1080200001212046FFF740FE6B0303D502212046C5 +:10803000FFF73AFE2F0303D503212046FFF734FE56 +:10804000E80203D504212046FFF72EFEA90203D53E +:1080500005212046FFF728FE6A0203D506212046A7 +:10806000FFF722FE2B0203D507212046FFF71CFE57 +:10807000EF0103D508212046FFF716FE700340F1FB +:10808000A780E90703D500212046FFF79FFEAA0736 +:1080900003D501212046FFF799FE6B0703D5022186 +:1080A0002046FFF793FE2F0703D503212046FFF755 +:1080B0008DFEEE0603D504212046FFF787FEA806B5 +:1080C00003D505212046FFF781FE690603D5062169 +:1080D0002046FFF77BFE2A0603D507212046FFF73F +:1080E00075FEEB0574D520460821BDE8F84FFFF773 +:1080F0006DBED4F890904FF0000B4FF0010AD4F809 +:1081000094305FFA8BF79B689F423FF638AF09EBDC +:108110004713D3F8002902F44022B2F5802F20D172 +:10812000D3F80029002A1CDAD3F8002942F0904243 +:10813000C3F80029D3F80029002AFBDB3946D4F81C +:108140009000FFF787FB22890AFA07F322EA03036C +:10815000238104EB8703DB689B6813B13946204613 +:1081600098470BF1010BCAE7910701D1D0F80080C5 +:10817000072A02F101029CBF03F8018B4FEA18287D +:108180003FE704EB830300F58050DA68D2F818C0AB +:10819000DCF80820DCE9001CA1EB0C0C00218F426C +:1081A00008D1DB689B699A683A449A605A683A44F5 +:1081B0005A6029E711F0030F01D1D0F800808C45F7 +:1081C00001F1010184BF02F8018B4FEA1828E6E7AC +:1081D000BDE8F88F08B50348FFF774FEBDE8084016 +:1081E000FFF744BA5C5C002008B50348FFF76AFE5D +:1081F000BDE80840FFF73ABAF85C0020D0F89030AC +:1082000003EB4111D1F8003B43F40013C1F8003BEC +:1082100070470000D0F8903003EB4111D1F80039DD +:1082200043F40013C1F8003970470000D0F89030D3 +:1082300003EB4111D1F8003B23F40013C1F8003BDC +:1082400070470000D0F8903003EB4111D1F80039AD +:1082500023F40013C1F8003970470000064BD3F82F +:10826000DC200243C3F8DC20D3F804211043C3F818 +:108270000401D3F8043170470044025808B53C4B60 +:108280004FF0FF31D3F8802062F00042C3F8802025 +:10829000D3F8802002F00042C3F88020D3F8802079 +:1082A000D3F88420C3F88410D3F884200022C3F8C4 +:1082B0008420D3F88400D86F40F0FF4040F4FF00E2 +:1082C00040F4DF4040F07F00D867D86F20F0FF40D7 +:1082D00020F4FF0020F4DF4020F07F00D867D86F43 +:1082E000D3F888006FEA40506FEA5050C3F8880016 +:1082F000D3F88800C0F30A00C3F88800D3F88800D8 +:10830000D3F89000C3F89010D3F89000C3F89020F1 +:10831000D3F89000D3F89400C3F89410D3F89400E5 +:10832000C3F89420D3F89400D3F89800C3F89810B9 +:10833000D3F89800C3F89820D3F89800D3F88C00AD +:10834000C3F88C10D3F88C00C3F88C20D3F88C00C1 +:10835000D3F89C00C3F89C10D3F89C10C3F89C2061 +:10836000D3F89C30FCF7B4FABDE8084000F0C2B97D +:108370000044025808B50122534BC3F80821534B5F +:10838000D3F8F42042F00202C3F8F420D3F81C2101 +:1083900042F00202C3F81C210222D3F81C314C4BDC +:1083A000DA605A689104FCD54A4A1A6001229A6040 +:1083B000494ADA6000221A614FF440429A61444B04 +:1083C0009A699204FCD51A6842F480721A603F4B95 +:1083D0001A6F12F4407F04D04FF480321A670022E3 +:1083E0001A671A6842F001021A60384B1A6850077F +:1083F000FCD500221A611A6912F03802FBD1012162 +:1084000019604FF0804159605A67344ADA62344A41 +:108410001A611A6842F480321A602C4B1A68910370 +:10842000FCD51A6842F480521A601A689204FCD58E +:108430002C4A2D499A6200225A63196301F57C0186 +:10844000DA6301F2E71199635A64284A1A64284AE8 +:10845000DA621A6842F0A8521A601C4B1A6802F0DD +:108460002852B2F1285FF9D148229A614FF488620C +:10847000DA6140221A621F4ADA641F4A1A651F4AEB +:108480005A651F4A9A6532231E4A1360136803F027 +:108490000F03022BFAD10D4A136943F00303136152 +:1084A000136903F03803182BFAD14FF00050FFF78F +:1084B000D5FE4FF08040FFF7D1FE4FF00040BDE801 +:1084C0000840FFF7CBBE00BF0080005100440258B7 +:1084D0000048025800C000F0020000010000FF0147 +:1084E000008890081210200063020901470E050859 +:1084F000DD0BBF0120000020000001100910E0008A +:1085000000010110002000524FF0B04208B5D2F82F +:10851000883003F00103C2F8883023B1044A13689D +:108520000BB150689847BDE80840FFF79FB800BFFF +:10853000D45D00204FF0B04208B5D2F8883003F087 +:108540000203C2F8883023B1044A93680BB1D068A3 +:108550009847BDE80840FFF789B800BFD45D002008 +:108560004FF0B04208B5D2F8883003F00403C2F8E7 +:10857000883023B1044A13690BB150699847BDE8AC +:108580000840FFF773B800BFD45D00204FF0B04241 +:1085900008B5D2F8883003F00803C2F8883023B158 +:1085A000044A93690BB1D0699847BDE80840FFF7CA +:1085B0005DB800BFD45D00204FF0B04208B5D2F8DE +:1085C000883003F01003C2F8883023B1044A136ADC +:1085D0000BB1506A9847BDE80840FFF747B800BFA5 +:1085E000D45D00204FF0B04310B5D3F8884004F4B8 +:1085F0007872C3F88820A30604D5124A936A0BB197 +:10860000D06A9847600604D50E4A136B0BB1506BC5 +:108610009847210604D50B4A936B0BB1D06B984752 +:10862000E20504D5074A136C0BB1506C9847A305BB +:1086300004D5044A936C0BB1D06C9847BDE8104048 +:10864000FFF714B8D45D00204FF0B04310B5D3F855 +:10865000884004F47C42C3F88820620504D5164A99 +:10866000136D0BB1506D9847230504D5124A936DD5 +:108670000BB1D06D9847E00404D50F4A136E0BB1CF +:10868000506E9847A10404D50B4A936E0BB1D06E7F +:108690009847620404D5084A136F0BB1506F98478E +:1086A000230404D5044A936F0BB1D06F9847BDE8FB +:1086B0001040FEF7DBBF00BFD45D002008B50348C3 +:1086C000FCF7CEFCBDE80840FEF7D0BFC036002066 +:1086D00008B50348FCF75EFDBDE80840FEF7C6BFDD +:1086E0001839002008B500F0B5FCBDE80840FEF7D9 +:1086F000BDBF0000062108B50846FCF7D1FD0621E4 +:108700000720FCF7CDFD06210820FCF7C9FD062156 +:108710000920FCF7C5FD06210A20FCF7C1FD062152 +:108720001720FCF7BDFD06212820FCF7B9FD092123 +:108730007A20FCF7B5FD09213120FCF7B1FD0721B6 +:108740003220FCF7ADFD0C215220BDE80840FCF7BB +:10875000A7BD000008B5FFF791FD00F043FCFDF751 +:108760007FF9FDF71DF9FDF755FBFDF727FAFEF739 +:10877000E9F9BDE8084000F029BA000030B504333B +:10878000039C0172002104FB0325C160C0E906536C +:10879000049B0363059BC0E90000C0E90422C0E913 +:1087A0000842C0E90A11436330BD00000022416A5B +:1087B000C260C0E90411C0E90A226FF00101FDF7AF +:1087C00037BF0000D0E90432934201D1C2680AB930 +:1087D000181D704700207047036919600021C268A6 +:1087E0000132C260C269134482699342036124BFAB +:1087F000436A0361FDF710BF38B504460D46E368D0 +:108800003BB162690020131D1268A3621344E36246 +:1088100007E0237A33B929462046FDF7EDFE00280C +:10882000EDDA38BD6FF00100FBE70000C368C269F4 +:10883000013BC3604369134482699342436124BF8F +:10884000436A436100238362036B03B11847704797 +:1088500070B53023044683F31188866A3EB9FFF76A +:10886000CBFF054618B186F31188284670BDA36A70 +:10887000E26A13F8015B9342A36202D32046FFF73A +:10888000D5FF002383F31188EFE700002DE9F84FAF +:1088900004460E46174698464FF0300989F3118872 +:1088A0000025AA46D4F828B0BBF1000F09D14146F3 +:1088B0002046FFF7A1FF20B18BF311882846BDE8C1 +:1088C000F88FD4E90A12A7EB050B521A934528BF7B +:1088D0009346BBF1400F1BD9334601F1400251F8DA +:1088E000040B914243F8040BF9D1A36A403640359A +:1088F0004033A362D4E90A239A4202D32046FFF709 +:1089000095FF8AF31188BD42D8D289F31188C9E74F +:1089100030465A46F9F7F4F9A36A5E445D445B4475 +:10892000A362E7E710B5029C0433017203FB042144 +:10893000C460C0E906130023C0E90A33039B036344 +:10894000049BC0E90000C0E90422C0E90842436377 +:1089500010BD0000026A6FF00101C260426AC0E906 +:1089600004220022C0E90A22FDF762BED0E90423F6 +:108970009A4201D1C26822B9184650F8043B0B60F4 +:10898000704700231846FAE7C3680021C269013323 +:10899000C3604369134482699342436124BF436ABD +:1089A0004361FDF739BE000038B504460D46E36863 +:1089B0003BB1236900201A1DA262E2691344E362FD +:1089C00007E0237A33B929462046FDF715FE002833 +:1089D000EDDA38BD6FF00100FBE7000003691960B4 +:1089E000C268013AC260C26913448269934203615A +:1089F00024BF436A036100238362036B03B11847FA +:108A00007047000070B530230D460446114683F3CD +:108A10001188866A2EB9FFF7C7FF10B186F3118857 +:108A200070BDA36A1D70A36AE26A01339342A36218 +:108A300004D3E16920460439FFF7D0FF002080F31A +:108A40001188EDE72DE9F84F04460D46904699460A +:108A50004FF0300A8AF311880026B346A76A4FB94F +:108A600049462046FFF7A0FF20B187F31188304622 +:108A7000BDE8F88FD4E90A073A1AA8EB060797422F +:108A800028BF1746402F1BD905F1400355F8042B8A +:108A90009D4240F8042BF9D1A36A40364033A362CB +:108AA000D4E90A239A4204D3E16920460439FFF746 +:108AB00095FF8BF311884645D9D28AF31188CDE70B +:108AC00029463A46F9F71CF9A36A3D443E443B4423 +:108AD000A362E5E7D0E904239A4217D1C3689BB1AA +:108AE000836A8BB1043B9B1A0ED01360C368013BB1 +:108AF000C360C3691A4483699A42026124BF436A0E +:108B00000361002383620123184670470023FBE7BB +:108B100001F01F03F0B502F01F0456095A1C01238F +:108B2000B6EB511F50F8265003FA02F34FEA5117E3 +:108B300003F1FF333DBF50F82720C4F1200013405C +:108B400003EA05003BBF03FA00F225FA04F0E04017 +:108B50001043F0BD70B57E227F210546FFF7D8FF98 +:108B600018B1012819D0002070BD3E2249212846A5 +:108B7000FFF7CEFF2F22044631212846FFF7C8FF1A +:108B8000064601345022023653212846B440FFF7EE +:108B9000BFFF093804FA00F0E6E7302245212846F5 +:108BA000FFF7B6FF01308002DEE7000090F8D63014 +:108BB00090F8D7201B0403EB026390F8D42090F8C0 +:108BC000D500134403EB00207047000000F018BAF2 +:108BD000014B586A704700BF000C0040034B002255 +:108BE00058631A610222DA60704700BF000C00402F +:108BF000014B0022DA607047000C0040014B5863C3 +:108C0000704700BF000C0040024B034A1A60034A41 +:108C10005A607047AC5D0020585E002000000220C2 +:108C2000074B494210B55C68201A08401968821A3F +:108C30008A4203D3A24201D85A6010BD0020FCE74B +:108C4000AC5D002008B5302383F31188FFF7E8FFFF +:108C5000002383F3118808BD0448054B03600023FB +:108C6000C0E901330C3000F017B900BFB45D00203B +:108C7000458C0008CB1D083A23F00703591A521AF5 +:108C800010B4D2080024C0E9004384600C301C609A +:108C90005A605DF8044B00F0FFB800002DE9F74F73 +:108CA000364FCD1D8846002818BF0746082A4FEAD0 +:108CB000D50538BF082207F10C003C1D91460190F4 +:108CC00000F02CF9019809F10701C9F1000E2246C4 +:108CD000246864B900F02CF93B68CBB308224946FC +:108CE000E8009847044698B340E9027830E004EB86 +:108CF000010CD4F804A00CEA0E0C0AF10106ACF148 +:108D0000080304EBC6069E42E1D9A6EB0C0CB5EBBA +:108D1000EC0F4FEAEC0BDAD89C421DD204F10802AA +:108D2000AB45A3EB02024FEAE202626009D9691C7B +:108D3000ED4303EBC1025D445560256843F83150B3 +:108D400022601C46C3F8048044F8087B00F0F0F869 +:108D5000204603B0BDE8F08FAA45216802D111601A +:108D60002346EEE7013504EBC50344F8351003F163 +:108D70000801761AF6105E601360F1E7B45D00201A +:108D800073B50446A0F1080550F8080C54F8043CEB +:108D9000061D0C3007330190DB0844F8043C00F05A +:108DA000BDF8334601989E421A6801D0AB4228D2E2 +:108DB0000AB1954225D244F8082C54F8042C1D60C1 +:108DC000013254F8081C05EBC206B14206D14E68C8 +:108DD000324444F8042C0A6844F8082C5E68711C7C +:108DE00003EBC1018D4207D154F8042C0132324407 +:108DF0005A6054F8082C1A6002B0BDE8704000F0C8 +:108E000097B81346CFE70000FEE7000070B51E4B91 +:108E10000025044686B058600E4605638163FEF760 +:108E2000FDFB04F12803A5606563C4E90A3304F17E +:108E30001003C4E904334FF0FF33C4E90044C4E92C +:108E40000635FFF7C5FE2B46024604F13C012046DD +:108E5000C4E9082380230D4A6567FDF747FB736863 +:108E6000E0600B4A03620123009280F824306846D8 +:108E7000F26801923269CDE90223064BCDE904354F +:108E8000FDF768FB06B070BD30400020389B00083D +:108E9000309B0008098E00080023C0E900008360B1 +:108EA0000361704770B51C4B05468468DE685CB38F +:108EB000B44213D103690133036170BDA36094F818 +:108EC000243083B1062B15D1A06A2146D4E90032A3 +:108ED00013605A60FDF776FAA36A9C68B368A268CB +:108EE0009A42EBD306E0D4E90032204613605A6080 +:108EF000FDF778FA28463146FDF764FAB562062098 +:108F0000BDE87040FDF770BA036986600133036104 +:108F1000336BC3603063D0E7883D002008B5302351 +:108F200083F31188FFF7BEFF002383F3118808BD88 +:108F3000194BD96883688B4210B520D1302383F355 +:108F400011880269013A0261B2B90468C368A0429B +:108F50000B631ED04A6B9BB901238A6003610368CF +:108F60001A68026050601A6B8360C260186318460A +:108F7000FDF738FAFDF788FA002383F3118810BD56 +:108F80001C68A34203D0A468A24238BF2246DB6813 +:108F9000E1E78260F0E700BF883D0020024A536BA2 +:108FA00018435063704700BF883D002038B5EFF389 +:108FB00011859DB9EFF30584C4F30804302334B15F +:108FC00083F31188FDF76CFC85F3118838BD83F3BA +:108FD0001188FDF765FC84F3118838BDBDE8384081 +:108FE000FDF75EBC0023054A19460133102BC2E988 +:108FF000001102F10802F8D1704700BFD45D0020D3 +:10900000114BD3F8E82042F00802C3F8E820D3F867 +:10901000102142F00802C3F810210C4AD3F8103195 +:10902000D36B43F00803D363C722094B9A624FF016 +:10903000FF32DA6200229A615A63DA605A600122D2 +:109040005A611A60704700BF004402580010005C6B +:10905000000C0040094A08B51169D3680B40D9B229 +:109060009B076FEA0101116107D5302383F3118853 +:10907000FDF730FA002383F3118808BD000C00408F +:1090800010B501390244904201D1002005E0037877 +:1090900011F8014FA34201D0181B10BD0130F2E7B7 +:1090A000884210B501EB020402D98442234607D856 +:1090B000431EA14208D011F8012B03F8012FF8E755 +:1090C000024401468A4200D110BD13F8014D02F856 +:1090D000014DF7E7C9B2034610F8012B1AB18A42D5 +:1090E000F9D118467047002918BF0023F9E700009E +:1090F000034611F8012B03F8012B002AF9D1704720 +:1091000010B50139034632B111F8014F03F8014B94 +:10911000013A002CF7D11A440021934200D110BD2E +:1091200003F8011BF9E700004D4435002D2D0A001E +:109130002F6172647570696C6F742E6162696E0064 +:109140002F6172647570696C6F742D7665726966D3 +:10915000792E6162696E002F6172647570696C6F3F +:10916000742D666C6173682E6162696E002F617286 +:10917000647570696C6F742D666C61736865642EBC +:109180006162696E00000000000000000000000045 +:10919000050F0008A10F000851110008D90F0008A1 +:1091A000990F00080000000000000000010F0008F7 +:1091B000AD0F000889110008FD0E0008090F000816 +:1091C00053544D333248373F3F3F0053544D3332B1 +:1091D000483733782F3732780053544D333248377D +:1091E00034332F3735332F373530000001105A0014 +:1091F0000310590001205800032056002F000000E2 +:109200005375636365737366756C6C79206D6F75E8 +:109210006E746564205344436172642028736C6FDC +:1092200077646F776E3D2575290A0000EB769045CF +:1092300058464154202020004641543332202020FB +:10924000000000002A3A3C3E7C223F7F002B2C3B52 +:109250003D5B5D00435545414141414345454549DD +:10926000494941414592924F4F4F5555594F554F9E +:109270009C4F9E9F41494F55A5A5A6A7A8A9AAAB5B +:10928000ACADAEAFB0B1B2B3B4414141B8B9BABB05 +:10929000BCBDBEBFC0C1C2C3C4C54141C8C9CACBA1 +:1092A000CCCDCECFD1D145454549494949D9DADB65 +:1092B000DCDD49DF4FE14F4F4F4FE6E8E8555555AC +:1092C0005959EEEFF0F1F2F3F4F5F6F7F8F9FAFB8D +:1092D000FCFDFEFF01030507090E10121416181CF1 +:1092E0001E00000061001A03E0001703F8000703E6 +:1092F000FF0001007801000130013201060139014F +:1093000010014A012E017901060180014D0043023E +:109310008101820182018401840186018701870124 +:1093200089018A018B018B018D018E018F019001D2 +:109330009101910193019401F60196019701980121 +:1093400098013D029B019C019D0120029F01A0010B +:10935000A001A201A201A401A401A601A701A701E5 +:10936000A901AA01AB01AC01AC01AE01AF01AF0193 +:10937000B101B201B301B301B501B501B701B80143 +:10938000B801BA01BB01BC01BC01BE01F701C001BB +:10939000C101C201C301C401C501C401C701C801A3 +:1093A000C701CA01CB01CA01CD011001DD010100D5 +:1093B0008E01DE011201F3010300F101F401F40159 +:1093C000F8012801220212013A020900652C3B0231 +:1093D0003B023D02662C3F0240024102410246022E +:1093E0000A015302400081018601550289018A0168 +:1093F00058028F015A0290015C025D025E025F0218 +:1094000093016102620294016402650266026702CE +:10941000970196016A02622C6C026D026E029C0139 +:10942000700271029D01730274029F01760277023D +:10943000780279027A027B027C02642C7E027F022F +:10944000A60181028202A9018402850286028702A6 +:10945000AE014402B101B20145028D028E028F02BB +:1094600090029102B7017B030300FD03FE03FF039B +:10947000AC0304008603880389038A03B103110344 +:10948000C2030200A303A303C4030803CC03030025 +:109490008C038E038F03D8031801F2030A00F9032B +:1094A000F303F403F503F603F703F703F903FA03F1 +:1094B000FA033004200350041007600422018A04D8 +:1094C0003601C1040E01CF040100C004D0044401E0 +:1094D00061052604000000007D1D0100632C001EB4 +:1094E0009601A01E5A01001F0806101F0606201F25 +:1094F0000806301F0806401F0606511F0700591FA7 +:10950000521F5B1F541F5D1F561F5F1F601F080601 +:10951000701F0E00BA1FBB1FC81FC91FCA1FCB1F59 +:10952000DA1FDB1FF81FF91FEA1FEB1FFA1FFB1FD3 +:10953000801F0806901F0806A01F0806B01F040021 +:10954000B81FB91FB21FBC1FCC1F0100C31FD01F03 +:109550000206E01F0206E51F0100EC1FF31F0100D9 +:10956000FC1F4E21010032217021100284210100D4 +:109570008321D0241A05302C2F04602C0201672C83 +:109580000601752C0201802C6401002D260841FF84 +:109590001A030000C700FC00E900E200E400E0005C +:1095A000E500E700EA00EB00E800EF00EE00EC0069 +:1095B000C400C500C900E600C600F400F600F200D1 +:1095C000FB00F900FF00D600DC00F800A300D80083 +:1095D000D7009201E100ED00F300FA00F100D100A4 +:1095E000AA00BA00BF00AE00AC00BD00BC00A100E4 +:1095F000AB00BB0091259225932502252425C100AF +:10960000C200C000A9006325512557255D25A20091 +:10961000A5001025142534252C251C2500253C25C6 +:10962000E300C3005A255425692566256025502589 +:109630006C25A400F000D000CA00CB00C8003101A6 +:10964000CD00CE00CF0018250C2588258425A60046 +:10965000CC008025D300DF00D400D200F500D50077 +:10966000B500FE00DE00DA00DB00D900FD00DD0001 +:10967000AF00B400AD00B1001720BE00B600A700D7 +:10968000F700B800B000A800B700B900B300B200FE +:10969000A025A0001000024008000240000802407F +:1096A00000000B00280002400800024004080240AD +:1096B00006010C0040000240080002400808024079 +:1096C00010020D0058000240080002400C08024041 +:1096D00016030E00700002400C0002401008024009 +:1096E00000040F00880002400C00024014080240F1 +:1096F00006051000A00002400C00024018080240BD +:1097000010061100B80002400C0002401C08024084 +:1097100016072F00100402400804024020080240EF +:1097200000083800280402400804024024080240CF +:10973000060939004004024008040240280802409B +:10974000100A3A0058040240080402402C08024063 +:10975000160B3B00700402400C040240300802402B +:10976000000C3C00880402400C0402403408024013 +:10977000060D4400A00402400C04024038080240D8 +:10978000100E4500B80402400C0402403C080240A0 +:10979000160F4600010000000000000000960000C7 +:1097A00000000000000000000000000000000000B9 +:1097B00000000000000000003D6B0008416B000845 +:1097C000355600086D590008C9550008F1550008C4 +:1097D00019560008B155000800000000215A000881 +:1097E0000D5A0008495A0008355A0008415A000825 +:1097F0002D5A0008195A0008055A0008555A000841 +:1098000000000000395B0008255B0008615B000870 +:109810004D5B0008595B0008455B0008315B0008A0 +:109820001D5B00086D5B00080000000001000000E7 +:1098300000000000633000003498000800000000C1 +:1098400000000000003E0020304000200000802A80 +:1098500000000000AAAAAAAA00000024FFFF00003E +:109860000000000000A00A0000000001000000004D +:10987000AAAAAAAA00000001FFFF00000000000041 +:10988000000000000000AA4600000000AAAAAAAA40 +:1098900000005540FFDF000000000000CCCC0C00B1 +:1098A0002001500000000000AAAAAAAA100100008E +:1098B000FFF30000000C0000000000005080420098 +:1098C00000000000AAAAAAAA10404100F7FF000069 +:1098D0000000007007000000000000000000000011 +:1098E000AAAAAAAA00000000FFFF000000000000D2 +:1098F000000000000000000000000000AAAAAAAAC0 +:1099000000000000FFFF0000000000000000000059 +:109910000000000000000000AAAAAAAA000000009F +:10992000FFFF000000000000000000000000000039 +:1099300000000000AAAAAAAA00000000FFFF000081 +:109940000000000000000000000000000000000017 +:10995000AAAAAAAA00000000FFFF00000000000061 +:10996000000000000000000000000000AAAAAAAA4F +:1099700000000000FFFF00000000000000000000E9 +:109980004172647550696C6F740025424F415244B6 +:10999000252D424C002553455249414C25000000DD +:1099A0000200000000000000595D0008C95D0008C9 +:1099B00040004000E0580020F05800200200000065 +:1099C000000000000300000000000000115E00081D +:1099D00000000000100000000059002000000000FE +:1099E00001000000000000005C5C0020010102009A +:1099F000396C0008496B0008E56B0008C96B00086A +:109A000043000000089A000809024300020100C058 +:109A100032090400000102020100052400100105C2 +:109A20002401000104240202052406000107058226 +:109A3000030800FF09040100020A000000070501F5 +:109A400002400000070581024000000012000000F3 +:109A5000549A0008120110010200004009124157F7 +:109A600000020102030100000403090425424F41E2 +:109A7000524425005442535F4C554349445F483794 +:109A8000003031323334353637383941424344457A +:109A9000460000000000002000000200020000005C +:109AA0000000003000000400080000000000002456 +:109AB00000000800040000000004000000FC00009A +:109AC00002000000000004300080000008000000D8 +:109AD0000000003800000100010000001F1C1F1ED4 +:109AE0001F1E1F1F1E1F1E1F1F1D1F1E1F1E1F1F8D +:109AF0001E1F1E1F000000006D5F00082562000889 +:109B0000D162000840004000945D0020945D002078 +:109B100001000000A45D0020800000004001000062 +:109B20000800000000010000001000000800000014 +:109B300069646C65000000006D61696E002C04387A +:109B4000040438080C10141C2024252600000000F2 +:109B5000000064040100040000000000000C00107C +:109B6000283034000469FF7F01000000000000007D +:109B7000821400000000000000001A000000000035 +:109B8000FF000000384000201839002000000000CD +:109B9000C091000883040000CB910008500400002D +:109BA000D9910008010000000000000000960000AC +:109BB00000000800960000000008000004000000FB +:109BC000689A00080000000000000000000000008B +:0C9BD00000000000000000000000000089 +:00000001FF diff --git a/Tools/bootloaders/VUAV-V7pro_bl.bin b/Tools/bootloaders/VUAV-V7pro_bl.bin new file mode 100755 index 00000000000000..1ef7960f61284b Binary files /dev/null and b/Tools/bootloaders/VUAV-V7pro_bl.bin differ diff --git a/Tools/bootloaders/X-MAV-AP-H743v2_bl.bin b/Tools/bootloaders/X-MAV-AP-H743v2_bl.bin new file mode 100755 index 00000000000000..d064e7b2428171 Binary files /dev/null and b/Tools/bootloaders/X-MAV-AP-H743v2_bl.bin differ diff --git a/Tools/bootloaders/ZeroOneX6_bl.bin b/Tools/bootloaders/ZeroOneX6_bl.bin new file mode 100644 index 00000000000000..d011831d18a437 Binary files /dev/null and b/Tools/bootloaders/ZeroOneX6_bl.bin differ diff --git a/Tools/bootloaders/ZeroOneX6_bl.hex b/Tools/bootloaders/ZeroOneX6_bl.hex new file mode 100644 index 00000000000000..cc285977531fb7 --- /dev/null +++ b/Tools/bootloaders/ZeroOneX6_bl.hex @@ -0,0 +1,2611 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008FD7C000888 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008098C0008358C000860 +:10006000618C00088D8C0008B98C0008FD4B0008DD +:10007000254C0008514C00087D4C0008A94C000894 +:10008000D14C0008FD4C0008E3020008E302000820 +:10009000E3020008E3020008E3020008E58C000820 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008D18D0008F3 +:1000E000498D0008E3020008E3020008E30200086B +:1000F000E3020008E3020008E3020008294D0008BB +:10010000E3020008E30200080D8E0008E302000885 +:10011000E3020008E58D0008E3020008E30200089E +:10012000554D00087D4D0008A94D0008D54D00082B +:10013000014E0008E3020008E3020008E3020008A1 +:10014000E3020008E3020008E3020008E3020008FB +:10015000294E0008554E0008814E0008E3020008B1 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008E9880008E3020008E30200083F +:10018000E3020008E3020008F98D0008E30200081A +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008D5880008E3020008E3020008F3 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000BD8D0008E3020008E3020008E3020008A5 +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F07F038FD34 +:1003500006F09EFE4FF055301F491B4A91423CBFAC +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE707F050FD06F0FCFE05 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0BCFC114C124DAC4203DA54F8041BA3 +:1003C0008847F9E707F038BD00060020002200202A +:1003D0000000000808ED00E00000002000060020FA +:1003E00030A2000800220020D8220020D8220020BD +:1003F00098670020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002006F014FCFEE706F0DD +:100430006DFB00DFFEE7000053B94AB9002908BF91 +:1004400000281CBF4FF0FF314FF0FF3000F074B9AF +:10045000ADF1080C6DE904CE00F006F8DDF804E01B +:10046000DDE9022304B070472DE9F047089D0446FA +:100470008E46002B4DD18A42944669D9B2FA82F257 +:1004800052B101FA02F3C2F1200120FA01F10CFA93 +:1004900002FC41EA030E94404FEA1C48210CBEFBCB +:1004A000F8F61FFA8CF708FB16E341EA034306FB54 +:1004B00007F199420AD91CEB030306F1FF3080F0E3 +:1004C0001F81994240F21C81023E63445B1AA4B230 +:1004D000B3FBF8F008FB103344EA034400FB07F7D2 +:1004E000A7420AD91CEB040400F1FF3380F00A8113 +:1004F000A74240F207816444023840EA0640E41B08 +:1005000000261DB1D4400023C5E900433146BDE8B3 +:10051000F0878B4209D9002D00F0EF800026C5E955 +:10052000000130463146BDE8F087B3FA83F6002E6D +:100530004AD18B4202D3824200F2F980841A61EBE5 +:10054000030301209E46002DE0D0C5E9004EDDE703 +:1005500002B9FFDEB2FA82F2002A40F09280A1EBEB +:100560000C014FEA1C471FFA8CFE0126200CB1FB40 +:10057000F7F307FB131140EA01410EFB03F0884239 +:1005800008D91CEB010103F1FF3802D2884200F2C6 +:10059000CB804346091AA4B2B1FBF7F007FB101158 +:1005A00044EA01440EFB00FEA64508D91CEB0404F6 +:1005B00000F1FF3102D2A64500F2BB800846A4EB51 +:1005C0000E0440EA03409CE7C6F12007B34022FA3C +:1005D00007FC4CEA030C20FA07F401FA06F31C436B +:1005E000F9404FEA1C4900FA06F3B1FBF9F8200C78 +:1005F0001FFA8CFE09FB181140EA014108FB0EF0BE +:10060000884202FA06F20BD91CEB010108F1FF3A0D +:1006100080F08880884240F28580A8F10208614419 +:10062000091AA4B2B1FBF9F009FB101144EA014127 +:1006300000FB0EFE8E4508D91CEB010100F1FF34D2 +:100640006CD28E456AD90238614440EA0840A0FB6A +:100650000294A1EB0E01A142C846A64656D353D040 +:100660005DB1B3EB080261EB0E0101FA07F722FA64 +:1006700006F3F1401F43C5E9007100263146BDE88D +:10068000F087C2F12003D8400CFA02FC21FA03F3F0 +:10069000914001434FEA1C471FFA8CFEB3FBF7F071 +:1006A00007FB10360B0C43EA064300FB0EF69E4296 +:1006B00004FA02F408D91CEB030300F1FF382FD22F +:1006C0009E422DD9023863449B1B89B2B3FBF7F6D7 +:1006D00007FB163341EA034106FB0EF38B4208D9B0 +:1006E0001CEB010106F1FF3816D28B4214D9023EF1 +:1006F0006144C91A46EA004638E72E46284605E70F +:100700000646E3E61846F8E64B45A9D2B9EB0208DF +:1007100064EB0C0E0138A3E74646EAE7204694E76F +:100720004046D1E7D0467BE7023B614432E73046A2 +:1007300009E76444023842E7704700BF08B5062065 +:1007400000F046F9012006F08BFC00BF032A70B5CB +:1007500015D940EA010C1CF0030F04460B4621D1C9 +:10076000194620460E680568B54204F1040403F1F9 +:10077000040317D1043A032A20461946F0D8541E20 +:10078000A2B100F1FF3C013901E0C3180CD01CF804 +:1007900001EF11F8012F9645A4EB0C03F5D0AEEB59 +:1007A000020070BD541EECE7184670BD104670BDC7 +:1007B00088420DD98B1883420AD900EB020CBAB1DA +:1007C000624613F801CD02F801CD9942F9D1704784 +:1007D0000F2A0ED8034602F1FF3C4AB10CF1010C7E +:1007E000013B8C4411F8012B03F8012F6145F9D12D +:1007F000704740EA01039B0750D1A2F1100370B586 +:1008000001F1200C23F00F0501F1100E00F110048E +:10081000AC441B095EF8105C44F8105C5EF80C5C9C +:1008200044F80C5C5EF8085C44F8085C5EF8045C14 +:1008300044F8045C0EF1100EE64504F11004E9D111 +:10084000013312F00C0F01EB031102F00F0400EB67 +:10085000031327D0043C24F003064FEA940C1E44F3 +:100860001C1F8E465EF8045B44F8045FB442F9D165 +:100870000CF1010402F0030203EB840301EB840199 +:1008800002F1FF3C4AB10CF1010C013B8C4411F820 +:10089000012B03F8012F6145F9D170BD02F1FF3C36 +:1008A00003469BE72246EBE738B5446C0CB10020C9 +:1008B00038BD8021054607F001F80246686430B172 +:1008C000031F7C3243F8044F9342FBD1EFE74FF014 +:1008D000FF3038BD1F29F8B5054608D8466C0C46D0 +:1008E00017464EB156F8240046F82470F8BD16237A +:1008F00003604FF0FF30F8BD802106F0DFFF0646B1 +:10090000686440B1031F00F17C05002143F8041F17 +:100910009D42FBD1E6E74FF0FF30F8BD1F2938B507 +:10092000054620D8426C0C466AB152F8213053B1CA +:10093000012B16D0591C10D00025204642F8245017 +:100940009847284638BD284600F0F8F82246014668 +:100950002846BDE8384000F0DBB8162303600120CC +:1009600038BD002038BD162303604FF0FF3038BD7E +:100970001F292AD8426C38B50C46054682B152F878 +:10098000243002EB84024BB1591C19D0012B15D035 +:100990000025204615609847284638BD012038BDFF +:1009A000802106F08BFF0246686458B1031F0021C6 +:1009B0007C3043F8041F9842FBD1E0E7032038BDA8 +:1009C000022038BD4FF0FF3038BD4FF0FF30704788 +:1009D00038B5144B1F281D681FD86A6C044662B1D5 +:1009E00052F820304BB1012B15D0591C0FD00025E7 +:1009F00042F820509847284638BD284600F09EF817 +:100A0000224601462846BDE8384000F081B816234A +:100A10002B60012038BD002038BD16232B604FF01D +:100A2000FF3038BD00220020124B1F2870B51E6811 +:100A300008D80D46716C044649B151F8240041F8BC +:100A4000245070BD162333604FF0FF3070BD8021FD +:100A5000304606F033FF0146706440B1031F00F1D9 +:100A60007C0C002243F8042F6345FBD1E5E74FF0EF +:100A7000FF3070BD0022002038B50B4B1D686C6C38 +:100A80000CB1002038BD8021284606F017FF6864AD +:100A900038B1031F00F17C0243F8044F9342FBD1AD +:100AA000EFE74FF0FF3038BD0022002038B5174B7C +:100AB0001F281D6826D86A6C044682B152F824307B +:100AC00002EB84024BB1591C1AD0012B16D0002521 +:100AD000204615609847284638BD012038BD802142 +:100AE000284606F0EBFE0246686458B1031F002159 +:100AF0007C3043F8041F8342FBD1DFE7032038BD7D +:100B0000022038BD4FF0FF3038BD00BF002200206A +:100B100070B50C46084D03460026204611461C467B +:100B20002E6006F0A1FA431C00D070BD2B68002B8C +:100B3000FBD0236070BD00BFD822002006F08EBA23 +:100B400011F0FF01034644D0820732D110B504688A +:100B500041EA012E4EEA0E4E8EEA0402A2F1013362 +:100B600023EA0203A4F1013222EA0402134313F040 +:100B7000803F0FD150F8044F84EA0E0CA4F10133EA +:100B8000ACF1013223EA040322EA0C02134313F00E +:100B9000803FEFD0037823B936E010F8013F002BF7 +:100BA00032D09942F9D110BD8A4211D09A07184625 +:100BB000CCD0184613F8012B002AF5D11046704707 +:100BC0009907184607D0184601330278002AF7D152 +:100BD00070478207F7D10268A2F1013323EA0203CA +:100BE00013F0803F08D150F8042FA2F1013323EA1B +:100BF000020313F0803FF6D00378002BE8D010F802 +:100C0000013F002BFBD17047184610BD80EA01025E +:100C1000844612F0030F4FD111F0030F32D14DF87B +:100C2000044D11F0040F51F8043B0BD0A3F1013235 +:100C30009A4312F0803F04BF4CF8043B51F8043B48 +:100C400016D100BF51F8044BA3F101329A4312F0C0 +:100C5000803FA4F101320BD14CF8043BA24312F0C7 +:100C6000803F04BF51F8043B4CF8044BEAD02346C4 +:100C70000CF8013B13F0FF0F4FEA3323F8D15DF876 +:100C8000044B704711F0010F06D011F8012B0CF83E +:100C9000012B002A08BF704711F0020FBFD031F8B6 +:100CA000022B12F0FF0F16BF2CF8022B8CF800203D +:100CB00012F47F4FB3D1704711F8012B0CF8012BC0 +:100CC000002AF9D1704700BF30B540EA0104A307FC +:100CD00001D1032A0FD8844601F1FF3E07E01EF838 +:100CE000011F03F8011B541EC1B19C4622466346F6 +:100CF000002AF4D130BD0B468446194653F8045BF4 +:100D0000A5F1013424EA050414F0803FE4D1043A4B +:100D1000032A4CF8045B1946EFD8DDE76244002C47 +:100D2000E8D003F8011B9342FBD130BD38B501F088 +:100D3000FFF901F0C1FB06F0C7FE054606F0D4FF3F +:100D40000446D0B90F4B9D4219D001339D4241F268 +:100D5000883504BF01240025002006F0BFFE0CB139 +:100D600000F078F801F048FB00F026FD08B100F033 +:100D700071F8284600F01CF9F9E70025ECE7054674 +:100D8000EAE700BF010007B008B501F09DF9A0F146 +:100D900020035842584108BD07B541F21203022111 +:100DA00001A8ADF8043001F0ADF903B05DF804FB23 +:100DB00038B5302383F31188174803680BB106F068 +:100DC0002DF80023154A4FF47A71134806F01CF8E9 +:100DD000002383F31188124C236813B12368013B6D +:100DE0002360636813B16368013B63600D4D2B782A +:100DF00033B963687BB9022001F060FA3223636083 +:100E00002B78032B07D163682BB9022001F056FA27 +:100E10004FF47A73636038BDDC220020B10D000806 +:100E2000FC230020F4220020084B187003280CD863 +:100E3000DFE800F008050208022001F031BA0220C4 +:100E400001F01EBA024B00225A607047F4220020C3 +:100E5000FC230020F8B5504B504A1C46196801315C +:100E600000F0998004339342F8D162684C4B9A4267 +:100E700040F291804B4B9B6803F1006303F5003314 +:100E80009A4280F08880002001F06CF90220FFF780 +:100E9000CBFF454B0021D3F8E820C3F8E810D3F886 +:100EA0001021C3F81011D3F81021D3F8EC20C3F8A7 +:100EB000EC10D3F81421C3F81411D3F81421D3F88B +:100EC000F020C3F8F010D3F81821C3F81811D3F8A4 +:100ED0001821D3F8802042F00062C3F88020D3F8B4 +:100EE000802022F00062C3F88020D3F88020D3F85D +:100EF000802042F00072C3F88020D3F8802022F0D6 +:100F00000072C3F88020D3F8803072B64FF0E0232F +:100F1000C3F8084DD4E90004BFF34F8FBFF36F8FC0 +:100F2000224AC2F88410BFF34F8F536923F48033F1 +:100F30005361BFF34F8FD2F8803043F6E076C3F3AE +:100F4000C905C3F34E335B0103EA060C29464CEA9C +:100F500081770139C2F87472F9D2203B13F1200F66 +:100F6000F2D1BFF34F8FBFF36F8FBFF34F8FBFF33C +:100F70006F8F536923F4003353610023C2F850325A +:100F8000BFF34F8FBFF36F8F302383F311888546F4 +:100F900080F308882047F8BD0000020820000208FE +:100FA000FFFF0108642200200044025800ED00E029 +:100FB0002DE9F04F93B0B44B2022FF2100900AA8F6 +:100FC0009D6801F0C3F9B14A1378A3B90121B04873 +:100FD00011700360302383F3118803680BB105F0AF +:100FE0001DFF0023AB4A4FF47A71A94805F00CFFAE +:100FF000002383F31188009B13B1A74B009A1A605A +:10100000A64A1378032B03D000231370A24A53601F +:101010004FF0000A009CD3465646D146012001F00D +:101020003FF924B19C4B1B68002B00F02682002066 +:1010300001F04AF80390039B002BF2DB012001F042 +:101040001FF9039B213B1F2BE8D801A252F823F084 +:10105000D1100008F91000088D1100081D100008BB +:101060001D1000081D1000081F120008EF130008D3 +:10107000091300086B13000893130008B913000844 +:101080001D100008CB1300081D1000083D140008B7 +:10109000711100081D10000881140008DD100008FF +:1010A000711100081D1000086B1300081D100008C6 +:1010B0001D1000081D1000081D1000081D1000085C +:1010C0001D1000081D1000081D1000088D110008DB +:1010D0000220FFF759FE002840F0F981009B022111 +:1010E00005A8BAF1000F08BF1C4641F21233ADF853 +:1010F000143001F007F891E74FF47A7000F0E4FF44 +:10110000071EEBDB0220FFF73FFE0028E6D0013F81 +:10111000052F00F2DE81DFE807F0030A0D10133619 +:101120000523042105A8059300F0ECFF17E0042136 +:101130005548F9E704215A48F6E704215948F3E7EE +:101140004FF01C08404608F1040801F00DF8042196 +:10115000059005A800F0D6FFB8F12C0FF2D10120C0 +:101160004FF0000900FA07F747EA0B0B5FFA8BFB19 +:1011700001F038F926B10BF00B030B2B08BF00244C +:10118000FFF70AFE4AE704214748CDE7002EA5D025 +:101190000BF00B030B2BA1D10220FFF7F5FD074647 +:1011A00000289BD00120002600F0DCFF0220FFF782 +:1011B0003BFE1FFA86F8404600F0E4FF0446B0B15B +:1011C000039940460136A1F140025142514100F0DD +:1011D000E9FF0028EDD1BA46044641F2121302217C +:1011E00005A83E46ADF8143000F08CFF16E7254602 +:1011F0000120FFF719FE244B9B68AB4207D9284614 +:1012000000F0B2FF013040F067810435F3E70025BC +:10121000224BBA463E461D701F4B5D60A8E7002E6C +:101220003FF45CAF0BF00B030B2B7FF457AF0220A6 +:10123000FFF7FAFD322000F047FFB0F10008FFF69B +:101240004DAF18F003077FF449AF0F4A08EB0503D1 +:10125000926893423FF642AFB8F5807F3FF73EAFCA +:10126000124BB845019323DD4FF47A7000F02CFF48 +:101270000390039A002AFFF631AF039A0137019BCE +:1012800003F8012BEDE700BF64220020F8230020C3 +:10129000DC220020B10D0008FC230020F4220020F5 +:1012A000682200206C22002070220020F8220020FA +:1012B000C820FFF769FD074600283FF40FAF1F2D38 +:1012C00011D8C5F120020AAB25F00300844942453C +:1012D000184428BF4246019201F012F8019AFF21FA +:1012E0007F4801F033F84FEAA803C8F387027C492E +:1012F0002846019301F032F8064600283FF46DAF0E +:10130000019B05EB830533E70220FFF73DFD002835 +:101310003FF4E4AE00F064FF00283FF4DFAE0027A6 +:10132000B846704B9B68BB4218D91F2F11D80A9B37 +:1013300001330ED027F0030348336B4453F8203CAD +:1013400005934046042205A9043701F00BF98046B5 +:10135000E7E7384600F008FF0590F2E7CDF8148083 +:10136000042105A800F0CEFE02E70023642104A8B2 +:10137000049300F0BDFE00287FF4B0AE0220FFF71A +:1013800003FD00283FF4AAAE049800F01FFF05906B +:10139000E6E70023642104A8049300F0A9FE0028D6 +:1013A0007FF49CAE0220FFF7EFFC00283FF496AEDE +:1013B000049800F00DFFEAE70220FFF7E5FC0028A3 +:1013C0003FF48CAE00F01CFFE1E70220FFF7DCFCED +:1013D00000283FF483AE05A9142000F017FF07464C +:1013E0000421049004A800F08DFE3946B9E73220AC +:1013F00000F06AFE071EFFF671AEBB077FF46EAE0B +:10140000384A07EB0903926893423FF667AE022021 +:10141000FFF7BAFC00283FF461AE27F003074F4402 +:10142000B9453FF4A5AE484609F1040900F09CFE19 +:101430000421059005A800F065FEF1E74FF47A70ED +:10144000FFF7A2FC00283FF449AE00F0C9FE0028D7 +:1014500044D00A9B01330BD008220AA9002000F0D7 +:101460007DFF00283AD02022FF210AA800F06EFF5D +:10147000FFF792FC1C4805F0F3FB13B0BDE8F08FBA +:10148000002E3FF42BAE0BF00B030B2B7FF426AE9C +:101490000023642105A8059300F02AFE07460028D2 +:1014A0007FF41CAE0220FFF76FFC804600283FF45B +:1014B00015AEFFF771FC41F2883005F0D1FB0598BD +:1014C00000F0D8FF46463C4600F08CFFA6E50646F5 +:1014D0004EE64FF0000901E6BA467EE637467CE666 +:1014E000F822002064220020A0860100704700003E +:1014F00070470000704700002DE9F04100F580378B +:10150000044616463B7C5BB9C0681030204400F0AE +:10151000F7FEE5683544B5F5004FE56002D816B131 +:10152000BDE8F081DEB905F07F0605F1100000216D +:10153000C6F180062044F6B232462E4400F006FF83 +:10154000A06804F11008324600F10060414600F541 +:10155000003006F061F830B901233B74E0E74FF446 +:1015600000463546ECE7A26805F1100140463244DA +:101570002144A260E268521BE26000F0C1FE02203A +:10158000BDE8F04100F09ABE183000F0E9BC000060 +:1015900010B5044608F010F9204610BD10B50446F9 +:1015A00008F00AF9204610BDC3B280B2A3F141028F +:1015B000052A02D8373800B27047613B052B94BF2B +:1015C00057383038F7E70000F8B5044615460846A6 +:1015D00003220C4900F09EFE014688B908346F1CB6 +:1015E00015F91100FFF7E0FF064617F91100013168 +:1015F000FFF7DAFF102940EA061004F8010BEFD1DB +:10160000F8BD00BFF09700082DE9F04FADF53F7D24 +:101610000746416801222AA802F09CFE002840F0FB +:1016200087800646824681461125DFF80C81DFF867 +:101630000CB101AB4FF4805241462AA802F0EAFFF8 +:10164000002875D1019AB2F5805F71D8002A65D063 +:101650000446019A9442ECD2282D0FD008DC132DB9 +:101660002DD01E2D39D0112D13D00134A4B2F0E7A6 +:10167000322D2DD0372D2FD02D2DF6D13B68121BBA +:1016800008EB040138461B692D259847BDF8044036 +:10169000EBE7121B022A09D9594608EB040000F0B7 +:1016A00039FE18B902342825A4B2DEE718F8043050 +:1016B0003A2B3DD00A2B1CBFA1461325D5E718F8BD +:1016C00004300A2B34D03A2B04BFA2463225CCE793 +:1016D00018F80430202BC8D0264618F804300A2BFE +:1016E0001AD1AAEB090208EB090102A811254F2A19 +:1016F00028BF4F22FFF7E8FAA21B08EB060116A845 +:101700004F2A28BF4F22FFF7DFFA3B6816AA02A92B +:10171000DB6838469847A8E71E25A6E73B683846A9 +:1017200004491B69984701200DF53F7DBDE8F08F06 +:101730000020F9E7F298000804240020F49700083C +:1017400000F1180110B5044686B00846019100F07A +:10175000F1FB2046FFF758FF60B1019902A800F0A5 +:1017600049FC102204F1080102A8FEF7EFFFB0FACD +:1017700080F0400906B010BD70B504460025EEB2F9 +:10178000304600F0FFFC58B100213046013500F032 +:1017900009FD08B9002070BD022000F08FFDEEE7C2 +:1017A0002046FFF731FF0028F4D004F58034207C78 +:1017B00080F00100EFE70000F0B5C9B006F09CF939 +:1017C00000F0FEFE18B90025284649B0F0BD694674 +:1017D0002A4802F0E1FF00284BD1294C204603F0B3 +:1017E0000BF8284803F008F8274803F005F82146CD +:1017F000224803F07DF80028E5D1702007F0DEFFD5 +:10180000064610B1214B44600360336830469B6844 +:101810009847054600282ED01A4F1948394603F03C +:1018200067F805460028CED1194807F0C7FF0446DF +:1018300038B1184B4760036000F58033C0E90255AA +:101840001D74236820469B689847054628B10E49B9 +:101850000C4803F04DF80028B5D1336830465B687A +:1018600098471CB1236820465B68984700F090FEBB +:10187000AAE70025FAE70446EFE700BFF89700085B +:10188000089800081F980008359800085898000824 +:1018900014000100749800082DE9F04FD44A8DB06F +:1018A0000B68D0F804A001931A440368D14E1A447F +:1018B000D1F81C90DFF8B4C3DFF8B4B3D0E9023438 +:1018C000634003EA0A03634013444A6802920AEB46 +:1018D0007363029CC84A2244C468224484688AEA2A +:1018E00004051D40654015448A68039203EB355595 +:1018F000039CC24A2244846822448AEA03042C409E +:1019000084EA0A041444CA6805EBF43404921644C9 +:1019100083EA0502224056445A4032440E69059635 +:1019200004EBB222059FB64E3E441E4485EA0403F2 +:1019300013406B4033444E69069602EB7363069F77 +:10194000B04E3E442E4484EA02051D4065403544B5 +:101950008E69079603EB3555079FAB4E3E442644F0 +:1019600082EA03042C4054403444A84E4E4405EB14 +:10197000F434164483EA050222405A4032440E6A87 +:10198000089604EBB222089FA14E3E441E4485EA0D +:10199000040313406B4033444E6A099602EB7363B1 +:1019A000099F9C4ED1F830E03E44D1F83880F34492 +:1019B0002E4484EA02051D40654035448E6AA6F532 +:1019C000244703EB35550A964F3F274482EA030428 +:1019D0002C4054403C44CF6A0B9705EBF4340B9EEB +:1019E0008D4F3744029E174483EA050222405A4035 +:1019F0003A448A4F774404EBB2221F4485EA040339 +:101A000013406B403B444F6BBC4402EB7363654433 +:101A100084EA020C0CEA030C8CEA040C6544DFF83F +:101A200054C2C44403EB3555A44482EA03042C4059 +:101A300054406444D1F83CC0794905EBF434614426 +:101A4000114483EA050222405A400A44754904EBD6 +:101A5000B2223144079E194484EA02032B406340BA +:101A60000B44714902EBF36331440B9E0D4482EA4F +:101A700003012140514029446C4D03EBF1513544A1 +:101A8000019E254483EA010414405C402C44684DC7 +:101A900001EBB4443544069E154481EA04021A4021 +:101AA0004A402A44634D04EB323235440A9E1D44B9 +:101AB00084EA02030B4063402B445F4D02EBF36367 +:101AC0003544059E0D4482EA0301214051402944DA +:101AD0005A4D03EBF1516544254483EA0104144057 +:101AE0005C402C44564D01EBB4443544099E1544EA +:101AF00081EA04021A404A402A44524D04EB323231 +:101B00003544049E1D4484EA02030B4063402B4489 +:101B10004D4D02EBF36345440D4482EA030121403D +:101B200051402944494D03EBF1513544089E2C4462 +:101B300083EA010515405D402C44454D01EBB4445A +:101B40003544039E2A4481EA04051D404D402A4441 +:101B5000404D04EB32323D442B4484EA0205934469 +:101B60000D4065402B443C4D02EBF3633544069E2B +:101B7000294482EA0305254055402944374D03EBAB +:101B8000F1514D442C4483EA010515405D40254444 +:101B900001EBB54581EA050404EA03024A405A44D0 +:101BA000A6F5B82B089E05EB3232ABF2BE6B544063 +:101BB0005B4423442A4C344402EB33730B9E0C44A5 +:101BC00085EA020159402144264C344403EB71510B +:101BD000029E254482EA03044C402544224C44449E +:101BE00001EB3545144483EA01026A40224443E094 +:101BF00078A46AD7EECEBDC156B7C7E8DB70202403 +:101C0000AF0F7CF52AC68747134630A8019546FDDD +:101C1000D8988069AFF7448BBED75C892211906B4E +:101C20002108B44962251EF640B340C0515A5E26D1 +:101C3000AAC7B6E95D102FD65314440281E6A1D895 +:101C4000C8FBD3E7E6CDE121D60737C3870DD5F42E +:101C5000ED145A4505E9E3A9F8A3EFFCD9026F6733 +:101C600081F6718722619D6D0C38E5FD937198FDB9 +:101C70008A4C2A8D8E4379A6934C344405EB72220C +:101C8000059E1C4481EA0503534023448F4C344491 +:101C900002EB33730A9E0C4485EA02015940214449 +:101CA0008B4C4C4403EB7151254482EA03044C40B5 +:101CB0002C44884D354401EB3444019E154483EA9D +:101CC000010262402A44844D3D4404EB72221D44CB +:101CD00081EA040353402B44804D354402EB3373B7 +:101CE000049E294484EA02055D4029447C4D354424 +:101CF00003EB7151079E254482EA03044C402C44B7 +:101D0000784D354401EB3444099E2A4483EA0105A9 +:101D100065401544744A324404EB7525039E134410 +:101D200081EA04026A401A44704B734405EB327234 +:101D30000B4484EA0501514019446D4B634402EBA6 +:101D400071511C4485EA02034B401C44694B3344E7 +:101D500001EB3444019E1D4482EA010363402B449D +:101D6000654D04EB73233544069E154463EA010276 +:101D700062402A44614D03EBB2624D4462EA0409B9 +:101D800029445F4D89EA0309454449442C445D4D8B +:101D900002EBB1513544049E61EA03081D4488EA10 +:101DA0000208444401EB744464EA02034B402B44B0 +:101DB000554D04EBF323754463EA010E15448EEA96 +:101DC000040E0EEB0502514D03EBB262354462EA9C +:101DD000040E29440A9D8EEA030EA5F580164C4D8B +:101DE0007144A6F6833602EBB151264461EA03043E +:101DF00054403444029E01EB7444354464EA0206C4 +:101E00001D444E407319089E424D04EBF3233544A4 +:101E100063EA01061544664072193F4D03EBB26256 +:101E2000654462EA040629443C4D5E403144079E05 +:101E300002EBB151354461EA03062C44384D56405B +:101E40003D443444059E1D4401EB744464EA02039E +:101E50004B402B44334D04EBF32335440B9E154488 +:101E600063EA010262402A442F4D03EBB26235441B +:101E7000039E0D4462EA0401594029442B4D02EBB4 +:101E8000B15135442A4E254461EA030454402C44A0 +:101E9000099D01EB74442E4464EA02051E4485EA60 +:101EA00001039D1903681A440AEB040303EBF523AD +:101EB0000260436083681C44C36819448460C16045 +:101EC0000DB0BDE8F08F00BF44EABEA4A9CFDE4B41 +:101ED000604BBBF670BCBFBEC67E9B28FA27A1EA4A +:101EE0008530EFD4051D880439D0D4D9E599DBE6D7 +:101EF000F87CA21F6556ACC4442229F497FF2A43FC +:101F0000A72394AB39A093FCC3595B6592CC0C8F8B +:101F1000D15D84854F7EA86FE0E62CFE144301A3BB +:101F2000A111084E827E53F735F23ABDBBD2D72AB3 +:101F300091D386EB094B036003F18833436003F1CF +:101F40002943A3F59613A3F68B638360A3F188332B +:101F5000C3600023C0E90433704700BF0123456715 +:101F60002DE9F8431446026905460E46E300C2F324 +:101F7000C50800F118079B18036122BF43690133AC +:101F8000436112F4FC7F436903EB5473436114D043 +:101F9000C8F1400907EB08004C4504D22246BDE8D1 +:101FA000F843FEF705BC403C4A464E44FEF700FCB1 +:101FB000444439462846FFF76FFCA04606EB040967 +:101FC000B8F13F0FA9EB08010AD940223846FEF7C5 +:101FD000EFFB39462846A8F14008FFF75DFCEFE724 +:101FE000A1096FF03F02384602FB014206EB811166 +:101FF000D5E7000070B50B6901F1180506460C46DF +:10200000C3F3C503EA18501C8022EA54C3F13F020F +:10201000072A1FD8002100F099F929462046FFF72A +:102020003BFC38220021284600F090F9236929461C +:102030002046236563696365FFF72EFC2146102265 +:102040003046FEF7B5FB204658220021BDE870401F +:1020500000F07CB9C3F137020021E5E72DE9F84F24 +:102060004FF47A7306460D46002402FB03F7DFF8AF +:102070005080DFF8509098F900305FFA84FA5A1CCB +:1020800001D0A34210D159F824002A4631460368F2 +:10209000D3F820B03B46D847854205D1074B0120F5 +:1020A00083F800A0BDE8F88F0134042CE3D14FF48D +:1020B000FA7004F0D5FD0020F4E700BF483400209A +:1020C0007422002078220020002307B50246012157 +:1020D0000DF107008DF80730FFF7C0FF20B19DF824 +:1020E000070003B05DF804FB4FF0FF30F9E7000094 +:1020F0000A46042108B5FFF7B1FF80F00100C0B225 +:10210000404208BD074B0A4630B41978064B53F8D5 +:102110002140014623682046DD69044BAC4630BCB3 +:10212000604700BF4834002078220020A0860100CC +:1021300070B50A4E00240A4D05F012FA3080286866 +:102140003388834208D905F007FA2B680444013329 +:10215000B4F5003F2B60F2D370BD00BF4A340020BD +:102160000434002005F0CABA00F1006000F5003028 +:102170000068704700F10060920000F5003005F043 +:102180004BBA0000054B1A68054B1B889B1A83420B +:1021900002D9104405F0E0B9002070470434002053 +:1021A0004A34002038B50446074D29B12868204438 +:1021B000BDE8384005F0E8B92868204405F0D2F9B8 +:1021C0000028F3D038BD00BF043400200020704741 +:1021D00000F1FF5000F58F10D0F8000870470000A4 +:1021E000064991F8243033B100230822086A81F8A7 +:1021F0002430FFF7BFBF0120704700BF0834002024 +:10220000014B1868704700BF0010005C194B013883 +:102210000322084470B51D68174BC5F30B042D0C41 +:102220001E88A6420BD15C680A46013C82421346D6 +:102230000FD214F9016F4EB102F8016BF6E7013AC3 +:1022400003F10803ECD181420B4602D22C2203F8A1 +:10225000012B0424094A1688AE4204D1984284BF57 +:10226000967803F8016B013C02F10402F3D1581A8D +:1022700070BD00BF0010005C88220020B4980008E8 +:10228000022804D1054B4FF400129A6170470128CF +:10229000FCD1024B4FF40022F7E700BF00100258B8 +:1022A000022803D1044B20229A6170470128FCD1F7 +:1022B000014B0822F8E700BF00100258022805D1A0 +:1022C000064A536983F02003536170470128FCD10B +:1022D000024A536983F00803F6E700BF0010025872 +:1022E00070B504464FF47A764CB1412C254628BF90 +:1022F000412506FB05F0641B04F0B2FCF4E770BD59 +:10230000002310B5934203D0CC5CC4540133F9E7E9 +:1023100010BD0000013810B510F9013F3BB191F933 +:1023200000409C4203D11AB10131013AF4E71AB1DD +:1023300091F90020981A10BD1046FCE703460246AA +:10234000D01A12F9011B0029FAD170470244034642 +:10235000934202D003F8011BFAE770472DE9F843D6 +:102360001F4D14460746884695F8242052BBDFF8D7 +:1023700070909CB395F824302BB92022FF21484659 +:102380002F62FFF7E3FF95F824004146C0F10802F1 +:1023900005EB8000A24228BF2246D6B29200FFF78A +:1023A000AFFF95F82430A41B17441E449044E4B2B8 +:1023B000F6B2082E85F82460DBD1FFF711FF002864 +:1023C000D7D108E02B6A03EB82038342CFD0FFF71B +:1023D00007FF0028CBD10020BDE8F8830120FBE7F0 +:1023E00008340020024B1A78024B1A70704700BF65 +:1023F0004834002074220020F8B5194C194803F025 +:1024000037FF2146174803F05FFF24684FF47A70C6 +:10241000154ED4F89020154DD2F80438114F43F0E2 +:102420000203C2F80438FFF75BFF2046104904F0AE +:1024300059F8D4F890200424D2F8043823F0020389 +:10244000C2F804384FF4E133336055F8040BB84256 +:1024500002D0314603F06AFE013CF6D1F8BD00BF60 +:10246000B0A00008784900203034002078220020F5 +:10247000B8A000080C4B70B50C4D04461E780C4BF0 +:1024800055F826209A420DD00A4B002118221846F2 +:10249000FFF75CFF0460014655F82600BDE8704078 +:1024A00003F044BE70BD00BF4834002078220020F5 +:1024B0007849002030340020F0B5A1B071B6002377 +:1024C0000120002480261A46194602F081FD4FF4AF +:1024D000D067214A3D25136923BBD2F810310BBBCD +:1024E000036804F1006199600368C3F80CD00368C5 +:1024F0005E6003681F6001680B6843F001030B60B6 +:1025000001680B6823F01E030B6001680B68DB0792 +:10251000FCD4037B8034416805FA03F3B4F5001F53 +:102520000B60D8D102F094FDB4F5001F11D0002447 +:102530000A4E0B4D012005F0E1F83388A34205D97E +:1025400028682044013405F01FF8F6E7002005F064 +:10255000D5F861B621B0F0BD002000524A34002009 +:102560000434002030B50A44084D91420DD011F8D2 +:10257000013B5840082340F30004013B2C4013F07A +:10258000FF0384EA5000F6D1EFE730BD2083B8EDB9 +:1025900010B5084C01220849002001F0B7FE23784D +:1025A0003BB1064803F03AFD044803F06DFD0023FB +:1025B000237010BD4C340020C49800082C37002034 +:1025C0001D482DE9F041036D2BB901224FF48051D4 +:1025D000503005F0DBFA194E33780BB1FFF7D8FF16 +:1025E0000324174F4FF00008134D15492846C7F82C +:1025F000048003F03BFD284603F074FB48B1013C26 +:10260000284603F041FD14F0FF04EED1204634705B +:102610000FE00C4901220C4801F078FE014618B188 +:10262000284603F0FBFCEAE7084800F011F8012017 +:102630003070BDE8F08100BF2C3700204C34002002 +:10264000A0220020C498000850340020C898000838 +:102650000FB4002004B0704700687047034600685C +:10266000596870470B0A017043700B0C090E837098 +:10267000C1707047110A027003714170110C120E83 +:102680008170C2701A0A42711A0C1B0E8271C371DA +:1026900070470000C36A0239023B8B4283BF438903 +:1026A000006C01FB0300002070470000C2F3072309 +:1026B0008A76CB760378032B01BF120C0A75120AB7 +:1026C0004A75704700F10B010022D30143EA52031F +:1026D00010F8012B52FA83F38842DAB2F5D1104692 +:1026E0007047000010B541780446002001310246D1 +:1026F0004901022A16BFA35C032203EBC03302F197 +:1027000001021EBF9BB203EB500398B29142F0D876 +:1027100010BD000002684AB1134613F8011B1F29BF +:102720000DD93A29F9D1911C8B4202D04FF0FF30DC +:1027300070471278302AF9D1036000207047014BAE +:10274000187870479C36002038B50D46044618B9F5 +:10275000092000232B6038BD0368002BF8D01A78BD +:10276000002AF5D08188DA889142F1D1587804F0B6 +:1027700013FC10F00100EBD12368EBE738B50D46F0 +:1027800040F25231144602F0BDF9FF2807D9012C5E +:102790000BD9030A022468702B70204638BD30B173 +:1027A000002CFAD001242870F7E70024F5E704464E +:1027B000F3E700002DE9F8430026D0F80080054635 +:1027C0000C468E76836B002B4AD098F80030042B91 +:1027D0004BD133463546402720E0B7F5187F80F0CF +:1027E000C480F90606F1010608BF0237D05B023744 +:1027F0002BB900F5205292B2B2F5006F0DD305F15E +:102800001A01C5F1FF0240EA03402144FFF7B6FF79 +:10281000002800F0AA80054400200346D8F81020C4 +:1028200092F82310B142D8D8002B40F09E80002DA2 +:1028300000F09B8000232544AB766373D8F810200A +:10284000137903F03701DB0621730BD402F1380052 +:10285000FFF704FFC4E9000193896381D3892381D1 +:10286000BDE8F88300200146F4E7C36C01335ED174 +:10287000EA6B00232E26551E184615F8011F01305D +:1028800020290CD0052908BFE521092804D10B2BEC +:102890009EBFE71801337E73E718013379730B2865 +:1028A000EBD1E11800204873A17E00294BD1002B09 +:1028B00040D06FF00C0604F10D000825361B3318CC +:1028C00010F8011B002938D02E298BB24AD0A3F171 +:1028D0004101192903D8117B0D4200D02033037325 +:1028E000EDE7B9F1000F05D100F520539BB2B3F528 +:1028F000006F0BD307F11A01C7F1FF0240EA09404C +:102900002144FFF73BFF48B10744002002368146CF +:10291000D8F80C30985B0028E3D13846B9F1000FA5 +:102920004FF0000218BF002023189A76A0E7B146A6 +:102930003746EDE73F23A376012323440021997610 +:10294000137B03B96373D37A02F11C0003F03F03D6 +:1029500023730023FFF780FE20606360D38A6381C6 +:10296000138B7CE710250B46B9E73F230125A3769F +:1029700060E7000038B50546002435F8020B08B9B9 +:10298000204638BD02F0F2F86308C2B203EBC4334C +:1029900012FA83F39AB2C0F3072303EB520303EB5B +:1029A000C2339CB2E9E7000037B5C37804461BB9CF +:1029B0000025284603B030BD00F14C01826C012394 +:1029C0004078019104F00EFB054680B9A36BE070DE +:1029D000A06C226BC31A9342EAD2A3780199022B0E +:1029E000E6D102440123607804F0FCFAE1E7012516 +:1029F000DFE7000038B5836C05460C468B4210D0EB +:102A0000FFF7D2FF60B92246012305F14C01687837 +:102A100004F0C4FA00281CBF4FF0FF340120AC645E +:102A200038BD0020FCE7000038B500230446C37021 +:102A30004FF0FF338364FFF7DDFF00284BD1B4F87C +:102A40004A524AF655239D4207D10B22254904F1EB +:102A50004C00FDF77BFE00283FD094F84C30EB2B68 +:102A600003D01833DBB2012B2ED84AF655239D42F2 +:102A700006D108221C4904F19E00FDF767FE48B309 +:102A8000B4F85730B3F5007F1ED194F85930DBB15C +:102A90005A1E1A4218D1B4F85A30ABB194F85C30CF +:102AA000013B012B10D8B4F85D306BB1B4F85F3046 +:102AB0007F2B06D804F16C00FFF7CEFDB0F5803F08 +:102AC00002D3B4F8623053B94AF6552085420CBFA0 +:102AD0000220032038BD0420FCE70120FAE7002093 +:102AE000F8E700BFF49800080099000802392DE9C2 +:102AF000F04701F007044FF0010A466C05460AFA58 +:102B000004F41746984606EB1136C1F3C809E4B23F +:102B1000314628460136FFF76DFF18B10120BDE8A8 +:102B2000F087994605EB090292F84C30234214BF16 +:102B300001210021414513D06340013F82F84C3010 +:102B400085F803A0EBD0640014F0FF04EAD109F18A +:102B5000010301244FF00009B3F5007FE1D1D7E76D +:102B60000220DCE701290246F8B50C4640F28C80D1 +:102B70000668F36A8B4240F287803378013B032B6F +:102B800000F28280DFE803F00229384B04EB5405A1 +:102B9000B16B304601EB5521FFF72CFF10B14FF020 +:102BA000FF30F8BD6F1CC5F30805B16B30463544E6 +:102BB00001EB572195F84C50FFF71CFF0028EED190 +:102BC000C7F30807E3073E4496F84C0045EA0020A7 +:102BD0004CBF0009C0F30B00E3E7B16B304601EBDB +:102BE0001421FFF707FF0028D9D1640004F4FF7413 +:102BF0002644B6F84C00D4E7B16B304601EBD41153 +:102C0000FFF7F8FE0028CAD1A40006F14C0004F436 +:102C1000FE742044FFF720FD20F07040C1E7D0E9AA +:102C20000430D57953EA000101D0916801B95DBB48 +:102C30009168022DA4EB01010DD1013B728940F195 +:102C4000FF305B0A43EAC053B3FBF2F399421BD84F +:102C50001CD0601CA5E7032D02D193698B42F8D8E4 +:102C6000D3699BB9B16B304601EBD411FFF7C2FEBB +:102C7000002894D1A0004C3600F4FE703044FFF7D9 +:102C8000EBFC20F000408CE701208AE76FF0004069 +:102C900087E70000F8B5066804460D463378042B34 +:102CA0000CBF4FF080524FF400128A4201D802202C +:102CB000F8BDCA06FBD182680163D2B9022B13D8D2 +:102CC0003389B3EB551FF2D9F36BA363A36B626334 +:102CD000002BECD003EB55234C36C5F30805002040 +:102CE000A3633544E563E3E7F36BC271002BE7D0E0 +:102CF0001A4677897F02BD42114604D23046FFF75B +:102D0000C9FCA063E2E72046FFF72CFF431C024604 +:102D100006D00128CBD9F36A8342C8D9ED1BEAE774 +:102D20000120C5E701292DE9F04706460C46174664 +:102D300008D9C36A8B4205D90378022B62D003D825 +:102D4000012B22D0022552E0033B012BFAD8816BE4 +:102D500001EBD411FFF74EFE0546002847D1A40031 +:102D600006F14C0304F4FE741C443378042B07D0A2 +:102D7000204627F07047FFF76FFC00F070400743D4 +:102D800039462046FFF76EFC2FE001EB5108816BBE +:102D900001EB5821FFF72EFE054640BB14F001045D +:102DA00006F14C0908F1010AC8F3080808BFFBB294 +:102DB00030461FBF19F8083003F00F023B0103F043 +:102DC000F00318BF134309F808300123B16BF37007 +:102DD00001EB5A21FFF70EFE054640B9CAF3080A77 +:102DE00044B1C7F3071709F80A700123F3702846A6 +:102DF000BDE8F08719F80A30C7F3032723F00F0363 +:102E00001F43F0E7816B01EB1421FFF7F3FD05464B +:102E10000028ECD1640006F14C0304F4FF741F5544 +:102E20001919C7F307274F70DFE70000F8B504460C +:102E30000E461746E3690BB91846F8BD012BA6EB01 +:102E40000305206814BFAA1C3A46691CFFF76AFFF5 +:102E50000028F2D1E369013BE361EBE701292DE9A9 +:102E6000F84306460C461746056802D80220BDE81E +:102E7000F883EB6A8B42F9D97AB9A14621463046EC +:102E8000A046FFF76FFE0446B0B92B78042B02D1A1 +:102E9000002F43D1F7710020E9E72B78042B02D1F2 +:102EA000C379022BE9D04FF0FF3239462846FFF7AD +:102EB00039FF0028E1D0DAE70128D7D0421C01D140 +:102EC0000120D4E72B78042B19D1EA6AAB69023AC6 +:102ED00093421CD308F10102A2420CD02B78042BA0 +:102EE00008D10023A2EB090249462846FFF7FEFD60 +:102EF0000028BCD1A146EB6AA342BFD8C5E7002297 +:102F000041462846FFF70EFF0028DED0AFE7013329 +:102F1000AB612B7943F001032B71DBE7F3798BB9BC +:102F2000B468BC4202D10223F371B4E721463046B3 +:102F3000FFF718FE012899D9431CC1D001348442FF +:102F4000EFD0A8E7032BA6D1B368BB42A3D8B269E0 +:102F50001344BB429FD3E6E770B5C3790446032B05 +:102F600006D181688369CD18A94203D10023E3719A +:102F7000002070BD4E1C20683246FFF7D3FE0028AB +:102F8000F7D13146F0E700002DE9F74305460191FE +:102F9000FFF70AFD0446002849D105F14C090199C3 +:102FA00028464FF40072FFF775FB2146A8640746D8 +:102FB0004846FFF7CBF96C896402B4F5004F28BF8F +:102FC0004FF40044B4F5007F2FD9204604F07AFC7A +:102FD000804630B122460021640A0026FFF7B6F988 +:102FE00009E06408EEE72346BA194146687803F021 +:102FF000F9FF18B926446B899E42F4D3404604F089 +:1030000071FC6889801B18BF012003B0BDE8F08304 +:1030100001366B899E42F4D20123BA194946687879 +:1030200003F0E0FF0028F3D0EBE70026F1E70120F2 +:10303000EBE70000F8B50446FFF7B6FC05460028AC +:1030400042D12378032B37D12779012F34D104F1D2 +:103050004C0601464FF400723046FFF777F95523CE +:103060004122722184F84A32AA2304F50D7084F8B3 +:103070004F2084F84B32522384F8301284F84C30BD +:1030800084F84D30612384F8311284F84E3084F88E +:103090003332A16984F83222FFF7E4FA616904F55A +:1030A0000E70FFF7DFFA626B3B4631460132607803 +:1030B000A26403F097FF257100226078114603F0A7 +:1030C000B5FF003818BF0120F8BD000000232DE92E +:1030D000F0430B6085B00F461546FFF71BFB061E3D +:1030E000C0F2B281804B53F82640002C00F0AE8134 +:1030F0003C6005F0FE0523786BB1607803F04CFF6F +:10310000C70708D41DB110F0040500D00A252846D1 +:1031100005B0BDE8F0830023F0B22370607003F0C7 +:1031200027FFC10700F194810DB14207EED40021C1 +:103130002046FFF779FC022840F099806E4604F2A1 +:10314000122304F25221324618461033FFF784FA54 +:1031500042F8040B8B42F7D1002556F8041B0029D6 +:103160007DD02046FFF760FC012879D80128A26CA9 +:1031700040F0C08004F1570304F18C0113F8015BA7 +:10318000002D7BD18B42F9D1B4F8B430B3F5807FF8 +:1031900074D194F8B830092B70D104F19400FFF782 +:1031A0005DFA4FF0FF33171841F10001BB4275EB98 +:1031B000010363D304F1A000FFF74EFA94F8BA308C +:1031C0002063012BA37059D194F8B99003FA09F93F +:1031D0001FFA89F36381002B50D0444B04F1A800FF +:1031E000FFF73AFA0646984248D8831C626304F116 +:1031F000A400E362FFF730FA00EB020804F19C0040 +:10320000C4F84080FFF728FA10441FFA89F2A0633F +:1032100006FB02F313EB080345EB05029F4271EB3B +:1032200002032BD32E4604F1AC00FFF715FAE0633E +:1032300065B96389B34221D9E16B2046FFF72AFAC9 +:1032400081192046FFF7D6FB98B90136631993F828 +:103250004C30812B14D02035C5F30805E8E7032056 +:103260000135042D7FF479AF042807D101E004284B +:1032700001D101254BE701287FF678AF0D2546E700 +:1032800005F1140004F14C063044FFF7E5F901287C +:103290000546F3D9E36A8342F0D96189821E236C23 +:1032A00002FB01336364A16B204601EBD511FFF7EC +:1032B000A1FB0028DDD105F07F0006EB8000FFF7C1 +:1032C000CBF9431C03D00135A842ECD0D6E7042546 +:1032D000C4E90500064A257000251388E56101331D +:1032E0009BB21380E38012E7A0360020FDFFFF7F32 +:1032F000A4360020B4F85730B3F5007FBED1B4F83F +:10330000626026B904F17000FFF7A6F9064694F84A +:103310005C302663591EA3700129AFD894F8595028 +:103320006581002DAAD0691E2942A7D1B4F85D801D +:1033300018F00F0FA4F80880A0D1B4F85F0018B9F6 +:1033400004F16C00FFF788F9B4F85A10002995D001 +:1033500006FB03FE01EB181CF44460458ED3A0EB82 +:103360000C00A842B0FBF5F388D33E48834285D8D1 +:103370004FF6F57083426DD903259F1C114402EB73 +:103380000C03032DE7626263A16323644CD1B4F89C +:10339000763053EA08037FF471AFBB0004F1780084 +:1033A000FFF75AF9E06303F2FF13B6EB532FFFF474 +:1033B00065AF4FF0FF33032DC4E905334FF08003B1 +:1033C000237187D1B4F87C30012B83D1511C204666 +:1033D000FFF710FB00287FF47DAFB4F84A224AF6CD +:1033E000552320719A427FF475AF1F4B04F14C00B6 +:1033F000FFF732F998427FF46DAF03F1FF5304F504 +:103400000C70FFF729F903F50053203398427FF43D +:1034100061AF04F50D70FFF71FF9A06104F50E70A0 +:10342000FFF71AF9606155E7B8F1000F3FF426AFD6 +:103430007144022D4FEA4703E1631EBFD91907F01B +:10344000010303EB5103AEE70B2560E60C255EE6B6 +:1034500003255CE640F6F575AB428CBF02250125DD +:103460008BE700BFF5FFFF0F525261412DE9F84F86 +:1034700007460568884649B96E69C6B1EB6AB3422A +:1034800098BF0126AB69A3B9002405E0FFF76AFBEA +:103490000128044603D801242046BDE8F88F421CC9 +:1034A00000F0D280EB6A8342F6D84646EAE701266E +:1034B000E8E72A78EB6A042A40F08380A6F1020A42 +:1034C000023B4FF0010B9A4528BF4FF0000AD1464E +:1034D000696C284601EB1931FFF78CFA00283BD1C3 +:1034E00009F00703EA6AC9F3C8010BFA03F3901E57 +:1034F000DBB26A184C4609F1010992F84C2081456B +:1035000002EA030233BF5B0000234FF40071DBB219 +:1035100028BF9946B2B90234631E0333BCD80123D5 +:10352000214628461A46FFF7E1FA0228B3D00128BF +:1035300000F08A80B8F1000F13D10223FB7100283C +:10354000A9D130E0CA450AD0002BD2D10131B1F562 +:10355000007FBDD20123CCE74FF0FF34DCE700242D +:10356000DAE7FB79022B07D1731CA342E7D0BB68D3 +:10357000F31ABB610323FB7108F10102FB69A2424C +:1035800005D113B10133FB61D9E70223FBE70BB986 +:103590000123FB61224641463846FFF747FC0028DD +:1035A0004FD10123FB61EA6AAB69023A6C61934235 +:1035B0009CBF03F1FF33AB612B7943F001032B7107 +:1035C0006AE7464514D1741C38469C4228BF022441 +:1035D0002146FFF7C7FA01283FF45DAF431C33D003 +:1035E000E0B16B69012B03D9EA6A934238BF1E46EA +:1035F00034460134EB6AA34203D8012E7FF644AF70 +:10360000022421463846FFF7ADFA48B101283FF4BD +:1036100042AF013018D0B442EBD135E7002CE7D0EF +:103620004FF0FF3221462846FFF77CFB48B9B8F13E +:10363000000FB8D0224641462846FFF773FB00280A +:10364000B1D001287FF427AF4FF0FF3424E700000A +:103650002DE9F84306680446076B8946337820371E +:10366000042B0CBF4FF080534FF40013BB429CBFA0 +:1036700000238363836B73B1C7F30808B8F1000FAD +:103680003CD10133416B836339B93389B3EB571FA5 +:1036900034D80023A36304200AE07389013B13EAB2 +:1036A00057232BD1FFF75EFA0128054602D80220E6 +:1036B000BDE8F883421C01D10120F9E7F36A834297 +:1036C00016D8B9F1000FE4D0616B2046FFF7CEFEAB +:1036D0000546C8B10128EAD0431CEDD0014630466A +:1036E000FFF752FC0028E7D1E37943F00403E371CC +:1036F000294630466563FEF7CDFFA0634C360020B7 +:1037000027634644E663D3E70720D1E7F8B50E46C2 +:10371000002104460768FFF7BDFA98B90546A16B7A +:103720003846FFF767F968B93A78E36B042A1B78E3 +:103730000CD11B060ED5054601212046FFF788FF58 +:103740000028ECD0042808BF072006E0E52B01D0B4 +:10375000002BF0D10135B542EED1F8BDC16C4B1C48 +:103760002DE9F04104460568066B1FD1E5274FF0AF +:103770000108A16B2846FFF73DF998B92A78E36B59 +:10378000042A09BF1A781F7002F07F021A7085F8A8 +:103790000380236BB3420DD200212046FFF758FF70 +:1037A0000028E6D0042808BF022003E0FFF772FAE1 +:1037B0000028DBD0BDE8F0812DE9F0410546006826 +:1037C000A96B0669FFF716F9044620B9EB6B1A7866 +:1037D000852A03D002242046BDE8F081324603F159 +:1037E000200153F8040B8B4242F8040BF9D177788F +:1037F00001377F01A7F16003B3F5007FEAD800210C +:103800002846FFF725FF04280446E3D00028E2D12C +:10381000A96B2868FFF7EEF804460028DBD1EB6BB4 +:103820001A78C02AD6D106F1200203F1200153F8FC +:10383000040B8B4242F8040BF9D196F823300F2287 +:103840002C33B3FBF2F3B7EB431FC3D34FF0400865 +:1038500000212846FFF7FCFE04280446BAD00028C1 +:10386000B9D1A96B2868FFF7C5F804460028B2D182 +:10387000EB6B1A78C12AADD1B8F5187F09D206EBE7 +:10388000080203F1200153F8040B8B4242F8040BA9 +:10389000F9D108F120084745DAD8B8F5187F9AD849 +:1038A0003046FEF71FFF7388834294D092E70000F2 +:1038B0000B68002210B5036004460B6A83604B6AF4 +:1038C000C261C37123F0FF03896AC0E90432C16495 +:1038D000FFF7E0F920B92046BDE81040FFF76CBFC4 +:1038E00010BD0000F8B50368054601271C69204695 +:1038F000FEF7F8FEA070000A6678E0702846E96CD2 +:10390000FFF7C8F920B1022828BF0220C0B2F8BDD5 +:10391000A96B2868FFF76EF80028F4D1EB6B04F16F +:10392000200254F8041B944243F8041BF9D12B687D +:10393000DF70002EE7D000212846013EFFF788FE09 +:10394000E0E700002DE9F8434FF0FF08064607685E +:10395000042445464FF6FF79B16B11B9002C73D0A2 +:1039600063E03846FFF746F8044600285DD1F06B67 +:103970000378002B6ED03A78042A11D1852B4DD1D3 +:10398000336B3046F364FFF717FF044600284CD131 +:103990003B691B7903F03F03B3712046BDE8F88310 +:1039A000C27AE52B02F03F02B27143D02E2B41D0F8 +:1039B00022F0200108293DD00F2A40D1590637D5E1 +:1039C00003F0BF05336B90F80D80F364437B4345F0 +:1039D00030D1428B72BB03780D21FC6823F0400389 +:1039E000DFF874E0013B4B4301211EF801CB30F8B6 +:1039F0000CC009B3FF2B1DD824F813C06146013356 +:103A000001320D2AF1D10278520605D521B1FF2BE2 +:103A100010D8002224F81320013DEDB200213046D9 +:103A2000FFF716FE0446002896D00023B363B4E7E0 +:103A3000AB42CBD0FF25F1E7CC45E1D0FAE72DB979 +:103A4000FEF740FE404501D10024A6E74FF0FF33CA +:103A5000F364A2E70424E8E79C9900082DE9F04FFD +:103A6000002187B00446D0F80090FFF713F9804694 +:103A700070B999F80030042B33D1D9F80C00FEF757 +:103A800079FF07462046FFF75DFF054620B18046D7 +:103A9000404607B0BDE8F08FD9F810309A8CBA4292 +:103AA000F0D193F823B040265D4506D1D9F80C300B +:103AB00033F81530002BE5D1EAE7F106D9F81030DC +:103AC00008BF0236985B01F051F8D9F80C308246F5 +:103AD00033F8150001F04AF88245D3D1023601359A +:103AE000E2E74FF0FF0A4FF0FF3B5546C4F84CB0F9 +:103AF000A16B4846FEF77EFF00285CD1E66B377865 +:103B0000002F77D0F27AE52F02F03F03A37103D0A4 +:103B1000120704D50F2B04D0C4F84CB04FE00F2B84 +:103B200054D194F84B3058063FD4790645D5236BD1 +:103B300007F0BF0796F80DA0E364737B53453ED1B1 +:103B4000738B002B3BD135780121D9F80C3005F06F +:103B50003F0501930D23013D5D43284B13F8012BD5 +:103B6000B25A71B3FF2D059329D81046049200F084 +:103B7000FDFF6B1C03900293019B33F8150000F0CE +:103B8000F5FF039981421AD1049A029D1146059BC3 +:103B90001B4A9342E2D133785A0604D519B1019BEE +:103BA00033F815305BB97D1EEDB200212046FFF7DA +:103BB0004FFD00289CD080466AE7BD42BDD0FF255E +:103BC000F3E74FF6FF708242E2D0F8E72DB93046B6 +:103BD000FEF778FD50453FF45BAF94F84B30DB07C0 +:103BE0009AD40B2204F140013046FCF7AFFD0028C7 +:103BF00092D14DE74FF004084AE700BF9C990008B6 +:103C0000A99900082DE9F04F90F84BB099B00446FF +:103C10001BF0A00540F06C810668F26832F81530A0 +:103C2000002B4AD13378042B40F087800F230E35C8 +:103C30002046B5FBF3F5A91CFFF768FD8146002877 +:103C400077D1236B0135A3EB4515E3795A07E5647A +:103C500035D523F004032046E371FFF77DF950BB0F +:103C60004FF0FF32616B2046FFF7E0F818BBA36806 +:103C70002BB3214604A8FFF71BFEE0B970894FF46F +:103C80000071D4E90423E0FB01233069C4E9042373 +:103C90003830FEF7EFFC3069D4E904232830FEF712 +:103CA000E9FCE379326904A843F0010382F821308A +:103CB000FFF718FE18B181463BE00135AEE7D6E9C3 +:103CC0000354402200212046FEF740FB85230121BA +:103CD00040222370C0234FF0C10C04EB010884F88C +:103CE000203000231E469E46571C04F802C0F0B246 +:103CF000023204F807E021B135F8131009B101339D +:103D0000DBB20F0AA15408F802700232D706F2D1D2 +:103D100035F813700136002FE6D184F82330831C68 +:103D200028466370FEF726FE84F82400000A84F813 +:103D30002500484619B0BDE8F08F04F140070DF1A9 +:103D4000100A1BF0010F97E807008AE8070000F04F +:103D5000D78040234FF0010884F84B30BC46F3680D +:103D6000B8F1050F9AE80700ACE803002CF8022B25 +:103D70004FEA12428CF800205DD9981E424630F876 +:103D8000021F002946D10DF10F0C072102F00F0E82 +:103D9000914612090EF13000392888BF0EF1370024 +:103DA00001390CF8010902D0B9F10F0FEED801F179 +:103DB00060037E200DEB030202F8580C3846002207 +:103DC000914206D010F801CB02F1010EBCF1200F98 +:103DD00033D104F13F0C072902F1010297BF01F131 +:103DE0006003202001310DEB030098BF10F8580C40 +:103DF000072A0CF80200EED92046FFF72FFE814675 +:103E0000002878D108F10108B8F1640FA6D14FF06D +:103E100007098EE74FF0100C01F0010E49080EEB78 +:103E20004202D30344BF82F4883282F02102BCF103 +:103E3000010CF1D1A3E74246A5E77246C0E7216B2A +:103E40002046A1EB4511FEF725FF814600287FF4AF +:103E500070AF4FF6FF783846FEF734FC0190A16B47 +:103E60003046FEF7C7FD814600287FF462AFE36B62 +:103E7000E9B2019A4FF00D0CD6F80CE05A734FF0EE +:103E80000F02DFF8E0A0DA724A1E18730CFB02F290 +:103E900084469876D87640451AF8019B0CF1010CBF +:103EA00018BF3EF8120003EB090B18BF013203F8EC +:103EB00009004FEA1029002808BF4046BCF10D0F49 +:103EC0008BF80190E7D1404502D03EF812200AB9A4 +:103ED00041F040011970012300212046F370FFF7E3 +:103EE000B7FB814600287FF424AF013DB7D11BE02A +:103EF0004FF006091DE704287FF41BAF84F84BB090 +:103F00001BF0020F20461BBF0C350D210125B5FB10 +:103F1000F1F518BF01352946FFF7F8FB8146002867 +:103F20007FF407AF013D8AD1A16B3046FEF762FDF9 +:103F3000814600287FF4FDAE01462022E06BFEF7AB +:103F400005FAE36B03CF18605960BA7839889A7222 +:103F5000198194F84B30E26B03F0180313730123BB +:103F6000F370E6E69C99000810B504460A46343022 +:103F7000FEF772FB886004F13800FEF76FFBC2E9C0 +:103F8000040194F8213003F00203D3710023D361BC +:103F900010BD000003284B8B04BF8A8A43EA02430A +:103FA000184670472DE9F04F0B7899B004468946C2 +:103FB0002F2BD0F800B001D05C2B09D14A461378E2 +:103FC000914601322F2BFAD05C2BF8D0002301E070 +:103FD000DBF81C30A3600023E3619BF80030042B66 +:103FE0001ED1A368E3B1DBF82030214604A8236288 +:103FF000DBF824306362DBF82830A362FFF758FC5B +:104000000346002854D1DBF8102002F13800FEF7F7 +:1040100023FBC4E9040392F8213003F00203E371A7 +:1040200099F800301F2B00F23581802300212046B3 +:1040300084F84B3019B0BDE8F04FFEF72BBE49466F +:104040000B78894601312F2BFAD05C2BF8D01F2B2F +:104050008CBF00250425012F2FD113882E2B31D1A1 +:10406000002322F8173004F140029F428CBF2E211A +:10407000202101330B2B02F8011BF6D145F020055E +:10408000204684F84B50FFF7E9FC94F84B300028A9 +:1040900000F0E78004280BD1990603F0040240F1F8 +:1040A000DC80002A00F0F6808023002084F84B306A +:1040B00019B0BDE8F08F0425CDE7022F02D1538857 +:1040C0002E2BCAD0911E87BB002322F81730002F59 +:1040D00000F0118132F81300194601332028F9D07D +:1040E00009B92E2801D145F00305901E30F817308C +:1040F0002E2B01D0013FF9D14FF020334FF0000AB1 +:104100006364D0462364C4F847300823481C32F85F +:1041100011600090F6B1202E03D02E2E0DD1B842A2 +:1041200010D045F003050099F0E731F81730202B47 +:1041300001D02E2BC8D1013FC5E79A4505D2009981 +:10414000B9423BD10B2B30D101E00B2B27D145F0ED +:1041500003050B2394F84020E52A04BF052284F8C8 +:104160004020082B04BF4FEA88085FFA88F808F05F +:104170000C030C2B03D008F00303032B01D145F0F3 +:104180000205A8073FF57CAF18F0010F18BF45F0F6 +:10419000100518F0040F18BF45F0080570E70099E6 +:1041A000B94202D045F00305D4D84FEA88080B2362 +:1041B0004FF0080A00975FFA88F8B4E77F2E15D908 +:1041C000304640F25231CDE9022345F0020301931B +:1041D00000F098FC10F0800F0646DDE9022316D0AF +:1041E00000F07F0646498E5D019D46B33146454845 +:1041F000CDE90123FCF7A4FCDDE90123F8B9A6F120 +:10420000410189B219291ED848F0020810E0FF28A0 +:10421000EAD9591E8A4503D345F003059A4682E739 +:1042200004EB0A01000A0AF1010A019D81F840002D +:1042300004EB0A010AF1010A81F8406073E745F0D6 +:1042400003055F26F4E7A6F1610189B219299EBF33 +:10425000203E48F00108B6B2EAE7002A08BF052070 +:1042600026E75A073FF524AFA379DB0645D59BF82F +:104270000000042835D1A3682146E279236223692E +:10428000DBF8100023F0FF0313436362E36CA362C7 +:10429000FFF76AFE23680027DA6819F8010B002887 +:1042A0003FF409AF40F25231009200F04BFC05465A +:1042B00008B31F28009A7FF6FEAE2F283FF4BFAE4A +:1042C0005C283FF4BCAE7F2805D801460E48FCF7B9 +:1042D00037FC009A78B9FF2F0DD022F8175001371C +:1042E000DBE7216B0BF14C03C1F308011944FFF725 +:1042F00051FEA060CEE70620DAE60520D8E600BF32 +:104300001C990008159900080C9900081FB5CDE903 +:10431000001003A814460391FEF7FCF9002815DBF2 +:104320000B4A52F820300BB100211970019B0BB1E0 +:104330000021197042F820302CB1002201A96846F2 +:10434000FEF7C4FE0446204604B010BD0B24FAE775 +:10435000A03600202DE9F04798B09046054601911F +:10436000002800F0528102F03F0603A901A832465E +:10437000FEF7ACFE002840F04681039B4FF48C60B2 +:10438000049303F09FFA0746002800F04081039B46 +:1043900000F500720199D86004A81A61FFF702FEC7 +:1043A000044620B99DF95B30002BB8BF062418F0F5 +:1043B0001C0F00F0CD80002C4CD0042C40D104A860 +:1043C000FFF720FC044600283AD146F00806039B7C +:1043D0001A78042A40F08380186929462B60FFF779 +:1043E000C3FD039B1E22002118690230FDF7AEFFBA +:1043F000039C00211A2220692630FDF7A7FF2369BC +:1044000020221A71246903F097FA01460122083428 +:104410002046FEF727F9039B04A81B6983F8212097 +:10442000FFF760FA044658B9A96801B30246284666 +:10443000FEF714FDAB68039A0446013B5361B4B127 +:10444000384603F04FFA0CB100232B60204618B019 +:10445000BDE8F0879DF8163013F0110F40F084800E +:1044600018F0040F40F0C98018F0080FAFD1039A7C +:1044700031071399936C48BF46F04006E964AB647A +:104480001078042872D1069B9DF817102B62089BA8 +:10449000106923F0FF030B4329466B62179BAB6245 +:1044A000FFF762FDDDF80CA00024002205F15008A2 +:1044B000BAF8063021464046C5F800A0AB8000237C +:1044C00085F8306085F831406C64C5E90E234FF4FF +:1044D0000072FDF73BFFB20653D40024B0E703F0AF +:1044E0002BFA0146009013980E30FEF7BBF8139894 +:1044F00000991630FEF7B6F8039C13992078FFF761 +:1045000049FD202300228046CB7220461399FEF7F6 +:10451000CDF8139B002201211A775A779A77DA7720 +:10452000039BD970B8F1000FA1D0414604A8D3F87D +:104530004890FEF793FC0446002881D14946039831 +:10454000FEF758FA039B044608F1FF30586176E7FE +:10455000002C7FF475AF9DF81630DC064FD418F0B0 +:10456000020F84D0D80782D5072469E7FFF712FD30 +:104570000023A86001F11C00FEF76EF86B61286152 +:1045800090E7D5E9046956EA0903A6D0BAF80AA06B +:10459000A9684FEA4A2AC5E90E69B24574EB0903D6 +:1045A0001BD300242964002C7FF44AAFC6F3080310 +:1045B000002B92D0039C2046FEF76CF808B3760AD5 +:1045C0000123414646EAC95682196A64607802F0BE +:1045D000E5FC041E18BF012432E72846FEF7C2FAA4 +:1045E000B6EB0A06014669F10009012803D9431C0C +:1045F000D3D10124D6E70224D4E7082420E70424F9 +:104600001EE702241CE704461EE709241EE71124C6 +:104610001CE700002DE9F04F994685B0002388463D +:1046200003A90446C9F800301646FEF78DF8054682 +:1046300080BB94F831506DBB94F8303013F0010317 +:10464000009300F0A68004F1500AD4E90432D4E9C2 +:104650000E011B1A62EB0102B34272F1000238BF75 +:104660001E46BEB1D4E90E10C1F30803002B40F082 +:104670008280039B5A894B0A013A43EAC0531A408D +:104680001BD151EA000309D1A06801280DD80225E9 +:1046900084F83150284605B0BDE8F08F216C2046E3 +:1046A0000192FEF75FFA019AEFE7431C04D1012360 +:1046B000009D84F83130EDE72064DDF80CB0216C0A +:1046C0005846FDF7E7FF0028E1D0B6F5007F02EB82 +:1046D000000731D3BBF80A1002EB5620730A884258 +:1046E0009BF8010088BF8B1A3A464146019302F0BD +:1046F00055FC0028DBD194F93020019B002A0BDA0D +:10470000606CC01B984207D24FF40072514608EB10 +:104710004020FDF7F5FD019B5F02D9F80030F61B44 +:10472000B8443B44C9F80030D4E90E32DB1942F1F9 +:104730000002C4E90E3294E7626CBA421AD094F9CE +:104740003030002B0DDA012351469BF8010002F0B6 +:1047500049FC0028ABD194F8303003F07F0384F893 +:104760003030039801233A465146407802F016FC57 +:1047700000289CD16764A16B4046C1F30801C1F5D4 +:1047800000775144B74228BF37463A46FDF7B8FD97 +:10479000C3E707257EE7000070B596B00E460022FD +:1047A000019002A901A8FEF791FC0446E0B94FF47C +:1047B0008C6003F087F80546D8B1029B00F50072C3 +:1047C0000199D86002A81A61FFF7ECFB044640B9D2 +:1047D0009DF95330002B0ADB1EB1314602A8FDF7CC +:1047E000E9FF284603F07EF8204616B070BD062487 +:1047F000F7E71124F8E7000070B5B8B00222019085 +:1048000003A901A8FEF762FC044608BB039B4FF412 +:104810008C60109303F056F80546002866D0039B81 +:1048200000F500720199D86010A81A61FFF7BAFB71 +:10483000044650B99DF88B30980655D4190653D4C8 +:104840009DF84630DA0706D50724284603F04AF8D3 +:10485000204638B070BD039B04931878042814D107 +:1048600004A91869FFF780FB069E9DF84630DB0619 +:1048700010D410A8FEF772FF04460028E5D156BBFD +:104880000398FEF7D7FB0446DFE71F99FFF782FB8B +:104890000646EAE7039BDA69B242D5D024930021A9 +:1048A000269624A81B78042B01BFDDE90823CDE957 +:1048B00028239DF817308DF89730FEF7EBF9044662 +:1048C0000028C2D124A8FFF73DF804460028BBD039 +:1048D0000428BAD1CDE70246314604A8FEF7BEFA55 +:1048E00004460028B1D1CBE70624AEE71124AFE798 +:1048F000F0B5BDB0CDE900106846FDF70BFF022210 +:1049000003A901A8FEF7E2FB0446002841D1039B5E +:104910004FF48C60149302F0D5FF0546002800F098 +:10492000EE80039B00F5007214AE0199D8601A6105 +:104930003046FFF737FB044640BB9DF89B3013F031 +:10494000A00F40F0D880039B009F1A78042A68D1FA +:104950001B6904AC03F1400C1868083353F8041CBD +:104960002246634503C21446F6D15022314628A898 +:10497000FDF7C6FC394628A8FFF714FB04460028BB +:104980004CD12A9A169B9A4206D00824284602F057 +:10499000A9FF20463DB0F0BD349A209B9A42F4D145 +:1049A00028A8FFF72FF904460028EFD1039B04AF96 +:1049B0001B6993F801E093F823C09C8C3A460833B6 +:1049C00003CAB24243F8080C43F8041C1746F5D159 +:1049D000039B28A81B6983F801E0039B1A6982F8EE +:1049E00023C01A6982F82440240A82F825401A69F3 +:1049F0001379D9065CBF43F020031371FEF772FFF1 +:104A000004460028C2D13046FEF7A8FE044600281E +:104A1000BCD10398FEF70EFB0446B7E70428B5D1D6 +:104A2000BEE7239A04AB02F1200C1068083252F85A +:104A3000041C1C46624503C42346F6D1502231466D +:104A400028A8FDF75DFC394628A8FFF7ABFA044615 +:104A500000284CD12A9A169B9A4296D1349A209BD0 +:104A60009A4292D128A8FFF7CDF8044600288DD1AC +:104A700037990DF11D030DF12D0001F10D0253F8D1 +:104A8000044B834242F8044BF9D118880127108067 +:104A90009B7893709DF81B30039CDA0658BF43F057 +:104AA0002003CB72E770CB7ADB06ACD5169A2A9B33 +:104AB0009A42A8D02078FFF76DFA01462046FDF70C +:104AC000E9FD0146C8B12046FDF794FF04460028E1 +:104AD0007FF45CAF039890F86D302E2B93D12A9A17 +:104AE00000F16C01FDF7E2FD039BDF708BE704280A +:104AF0007FF44CAFB6E7062448E7022446E71124CA +:104B000047E700007F2810B501D880B210BDB0F58E +:104B1000803F13D240F2523399420FD1084900220C +:104B200031F8024B93B2844203D103F18000C0B24A +:104B3000ECE70132802AF3D11346F6E70020E5E7DF +:104B40005C9C00087F280DD940F25233994208D16D +:104B5000FF2806D800F10040034B803833F81000DE +:104B600070470020704700BF5C9C0008B0F5803F94 +:104B7000F0B522D21F4A83B21F49B0F5805F28BF2B +:104B80000A46141D34F8042C2146AAB1934213D3CB +:104B900034F8025C2E0AEFB252FA85F5A84222DA06 +:104BA000082E09D8DFE806F0050A10121416181AA4 +:104BB0001C00801A34F810301846F0BD981A00F026 +:104BC00001001B1A9BB2F7E7103BFBE7203BF9E71C +:104BD000303BF7E71A3BF5E70833F3E7503BF1E7E3 +:104BE000A3F5E353EEE70434002ECBD101EB4702EB +:104BF000C7E700BFAC990008A09B000808B5074BA9 +:104C0000074A196801F03D01996053680BB190683B +:104C10009847BDE8084003F0A9B800BF0000024073 +:104C2000A836002008B5084B1968890901F03D0134 +:104C30008A019A60054AD3680BB110699847BDE8AC +:104C4000084003F093B800BF00000240A8360020DF +:104C500008B5084B1968090C01F03D010A049A6077 +:104C6000054A53690BB190699847BDE8084003F0C5 +:104C70007DB800BF00000240A836002008B5084BF0 +:104C80001968890D01F03D018A059A60054AD369CA +:104C90000BB1106A9847BDE8084003F067B800BF41 +:104CA00000000240A836002008B5074B074A5968A3 +:104CB00001F03D01D960536A0BB1906A9847BDE895 +:104CC000084003F053B800BF00000240A83600209F +:104CD00008B5084B5968890901F03D018A01DA607D +:104CE000054AD36A0BB1106B9847BDE8084003F042 +:104CF0003DB800BF00000240A836002008B5084BB0 +:104D00005968090C01F03D010A04DA60054A536B49 +:104D10000BB1906B9847BDE8084003F027B800BF7F +:104D200000000240A836002008B5084B5968890DDC +:104D300001F03D018A05DA60054AD36B0BB1106CB6 +:104D40009847BDE8084003F011B800BF00000240DA +:104D5000A836002008B5074B074A196801F03D0145 +:104D60009960536C0BB1906C9847BDE8084002F015 +:104D7000FDBF00BF00040240A836002008B5084B64 +:104D80001968890901F03D018A019A60054AD36CCE +:104D90000BB1106D9847BDE8084002F0E7BF00BFB7 +:104DA00000040240A836002008B5084B1968090C19 +:104DB00001F03D010A049A60054A536D0BB1906DF4 +:104DC0009847BDE8084002F0D1BF00BF0004024090 +:104DD000A836002008B5084B1968890D01F03D017F +:104DE0008A059A60054AD36D0BB1106E9847BDE8ED +:104DF000084002F0BBBF00BF00040240A8360020FC +:104E000008B5074B074A596801F03D01D960536E58 +:104E10000BB1906E9847BDE8084002F0A7BF00BFF5 +:104E200000040240A836002008B5084B59688909DB +:104E300001F03D018A01DA60054AD36E0BB1106FB3 +:104E40009847BDE8084002F091BF00BF000402404F +:104E5000A836002008B5084B5968090C01F03D013F +:104E60000A04DA60054A536F0BB1906F9847BDE8AA +:104E7000084002F07BBF00BF00040240A8360020BB +:104E800008B5084B5968890D01F03D018A05DA60C3 +:104E9000054AD36F13B1D2F880009847BDE80840A7 +:104EA00002F064BF00040240A836002000230C4931 +:104EB00010B51A460B4C0B6054F82300026001EB4E +:104EC000430004334260402BF6D1074A4FF0FF33D2 +:104ED0009360D360C2F80834C2F80C3410BD00BF30 +:104EE000A83600205C9D0008000002400F28F8B59D +:104EF00010D9102810D0112811D0122808D10F2451 +:104F00000720DFF8C8E00126DEF80050A04208D9EB +:104F1000002653E00446F4E70F240020F1E70724BD +:104F2000FBE706FA00F73D424AD1264C4FEA001C47 +:104F30003D4304EB00160EEBC000CEF80050C0E974 +:104F40000123FBB273B12048D0F8D83043F00103FD +:104F5000C0F8D830D0F8003143F00103C0F8003178 +:104F6000D0F8003117F47F4F0ED01748D0F8D83062 +:104F700043F00203C0F8D830D0F8003143F0020308 +:104F8000C0F80031D0F8003154F80C00036823F069 +:104F90001F030360056815F00105FBD104EB0C034A +:104FA0003D2493F80CC05F6804FA0CF43C602124A3 +:104FB0000560446112B1987B00F0CAFC3046F8BD30 +:104FC0000130A3E75C9D000800440258A836002089 +:104FD00010B5302484F31188FFF788FF002383F392 +:104FE000118810BD10B50446807B00F0C7FC01237A +:104FF0001549627B03FA02F20B6823EA0203DAB274 +:105000000B6072B9114AD2F8D81021F00101C2F830 +:10501000D810D2F8001121F00101C2F80011D2F825 +:10502000002113F47F4F0ED1084BD3F8D82022F083 +:105030000202C3F8D820D3F8002122F00202C3F8FC +:105040000021D3F8003110BDA836002000440258DA +:1050500008B5302383F31188FFF7C4FF002383F3DF +:10506000118808BD836CC26A8B42506810B506D99E +:105070005A1E4C0002EB4103B3FBF4F3184410BD7D +:1050800001F001038A0748BF43F002034A0748BF03 +:1050900043F008030A0748BF43F00403CA0648BFA9 +:1050A00043F010038A06426B48BF43F020031343CA +:1050B0004363704710B5074C204600F0CBFF064B0A +:1050C0000022C4E91023054BA364054BE363054BA1 +:1050D000E36410BD2C3700200024024800B4C4044F +:1050E0008037002080390020C36A0BB9104BC3629F +:1050F0000379012B11D10F4B98420ED10E4BD3F8EF +:10510000DC2042F40072C3F8DC20D3F8042142F41E +:105110000072C3F80421D3F80431436C00221A65ED +:10512000DA621A605A605A624FF0FF329A6370472F +:105130005C9E00082C370020004402580379012BA4 +:105140001BD0436C00221A65DA621A605A605A62F8 +:105150004FF0FF329A63094B98420ED1084BD3F8B7 +:10516000DC2022F40072C3F8DC20D3F8042122F4FE +:105170000072C3F80421D3F8043170472C370020A3 +:105180000044025810B5446C0649FFF76BFF60609D +:10519000236842F2107043F003032360BDE810401F +:1051A00001F05EBD801A06000129F8B5466C0B4F70 +:1051B00009D175680A493D40FFF754FF054345F49E +:1051C00080557560F8BD746806493C40FFF74AFF9A +:1051D000044344F480547460F4E700BF00ECFFFF24 +:1051E00080F0FA0240787D01436C00225A601A6018 +:1051F00070470000426C0129536823F4404304D0F7 +:10520000022905D001B95360704743F48043FAE79F +:1052100043F40043F7E70000436C41F480519A6087 +:10522000D9605A6B1206FCD580229A637047000041 +:1052300010B541F48851446CA260E160616B11F0DB +:105240004502FBD0A26311F0040203D0FFF718FF60 +:10525000012010BD616910461960FAE710B541F4EC +:105260008851446CA260E160616B11F04502FBD093 +:10527000A26311F0050203D0FFF702FF012010BD69 +:10528000616910461960FAE773B5134604460E4685 +:10529000302282F31188426CD26B32B14FF0FF3171 +:1052A0004030019301F0E8FC019B606C0022026534 +:1052B000C263C262456B15F4807504D185F3118811 +:1052C000012002B070BD4FF0FF31816382F311887D +:1052D000012E06D90C21204602B0BDE87040FFF730 +:1052E000BDBF1046EDE7000073B5446C0E460025C7 +:1052F0000192616BA1632565E562FFF7C1FE012E96 +:1053000007D9019B2A460C2102B0BDE87040FFF787 +:10531000A5BF02B070BD000010B541F49851446CB7 +:10532000A260E160616B11F04502FBD0A26311F055 +:105330003F0203D0FFF7A4FE012010BD216A1046F2 +:105340001960E1695960A16999606169D960F4E700 +:105350002DE9F74304460191006D01A917469846CF +:1053600002F02CFC064600284AD0626C2046DDF88C +:1053700004905568C5F3090501356B00A56CB5FBB4 +:10538000F3F54FF47A73B5FBF3F55D43556200F026 +:1053900027FE50BB636C4FF0FF3201254146C3F836 +:1053A000589020461D659A634FF49572DA6342F275 +:1053B00007029F62DA62E36C0A9AFFF74FFFA0B917 +:1053C000E26C104B11680B407BB929462046FFF771 +:1053D0005BFF054648B92E463A460199206D02F01A +:1053E00025FC304603B0BDE8F0833A460199206DB4 +:1053F00002F01CFCE26C01212046FFF775FFF0E78C +:105400000126EEE708E0FFFD2DE9F7431F46436C58 +:1054100001924FF47A725D6804468846C5F3090527 +:1054200001356E00856CB5FBF6F5B5FBF2F555431D +:105430005D6200F0D5FD20B10125284603B0BDE82E +:10544000F0837E0201A9206D324602F0B7FB0546CB +:105450000028F1D0636C019AD4F84C909A6501222F +:105460001A654FF0FF329A634FF49572DA639E62C9 +:10547000236BDB064B4658BF4FEA4828012F4246B4 +:105480001BD912212046FFF7E9FEC0B9D9F8002048 +:10549000104B13409BB9636C42F29302394620468D +:1054A000DA62E26CFFF7F0FE804640B932460199BD +:1054B000206D454602F0BAFBBFE71121E2E7324614 +:1054C0000199206D02F0B2FBE26C39462046FFF7ED +:1054D0000BFFB2E708E0FFFD2DE9F3411F46436CE7 +:1054E00001924FF47A725D6804468846C5F3090557 +:1054F00001356E00856CB5FBF6F5B5FBF2F555434D +:105500005D6200F06DFD20B10125284602B0BDE8C6 +:10551000F0817E0201A9206D324602F095FB05461E +:105520000028F1D0636C019A9A6501221A654FF048 +:10553000FF329A634FF48D72DA639E62236BE66CDE +:10554000DB06334658BF4FEA4828012F424619D997 +:1055500019212046FFF782FEB0B932680F4B134085 +:1055600093B9636C42F2910239462046DA62E26CEA +:10557000FFF78AFE064638B901993546206D02F0DC +:105580009FFBC2E71821E4E70199206D02F098FB28 +:10559000E26C39462046FFF7A7FEB6E708E0FFFDBC +:1055A00012F0030F2DE9F04107460C4615461E4642 +:1055B00017D00E44B44202D10020BDE8F08101238F +:1055C000FA6B21463846FFF71FFF0028F5D1284621 +:1055D0004FF40072F96B05F500750134FCF790FE8D +:1055E000E8E7BDE8F041FFF70FBF000012F0030F3E +:1055F0002DE9F04107460C4615461E4617D00E44CD +:10560000B44202D10020BDE8F08129464FF4007277 +:10561000F86B05F50075FCF773FE0123FA6B214664 +:105620003846FFF759FF0028EDD10134E8E7BDE81F +:10563000F041FFF751BF000000207047302310B544 +:1056400083F311880024436C40302146DC6301F071 +:1056500021FB84F3118810BD026843681143016087 +:1056600003B1184770470000024A136843F0C003B3 +:105670001360704700480040024A136843F0C003BB +:105680001360704700500040024A136843F0C003A3 +:105690001360704700780040064BD3F8E8200243BF +:1056A000C3F8E820D3F810211043C3F81001D3F851 +:1056B000103170470044025837B5274C274D20461B +:1056C00000F028FD04F11400009400234FF4007250 +:1056D000234900F0C3F94FF40072224904F1380065 +:1056E0000094214B00F03CFA204BC4E91735204CC4 +:1056F000204600F00FFD04F11400009400234FF445 +:1057000000721C4900F0AAF94FF400721A4904F122 +:1057100038000094194B00F023FA194BC4E91735EF +:10572000184C204600F0F6FC04F1140000234FF45E +:1057300000721549009400F091F9144B4FF4007277 +:10574000134904F13800009400F00AFA114BC4E93F +:10575000173503B030BD00BF8439002000E1F505E6 +:10576000C83A0020C84000206956000800480040A0 +:10577000F0390020C83C0020C842002079560008BB +:10578000005000405C3A0020C83E002089560008C6 +:10579000C84400200078004038B5264D0446037CFC +:1057A000002918BF0D46012B06D1234B984230D15A +:1057B0004FF48020FFF770FF2A68236EE16D03EB42 +:1057C0005203A566B3FBF2F36A68100442BF23F0EC +:1057D000070003F0070343EA4003CB60AB6843F0E4 +:1057E00040034B60EB6843F001038B6042F4967317 +:1057F00043F001030B604FF0FF330B62510505D5F9 +:1058000012F0102211D0B2F1805F10D084F8643011 +:1058100038BD0A4B984205D0094B9842CCD14FF085 +:105820008040C7E74FF48010C4E77F23EEE73F23B3 +:10583000ECE700BF649E000884390020F0390020A6 +:105840005C3A00202DE9F047C66D05463768F469DB +:10585000210734621AD014F0080118BF4FF4807188 +:10586000E20748BF41F02001A3074FF0300348BFD3 +:1058700041F04001600748BF41F0800183F3118887 +:10588000281DFFF7E9FE002383F31188E2050AD5FE +:10589000302383F311884FF48061281DFFF7DCFE6D +:1058A000002383F311884FF030094FF0000A14F001 +:1058B000200838D13B0616D54FF0300905F1380ADB +:1058C000200610D589F31188504600F07DF9002894 +:1058D00036DA0821281DFFF7BFFE27F0800333606A +:1058E000002383F31188790614D5620612D530237C +:1058F00083F31188D5E913239A4208D12B6C33B175 +:1059000027F040071021281DFFF7A6FE376000236F +:1059100083F31188E30618D5AA6E1369ABB15069F9 +:10592000BDE8F047184789F31188736A284695F84F +:105930006410194000F008FC8AF31188F469B6E796 +:10594000B06288F31188F469BAE7BDE8F087000017 +:10595000090100F16043012203F56143C9B283F8F4 +:10596000001300F01F039A4043099B0003F16043BA +:1059700003F56143C3F880211A60704700F01F03EC +:1059800001229A40430900F160409B0000F561400C +:1059900003F1604303F56143C3F88020C3F880211D +:1059A000002380F800337047F8B515468268044636 +:1059B0000B46AA4200D28568A1692669761AB542CB +:1059C0000BD218462A46FCF79BFCA3692B44A36123 +:1059D0002846A3685B1BA360F8BD0CD9AF1B184613 +:1059E0003246FCF78DFC3A46E1683044FCF788FC0F +:1059F000E3683B44EBE718462A46FCF781FCE36882 +:105A0000E5E7000083689342F7B50446154600D2E7 +:105A10008568D4E90460361AB5420BD22A46FCF7F1 +:105A20006FFC63692B4463612846A3685B1BA3601A +:105A300003B0F0BD0DD93246AF1B0191FCF760FCFD +:105A400001993A46E0683144FCF75AFCE3683B446C +:105A5000E9E72A46FCF754FCE368E4E710B50A449A +:105A60000024C361029B8460C16002610362C0E9DB +:105A70000000C0E9051110BD08B5D0E90532934218 +:105A800001D1826882B98268013282605A1C426107 +:105A900019700021D0E904329A4224BFC3684361DF +:105AA00001F012F9002008BD4FF0FF30FBE70000C5 +:105AB00070B5302304460E4683F31188A568A5B15E +:105AC000A368A269013BA360531CA36115782269F6 +:105AD000934224BFE368A361E3690BB12046984772 +:105AE000002383F31188284607E03146204601F061 +:105AF000DBF80028E2DA85F3118870BD2DE9F74F55 +:105B000004460E4617469846D0F81C904FF0300ACF +:105B10008AF311884FF0000B154665B12A463146CD +:105B20002046FFF741FF034660B94146204601F099 +:105B3000BBF80028F1D0002383F31188781B03B051 +:105B4000BDE8F08FB9F1000F03D001902046C8479F +:105B5000019B8BF31188ED1A1E448AF31188DCE750 +:105B6000C160C361009B82600362C0E905111144FA +:105B7000C0E9000001617047F8B504460D461646BD +:105B8000302383F31188A768A7B1A368013BA36002 +:105B900063695A1C62611D70D4E904329A4224BFC1 +:105BA000E3686361E3690BB120469847002080F306 +:105BB000118807E03146204601F076F80028E2DA45 +:105BC00087F31188F8BD0000D0E9052310B59A428B +:105BD00001D182687AB982680021013282605A1C40 +:105BE00082611C7803699A4224BFC368836101F013 +:105BF0006BF8204610BD4FF0FF30FBE72DE9F74F63 +:105C000004460E4617469846D0F81C904FF0300ACE +:105C10008AF311884FF0000B154665B12A463146CC +:105C20002046FFF7EFFE034660B94146204601F0EB +:105C30003BF80028F1D0002383F31188781B03B0D0 +:105C4000BDE8F08FB9F1000F03D001902046C8479E +:105C5000019B8BF31188ED1A1E448AF31188DCE74F +:105C60000379052B05BF836A002001204B6004BF28 +:105C70004FF400730B60704770B55D1E866A044672 +:105C80000D44B54205D9436B43F0800343630120C3 +:105C900070BD06250571FFF783FC05232371F7E727 +:105CA00070B55D1E866A04460D44B54205D9436B46 +:105CB00043F080034363012070BD07250571FFF7A2 +:105CC00095FC05232371F7E738B505790446052DC2 +:105CD00005D108230371FFF7AFFC257138BD012002 +:105CE000FCE700000323F0B5037185B00446FFF71D +:105CF00049FA002220461146FFF78EFA4FF4D5727A +:105D000003AB08212046FFF7A9FA0246B8B90123E0 +:105D10002363039BC3F30323012B09D103AB372177 +:105D20002046FFF79BFA18B9A44B039A1340ABB176 +:105D300020460125FFF758FA0223237137E103AB10 +:105D4000002237212046FFF789FA28B99B4A039B96 +:105D50001A40002A00F0A78002232363236B03F07C +:105D60000F03022B40F0A9806425954E42F210707B +:105D700000F076FF03AB324601212046FFF758FAC8 +:105D80000028D5D1039B002B80F293805A0003D5C5 +:105D9000236B43F010032363002204F10803022164 +:105DA0002046FFF7B9FA02460028C1D104F13803B2 +:105DB00003212046FFF752FA0028B9D104F1180553 +:105DC000A26B092120462B46FFF7A6FA0028AFD187 +:105DD00002ABA26B07212046FFF740FA06460028D7 +:105DE000A6D1236B03F00F03022B40F08F807E229D +:105DF0007F21284603F028FA012840F28780E76BCC +:105E000042F2107000F02CFF08234FF40072394664 +:105E100020460096FFF79CFA002889D1384603F007 +:105E200061FA236BA06203F00F03022B72D103AB64 +:105E3000644A06212046FFF711FA002871D15F4914 +:105E4000039B1940B1FA81F149092046FFF7ACF9EB +:105E500002AB4FF4007210212046FFF7FFF9054610 +:105E600000287FF465AF554E029B33427FF460AF4C +:105E7000236B13F00E0F03F00F0273D0022A7FF48E +:105E800057AFE36A1978012900F09480022900F0E5 +:105E90009380002900F089804B4F2046FFF7AAF934 +:105EA00003AB3A4676E0114620462263FFF7B4F989 +:105EB00054E7013D7FF45AAF3AE7444D6426444A23 +:105EC0003E4F012B18BF154603AB00223721204659 +:105ED000FFF7C4F900287FF42BAF039B3B427FF40C +:105EE00027AF03AB2A4629212046FFF7A1F9002856 +:105EF0007FF41EAF039B002BFFF648AF013E3FF43B +:105F000017AF42F2107000F0ABFEDDE7284603F059 +:105F1000BDF986E77E227F212846E66B03F094F9DF +:105F200008B9002191E70023402231462046009322 +:105F30000623FFF70DFA0028F3D1B3895BBA9B075C +:105F4000EFD5244B40223146204600930623FFF72D +:105F5000FFF90028E5D1317C01F00F010F3918BF9E +:105F6000012172E7E36A1978F9B101297FF4E0AE03 +:105F70002046FFF73FF903ABA26B37212046FFF71E +:105F80006DF900287FF4D4AE039B33427FF4D0AE8A +:105F900003AB022206212046FFF760F900287FF4B8 +:105FA000C7AE039B33427FF4C3AE0523237128465B +:105FB00005B0F0BD084F70E7084F6EE708E0FFFD41 +:105FC0000080FFC00001B9030000B7030080FF504C +:105FD00000001080F1FFFF800001B7030002B7034B +:105FE00037B504460C4D01ABA26B0D212046FFF7DF +:105FF00035F978B9019B2B420BD1C3F34323042B12 +:1060000008D0053B022B04D84FF47A7000F028FE2C +:10601000E9E7012003B030BD08E0FFFD70B5302393 +:10602000054683F3118803790024022B03D184F3FE +:106030001188204670BD0423037184F31188022661 +:10604000FFF7CEFF04462846FFF7CEF82E71F0E7A3 +:10605000FFF730B8044B036001230371002343634F +:10606000C0E90A33704700BF7C9E000810B530239A +:10607000044683F31188C162FFF736F8022300203B +:10608000237180F3118810BD10B53023044683F3CB +:106090001188FFF753F800230122E362227183F392 +:1060A000118810BD026843681143016003B11847AD +:1060B000704700001430FFF721BD00004FF0FF33A0 +:1060C0001430FFF71BBD00003830FFF797BD00000C +:1060D0004FF0FF333830FFF791BD00001430FFF769 +:1060E000E7BC00004FF0FF311430FFF7E1BC0000C7 +:1060F0003830FFF741BD00004FF0FF323830FFF776 +:106100003BBD0000012914BF6FF013000020704751 +:10611000FFF7D2BA044B036000234360C0E90233A7 +:1061200001230374704700BFA09E000810B5302300 +:10613000044683F31188FFF72FFB0223002023740A +:1061400080F3118810BD000038B5C36904460D46C0 +:106150001BB904210844FFF7A5FF294604F11400E8 +:10616000FFF78AFC002806DA201D4FF40061BDE825 +:106170003840FFF797BF38BD02684368114301609C +:1061800003B118477047000013B5406B00F5805409 +:10619000D4F8A4381A681178042914D1017C022992 +:1061A00011D11979012312898B4013420BD101A916 +:1061B0004C3002F077FFD4F8A4480246019B2179C5 +:1061C000206800F0DFF902B010BD0000143002F0CA +:1061D000F9BE00004FF0FF33143002F0F3BE0000B0 +:1061E0004C3002F0CBBF00004FF0FF334C3002F0D8 +:1061F000C5BF0000143002F0C7BE00004FF0FF31F1 +:10620000143002F0C1BE00004C3002F097BF000015 +:106210004FF0FF324C3002F091BF00000020704779 +:1062200010B500F58054D4F8A4381A681178042900 +:1062300017D1017C022914D15979012352898B404D +:1062400013420ED1143002F059FE024648B1D4F880 +:10625000A4484FF4407361792068BDE8104000F015 +:106260007FB910BD406BFFF7DBBF00007047000037 +:106270007FB5124B012504260446036000230574F4 +:1062800000F1840243602946C0E902330C4B0290BE +:10629000143001934FF44073009602F00BFE094B4B +:1062A00004F69442294604F14C000294CDE90063BF +:1062B0004FF4407302F0D2FE04B070BDC89E0008D7 +:1062C00065620008896100080A68302383F3118839 +:1062D0000B790B3342F823004B79133342F8230038 +:1062E0008B7913B10B3342F8230000F58053C3F8C8 +:1062F000A41802230374002080F311887047000063 +:1063000038B5037F044613B190F85430ABB901257A +:10631000201D0221FFF730FF04F114006FF001018E +:10632000257700F0DDFC04F14C0084F854506FF048 +:106330000101BDE8384000F0D3BC38BD10B50121E3 +:1063400004460430FFF718FF0023237784F8543005 +:1063500010BD000038B504460025143002F0C2FD1F +:1063600004F14C00257702F091FE201D84F8545072 +:106370000121FFF701FF2046BDE83840FFF750BF7D +:1063800090F8803003F06003202B06D190F8812034 +:106390000023212A03D81F2A06D800207047222A6A +:1063A000FBD1C0E91D3303E0034A4267072282673D +:1063B000C3670120704700BFA822002037B500F551 +:1063C0008055D5F8A4381A68117804291AD1017CAF +:1063D000022917D11979012312898B40134211D157 +:1063E00000F14C04204602F011FF58B101A92046EB +:1063F00002F058FED5F8A4480246019B2179206896 +:1064000000F0C0F803B030BD01F10B03F0B550F857 +:10641000236085B004460D46FEB1302383F3118816 +:1064200004EB8507301D0821FFF7A6FEFB6806F187 +:106430004C005B691B681BB1019002F041FE0198A2 +:1064400003A902F02FFE024648B1039B29462046CD +:1064500000F098F8002383F3118805B0F0BDFB68C5 +:106460005A691268002AF5D01B8A013B1340F1D10A +:1064700004F18002EAE70000133138B550F82140FA +:10648000ECB1302383F3118804F58053D3F8A428AA +:106490001368527903EB8203DB689B695D6845B141 +:1064A00004216018FFF768FE294604F1140002F089 +:1064B0002FFD2046FFF7B4FE002383F3118838BD7B +:1064C0007047000001F050BD01234022002110B5AB +:1064D000044600F8303BFBF739FF0023C4E90133E1 +:1064E00010BD000010B53023044683F31188242228 +:1064F000416000210C30FBF729FF204601F056FDDA +:1065000002230020237080F3118810BD70B500EBCA +:106510008103054650690E461446DA6018B1102210 +:106520000021FBF713FFA06918B110220021FBF72F +:106530000DFF31462846BDE8704001F03DBE000029 +:1065400083682022002103F0011310B50446836004 +:106550001030FBF7FBFE2046BDE8104001F0B8BE4E +:10656000F0B4012500EB810447898D40E4683D4388 +:10657000A469458123600023A2606360F0BC01F040 +:10658000D5BE0000F0B4012500EB810407898D40E1 +:10659000E4683D436469058123600023A260636071 +:1065A000F0BC01F04BBF000070B50223002504468B +:1065B000242203702946C0F888500C3040F8045C4F +:1065C000FBF7C4FE204684F8705001F089FD636833 +:1065D0001B6823B129462046BDE87040184770BDAE +:1065E0000378052B10B504460AD080F88C300523BB +:1065F000037043681B680BB1042198470023A36014 +:1066000010BD00000178052906D190F88C20436860 +:1066100002701B6803B118477047000070B590F80E +:106620007030044613B1002380F8703004F180020A +:10663000204601F071FE63689B68B3B994F880301E +:1066400013F0600535D00021204602F063F90021E7 +:10665000204602F053F963681B6813B106212046F7 +:106660009847062384F8703070BD2046984700286C +:10667000E4D0B4F88630A26F9A4288BFA36794F939 +:106680008030A56F002B4FF0300380F20381002D86 +:1066900000F0F280092284F8702083F31188002131 +:1066A0002046D4E91D23FFF76DFF002383F31188F3 +:1066B000DAE794F8812003F07F0343EA022340F2F3 +:1066C0000232934200F0C58021D8B3F5807F48D0D4 +:1066D0000DD8012B3FD0022B00F09380002BB2D1BC +:1066E00004F1880262670222A267E367C1E7B3F59B +:1066F000817F00F09B80B3F5407FA4D194F8823075 +:10670000012BA0D1B4F8883043F0020332E0B3F596 +:10671000006F4DD017D8B3F5A06F31D0A3F5C0638B +:10672000012B90D86368204694F882205E6894F824 +:106730008310B4F88430B047002884D0436863677E +:106740000368A3671AE0B3F5106F36D040F6024233 +:1067500093427FF478AF5C4B63670223A367002307 +:10676000C3E794F88230012B7FF46DAFB4F8883022 +:1067700023F00203A4F88830C4E91D55E56778E7E3 +:10678000B4F88030B3F5A06F0ED194F88230204673 +:1067900084F88A3001F002FD63681B6813B101219F +:1067A00020469847032323700023C4E91D339CE748 +:1067B00004F18B0363670123C3E72378042B10D113 +:1067C000302383F311882046FFF7BAFE85F3118842 +:1067D0000321636884F88B5021701B680BB120463D +:1067E000984794F88230002BDED084F88B30042355 +:1067F000237063681B68002BD6D00221204698477F +:10680000D2E794F8843020461D0603F00F010AD524 +:1068100001F074FD012804D002287FF414AF2B4B43 +:106820009AE72B4B98E701F05BFDF3E794F8823091 +:10683000002B7FF408AF94F8843013F00F01B3D02D +:106840001A06204602D502F07DF8ADE702F06EF898 +:10685000AAE794F88230002B7FF4F5AE94F88430E8 +:1068600013F00F01A0D01B06204602D502F052F80B +:106870009AE702F043F897E7142284F8702083F334 +:1068800011882B462A4629462046FFF769FE85F3E4 +:106890001188E9E65DB1152284F8702083F3118830 +:1068A00000212046D4E91D23FFF75AFEFDE60B2206 +:1068B00084F8702083F311882B462A462946204607 +:1068C000FFF760FEE3E700BFF89E0008F09E0008B7 +:1068D000F49E000838B590F870300446002B3ED086 +:1068E000063BDAB20F2A34D80F2B32D8DFE803F098 +:1068F00037313108223231313131313131313737AD +:10690000856FB0F886309D4214D2C3681B8AB5FBF0 +:10691000F3F203FB12556DB9302383F311882B4634 +:106920002A462946FFF72EFE85F311880A2384F8AC +:1069300070300EE0142384F87030302383F3118814 +:10694000002320461A461946FFF70AFE002383F368 +:10695000118838BDC36F03B198470023E7E70021D2 +:10696000204601F0D7FF0021204601F0C7FF6368F1 +:106970001B6813B10621204698470623D7E700007D +:1069800010B590F870300446142B29D017D8062B78 +:1069900005D001D81BB110BD093B022BFBD800214B +:1069A000204601F0B7FF0021204601F0A7FF6368F1 +:1069B0001B6813B1062120469847062319E0152BC2 +:1069C000E9D10B2380F87030302383F31188002342 +:1069D0001A461946FFF7D6FD002383F31188DAE73C +:1069E000C3689B695B68002BD5D1C36F03B198471F +:1069F000002384F87030CEE70023826880F82430CA +:106A000083691B6899689142FBD25A6803604260AF +:106A100010605860704700000023826880F82430BE +:106A200083691B6899689142FBD85A680360426089 +:106A3000106058607047000008B50846302383F3A3 +:106A4000118891F82430032B05D0042B0DD02BB9DD +:106A500083F3118808BD8B6A00221A604FF0FF3360 +:106A60008362FFF7C9FF0023F2E7D1E90032136028 +:106A70005A60F3E7034610B51B68984203D09C6840 +:106A80008A689442F8D25A680B604A601160596073 +:106A900010BD0000FFF7B0BF064BD96881F8240095 +:106AA0001868026853601A600122D86080F82420B8 +:106AB000F9F7A8BCC84600200C4B30B5DD684B1C6C +:106AC00087B004460FD02B46094A684600F09CF96F +:106AD0002046FFF7E1FF009B13B1684600F09EF9E6 +:106AE000A86A07B030BDFFF7D7FFF9E7C846002016 +:106AF000396A0008044B1A68DB6890689B68984202 +:106B000094BF002001207047C8460020094B10B5F3 +:106B10001C68D868226853601A600122DC6084F81F +:106B20002420FFF779FF01462046BDE81040F9F721 +:106B300069BC00BFC8460020044B1A68DB68926835 +:106B40009B689A4201D9FFF7E1BF7047C846002011 +:106B500038B50123084C00252370656002F0F0FB76 +:106B600002F016FC0549064802F0ECFC02232370F3 +:106B700085F3118838BD00BF70490020009F0008D0 +:106B8000C846002000F080B9034A516853685B1A78 +:106B90009842FBD8704700BF001000E08B604B6349 +:106BA0000023CA6100F128020B6302230A618B846F +:106BB0000123886181F8263001F11003C26A4A611D +:106BC0001360C36201F12C030846CB6270470000DA +:106BD000D0E90131026841F8183CA1F19C03383931 +:106BE000CB60036941F8243C436941F8203C034BE6 +:106BF00041F8043CC3680248FFF7D0BF1D040008F9 +:106C0000C846002008B5FFF7E3FFBDE80840FFF7DE +:106C100041BF000038B50E4BDC6804F12C05A062C2 +:106C2000E06AA8420FD194F826303BB994F8253099 +:106C30009B0702BFD4E9043213605A600F20BDE8FD +:106C40003840FFF729BF0368E362FFF723FFE7E758 +:106C5000C8460020302383F31188FFF7DBBF000014 +:106C600008B50146302383F311880820FFF724FF7D +:106C7000002383F3118808BD054BDB6821B1036055 +:106C800098620320FFF718BF4FF0FF30704700BF36 +:106C9000C846002003682BB10022026018469962A2 +:106CA000FFF7F8BE70470000064BDB6839B1426859 +:106CB00018605A60136043600420FFF7FDBE4FF078 +:106CC000FF307047C84600200368984206D01A6813 +:106CD0000260506018469962FFF7DCBE7047000002 +:106CE00038B504460D462068844200D138BD03689B +:106CF00023605C608562FFF7CDFEF4E7036810B5A2 +:106D00009C68A2420CD85C688A600B604C60216071 +:106D1000596099688A1A9A604FF0FF33836010BDFA +:106D2000121B1B68ECE700000A2938BF0A2170B566 +:106D300004460D460A26601902F0FCFA02F0E4FA55 +:106D4000041BA54203D8751C04462E46F3E70A2E01 +:106D500004D90120BDE8704002F0BCBC70BD000049 +:106D6000F8B5144B0D460A2A4FF00A07D96103F112 +:106D70001001826038BF0A2241601969144601601F +:106D800048601861A81802F0C5FA02F0BDFA431B6A +:106D90000646A34206D37C1C28192746354602F036 +:106DA000C9FAF2E70A2F04D90120BDE8F84002F041 +:106DB00091BCF8BDC8460020F8B506460D4602F065 +:106DC000A3FA0F4A134653F8107F9F4206D12A4672 +:106DD00001463046BDE8F840FFF7C2BFD169BB6845 +:106DE000441A2C1928BF2C46A34202D92946FFF782 +:106DF0009BFF224631460348BDE8F840FFF77EBFBF +:106E0000C8460020D8460020C0E90323002310B460 +:106E10005DF8044B4361FFF7CFBF000010B5194C7C +:106E2000236998420DD08168D0E9003213605A601E +:106E30009A680A449A60002303604FF0FF33A3610D +:106E400010BD0268234643F8102F536000220260F1 +:106E500022699A4203D1BDE8104002F065BA9368F6 +:106E600081680B44936002F04FFA2269E1699268ED +:106E7000441AA242E4D91144BDE81040091AFFF7B0 +:106E800053BF00BFC84600202DE9F047DFF8BC80A3 +:106E900008F110072C4ED8F8105002F035FAD8F847 +:106EA0001C40AA68031B9A423ED814444FF00009C4 +:106EB000D5E90032C8F81C4013605A60C5F800904C +:106EC000D8F81030B34201D102F02EFA89F31188BC +:106ED000D5E9033128469847302383F311886B693D +:106EE000002BD8D002F010FA6A69A0EB04098246A0 +:106EF0004A450DD2022002F0EDFB0022D8F81030F6 +:106F0000B34208D151462846BDE8F047FFF728BFF5 +:106F1000121A2244F2E712EB09092946384638BF13 +:106F20004A46FFF7EBFEB5E7D8F81030B34208D079 +:106F30001444C8F81C00211AA960BDE8F047FFF707 +:106F4000F3BEBDE8F08700BFD8460020C846002049 +:106F500038B502F0D9F9054AD2E90845031B1819DA +:106F600045F10001C2E9080138BD00BFC846002054 +:106F700010B560B9074804790368053C9B6818BFE1 +:106F80000124984708B144F00404204610BD0124B0 +:106F9000FBE700BF2C370020FFF7EABF2DE9F047E1 +:106FA000884617469A460446B0B90D4E3579052DE8 +:106FB00005D003240DE0013D15F0FF050ED0326829 +:106FC000534639463046D2F814904246C847002806 +:106FD000F1D12046BDE8F0870424FAE70124F8E760 +:106FE0002C3700202DE9F047884617469A4604467C +:106FF000B0B90D4E3579052D05D003240DE0013DC6 +:1070000015F0FF050ED03268534639463046D2F8A7 +:1070100018904246C8470028F1D12046BDE8F087C5 +:107020000424FAE70124F8E72C37002037B50C4692 +:10703000154670B951B101290BD10748694603685B +:107040001B6A984710B9019B04462B60204603B089 +:1070500030BD0424FAE700BF2C3700200020704721 +:10706000FEE70000704700004FF0FF30704700005F +:107070004B6843608B688360CB68C3600B69436176 +:107080004B6903628B6943620B68036070470000C1 +:1070900008B53C4B40F2FF713B48D3F888200A43C7 +:1070A000C3F88820D3F8882022F4FF6222F0070278 +:1070B000C3F88820D3F88820D3F8E0200A43C3F827 +:1070C000E020D3F808210A43C3F808212F4AD3F857 +:1070D00008311146FFF7CCFF00F5806002F11C017A +:1070E000FFF7C6FF00F5806002F13801FFF7C0FF2F +:1070F00000F5806002F15401FFF7BAFF00F58060EF +:1071000002F17001FFF7B4FF00F5806002F18C011D +:10711000FFF7AEFF00F5806002F1A801FFF7A8FFBE +:1071200000F5806002F1C401FFF7A2FF00F5806066 +:1071300002F1E001FFF79CFF00F5806002F1FC0125 +:10714000FFF796FF02F58C7100F58060FFF790FF66 +:1071500001F090FC0E4BD3F8902242F00102C3F8EC +:107160009022D3F8942242F00102C3F8942205221F +:10717000C3F898204FF06052C3F89C20054AC3F82A +:10718000A02008BD0044025800000258149F0008C7 +:1071900000ED00E01F00080308B501F077FEFFF7DF +:1071A000D7FC104BD3F8DC2042F04002C3F8DC20BF +:1071B000D3F8042122F04002C3F80421D3F80431AB +:1071C000094B1A6842F008021A601A6842F0040279 +:1071D0001A6000F07DFD00F035FBBDE8084000F0CE +:1071E000B5B800BF0044025800180248012070479B +:1071F000002070477047000002290CD0032904D0FA +:107200000129074818BF00207047032A05D8054800 +:1072100000EBC2007047044870470020704700BF71 +:1072200014A10008B8220020C8A0000870B59AB0C8 +:1072300005460846144601A900F0C2F801A8FBF76C +:107240007DF8431C0022C6B25B001046C5E900343D +:1072500023700323023404F8013C01ABD1B20234A1 +:107260008E4201D81AB070BD13F8011B013204F828 +:10727000010C04F8021CF1E708B5302383F31188F0 +:107280000348FFF79BF8002383F3118808BD00BF74 +:107290007849002090F8803003F01F02012A07D1BE +:1072A00090F881200B2A03D10023C0E91D3315E09B +:1072B00003F06003202B08D1B0F884302BB990F88C +:1072C0008120212A03D81F2A04D8FFF759B8222A7F +:1072D000EBD0FAE7034A426707228267C3670120BF +:1072E000704700BFAF22002007B5052917D8DFE897 +:1072F00001F0191603191920302383F31188104A5D +:1073000001210190FFF702F9019802210D4AFFF7D0 +:10731000FDF80D48FFF71EF8002383F3118803B032 +:107320005DF804FB302383F311880748FEF7E8FF7C +:10733000F2E7302383F311880348FEF7FFFFEBE702 +:1073400068A000088CA000087849002038B50C4DD2 +:107350000C4C2A460C4904F10800FFF767FF05F1C1 +:10736000CA0204F110000949FFF760FF05F5CA726F +:1073700004F118000649BDE83840FFF757BF00BFC9 +:1073800050620020B822002048A0000852A0000847 +:107390005DA0000870B5044608460D46FAF7CEFF1A +:1073A000C6B22046013403780BB9184670BD324688 +:1073B0002946FAF7AFFF0028F3D10120F6E70000D5 +:1073C0002DE9F84F05460C46FAF7B8FF2C49C6B22E +:1073D0002846FFF7DFFF08B10236F6B229492846F2 +:1073E000FFF7D8FF08B11036F6B2632E0DD8DFF8DC +:1073F0009080DFF89090244FDFF894A0DFF894B0ED +:107400002E7846B92670BDE8F88F29462046BDE89B +:10741000F84FF9F7FBBB252E2ED10722414628460F +:10742000FAF778FF70B9DBF800300735093444F813 +:10743000093CDBF8043044F8053C9BF8083004F8BC +:10744000013CDDE7082249462846FAF763FF98B970 +:10745000A21C0E4B197802320909C95D02F8041CFE +:1074600013F8011B01F00F015345C95D02F8031C1D +:10747000F0D118340835C3E7013504F8016BBFE7D4 +:1074800034A100085DA0000846A1000800E8F11F33 +:107490000CE8F11F3CA10008BFF34F8F044B1A69A1 +:1074A0005107FCD1D3F810215207F8D1704700BF23 +:1074B0000020005208B50D4B1B78ABB9FFF7ECFF6D +:1074C0000B4BDA68D10704D50A4A5A6002F18832B8 +:1074D0005A60D3F80C21D20706D5064AC3F8042116 +:1074E00002F18832C3F8042108BD00BFAE64002059 +:1074F000002000522301674508B5114B1B78F3B9F2 +:10750000104B1A69510703D5DA6842F04002DA607D +:10751000D3F81021520705D5D3F80C2142F04002D0 +:10752000C3F80C21FFF7B8FF064BDA6842F00102FE +:10753000DA60D3F80C2142F00102C3F80C2108BD37 +:10754000AE640020002000520F289ABF00F5806032 +:1075500040040020704700004FF4003070470000E6 +:10756000102070470F2808B50BD8FFF7EDFF00F586 +:1075700000330268013204D104308342F9D1012082 +:1075800008BD0020FCE700000F2838B505463FD8AD +:10759000FFF782FF1F4CFFF78DFF4FF0FF330728E7 +:1075A0006361C4F814311DD82361FFF775FF03022E +:1075B00043F02403E360E36843F08003E36023695E +:1075C0005A07FCD42846FFF767FFFFF7BDFF4FF4CB +:1075D000003100F0B7FA2846FFF78EFFBDE83840CB +:1075E000FFF7C0BFC4F81031FFF756FFA0F1080342 +:1075F0001B0243F02403C4F80C31D4F80C3143F0DF +:107600008003C4F80C31D4F810315B07FBD4D9E700 +:10761000002038BD002000522DE9F84F05460C46E9 +:10762000104645EA0203DE0602D00020BDE8F88FCE +:1076300020F01F00DFF8BCB0DFF8BCA0FFF73AFF76 +:1076400004EB0008444503D10120FFF755FFEDE7A7 +:10765000202229462046F9F779F810B92035203440 +:10766000F0E72B4605F120021F68791CDDD10433B9 +:107670009A42F9D105F178431B481C4EB3F5801F9F +:107680001B4B38BF184603F1F80332BFD946D14629 +:107690001E46FFF701FF0760A5EB040C336804F1F9 +:1076A0001C0143F002033360231FD9F8007017F068 +:1076B0000507FAD153F8042F8B424CF80320F4D17C +:1076C000BFF34F8FFFF7E8FE4FF0FF332022214634 +:1076D00003602846336823F002033360F9F736F875 +:1076E0000028BBD03846B0E7142100520C200052CD +:1076F00014200052102000521021005210B5084CE6 +:10770000237828B11BB9FFF7D5FE0123237010BDE4 +:10771000002BFCD02070BDE81040FFF7EDBE00BF8D +:10772000AE6400202DE9F04F0D4685B0814658B17A +:1077300011F00D0614BF2022082211F00803019356 +:1077400004D0431E034269D0002435E0002E37D018 +:1077500009F11F0121F01F094FF00108314F05F019 +:107760000403DFF8CCA005EA080BBBF1000F32D010 +:107770007869C0072FD408F101080C37B8F1060F5B +:10778000F3D19EB9284D4946A819019201F022FE75 +:107790000446002839D12036019AA02EF3D149465B +:1077A00001F018FE044600282FD1019A49461F48CF +:1077B00001F010FE044660BB204605B0BDE8F08F26 +:1077C0000029C9D101462846029201F003FE044671 +:1077D000D8B9029AC0E713B178694107CBD5AC0795 +:1077E00002D578698007C6D5019911B1786901077A +:1077F000C1D549460AEB4810CDE9022301F0EAFD64 +:107800000446DDE902230028B5D04A46002120467F +:1078100001E04A460021FAF799FDCDE70246002E25 +:1078200096D199E758A10008F0640020B0640020C8 +:10783000D06400200021FFF775BF00000121FFF791 +:1078400071BF000070B5144D0124144E40F2FF3298 +:1078500000210120FAF77AFD06EB441001342A6971 +:1078600055F80C1F01F0A2FD062CF5D137254FF479 +:10787000C0542046FFF7E2FF014628B122460848DF +:10788000BDE8704001F092BDC4EBC404013D4FEA75 +:10789000D404EED170BD00BF58A10008D064002010 +:1078A000B06400200421FFF73DBF00004843FFF70C +:1078B000C1BF000008B101F0FFBD70470846FFF7E7 +:1078C000B9BF0000B0F5805F10B5044607D8FFF7D8 +:1078D000E9FF28B92046BDE81040FFF7ABBF002004 +:1078E00010BD0000FFF7E6BF70B5AAB140EA010382 +:1078F00013F01F030FD1094C0144A5686D0706D58D +:107900002568A84203D366683544A94204D90333E5 +:107910000C34122BF1D10022104670BD58A1000882 +:1079200008B501F0DFFE034AD2E90032C01842EB8D +:10793000010108BD90650020434BD3E900232DE9E8 +:10794000F34113437CD0FFF7EBFF404A00230027AD +:10795000F8F772FD06460D463D4A0023F8F76CFD28 +:107960000023144630462946394AF8F765FD4FF49E +:1079700061613C23ADF80170B4FBF1F5B4FBF3F6A3 +:1079800001FB154103FB16464624B1FBF3F1314BD5 +:10799000F6B28DF8004098423CD84FF0640C4FF49A +:1079A000C87EA30704F26C7225D1B2FBFCF30CFB7A +:1079B000132313BBB2FBFEF30EFB1322B2FA82F3C6 +:1079C0005B0903F26D18621C8045D2B217D90FB162 +:1079D0008DF800400022204C4FF00C0C17460CFB99 +:1079E0000343D4B2013213F804C084450CD8A0EB91 +:1079F0000C000127F5E70023E3E70123E1E7A0EB13 +:107A0000080014460127CCE70FB18DF80140431C54 +:107A10008DF802309DF80100431C9DF8000050389D +:107A2000400640EA43509DF8023040EA034040EAF5 +:107A3000560040EAC52040EA411002B0BDE8F0819E +:107A40004FF40410F9E700BF9065002040420F009A +:107A50008051010090230B00A0A100080244074BB5 +:107A6000D2B210B5904200D110BD441C00B253F800 +:107A7000200041F8040BE0B2F4E700BF504000588A +:107A80000E4B30B51C6F240405D41C6F1C671C6F93 +:107A900044F400441C670A4C02442368D2B243F405 +:107AA00080732360074B904200D130BD441C51F8D5 +:107AB000045B00B243F82050E0B2F4E700440258FF +:107AC000004802585040005807B5012201A9002083 +:107AD000FFF7C4FF019803B05DF804FB13B504463B +:107AE000FFF7F2FFA04205D0012201A90020019476 +:107AF000FFF7C6FF02B010BD10B56424013C4FF47F +:107B00007A70FFF7ADF814F0FF04F7D10C4B4FF487 +:107B1000801214249A61A3F580634FF08052A3F57C +:107B20004063C3F8182C4FF400529A61013C4FF4A3 +:107B30007A70FFF795F814F0FF04F7D110BD00BF7D +:107B4000001802580144BFF34F8F064B884204D3FC +:107B5000BFF34F8FBFF36F8F7047C3F85C022030C5 +:107B6000F4E700BF00ED00E00144BFF34F8F064B88 +:107B7000884204D3BFF34F8FBFF36F8F7047C3F8B2 +:107B800070022030F4E700BF00ED00E070B505465C +:107B900016460C4601201021FFF788FE2860467328 +:107BA0003CB1204636B1FFF77DFE2B68186000B16E +:107BB0009C6070BDFFF742FEF7E70000F8B50F4686 +:107BC0001546044648B905F11F010126386821F021 +:107BD0001F01FFF7B7FF3046F8BD427B29463868E2 +:107BE000FFF782FE06460028EDD13B686360A3687C +:107BF000AB4210D213B12068FFF75CFE637B2846CE +:107C00002BB1FFF74FFE206020B9A060E3E7FFF73C +:107C100015FEF8E7A560206805F11F01012621F097 +:107C20001F013860FFF78EFF2673D4E710B50446B6 +:107C300040B10068884205D1606808B1FAF760FB7E +:107C40000023237310BD0000F8B50F461446054607 +:107C500048B904F11F010126386821F01F01FFF720 +:107C600083FF3046F8BD427B21463868FFF73CFE73 +:107C700006460028EDD1AB68A34210D213B12868A4 +:107C8000FFF718FE6B7B20462BB1FFF70BFE286039 +:107C900020B9A860E5E7FFF7D1FDF8E7AC603968E7 +:107CA00019B122462868FAF72BFB286804F11F0156 +:107CB000012621F01F013860FFF756FF2E73D0E731 +:107CC00020B103688B4204BF002303737047000098 +:107CD000034B1A681AB9034AD2F8D0241A607047C5 +:107CE000986500200040025808B5FFF7F1FF024BED +:107CF0001868C0F3806008BD98650020EFF3098321 +:107D0000054968334A6B22F001024A6383F309880C +:107D1000002383F31188704700EF00E0302080F3E8 +:107D2000118862B60D4B0E4AD96821F4E06109044E +:107D3000090C0A430B49DA60D3F8FC2042F0807248 +:107D4000C3F8FC20084AC2F8B01F116841F00101D5 +:107D500011602022DA7783F82200704700ED00E0FE +:107D60000003FA0555CEACC5001000E0302310B575 +:107D700083F311880E4B5B6813F4006314D0F1EEAB +:107D8000103AEFF309844FF08073683CE361094BCC +:107D9000DB6B236684F30988FEF7ACFE10B1064B5B +:107DA000A36110BD054BFBE783F31188F9E700BF22 +:107DB00000ED00E000EF00E02F04000832040008AE +:107DC00070B5BFF34F8FBFF36F8F1A4A0021C2F80F +:107DD0005012BFF34F8FBFF36F8F536943F40033DB +:107DE0005361BFF34F8FBFF36F8FC2F88410BFF39F +:107DF0004F8FD2F8803043F6E074C3F3C900C3F369 +:107E00004E335B0103EA0406014646EA81750139F7 +:107E1000C2F86052F9D2203B13F1200FF2D1BFF328 +:107E20004F8F536943F480335361BFF34F8FBFF3D8 +:107E30006F8F70BD00ED00E0FEE70000214B22488F +:107E4000224A70B5904237D3214BC11EDA1C121A58 +:107E500022F003028B4238BF00220021FAF776FAA3 +:107E60001C4A0023C2F88430BFF34F8FD2F8803011 +:107E700043F6E074C3F3C900C3F34E335B0103EA76 +:107E80000406014646EA81750139C2F86C52F9D2FE +:107E9000203B13F1200FF2D1BFF34F8FBFF36F8F51 +:107EA000BFF34F8FBFF36F8F0023C2F85032BFF381 +:107EB0004F8FBFF36F8F70BD53F8041B40F8041B46 +:107EC000C0E700BF08A3000898670020986700205B +:107ED0009867002000ED00E0074BD3F8D81021EAA6 +:107EE0000001C3F8D810D3F8002122EA0002C3F839 +:107EF0000021D3F8003170470044025870B5D0E932 +:107F0000244300224FF0FF359E6804EB42135101D9 +:107F1000D3F80009002805DAD3F8000940F08040C2 +:107F2000C3F80009D3F8000B002805DAD3F8000BDA +:107F300040F08040C3F8000B013263189642C3F84A +:107F40000859C3F8085BE0D24FF00113C4F81C389D +:107F500070BD0000890141F02001016103699B06A9 +:107F6000FCD41220FEF710BE10B50A4C2046FEF7D6 +:107F7000ABFA094BC4F89030084BC4F89430084C65 +:107F80002046FEF7A1FA074BC4F89030064BC4F820 +:107F9000943010BD9C65002000000840DCA1000862 +:107FA0003866002000000440E8A1000870B503789E +:107FB0000546012B5CD1434BD0F89040984258D1F4 +:107FC000414B0E216520D3F8D82042F00062C3F85F +:107FD000D820D3F8002142F00062C3F80021D3F882 +:107FE0000021D3F8802042F00062C3F88020D3F84B +:107FF000802022F00062C3F88020D3F88030FDF7A3 +:10800000A7FC324BE360324BC4F800380023D5F8AC +:108010009060C4F8003EC02323604FF40413A363B0 +:108020003369002BFCDA01230C203361FEF7ACFD31 +:108030003369DB07FCD41220FEF7A6FD3369002B61 +:10804000FCDA00262846A660FFF758FF6B68C4F8E4 +:108050001068DB68C4F81468C4F81C6883BB1D4B47 +:10806000A3614FF0FF336361A36843F00103A36092 +:1080700070BD194B9842C9D1134B4FF08060D3F8B3 +:10808000D82042F00072C3F8D820D3F8002142F083 +:108090000072C3F80021D3F80021D3F8802042F009 +:1080A0000072C3F88020D3F8802022F00072C3F859 +:1080B0008020D3F88030FFF70FFF0E214D209EE780 +:1080C000064BCDE79C650020004402584014004058 +:1080D00003002002003C30C038660020083C30C05D +:1080E000F8B5D0F89040054600214FF000662046D4 +:1080F000FFF730FFD5F8941000234FF001128F687E +:108100004FF0FF30C4F83438C4F81C2804EB431295 +:1081100001339F42C2F80069C2F8006BC2F8080937 +:10812000C2F8080BF2D20B68D5F89020C5F8983049 +:10813000636210231361166916F01006FBD112203A +:10814000FEF722FDD4F8003823F4FE63C4F80038AB +:10815000A36943F4402343F01003A3610923C4F847 +:108160001038C4F814380B4BEB604FF0C043C4F820 +:10817000103B094BC4F8003BC4F81069C4F800393F +:10818000D5F8983003F1100243F48013C5F8982015 +:10819000A362F8BDB8A1000840800010D0F890207C +:1081A00090F88A10D2F8003823F4FE6343EA0113F2 +:1081B000C2F80038704700002DE9F84300EB810356 +:1081C000D0F890500C468046DA680FFA81F94801E1 +:1081D000166806F00306731E022B05EB41134FF0E1 +:1081E000000194BFB604384EC3F8101B4FF00101D4 +:1081F00004F1100398BF06F1805601FA03F3916968 +:1082000098BF06F5004600293AD0578A04F1580174 +:10821000374349016F50D5F81C180B430021C5F8AE +:108220001C382B180127C3F81019A7405369611E89 +:108230009BB3138A928B9B08012A88BF5343D8F8BB +:108240009820981842EA034301F140022146C8F8F9 +:108250009800284605EB82025360FFF77BFE08EB8F +:108260008900C3681B8A43EA845348341E4364016F +:108270002E51D5F81C381F43C5F81C78BDE8F8838B +:1082800005EB4917D7F8001B21F40041C7F8001B84 +:10829000D5F81C1821EA0303C0E704F13F030B4A99 +:1082A0002846214605EB83035A60FFF753FE05EB92 +:1082B0004910D0F8003923F40043C0F80039D5F84C +:1082C0001C3823EA0707D7E70080001000040002EB +:1082D000D0F894201268C0F89820FFF70FBE000075 +:1082E0005831D0F8903049015B5813F4004004D065 +:1082F00013F4001F0CBF0220012070474831D0F852 +:10830000903049015B5813F4004004D013F4001F6F +:108310000CBF02200120704700EB8101CB68196A75 +:108320000B6813604B6853607047000000EB8103DB +:1083300030B5DD68AA691368D36019B9402B84BFD2 +:10834000402313606B8A1468D0F890201C4402EB21 +:108350004110013C09B2B4FBF3F46343033323F04F +:10836000030343EAC44343F0C043C0F8103B2B6807 +:1083700003F00303012B0ED1D2F8083802EB4110B1 +:1083800013F4807FD0F8003B14BF43F0805343F0D8 +:108390000053C0F8003B02EB4112D2F8003B43F01F +:1083A0000443C2F8003B30BD2DE9F041D0F89060A5 +:1083B00005460C4606EB4113D3F8087B3A07C3F891 +:1083C000087B08D5D6F814381B0704D500EB8103C9 +:1083D000DB685B689847FA071FD5D6F81438DB07C7 +:1083E0001BD505EB8403D968CCB98B69488A5A68D8 +:1083F000B2FBF0F600FB16228AB91868DA689042E0 +:108400000DD2121AC3E90024302383F311882146C8 +:108410002846FFF78BFF84F31188BDE8F081012324 +:1084200003FA04F26B8923EA02036B81CB68002B09 +:10843000F3D021462846BDE8F041184700EB810300 +:108440004A0170B5DD68D0F890306C692668E66046 +:1084500056BB1A444FF40020C2F810092A6802F0F3 +:108460000302012A0AB20ED1D3F8080803EB421422 +:1084700010F4807FD4F8000914BF40F0805040F021 +:108480000050C4F8000903EB4212D2F8000940F092 +:108490000440C2F800090122D3F8340802FA01F1BD +:1084A0000143C3F8341870BD19B9402E84BF402071 +:1084B000206020681A442E8A8419013CB4FBF6F42B +:1084C00040EAC44040F00050C6E700002DE9F84300 +:1084D000D0F8906005460C464F0106EB4113D3F8E7 +:1084E000088918F0010FC3F808891CD0D6F8103895 +:1084F000DB0718D500EB8103D3F80CC0DCF814308F +:10850000D3F800E0DA68964530D2A2EB0E024FF0C5 +:1085100000091A60C3F80490302383F31188FFF731 +:108520008DFF89F3118818F0800F1DD0D6F83438EC +:108530000126A640334217D005EB84030134D5F859 +:108540009050D3F80CC0E4B22F44DCF8142005EBB3 +:108550000434D2F800E05168714514D3D5F83438AA +:1085600023EA0606C5F83468BDE8F883012303FA58 +:1085700001F2038923EA02030381DCF80830002BAF +:10858000D1D09847CFE7AEEB0103BCF8100083428F +:1085900028BF0346D7F8180980B2B3EB800FE3D8A1 +:1085A0009068A0F1040959F8048FC4F80080A0EB8A +:1085B00009089844B8F1040FF5D818440B449060AA +:1085C0005360C8E72DE9F84FD0F8905004466E6923 +:1085D000AB691E4016F480586E6103D0BDE8F84FB9 +:1085E000FDF7E2BF002E12DAD5F8003E9B0705D05A +:1085F000D5F8003E23F00303C5F8003ED5F8043853 +:10860000204623F00103C5F80438FDF7FBFF3705CA +:1086100005D52046FFF772FC2046FDF7E1FFB004C8 +:108620000CD5D5F8083813F0060FEB6823F4705317 +:108630000CBF43F4105343F4A053EB6031071BD538 +:108640006368DB681BB9AB6923F00803AB6123786F +:10865000052B0CD1D5F8003E9A0705D0D5F8003E81 +:1086600023F00303C5F8003E2046FDF7CBFF636807 +:10867000DB680BB120469847F30200F1BA80B702DD +:1086800026D5D4F8909000274FF0010A09EB471245 +:10869000D2F8003B03F44023B3F5802F11D1D2F878 +:1086A000003B002B0DDA62890AFA07F322EA030382 +:1086B000638104EB8703DB68DB6813B1394620462E +:1086C00098470137D4F89430FFB29B689F42DDD9B8 +:1086D000F00619D5D4F89000026AC2F30A1702F026 +:1086E0000F0302F4F012B2F5802F00F0CA80B2F549 +:1086F000402F09D104EB8303002200F58050DB6892 +:108700001B6A974240F0B0803003D5F8185835D531 +:10871000E90303D500212046FFF746FEAA0303D54F +:1087200001212046FFF740FE6B0303D502212046BE +:10873000FFF73AFE2F0303D503212046FFF734FE4F +:10874000E80203D504212046FFF72EFEA90203D537 +:1087500005212046FFF728FE6A0203D506212046A0 +:10876000FFF722FE2B0203D507212046FFF71CFE50 +:10877000EF0103D508212046FFF716FE700340F1F4 +:10878000A780E90703D500212046FFF79FFEAA072F +:1087900003D501212046FFF799FE6B0703D502217F +:1087A0002046FFF793FE2F0703D503212046FFF74E +:1087B0008DFEEE0603D504212046FFF787FEA806AE +:1087C00003D505212046FFF781FE690603D5062162 +:1087D0002046FFF77BFE2A0603D507212046FFF738 +:1087E00075FEEB0574D520460821BDE8F84FFFF76C +:1087F0006DBED4F890904FF0000B4FF0010AD4F802 +:1088000094305FFA8BF79B689F423FF638AF09EBD5 +:108810004713D3F8002902F44022B2F5802F20D16B +:10882000D3F80029002A1CDAD3F8002942F090423C +:10883000C3F80029D3F80029002AFBDB3946D4F815 +:108840009000FFF787FB22890AFA07F322EA030365 +:10885000238104EB8703DB689B6813B1394620460C +:1088600098470BF1010BCAE7910701D1D0F80080BE +:10887000072A02F101029CBF03F8018B4FEA182876 +:108880003FE704EB830300F58050DA68D2F818C0A4 +:10889000DCF80820DCE9001CA1EB0C0C00218F4265 +:1088A00008D1DB689B699A683A449A605A683A44EE +:1088B0005A6029E711F0030F01D1D0F800808C45F0 +:1088C00001F1010184BF02F8018B4FEA1828E6E7A5 +:1088D000BDE8F88F08B50348FFF774FEBDE808400F +:1088E000FFF744BA9C65002008B50348FFF76AFE0D +:1088F000BDE80840FFF73ABA38660020D0F890305B +:1089000003EB4111D1F8003B43F40013C1F8003BE5 +:1089100070470000D0F8903003EB4111D1F80039D6 +:1089200043F40013C1F8003970470000D0F89030CC +:1089300003EB4111D1F8003B23F40013C1F8003BD5 +:1089400070470000D0F8903003EB4111D1F80039A6 +:1089500023F40013C1F8003970470000064BD3F828 +:10896000DC200243C3F8DC20D3F804211043C3F811 +:108970000401D3F8043170470044025808B53C4B59 +:108980004FF0FF31D3F8802062F00042C3F880201E +:10899000D3F8802002F00042C3F88020D3F8802072 +:1089A000D3F88420C3F88410D3F884200022C3F8BD +:1089B0008420D3F88400D86F40F0FF4040F4FF00DB +:1089C00040F4DF4040F07F00D867D86F20F0FF40D0 +:1089D00020F4FF0020F4DF4020F07F00D867D86F3C +:1089E000D3F888006FEA40506FEA5050C3F888000F +:1089F000D3F88800C0F30A00C3F88800D3F88800D1 +:108A0000D3F89000C3F89010D3F89000C3F89020EA +:108A1000D3F89000D3F89400C3F89410D3F89400DE +:108A2000C3F89420D3F89400D3F89800C3F89810B2 +:108A3000D3F89800C3F89820D3F89800D3F88C00A6 +:108A4000C3F88C10D3F88C00C3F88C20D3F88C00BA +:108A5000D3F89C00C3F89C10D3F89C10C3F89C205A +:108A6000D3F89C30FCF722FABDE8084000F0D6B9F4 +:108A70000044025808B50122534BC3F80821534B58 +:108A8000D3F8F42042F00202C3F8F420D3F81C21FA +:108A900042F00202C3F81C210222D3F81C314C4BD5 +:108AA000DA605A689104FCD54A4A1A6001229A6039 +:108AB000494ADA6000221A614FF440429A61444BFD +:108AC0009A699204FCD51A6842F480721A603F4B8E +:108AD0001A6F12F4407F04D04FF480321A670022DC +:108AE0001A671A6842F001021A60384B1A68500778 +:108AF000FCD500221A611A6912F03802FBD101215B +:108B000019604FF0804159605A67344ADA62344A3A +:108B10001A611A6842F480321A602C4B1A68910369 +:108B2000FCD51A6842F480521A601A689204FCD587 +:108B30002C4A2D499A6200225A63196301F57C017F +:108B4000DA6301F2E71199635A64284A1A64284AE1 +:108B5000DA621A6842F0A8521A601C4B1A6802F0D6 +:108B60002852B2F1285FF9D148229A614FF4886205 +:108B7000DA6140221A621F4ADA641F4A1A651F4AE4 +:108B80005A651F4A9A6532231E4A1360136803F020 +:108B90000F03022BFAD10D4A136943F0030313614B +:108BA000136903F03803182BFAD14FF00050FFF788 +:108BB000D5FE4FF08040FFF7D1FE4FF00040BDE8FA +:108BC0000840FFF7CBBE00BF0080005100440258B0 +:108BD0000048025800C000F0020000010000FF0140 +:108BE000008890082220400063020901470E050812 +:108BF000DD0BBF0120000020000001100910E00083 +:108C000000010110002000524FF0B04208B5D2F828 +:108C1000883003F00103C2F8883023B1044A136896 +:108C20000BB150689847BDE80840FFF79FB800BFF8 +:108C3000146700204FF0B04208B5D2F8883003F036 +:108C40000203C2F8883023B1044A93680BB1D0689C +:108C50009847BDE80840FFF789B800BF14670020B7 +:108C60004FF0B04208B5D2F8883003F00403C2F8E0 +:108C7000883023B1044A13690BB150699847BDE8A5 +:108C80000840FFF773B800BF146700204FF0B042F0 +:108C900008B5D2F8883003F00803C2F8883023B151 +:108CA000044A93690BB1D0699847BDE80840FFF7C3 +:108CB0005DB800BF146700204FF0B04208B5D2F88D +:108CC000883003F01003C2F8883023B1044A136AD5 +:108CD0000BB1506A9847BDE80840FFF747B800BF9E +:108CE000146700204FF0B04310B5D3F8884004F467 +:108CF0007872C3F88820A30604D5124A936A0BB190 +:108D0000D06A9847600604D50E4A136B0BB1506BBE +:108D10009847210604D50B4A936B0BB1D06B98474B +:108D2000E20504D5074A136C0BB1506C9847A305B4 +:108D300004D5044A936C0BB1D06C9847BDE8104041 +:108D4000FFF714B8146700204FF0B04310B5D3F804 +:108D5000884004F47C42C3F88820620504D5164A92 +:108D6000136D0BB1506D9847230504D5124A936DCE +:108D70000BB1D06D9847E00404D50F4A136E0BB1C8 +:108D8000506E9847A10404D50B4A936E0BB1D06E78 +:108D90009847620404D5084A136F0BB1506F984787 +:108DA000230404D5044A936F0BB1D06F9847BDE8F4 +:108DB0001040FEF7DBBF00BF1467002008B5034872 +:108DC000FCF73CFCBDE80840FEF7D0BF2C37002084 +:108DD00008B50348FCF736FDBDE80840FEF7C6BFFE +:108DE0008439002008B50348FCF72CFDBDE8084095 +:108DF000FEF7BCBFF039002008B50348FCF722FDA0 +:108E0000BDE80840FEF7B2BF5C3A002008B500F0AC +:108E1000BDFCBDE80840FEF7A9BF0000062108B56B +:108E20000846FCF795FD06210720FCF791FD062179 +:108E30000820FCF78DFD06210920FCF789FD06219D +:108E40000A20FCF785FD06211720FCF781FD06218D +:108E50002820FCF77DFD09217A20FCF779FD092106 +:108E60007C20FCF775FD07213220FCF771FD0C21F9 +:108E70002720FCF76DFD0C213520FCF769FD0C2146 +:108E80005220BDE80840FCF763BD000008B5FFF7BD +:108E900075FD00F043FCFDF73BF9FDF7D9F8FDF750 +:108EA00011FBFDF7E3F9FEF7A5F9BDE8084000F076 +:108EB00029BA000030B50433039C0172002104FB81 +:108EC0000325C160C0E90653049B0363059BC0E909 +:108ED0000000C0E90422C0E90842C0E90A11436366 +:108EE00030BD00000022416AC260C0E90411C0E93F +:108EF0000A226FF00101FDF7F3BE0000D0E9043251 +:108F0000934201D1C2680AB9181D7047002070470A +:108F1000036919600021C2680132C260C26913444A +:108F200082699342036124BF436A0361FDF7CCBEAB +:108F300038B504460D46E3683BB162690020131D55 +:108F40001268A3621344E36207E0237A33B9294627 +:108F50002046FDF7A9FE0028EDDA38BD6FF00100CC +:108F6000FBE70000C368C269013BC3604369134467 +:108F700082699342436124BF436A43610023836251 +:108F8000036B03B11847704770B53023044683F371 +:108F90001188866A3EB9FFF7CBFF054618B186F304 +:108FA0001188284670BDA36AE26A13F8015B9342F8 +:108FB000A36202D32046FFF7D5FF002383F3118875 +:108FC000EFE700002DE9F84F04460E461746984695 +:108FD0004FF0300989F311880025AA46D4F828B04B +:108FE000BBF1000F09D141462046FFF7A1FF20B198 +:108FF0008BF311882846BDE8F88FD4E90A12A7EB55 +:10900000050B521A934528BF9346BBF1400F1BD95D +:10901000334601F1400251F8040B914243F8040B2E +:10902000F9D1A36A403640354033A362D4E90A231C +:109030009A4202D32046FFF795FF8AF31188BD427A +:10904000D8D289F31188C9E730465A46F9F758F95A +:10905000A36A5E445D445B44A362E7E710B5029CEB +:109060000433017203FB0421C460C0E9061300232A +:10907000C0E90A33039B0363049BC0E90000C0E915 +:109080000422C0E90842436310BD0000026A6FF089 +:109090000101C260426AC0E904220022C0E90A223A +:1090A000FDF71EBED0E904239A4201D1C26822B95D +:1090B000184650F8043B0B60704700231846FAE747 +:1090C000C3680021C2690133C360436913448269E4 +:1090D0009342436124BF436A4361FDF7F5BD00003D +:1090E00038B504460D46E3683BB1236900201A1DDC +:1090F000A262E2691344E36207E0237A33B92946A6 +:109100002046FDF7D1FD0028EDDA38BD6FF00100F3 +:10911000FBE7000003691960C268013AC260C269D6 +:10912000134482699342036124BF436A03610023AD +:109130008362036B03B118477047000070B530239A +:109140000D460446114683F31188866A2EB9FFF74F +:10915000C7FF10B186F3118870BDA36A1D70A36AA2 +:10916000E26A01339342A36204D3E16920460439E1 +:10917000FFF7D0FF002080F31188EDE72DE9F84FCD +:1091800004460D46904699464FF0300A8AF31188FE +:109190000026B346A76A4FB949462046FFF7A0FF0D +:1091A00020B187F311883046BDE8F88FD4E90A076B +:1091B0003A1AA8EB0607974228BF1746402F1BD93B +:1091C00005F1400355F8042B9D4240F8042BF9D1DA +:1091D000A36A40364033A362D4E90A239A4204D3F7 +:1091E000E16920460439FFF795FF8BF31188464566 +:1091F000D9D28AF31188CDE729463A46F9F780F8A3 +:10920000A36A3D443E443B44A362E5E7D0E904231E +:109210009A4217D1C3689BB1836A8BB1043B9B1AF6 +:109220000ED01360C368013BC360C3691A448369ED +:109230009A42026124BF436A0361002383620123CF +:10924000184670470023FBE701F01F03F0B502F05A +:109250001F0456095A1C0123B6EB511F50F8265023 +:1092600003FA02F34FEA511703F1FF333DBF50F801 +:109270002720C4F12000134003EA05003BBF03FA96 +:1092800000F225FA04F0E0401043F0BD70B57E22F4 +:109290007F210546FFF7D8FF18B1012819D000201B +:1092A00070BD3E2249212846FFF7CEFF2F220446FB +:1092B00031212846FFF7C8FF064601345022023606 +:1092C00053212846B440FFF7BFFF093804FA00F0E5 +:1092D000E6E7302245212846FFF7B6FF013080023D +:1092E000DEE7000090F8D63090F8D7201B0403EB9F +:1092F000026390F8D42090F8D500134403EB0020CB +:109300007047000000F018BA014B586A704700BF60 +:10931000000C0040034B002258631A610222DA60FD +:10932000704700BF000C0040014B0022DA6070471C +:10933000000C0040014B5863704700BF000C004018 +:10934000024B034A1A60034A5A607047EC660020D9 +:109350009867002000000220074B494210B55C6866 +:10936000201A08401968821A8A4203D3A24201D8FF +:109370005A6010BD0020FCE7EC66002008B53023E1 +:1093800083F31188FFF7E8FF002383F3118808BDFA +:109390000448054B03600023C0E901330C3000F0A2 +:1093A00017B900BFF46600207D930008CB1D083A72 +:1093B00023F00703591A521A10B4D2080024C0E946 +:1093C000004384600C301C605A605DF8044B00F070 +:1093D000FFB800002DE9F74F364FCD1D8846002815 +:1093E00018BF0746082A4FEAD50538BF082207F1FB +:1093F0000C003C1D9146019000F02CF9019809F1F8 +:109400000701C9F1000E2246246864B900F02CF966 +:109410003B68CBB308224946E8009847044698B316 +:1094200040E9027830E004EB010CD4F804A00CEA27 +:109430000E0C0AF10106ACF1080304EBC6069E42CD +:10944000E1D9A6EB0C0CB5EBEC0F4FEAEC0BDAD83C +:109450009C421DD204F10802AB45A3EB02024FEA85 +:10946000E202626009D9691CED4303EBC1025D446D +:109470005560256843F8315022601C46C3F80480CB +:1094800044F8087B00F0F0F8204603B0BDE8F08F08 +:10949000AA45216802D111602346EEE7013504EBAD +:1094A000C50344F8351003F10801761AF6105E6022 +:1094B0001360F1E7F466002073B50446A0F10805D7 +:1094C00050F8080C54F8043C061D0C30073301908A +:1094D000DB0844F8043C00F0BDF8334601989E4296 +:1094E0001A6801D0AB4228D20AB1954225D244F87D +:1094F000082C54F8042C1D60013254F8081C05EBAC +:10950000C206B14206D14E68324444F8042C0A68BF +:1095100044F8082C5E68711C03EBC1018D4207D131 +:1095200054F8042C013232445A6054F8082C1A6062 +:1095300002B0BDE8704000F097B81346CFE70000D6 +:10954000FEE7000070B51E4B0025044686B058604B +:109550000E4605638163FEF7E1FB04F12803A56075 +:109560006563C4E90A3304F11003C4E904334FF01E +:10957000FF33C4E90044C4E90635FFF7C5FE2B46B6 +:10958000024604F13C012046C4E9082380230D4A29 +:109590006567FDF703FB7368E0600B4A0362012314 +:1095A000009280F824306846F26801923269CDE971 +:1095B0000223064BCDE90435FDF724FB06B070BD50 +:1095C00070490020FCA10008F4A1000841950008A2 +:1095D0000023C0E9000083600361704770B51C4B35 +:1095E00005468468DE685CB3B44213D10369013375 +:1095F000036170BDA36094F8243083B1062B15D1AC +:10960000A06A2146D4E9003213605A60FDF732FAAD +:10961000A36A9C68B368A2689A42EBD306E0D4E9D7 +:109620000032204613605A60FDF734FA284631466E +:10963000FDF720FAB5620620BDE87040FDF72CBAB0 +:109640000369866001330361336BC3603063D0E725 +:10965000C846002008B5302383F31188FFF7BEFF0A +:10966000002383F3118808BD194BD96883688B42A6 +:1096700010B520D1302383F311880269013A0261C9 +:10968000B2B90468C368A0420B631ED04A6B9BB991 +:1096900001238A60036103681A68026050601A6BD4 +:1096A0008360C26018631846FDF7F4F9FDF744FAC9 +:1096B000002383F3118810BD1C68A34203D0A46863 +:1096C000A24238BF2246DB68E1E78260F0E700BFD4 +:1096D000C8460020024A536B18435063704700BFCE +:1096E000C846002038B5EFF311859DB9EFF3058426 +:1096F000C4F30804302334B183F31188FDF728FC48 +:1097000085F3118838BD83F31188FDF721FC84F3BC +:10971000118838BDBDE83840FDF71ABC0023054A62 +:1097200019460133102BC2E9001102F10802F8D1E9 +:10973000704700BF14670020114BD3F8E82042F0B7 +:109740000802C3F8E820D3F8102142F00802C3F859 +:1097500010210C4AD3F81031D36B43F00803D363C4 +:10976000C722094B9A624FF0FF32DA6200229A61F7 +:109770005A63DA605A6001225A611A60704700BF6A +:10978000004402580010005C000C0040094A08B573 +:109790001169D3680B40D9B29B076FEA01011161CF +:1097A00007D5302383F31188FDF7ECF9002383F309 +:1097B000118808BD000C0040FEF77CB8012838BFB6 +:1097C000012010B504462046FEF734F830B900F009 +:1097D00007F808B9F6F7B2FF8047F4E710BD0000BC +:1097E000024B1868BFF35B8F704700BF946700207F +:1097F0004D4435002D2D0A002F6172647570696C1F +:109800006F742E6162696E002F6172647570696C8D +:109810006F742D7665726966792E6162696E002FAC +:109820006172647570696C6F742D666C6173682EFB +:109830006162696E002F6172647570696C6F742D5E +:10984000666C61736865642E6162696E0000000079 +:109850000000000000000000F51400089115000849 +:1098600041170008C915000889150008000000000C +:1098700000000000F11400089D1500087917000889 +:10988000ED140008F914000853544D333248373FA3 +:109890003F3F0053544D3332483733782F373278B7 +:1098A0000053544D3332483734332F3735332F3745 +:1098B0003530000001105A000310590001205800F3 +:1098C000032056002F0000005375636365737366B1 +:1098D000756C6C79206D6F756E74656420534443AC +:1098E0006172642028736C6F77646F776E3D2575A5 +:1098F000290A0000EB76904558464154202020006C +:109900004641543332202020000000002A3A3C3ED9 +:109910007C223F7F002B2C3B3D5B5D004355454146 +:109920004141414345454549494941414592924F4D +:109930004F4F5555594F554F9C4F9E9F41494F553D +:10994000A5A5A6A7A8A9AAABACADAEAFB0B1B2B35E +:10995000B4414141B8B9BABBBCBDBEBFC0C1C2C3AE +:10996000C4C54141C8C9CACBCCCDCECFD1D1454564 +:109970004549494949D9DADBDCDD49DF4FE14F4F41 +:109980004F4FE6E8E85555555959EEEFF0F1F2F32F +:10999000F4F5F6F7F8F9FAFBFCFDFEFF0103050705 +:1099A000090E10121416181C1E00000061001A0384 +:1099B000E0001703F8000703FF0001007801000131 +:1099C000300132010601390110014A012E017901ED +:1099D000060180014D004302810182018201840160 +:1099E000840186018701870189018A018B018B012E +:1099F0008D018E018F0190019101910193019401DC +:109A0000F60196019701980198013D029B019C0186 +:109A10009D0120029F01A001A001A201A201A401B9 +:109A2000A401A601A701A701A901AA01AB01AC01EC +:109A3000AC01AE01AF01AF01B101B201B301B3019D +:109A4000B501B501B701B801B801BA01BB01BC014C +:109A5000BC01BE01F701C001C101C201C301C401C3 +:109A6000C501C401C701C801C701CA01CB01CA01B0 +:109A7000CD011001DD0101008E01DE011201F301B3 +:109A80000300F101F401F401F8012801220212019E +:109A90003A020900652C3B023B023D02662C3F0264 +:109AA00040024102410246020A0153024000810184 +:109AB0008601550289018A0158028F015A029001DC +:109AC0005C025D025E025F02930161026202940128 +:109AD0006402650266026702970196016A02622CBF +:109AE0006C026D026E029C01700271029D01730294 +:109AF00074029F0176027702780279027A027B0271 +:109B00007C02642C7E027F02A60181028202A901EE +:109B10008402850286028702AE014402B101B201CD +:109B200045028D028E028F0290029102B7017B03E3 +:109B30000300FD03FE03FF03AC0304008603880358 +:109B400089038A03B1031103C2030200A303A30321 +:109B5000C4030803CC0303008C038E038F03D803D4 +:109B60001801F2030A00F903F303F403F503F60303 +:109B7000F703F703F903FA03FA0330042003500450 +:109B80001007600422018A043601C1040E01CF04CB +:109B90000100C004D0044401610526040000000057 +:109BA0007D1D0100632C001E9601A01E5A01001F9E +:109BB0000806101F0606201F0806301F0806401F53 +:109BC0000606511F0700591F521F5B1F541F5D1FC0 +:109BD000561F5F1F601F0806701F0E00BA1FBB1FB5 +:109BE000C81FC91FCA1FCB1FDA1FDB1FF81FF91FB1 +:109BF000EA1FEB1FFA1FFB1F801F0806901F0806B5 +:109C0000A01F0806B01F0400B81FB91FB21FBC1F59 +:109C1000CC1F0100C31FD01F0206E01F0206E51F74 +:109C20000100EC1FF31F0100FC1F4E210100322137 +:109C300070211002842101008321D0241A05302CC8 +:109C40002F04602C0201672C0601752C0201802C68 +:109C50006401002D260841FF1A030000C700FC0024 +:109C6000E900E200E400E000E500E700EA00EB00C4 +:109C7000E800EF00EE00EC00C400C500C900E600FB +:109C8000C600F400F600F200FB00F900FF00D60069 +:109C9000DC00F800A300D800D7009201E100ED003D +:109CA000F300FA00F100D100AA00BA00BF00AE0034 +:109CB000AC00BD00BC00A100AB00BB00912592250B +:109CC000932502252425C100C200C000A9006325F8 +:109CD000512557255D25A200A50010251425342502 +:109CE0002C251C2500253C25E300C3005A255425BE +:109CF00069256625602550256C25A400F000D0005C +:109D0000CA00CB00C8003101CD00CE00CF0018251D +:109D10000C2588258425A600CC008025D300DF00F3 +:109D2000D400D200F500D500B500FE00DE00DA0058 +:109D3000DB00D900FD00DD00AF00B400AD00B100D4 +:109D40001720BE00B600A700F700B800B000A800BA +:109D5000B700B900B300B200A025A0001000024077 +:109D6000080002400008024000000B0028000240EA +:109D7000080002400408024006010C0040000240B6 +:109D8000080002400808024010020D00580002407E +:109D9000080002400C08024016030E00700002404A +:109DA0000C0002401008024000040F00880002402E +:109DB0000C0002401408024006051000A0000240FA +:109DC0000C0002401808024010061100B8000240C2 +:109DD0000C0002401C08024016072F00100402402D +:109DE000080402402008024000083800280402400D +:109DF00008040240240802400609390040040240D9 +:109E00000804024028080240100A3A0058040240A0 +:109E1000080402402C080240160B3B00700402406C +:109E20000C04024030080240000C3C008804024050 +:109E30000C04024034080240060D4400A004024015 +:109E40000C04024038080240100E4500B8040240DD +:109E50000C0402403C080240160F460001000000BE +:109E6000000000000096000000000000000000005C +:109E700000000000000000000000000000000000E2 +:109E8000ED710008F1710008E55C00081D60000834 +:109E9000795C0008A15C0008C95C0008615C0008EE +:109EA00000000000D1600008BD600008F9600008F3 +:109EB000E5600008F1600008DD600008C960000886 +:109EC000B56000080561000800000000E9610008B5 +:109ED000D561000811620008FD61000809620008F0 +:109EE000F5610008E1610008CD6100081D6200080D +:109EF00000000000010000000000000063300000CE +:109F0000FC9E000800000000000000004047002008 +:109F1000704900200000802A00020000AAAAAAAA14 +:109F200000000024FFFF00000000000000A00A0065 +:109F3000000200A000000000AAAAAAAA0001005086 +:109F4000FFFF00000000090000000099000000066B +:109F500000000000AAAAAAAA00000001FFFF00005A +:109F6000000000000000080020A00A00000000001F +:109F7000AAAAAAAA10400500FFFF0000000800BB23 +:109F8000770000004014020028000000AAAAAAAA34 +:109F900000000100FFFF00000000000007000000BB +:109FA0000020000100000000AAAAAAAA00100000D8 +:109FB000FFFF0000000000070000000000518000CB +:109FC00000000000AAAAAAAA00404000FFFF00006B +:109FD0000000000000A0000000040040000000009D +:109FE000AAAAAAAA00040040FFFF00000000000087 +:109FF000000000000001150000000000AAAAAAAAA3 +:10A0000000011500FFFF000000000000000000003C +:10A010000000000000000000AAAAAAAA0000000098 +:10A02000FFFF000000000000000000000000000032 +:10A0300000000000AAAAAAAA00000000FFFF00007A +:10A0400000000000000000004172647550696C6FF0 +:10A05000740025424F415244252D424C0025534562 +:10A060005249414C250000000200000000000000A1 +:10A070000964000879640008400040002062002064 +:10A080003062002002000000000000000300000019 +:10A0900000000000C1640008000000001000000083 +:10A0A00040620020000000000100000000000000ED +:10A0B0009C65002001010200E9720008F9710008A6 +:10A0C000957200087972000843000000D0A00008D3 +:10A0D00009024300020100C032090400000102022B +:10A0E00001000524001001052401000104240202DE +:10A0F0000524060001070582030800FF090401008A +:10A10000020A000000070501024000000705810265 +:10A1100040000000120000001CA100081201100104 +:10A120000200004009124157000201020301000031 +:10A130000403090425424F41524425005A65726FB9 +:10A140004F6E655836003031323334353637383952 +:10A150004142434445460000000000200000020048 +:10A1600002000000000000300000040008000000B1 +:10A1700000000024000008000400000000040000AB +:10A1800000FC00000200000000000430008000001D +:10A19000080000000000003800000100010000007D +:10A1A0001F1C1F1E1F1E1F1F1E1F1E1F1F1D1F1EC9 +:10A1B0001F1E1F1F1E1F1E1F000000001D6600081F +:10A1C000D56800088169000840004000D46600207E +:10A1D000D466002001000000E4660020800000003A +:10A1E0004001000008000000000100000010000015 +:10A1F0000800000069646C65000000006D61696E14 +:10A20000002C0438040438080C10141C20242526C3 +:10A2100000000000000064040100040000000000D1 +:10A22000000C0010283034004062FF7F0100000065 +:10A2300004220020000000000000000000000000D8 +:10A24000000000000000000000000000000000000E +:10A2500000000000000000000000000000000000FE +:10A2600000000000000000000000000000000000EE +:10A2700000000000000000000000000000000000DE +:10A2800000000000000000000000000000000000CE +:10A2900000000000E01500000000000000001E00AB +:10A2A00000000000FF000000784900205C3A002018 +:10A2B000F039002084390020000000008898000850 +:10A2C000830400009398000850040000A19800083F +:10A2D00001000000000000000096000000000800DF +:10A2E00096000000000800000400000030A10008F3 +:10A2F000000000000000000000000000000000005E +:08A30000000000000000000055 +:00000001FF diff --git a/Tools/cameras_gimbals/siyi-download/siyi-download.py b/Tools/cameras_gimbals/siyi-download/siyi-download.py new file mode 100644 index 00000000000000..97dea2da945d61 --- /dev/null +++ b/Tools/cameras_gimbals/siyi-download/siyi-download.py @@ -0,0 +1,145 @@ +#!/usr/bin/env python3 + +""" +Downloads files from a Siyi camera connected via ethernet + +AP_FLAKE8_CLEAN +""" + +# +# utility to download files from a siyi camera +# + +import os +import json +from argparse import ArgumentParser +from urllib.request import urlopen, urlretrieve +from urllib.parse import urlencode +from urllib.error import URLError, HTTPError +from enum import Enum + +# prefix string for text outout to user +prefix_str = "siyi-download.py: " +ip_address_default = "192.168.144.25" + + +# media types +class MediaTypes(Enum): + IMAGE = 0 + VIDEO = 1 + + +# media type strings. used to display to user +MEDIA_TYPE_STR = ["image", "video"] + + +# get URL for list of directories +def get_dirlist_url(ip_address, media_type): + params = {'media_type': media_type} + return f"http://{ip_address}:82/cgi-bin/media.cgi/api/v1/getdirectories?" + urlencode(params) + + +# get URL for list of files in a directory +def get_filelist_url(ip_address, media_type, dir_path): + params = { + 'media_type': str(media_type), + 'path': dir_path, + 'start': 0, + 'count': 999 + } + return f"http://{ip_address}:82/cgi-bin/media.cgi/api/v1/getmedialist?" + urlencode(params) + + +# download files from camera +def download_files(ip_address, dest_dir): + + # repeat for images and videos + for media_type in [mt.value for mt in MediaTypes]: + + # display output to user + print(prefix_str + f"downloading {MEDIA_TYPE_STR[media_type]} files") + + # download list of directories in JSON format + dir_list_url = get_dirlist_url(ip_address, media_type) + with urlopen(dir_list_url) as get_dir_url: + dir_dict = json.load(get_dir_url) + + # check that the request succeeded + if (not dir_dict['success']): + exit(prefix_str + "failed to get list of directories") + + # check response includes 'data' + if ('data' not in dir_dict.keys()): + exit(prefix_str + "could not get list of directories, no 'data' in response") + dir_dict_data = dir_dict['data'] + + # check response includes 'directories' + if ('directories' not in dir_dict_data.keys()): + exit(prefix_str + "could not get list of directories, no 'directories' in response") + dir_dict_data_directories = dir_dict_data['directories'] + + # create list of directories from 'path' values + dir_list = [] + for dir in dir_dict_data_directories: + if ('path' in dir.keys()): + dir_list.append(dir['path']) + print(prefix_str + f"{len(dir_list)} directories") + + # get list of files in each directory + for dir_path in dir_list: + filenames_url = get_filelist_url(ip_address, media_type, dir_path) + with urlopen(filenames_url) as get_filenames_url: + filename_dict = json.load(get_filenames_url) + + # check that the request succeeded + if (not filename_dict['success']): + exit(prefix_str + "failed to get list of files") + + # check response includes 'data' + if ('data' not in filename_dict.keys()): + exit(prefix_str + "could not get list of files, no 'data' in response") + filename_dict_data = filename_dict['data'] + + # check response includes 'list' + if ('list' not in filename_dict_data.keys()): + exit(prefix_str + "could not get list of files, no 'list' in response") + filename_dict_data_list = filename_dict_data['list'] + print(prefix_str + f"{len(filename_dict_data_list)} files") + + # download each image + for fileinfo in filename_dict_data_list: + if ('name' not in fileinfo.keys() or 'url' not in fileinfo.keys()): + exit(prefix_str + "could not get list of files, no 'name' or 'url' in response") + filename = fileinfo['name'] + file_url = fileinfo['url'] + + # correct incorrect ip address in returned url + file_url_fixed = file_url.replace(ip_address_default, ip_address) + + # download file + print(prefix_str + f"downloading {filename} from {file_url_fixed}") + dest_filename = os.path.join(dest_dir, filename) + try: + urlretrieve(file_url_fixed, dest_filename) + except (URLError, HTTPError) as e: + print(prefix_str + f"failed to download {filename}: {e}") + + +# main function +def main(): + parser = ArgumentParser(description=__doc__) + parser.add_argument("--ipaddr", default=ip_address_default, help="IP address of camera") + parser.add_argument("--dest", default=".", help="destination directory where downloaded files will be saved") + args = parser.parse_args() + + # check destination directory exists + if not os.path.exists(args.dest): + exit(prefix_str + "invalid destination directory") + + # download files + download_files(args.ipaddr, args.dest) + + +# main +if __name__ == "__main__": + main() diff --git a/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp new file mode 100644 index 00000000000000..88325f17f155c6 --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp @@ -0,0 +1,142 @@ +// ============================================================================= +/** + * @file CX-GBXXXCtrl.cpp + * @brief CX-GBXXX用コントロールクラス ヘッダ + * @copyright (c) 2022 Xacti Corporation + */ +// ============================================================================= + +#include "CX-GBXXXCtrl.h" +#include +#include +#include + +// ----------------------------------------------------------------------------- +/*! + * @brief CX_GBXXXCtrlコンストラクタ + */ +// ----------------------------------------------------------------------------- +CX_GBXXXCtrl::CX_GBXXXCtrl() + : m_ctx(NULL), m_dev(NULL), m_devh(NULL) +{ + uvc_error_t res = uvc_init(&m_ctx, NULL); + if (res < 0) + { + uvc_perror(res, "uvc_init"); + assert(res == 0); + } +} + +// ----------------------------------------------------------------------------- +/*! + * @brief CX_GBXXXCtrlデストラクタ + */ +// ----------------------------------------------------------------------------- +CX_GBXXXCtrl::~CX_GBXXXCtrl() +{ + uvc_exit(m_ctx); +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラオープン + * + * @param [in] callback カメラシリアル番å·(NULL: Don't Care) + * + * @return オープンæˆåŠŸå¯å¦ + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::Open(const char *serial) +{ + uvc_error_t res; + if ((res = uvc_find_device( + m_ctx, &m_dev, + 0x296b, 0, serial)) < 0) + { + uvc_perror(res, "uvc_find_device"); // CX-GBXXX未接続 + return false; + } + + if ((res = uvc_open(m_dev, &m_devh)) < 0) + { + uvc_perror(res, "uvc_open"); + return false; + } + + return true; +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラクローズ + */ +// ----------------------------------------------------------------------------- +void CX_GBXXXCtrl::Close() +{ + if (m_devh) + { + uvc_close(m_devh); + } + if (m_dev) + { + uvc_unref_device(m_dev); + } +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラ情報設定 + * + * @param [in] unit_id ユニットID + * @param [in] cotrol_id コントロールID + * @param [in] data データãƒãƒƒãƒ•ã‚¡ + * @param [in] length データサイズ(ãƒã‚¤ãƒˆï¼‰ + * + * @return æˆåŠŸå¯å¦ + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length) +{ + if (!m_devh) + { + uvc_perror(UVC_ERROR_INVALID_DEVICE, "SetCameraCtrl"); + return false; + } + + if (uvc_set_ctrl(m_devh, unit_id, cotrol_id, data, length) != length) + { + uvc_perror(UVC_ERROR_OTHER, "SetCameraCtrl"); + return false; + } + + return true; +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラ情報å–å¾— + * + * @param [in] unit_id ユニットID + * @param [in] cotrol_id コントロールID + * @param [out] data データãƒãƒƒãƒ•ã‚¡ + * @param [in] length データサイズ(ãƒã‚¤ãƒˆï¼‰ + * + * @return æˆåŠŸå¯å¦ + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length) +{ + if (!m_devh) + { + uvc_perror(UVC_ERROR_INVALID_DEVICE, "GetCameraCtrl"); + return false; + } + + if (uvc_get_ctrl(m_devh, unit_id, cotrol_id, data, length, UVC_GET_CUR) != length) + { + uvc_perror(UVC_ERROR_OTHER, "GetCameraCtrl"); + return false; + } + + return true; +} diff --git a/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h new file mode 100644 index 00000000000000..ee08e3a804a6ca --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h @@ -0,0 +1,40 @@ +// ============================================================================= +/** + * @file CX-GBXXXCtrl.h + * @brief CX-GBXXX用コントロールクラス ヘッダ + * @copyright (c) 2022 Xacti Corporation + */ +// ============================================================================= + +#pragma once + +#include + +struct uvc_context; +typedef struct uvc_context uvc_context_t; +struct uvc_device; +typedef struct uvc_device uvc_device_t; +struct uvc_device_handle; +typedef struct uvc_device_handle uvc_device_handle_t; +struct uvc_frame; +typedef struct uvc_frame uvc_frame_t; + +/*! @brief CCX_GBXXX用コントロールクラス */ +class CX_GBXXXCtrl +{ +public: + CX_GBXXXCtrl(); + virtual ~CX_GBXXXCtrl(); + bool Open(const char *serial); + void Close(); + + //! カメラコマンド + bool SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length); + bool GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length); + +private: + + uvc_context_t *m_ctx; + uvc_device_t *m_dev; + uvc_device_handle_t *m_devh; +}; diff --git a/Tools/cameras_gimbals/xacti-config/Makefile b/Tools/cameras_gimbals/xacti-config/Makefile new file mode 100644 index 00000000000000..1cca5c12ccf68a --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/Makefile @@ -0,0 +1,48 @@ +################################################################################ +# Copyright (c) 2022, Xacti Corporation. All rights reserved. +# Modified by Randy Mackay +################################################################################ + +APP:= xacti-config +CC = g++ + +# Optimisation Options +# +CFLAGOPT = +CFLAGOPT += -O0 + +SRCS:= $(wildcard *.c) $(wildcard *.cpp) + +INCS:= $(wildcard *.h) + +PKGS:= x11 + +OBJS:= $(SRCS:.c=.o) +OBJS:= $(OBJS:.cpp=.o) + +CFLAGS+= -g +CFLAGS+= $(CFLAGOPT) + +LIBS+= -lm \ + -Wl,-rpath \ + -lpthread -pthread -luvc + +CFLAGS+= `pkg-config --cflags $(PKGS)` + +LIBS+= `pkg-config --libs $(PKGS)` + +all: $(APP) + +%.o: %.c $(INCS) Makefile + $(CC) -c -o $@ $(CFLAGS) $< +%.o: %.cpp $(INCS) Makefile + $(CC) -c -o $@ $(CFLAGS) $< + +$(APP): $(OBJS) Makefile + $(CC) -o $(APP) $(OBJS) $(LIBS) + +clean: + rm -rf $(OBJS) $(APP) + +exec: + ./$(APP) diff --git a/Tools/cameras_gimbals/xacti-config/README b/Tools/cameras_gimbals/xacti-config/README new file mode 100644 index 00000000000000..364e6f16d5f8ba --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/README @@ -0,0 +1,23 @@ +******************** + xacti-config + README +******************** + +Install Instructions + +- download this program to your Linux/Ubuntu PC +- sudo apt-get install libusb-1.0-0-dev +- sudo apt install libuvc-dev +- make + +Execution instructions + +- sudo xacti-config option [value] +- the following options are available + --dronecan enable (value=1) or disable (value=0) dronecan parsing + --format format SD card + --help display usage + --irpalette set IR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest) + --msc change to mass storage class mode (for downloading from SD card) + + diff --git a/Tools/cameras_gimbals/xacti-config/main.cpp b/Tools/cameras_gimbals/xacti-config/main.cpp new file mode 100644 index 00000000000000..8977bf569c1403 --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/main.cpp @@ -0,0 +1,99 @@ +#include +#include +#include +#include "CX-GBXXXCtrl.h" + +const char* this_app_str = "xacti-config"; + +// display help +void display_help() +{ + printf("Usage: sudo %s option [value]\n", this_app_str); + printf(" --dronecan\tenable (value=1) or disable (value=0) dronecan parsing\n"); + printf(" --format\tformat SD card\n"); + printf(" --help\t\tdisplay usage\n"); + printf(" --irpalette\t\tIR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest)\n"); + printf(" --msc\t\tchange to mass storage class mode (for downloading from SD card)\n"); +} + +int main(int argc, char **argv) +{ + // display help + if ((argc <= 1) || ((argc >= 2) && (strcmp(argv[1], "--help") == 0))) { + display_help(); + return 0; + } + + // open camera + CX_GBXXXCtrl camera_ctrl; + if (!camera_ctrl.Open(NULL)) { + printf("%s: failed to open camera\n", this_app_str); + return 1; + } + + // args_ok set to true when command line processed correctly + bool args_ok = false; + bool ret_ok = true; + + // enable DroneCAN + if ((argc >= 3) && (strcmp(argv[1], "--dronecan") == 0)) { + args_ok = true; + uint8_t enable = (strcmp(argv[2], "1") == 0); + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x1e, &enable, sizeof(enable)); + const char* enable_or_disable_str = enable ? "enable" : "disable"; + if (ret_ok) { + printf("%s: %s DroneCAN\n", this_app_str, enable_or_disable_str); + } else { + printf("%s: failed to %s DroneCAN\n", this_app_str, enable_or_disable_str); + } + } + + // format SD card + if ((argc >= 2) && (strcmp(argv[1], "--format") == 0)) { + args_ok = true; + uint8_t format_sd = 0; + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x15, &format_sd, sizeof(format_sd)); + if (ret_ok) { + printf("%s: formatted SD card\n", this_app_str); + } else { + printf("%s: failed format SD card\n", this_app_str); + } + } + + // IR palette + if ((argc >= 3) && (strcmp(argv[1], "--irpalette") == 0)) { + args_ok = true; + int palette_int = 0; + sscanf(argv[2], "%d", &palette_int); + uint8_t palette_uint8 = (uint8_t)palette_int; + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x19, &palette_uint8, sizeof(palette_uint8)); + if (ret_ok) { + printf("%s: IR palette set to %d\n", this_app_str, (int)palette_uint8); + } else { + printf("%s: failed to set IR palette to %d\n", this_app_str, (int)palette_uint8); + } + } + + // change to Mass Storage Mode to allow downloading of images and videos + if ((argc >= 2) && (strcmp(argv[1], "--msc") == 0)) { + args_ok = true; + uint8_t msc_mode = 1; + ret_ok = camera_ctrl.SetCameraCtrl(0x06, 0x07, &msc_mode, sizeof(msc_mode)); + if (ret_ok) { + printf("%s: changed to mass storage mode\n", this_app_str); + } else { + printf("%s: failed to change to mass storage mode\n", this_app_str); + } + } + + // close camera + camera_ctrl.Close(); + + // display help if args could not be processed + if (!args_ok) { + display_help(); + } + + // return 0 if OK, 1 if not OK + return ret_ok ? 0 : 1; +} diff --git a/Tools/completion/zsh/_ap_bin b/Tools/completion/zsh/_ap_bin index 543bc72c34ecaf..36e273642ca50d 100644 --- a/Tools/completion/zsh/_ap_bin +++ b/Tools/completion/zsh/_ap_bin @@ -21,16 +21,6 @@ _ap_bin() { '--gimbal[enable simulated MAVLink gimbal]' \ '--autotest-dir[set directory for additional files]:DIR:' \ '--defaults[set path to defaults file]:PATH:' \ - '--uartA[(deprecated) set device string for SERIAL0]:DEVICE:' \ - '--uartC[(deprecated) set device string for SERIAL1]:DEVICE:' \ - '--uartD[(deprecated) set device string for SERIAL2]:DEVICE:' \ - '--uartB[(deprecated) set device string for SERIAL3]:DEVICE:' \ - '--uartE[(deprecated) set device string for SERIAL4]:DEVICE:' \ - '--uartF[(deprecated) set device string for SERIAL5]:DEVICE:' \ - '--uartG[(deprecated) set device string for SERIAL6]:DEVICE:' \ - '--uartH[(deprecated) set device string for SERIAL7]:DEVICE:' \ - '--uartI[(deprecated) set device string for SERIAL8]:DEVICE:' \ - '--uartJ[(deprecated) set device string for SERIAL9]:DEVICE:' \ '--serial0[set device string for SERIAL0]:DEVICE:' \ '--serial1[set device string for SERIAL1]:DEVICE:' \ '--serial2[set device string for SERIAL2]:DEVICE:' \ diff --git a/Tools/environment_install/install-prereqs-alpine.sh b/Tools/environment_install/install-prereqs-alpine.sh new file mode 100755 index 00000000000000..c01da408db3ef6 --- /dev/null +++ b/Tools/environment_install/install-prereqs-alpine.sh @@ -0,0 +1,23 @@ +#!/usr/bin/env sh +echo "---------- $0 start ----------" +set -e +set -x + +echo "===================================================================" +echo "Warning: This script is not fully tested. Please report any issues." +echo "===================================================================" + + +apk update && apk add --no-cache \ + linux-headers \ + g++ \ + python3 \ + py-future \ + py-pip \ + libxml2-dev \ + libxslt-dev \ + git \ + && ln -sf python3 /usr/bin/python \ + && rm -rf /var/cache/apk/* + +python3 -m pip install --user --no-deps --no-cache-dir empy==3.3.4 pexpect ptyprocess --break-system-packages diff --git a/Tools/environment_install/install-prereqs-arch.sh b/Tools/environment_install/install-prereqs-arch.sh index 965815ec71efc1..6abdb7f5926b8c 100755 --- a/Tools/environment_install/install-prereqs-arch.sh +++ b/Tools/environment_install/install-prereqs-arch.sh @@ -26,13 +26,14 @@ BASE_PKGS="base-devel ccache git gsfonts tk wget gcc" 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 pexpect argparse matplotlib pyparsing geocoder pyserial empy==3.3.4 dronecan" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect argparse matplotlib pyparsing geocoder pyserial empy==3.3.4 dronecan packaging setuptools wheel" # 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" +ARM_TARBALL_CHECKSUM="21134caa478bbf5352e239fbc6e2da3038f8d2207e089efc96c3b55f1edcd618" # Ardupilot Tools ARDUPILOT_TOOLS="ardupilot/Tools/autotest" @@ -54,7 +55,7 @@ sudo usermod -a -G uucp "$USER" sudo pacman -Syu --noconfirm --needed $BASE_PKGS $SITL_PKGS $PX4_PKGS -python3 -m venv "$HOME"/venv-ardupilot +python3 -m venv --system-site-packages "$HOME"/venv-ardupilot # activate it: SOURCE_LINE="source $HOME/venv-ardupilot/bin/activate" @@ -66,6 +67,8 @@ fi if [[ $DO_PYTHON_VENV_ENV -eq 1 ]]; then echo "$SOURCE_LINE" >> ~/.bashrc +else + echo "Please use \`$SOURCE_LINE\` to activate the ArduPilot venv" fi pip3 -q install -U $PYTHON_PKGS @@ -83,9 +86,33 @@ pip3 -q install -U $PYTHON_PKGS if [ ! -d $OPT/$ARM_ROOT ]; then ( cd $OPT; - sudo wget --progress=dot:giga $ARM_TARBALL_URL; - sudo tar xjf ${ARM_TARBALL}; - sudo rm ${ARM_TARBALL}; + + # Check if file exists and verify checksum + download_required=false + if [ -e "$ARM_TARBALL" ]; then + echo "File exists. Verifying checksum..." + + # Calculate the checksum of the existing file + ACTUAL_CHECKSUM=$(sha256sum "$ARM_TARBALL" | awk '{ print $1 }') + + # Compare the actual checksum with the expected one + if [ "$ACTUAL_CHECKSUM" == "$ARM_TARBALL_CHECKSUM" ]; then + echo "Checksum valid. No need to redownload." + else + echo "Checksum invalid. Redownloading the file..." + download_required=true + sudo rm $ARM_TARBALL + fi + else + echo "File does not exist. Downloading..." + download_required=true + fi + + if $download_required; then + sudo wget -O "$ARM_TARBALL" --progress=dot:giga $ARM_TARBALL_URL + fi + + sudo tar xjf ${ARM_TARBALL} ) fi diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 7c0701b38a161c..0703782d2e5b37 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -106,7 +106,7 @@ find /usr/local/bin -lname '*/Library/Frameworks/Python.framework/*' -delete # brew update randomly failing on CI, so ignore errors: brew update -brew install --force --overwrite gawk curl coreutils wget +brew install --force --overwrite gawk coreutils wget PIP=pip if maybe_prompt_user "Install python using pyenv [N/y]?" ; then diff --git a/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh b/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh index 5895dbdeb5b2be..c1280fef1bd51b 100755 --- a/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh +++ b/Tools/environment_install/install-prereqs-openSUSE-Tumbleweed.sh @@ -102,10 +102,12 @@ if ! grep -Fxq "$SOURCE_LINE" ~/.bashrc; then if [[ $DO_PYTHON_VENV_ENV -eq 1 ]]; then echo $SOURCE_LINE >> ~/.bashrc + else + echo "Please use \`$SOURCE_LINE\` to activate the ArduPilot venv" fi fi -$PIP3 install -U pip setuptools wheel +$PIP3 install -U pip packaging setuptools wheel $PIP3 install -U attrdict3 $PIP3 install -U $PYTHON_PKGS diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index 76ea0c3098543c..5c205577ba73a6 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -62,6 +62,9 @@ RELEASE_CODENAME=$(lsb_release -c -s) # translate Mint-codenames to Ubuntu-codenames based on https://www.linuxmint.com/download_all.php case ${RELEASE_CODENAME} in + wilma) + RELEASE_CODENAME='noble' + ;; vanessa) RELEASE_CODENAME='jammy' ;; @@ -80,10 +83,8 @@ PYTHON_V="python3" # starting from ubuntu 20.04, python isn't symlink to defaul PIP=pip3 if [ ${RELEASE_CODENAME} == 'bionic' ] ; then - SITLFML_VERSION="2.4" - SITLCFML_VERSION="2.4" - PYTHON_V="python3" - PIP=pip3 + echo "ArduPilot no longer supports developing on this operating system that has reached end of standard support." + exit 1 elif [ ${RELEASE_CODENAME} == 'bookworm' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" @@ -161,9 +162,9 @@ else fi # Lists of packages to install -BASE_PKGS="build-essential ccache g++ gawk git make wget valgrind screen" -PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy pexpect geocoder empy==3.3.4 ptyprocess dronecan" -PYTHON_PKGS="$PYTHON_PKGS flake8 junitparser" +BASE_PKGS="build-essential ccache g++ gawk git make wget valgrind screen python3-pexpect astyle" +PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy geocoder empy==3.3.4 ptyprocess dronecan" +PYTHON_PKGS="$PYTHON_PKGS flake8 junitparser wsproto tabulate" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then @@ -383,7 +384,7 @@ fi if [ -n "$PYTHON_VENV_PACKAGE" ]; then $APT_GET install $PYTHON_VENV_PACKAGE - python3 -m venv $HOME/venv-ardupilot + python3 -m venv --system-site-packages $HOME/venv-ardupilot # activate it: SOURCE_LINE="source $HOME/venv-ardupilot/bin/activate" @@ -396,11 +397,17 @@ if [ -n "$PYTHON_VENV_PACKAGE" ]; then if [[ $DO_PYTHON_VENV_ENV -eq 1 ]]; then echo $SOURCE_LINE >> ~/$SHELL_LOGIN + else + echo "Please use \`$SOURCE_LINE\` to activate the ArduPilot venv" fi fi # try update packaging, setuptools and wheel before installing pip package that may need compilation -$PIP install $PIP_USER_ARGUMENT -U pip packaging setuptools wheel +SETUPTOOLS="setuptools" +if [ ${RELEASE_CODENAME} == 'focal' ]; then + SETUPTOOLS=setuptools==70.3.0 +fi +$PIP install $PIP_USER_ARGUMENT -U pip packaging $SETUPTOOLS wheel if [ "$GITHUB_ACTIONS" == "true" ]; then PIP_USER_ARGUMENT+=" --progress-bar off" @@ -414,7 +421,11 @@ if [ ${RELEASE_CODENAME} == 'bookworm' ] || $PIP install $PIP_USER_ARGUMENT -U attrdict3 fi -$PIP install $PIP_USER_ARGUMENT -U $PYTHON_PKGS +# install Python packages one-at-a-time so it is clear which package +# is causing problems: +for PACKAGE in $PYTHON_PKGS; do + $PIP install $PIP_USER_ARGUMENT -U $PACKAGE +done if [[ -z "${DO_AP_STM_ENV}" ]] && maybe_prompt_user "Install ArduPilot STM32 toolchain [N/y]?" ; then DO_AP_STM_ENV=1 diff --git a/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 b/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 index 2076ce1f588d6b..5cc7735a5b0f24 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==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'python3.7 -m pip install empy==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" 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 15bac628949e85..543f1370c9d0be 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==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'python3.7 -m pip install empy==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" 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/ros2/README.md b/Tools/ros2/README.md index 9832e412f999d5..4fd2e6e6bf8f59 100644 --- a/Tools/ros2/README.md +++ b/Tools/ros2/README.md @@ -1,19 +1,35 @@ # ArduPilot ROS 2 packages - This directory contains ROS 2 packages and configuration files for running - ROS 2 processes and nodes that communicate with the ArduPilot DDS client - library using the microROS agent. It contains the following packages: +This directory contains ROS 2 packages and configuration files for running +ROS 2 processes and nodes that communicate with the ArduPilot DDS client +library using the microROS agent. It contains the following packages: #### `ardupilot_sitl` -A `colcon` package for building and running ArduPilot SITL using the ROS 2 CLI. +This is a `colcon` package for building and running ArduPilot SITL using the ROS 2 CLI. For example `ardurover` SITL may be launched with: ```bash ros2 launch ardupilot_sitl sitl.launch.py command:=ardurover model:=rover ``` -#### `ardupilot_dds_test` +Other launch files are included with many arguments. +Some common arguments are exposed and forwarded to the underlying process. + +For example, MAVProxy can be launched, and you can enable the `console` and `map`. +```bash +ros2 launch ardupilot_sitl sitl_mavproxy.launch.py map:=True console:=True +``` + +ArduPilot SITL does not yet expose all arguments from the underlying binary. +See [#27714](https://github.com/ArduPilot/ardupilot/issues/27714) for context. + +To see all current options, use the `-s` argument: +```bash +ros2 launch ardupilot_sitl sitl.launch.py -s +``` + +#### `ardupilot_dds_tests` A `colcon` package for testing communication between `micro_ros_agent` and the ArduPilot `AP_DDS` client library. @@ -30,7 +46,7 @@ The packages depend on: #### 1. Create a workspace folder ```bash -mkdir -p ~/ros_ws/src && cd ~/ros_ws/src +mkdir -p ~/ros2_ws/src && cd ~/ros2_ws/src ``` The ROS 2 tutorials contain more details regarding [ROS 2 workspaces](https://docs.ros.org/en/humble/Tutorials/Workspace/Creating-A-Workspace.html). @@ -46,7 +62,7 @@ vcs import --recursive < ros2.repos #### 3. Update dependencies ```bash -cd ~/ros_ws +cd ~/ros2_ws source /opt/ros/humble/setup.bash sudo apt update rosdep update @@ -64,7 +80,7 @@ ROS_DISTRO=humble ``` ```bash -cd ~/ros_ws +cd ~/ros2_ws colcon build --cmake-args -DBUILD_TESTING=ON ``` @@ -76,6 +92,11 @@ colcon test --packages-select ardupilot_dds_tests colcon test-result --all --verbose ``` +To debug a specific test, you can do the following: +``` +colcon --log-level DEBUG test --packages-select ardupilot_dds_tests --event-handlers=console_direct+ --pytest-args -k test_dds_udp_geopose_msg_recv -s +``` + ## Install macOS The install procedure on macOS is similar, except that all dependencies @@ -84,7 +105,7 @@ must be built from source and additional compiler flags are needed. #### 1. Create a workspace folder ```bash -mkdir -p ~/ros_ws/src && cd ~/ros_ws/src +mkdir -p ~/ros2_ws/src && cd ~/ros2_ws/src ``` #### 2. Get the `ros2_macos.repos` file @@ -100,7 +121,7 @@ vcs import --recursive < ros2_macos.repos #### 3. Update dependencies ```bash -cd ~/ros_ws +cd ~/ros2_ws source /{path_to_your_ros_distro_workspace}/install/setup.zsh ``` @@ -183,7 +204,7 @@ socat -d -d pty,raw,echo=0,link=./dev/ttyROS0 pty,raw,echo=0,link=./dev/ttyROS1 ``` ```bash -ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/ttyROS0 --refs $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml +ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/ttyROS0 ``` ```bash @@ -201,7 +222,7 @@ ros2 launch ardupilot_sitl virtual_ports.launch.py tty0:=./dev/ttyROS0 tty1:=./d ``` ```bash -ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml baudrate:=115200 device:=./dev/ttyROS0 +ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial baudrate:=115200 device:=./dev/ttyROS0 ``` ```bash @@ -221,7 +242,6 @@ tty0:=./dev/ttyROS0 \ tty1:=./dev/ttyROS1 \ \ transport:=serial \ -refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml \ baudrate:=115200 \ device:=./dev/ttyROS0 \ \ @@ -242,5 +262,5 @@ sitl:=127.0.0.1:5501 UDP version ``` -ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml synthetic_clock:=True wipe:=False model:=quad speedup:=1 slave:=0 instance:=0 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_udp.parm sim_address:=127.0.0.1 master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501 +ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 synthetic_clock:=True wipe:=False model:=quad speedup:=1 slave:=0 instance:=0 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_udp.parm sim_address:=127.0.0.1 master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501 ``` diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/copter_takeoff.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/copter_takeoff.py new file mode 100755 index 00000000000000..4443c17ab24fcb --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/copter_takeoff.py @@ -0,0 +1,180 @@ +#!/usr/bin/env python3 +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Run takeoff test on Copter. + +Warning - This is NOT production code; it's a simple demo of capability. +""" + +import math +import rclpy +import time +import errno + +from rclpy.node import Node +from builtin_interfaces.msg import Time +from ardupilot_msgs.msg import GlobalPosition +from geographic_msgs.msg import GeoPoseStamped +from geopy import distance +from geopy import point +from ardupilot_msgs.srv import ArmMotors +from ardupilot_msgs.srv import ModeSwitch +from ardupilot_msgs.srv import Takeoff + + + +COPTER_MODE_GUIDED = 4 + +TAKEOFF_ALT = 10.5 + +class CopterTakeoff(Node): + """Copter takeoff using guided control.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("copter_takeoff") + + self.declare_parameter("arm_topic", "/ap/arm_motors") + self._arm_topic = self.get_parameter("arm_topic").get_parameter_value().string_value + self._client_arm = self.create_client(ArmMotors, self._arm_topic) + while not self._client_arm.wait_for_service(timeout_sec=1.0): + self.get_logger().info('arm service not available, waiting again...') + + self.declare_parameter("mode_topic", "/ap/mode_switch") + self._mode_topic = self.get_parameter("mode_topic").get_parameter_value().string_value + self._client_mode_switch = self.create_client(ModeSwitch, self._mode_topic) + while not self._client_mode_switch.wait_for_service(timeout_sec=1.0): + self.get_logger().info('mode switch service not available, waiting again...') + + self.declare_parameter("takeoff_service", "/ap/experimental/takeoff") + self._takeoff_topic = self.get_parameter("takeoff_service").get_parameter_value().string_value + self._client_takeoff = self.create_client(Takeoff, self._takeoff_topic) + while not self._client_takeoff.wait_for_service(timeout_sec=1.0): + self.get_logger().info('takeoff service not available, waiting again...') + + self.declare_parameter("geopose_topic", "/ap/geopose/filtered") + self._geopose_topic = self.get_parameter("geopose_topic").get_parameter_value().string_value + qos = rclpy.qos.QoSProfile( + reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT, durability=rclpy.qos.DurabilityPolicy.VOLATILE, depth=1 + ) + + self._subscription_geopose = self.create_subscription(GeoPoseStamped, self._geopose_topic, self.geopose_cb, qos) + self._cur_geopose = GeoPoseStamped() + + def geopose_cb(self, msg: GeoPoseStamped): + """Process a GeoPose message.""" + stamp = msg.header.stamp + if stamp.sec: + self.get_logger().info("From AP : Geopose [sec:{}, nsec: {}]".format(stamp.sec, stamp.nanosec)) + + # Store current state + self._cur_geopose = msg + + + def arm(self): + req = ArmMotors.Request() + req.arm = True + future = self._client_arm.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def arm_with_timeout(self, timeout: rclpy.duration.Duration): + """Try to arm. Returns true on success, or false if arming fails or times out.""" + armed = False + start = self.get_clock().now() + while not armed and self.get_clock().now() - start < timeout: + armed = self.arm().result + time.sleep(1) + return armed + + def switch_mode(self, mode): + req = ModeSwitch.Request() + assert mode in [COPTER_MODE_GUIDED] + req.mode = mode + future = self._client_mode_switch.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def switch_mode_with_timeout(self, desired_mode: int, timeout: rclpy.duration.Duration): + """Try to switch mode. Returns true on success, or false if mode switch fails or times out.""" + is_in_desired_mode = False + start = self.get_clock().now() + while not is_in_desired_mode: + result = self.switch_mode(desired_mode) + # Handle successful switch or the case that the vehicle is already in expected mode + is_in_desired_mode = result.status or result.curr_mode == desired_mode + time.sleep(1) + + return is_in_desired_mode + + def takeoff(self, alt): + req = Takeoff.Request() + req.alt = alt + future = self._client_takeoff.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def takeoff_with_timeout(self, alt: int, timeout: rclpy.duration.Duration): + """Try to takeoff. Returns true on success, or false if takeoff fails or times out.""" + takeoff_success = False + start = self.get_clock().now() + while not takeoff_success: + result = self.takeoff(alt) + takeoff_success = result.status + time.sleep(1) + + return takeoff_success + + def get_cur_geopose(self): + """Return latest geopose.""" + return self._cur_geopose + +def main(args=None): + """Node entry point.""" + rclpy.init(args=args) + node = CopterTakeoff() + try: + if not node.switch_mode_with_timeout(COPTER_MODE_GUIDED, rclpy.duration.Duration(seconds=20)): + raise RuntimeError("Unable to switch to guided mode") + # Block till armed, which will wait for EKF3 to initialize + if not node.arm_with_timeout(rclpy.duration.Duration(seconds=30)): + raise RuntimeError("Unable to arm") + + # Block till in takeoff + if not node.takeoff_with_timeout(TAKEOFF_ALT, rclpy.duration.Duration(seconds=20)): + raise RuntimeError("Unable to takeoff") + + is_ascending_to_takeoff_alt = True + while is_ascending_to_takeoff_alt: + rclpy.spin_once(node) + time.sleep(1.0) + + is_ascending_to_takeoff_alt = node.get_cur_geopose().pose.position.altitude < TAKEOFF_ALT + + if is_ascending_to_takeoff_alt: + raise RuntimeError("Failed to reach takeoff altitude") + + except KeyboardInterrupt: + pass + + # Destroy the node explicitly. + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py index 27de6f272f2ed8..7db9aa9be5eee1 100755 --- a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py @@ -33,6 +33,7 @@ from geopy import point from ardupilot_msgs.srv import ArmMotors from ardupilot_msgs.srv import ModeSwitch +from geographic_msgs.msg import GeoPointStamped PLANE_MODE_TAKEOFF = 13 @@ -78,6 +79,15 @@ def __init__(self): self._subscription_geopose = self.create_subscription(GeoPoseStamped, self._geopose_topic, self.geopose_cb, qos) self._cur_geopose = GeoPoseStamped() + + self.declare_parameter("goal_topic", "/ap/goal_lla") + self._goal_topic = self.get_parameter("goal_topic").get_parameter_value().string_value + qos = rclpy.qos.QoSProfile( + reliability=rclpy.qos.ReliabilityPolicy.RELIABLE, durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, depth=1 + ) + + self._subscription_goal = self.create_subscription(GeoPointStamped, self._goal_topic, self.goal_cb, qos) + self._cur_goal = GeoPointStamped() def geopose_cb(self, msg: GeoPoseStamped): """Process a GeoPose message.""" @@ -87,6 +97,15 @@ def geopose_cb(self, msg: GeoPoseStamped): # Store current state self._cur_geopose = msg + + def goal_cb(self, msg: GeoPointStamped): + """Process a Goal message.""" + stamp = msg.header.stamp + self.get_logger().info("From AP : Goal [sec:{}, nsec: {}, lat:{} lon:{}]" + .format(stamp.sec, stamp.nanosec,msg.position.latitude, msg.position.longitude)) + + # Store current state + self._cur_goal = msg def arm(self): req = ArmMotors.Request() @@ -127,6 +146,10 @@ def switch_mode_with_timeout(self, desired_mode: int, timeout: rclpy.duration.Du def get_cur_geopose(self): """Return latest geopose.""" return self._cur_geopose + + def get_cur_goal(self): + """Return latest goal.""" + return self._cur_goal def send_goal_position(self, goal_global_pos): """Send goal position. Must be in guided for this to work.""" @@ -148,6 +171,15 @@ def achieved_goal(goal_global_pos, cur_geopose): print(f"Goal is {euclidian_distance} meters away") return euclidian_distance < 150 +def going_to_goal(goal_global_pos, cur_goal): + p1 = (goal_global_pos.latitude, goal_global_pos.longitude, goal_global_pos.altitude) + cur_pos_lla = cur_goal.position + p2 = (cur_pos_lla.latitude, cur_pos_lla.longitude, cur_pos_lla.altitude) + + flat_distance = distance.distance(p1[:2], p2[:2]).m + euclidian_distance = math.sqrt(flat_distance**2 + (p2[2] - p1[2]) ** 2) + print(f"Commanded and received goal are {euclidian_distance} meters away") + return euclidian_distance < 1 def main(args=None): """Node entry point.""" @@ -191,11 +223,15 @@ def main(args=None): start = node.get_clock().now() has_achieved_goal = False + is_going_to_goal = False while not has_achieved_goal and node.get_clock().now() - start < rclpy.duration.Duration(seconds=120): rclpy.spin_once(node) + is_going_to_goal = going_to_goal(goal_pos, node.get_cur_goal()) has_achieved_goal = achieved_goal(goal_pos, node.get_cur_geopose()) time.sleep(1.0) + if not is_going_to_goal: + raise RuntimeError("Unable to go to goal location") if not has_achieved_goal: raise RuntimeError("Unable to achieve goal location") diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/pre_arm_check_service.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/pre_arm_check_service.py new file mode 100644 index 00000000000000..e835209015fa43 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/pre_arm_check_service.py @@ -0,0 +1,78 @@ +#!/usr/bin/env python3 +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Run pre_arm check test on Copter. + +Warning - This is NOT production code; it's a simple demo of capability. +""" + +import math +import rclpy +import time +import errno + +from rclpy.node import Node +from builtin_interfaces.msg import Time +from std_srvs.srv import Trigger + + +class CopterPreArm(Node): + """Check Prearm Service.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("copter_prearm") + + self.declare_parameter("pre_arm_service", "/ap/prearm_check") + self._prearm_service = self.get_parameter("pre_arm_service").get_parameter_value().string_value + self._client_prearm = self.create_client(Trigger, self._prearm_service) + while not self._client_prearm.wait_for_service(timeout_sec=1.0): + self.get_logger().info('prearm service not available, waiting again...') + + def prearm(self): + req = Trigger.Request() + future = self._client_prearm.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def prearm_with_timeout(self, timeout: rclpy.duration.Duration): + """Check if armable. Returns true on success, or false if arming will fail or times out.""" + armable = False + start = self.get_clock().now() + while not armable and self.get_clock().now() - start < timeout: + armable = self.prearm().success + time.sleep(1) + return armable + +def main(args=None): + """Node entry point.""" + rclpy.init(args=args) + node = CopterPreArm() + try: + # Block till armed, which will wait for EKF3 to initialize + if not node.prearm_with_timeout(rclpy.duration.Duration(seconds=30)): + raise RuntimeError("Vehicle not armable") + except KeyboardInterrupt: + pass + + # Destroy the node explicitly. + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml b/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml index 67d472c34fb946..0af1702d4fdc17 100644 --- a/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml +++ b/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml @@ -3,7 +3,6 @@ middleware: dds serial_baud: 115200 serial_device: ./dev/ttyROS0 - refs_file: ./src/ardupilot/libraries/AP_DDS/dds_xrce_profile.xml /ardupilot: sim_vehicle_cmd: ./src/ardupilot/Tools/autotest/sim_vehicle.py diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index b4cc9fa2a0e358..c3eb345058959e 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -27,12 +27,17 @@ ament_lint_auto ardupilot_msgs ardupilot_sitl + builtin_interfaces + geographic_msgs launch launch_pytest + micro_ros_agent launch_ros micro_ros_msgs python3-pytest rclpy + sensor_msgs + python3-scipy ament_python diff --git a/Tools/ros2/ardupilot_dds_tests/setup.py b/Tools/ros2/ardupilot_dds_tests/setup.py index bbe11e6a5c8123..bf9e0577af6a92 100644 --- a/Tools/ros2/ardupilot_dds_tests/setup.py +++ b/Tools/ros2/ardupilot_dds_tests/setup.py @@ -26,6 +26,8 @@ 'console_scripts': [ "time_listener = ardupilot_dds_tests.time_listener:main", "plane_waypoint_follower = ardupilot_dds_tests.plane_waypoint_follower:main", + "pre_arm_check = ardupilot_dds_tests.pre_arm_check_service:main", + "copter_takeoff = ardupilot_dds_tests.copter_takeoff:main", ], }, ) diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py index f1a1a4532ea243..13940c4a86adf6 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py @@ -74,13 +74,6 @@ def micro_ros_agent_serial(device_dir): LaunchDescriptionSource(mra_ld), launch_arguments={ "transport": "serial", - "refs": PathJoinSubstitution( - [ - FindPackageShare("ardupilot_sitl"), - "config", - "dds_xrce_profile.xml", - ] - ), "baudrate": "115200", "device": str(tty0), }.items(), @@ -97,13 +90,6 @@ def micro_ros_agent_udp(): LaunchDescriptionSource(mra_ld), launch_arguments={ "transport": "udp4", - "refs": PathJoinSubstitution( - [ - FindPackageShare("ardupilot_sitl"), - "config", - "dds_xrce_profile.xml", - ] - ), }.items(), ) yield ld, mra_actions diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py index f8c8a5efb881dd..33363f42e24069 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py @@ -24,7 +24,6 @@ # # default params # self.mra_serial_device = f"./dev/ttyROS0" # self.mra_serial_baud = 115200 -# self.mra_refs_file = "dds_xrce_profile.xml" # # self.ap_sim_vehicle_cmd = "sim_vehicle.py" # self.ap_serial_device = f"./dev/ttyROS1" diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_battery_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_battery_msg_received.py new file mode 100644 index 00000000000000..50a5a517c1df5b --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_battery_msg_received.py @@ -0,0 +1,173 @@ +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Bring up ArduPilot SITL and check the BatteryState message is being published. + +Checks whether a message is received and that only frame_id = '0' is received, +as SITL has only one battery available. + +colcon test --packages-select ardupilot_dds_tests \ +--event-handlers=console_cohesion+ --pytest-args -k test_battery_msg_received + +""" + +import launch_pytest +import pytest +import rclpy +import rclpy.node +import threading + +from launch import LaunchDescription + +from launch_pytest.tools import process as process_tools + +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import QoSHistoryPolicy + +from sensor_msgs.msg import BatteryState + +TOPIC = "ap/battery" + + +class BatteryListener(rclpy.node.Node): + """Subscribe to BatteryState messages.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("battery_listener") + self.msg_event_object = threading.Event() + self.frame_id_correct_object = threading.Event() + self.frame_id_incorrect_object = threading.Event() + + # Declare and acquire `topic` parameter + self.declare_parameter("topic", TOPIC) + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + def start_subscriber(self): + """Start the subscriber.""" + qos_profile = QoSProfile( + reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ) + + self.subscription = self.create_subscription(BatteryState, self.topic, self.subscriber_callback, qos_profile) + + # Add a spin thread. + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, msg): + """Process a BatteryState message.""" + self.msg_event_object.set() + + self.get_logger().info("From AP : ID {} Voltage {}".format(msg.header.frame_id, msg.voltage)) + + if msg.header.frame_id == '0': + self.frame_id_correct_object.set() + + if msg.header.frame_id == '1': + self.frame_id_incorrect_object.set() + + +@launch_pytest.fixture +def launch_sitl_copter_dds_serial(sitl_copter_dds_serial): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_serial + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial) +def test_dds_serial_battery_msg_recv(launch_context, launch_sitl_copter_dds_serial): + """Test battery messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_serial + virtual_ports = actions["virtual_ports"].action + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, virtual_ports, timeout=2) + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = BatteryListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + battery_correct_flag = node.frame_id_correct_object.wait(timeout=10.0) + assert battery_correct_flag, f"Did not receive correct battery ID." + battery_incorrect_flag = not node.frame_id_incorrect_object.wait(timeout=10.0) + assert battery_correct_flag, f"Did received incorrect battery ID." + finally: + rclpy.shutdown() + yield + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_battery_msg_recv(launch_context, launch_sitl_copter_dds_udp): + """Test battery messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = BatteryListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + battery_correct_flag = node.frame_id_correct_object.wait(timeout=10.0) + assert battery_correct_flag, f"Did not receive correct battery ID." + battery_incorrect_flag = not node.frame_id_incorrect_object.wait(timeout=10.0) + assert battery_correct_flag, f"Did received incorrect battery ID." + + finally: + rclpy.shutdown() + yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py new file mode 100644 index 00000000000000..879a383293c752 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_geopose_msg_received.py @@ -0,0 +1,216 @@ +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Bring up ArduPilot SITL and check the GeoPoseStamped message is being published. + +colcon test --packages-select ardupilot_dds_tests \ +--event-handlers=console_cohesion+ --pytest-args -k test_geopose_msg_received + +""" + +import launch_pytest +import math +import pytest +import rclpy +import rclpy.node +from scipy.spatial.transform import Rotation as R +import threading + +from launch import LaunchDescription + +from launch_pytest.tools import process as process_tools + +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import QoSHistoryPolicy + +from geographic_msgs.msg import GeoPoseStamped + +TOPIC = "ap/geopose/filtered" +# Copied from locations.txt +CMAC_LAT = -35.363261 +CMAC_LON = 149.165230 +CMAC_ABS_ALT = 584 +CMAC_HEADING = 353 + + +def ros_quat_to_heading_deg(quat): + # By default, scipy follows scalar-last order – (x, y, z, w) + rot = R.from_quat([quat.x, quat.y, quat.z, quat.w]) + r, p, y = rot.as_euler(seq="xyz", degrees=True) + return y + + +def validate_position_cmac(position): + """Return true if the vehicle is at CMAC.""" + LAT_LON_TOL = 1e-5 + return ( + math.isclose(position.latitude, CMAC_LAT, abs_tol=LAT_LON_TOL) + and math.isclose(position.longitude, CMAC_LON, abs_tol=LAT_LON_TOL) + and math.isclose(position.altitude, CMAC_ABS_ALT, abs_tol=1.0) + ) + +def wrap_360(angle): + if angle > 360: + angle -= 360.0 + return wrap_360(angle) + if angle < 0: + angle += 360.0 + return wrap_360(angle) + return angle + +def validate_heading_cmac(orientation): + """ + Return true if the vehicle is facing the right way for CMAC. + + Per ROS REP-103, the quaternion should report 0 when the vehicle faces east, + and 90 degrees when facing north. + Because CMAC is NNW, we expect ~97 degees. + See this PR for more info: + * https://github.com/ros-infrastructure/rep/pull/407 + """ + # The following converts from compass bearing (locations.txt) to REP-103 heading. + CMAC_YAW_ENU_REP103 = wrap_360(-1 * CMAC_HEADING) + 90 + return math.isclose(ros_quat_to_heading_deg(orientation), CMAC_YAW_ENU_REP103, abs_tol=5) + + +class GeoPoseListener(rclpy.node.Node): + """Subscribe to GeoPoseStamped messages.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("geopose_listener") + self.msg_event_object = threading.Event() + self.position_correct_event_object = threading.Event() + self.orientation_event_object = threading.Event() + + # Declare and acquire `topic` parameter + self.declare_parameter("topic", TOPIC) + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + def start_subscriber(self): + """Start the subscriber.""" + qos_profile = QoSProfile( + reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ) + + self.subscription = self.create_subscription(GeoPoseStamped, self.topic, self.subscriber_callback, qos_profile) + + # Add a spin thread. + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def subscriber_callback(self, msg): + """Process a GeoPoseStamped message.""" + self.msg_event_object.set() + + position = msg.pose.position + + self.get_logger().info("From AP : Position [lat:{}, lon: {}]".format(position.latitude, position.longitude)) + + if validate_position_cmac(msg.pose.position): + self.position_correct_event_object.set() + + if validate_heading_cmac(msg.pose.orientation): + self.orientation_event_object.set() + + +@launch_pytest.fixture +def launch_sitl_copter_dds_serial(sitl_copter_dds_serial): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_serial + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial) +def test_dds_serial_geopose_msg_recv(launch_context, launch_sitl_copter_dds_serial): + """Test position messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_serial + virtual_ports = actions["virtual_ports"].action + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, virtual_ports, timeout=2) + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = GeoPoseListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + pose_correct_flag = node.position_correct_event_object.wait(timeout=10.0) + assert pose_correct_flag, f"Did not receive correct position." + orientation_correct_flag = node.orientation_event_object.wait(timeout=10.0) + assert orientation_correct_flag, f"Did not receive correct orientation." + finally: + rclpy.shutdown() + yield + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_geopose_msg_recv(launch_context, launch_sitl_copter_dds_udp): + """Test position messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = GeoPoseListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." + pose_correct_flag = node.position_correct_event_object.wait(timeout=10.0) + assert pose_correct_flag, f"Did not receive correct position." + finally: + rclpy.shutdown() + yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_joy_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_joy_msg_received.py new file mode 100644 index 00000000000000..9df6c37145fcee --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_joy_msg_received.py @@ -0,0 +1,229 @@ +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Bring up ArduPilot SITL and check the Joy message is being published. + +Arms the copter and commands a throttle up. Check that the vehicle climbs. + +colcon test --packages-select ardupilot_dds_tests \ +--event-handlers=console_cohesion+ --pytest-args -k test_joy_msg_received + +""" + +import rclpy +import time +import launch_pytest +from rclpy.node import Node +from builtin_interfaces.msg import Time +from geographic_msgs.msg import GeoPoseStamped +from geometry_msgs.msg import TwistStamped +from geopy import point +from ardupilot_msgs.srv import ArmMotors +from ardupilot_msgs.srv import ModeSwitch +from sensor_msgs.msg import Joy +from scipy.spatial.transform import Rotation as R +import pytest +from launch_pytest.tools import process as process_tools +from launch import LaunchDescription +import threading + +GUIDED = 4 +LOITER = 5 + +FRAME_GLOBAL_INT = 5 + +# Hard code some known locations +# Note - Altitude in geopy is in km! +GRAYHOUND_TRACK = point.Point(latitude=-35.345996, longitude=149.159017, altitude=0.575) +CMAC = point.Point(latitude=-35.3627010, longitude=149.1651513, altitude=0.585) + + +class PlaneFbwbJoyControl(Node): + """Plane follow waypoints using guided control.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("copter_joy_listener") + + self.arming_event_object = threading.Event() + self.mode_event_object = threading.Event() + self.climbing_event_object = threading.Event() + + self._client_arm = self.create_client(ArmMotors, "/ap/arm_motors") + + self._client_mode_switch = self.create_client(ModeSwitch, "/ap/mode_switch") + + self._joy_pub = self.create_publisher(Joy, "/ap/joy", 1) + + # Create subscriptions after services are up + qos = rclpy.qos.QoSProfile( + reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT, durability=rclpy.qos.DurabilityPolicy.VOLATILE, depth=1 + ) + self._subscription_geopose = self.create_subscription(GeoPoseStamped, "/ap/geopose/filtered", self.geopose_cb, qos) + self._cur_geopose = GeoPoseStamped() + + self._subscription_twist = self.create_subscription(TwistStamped, "/ap/twist/filtered", self.twist_cb, qos) + self._climb_rate = 0.0 + + # Add a spin thread. + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def geopose_cb(self, msg: GeoPoseStamped): + """Process a GeoPose message.""" + stamp = msg.header.stamp + if stamp.sec: + # Store current state + self._cur_geopose = msg + + def twist_cb(self, msg: TwistStamped): + """Process a Twist message.""" + linear = msg.twist.linear + self._climb_rate = linear.z + + def arm(self): + req = ArmMotors.Request() + req.arm = True + future = self._client_arm.call_async(req) + time.sleep(0.2) + try: + return future.result().result + except: + return False + + def arm_with_timeout(self, timeout: rclpy.duration.Duration): + """Try to arm. Returns true on success, or false if arming fails or times out.""" + armed = False + start = self.get_clock().now() + while not armed and self.get_clock().now() - start < timeout: + armed = self.arm() + time.sleep(1) + return armed + + def switch_mode(self, mode): + req = ModeSwitch.Request() + req.mode = mode + future = self._client_mode_switch.call_async(req) + time.sleep(1) + try: + return future.result().status and future.result().curr_mode == mode + except: + return False + + def switch_mode_with_timeout(self, desired_mode: int, timeout: rclpy.duration.Duration): + """Try to switch mode. Returns true on success, or false if mode switch fails or times out.""" + is_in_desired_mode = False + start = self.get_clock().now() + while not is_in_desired_mode: + is_in_desired_mode = self.switch_mode(desired_mode) + time.sleep(1) + + return is_in_desired_mode + + def get_cur_geopose(self): + """Return latest geopose.""" + return self._cur_geopose + + def send_joy_value(self, joy_val): + self._joy_pub.publish(joy_val) + + #-------------- PROCESSES ----------------- + def process_arm(self): + if self.arm_with_timeout(rclpy.duration.Duration(seconds=30)): + self.arming_event_object.set() + + def start_arm(self): + self.arm_thread = threading.Thread(target=self.process_arm) + self.arm_thread.start() + + def process_climb(self): + joy_msg = Joy() + joy_msg.axes.append(0.0) + joy_msg.axes.append(0.0) + joy_msg.axes.append(0.8) #- straight up + joy_msg.axes.append(0.0) + + while True: + self.send_joy_value(joy_msg) + self.arm() #- Keep the system armed (sometimes it disarms and the test fails) + time.sleep(0.1) + self.get_logger().info("From AP : Climb rate {}".format(self._climb_rate)) + if self._climb_rate > 0.5: + self.climbing_event_object.set() + return + + def climb(self): + self.climb_thread = threading.Thread(target=self.process_climb) + self.climb_thread.start() + + def arm_and_takeoff_process(self): + self.process_arm() + self.climb() + + def arm_and_takeoff(self): + self.climb_thread = threading.Thread(target=self.arm_and_takeoff_process) + self.climb_thread.start() + +@launch_pytest.fixture +def launch_sitl_copter_dds_serial(sitl_copter_dds_serial): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_serial + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_joy_msg_recv(launch_context, launch_sitl_copter_dds_udp): + """Test joy messages are published by AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = PlaneFbwbJoyControl() + node.arm_and_takeoff() + climb_flag = node.climbing_event_object.wait(10) + assert climb_flag, "Could not climb" + finally: + rclpy.shutdown() + yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py index 05ff1343d271df..b4c3c716e06828 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py @@ -30,9 +30,11 @@ from sensor_msgs.msg import NavSatFix +TOPIC = "ap/navsat" + class NavSatFixListener(rclpy.node.Node): - """Subscribe to NavSatFix messages on /ap/navsat/navsat0.""" + """Subscribe to NavSatFix messages.""" def __init__(self): """Initialise the node.""" @@ -40,7 +42,7 @@ def __init__(self): self.msg_event_object = threading.Event() # Declare and acquire `topic` parameter - self.declare_parameter("topic", "ap/navsat/navsat0") + self.declare_parameter("topic", TOPIC) self.topic = self.get_parameter("topic").get_parameter_value().string_value def start_subscriber(self): @@ -117,7 +119,7 @@ def test_dds_serial_navsat_msg_recv(launch_context, launch_sitl_copter_dds_seria node = NavSatFixListener() node.start_subscriber() msgs_received_flag = node.msg_event_object.wait(timeout=10.0) - assert msgs_received_flag, "Did not receive 'ap/navsat/navsat0' msgs." + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." finally: rclpy.shutdown() yield @@ -141,7 +143,7 @@ def test_dds_udp_navsat_msg_recv(launch_context, launch_sitl_copter_dds_udp): node = NavSatFixListener() node.start_subscriber() msgs_received_flag = node.msg_event_object.wait(timeout=10.0) - assert msgs_received_flag, "Did not receive 'ap/navsat/navsat0' msgs." + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." finally: rclpy.shutdown() yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_parameter_service.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_parameter_service.py new file mode 100644 index 00000000000000..8e6e95601c971a --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_parameter_service.py @@ -0,0 +1,197 @@ +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Bring up ArduPilot SITL and check that the get/set_parameters services are up and running. + +Checks whether a parameter is changed using service call. + +colcon test --packages-select ardupilot_dds_tests \ +--event-handlers=console_cohesion+ --pytest-args -k test_parameter_service + +""" + +import launch_pytest +import pytest +import rclpy +import rclpy.node +import threading +import time + +from launch import LaunchDescription + +from launch_pytest.tools import process as process_tools + +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.qos import QoSHistoryPolicy + +from rcl_interfaces.srv import GetParameters +from rcl_interfaces.srv import SetParameters +from rcl_interfaces.msg import Parameter + +# Enums for parameter type +PARAMETER_NOT_SET = 0 +PARAMETER_INTEGER = 2 +PARAMETER_DOUBLE = 3 + + +class ParameterClient(rclpy.node.Node): + """Send GetParameters and SetParameters Requests.""" + + def __init__(self): + """Initialize the node.""" + super().__init__('parameter_client') + self.get_param_event_object = threading.Event() + self.set_param_event_object = threading.Event() + self.set_correct_object = threading.Event() + + def start_client(self): + """Start the parameter client.""" + qos_profile = QoSProfile( + reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ) + + # Define clients for getting and setting parameter + self.get_cli = self.create_client(GetParameters, 'ap/get_parameters') + while not self.get_cli.wait_for_service(timeout_sec=1.0): + self.get_logger().info('GetParameters service not available, waiting again...') + + self.set_cli = self.create_client(SetParameters, 'ap/set_parameters') + while not self.set_cli.wait_for_service(timeout_sec=1.0): + self.get_logger().info('SetParameters service not availabel, waiting again...') + + # Add a spin thread + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def send_get_param_req(self, param_name): + self.get_req = GetParameters.Request() + self.get_req.names.append(param_name) + + self.get_future = self.get_cli.call_async(self.get_req) + while not self.get_future.done(): + self.get_logger().info("Waiting for GetParameters service response...") + time.sleep(0.1) + + resp = self.get_future.result() + value = resp.values[0] + + if value.type != PARAMETER_NOT_SET: + self.get_param_event_object.set() + + def send_set_param_req(self, param_name, param_value, param_type): + self.set_req = SetParameters.Request() + param_update = Parameter() + param_update.name = param_name + param_update.value.type = param_type + if param_type == PARAMETER_INTEGER: + param_update.value.integer_value = int(param_value) + else: + param_update.value.double_value = float(param_value) + + self.set_req.parameters.append(param_update) + + self.desired_value = param_value + get_response = self.get_future.result() + initial_value = get_response.values[0] + + if initial_value.type == PARAMETER_INTEGER: + self.param_value = initial_value.integer_value + elif initial_value.type == PARAMETER_DOUBLE: + self.param_value = initial_value.double_value + else: + self.param_value = 'nan' + + self.set_future = self.set_cli.call_async(self.set_req) + + while not self.set_future.done(): + self.get_logger().info("Waiting for SetParameters service response...") + time.sleep(0.1) + + if self.set_future.done(): + response = self.set_future.result() + if response.results[0].successful: + self.set_param_event_object.set() + + def check_param_change(self): + param_name = self.set_req.parameters[0].name + + self.send_get_param_req(param_name) + + get_response = self.get_future.result() + new_value = get_response.values[0] + + if new_value.type == PARAMETER_INTEGER: + updated_value = new_value.integer_value + elif new_value.type == PARAMETER_DOUBLE: + updated_value = new_value.double_value + else: + updated_value = 'nan' + + if updated_value == self.desired_value: + self.set_correct_object.set() + + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_parameter_services(launch_context, launch_sitl_copter_dds_udp): + """Test Get/Set parameter services broadcast by AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = ParameterClient() + node.start_client() + parameter_name = "LOIT_SPEED" + param_change_value = 1250 + param_type = PARAMETER_DOUBLE + node.send_get_param_req(parameter_name) + get_param_received_flag = node.get_param_event_object.wait(timeout=10.0) + assert get_param_received_flag, f"Did not get '{parameter_name}' param." + node.send_set_param_req(parameter_name, param_change_value, param_type) + set_param_received_flag = node.set_param_event_object.wait(timeout=10.0) + assert set_param_received_flag, f"Could not set '{parameter_name}' to '{param_change_value}'" + node.check_param_change() + set_param_changed_flag = node.set_correct_object.wait(timeout=10.0) + assert set_param_changed_flag, f"Did not confirm '{parameter_name}' value change" + + finally: + rclpy.shutdown() + yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_prearm_service.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_prearm_service.py new file mode 100644 index 00000000000000..f081d5cc1cfe6f --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_prearm_service.py @@ -0,0 +1,166 @@ +# Copyright 2023 ArduPilot.org. +# +# 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 . + +""" +Bring up ArduPilot SITL and check whether the vehicle can be armed. + +colcon test --executor sequential --parallel-workers 0 --base-paths src/ardupilot \ + --event-handlers=console_cohesion+ --packages-select ardupilot_dds_tests \ + --pytest-args -k test_prearm_service + +""" + +import launch_pytest +import math +import time +import pytest +import rclpy +import rclpy.node +import threading + +from launch import LaunchDescription + +from launch_pytest.tools import process as process_tools +from std_srvs.srv import Trigger + + +SERVICE = "/ap/prearm_check" + +class PreamService(rclpy.node.Node): + def __init__(self): + """Initialise the node.""" + super().__init__("prearm_client") + self.service_available_object = threading.Event() + self.is_armable_object = threading.Event() + self._client_prearm = self.create_client(Trigger, "/ap/prearm_check") + + def start_node(self): + # Add a spin thread. + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) + self.ros_spin_thread.start() + + def prearm_check(self): + req = Trigger.Request() + future = self._client_prearm.call_async(req) + time.sleep(0.2) + try: + return future.result().success + except Exception as e: + print(e) + return False + + def prearm_with_timeout(self, timeout: rclpy.duration.Duration): + result = False + start = self.get_clock().now() + while not result and self.get_clock().now() - start < timeout: + result = self.prearm_check() + time.sleep(1) + return result + + def process_prearm(self): + if self.prearm_with_timeout(rclpy.duration.Duration(seconds=30)): + self.is_armable_object.set() + + def start_prearm(self): + try: + self.prearm_thread.stop() + except: + print("start_prearm not started yet") + self.prearm_thread = threading.Thread(target=self.process_prearm) + self.prearm_thread.start() + + + + +@launch_pytest.fixture +def launch_sitl_copter_dds_serial(sitl_copter_dds_serial): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_serial + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@launch_pytest.fixture +def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): + """Fixture to create the launch description.""" + sitl_ld, sitl_actions = sitl_copter_dds_udp + + ld = LaunchDescription( + [ + sitl_ld, + launch_pytest.actions.ReadyToTest(), + ] + ) + actions = sitl_actions + yield ld, actions + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial) +def test_dds_serial_prearm_service_call(launch_context, launch_sitl_copter_dds_serial): + """Test prearm service AP_DDS.""" + _, actions = launch_sitl_copter_dds_serial + virtual_ports = actions["virtual_ports"].action + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, virtual_ports, timeout=2) + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = PreamService() + node.start_node() + node.start_prearm() + is_armable_flag = node.is_armable_object.wait(timeout=25.0) + assert is_armable_flag, f"Vehicle not armable." + finally: + rclpy.shutdown() + yield + + +@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) +def test_dds_udp_prearm_service_call(launch_context, launch_sitl_copter_dds_udp): + """Test prearm service AP_DDS.""" + _, actions = launch_sitl_copter_dds_udp + micro_ros_agent = actions["micro_ros_agent"].action + mavproxy = actions["mavproxy"].action + sitl = actions["sitl"].action + + # Wait for process to start. + process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2) + process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2) + process_tools.wait_for_start_sync(launch_context, sitl, timeout=2) + + rclpy.init() + try: + node = PreamService() + node.start_node() + node.start_prearm() + is_armable_flag = node.is_armable_object.wait(timeout=25.0) + assert is_armable_flag, f"Vehicle not armable." + finally: + rclpy.shutdown() + yield diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py index 5ffa1de6e0b11c..dc33b88c0e9ec3 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py @@ -26,9 +26,11 @@ from builtin_interfaces.msg import Time +TOPIC = "ap/time" + class TimeListener(rclpy.node.Node): - """Subscribe to Time messages on /ap/time.""" + """Subscribe to Time messages.""" def __init__(self): """Initialise the node.""" @@ -36,7 +38,7 @@ def __init__(self): self.msg_event_object = threading.Event() # Declare and acquire `topic` parameter. - self.declare_parameter("topic", "ap/time") + self.declare_parameter("topic", TOPIC) self.topic = self.get_parameter("topic").get_parameter_value().string_value def start_subscriber(self): @@ -89,7 +91,7 @@ def launch_sitl_copter_dds_udp(sitl_copter_dds_udp): @pytest.mark.launch(fixture=launch_sitl_copter_dds_serial) def test_dds_serial_time_msg_recv(launch_context, launch_sitl_copter_dds_serial): - """Test /ap/time is published by AP_DDS.""" + """Test Time is published by AP_DDS.""" _, actions = launch_sitl_copter_dds_serial virtual_ports = actions["virtual_ports"].action micro_ros_agent = actions["micro_ros_agent"].action @@ -107,7 +109,7 @@ def test_dds_serial_time_msg_recv(launch_context, launch_sitl_copter_dds_serial) node = TimeListener() node.start_subscriber() msgs_received_flag = node.msg_event_object.wait(timeout=10.0) - assert msgs_received_flag, "Did not receive 'ROS_Time' msgs." + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." finally: rclpy.shutdown() yield @@ -115,7 +117,7 @@ def test_dds_serial_time_msg_recv(launch_context, launch_sitl_copter_dds_serial) @pytest.mark.launch(fixture=launch_sitl_copter_dds_udp) def test_dds_udp_time_msg_recv(launch_context, launch_sitl_copter_dds_udp): - """Test /ap/time is published by AP_DDS.""" + """Test Time is published by AP_DDS.""" _, actions = launch_sitl_copter_dds_udp micro_ros_agent = actions["micro_ros_agent"].action mavproxy = actions["mavproxy"].action @@ -131,7 +133,7 @@ def test_dds_udp_time_msg_recv(launch_context, launch_sitl_copter_dds_udp): node = TimeListener() node.start_subscriber() msgs_received_flag = node.msg_event_object.wait(timeout=10.0) - assert msgs_received_flag, "Did not receive 'ROS_Time' msgs." + assert msgs_received_flag, f"Did not receive '{TOPIC}' msgs." finally: rclpy.shutdown() yield diff --git a/Tools/ros2/ardupilot_msgs/CMakeLists.txt b/Tools/ros2/ardupilot_msgs/CMakeLists.txt index d066a2d32b2e43..767b89a89b7691 100644 --- a/Tools/ros2/ardupilot_msgs/CMakeLists.txt +++ b/Tools/ros2/ardupilot_msgs/CMakeLists.txt @@ -14,8 +14,10 @@ find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "msg/GlobalPosition.msg" + "msg/Status.msg" "srv/ArmMotors.srv" "srv/ModeSwitch.srv" + "srv/Takeoff.srv" DEPENDENCIES geometry_msgs std_msgs ADD_LINTER_TESTS ) diff --git a/Tools/ros2/ardupilot_msgs/msg/Status.msg b/Tools/ros2/ardupilot_msgs/msg/Status.msg new file mode 100644 index 00000000000000..38ff02804d12c0 --- /dev/null +++ b/Tools/ros2/ardupilot_msgs/msg/Status.msg @@ -0,0 +1,27 @@ +std_msgs/Header header + +uint8 APM_ROVER = 1 +uint8 APM_ARDUCOPTER = 2 +uint8 APM_ARDUPLANE = 3 +uint8 APM_ANTENNATRACKER = 4 +uint8 APM_UNKNOWN = 5 +uint8 APM_REPLAY = 6 +uint8 APM_ARDUSUB = 7 +uint8 APM_IOFIRMWARE = 8 +uint8 APM_AP_PERIPH = 9 +uint8 APM_AP_DAL_STANDALONE = 10 +uint8 APM_AP_BOOTLOADER = 11 +uint8 APM_BLIMP = 12 +uint8 APM_HELI = 13 +uint8 vehicle_type # From AP_Vehicle_Type.h + +bool armed # true if vehicle is armed. +uint8 mode # Vehicle mode, enum depending on vehicle type. +bool flying # True if flying/driving/diving/tracking. +bool external_control # True is external control is enabled. + +uint8 FS_RADIO = 21 +uint8 FS_BATTERY = 22 +uint8 FS_GCS = 23 +uint8 FS_EKF = 24 +uint8[] failsafe # Array containing all active failsafe. diff --git a/Tools/ros2/ardupilot_msgs/srv/Takeoff.srv b/Tools/ros2/ardupilot_msgs/srv/Takeoff.srv new file mode 100644 index 00000000000000..05e5de8bd5a34e --- /dev/null +++ b/Tools/ros2/ardupilot_msgs/srv/Takeoff.srv @@ -0,0 +1,10 @@ + +# This service requests the vehicle to takeoff + +# alt : Set the takeoff altitude above home or above terrain(in case of rangefinder) + +float32 alt +--- +# status : True if the request for mode switch was successful, False otherwise + +bool status diff --git a/Tools/ros2/ardupilot_sitl/CMakeLists.txt b/Tools/ros2/ardupilot_sitl/CMakeLists.txt index 83a30907c549fd..5759fca6108e7d 100644 --- a/Tools/ros2/ardupilot_sitl/CMakeLists.txt +++ b/Tools/ros2/ardupilot_sitl/CMakeLists.txt @@ -18,6 +18,9 @@ option(ARDUPILOT_DISABLE_WATCHDOG "Build with watchdog disabled" OFF) option(ARDUPILOT_ENABLE_DDS "Enable the DDS client" ON) option(ARDUPILOT_ENABLE_NETWORKING_TESTS "Enable the networking test code" OFF) option(ARDUPILOT_ENABLE_PPP "Enable PPP networking" OFF) +set(ARDUPILOT_WAF_CONFIGURE_ARGS "" CACHE STRING "Arbitrary waf configure arguments") +set(ARDUPILOT_WAF_BUILD_ARGS "" CACHE STRING "Arbitrary waf build arguments") + # NOTE: look for `waf` and set source and build directories to top level. # ${PROJECT_SOURCE_DIR} = ./Tools/ros2/ardupilot @@ -34,7 +37,7 @@ set(WAF_DISABLE_SCRIPTING $<$:"--disable-sc set(WAF_DISABLE_WATCHDOG $<$:"--disable-watchdog">) set(WAF_ENABLE_DDS $<$:"--enable-dds">) set(WAF_ENABLE_NETWORKING_TESTS $<$:"--enable-networking-tests">) -set(WAF_ENABLE_PPP $<$:"--enable-ppp">) +set(WAF_ENABLE_PPP $<$:"--enable-PPP">) add_custom_target(ardupilot_configure ALL ${WAF_COMMAND} configure --board sitl @@ -45,11 +48,12 @@ add_custom_target(ardupilot_configure ALL ${WAF_ENABLE_DDS} ${WAF_ENABLE_NETWORKING_TESTS} ${WAF_ENABLE_PPP} + ${ARDUPILOT_WAF_CONFIGURE_ARGS} WORKING_DIRECTORY ${ARDUPILOT_ROOT} ) add_custom_target(ardupilot_build ALL - ${WAF_COMMAND} build --enable-dds ${WAF_CONFIG} + ${WAF_COMMAND} build --enable-dds ${WAF_CONFIG} ${ARDUPILOT_WAF_BUILD_ARGS} WORKING_DIRECTORY ${ARDUPILOT_ROOT} ) add_dependencies(ardupilot_build ardupilot_configure) @@ -81,12 +85,6 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME}/ ) -# Install DDS profile. -install(FILES - ${ARDUPILOT_ROOT}/libraries/AP_DDS/dds_xrce_profile.xml - DESTINATION share/${PROJECT_NAME}/config -) - # Install additional default params. install(DIRECTORY config/default_params @@ -99,6 +97,12 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME}/config/ ) +# Install additional autotest model params. +install(DIRECTORY + ${ARDUPILOT_ROOT}/Tools/autotest/models + DESTINATION share/${PROJECT_NAME}/config/ +) + # Install Python package. ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR src/${PROJECT_NAME} diff --git a/Tools/ros2/ardupilot_sitl/package.xml b/Tools/ros2/ardupilot_sitl/package.xml index 5cc0abfd72a73c..fd1cc359ed184b 100644 --- a/Tools/ros2/ardupilot_sitl/package.xml +++ b/Tools/ros2/ardupilot_sitl/package.xml @@ -11,7 +11,15 @@ ament_cmake ament_cmake_python + ardupilot_msgs + builtin_interfaces + geographic_msgs + geometry_msgs micro_ros_agent + rosgraph_msgs + sensor_msgs + std_msgs + tf2_msgs ament_lint_auto ament_cmake_black diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index 10203e148bf530..15ef9bc9e3a26e 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -31,6 +31,10 @@ from .actions import ExecuteFunction +TRUE_STRING = "True" +FALSE_STRING = "False" +BOOL_STRING_CHOICES = set([TRUE_STRING, FALSE_STRING]) + class VirtualPortsLaunch: """Launch functions for creating virtual ports using `socat`.""" @@ -286,26 +290,36 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: master = LaunchConfiguration("master").perform(context) out = LaunchConfiguration("out").perform(context) sitl = LaunchConfiguration("sitl").perform(context) + console = LaunchConfiguration("console").perform(context) + map = LaunchConfiguration("map").perform(context) # Display launch arguments. print(f"command: {command}") print(f"master: {master}") print(f"sitl: {sitl}") print(f"out: {out}") + print(f"console: {console}") + print(f"map: {map}") + + cmd = [ + f"{command} ", + f"--out {out} ", + "--out ", + "127.0.0.1:14551 ", + f"--master {master} ", + f"--sitl {sitl} ", + "--non-interactive ", + ] + + if console == TRUE_STRING: + cmd.append("--console ") + + if map == TRUE_STRING: + cmd.append("--map ") # Create action. mavproxy_process = ExecuteProcess( - cmd=[ - [ - f"{command} ", - f"--out {out} ", - "--out ", - "127.0.0.1:14551 ", - f"--master {master} ", - f"--sitl {sitl} ", - "--non-interactive ", - ] - ], + cmd=cmd, shell=True, output="both", respawn=False, @@ -355,14 +369,18 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: default_value="127.0.0.1:5501", description="SITL output port.", ), + DeclareLaunchArgument( + "map", default_value="False", description="Enable MAVProxy Map.", choices=BOOL_STRING_CHOICES + ), + DeclareLaunchArgument( + "console", default_value="False", description="Enable MAVProxy Console.", choices=BOOL_STRING_CHOICES + ), ] class SITLLaunch: """Launch functions for ArduPilot SITL.""" - # Labels for the optional uart launch arguments. - UART_LABELS = ["A", "B", "C", "D", "E", "F", "H", "I", "J"] MAX_SERIAL_PORTS = 10 @staticmethod @@ -399,12 +417,12 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: # Optional arguments. wipe = LaunchConfiguration("wipe").perform(context) - if wipe == "True": + if wipe == TRUE_STRING: cmd_args.append("--wipe ") print(f"wipe: {wipe}") synthetic_clock = LaunchConfiguration("synthetic_clock").perform(context) - if synthetic_clock == "True": + if synthetic_clock == TRUE_STRING: cmd_args.append("--synthetic-clock ") print(f"synthetic_clock: {synthetic_clock}") @@ -413,13 +431,6 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: cmd_args.append(f"--home {home} ") print(f"home: {home}") - # Optional uart arguments. - for label in SITLLaunch.UART_LABELS: - arg = LaunchConfiguration(f"uart{label}").perform(context) - if arg: - cmd_args.append(f"--uart{label} {arg} ") - print(f"uart{label}: {arg}") - # Optional serial arguments. for label in range(10): arg = LaunchConfiguration(f"serial{label}").perform(context) @@ -566,13 +577,13 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: "wipe", default_value="False", description="Wipe eeprom.", - choices=["True", "False"], + choices=BOOL_STRING_CHOICES, ), DeclareLaunchArgument( "synthetic_clock", default_value="False", description="Set synthetic clock mode.", - choices=["True", "False"], + choices=BOOL_STRING_CHOICES, ), DeclareLaunchArgument( "home", @@ -626,16 +637,6 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: ), ] - # UART launch arguments. - uart_args = [] - for label in SITLLaunch.UART_LABELS: - arg = DeclareLaunchArgument( - f"uart{label}", - default_value="", - description=f"set device string for UART{label}.", - ) - uart_args.append(arg) - # Serial launch arguments. serial_args = [] for label in range(SITLLaunch.MAX_SERIAL_PORTS): @@ -646,4 +647,4 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: ) serial_args.append(arg) - return launch_args + uart_args + serial_args + return launch_args + serial_args diff --git a/Tools/scripts/annotate_params.py b/Tools/scripts/annotate_params.py index 11c9ca80240097..aaf679471aa7ad 100755 --- a/Tools/scripts/annotate_params.py +++ b/Tools/scripts/annotate_params.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 """ This script fetches online ArduPilot parameter documentation (if not cached) and adds it to the specified file diff --git a/Tools/scripts/board_list.py b/Tools/scripts/board_list.py index 9758a1cc800ea3..9fe7a15ac64926 100755 --- a/Tools/scripts/board_list.py +++ b/Tools/scripts/board_list.py @@ -62,12 +62,14 @@ def __init__(self): self.boards = [ Board("erlebrain2"), Board("navigator"), + Board("navigator64"), Board("navio"), Board("navio2"), Board("edge"), Board("obal"), Board("pxf"), Board("bbbmini"), + Board("bebop"), Board("blue"), Board("pxfmini"), Board("canzero"), diff --git a/Tools/scripts/build_appveyor.sh b/Tools/scripts/build_appveyor.sh index d392bbe4e041db..e06ef2591ac52b 100755 --- a/Tools/scripts/build_appveyor.sh +++ b/Tools/scripts/build_appveyor.sh @@ -18,7 +18,7 @@ cd /cygdrive/c/work ./waf configure --board sitl - /usr/bin/python waf -j4 copter plane rover heli sub + python3 waf -j4 copter plane rover heli sub # map to the names that MissionPlanner expects cp /cygdrive/c/work/build/sitl/bin/ardurover.exe /cygdrive/c/work/sitl/Rover.elf diff --git a/Tools/scripts/build_autotest.sh b/Tools/scripts/build_autotest.sh index cde9769bd290c1..bf212bfacd4a3e 100755 --- a/Tools/scripts/build_autotest.sh +++ b/Tools/scripts/build_autotest.sh @@ -71,13 +71,13 @@ pushd MAVProxy git fetch origin git reset --hard origin/master git show -python setup.py build install --user +python3 -m pip install --user . popd echo "Updating pymavlink" pushd APM/modules/mavlink/pymavlink git show -python setup.py build install --user +python3 -m pip install --user . popd githash=$(cd APM && git rev-parse HEAD) @@ -100,7 +100,7 @@ export BUILD_BINARIES_PATH=$HOME/build/tmp # exit on panic so we don't waste time waiting around export SITL_PANIC_EXIT=1 -timelimit 72000 python3 APM/Tools/autotest/autotest.py --autotest-server --timeout=70000 > buildlogs/autotest-output.txt 2>&1 +timelimit 144000 python3 APM/Tools/autotest/autotest.py --autotest-server --timeout=143000 > buildlogs/autotest-output.txt 2>&1 mkdir -p "buildlogs/history/$hdate" diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index c82d184d47b5a3..460d0db00f0f3e 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -5,7 +5,13 @@ XOLDPWD=$PWD # profile changes directory :-( -. ~/.profile +if [ -z "$GITHUB_ACTIONS" ] || [ "$GITHUB_ACTIONS" != "true" ]; then + . ~/.profile +fi + +if [ "$CI" = "true" ]; then + export PIP_ROOT_USER_ACTION=ignore +fi cd $XOLDPWD @@ -40,7 +46,7 @@ function install_pymavlink() { if [ $pymavlink_installed -eq 0 ]; then echo "Installing pymavlink" git submodule update --init --recursive --depth 1 - (cd modules/mavlink/pymavlink && python setup.py build install --user) + (cd modules/mavlink/pymavlink && python3 -m pip install --progress-bar off --cache-dir /tmp/pip-cache --user .) pymavlink_installed=1 fi } @@ -51,12 +57,12 @@ function install_mavproxy() { pushd /tmp git clone https://github.com/ardupilot/MAVProxy --depth 1 pushd MAVProxy - python setup.py build install --user --force + python3 -m pip install --progress-bar off --cache-dir /tmp/pip-cache --user --force . popd popd mavproxy_installed=1 # now uninstall the version of pymavlink pulled in by MAVProxy deps: - python -m pip uninstall -y pymavlink + python3 -m pip uninstall -y pymavlink --cache-dir /tmp/pip-cache fi } @@ -135,8 +141,12 @@ for t in $CI_BUILD_TARGET; do run_autotest "Copter" "build.SITLPeriphUniversal" "test.CAN" continue fi - if [ "$t" == "sitltest-plane" ]; then - run_autotest "Plane" "build.Plane" "test.Plane" + if [ "$t" == "sitltest-plane-tests1a" ]; then + run_autotest "Plane" "build.Plane" "test.PlaneTests1a" + continue + fi + if [ "$t" == "sitltest-plane-tests1b" ]; then + run_autotest "Plane" "build.Plane" "test.PlaneTests1b" continue fi if [ "$t" == "sitltest-quadplane" ]; then @@ -239,6 +249,10 @@ for t in $CI_BUILD_TARGET; do $waf configure --board FreeflyRTK $waf clean $waf AP_Periph + echo "Building CubeNode-ETH peripheral fw" + $waf configure --board CubeNode-ETH + $waf clean + $waf AP_Periph continue fi @@ -321,7 +335,15 @@ for t in $CI_BUILD_TARGET; do if [ "$t" == "CubeOrange-PPP" ]; then echo "Building CubeOrange-PPP" - $waf configure --board CubeOrange --enable-ppp + $waf configure --board CubeOrange --enable-PPP + $waf clean + $waf copter + continue + fi + + if [ "$t" == "CubeRed-EKF2" ]; then + echo "Building CubeRed with EKF2 enabled" + $waf configure --board CubeRedPrimary --enable-EKF2 $waf clean $waf copter continue @@ -345,6 +367,18 @@ for t in $CI_BUILD_TARGET; do $waf bootloader continue fi + + if [ "$t" == "new-check" ]; then + echo "Building Pixhawk6X with new check" + $waf configure --board Pixhawk6X --enable-new-checking + $waf clean + $waf + echo "Building Pixhawk6X-PPPGW with new check" + $waf configure --board Pixhawk6X-PPPGW --enable-new-checking + $waf clean + $waf AP_Periph + continue + fi if [ "$t" == "dds-stm32h7" ]; then echo "Building with DDS support on a STM32H7" @@ -389,6 +423,14 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "navigator64" ]; then + echo "Building navigator64" + $waf configure --board navigator64 --toolchain=aarch64-linux-gnu + $waf sub + ./Tools/scripts/firmware_version_decoder.py -f build/navigator64/bin/ardusub --expected-hash $GIT_VERSION + continue + fi + if [ "$t" == "replay" ]; then echo "Building replay" $waf configure --board sitl --debug --disable-scripting @@ -422,7 +464,7 @@ for t in $CI_BUILD_TARGET; do echo "Building signed firmwares" sudo apt-get update sudo apt-get install -y python3-dev - python3 -m pip install pymonocypher + python3 -m pip install pymonocypher==3.1.3.2 --progress-bar off --cache-dir /tmp/pip-cache ./Tools/scripts/signing/generate_keys.py testkey $waf configure --board CubeOrange-ODID --signed-fw --private-key testkey_private_key.dat $waf copter @@ -441,7 +483,11 @@ for t in $CI_BUILD_TARGET; do if [ "$t" == "astyle-cleanliness" ]; then echo "Checking AStyle code cleanliness" + ./Tools/scripts/run_astyle.py --dry-run + if [ $? -ne 0 ]; then + echo The code failed astyle cleanliness checks. Please run ./Tools/scripts/run_astyle.py + fi continue fi @@ -480,7 +526,14 @@ for t in $CI_BUILD_TARGET; do if [ "$t" == "param_parse" ]; then for v in Rover AntennaTracker ArduCopter ArduPlane ArduSub Blimp AP_Periph; do - python Tools/autotest/param_metadata/param_parse.py --vehicle $v + python3 Tools/autotest/param_metadata/param_parse.py --vehicle $v + done + continue + fi + + if [ "$t" == "logger_metadata" ]; then + for v in Rover Tracker Copter Plane Sub Blimp; do + python3 Tools/autotest/logger_metadata/parse.py --vehicle $v done continue fi diff --git a/Tools/scripts/build_iofirmware.py b/Tools/scripts/build_iofirmware.py index 6d6c927addab35..c2f67096a82fce 100755 --- a/Tools/scripts/build_iofirmware.py +++ b/Tools/scripts/build_iofirmware.py @@ -29,12 +29,24 @@ def run_program(cmd_list): shutil.copy('build/iomcu/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_lowpolh.bin') shutil.copy('build/iomcu/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_highpolh.bin') +run_program(["./waf", "configure", "--board", 'iomcu', '--enable-iomcu-profiled-support']) +run_program(["./waf", "clean"]) +run_program(["./waf", "iofirmware"]) +shutil.copy('build/iomcu/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_lowpolh.bin') +shutil.copy('build/iomcu/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_highpolh.bin') + run_program(["./waf", "configure", "--board", 'iomcu-dshot']) run_program(["./waf", "clean"]) run_program(["./waf", "iofirmware"]) shutil.copy('build/iomcu-dshot/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin') shutil.copy('build/iomcu-dshot/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_dshot_highpolh.bin') +run_program(["./waf", "configure", "--board", 'iomcu-dshot', '--enable-iomcu-profiled-support']) +run_program(["./waf", "clean"]) +run_program(["./waf", "iofirmware"]) +shutil.copy('build/iomcu-dshot/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin') +shutil.copy('build/iomcu-dshot/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin') + run_program(["./waf", "configure", "--board", 'iomcu-f103']) run_program(["./waf", "clean"]) run_program(["./waf", "iofirmware"]) @@ -52,3 +64,11 @@ def run_program(cmd_list): run_program(["./waf", "iofirmware"]) shutil.copy('build/iomcu_f103_8MHz/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin') shutil.copy('build/iomcu_f103_8MHz/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin') + +run_program(["./waf", "configure", "--board", 'iomcu-f103-8MHz-dshot']) +run_program(["./waf", "clean"]) +run_program(["./waf", "iofirmware"]) +shutil.copy('build/iomcu-f103-8MHz-dshot/bin/iofirmware_lowpolh.bin', + 'Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin') +shutil.copy('build/iomcu-f103-8MHz-dshot/bin/iofirmware_highpolh.bin', + 'Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_highpolh.bin') diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index ff1f5b093cae43..ecb4279febc13e 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -23,6 +23,10 @@ def __init__(self, self.default = default self.dependency = dependency + def config_option(self): + '''the name of the configure option to be used by waf''' + return "enable-" + self.label.replace(" ", "-") + # list of build options to offer NOTE: the dependencies must be # written as a single string with commas and no spaces, @@ -31,29 +35,32 @@ def __init__(self, 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', 'MicroStrain5', 'AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED', 'Enable MICROSTRAIN 5-series External AHRS', 0, "AHRS_EXT"), # noqa: E501 - Feature('AHRS', 'MicroStrain7', 'AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED', 'Enable MICROSTRAIN 7-series External AHRS', 0, "AHRS_EXT"), # noqa: E501 - Feature('AHRS', 'AHRS_EXT_VECTORNAV', 'AP_EXTERNAL_AHRS_VECTORNAV_ENABLED', 'Enable VectorNav External AHRS', 0, "AHRS_EXT"), # noqa - Feature('AHRS', 'TEMPCAL', 'HAL_INS_TEMPERATURE_CAL_ENABLE', 'Enable IMU Temperature Calibration', 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, 'EKF3'), - Feature('AHRS', 'EKF3_WINDEST', 'EK3_FEATURE_DRAG_FUSION', 'Enable Wind Estimation for EKF3', 0, 'EKF3'), - Feature('AHRS', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), + Feature('AHRS', 'MicroStrain5', 'AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED', 'Enable MICROSTRAIN 5-series external AHRS', 0, "AHRS_EXT"), # noqa: E501 + Feature('AHRS', 'MicroStrain7', 'AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED', 'Enable MICROSTRAIN 7-series external AHRS', 0, "AHRS_EXT"), # noqa: E501 + Feature('AHRS', 'AHRS_EXT_VECTORNAV', 'AP_EXTERNAL_AHRS_VECTORNAV_ENABLED', 'Enable VectorNav external AHRS', 0, "AHRS_EXT"), # noqa + Feature('AHRS', 'InertialLabs', 'AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED', 'Enable InertialLabs external AHRS', 0, "AHRS_EXT"), # noqa + Feature('AHRS', 'VISUALODOM', 'HAL_VISUALODOM_ENABLED', 'Enable Visual Odometry', 0, None), + Feature('AHRS', 'EKF3_EXTNAV', 'EK3_FEATURE_EXTERNAL_NAV', 'Enable External navigation for EKF3', 0, 'EKF3'), + Feature('AHRS', 'EKF3_WINDEST', 'EK3_FEATURE_DRAG_FUSION', 'Enable Wind estimation for EKF3', 0, 'EKF3'), + Feature('AHRS', 'EKF3_OPTFLOW', 'EK3_FEATURE_OPTFLOW_FUSION', 'Enable OpticalFlow fusion for EKF3', 0, 'EKF3,OPTICALFLOW'), + Feature('AHRS', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro wind compensation', 0, None), Feature('Safety', 'PARACHUTE', 'HAL_PARACHUTE_ENABLED', 'Enable Parachute', 0, None), - Feature('Safety', 'FENCE', 'AP_FENCE_ENABLED', 'Enable Geofence', 2, None), - Feature('Safety', 'RALLY', 'HAL_RALLY_ENABLED', 'Enable Rally Points', 0, None), # noqa - Feature('Safety', 'AC_AVOID', 'AP_AVOIDANCE_ENABLED', 'Enable Avoidance', 0, 'FENCE'), + Feature('Safety', 'FENCE', 'AP_FENCE_ENABLED', 'Enable Geofences', 2, None), + Feature('Safety', 'RALLY', 'HAL_RALLY_ENABLED', 'Enable Rally points', 0, None), # noqa + Feature('Safety', 'AC_AVOID', 'AP_AVOIDANCE_ENABLED', 'Enable Object Avoidance', 0, 'FENCE'), Feature('Safety', 'AC_OAPATHPLANNER', 'AP_OAPATHPLANNER_ENABLED', 'Enable Object Avoidance Path Planner', 0, 'FENCE'), - Feature('Battery', 'BATTERY_FUELFLOW', 'AP_BATTERY_FUELFLOW_ENABLED', 'Enable Fuel Flow BatteryMonitor', 0, None), - Feature('Battery', 'BATTERY_FUELLEVEL_PWM', 'AP_BATTERY_FUELLEVEL_PWM_ENABLED', 'Enable Flow Level PWM BatteryMonitor', 0, None), # noqa: E501 - Feature('Battery', 'BATTERY_FUELLEVEL_ANALOG', 'AP_BATTERY_FUELLEVEL_ANALOG_ENABLED', 'Enable Flow Level Analog BattryMonitor', 0, None), # noqa: E501 - Feature('Battery', 'BATTERY_SMBUS', 'AP_BATTERY_SMBUS_ENABLED', 'Enable SMBUS BatteryMonitor', 0, None), - Feature('Battery', 'BATTERY_INA2XX', 'AP_BATTERY_INA2XX_ENABLED', 'Enable INA2XX BatteryMonitor', 0, None), - Feature('Battery', 'BATTERY_SYNTHETIC_CURRENT', 'AP_BATTERY_SYNTHETIC_CURRENT_ENABLED', 'Enable Synthetic Current Monitor', 0, None), # noqa: E501 - Feature('Battery', 'BATTERY_ESC_TELEM_OUT', 'AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'Enable ability to put battery monitor data in ESC telem stream', 0, None), # noqa: E501 - Feature('Battery', 'BATTERY_WATT_MAX', 'AP_BATTERY_WATT_MAX_ENABLED', 'Enable param BATT_WATT_MAX', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_FUELFLOW', 'AP_BATTERY_FUELFLOW_ENABLED', 'Enable Fuel flow battery monitor', 0, None), + Feature('Battery', 'BATTERY_FUELLEVEL_PWM', 'AP_BATTERY_FUELLEVEL_PWM_ENABLED', 'Enable PWM Fuel level battery monitor', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_FUELLEVEL_ANALOG', 'AP_BATTERY_FUELLEVEL_ANALOG_ENABLED', 'Enable Analog Fuel level battry monitor', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_SMBUS', 'AP_BATTERY_SMBUS_ENABLED', 'Enable SMBUS battery monitor', 0, None), + Feature('Battery', 'BATTERY_INA2XX', 'AP_BATTERY_INA2XX_ENABLED', 'Enable INA2XX battery monitor', 0, None), + Feature('Battery', 'BATTERY_SYNTHETIC_CURRENT', 'AP_BATTERY_SYNTHETIC_CURRENT_ENABLED', 'Enable Synthetic Current monitor', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_ESC_TELEM_OUT', 'AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'Enable Ability to put battery monitor data into ESC telem stream', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_SUM', 'AP_BATTERY_SUM_ENABLED', 'Enable Synthetic sum-of-other-batteries backend', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_WATT_MAX', 'AP_BATTERY_WATT_MAX_ENABLED', 'Enable BATT_WATT_MAX parameter', 0, None), # noqa: E501 + Feature('Ident', 'ADSB', 'HAL_ADSB_ENABLED', 'Enable ADSB', 0, None), Feature('Ident', 'ADSB_SAGETECH', 'HAL_ADSB_SAGETECH_ENABLED', 'Enable Sagetech ADSB', 0, 'ADSB'), @@ -63,76 +70,82 @@ def __init__(self, Feature('Ident', 'AIS', 'AP_AIS_ENABLED', 'Enable AIS', 0, None), Feature('Ident', 'OpenDroneID', 'AP_OPENDRONEID_ENABLED', 'Enable OpenDroneID (Remote ID)', 0, None), - Feature('Telemetry', 'CRSF', 'HAL_CRSF_TELEM_ENABLED', 'Enable CRSF Telemetry', 0, 'FrSky SPort PassThrough,FrSky,FrSky SPort,RC_CRSF'), # noqa - Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF Text Param Selection', 0, 'CRSF,OSD_PARAM,FrSky SPort PassThrough,FrSky,FrSky SPort'), # NOQA: E501 - 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('Telemetry', 'AUX_FUNCTION_STRINGS', 'AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED', 'Enable Auxilliary Function activation text', 0, None), # noqa - Feature('Telemetry', 'FrSky', 'AP_FRSKY_TELEM_ENABLED', 'Enable FrSky Telemetry', 0, None), - Feature('Telemetry', 'FrSky D', 'AP_FRSKY_D_TELEM_ENABLED', 'Enable FrSkyD Telemetry', 0, 'FrSky'), - Feature('Telemetry', 'FrSky SPort', 'AP_FRSKY_SPORT_TELEM_ENABLED', 'Enable FrSkySPort Telemetry', 0, 'FrSky'), # noqa - Feature('Telemetry', 'FrSky SPort PassThrough', 'AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'Enable FrSkySPort PassThrough Telemetry', 0, 'FrSky SPort,FrSky'), # noqa - Feature('Telemetry', 'GHST', 'AP_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, "RC_GHST"), # noqa - - Feature('Notify', 'PLAY_TUNE', 'AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', 'Enable MAVLink Play Tune', 0, None), # noqa - Feature('Notify', 'TONEALARM', 'AP_NOTIFY_TONEALARM_ENABLED', 'Enable ToneAlarm on PWM', 0, None), # noqa - Feature('Notify', 'LED_CONTROL', 'AP_NOTIFY_MAVLINK_LED_CONTROL_SUPPORT_ENABLED', 'Enable MAVLink LED Control', 0, None), # noqa + Feature('Telemetry', 'CRSF', 'HAL_CRSF_TELEM_ENABLED', 'Enable CRSF telemetry', 0, 'FrSky SPort PassThrough,FrSky,FrSky SPort,RC_CRSF'), # noqa + Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF text param selection', 0, 'CRSF,OSD_PARAM,FrSky SPort PassThrough,FrSky,FrSky SPort'), # NOQA: E501 + 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('Telemetry', 'AUX_FUNCTION_STRINGS', 'AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED', 'Enable Auxilliary function activation text messages', 0, None), # noqa + Feature('Telemetry', 'FrSky', 'AP_FRSKY_TELEM_ENABLED', 'Enable FrSky telemetry', 0, None), + Feature('Telemetry', 'FrSky D', 'AP_FRSKY_D_TELEM_ENABLED', 'Enable FrSkyD telemetry', 0, 'FrSky'), + Feature('Telemetry', 'FrSky SPort', 'AP_FRSKY_SPORT_TELEM_ENABLED', 'Enable FrSkySPort telemetry', 0, 'FrSky'), # noqa + Feature('Telemetry', 'FrSky SPort PassThrough', 'AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'Enable FrSkySPort pass-through telemetry', 0, 'FrSky SPort,FrSky'), # noqa + Feature('Telemetry', 'Bidirectional FrSky Telemetry', 'HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', 'Enable bidirectional FrSky telemetry', 0, 'FrSky SPort'), # noqa + Feature('Telemetry', 'GHST', 'AP_GHST_TELEM_ENABLED', 'Enable Ghost telemetry', 0, "RC_GHST"), # noqa + Feature('Telemetry', 'i-BUS', 'AP_IBUS_TELEM_ENABLED', 'Enable i-BUS telemetry', 0, None), + + Feature('Notify', 'PLAY_TUNE', 'AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', 'Enable MAVLink Play Tune command', 0, None), # noqa + Feature('Notify', 'TONEALARM', 'AP_NOTIFY_TONEALARM_ENABLED', 'Enable PWM tone alarm', 0, None), # noqa + Feature('Notify', 'LED_CONTROL', 'AP_NOTIFY_MAVLINK_LED_CONTROL_SUPPORT_ENABLED', 'Enable MAVLink LED control', 0, None), # noqa Feature('Notify', 'NOTIFY_NCP5623', 'AP_NOTIFY_NCP5623_ENABLED', 'Enable NCP5623 LED', 0, None), # noqa # Feature('Notify', 'NOTIFY_PCA9685', 'AP_NOTIFY_PCA9685_ENABLED', 'Enable PCA9685 LED', 0, None), # noqa linux-only Feature('Notify', 'NOTIFY_PROFILED', 'AP_NOTIFY_PROFILED_ENABLED', 'Enable ProfiLED', 0, None), # noqa Feature('Notify', 'DISPLAY', 'HAL_DISPLAY_ENABLED', 'Enable I2C Displays', 0, None), Feature('Notify', 'NOTIFY_PROFILED_SPI', 'AP_NOTIFY_PROFILED_SPI_ENABLED', 'Enable ProfiLED (SPI)', 0, None), # noqa - Feature('Notify', 'NOTIFY_NEOPIXEL', 'AP_NOTIFY_NEOPIXEL_ENABLED', 'Enable NeoPixel', 0, None), # noqa + Feature('Notify', 'NOTIFY_NEOPIXEL', 'AP_NOTIFY_NEOPIXEL_ENABLED', 'Enable NeoPixel LED strings', 0, None), # noqa - 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'), # NOQA: E501 + 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'), # NOQA: E501 Feature('MSP', 'MSP_GPS', 'HAL_MSP_GPS_ENABLED', 'Enable MSP GPS', 0, 'MSP,OSD'), - Feature('MSP', 'MSP_COMPASS', 'AP_COMPASS_MSP_ENABLED', 'Enable MSP Compass', 0, 'MSP,OSD'), + Feature('MSP', 'MSP_COMPASS', 'AP_COMPASS_MSP_ENABLED', 'Enable MSP compass', 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_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, 'RPM'), - Feature('ICE', 'EFI', 'HAL_EFI_ENABLED', 'Enable EFI Monitoring', 0, None), - Feature('ICE', 'EFI_MegaSquirt', 'AP_EFI_SERIAL_MS_ENABLED', 'Enable EFI MegaSquirt', 0, 'EFI'), - Feature('ICE', 'EFI_Lutan', 'AP_EFI_SERIAL_LUTAN_ENABLED', 'Enable EFI Lutan', 0, 'EFI'), - Feature('ICE', 'EFI_NMPWU', 'AP_EFI_NWPWU_ENABLED', 'Enable EFI NMPMU', 0, 'EFI'), - Feature('ICE', 'EFI_CURRAWONGECU', 'AP_EFI_CURRAWONG_ECU_ENABLED', 'Enable EFI Currawong ECU', 0, 'EFI'), - Feature('ICE', 'EFI_HIRTH', 'AP_EFI_SERIAL_HIRTH_ENABLED', 'Enable EFI Hirth ECU', 0, 'EFI'), - Feature('ICE', 'EFI_DRONECAN', 'AP_EFI_DRONECAN_ENABLED', 'Enable EFI DroneCAN', 0, 'EFI'), - Feature('ICE', 'EFI_MAV', 'AP_EFI_MAV_ENABLED', 'Enable EFI MAV', 0, 'EFI'), + Feature('ICE', 'ICE Engine', 'AP_ICENGINE_ENABLED', 'Enable Internal combustion engine support', 0, 'RPM'), + Feature('ICE', 'EFI', 'HAL_EFI_ENABLED', 'Enable EFI monitoring', 0, None), + Feature('ICE', 'EFI_MegaSquirt', 'AP_EFI_SERIAL_MS_ENABLED', 'Enable MegaSquirt EFI', 0, 'EFI'), + Feature('ICE', 'EFI_Lutan', 'AP_EFI_SERIAL_LUTAN_ENABLED', 'Enable Lutan EFI', 0, 'EFI'), + Feature('ICE', 'EFI_NMPWU', 'AP_EFI_NWPWU_ENABLED', 'Enable NMPMU EFI', 0, 'EFI'), + Feature('ICE', 'EFI_CURRAWONGECU', 'AP_EFI_CURRAWONG_ECU_ENABLED', 'Enable Currawong ECU', 0, 'EFI'), + Feature('ICE', 'EFI_HIRTH', 'AP_EFI_SERIAL_HIRTH_ENABLED', 'Enable Hirth ECU', 0, 'EFI'), + Feature('ICE', 'EFI_DRONECAN', 'AP_EFI_DRONECAN_ENABLED', 'Enable DroneCAN EFI', 0, 'EFI,DroneCAN'), + Feature('ICE', 'EFI_MAV', 'AP_EFI_MAV_ENABLED', 'Enable MAVLink EFI', 0, 'EFI'), Feature('Generator', 'GENERATOR', 'HAL_GENERATOR_ENABLED', 'Enable Generator', 0, None), - Feature('Generator', 'GENERATOR_RICHENPOWER', 'AP_GENERATOR_RICHENPOWER_ENABLED', 'Enable Richenpower Generator', 0, "GENERATOR"), # noqa + Feature('Generator', 'GENERATOR_RICHENPOWER', 'AP_GENERATOR_RICHENPOWER_ENABLED', 'Enable Richenpower generator', 0, "GENERATOR"), # noqa Feature('Generator', 'GENERATOR_IE2400', 'AP_GENERATOR_IE_2400_ENABLED', 'Enable IntelligentEnergy 2400', 0, "GENERATOR"), # noqa - Feature('Generator', 'GENERATOR_IE650', 'AP_GENERATOR_IE_650_800_ENABLED', 'Enable IntelligentEnergy 650 and 800 support', 0, "GENERATOR"), # noqa + Feature('Generator', 'GENERATOR_IE650', 'AP_GENERATOR_IE_650_800_ENABLED', 'Enable IntelligentEnergy 650 and 800', 0, "GENERATOR"), # noqa Feature('OSD', 'OSD', 'OSD_ENABLED', 'Enable OSD', 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('OSD', 'OSD_EXTENDED_LINK_STATS', 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', 'Enable OSD panels with extended link stats data', 0, "OSD,RC_CRSF"), # noqa + Feature('OSD', 'OSD_PARAM', 'OSD_PARAM_ENABLED', 'Enable OSD param', 0, None), + Feature('OSD', 'OSD_SIDEBARS', 'HAL_OSD_SIDEBAR_ENABLE', 'Enable Scrolling sidebars', 0, 'OSD'), + Feature('OSD', 'OSD_EXTENDED_LINK_STATS', 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', 'Enable OSD panels with extended link stats data', 0, "OSD,RC_CRSF,MSP"), # noqa Feature('VTX', 'VIDEO_TX', 'AP_VIDEOTX_ENABLED', 'Enable VideoTX control', 0, None), - Feature('VTX', 'SMARTAUDIO', 'AP_SMARTAUDIO_ENABLED', 'Enable SmartAudio VTX Contol', 0, "VIDEO_TX"), - Feature('VTX', 'TRAMP', 'AP_TRAMP_ENABLED', 'Enable IRC Tramp VTX Control', 0, "VIDEO_TX"), + Feature('VTX', 'SMARTAUDIO', 'AP_SMARTAUDIO_ENABLED', 'Enable SmartAudio VTX contol', 0, "VIDEO_TX"), + Feature('VTX', 'TRAMP', 'AP_TRAMP_ENABLED', 'Enable IRC Tramp VTX control', 0, "VIDEO_TX"), - Feature('ESC', 'PICCOLOCAN', 'HAL_PICCOLO_CAN_ENABLE', 'Enable PiccoloCAN', 0, None), - Feature('ESC', 'TORQEEDO', 'HAL_TORQEEDO_ENABLED', 'Enable Torqeedo Motors', 0, None), + Feature('ESC', 'PICCOLOCAN', 'HAL_PICCOLO_CAN_ENABLE', 'Enable PiccoloCAN', 0, 'DroneCAN'), + Feature('ESC', 'TORQEEDO', 'HAL_TORQEEDO_ENABLED', 'Enable Torqeedo motors', 0, None), + + Feature('ESC', 'ESC_EXTENDED_TELM', 'AP_EXTENDED_ESC_TELEM_ENABLED', 'Enable Extended ESC telemetry', 0, 'DroneCAN'), Feature('AP_Periph', 'LONG_TEXT', 'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', 'Enable extended length text strings', 0, None), - Feature('Camera', 'Camera', 'AP_CAMERA_ENABLED', 'Enable Camera Trigger support', 0, None), - Feature('Camera', 'Camera_MAVLink', 'AP_CAMERA_MAVLINK_ENABLED', 'Enable MAVLink Camera support', 0, 'Camera'), - Feature('Camera', 'Camera_MAVLinkCamV2', 'AP_CAMERA_MAVLINKCAMV2_ENABLED', 'Enable MAVLink CameraV2 support', 0, 'Camera'), - Feature('Camera', 'Camera_Mount', 'AP_CAMERA_MOUNT_ENABLED', 'Enable Camera-in-Mount support', 0, 'Camera,MOUNT'), - Feature('Camera', 'Camera_Relay', 'AP_CAMERA_RELAY_ENABLED', 'Enable Camera Trigger via Relay support', 0, 'Camera,RELAY'), - Feature('Camera', 'Camera_Servo', 'AP_CAMERA_SERVO_ENABLED', 'Enable Camera Trigger via Servo support', 0, 'Camera'), - Feature('Camera', 'Camera_Solo', 'AP_CAMERA_SOLOGIMBAL_ENABLED', 'Enable Solo Gimbal support', 0, 'Camera'), - Feature('Camera', 'Camera_FOV_Status', 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'Enable Camera FOV Status send to GCS', 0, 'Camera,MOUNT'), # noqa: E501 + Feature('Camera', 'Camera', 'AP_CAMERA_ENABLED', 'Enable Camera trigger', 0, None), + Feature('Camera', 'Camera_MAVLink', 'AP_CAMERA_MAVLINK_ENABLED', 'Enable MAVLink camera ', 0, 'Camera'), + Feature('Camera', 'Camera_MAVLinkCamV2', 'AP_CAMERA_MAVLINKCAMV2_ENABLED', 'Enable MAVLink CameraV2', 0, 'Camera'), + Feature('Camera', 'Camera_Mount', 'AP_CAMERA_MOUNT_ENABLED', 'Enable Camera-in-Mount ', 0, 'Camera,MOUNT'), + Feature('Camera', 'Camera_Relay', 'AP_CAMERA_RELAY_ENABLED', 'Enable Relay camera trigger', 0, 'Camera,RELAY'), + Feature('Camera', 'Camera_Servo', 'AP_CAMERA_SERVO_ENABLED', 'Enable Servo camera trigger', 0, 'Camera'), + Feature('Camera', 'Camera_Solo', 'AP_CAMERA_SOLOGIMBAL_ENABLED', 'Enable Solo gimbal', 0, 'Camera'), + Feature('Camera', 'Camera_FOV_Status', 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'Enable GCS camera FOV status', 0, 'Camera,MOUNT'), # noqa: E501 + Feature('Camera', 'Camera_ThermalRange', 'AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'Enable GCS camera thermal range', 0, 'Camera,MOUNT'), # noqa: E501 + Feature('Camera', 'Camera_Info_From_Script', 'AP_CAMERA_INFO_FROM_SCRIPT_ENABLED', 'Enable Camera information messages via Lua script', 0, 'Camera,SCRIPTING'), # noqa - Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None), + Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam control', 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, 'Logging'), @@ -143,17 +156,22 @@ def __init__(self, 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('Copter', 'MODE_BRAKE', 'MODE_BRAKE_ENABLED', 'Enable Mode Brake', 0, None), + Feature('Copter', 'COPTER_ADVANCED_FAILSAFE', 'AP_COPTER_ADVANCED_FAILSAFE_ENABLED', 'Enable Advanced Failsafe', 0, "ADVANCED_FAILSAFE"), # NOQA: 501 + + Feature('Rover', 'ROVER_ADVANCED_FAILSAFE', 'AP_ROVER_ADVANCED_FAILSAFE_ENABLED', 'Enable Advanced Failsafe', 0, "ADVANCED_FAILSAFE"), # NOQA: 501 - Feature('Mission', 'MISSION_NAV_PAYLOAD_PLACE', 'AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', 'Enable handling of NAV_PAYLOAD_PLACE mission items', 0, None), # noqa - Feature('Copter', 'AC_PAYLOAD_PLACE_ENABLED', 'AC_PAYLOAD_PLACE_ENABLED', 'Enable Payload Place flight behaviour', 0, 'MISSION_NAV_PAYLOAD_PLACE'), # noqa + Feature('Mission', 'MISSION_NAV_PAYLOAD_PLACE', 'AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', 'Enable NAV_PAYLOAD_PLACE', 0, None), # noqa + Feature('Copter', 'AC_PAYLOAD_PLACE_ENABLED', 'AC_PAYLOAD_PLACE_ENABLED', 'Enable Copter Payload Place', 0, 'MISSION_NAV_PAYLOAD_PLACE'), # noqa Feature('Compass', 'AK09916', 'AP_COMPASS_AK09916_ENABLED', 'Enable AK09916 compasses', 1, None), Feature('Compass', 'AK8963', 'AP_COMPASS_AK8963_ENABLED', 'Enable AK8963 compasses', 1, None), Feature('Compass', 'BMM150', 'AP_COMPASS_BMM150_ENABLED', 'Enable BMM150 compasses', 1, None), + Feature('Compass', 'BMM350', 'AP_COMPASS_BMM350_ENABLED', 'Enable BMM350 compasses', 1, None), Feature('Compass', 'EXTERNALAHRS_COMPASS', 'AP_COMPASS_EXTERNALAHRS_ENABLED', 'Enable ExternalAHRS compasses', 0, "AHRS_EXT"), # noqa Feature('Compass', 'HMC5843', 'AP_COMPASS_HMC5843_ENABLED', 'Enable HMC5843 compasses', 1, None), Feature('Compass', 'ICM20948', 'AP_COMPASS_ICM20948_ENABLED', 'Enable AK09916 on ICM20948 compasses', 1, "AK09916"), Feature('Compass', 'IST8308', 'AP_COMPASS_IST8308_ENABLED', 'Enable IST8308 compasses', 1, None), + Feature('Compass', 'IST8310', 'AP_COMPASS_IST8310_ENABLED', 'Enable IST8310 compasses', 1, None), Feature('Compass', 'LIS3MDL', 'AP_COMPASS_LIS3MDL_ENABLED', 'Enable LIS3MDL compasses', 1, None), Feature('Compass', 'LSM303D', 'AP_COMPASS_LSM303D_ENABLED', 'Enable LSM303D compasses', 1, None), Feature('Compass', 'LSM9DS1', 'AP_COMPASS_LSM9DS1_ENABLED', 'Enable LSM9DS1 compasses', 1, None), @@ -162,21 +180,22 @@ def __init__(self, Feature('Compass', 'MMC5XX3', 'AP_COMPASS_MMC5XX3_ENABLED', 'Enable MMC5XX3 compasses', 1, None), Feature('Compass', 'QMC5883L', 'AP_COMPASS_QMC5883L_ENABLED', 'Enable QMC5883L compasses', 1, None), Feature('Compass', 'RM3100', 'AP_COMPASS_RM3100_ENABLED', 'Enable RM3100 compasses', 1, None), - Feature('Compass', 'DRONECAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable DroneCAN compasses', 0, None), - Feature('Compass', 'DRONECAN_COMPASS_HIRES', 'AP_COMPASS_DRONECAN_HIRES_ENABLED', 'Enable DroneCAN HiRes compasses for survey logging', 0, None), # noqa + Feature('Compass', 'DRONECAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable DroneCAN compasses', 0, "DroneCAN"), + Feature('Compass', 'DRONECAN_COMPASS_HIRES', 'AP_COMPASS_DRONECAN_HIRES_ENABLED', 'Enable DroneCAN HiRes compasses for survey logging', 0, "DroneCAN,DRONECAN_COMPASS"), # noqa Feature('Compass', 'FixedYawCal', 'AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Enable Fixed-Yaw Compass Calibration', 1, None), # noqa - Feature('Compass', 'CompassLearn', 'COMPASS_LEARN_ENABLED', 'Enable In-Flight Compass Learning', 1, "FixedYawCal"), - - Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Mount', 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('Gimbal', 'XACTI', 'HAL_MOUNT_XACTI_ENABLED', 'Enable Xacti Gimbal', 0, "MOUNT"), - Feature('Gimbal', 'VIEWPRO', 'HAL_MOUNT_VIEWPRO_ENABLED', 'Enable Viewpro Gimbal', 0, "MOUNT"), + Feature('Compass', 'CompassLearn', 'COMPASS_LEARN_ENABLED', 'Enable In-Flight compass learning', 1, "FixedYawCal"), + + Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Camera Mounts', 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 ServogGimbal', 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('Gimbal', 'TOPOTEK', 'HAL_MOUNT_TOPOTEK_ENABLED', 'Enable Topotek gimbal', 0, "MOUNT"), + Feature('Gimbal', 'XACTI', 'HAL_MOUNT_XACTI_ENABLED', 'Enable Xacti gimbal', 0, "MOUNT,DroneCAN"), + Feature('Gimbal', 'VIEWPRO', 'HAL_MOUNT_VIEWPRO_ENABLED', 'Enable Viewpro 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), @@ -190,28 +209,35 @@ def __init__(self, Feature('Payload', 'SPRAYER', 'HAL_SPRAYER_ENABLED', 'Enable Sprayer', 0, None), Feature('Payload', 'LANDING_GEAR', 'AP_LANDINGGEAR_ENABLED', 'Enable Landing Gear', 0, None), Feature('Payload', 'WINCH', 'AP_WINCH_ENABLED', 'Enable Winch', 0, None), - Feature('Payload', 'RELAY', 'AP_RELAY_ENABLED', 'Enable Relay support', 0, None), - Feature('Payload', 'SERVORELAY_EVENTS', 'AP_SERVORELAYEVENTS_ENABLED', 'Enable Servo/Relay Event support', 0, None), + Feature('Payload', 'WINCH_DAIWA', 'AP_WINCH_DAIWA_ENABLED', 'Enable DAIWA Winch', 0, 'WINCH'), + Feature('Payload', 'WINCH_PWM', 'AP_WINCH_PWM_ENABLED', 'Enable PWM Winch', 0, 'WINCH'), - Feature('Plane', 'ADVANCED_FAILSAFE', 'AP_ADVANCEDFAILSAFE_ENABLED', 'Enable Advanced Failsafe features', 0, None), - Feature('Plane', 'QUADPLANE', 'HAL_QUADPLANE_ENABLED', 'Enable QuadPlane support', 0, None), + Feature('Payload', 'RELAY', 'AP_RELAY_ENABLED', 'Enable Relays', 0, None), + Feature('Payload', 'SERVORELAY_EVENTS', 'AP_SERVORELAYEVENTS_ENABLED', 'Enable Servo/Relay Event', 0, None), + + Feature('Plane', 'ADVANCED_FAILSAFE', 'AP_ADVANCEDFAILSAFE_ENABLED', 'Enable Advanced Failsafe', 0, None), + Feature('Plane', 'QUADPLANE', 'HAL_QUADPLANE_ENABLED', 'Enable QuadPlane', 0, None), Feature('Plane', 'SOARING', 'HAL_SOARING_ENABLED', 'Enable Soaring', 0, None), - Feature('Plane', 'DEEPSTALL', 'HAL_LANDING_DEEPSTALL_ENABLED', 'Enable Deepstall Landing', 0, None), - Feature('Plane', 'QAUTOTUNE', 'QAUTOTUNE_ENABLED', 'Enable QuadPlane Autotune mode', 0, "QUADPLANE"), - Feature('Plane', 'PLANE_BLACKBOX', 'AP_PLANE_BLACKBOX_LOGGING', 'Enable blackbox logging', 0, None), + Feature('Plane', 'DEEPSTALL', 'HAL_LANDING_DEEPSTALL_ENABLED', 'Enable Deepstall landing', 0, None), + Feature('Plane', 'QAUTOTUNE', 'QAUTOTUNE_ENABLED', 'Enable QuadPlane AUTOTUNE', 0, "QUADPLANE"), + Feature('Plane', 'PLANE_BLACKBOX', 'AP_PLANE_BLACKBOX_LOGGING', 'Enable Blackbox logging', 0, None), Feature('Plane', 'AP_TX_TUNING', 'AP_TUNING_ENABLED', 'Enable TX-based tuning parameter adjustments', 0, None), - - Feature('RC', 'RC_Protocol', 'AP_RCPROTOCOL_ENABLED', "Enable Serial RC Protocol support", 0, None), # NOQA: E501 - Feature('RC', 'RC_CRSF', 'AP_RCPROTOCOL_CRSF_ENABLED', "Enable CRSF RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_IBUS', 'AP_RCPROTOCOL_IBUS_ENABLED', "Enable IBus RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_SBUS', 'AP_RCPROTOCOL_SBUS_ENABLED', "Enable SBUS Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_PPMSUM', 'AP_RCPROTOCOL_PPMSUM_ENABLED', "Enable PPMSum Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_SRXL', 'AP_RCPROTOCOL_SRXL_ENABLED', "Enable SRXL RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_SRXL2', 'AP_RCPROTOCOL_SRXL2_ENABLED', "Enable SRXL2 RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_ST24', 'AP_RCPROTOCOL_ST24_ENABLED', "Enable ST24 Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_SUMD', 'AP_RCPROTOCOL_SUMD_ENABLED', "Enable SUMD RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_GHST', 'AP_RCPROTOCOL_GHST_ENABLED', "Enable Ghost RC Protocol", 0, "RC_Protocol"), # NOQA: E501 - Feature('RC', 'RC_MAVLINK_RADIO', 'AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', "Enable MAVLink RC Protocol", 0, "RC_Protocol"), # NOQA: E501 + Feature('Plane', 'PLANE_GUIDED_SLEW', 'AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', 'Enable Offboard-guided slew commands', 0, None), # noqa:401 + Feature('Plane', 'PLANE_GLIDER_PULLUP', 'AP_PLANE_GLIDER_PULLUP_ENABLED', 'Enable Glider pullup support', 0, None), + Feature('Plane', 'QUICKTUNE', 'AP_QUICKTUNE_ENABLED', 'Enable VTOL quicktune', 0, None), + + Feature('RC', 'RC_Protocol', 'AP_RCPROTOCOL_ENABLED', "Enable Serial RC Protocols", 0, None), # NOQA: E501 + Feature('RC', 'RC_CRSF', 'AP_RCPROTOCOL_CRSF_ENABLED', "Enable CRSF", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_IBUS', 'AP_RCPROTOCOL_IBUS_ENABLED', "Enable IBus", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_SBUS', 'AP_RCPROTOCOL_SBUS_ENABLED', "Enable SBUS", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_PPMSUM', 'AP_RCPROTOCOL_PPMSUM_ENABLED', "Enable PPMSum", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_SRXL', 'AP_RCPROTOCOL_SRXL_ENABLED', "Enable SRXL", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_SRXL2', 'AP_RCPROTOCOL_SRXL2_ENABLED', "Enable SRXL2", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_ST24', 'AP_RCPROTOCOL_ST24_ENABLED', "Enable ST24", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_SUMD', 'AP_RCPROTOCOL_SUMD_ENABLED', "Enable SUMD", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_GHST', 'AP_RCPROTOCOL_GHST_ENABLED', "Enable Ghost", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_MAVLINK_RADIO', 'AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', "Enable MAVLink", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RSSI', 'AP_RSSI_ENABLED', 'RSSI', 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 @@ -245,7 +271,7 @@ def __init__(self, Feature('Rangefinder', 'RANGEFINDER_TOFSP_CAN', 'AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED', "Enable Rangefinder - ToFSense-P CAN", 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_DRONECAN', 'AP_RANGEFINDER_DRONECAN_ENABLED', "Enable Rangefinder - DroneCAN", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_DRONECAN', 'AP_RANGEFINDER_DRONECAN_ENABLED', "Enable Rangefinder - DroneCAN", 0, "RANGEFINDER,DroneCAN"), # 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 @@ -255,7 +281,7 @@ def __init__(self, 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"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_HEREFLOW', 'AP_OPTICALFLOW_HEREFLOW_ENABLED', 'Enable Optical flow HereFlow Sensor', 0, "OPTICALFLOW,DroneCAN"), # 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 @@ -264,7 +290,7 @@ def __init__(self, Feature('Proximity', 'PROXIMITY', 'HAL_PROXIMITY_ENABLED', 'Enable Proximity', 0, None), Feature('Proximity', 'PROXIMITY_CYGBOT', 'AP_PROXIMITY_CYGBOT_ENABLED', 'Enable Cygbot D1 Proximity Sensors', 0, "PROXIMITY"), # noqa - Feature('Proximity', 'PROXIMITY_DRONECAN', 'AP_PROXIMITY_DRONECAN_ENABLED', 'Enable DroneCAN Proximity Sensors', 0, "PROXIMITY"), # noqa + Feature('Proximity', 'PROXIMITY_DRONECAN', 'AP_PROXIMITY_DRONECAN_ENABLED', 'Enable DroneCAN Proximity Sensors', 0, "PROXIMITY,DroneCAN"), # noqa Feature('Proximity', 'PROXIMITY_LIGHTWARE_SF40C', 'AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED', 'Enable LightWare SF40C Proximity Sensors', 0, "PROXIMITY"), # noqa Feature('Proximity', 'PROXIMITY_LIGHTWARE_SF45B', 'AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED', 'Enable LightWare SF45B Proximity Sensors', 0, "PROXIMITY"), # noqa Feature('Proximity', 'PROXIMITY_MAV', 'AP_PROXIMITY_MAV_ENABLED', 'Enable MAVLink Proximity Sensors', 0, "PROXIMITY"), # noqa @@ -276,20 +302,22 @@ def __init__(self, Feature('Baro', 'BMP085', 'AP_BARO_BMP085_ENABLED', 'Enable BMP085 Barometric Sensor', 1, None), Feature('Baro', 'BMP280', 'AP_BARO_BMP280_ENABLED', 'Enable BMP280 Barometric Sensor', 1, None), Feature('Baro', 'BMP388', 'AP_BARO_BMP388_ENABLED', 'Enable BMP388 Barometric Sensor', 1, None), + Feature('Baro', 'BMP581', 'AP_BARO_BMP581_ENABLED', 'Enable BMP581 Barometric Sensor', 1, None), Feature('Baro', 'DPS280', 'AP_BARO_DPS280_ENABLED', 'Enable DPS280/DPS310 Barometric Sensor', 1, None), - Feature('Baro', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None), + # Feature('Baro', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None), Feature('Baro', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, 'AHRS_EXT'), Feature('Baro', 'FBM320', 'AP_BARO_FBM320_ENABLED', 'Enable FBM320 Barometric Sensor', 1, None), - Feature('Baro', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None), + # Feature('Baro', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None), Feature('Baro', 'KELLERLD', 'AP_BARO_KELLERLD_ENABLED', 'Enable KELLERLD Barometric Sensor', 1, None), Feature('Baro', 'LPS2XH', 'AP_BARO_LPS2XH_ENABLED', 'Enable LPS2XH Barometric Sensor', 1, None), Feature('Baro', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), Feature('Baro', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), Feature('Baro', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), - Feature('Baro', 'DRONECAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable DroneCAN Barometric Sensor', 0, None), - Feature('Baro', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), - Feature('Baro', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), + Feature('Baro', 'DRONECAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable DroneCAN Barometric Sensor', 0, "DroneCAN"), + # Feature('Baro', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), + # Feature('Baro', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), Feature('Baro', 'BARO_TEMPCAL', 'AP_TEMPCALIBRATION_ENABLED', 'Enable Baro Temperature Calibration', 0, None), + Feature('Baro', 'BARO_PROBEXT', 'AP_BARO_PROBE_EXTERNAL_I2C_BUSES', 'Enable Probing of External i2c buses', 0, None), Feature('Sensors', 'RPM', 'AP_RPM_ENABLED', 'Enable RPM sensors', 0, None), Feature('Sensors', 'RPM_EFI', 'AP_RPM_EFI_ENABLED', 'Enable RPM EFI sensors', 0, 'RPM,EFI'), @@ -297,52 +325,62 @@ def __init__(self, Feature('Sensors', 'RPM_HARMONIC_NOTCH', 'AP_RPM_HARMONICNOTCH_ENABLED', 'Enable RPM Harmonic Notch sensors', 0, 'RPM,HarmonicNotches'), # noqa Feature('Sensors', 'RPM_PIN', 'AP_RPM_PIN_ENABLED', 'Enable RPM Pin-based sensors', 0, 'RPM'), Feature('Sensors', 'RPM_GENERATOR', 'AP_RPM_GENERATOR_ENABLED', 'Enable Generator RPM sensors', 0, 'RPM,GENERATOR'), + Feature('Sensors', 'RPM_DRONECAN', 'AP_RPM_DRONECAN_ENABLED', 'Enable DroneCAN-based RPM sensors', 0, 'RPM,GENERATOR,DroneCAN'), # noqa Feature('Sensors', 'TEMP', 'AP_TEMPERATURE_SENSOR_ENABLED', 'Enable Temperature Sensors', 0, None), Feature('Sensors', 'TEMP_TSYS01', 'AP_TEMPERATURE_SENSOR_TSYS01_ENABLED', 'Enable Temp Sensor - TSYS01', 0, "TEMP"), Feature('Sensors', 'TEMP_MCP9600', 'AP_TEMPERATURE_SENSOR_MCP9600_ENABLED', 'Enable Temp Sensor - MCP9600', 0, "TEMP"), Feature('Sensors', 'TEMP_TSYS03', 'AP_TEMPERATURE_SENSOR_TSYS03_ENABLED', 'Enable Temp Sensor - TSYS03', 0, "TEMP"), + Feature('Sensors', 'TEMP_MLX90614', 'AP_TEMPERATURE_SENSOR_MLX90614_ENABLED', 'Enable Temp Sensor - MLX90614', 0, "TEMP"), Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users # NOQA: E501 Feature('Sensors', 'BEACON', 'AP_BEACON_ENABLED', 'Enable Beacon', 0, None), Feature('Sensors', 'GPS_MOVING_BASELINE', 'GPS_MOVING_BASELINE', 'Enable GPS Moving Baseline', 0, None), - Feature('Sensors', 'IMU_ON_UART', 'AP_SERIALMANAGER_IMUOUT_ENABLED', 'Enable sending raw IMU data on a serial port', 0, None), # NOQA: E501 + Feature('Sensors', 'IMU_ON_UART', 'AP_SERIALMANAGER_IMUOUT_ENABLED', 'Enable Send raw IMU data on a serial port', 0, None), # NOQA: E501 - Feature('Other', 'HarmonicNotches', 'AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', 'Enable InertialSensor Harmonic Notches', 0, None), # noqa - Feature('Other', 'GyroFFT', 'HAL_GYROFFT_ENABLED', 'Enable In-Flight Gyro FFT calculations', 0, None), - Feature('Other', 'NMEA_OUTPUT', 'HAL_NMEA_OUTPUT_ENABLED', 'Enable NMEA Output', 0, None), - Feature('Other', 'SDCARD_FORMATTING', 'AP_FILESYSTEM_FORMAT_ENABLED', 'Enable formatting of microSD cards', 0, None), + Feature('IMU', 'TEMPCAL', 'HAL_INS_TEMPERATURE_CAL_ENABLE', 'Enable IMU Temperature calibration', 0, None), + Feature('IMU', 'HarmonicNotches', 'AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', 'Enable InertialSensor harmonic notch filters', 0, None), # noqa + Feature('IMU', 'BatchSampler', 'AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED', 'Enable Batch sampler', 0, None), # noqa + + Feature('Other', 'GyroFFT', 'HAL_GYROFFT_ENABLED', 'Enable In-Flight gyro FFT calculations', 0, None), + Feature('Other', 'NMEA_OUTPUT', 'HAL_NMEA_OUTPUT_ENABLED', 'Enable NMEA output', 0, None), + Feature('Other', 'SDCARD_FORMATTING', 'AP_FILESYSTEM_FORMAT_ENABLED', 'Enable Formatting of microSD cards', 0, None), Feature('Other', 'BOOTLOADER_FLASHING', 'AP_BOOTLOADER_FLASHING_ENABLED', 'Enable Bootloader flashing', 0, "FILESYSTEM_ROMFS"), # noqa - Feature('Other', 'SCRIPTING', 'AP_SCRIPTING_ENABLED', 'Enable LUA Scripting', 0, None), + Feature('Other', 'SCRIPTING', 'AP_SCRIPTING_ENABLED', 'Enable Lua Scripting', 0, None), + Feature('Other', 'SERIALDEVICE_REGISTER', 'AP_SERIALMANAGER_REGISTER_ENABLED', 'Enable Serial device registration', 0, None), # noqa + Feature('Other', 'SCRIPTING_SERIALDEVICE', 'AP_SCRIPTING_SERIALDEVICE_ENABLED', 'Enable Lua serial device simulation', 0, "SCRIPTING,SERIALDEVICE_REGISTER"), # noqa Feature('Other', 'SLCAN', 'AP_CAN_SLCAN_ENABLED', 'Enable SLCAN serial protocol', 0, None), - Feature('Other', 'SDCARD_MISSION', 'AP_SDCARD_STORAGE_ENABLED', 'Enable storing mission on microSD cards', 0, None), - Feature('Other', 'COMPASS_CAL', 'COMPASS_CAL_ENABLED', 'Enable "tumble" compass calibration', 0, None), - Feature('Other', 'DRONECAN_SERIAL', 'AP_DRONECAN_SERIAL_ENABLED', 'Enable DroneCAN virtual serial ports', 0, None), + Feature('Other', 'SDCARD_MISSION', 'AP_SDCARD_STORAGE_ENABLED', 'Enable Storing mission on microSD cards', 0, None), + Feature('Other', 'COMPASS_CAL', 'COMPASS_CAL_ENABLED', 'Enable "Tumble" compass calibration', 0, None), + Feature('Other', 'DRONECAN_SERIAL', 'AP_DRONECAN_SERIAL_ENABLED', 'Enable DroneCAN virtual serial ports', 0, "DroneCAN,SERIALDEVICE_REGISTER"), # NOQA: E501 Feature('Other', 'Buttons', 'HAL_BUTTON_ENABLED', 'Enable Buttons', 0, None), Feature('Other', 'Logging', 'HAL_LOGGING_ENABLED', 'Enable Logging', 0, None), - Feature('Other', 'CUSTOM_ROTATIONS', 'AP_CUSTOMROTATIONS_ENABLED', 'Enable Custom Rotations', 0, None), + Feature('Other', 'CUSTOM_ROTATIONS', 'AP_CUSTOMROTATIONS_ENABLED', 'Enable Custom sensor rotations', 0, None), # MAVLink section for mavlink features and/or message handling, # rather than for e.g. mavlink-based sensor drivers Feature('MAVLink', 'HIGHLAT2', 'HAL_HIGH_LATENCY2_ENABLED', 'Enable HighLatency2 Support', 0, None), - Feature('MAVLink', 'FENCEPOINT_PROTOCOL', 'AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'Enable old MAVLink FencePoint protocol', 0, "FENCE"), # noqa - Feature('MAVLink', 'RALLYPOINT_PROTOCOL', 'AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED', 'Enable old MAVLink RallyPoint protocol', 0, "RALLY"), # noqa - Feature('MAVLink', 'MAVLINK_VERSION_REQUEST', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'Enable old AUTOPILOT_VERSION_REQUEST mesage', 0, None), # noqa - Feature('MAVLink', 'REQUEST_AUTOPILOT_CAPA', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'Enable old REQUEST_AUTOPILOT_CAPABILITIES command', 0, None), # noqa - Feature('MAVLink', 'MAV_MSG_RELAY_STATUS', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'Enable sending of RELAY_STATUS message', 0, 'RELAY'), # noqa - Feature('MAVLink', 'MAV_MSG_MOUNT_CONTROL', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'Enable handling of deprecated MOUNT_CONTROL message', 0, None), # noqa - Feature('MAVLink', 'MAV_MSG_MOUNT_CONFIGURE', 'AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', 'Enable handling of deprecated MOUNT_CONFIGURE message', 0, None), # noqa - Feature('MAVLink', 'AP_MAVLINK_BATTERY2_ENABLED', 'AP_MAVLINK_BATTERY2_ENABLED', 'Enable sending of old BATTERY2 message', 0, None), # noqa - Feature('MAVLink', 'MAV_DEVICE_OP', 'AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'Enable handling of DeviceOp mavlink messages', 0, None), # noqa - Feature('MAVLink', 'MAV_SERVO_RELAY', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'Enable handling of ServoRelay mavlink messages', 0, 'SERVORELAY_EVENTS'), # noqa - Feature('MAVLink', 'MAV_MSG_SERIAL_CONTROL', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'Enable handling of Serial Control mavlink messages', 0, None), # noqa - Feature('MAVLink', 'MAVLINK_MSG_MISSION_REQUEST', 'AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'Enable handling of MISSION_REQUEST mavlink messages', 0, None), # noqa - Feature('MAVLink', 'AP_MAVLINK_FTP_ENABLED', 'AP_MAVLINK_FTP_ENABLED', 'Enable MAVLink FTP Protocol', 0, None), # noqa + Feature('MAVLink', 'FENCEPOINT_PROTOCOL', 'AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'Enable Old MAVLink fence points protocol', 0, "FENCE"), # noqa + Feature('MAVLink', 'RALLYPOINT_PROTOCOL', 'AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED', 'Enable Old MAVLink rally points protocol', 0, "RALLY"), # noqa + Feature('MAVLink', 'MAVLINK_VERSION_REQUEST', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'Enable Old AUTOPILOT_VERSION_REQUEST mesage', 0, None), # noqa + Feature('MAVLink', 'REQUEST_AUTOPILOT_CAPA', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'Enable Old REQUEST_AUTOPILOT_CAPABILITIES command', 0, None), # noqa + Feature('MAVLink', 'MAV_MSG_RELAY_STATUS', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'Enable Send RELAY_STATUS message', 0, 'RELAY'), # noqa + Feature('MAVLink', 'MAV_MSG_MOUNT_CONTROL', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'Enable Deprecated MOUNT_CONTROL message', 0, "MOUNT"), # noqa + Feature('MAVLink', 'MAV_MSG_MOUNT_CONFIGURE', 'AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', 'Enable Deprecated MOUNT_CONFIGURE message', 0, "MOUNT"), # noqa + Feature('MAVLink', 'AP_MAVLINK_BATTERY2_ENABLED', 'AP_MAVLINK_BATTERY2_ENABLED', 'Enable Send old BATTERY2 message', 0, None), # noqa + Feature('MAVLink', 'MAV_DEVICE_OP', 'AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'Enable DeviceOp MAVLink messages', 0, None), # noqa + Feature('MAVLink', 'MAV_SERVO_RELAY', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'Enable ServoRelay MAVLink messages', 0, 'SERVORELAY_EVENTS'), # noqa + Feature('MAVLink', 'MAV_MSG_SERIAL_CONTROL', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'Enable Serial Control MAVLink messages', 0, None), # noqa + Feature('MAVLink', 'MAVLINK_MSG_MISSION_REQUEST', 'AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'Enable MISSION_REQUEST MAVLink messages', 0, None), # noqa + Feature('MAVLink', 'MAVLINK_MSG_RC_CHANNELS_RAW', 'AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED', 'Enable RC_CHANNELS_RAW MAVLink messages', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_FTP_ENABLED', 'AP_MAVLINK_FTP_ENABLED', 'Enable MAVLink FTP protocol', 0, None), # noqa + Feature('MAVLink', 'MAV_CMD_SET_HAGL', 'AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED', 'Enable MAVLink HAGL command', 0, None), # noqa + Feature('MAVLink', 'VIDEO_STREAM_INFORMATION', 'AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED', 'Enable MAVLink VIDEO_STREAM_INFORMATION message', 0, "Camera"), # noqa Feature('Developer', 'KILL_IMU', 'AP_INERTIALSENSOR_KILL_IMU_ENABLED', 'Allow IMUs to be disabled at runtime', 0, None), Feature('Developer', 'CRASHCATCHER', 'AP_CRASHDUMP_ENABLED', 'Enable CrashCatcher', 0, None), - Feature('GPS Drivers', 'UBLOX', 'AP_GPS_UBLOX_ENABLED', 'Enable u-blox GPS', 1, 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), @@ -353,32 +391,33 @@ def __init__(self, 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('GPS Drivers', 'DroneCAN_Out', 'AP_DRONECAN_SEND_GPS', 'Enable Sending GPS from Autopilot', 0, None), + Feature('GPS Drivers', 'DroneCAN_GPS_Out', 'AP_DRONECAN_SEND_GPS', 'Enable Sending GPS data from Autopilot', 0, "DroneCAN"), # noqa:401 + Feature('GPS Drivers', 'GPS_Blending', 'AP_GPS_BLENDED_ENABLED', 'Enable GPS Blending', 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_AIRSPEED', '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', 'DRONECAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'ENABLE DroneCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 + 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_AIRSPEED', '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', 'DRONECAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'Enable DroneCAN AIRSPEED', 0, 'AIRSPEED,DroneCAN'), # NOQA: E501 Feature('Actuators', 'Volz', 'AP_VOLZ_ENABLED', 'Enable Volz Protocol', 0, None), - Feature('Actuators', 'Volz_DroneCAN', 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', 'Enable Volz DroneCAN Feedback', 0, None), - Feature('Actuators', 'RobotisServo', 'AP_ROBOTISSERVO_ENABLED', 'Enable RobotisServo Protocol', 0, None), - Feature('Actuators', 'SBUS Output', 'AP_SBUSOUTPUT_ENABLED', 'Enable SBUS Output on serial ports', 0, None), + Feature('Actuators', 'Volz_DroneCAN', 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', 'Enable Volz DroneCAN Feedback', 0, "DroneCAN,Volz"), # noqa: E501 + Feature('Actuators', 'RobotisServo', 'AP_ROBOTISSERVO_ENABLED', 'Enable RobotisServo protocol', 0, None), + Feature('Actuators', 'SBUS Output', 'AP_SBUSOUTPUT_ENABLED', 'Enable SBUS output on serial ports', 0, None), Feature('Actuators', 'FETTecOneWire', 'AP_FETTEC_ONEWIRE_ENABLED', 'Enable FETTec OneWire ESCs', 0, None), Feature('Actuators', 'KDECAN', 'AP_KDECAN_ENABLED', 'KDE Direct KDECAN ESC', 0, None), - Feature('Actuators', 'HimarkServo', 'AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'Enable Himark DroneCAN servos', 0, None), - Feature('Actuators', 'HobbywingESC', 'AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'Enable Hobbywing DroneCAN ESCs', 0, None), + Feature('Actuators', 'HimarkServo', 'AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'Enable Himark DroneCAN servos', 0, "DroneCAN"), + Feature('Actuators', 'HobbywingESC', 'AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'Enable Hobbywing DroneCAN ESCs', 0, "DroneCAN"), Feature('Actuators', 'IrisOrca', 'HAL_IRISORCA_ENABLED', 'Enable Iris Orca Actuator', 0, None), - Feature('Precision Landing', 'PrecLand', 'AC_PRECLAND_ENABLED', 'Enable Precision Landing support', 0, None), - Feature('Precision Landing', 'PrecLand - Companion', 'AC_PRECLAND_COMPANION_ENABLED', 'Enable Companion-Supported Precision Landing support', 0, "PrecLand"), # noqa - Feature('Precision Landing', 'PrecLand - IRLock', 'AC_PRECLAND_IRLOCK_ENABLED', 'Enable IRLock-Supported Precision Landing support', 0, "PrecLand"), # noqa + Feature('Precision Landing', 'PrecLand', 'AC_PRECLAND_ENABLED', 'Enable Precision landing support', 0, None), + Feature('Precision Landing', 'PrecLand - Companion', 'AC_PRECLAND_COMPANION_ENABLED', 'Enable Companion computer precision landing ', 0, "PrecLand"), # noqa + Feature('Precision Landing', 'PrecLand - IRLock', 'AC_PRECLAND_IRLOCK_ENABLED', 'Enable IRLock precision landing support', 0, "PrecLand"), # noqa # Feature('Filesystem', 'FILESYSTEM_ESP32_ENABLED', 'AP_FILESYSTEM_ESP32_ENABLED', 'Enable ESP32 Filesystem', 0, None), # Feature('Filesystem', 'FILESYSTEM_FATFS', 'AP_FILESYSTEM_FATFS_ENABLED', 'Enable FATFS Filesystem', 0, None), @@ -389,7 +428,10 @@ def __init__(self, Feature('Filesystem', 'FILESYSTEM_SYS', 'AP_FILESYSTEM_SYS_ENABLED', 'Enable @SYS/ filesystem', 0, None), Feature('Filesystem', 'APJ_TOOL_PARAMETERS', 'FORCE_APJ_DEFAULT_PARAMETERS', 'Enable apj_tool parameter area', 0, None), - Feature('Networking', 'PPP Support', 'AP_NETWORKING_BACKEND_PPP', 'Enable PPP networking', 0, None), + Feature('Networking', 'PPP', 'AP_NETWORKING_BACKEND_PPP', 'Enable PPP networking', 0, None), + Feature('Networking', 'CAN MCAST', 'AP_NETWORKING_CAN_MCAST_ENABLED', 'Enable CAN multicast bridge', 0, None), + + Feature('DroneCAN', 'DroneCAN', 'HAL_ENABLE_DRONECAN_DRIVERS', 'Enable DroneCAN support', 0, None), ] BUILD_OPTIONS.sort(key=lambda x: (x.category + x.label)) diff --git a/Tools/scripts/pretty_diff_size.py b/Tools/scripts/build_tests/pretty_diff_size.py similarity index 89% rename from Tools/scripts/pretty_diff_size.py rename to Tools/scripts/build_tests/pretty_diff_size.py index 79598d706fb221..59d0c1eadeacb5 100755 --- a/Tools/scripts/pretty_diff_size.py +++ b/Tools/scripts/build_tests/pretty_diff_size.py @@ -90,6 +90,21 @@ def print_table(summary_data_list_second, summary_data_list_master): print_data.append(col_data) print(tabulate(print_data, headers=["Binary Name", "Text [B]", "Data [B]", "BSS (B)", "Total Flash Change [B] (%)", "Flash Free After PR (B)"])) + # Get the GitHub Actions summary file path + summary_file = os.getenv('GITHUB_STEP_SUMMARY') + if summary_file: + # Append the output to the summary file + with open(summary_file, 'a') as f: + f.write("### Diff summary\n") + f.write(tabulate(print_data, headers=[ + "Binary Name", + "Text [B]", + "Data [B]", + "BSS (B)", + "Total Flash Change [B] (%)", + "Flash Free After PR (B)" + ], tablefmt="github")) + f.write("\n") def extract_binaries_size(path): diff --git a/Tools/scripts/build_tests/test_ccache.py b/Tools/scripts/build_tests/test_ccache.py index c0d5543d1ebd0b..9abdb22badef6c 100755 --- a/Tools/scripts/build_tests/test_ccache.py +++ b/Tools/scripts/build_tests/test_ccache.py @@ -65,11 +65,22 @@ def build_board(boardname): build_board(boards[0]) subprocess.run(["ccache", "-z"]) build_board(boards[1]) -subprocess.run(["ccache", "-s"]) +result = subprocess.run(["ccache", "-s"], capture_output=True, text=True) +print(result.stdout) + +# Get the GitHub Actions summary file path +summary_file = os.getenv('GITHUB_STEP_SUMMARY') post = ccache_stats() hit_pct = 100 * post[0] / float(post[0]+post[1]) print("ccache hit percentage: %.1f%% %s" % (hit_pct, post)) +if summary_file: + # Append the output to the summary file + with open(summary_file, 'a') as f: + f.write(f"### ccache -s Output with {boards}\n") + f.write(f"```\n{result.stdout}\n```\n") + f.write(f"### ccache hit percentage (min {args.min_cache_pct})\n") + f.write("ccache hit percentage: %.1f%% %s\n" % (hit_pct, post)) if hit_pct < args.min_cache_pct: print("ccache hits too low, need %d%%" % args.min_cache_pct) sys.exit(1) diff --git a/Tools/scripts/create_OEM_board.py b/Tools/scripts/create_OEM_board.py index 6ba5b0fc530bfe..7d9c9dd750c921 100755 --- a/Tools/scripts/create_OEM_board.py +++ b/Tools/scripts/create_OEM_board.py @@ -3,27 +3,66 @@ """ script to automatically create a copy of a board for an OEM setup usage example : ./Tools/scripts/create_OEM_board.py mRoPixracerPro mRoPixracerPro-MyCompany + +AP_FLAKE8_CLEAN """ import sys import os import subprocess -board_name = sys.argv[1] -oem_board_name = sys.argv[2] +import pathlib + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../libraries/AP_HAL_ChibiOS/hwdef/scripts')) +import chibios_hwdef # noqa + + +class OEMCreate: + def __init__(self, oem_board_name, board_name): + self.oem_board_name = oem_board_name + self.board_name = board_name + + def run(self): + hwdef_dir = "libraries/AP_HAL_ChibiOS/hwdef" + oem_board_dirpath = f"{hwdef_dir}/{oem_board_name}" + + if os.path.exists(oem_board_dirpath): + raise ValueError(f"{oem_board_dirpath} already exists") # FIXME exception type + + hwdef_include_relpath = None + for extension in "dat", "inc": + tmp = f"../{board_name}/hwdef.{extension}" + tmp_norm = os.path.normpath(f"{oem_board_dirpath}/{tmp}") + if os.path.exists(tmp_norm): + hwdef_include_relpath = tmp + hwdef_include_normpath = tmp_norm + break + hwdef_content = f"include {hwdef_include_relpath}\n" -# directory creation -if not os.path.exists("libraries/AP_HAL_ChibiOS/hwdef/%s" % oem_board_name): - subprocess.run(["mkdir", "libraries/AP_HAL_ChibiOS/hwdef/%s" % oem_board_name]) - # create files and add reference to originals - f=open("libraries/AP_HAL_ChibiOS/hwdef/%s/hwdef.dat" % oem_board_name, "x") - f.write("include ../%s/hwdef.dat" % board_name) - f.close() - f=open("libraries/AP_HAL_ChibiOS/hwdef/%s/hwdef-bl.dat" % oem_board_name, "x") - f.write("include ../%s/hwdef-bl.dat" % board_name) - f.close() - if os.path.exists("libraries/AP_HAL_ChibiOS/hwdef/%s/defaults.parm" % board_name): - subprocess.run(["cp", "libraries/AP_HAL_ChibiOS/hwdef/%s/defaults.parm" % board_name, "libraries/AP_HAL_ChibiOS/hwdef/%s/defaults.parm" % oem_board_name]) + ch = chibios_hwdef.ChibiOSHWDef(hwdef_include_normpath) + use_bootloader_from_board = ch.get_config('USE_BOOTLOADER_FROM_BOARD', default=None, required=False) + if use_bootloader_from_board is None: + hwdef_content += "\n" + hwdef_content += f"USE_BOOTLOADER_FROM_BOARD {board_name}\n" + subprocess.run(["mkdir", oem_board_dirpath]) + + # create files and add reference to originals + new_hwdef = pathlib.Path(oem_board_dirpath, "hwdef.dat") + + if hwdef_include_relpath is None: + raise ValueError(f"Could not find .inc or .dat for {board_name}") + + new_hwdef.write_text(hwdef_content) + + if os.path.exists(f"{hwdef_dir}/{board_name}/defaults.parm"): + path = pathlib.Path(f"{hwdef_dir}/{oem_board_name}/defaults.parm") + path.write_text(f"@include ../{board_name}/defaults.parm\n") # noqa + + +board_name = sys.argv[1] +oem_board_name = sys.argv[2] +oemcreate = OEMCreate(board_name, oem_board_name) +oemcreate.run() diff --git a/Tools/scripts/cygwin_build.sh b/Tools/scripts/cygwin_build.sh index 8c8228df90afa5..b64892026964ab 100755 --- a/Tools/scripts/cygwin_build.sh +++ b/Tools/scripts/cygwin_build.sh @@ -18,8 +18,6 @@ $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 diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 04cf8b1738d954..8841d06d8769e5 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -66,6 +66,7 @@ def num(s): 0x14 : "DEVTYPE_AK09918", 0x15 : "DEVTYPE_AK09915", 0x16 : "DEVTYPE_QMC5883P", + 0x17 : "DEVTYPE_BMM350", } imu_types = { @@ -102,6 +103,8 @@ def num(s): 0x39 : "DEVTYPE_INS_BMI085", 0x3A : "DEVTYPE_INS_ICM42670", 0x3B : "DEVTYPE_INS_ICM45686", + 0x3C : "DEVTYPE_INS_SCHA63T", + 0x3D : "DEVTYPE_INS_IIM42653", } baro_types = { @@ -125,6 +128,7 @@ def num(s): 0x12 : "DEVTYPE_BARO_MS5837", 0x13 : "DEVTYPE_BARO_MS5637", 0x14 : "DEVTYPE_BARO_BMP390", + 0x15 : "DEVTYPE_BARO_BMP581", } airspeed_types = { diff --git a/Tools/scripts/esp32_get_idf.sh b/Tools/scripts/esp32_get_idf.sh index f7e8318b472fd3..a7ec1917016776 100755 --- a/Tools/scripts/esp32_get_idf.sh +++ b/Tools/scripts/esp32_get_idf.sh @@ -1,5 +1,8 @@ #!/usr/bin/env bash # if you have modules/esp_idf setup as a submodule, then leave it as a submodule and switch branches + +COMMIT="cc3203dc4f087ab41b434afff1ed7520c6d90993" + if [ ! -d modules ]; then echo "this script needs to be run from the root of your repo, sorry, giving up." exit 1 @@ -13,6 +16,7 @@ if [ ! -d esp_idf ]; then else echo 'found modules/esp_idf folder' ; fi + echo "looking for submodule or repo..." if [ `git submodule | grep esp_idf | wc | cut -c1-7` == '1' ]; then echo "found real submodule, syncing" @@ -23,40 +27,44 @@ else if [ ! `ls esp_idf/install.sh 2>/dev/null` ]; then echo "found empty IDF, cloning" # add esp_idf as almost submodule, depths uses less space - #git clone -b v4.4 --single-branch --depth 10 https://github.com/espressif/esp-idf.git esp_idf - git clone -b 'release/v4.4' https://github.com/espressif/esp-idf.git esp_idf - git checkout 6d853f - # check if we've got v4.4 checked out, only this version of esp_idf is tested and works? - + git clone -b 'release/v5.3' https://github.com/espressif/esp-idf.git esp_idf + git checkout $COMMIT fi fi - - echo "inspecting possible IDF... " cd esp_idf echo `git rev-parse HEAD` -# these are a selection of possible specific commit/s that represent v4.4 branch of the esp_idf -if [ `git rev-parse HEAD` == '6d853f0525b003afaeaed4fb59a265c8522c2da9' ]; then - echo "IDF version 'release/4.4' found OK, great."; +# these are a selection of possible specific commit/s that represent v5.3 branch of the esp_idf +if [ `git rev-parse HEAD` == '$COMMIT' ]; then + echo "IDF version 'release/5.3' found OK, great."; else - echo "looks like an idf, but not v4.4 branch, or wrong commit , trying to switch branch and reflect upstream"; + echo "looks like an idf, but not v5.3 branch, or wrong commit , trying to switch branch and reflect upstream"; ../../Tools/gittools/submodule-sync.sh >/dev/null - git fetch ; git checkout -f release/v4.4 - git checkout 6d853f + git fetch ; git checkout -f release/v5.3 + git checkout $COMMIT # retry same as above echo `git rev-parse HEAD` - if [ `git rev-parse HEAD` == '6d853f0525b003afaeaed4fb59a265c8522c2da9' ]; then - echo "IDF version 'release/4.4' found OK, great."; - git checkout 6d853f + if [ `git rev-parse HEAD` == '$COMMIT' ]; then + echo "IDF version 'release/5.3' found OK, great."; + git checkout $COMMIT fi fi cd ../.. -cd modules/esp_idf +cd modules/esp_idf git submodule update --init --recursive + +echo +echo "installing missing python modules" +python -m pip install empy==3.3.4 +python -m pip install pexpect +python -m pip install future + cd ../.. -echo "after changing IDF versions [ such as between 4.2 and 4.4 ] you should re-run these in your console:" + +echo +echo "after changing IDF versions [ such as between 4.4 and 5.3 ] you should re-run these in your console:" echo "./modules/esp_idf/install.sh" echo "source ./modules/esp_idf/export.sh" diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 4730767d327ec1..63ac8a13574d46 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -62,6 +62,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_EFI_ENABLED', 'AP_EFI::AP_EFI',), ('AP_EFI_{type}_ENABLED', 'AP_EFI_(?P.*)::update',), + ('AP_EXTENDED_ESC_TELEM_ENABLED', r'AP_DroneCAN::handle_esc_ext_status\b',), + ('AP_TEMPERATURE_SENSOR_ENABLED', 'AP_TemperatureSensor::AP_TemperatureSensor',), ('AP_TEMPERATURE_SENSOR_{type}_ENABLED', 'AP_TemperatureSensor_(?P.*)::update',), @@ -73,14 +75,15 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',), ('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',), ('HAL_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',), - ('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_{type}::healthy\b',), - ('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor::TCal::Learn::save_calibration',), + ('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_(?P.*)::healthy\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_{type}_ENABLED', r'AP_RangeFinder_(?P.*)::handle_frame\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',), @@ -88,6 +91,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',), ('AP_RANGEFINDER_RDS02UF_ENABLED', r'AP_RangeFinder_RDS02UF::get_reading\b',), + ('AP_GPS_NMEA_UNICORE_ENABLED', r'AP_GPS_NMEA::parse_agrica_field',), ('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P.*)::read\b',), ('AP_OPTICALFLOW_ENABLED', 'AP_OpticalFlow::AP_OpticalFlow',), @@ -105,14 +109,15 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_BATTERY_{type}_ENABLED', r'AP_BattMonitor_(?P.*)::init\b',), ('AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', r'AP_BattMonitor_Backend::update_esc_telem_outbound\b',), - ('AP_BATTERY_WATT_MAX_ENABLED', 'AP_BattMonitor_Params::_watt_max',), + ('AP_BATTERY_WATT_MAX_ENABLED', 'Plane::throttle_watt_limiter',), ('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_MOUNT_STORM32SERIAL_ENABLED', 'AP_Mount_SToRM32_serial::update',), + ('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::update',), + ('HAL_SPEKTRUM_TELEM_ENABLED', r'AP::spektrum_telem',), ('HAL_{type}_TELEM_ENABLED', r'AP_(?P.*)_Telem::init',), ('AP_{type}_TELEM_ENABLED', r'AP_(?P.*)_Telem::init',), ('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',), @@ -122,7 +127,10 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_FRSKY_TELEM_ENABLED', 'AP::frsky_telem',), ('AP_FRSKY_D_TELEM_ENABLED', 'AP_Frsky_D::send',), ('AP_FRSKY_SPORT_TELEM_ENABLED', 'AP_Frsky_SPort::send_sport_frame',), - ('AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'AP::frsky_passthrough_telem',), + ('AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'AP_Frsky_SPort_Passthrough::process_packet',), + ('HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', 'AP_Frsky_SPort_Passthrough::set_telem_data'), + + ('AP_IBUS_TELEM_ENABLED', 'AP_IBus_Telem::init',), ('MODE_{type}_ENABLED', r'Mode(?P.+)::init',), ('MODE_GUIDED_NOGPS_ENABLED', r'ModeGuidedNoGPS::init',), @@ -130,6 +138,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_CAMERA_ENABLED', 'AP_Camera::var_info',), ('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P.*)::trigger_pic',), ('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'), + ('AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'AP_Camera::send_camera_thermal_range'), + ('AP_CAMERA_INFO_FROM_SCRIPT_ENABLED', 'AP_Camera_Backend::set_camera_information'), ('HAL_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',), ('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',), @@ -139,7 +149,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',), ('AP_FENCE_ENABLED', r'AC_Fence::check\b',), - ('HAL_RALLY_ENABLED', r'AP_Rally::get_rally_max\b',), + ('HAL_RALLY_ENABLED', 'AP_Rally::find_nearest_rally_point',), ('AP_AVOIDANCE_ENABLED', 'AC_Avoid::AC_Avoid',), ('AP_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',), ('AC_PAYLOAD_PLACE_ENABLED', 'PayloadPlace::start_descent'), @@ -164,20 +174,23 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_CHECK_FIRMWARE_ENABLED', 'AP_CheckFirmware::check_signed_bootloader',), ('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',), + ('AP_PLANE_GLIDER_PULLUP_ENABLED', 'GliderPullup::in_pullup',), ('QAUTOTUNE_ENABLED', 'ModeQAutotune::_enter',), ('HAL_SOARING_ENABLED', 'SoaringController::var_info',), - ('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::terminate\b',), + ('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::override_servos',), ('AP_GRIPPER_ENABLED', r'AP_Gripper::init\b',), ('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',), ('AP_LANDINGGEAR_ENABLED', r'AP_LandingGear::init\b',), ('AP_WINCH_ENABLED', 'AP_Winch::AP_Winch',), + ('AP_WINCH_{type}_ENABLED', r'AP_Winch_(?P.*)::update\b',), ('AP_RELAY_ENABLED', 'AP_Relay::init',), ('AP_SERVORELAYEVENTS_ENABLED', 'AP_ServoRelayEvents::update_events',), ('AP_RCPROTOCOL_ENABLED', r'AP_RCProtocol::init\b',), + ('AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', r'AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels',), ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::_process_byte\b',), - ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::_process_pulse\b',), + ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::process_pulse\b',), ('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',), ('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_DroneCAN::handle_actuator_status_Volz\b',), @@ -191,11 +204,13 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_OPENDRONEID_ENABLED', 'AP_OpenDroneID::update',), - ('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',), + ('GPS_MOVING_BASELINE', r'MovingBase::var_info',), ('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',), + ('AP_GPS_BLENDED_ENABLED', r'AP_GPS::calc_blend_weights\b',), ('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',), ('AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', r'AP_InertialSensor::HarmonicNotch::update_params\b',), + ('AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED', r'AP_InertialSensor::BatchSampler::init'), ('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',), ('HAL_DISPLAY_ENABLED', r'Display::init\b',), ('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',), @@ -203,11 +218,13 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_TEMPCALIBRATION_ENABLED', r'AP_TempCalibration::apply_calibration',), ('HAL_PICCOLO_CAN_ENABLE', r'AP_PiccoloCAN::update',), - ('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3::writeExtNavVelData'), + ('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3_core::CorrectExtNavVelForSensorOffset'), ('EK3_FEATURE_DRAG_FUSION', r'NavEKF3_core::FuseDragForces'), + ('EK3_FEATURE_OPTFLOW_FUSION', r'NavEKF3_core::FuseOptFlow'), ('AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED', r'RC_Channel::lookuptable',), ('AP_SCRIPTING_ENABLED', r'AP_Scripting::init',), + ('AP_SCRIPTING_SERIALDEVICE_ENABLED', r'AP_Scripting_SerialDevice::init',), ('AP_NOTIFY_TONEALARM_ENABLED', r'AP_ToneAlarm::init'), ('AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', r'AP_Notify::handle_play_tune'), @@ -236,8 +253,11 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'GCS_MAVLINK::handle_device_op_write'), ('AP_MAVLINK_SERVO_RELAY_ENABLED', 'GCS_MAVLINK::handle_servorelay_message'), ('AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'GCS_MAVLINK::handle_serial_control'), - ('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_mission_request\b'), + ('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', r'GCS_MAVLINK::handle_mission_request\b'), + ('AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED', r'GCS_MAVLINK::send_rc_channels_raw\b'), ('AP_MAVLINK_FTP_ENABLED', 'GCS_MAVLINK::ftp_worker'), + ('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED', 'Plane::handle_external_hagl'), + ('AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED', 'AP_Camera::send_video_stream_information'), ('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'), ('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'), @@ -246,13 +266,24 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'), ('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'), ('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'), + ('AP_NETWORKING_CAN_MCAST_ENABLED', 'AP_Networking_CAN::start'), ('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'), ('HAL_BUTTON_ENABLED', 'AP_Button::update'), ('HAL_LOGGING_ENABLED', 'AP_Logger::init'), - ('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'AP_Compass::mag_cal_fixed_yaw'), + ('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Compass::mag_cal_fixed_yaw'), ('COMPASS_LEARN_ENABLED', 'CompassLearn::update'), - ('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotation::init'), + ('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'), ('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'), + ('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'), + ('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'), + ('AP_RSSI_ENABLED', r'AP_RSSI::init'), + + ('AP_ROVER_ADVANCED_FAILSAFE_ENABLED', r'Rover::afs_fs_check'), + ('AP_COPTER_ADVANCED_FAILSAFE_ENABLED', r'Copter::afs_fs_check'), + + ('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', r'GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands'), + ('AP_SERIALMANAGER_REGISTER_ENABLED', r'AP_SerialManager::register_port'), + ('AP_QUICKTUNE_ENABLED', r'AP_Quicktune::update'), ] def progress(self, msg): diff --git a/Tools/scripts/extract_param_defaults.py b/Tools/scripts/extract_param_defaults.py index cf50e16ab21e5b..4036b3900f7323 100755 --- a/Tools/scripts/extract_param_defaults.py +++ b/Tools/scripts/extract_param_defaults.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/env python3 ''' Extracts parameter default values from an ArduPilot .bin log file. diff --git a/Tools/scripts/filter_size_compare_branches_csv.py b/Tools/scripts/filter_size_compare_branches_csv.py index 8030608c5e7475..aa42fa2a097dc2 100755 --- a/Tools/scripts/filter_size_compare_branches_csv.py +++ b/Tools/scripts/filter_size_compare_branches_csv.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/env python3 import argparse import csv diff --git a/Tools/scripts/firmware_version_decoder.py b/Tools/scripts/firmware_version_decoder.py index cf3321701490d7..3ef137f4e30c13 100755 --- a/Tools/scripts/firmware_version_decoder.py +++ b/Tools/scripts/firmware_version_decoder.py @@ -18,6 +18,18 @@ class FirmwareVersionType(enum.Enum): Official = 255 EnumEnd = 256 + @staticmethod + def get_release(version: int) -> str: + """ + Return the closest release type for a given version type, going down. + This is required because it is common in ardupilot to increase the version type + for successive betas, such as here: + https://github.com/ArduPilot/ardupilot/blame/8890c44370a7cf27d5efc872ef6da288ae3bc41f/ArduCopter/version.h#L12 + """ + for release in reversed(FirmwareVersionType): + if version >= release.value: + return release + return "Unknown" class VehicleType(enum.Enum): Rover = 1 @@ -193,7 +205,7 @@ def unpack_fwversion(self) -> None: self.fwversion.major = self.unpack("B") self.fwversion.minor = self.unpack("B") self.fwversion.patch = self.unpack("B") - self.fwversion.firmware_type = FirmwareVersionType(self.unpack("B")) + self.fwversion.firmware_type = FirmwareVersionType.get_release(self.unpack("B")) self.fwversion.os_software_version = self.unpack("I") self.fwversion.firmware_string = self.unpack_string_from_pointer() diff --git a/Tools/scripts/format.sh b/Tools/scripts/format.sh deleted file mode 100755 index 4ad18ba18cdfd3..00000000000000 --- a/Tools/scripts/format.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -function format { - DIR=$1 - find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec astyle {} \; - find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec rm -f {}.orig \; -} - -format apo -format ArduRover -format ArduBoat -format libraries/APO -format libraries/AP_Common -format libraries/AP_GPS diff --git a/Tools/scripts/generate_lua_docs.sh b/Tools/scripts/generate_lua_docs.sh new file mode 100755 index 00000000000000..3ecc4fc9e60ee4 --- /dev/null +++ b/Tools/scripts/generate_lua_docs.sh @@ -0,0 +1,25 @@ +#!/usr/bin/env bash +# Generate md file from lua docs with lua-language-sever + +cd "$(dirname "$0")" +cd ../.. + +if [ -n "$(ls -A lualogs)" ]; then + echo "lualogs Not Empty" + exit 1 +fi + +if [ -e "lua-language-server/bin/lua-language-server" ]; then + LLS_PATH=$(realpath lua-language-server/bin/lua-language-server) +else + LLS_PATH=lua-language-server +fi + +# Need to use abs paths due to lua-language-sever bug +CONFIG_PATH=$(realpath libraries/AP_Scripting/tests/docs.json) +DOC_PATH=$(realpath libraries/AP_Scripting/docs/) + +${LLS_PATH} --configpath ${CONFIG_PATH} --logpath lualogs --doc ${DOC_PATH} + +mv lualogs/doc.md ScriptingDocs.md +rm -r lualogs diff --git a/Tools/scripts/generate_manifest.py b/Tools/scripts/generate_manifest.py index 9492ae627d2a5e..722c24b551ee60 100755 --- a/Tools/scripts/generate_manifest.py +++ b/Tools/scripts/generate_manifest.py @@ -105,6 +105,8 @@ "SkystarsH7HD" : ("Skystars", "H743 HD"), "SkystarsH7HD-bdshot" : ("Skystars", "H743 HD"), "MicoAir405v2" : ("MicoAir F405 v2.1", "MicoAir"), + "MicoAir405Mini" : ("MicoAir F405 Mini", "MicoAir"), + "GEPRCF745BTHD": ("TAKER F745 BT","GEPRC"), } class Firmware(): diff --git a/Tools/scripts/generate_pdef.xml_metadata.py b/Tools/scripts/generate_pdef.xml_metadata.py new file mode 100755 index 00000000000000..8c52f06ea9dbcb --- /dev/null +++ b/Tools/scripts/generate_pdef.xml_metadata.py @@ -0,0 +1,114 @@ +#!/usr/bin/env python3 + +''' +Rsync apm.pdef.xml files for different versions of the ArduPilot firmware +For each version, it checks out the corresponding tag, generates parameter metadata, +and finally rsyncs the updated parameter metadata pdef.xml files. + +SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas + +SPDX-License-Identifier: GPL-3.0-or-later +''' + +import os +import datetime +import shutil +import subprocess + +VEHICLE_TYPES = ["Copter", "Plane", "Rover", "ArduSub", "Tracker"] # Add future vehicle types here +RSYNC_USERNAME = 'amilcar' + +# Store the current working directory +old_cwd = os.getcwd() + +def get_vehicle_tags(vehicle_type): + """ + Lists all tags in the ArduPilot repository that start with the given vehicle type followed by '-'. + Returns a list of tag names. + """ + try: + # Change to the ArduPilot directory + os.chdir('../ardupilot/') + tags_output = subprocess.check_output(['git', 'tag', '--list', f'{vehicle_type}-[0-9]\\.[0-9]\\.[0-9]'], text=True) + return tags_output.splitlines() + except Exception as e: # pylint: disable=broad-exception-caught + print(f"Error getting {vehicle_type} tags: {e}") + return [] + +def generate_vehicle_versions(): + """ + Generates arrays for each vehicle type based on the tags fetched from the ArduPilot repository. + """ + vehicle_versions = {} + + for vehicle_type in VEHICLE_TYPES: + tags = get_vehicle_tags(vehicle_type) + if tags: + vehicle_versions[vehicle_type] = [tag.split('-')[1] for tag in tags] + + return vehicle_versions + +def create_one_pdef_xml_file(vehicle_type: str, dst_dir: str, git_tag: str): + os.chdir('../ardupilot') + subprocess.run(['git', 'checkout', git_tag], check=True) + # subprocess.run(['git', 'pull'], check=True) + subprocess.run(['Tools/autotest/param_metadata/param_parse.py', '--vehicle', vehicle_type, '--format', 'xml'], check=True) + # Return to the old working directory + os.chdir(old_cwd) + + if not os.path.exists(dst_dir): + os.makedirs(dst_dir) + + # Insert an XML comment on line 3 in the ../ardupilot/apm.pdef.xml file to indicate + # the tag used to generate the file and the current date + with open('../ardupilot/apm.pdef.xml', 'r', encoding='utf-8') as f: + lines = f.readlines() + lines.insert(2, f'\n') + with open('../ardupilot/apm.pdef.xml', 'w', encoding='utf-8') as f: + f.writelines(lines) + shutil.copy('../ardupilot/apm.pdef.xml', f'{dst_dir}/apm.pdef.xml') + +# Function to sync files using rsync +def sync_to_remote(vehicle_dir: str) -> None: + src_dir = f'{vehicle_dir}/' + dst_user = RSYNC_USERNAME + dst_host = 'firmware.ardupilot.org' + dst_path = f'param_versioned/{vehicle_dir}/' + + # Construct the rsync command + rsync_cmd = [ + 'rsync', + '-avz', + '--progress', + '--password-file=.rsync_pass', + src_dir, + f'{dst_user}@{dst_host}::{dst_path}' + ] + + print(f'Synchronizing {src_dir} to {dst_path}...') + print(rsync_cmd) + subprocess.run(rsync_cmd, check=True) + + +def main(): + vehicle_versions = generate_vehicle_versions() + + # Iterate over the vehicle_versions list + for vehicle_type, versions in vehicle_versions.items(): + + vehicle_dir = vehicle_type + if vehicle_type == 'ArduSub': + vehicle_dir = 'Sub' + + for version in versions: + if version[0] == '3' and vehicle_type != 'AP_Periph': + continue # Skip ArduPilot 3.x versions, as param_parse.py does not support them out of the box + if version[0] == '4' and version[2] == '0' and vehicle_type != 'ArduSub': + continue # Skip ArduPilot 4.0.x versions, as param_parse.py does not support them out of the box + create_one_pdef_xml_file(vehicle_type, f'{vehicle_dir}/stable-{version}', f'{vehicle_type}-{version}') + + sync_to_remote(vehicle_dir) + + +if __name__ == '__main__': + main() diff --git a/Tools/scripts/powr_change.py b/Tools/scripts/powr_change.py index 332f9814dcd9ea..d7c295a08c757f 100755 --- a/Tools/scripts/powr_change.py +++ b/Tools/scripts/powr_change.py @@ -70,8 +70,6 @@ def run(self): if new_acc_bit_set and not old_acc_bit_set: line += " ACCFLAGS+%s" % self.bit_description(bit) - elif not new_bit_set and old_bit_set: - line += " ACCFLAGS-%s" % self.bit_description(bit) if len(line) == 0: continue diff --git a/Tools/scripts/run_astyle.py b/Tools/scripts/run_astyle.py index 4e495994735b58..23ebee79ac16f0 100755 --- a/Tools/scripts/run_astyle.py +++ b/Tools/scripts/run_astyle.py @@ -23,11 +23,16 @@ def __init__(self, *, dry_run=DRY_RUN_DEFAULT): self.directories_to_check = [ 'libraries/AP_DDS', 'libraries/AP_ExternalControl', + 'libraries/AP_GSOF', ] self.files_to_check = [ pathlib.Path(s) for s in [ + 'ArduCopter/AP_ExternalControl_Copter.cpp', + 'ArduCopter/AP_ExternalControl_Copter.h', 'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp', 'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h', + 'Rover/AP_ExternalControl_Rover.cpp', + 'Rover/AP_ExternalControl_Rover.h', ] ] self.dry_run = dry_run @@ -55,7 +60,7 @@ def check(self): self.progress("astyle check failed: (%s)" % (ret.stdout)) self.retcode = 1 if "Formatted" in ret.stdout: - self.progress("Files needing formatting found") + self.progress("Files needing formatting found.") print(ret.stdout) self.retcode = 1 diff --git a/Tools/scripts/run_lua_language_check.py b/Tools/scripts/run_lua_language_check.py new file mode 100755 index 00000000000000..7353f016374ee1 --- /dev/null +++ b/Tools/scripts/run_lua_language_check.py @@ -0,0 +1,181 @@ +#!/usr/bin/env python3 + +''' +Reads lua-language-sever check + +It generates a json report that this then parses to make it look nicer + +AP_FLAKE8_CLEAN +''' + +import optparse +import sys +import os +import pathlib +import json +import shutil +import platform +from urllib.parse import unquote +import subprocess +import re + + +def print_failures(file_name, fails, original_name): + file_name = unquote(file_name) + file_path = pathlib.Path(file_name[5:]) + + if (original_name is not None) and (original_name.name == file_path.name): + file_path = original_name + + for fail in fails: + start = fail['range']['start'] + + # These seem to be off by one, not sure why + line = start['line'] + 1 + character = start['character'] + 1 + + print("%s:%i:%i" % (file_path, line, character)) + + print("\tCode: %s" % fail['code']) + message = fail['message'].split("\n") + for line in message: + print("\t%s" % line) + + print() + return len(fails) + + +if __name__ == '__main__': + + parser = optparse.OptionParser(__file__) + + opts, args = parser.parse_args() + + if len(args) > 1: + print('Usage: %s "check path"' % parser.usage) + sys.exit(0) + + check_path = "./" + if len(args) > 0: + check_path = args[0] + check_path = pathlib.Path(check_path) + + if not os.path.exists(check_path): + raise Exception("Path invalid: %s" % check_path) + + # Work out full path to config file + ap_root = (pathlib.Path(__file__) / "../../../").resolve() + setup = (ap_root / "libraries/AP_Scripting/tests/check.json").resolve() + logs = (ap_root / "lualogs").resolve() + docs = (ap_root / "libraries/AP_Scripting/docs/docs.lua").resolve() + + # Make sure the log directory is empty + if os.path.exists(logs) and len(os.listdir(logs)) != 0: + raise Exception("lualogs not empty") + + install_path = (ap_root / "lua-language-server").resolve() + + # See if there is a new version (only try on Linux) + if platform.system() == "Linux": + try: + from github_release_downloader import check_and_download_updates, GitHubRepo + except ImportError: + print("Import github-release-downloader failed") + print("Install with: python3 -m pip install github-release-downloader") + sys.exit(0) + + asset_re = re.compile(r".*linux-x64\.tar\.gz") + check_and_download_updates( + GitHubRepo("LuaLS", "lua-language-server"), + assets_mask=asset_re, + downloads_dir=ap_root, + ) + for filename in os.listdir(ap_root): + if asset_re.match(filename): + pack_path = (ap_root / filename).resolve() + shutil.unpack_archive(pack_path, install_path) + os.remove(pack_path) + + run_path = (install_path / "bin/lua-language-server") + if not os.path.isfile(run_path): + # Try and use version from path + run_path = "lua-language-server" + + # If the target is a single script copy it to a new directory + tmp_check_dir = None + original_name = None + if os.path.isfile(check_path): + tmp_check_dir = (check_path / "../tmp_llc").resolve() + os.mkdir(tmp_check_dir) + shutil.copyfile(check_path, (tmp_check_dir / check_path.name).resolve()) + original_name = check_path + check_path = tmp_check_dir + + # Can't get the lua-language-server to find docs outside of workspace, so just copy in and then delete + docs_check_path = (pathlib.Path(os.getcwd()) / check_path).resolve() + if os.path.isfile(docs_check_path): + docs_check_path = (docs_check_path / "../").resolve() + + docs_copy = None + if not docs.is_relative_to(docs_check_path): + docs_copy = (docs_check_path / "docs.lua").resolve() + + if docs_copy is not None: + # make copy of docs + shutil.copyfile(docs, docs_copy) + + # Run check, print output in real time for user and capture so we can confirm it has found at least one file + command = "%s --configpath %s --logpath %s --check %s" % (run_path, setup, logs, check_path) + p = subprocess.Popen(command, shell=True, text=True, stdout=subprocess.PIPE) + result = [] + while p.poll() is None: + line = p.stdout.readline() + result.append(line) + print(line, end="") + + # Make sure we checked at least one file + file_count_re = re.compile(r"^>*=* \d+/(\d+)") + checked_files = None + for line in result: + match = file_count_re.search(line) + if match is not None: + count = int(match.group(1)) + if checked_files is None: + checked_files = count + elif checked_files != count: + raise Exception("Checked files error expected: %i got: %i" % (checked_files, count)) + + if tmp_check_dir is not None: + # Remove test directory + shutil.rmtree(tmp_check_dir) + + elif docs_copy is not None: + # remove copy of docs + os.remove(docs_copy) + + # Read output + errors = 0 + result = (logs / "check.json").resolve() + if os.path.exists(result): + # File only created if there are errors + f = open((logs / "check.json").resolve()) + data = json.load(f) + f.close() + + if len(data) > 0: + # Print output if there are any errors + for key, value in data.items(): + errors += print_failures(key, value, original_name) + + # Remove output + shutil.rmtree(logs) + + # Rase error if detected + if errors != 0: + raise Exception("Detected %i errors" % errors) + + # Warn if no files were checked + if (checked_files is None) or (checked_files < 1): + raise Exception("No lua files found in: %s" % check_path) + + print("%i Files checked" % checked_files) diff --git a/Tools/scripts/serial_playback.py b/Tools/scripts/serial_playback.py new file mode 100755 index 00000000000000..b7d05b8f25a56a --- /dev/null +++ b/Tools/scripts/serial_playback.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python3 +''' +playback a capture from ardupilot with timing +the file format is a sequence of: + + HEADER + DATA + +HEADER is: + uint32_t magic == 0x7fe53b04 + uint32_t time_ms + uint32_t length +''' + +import socket +import time +import struct +from argparse import ArgumentParser + +parser = ArgumentParser(description="playback a capture file with ArduPilot timing headers") + +parser.add_argument("infile", default=None, help="input file") +parser.add_argument("dest", default=None, help="TCP destination in ip:port format") +parser.add_argument("--loop", action='store_true', help="loop to start of file at EOF") +args = parser.parse_args() + +def open_socket(dest): + a = dest.split(':') + ip = a[0] + port = int(a[1]) + tcp = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + tcp.connect((ip, port)) + return tcp + +f = open(args.infile,'rb') +tcpsock = open_socket(args.dest) + +last_ms = None + +while True: + hdr_raw = f.read(12) + if len(hdr_raw) != 12: + if args.loop: + f.seek(0) + continue + print("EOF") + break + magic, t_ms, n = struct.unpack(" 0: + time.sleep(dt*0.001) + last_ms = t_ms + data = f.read(n) + if len(data) != n: + if args.loop: + f.seek(0) + continue + print("short data, EOF") + break + tcpsock.send(data) + print("Wrote %u bytes t=%.3f" % (len(data), t_ms*0.001)) diff --git a/Tools/scripts/signing/README.md b/Tools/scripts/signing/README.md index dc4032c00987f3..06fe1d6527b29c 100644 --- a/Tools/scripts/signing/README.md +++ b/Tools/scripts/signing/README.md @@ -12,7 +12,7 @@ firmware doesn't match any of the public keys in the bootloader. To generate a public/private key pair, run the following command: ``` - python3 -m pip install pymonocypher + python3 -m pip install pymonocypher==3.1.3.2 Tools/scripts/signing/generate_keys.py NAME ``` @@ -131,7 +131,13 @@ This opens a secure command session using your private_key.dat file to allow the securecommand getpublickeys will return the number of public keys...you will need this next securecommand removepublickeys 0 X where X is the number of public keys...this removes them ``` -Re-run the 'getpublickeys' command again to verify that all keys have been removed. + +For example, if you have a standard firmware with the 3 ArduPilot +public keys and one of your own public keys then X will be 4 in the +above command. + +Re-run the 'getpublickeys' command again to verify that all keys have +been removed. Now exit MAVProxy and build a firmware using the normal bootloader but still using the --signed-fw option: diff --git a/Tools/scripts/signing/generate_keys.py b/Tools/scripts/signing/generate_keys.py index 5da4388c308f91..38b7d38650452f 100755 --- a/Tools/scripts/signing/generate_keys.py +++ b/Tools/scripts/signing/generate_keys.py @@ -9,9 +9,12 @@ try: import monocypher except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") sys.exit(1) +if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") + sys.exit(1) if len(sys.argv) != 2: print("Usage: generate_keys.py BASENAME") diff --git a/Tools/scripts/signing/make_secure_bl.py b/Tools/scripts/signing/make_secure_bl.py index bd60bee3c7af06..5187b0f15d3b16 100755 --- a/Tools/scripts/signing/make_secure_bl.py +++ b/Tools/scripts/signing/make_secure_bl.py @@ -7,12 +7,6 @@ import os import base64 -try: - import monocypher -except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") - sys.exit(1) - # get command line arguments from argparse import ArgumentParser parser = ArgumentParser(description='make_secure_bl') diff --git a/Tools/scripts/signing/make_secure_fw.py b/Tools/scripts/signing/make_secure_fw.py index 4e916090fc2276..8c8862cb62f8cb 100755 --- a/Tools/scripts/signing/make_secure_fw.py +++ b/Tools/scripts/signing/make_secure_fw.py @@ -10,9 +10,13 @@ try: import monocypher except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") sys.exit(1) +if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") + return None + key_len = 32 sig_len = 64 sig_version = 30437 diff --git a/Tools/scripts/sitl-on-hardware/README.md b/Tools/scripts/sitl-on-hardware/README.md index 26135aac74d1c2..af643a9db308c1 100644 --- a/Tools/scripts/sitl-on-hardware/README.md +++ b/Tools/scripts/sitl-on-hardware/README.md @@ -23,6 +23,13 @@ and quadplane: cd $HOME/ardupilot ./Tools/scripts/sitl-on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane --simclass QuadPlane +### Copter : + +Only the default quad frame is enable by default, to enable another frame type, you need to enable the right compile flag : +e.g. for octa-quad frame, AP_MOTORS_FRAME_OCTAQUAD_ENABLED 1 in the hwdef file. Compile flags list is in AP_Motors_class.h +Passing --frame parameter will enable the right compile flag for you. + + ## Configuring Wipe the parameters on the board; this can be done with a mavlink command, or by setting the FORMAT_VERSION parameter to 0. diff --git a/Tools/scripts/sitl-on-hardware/extra-hwdef-sitl-on-hw.dat b/Tools/scripts/sitl-on-hardware/extra-hwdef-sitl-on-hw.dat index fd766ad7dd2dd2..0b81cc3e778976 100644 --- a/Tools/scripts/sitl-on-hardware/extra-hwdef-sitl-on-hw.dat +++ b/Tools/scripts/sitl-on-hardware/extra-hwdef-sitl-on-hw.dat @@ -1,8 +1,5 @@ env SIM_ENABLED 1 -define INS_MAX_INSTANCES 2 -define HAL_COMPASS_MAX_SENSORS 2 - define AP_GPS_BACKEND_DEFAULT_ENABLED 0 define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0 diff --git a/Tools/scripts/sitl-on-hardware/plane-extra-hwdef-sitl-on-hw.dat b/Tools/scripts/sitl-on-hardware/plane-extra-hwdef-sitl-on-hw.dat index 27868fd515b3d7..145ffbcf8b47d7 100644 --- a/Tools/scripts/sitl-on-hardware/plane-extra-hwdef-sitl-on-hw.dat +++ b/Tools/scripts/sitl-on-hardware/plane-extra-hwdef-sitl-on-hw.dat @@ -1,8 +1,5 @@ env SIM_ENABLED 1 -define INS_MAX_INSTANCES 2 -define HAL_COMPASS_MAX_SENSORS 2 - define AP_GPS_BACKEND_DEFAULT_ENABLED 0 define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0 diff --git a/Tools/scripts/sitl-on-hardware/sitl-on-hw.py b/Tools/scripts/sitl-on-hardware/sitl-on-hw.py index 291005a7a73739..ffa4947fae0610 100755 --- a/Tools/scripts/sitl-on-hardware/sitl-on-hw.py +++ b/Tools/scripts/sitl-on-hardware/sitl-on-hw.py @@ -2,18 +2,44 @@ ''' script to build a firmware for SITL-on-hardware see https://ardupilot.org/dev/docs/sim-on-hardware.html + +AP_FLAKE8_CLEAN ''' import subprocess import sys import os import tempfile - from argparse import ArgumentParser + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../Tools', 'autotest')) +from pysim import vehicleinfo # noqa: E402 + +vinfo = vehicleinfo.VehicleInfo() + +vehicle_map = { + "APMrover2": "Rover", + "Copter": "ArduCopter", + "Heli": "Helicopter", + "Plane": "ArduPlane", + "Sub": "ArduSub", + "Blimp": "Blimp", + "Rover": "Rover", + "AntennaTracker": "AntennaTracker", +} +# add lower-case equivalents too +for k in list(vehicle_map.keys()): + vehicle_map[k.lower()] = vehicle_map[k] + +vehicle_choices = list(vinfo.options.keys()) +# add vehicle aliases to argument parser options: +for c in vehicle_map.keys(): + vehicle_choices.append(c) + parser = ArgumentParser("SITL on hardware builder") parser.add_argument("--board", default=None, help="board type") -parser.add_argument("--vehicle", default=None, help="vehicle type") -parser.add_argument("--frame", default=None, help="frame type") +parser.add_argument("-v", "--vehicle", choices=vehicle_choices, required=True, help="vehicle type") +parser.add_argument("-f", "--frame", default=None, help="frame type") parser.add_argument("--simclass", default=None, help="simulation class") parser.add_argument("--defaults", default=None, help="extra defaults file") parser.add_argument("--upload", action='store_true', default=False, help="upload firmware") @@ -22,33 +48,46 @@ extra_hwdef = None + def run_program(cmd_list): '''run a program from a command list''' print("Running (%s)" % " ".join(cmd_list)) retcode = subprocess.call(cmd_list) if retcode != 0: - print("FAILED: %s" % (' '.join(cmd_list))) - global extra_hwdef - if extra_hwdef is not None: - extra_hwdef.close() - os.unlink(extra_hwdef.name) - sys.exit(1) + print("FAILED: %s" % (' '.join(cmd_list))) + global extra_hwdef + if extra_hwdef is not None: + extra_hwdef.close() + os.unlink(extra_hwdef.name) + sys.exit(1) + + +frame_options = sorted(vinfo.options[vehicle_map[args.vehicle]]["frames"].keys()) +frame_options_string = ' '.join(frame_options) +if args.frame and args.frame not in frame_options: + print(f"ERROR: frame must be one of {frame_options_string}") + sys.exit(1) + extra_hwdef = tempfile.NamedTemporaryFile(mode='w') extra_defaults = tempfile.NamedTemporaryFile(mode='w') + def hwdef_write(s): '''write to the hwdef temp file''' extra_hwdef.write(s) + def defaults_write(s): '''write to the hwdef temp file''' extra_defaults.write(s) + def sohw_path(fname): '''get path to a file in on-hardware directory''' return os.path.join(os.path.dirname(os.path.realpath(__file__)), fname) + if args.vehicle == "plane": extra_hwdef_base = "plane-extra-hwdef-sitl-on-hw.dat" defaults_base = "plane-default.param" @@ -63,12 +102,47 @@ def sohw_path(fname): defaults_write(open(sohw_path(defaults_base), "r").read() + "\n") if args.defaults: - defaults_write(open(args.defaults,"r").read() + "\n") + defaults_write(open(args.defaults, "r").read() + "\n") if args.simclass: + if args.simclass == 'Glider': + hwdef_write("define AP_SIM_GLIDER_ENABLED 1\n") hwdef_write("define AP_SIM_FRAME_CLASS %s\n" % args.simclass) if args.frame: hwdef_write('define AP_SIM_FRAME_STRING "%s"\n' % args.frame) + if vehicle_map[args.vehicle] == "ArduCopter" or args.simclass == "MultiCopter": + frame_found = False + frame_defines = { + "quad": "AP_MOTORS_FRAME_QUAD_ENABLED", + "+": "AP_MOTORS_FRAME_QUAD_ENABLED", + "X": "AP_MOTORS_FRAME_QUAD_ENABLED", + "cwx": "AP_MOTORS_FRAME_QUAD_ENABLED", + "djix": "AP_MOTORS_FRAME_QUAD_ENABLED", + "quad-can": "AP_MOTORS_FRAME_QUAD_ENABLED", + "hexa": "AP_MOTORS_FRAME_HEXA_ENABLED", + "hexa-cwx": "AP_MOTORS_FRAME_HEXA_ENABLED", + "hexa-dji": "AP_MOTORS_FRAME_HEXA_ENABLED", + "hexax": "AP_MOTORS_FRAME_HEXA_ENABLED", + "deca": "AP_MOTORS_FRAME_DECA_ENABLED", + "deca-cwx": "AP_MOTORS_FRAME_DECA_ENABLED", + "dodeca-hexa": "AP_MOTORS_FRAME_DODECAHEXA_ENABLED", + "octa": "AP_MOTORS_FRAME_OCTA_ENABLED", + "octa-dji": "AP_MOTORS_FRAME_OCTA_ENABLED", + "octa-cwx": "AP_MOTORS_FRAME_OCTA_ENABLED", + "octa-quad": "AP_MOTORS_FRAME_OCTAQUAD_ENABLED", + "octa-quad-cwx": "AP_MOTORS_FRAME_OCTAQUAD_ENABLED", + "y6": "AP_MOTORS_FRAME_Y6_ENABLED" + } + for frame, define in frame_defines.items(): + if args.frame == frame: + print(f"Auto enabling {define} for frame {args.frame}") + hwdef_write(f'define {define} 1') + frame_found = True + break + if not frame_found: + print(f"Error: frame {args.frame} not found in frame_defines") + sys.exit(1) + extra_hwdef.flush() extra_defaults.flush() @@ -80,12 +154,22 @@ def sohw_path(fname): configure_args.extend(unknown_args) run_program(configure_args) -build_cmd = ["./waf", args.vehicle] + +def get_key_from_value(d, target_value): + for key, value in d.items(): + if value == target_value: + return key + return None + + +if args.vehicle in ["APMrover2", "apmrover2"]: # Double map, but waf only accepts rover. + args.vehicle = "Rover" +waf_vehicle = args.vehicle if args.vehicle in vehicle_map.keys() else get_key_from_value(vehicle_map, args.vehicle) +build_cmd = ["./waf", waf_vehicle.lower()] if args.upload: - build_cmd.append("--upload") + build_cmd.append("--upload") run_program(build_cmd) # cleanup extra_hwdef.close() - diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 5e6e29084f18d2..b57333a8ff622a 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -21,25 +21,15 @@ import optparse import os import pathlib +import queue import shutil import string import subprocess -import sys import tempfile import threading import time import board_list -try: - import queue as Queue -except ImportError: - import Queue - -if sys.version_info[0] < 3: - running_python3 = False -else: - running_python3 = True - class SizeCompareBranchesResult(object): '''object to return results from a comparison''' @@ -155,6 +145,7 @@ def __init__(self, 'iomcu-dshot', 'iomcu-f103', 'iomcu-f103-dshot', + 'iomcu-f103-8MHz-dshot', 'iomcu_f103_8MHz', 'luminousbee4', 'skyviper-v2450', @@ -165,6 +156,7 @@ def __init__(self, 'SITL_arm_linux_gnueabihf', 'RADIX2HD', 'canzero', + 'CUAV-Pixhack-v3', # uses USE_BOOTLOADER_FROM_BOARD ]) # blacklist all linux boards for bootloader build: @@ -248,10 +240,9 @@ def run_program(self, prefix, cmd_list, show_output=True, env=None, show_output_ # 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]) + 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() some_output = "%s: %s" % (prefix, x) @@ -435,7 +426,7 @@ def check_result_queue(self): while True: try: result = self.thread_exit_result_queue.get_nowait() - except Queue.Empty: + except queue.Empty: break if result is None: continue @@ -447,7 +438,7 @@ def run_build_tasks_in_parallel(self, tasks): # shared list for the threads: self.parallel_tasks = copy.copy(tasks) # make this an argument instead?! threads = [] - self.thread_exit_result_queue = Queue.Queue() + self.thread_exit_result_queue = queue.Queue() tstart = time.time() self.failure_exceptions = [] diff --git a/Tools/scripts/solution_status_change.py b/Tools/scripts/solution_status_change.py index 4a052aa0e4d4a1..4431b576eb8bc4 100755 --- a/Tools/scripts/solution_status_change.py +++ b/Tools/scripts/solution_status_change.py @@ -17,8 +17,11 @@ class SolutionStatusChange(object): - def __init__(self, master): + def __init__(self, master, core=None): self.master = master + self.core = core + if self.core is not None: + self.core = set(self.core) def progress(self, text): '''emit text with possible timestamps etc''' @@ -53,13 +56,13 @@ def run(self): old_message_per_core = {} while True: m = self.conn.recv_match(type=desired_type) - if m.C != 0: - continue if m is None: break if m.C not in old_message_per_core: old_message_per_core[m.C] = m continue + if self.core is not None and m.C not in self.core: + continue current = old_message_per_core[m.C] if m.SS == current.SS: continue @@ -86,6 +89,9 @@ def run(self): if __name__ == '__main__': parser = optparse.OptionParser("solution-status-change.py [options]") + parser.add_option("", "--core", action="append", type="int", + default=[], help="core to show (default is all)") + (opts, args) = parser.parse_args() if len(args) < 1: @@ -94,5 +100,8 @@ def run(self): master = args[0] - tester = SolutionStatusChange(master) + if len(opts.core) == 0: + opts.core = None + + tester = SolutionStatusChange(master, core=opts.core) tester.run() diff --git a/Tools/vagrant/initvagrant.sh b/Tools/vagrant/initvagrant.sh index acb0f482819d96..3da7d92442a174 100755 --- a/Tools/vagrant/initvagrant.sh +++ b/Tools/vagrant/initvagrant.sh @@ -22,9 +22,15 @@ echo USING VAGRANT_USER:$VAGRANT_USER cd /home/$VAGRANT_USER +IS_BENTO=0 +if [ -e /etc/update-motd.d/99-bento ]; then + IS_BENTO=1 +fi -# artful rootfs is 2GB without resize: -sudo resize2fs /dev/sda1 +# artful rootfs is 2GB without resize. Do not resize if using Bento: +if [ ! $IS_BENTO ]; then + sudo resize2fs /dev/sda1 +fi echo "calling pre-reqs script..." sudo -H -u $VAGRANT_USER /vagrant/Tools/environment_install/install-prereqs-ubuntu.sh -y diff --git a/Tools/vagrant/mavinit.scr b/Tools/vagrant/mavinit.scr index 4b56c421c538ba..fe7027ba0def73 100644 --- a/Tools/vagrant/mavinit.scr +++ b/Tools/vagrant/mavinit.scr @@ -17,7 +17,6 @@ module load graph @alias add odroidpower relay set 0 @alias add neutral2 servo set 12 1500 @alias add ekf param set AHRS_EKF_USE -@alias add gpsdisable param set SIM_GPS_DISABLE @alias add bb status gps* scaled* raw* @alias add g graph @alias add grc3 g RC_CHANNELS.chan3_raw SERVO_OUTPUT_RAW.servo3_raw diff --git a/Vagrantfile b/Vagrantfile index 9ab2a986a5a9af..e3344a75a4c9af 100644 --- a/Vagrantfile +++ b/Vagrantfile @@ -282,4 +282,25 @@ Vagrant.configure(VAGRANTFILE_API_VERSION) do |config| end mantic.vm.boot_timeout = 1200 end + + # 24.04 end of standard support Jun 2029 + # note the use of "bento" here; Ubuntu stopped providing Vagrant + # images due to Hashicorp adopting the "Business Source License". + config.vm.define "noble", autostart: false do |noble| + noble.vm.box = "bento/ubuntu-24.04" + noble.vm.provision :shell, path: "Tools/vagrant/initvagrant.sh" + noble.vm.provider "virtualbox" do |vb| + vb.name = "ArduPilot (noble)" + end + noble.vm.boot_timeout = 1200 + end + config.vm.define "noble-desktop", autostart: false do |noble| + noble.vm.box = "bento/ubuntu-24.04" + noble.vm.provision :shell, path: "Tools/vagrant/initvagrant-desktop.sh" + noble.vm.provider "virtualbox" do |vb| + vb.name = "ArduPilot (noble-desktop)" + vb.gui = true + end + noble.vm.boot_timeout = 1200 + end end diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index c68e143a112fb1..fbfa3305be080b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -9,10 +9,12 @@ extern const AP_HAL::HAL& hal; // 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 + #define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 0 #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 + #define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 1 #endif AC_AttitudeControl *AC_AttitudeControl::_singleton; @@ -24,7 +26,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Param: SLEW_YAW // @DisplayName: Yaw target slew rate - // @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes + // @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes // @Units: cdeg/s // @Range: 500 18000 // @Increment: 100 @@ -150,6 +152,27 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @User: Standard AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT), + // @Param: LAND_R_MULT + // @DisplayName: Landed roll gain multiplier + // @Description: Roll gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the roll axis. + // @Range: 0.25 1.0 + // @User: Advanced + AP_GROUPINFO("LAND_R_MULT", 21, AC_AttitudeControl, _land_roll_mult, 1.0), + + // @Param: LAND_P_MULT + // @DisplayName: Landed pitch gain multiplier + // @Description: Pitch gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the pitch axis. + // @Range: 0.25 1.0 + // @User: Advanced + AP_GROUPINFO("LAND_P_MULT", 22, AC_AttitudeControl, _land_pitch_mult, 1.0), + + // @Param: LAND_Y_MULT + // @DisplayName: Landed yaw gain multiplier + // @Description: Yaw gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the yaw axis. + // @Range: 0.25 1.0 + // @User: Advanced + AP_GROUPINFO("LAND_Y_MULT", 23, AC_AttitudeControl, _land_yaw_mult, 1.0), + AP_GROUPEND }; @@ -164,18 +187,45 @@ float AC_AttitudeControl::get_slew_yaw_max_degs() const return MIN(_ang_vel_yaw_max, _slew_yaw * 0.01); } +// get the latest gyro for the purposes of attitude control +// Counter-inuitively the lowest latency for rate control is achieved by running rate control +// *before* attitude control. This is because you want rate control to run as close as possible +// to the time that a gyro sample was read to minimise jitter and control errors. Running rate +// control after attitude control might makes sense logically, but the overhead of attitude +// control calculations (and other updates) compromises the actual rate control. +// +// In the case of running rate control in a separate thread, the ordering between rate and attitude +// updates is less important, except that gyro sample used should be the latest +// +// Currently quadplane runs rate control after attitude control, necessitating the following code +// to minimise latency. +// However this code can be removed once quadplane updates it's structure to run the rate loops before +// the Attitude controller. +const Vector3f AC_AttitudeControl::get_latest_gyro() const +{ +#if AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL + // rate updates happen before attitude updates so the last gyro value is the last rate gyro value + // this also allows a separate rate thread to be the source of gyro data + return _rate_gyro; +#else + // rate updates happen after attitude updates so the AHRS must be consulted for the last gyro value + return _ahrs.get_gyro_latest(); +#endif +} + // Ensure attitude controller have zero errors to relax rate controller output void AC_AttitudeControl::relax_attitude_controllers() { + // take a copy of the last gyro used by the rate controller before using it + Vector3f gyro = get_latest_gyro(); // Initialize the attitude variables to the current attitude _ahrs.get_quat_body_to_ned(_attitude_target); _attitude_target.to_euler(_euler_angle_target); _attitude_ang_error.initialise(); // Initialize the angular rate variables to the current rate - _ang_vel_target = _ahrs.get_gyro(); - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); - _ang_vel_body = _ahrs.get_gyro(); + _ang_vel_target = gyro; + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Initialize remaining variables _thrust_error_angle = 0.0f; @@ -187,6 +237,8 @@ void AC_AttitudeControl::relax_attitude_controllers() // Reset the I terms reset_rate_controller_I_terms(); + // finally update the attitude target + _ang_vel_body = gyro; } void AC_AttitudeControl::reset_rate_controller_I_terms() @@ -204,6 +256,25 @@ void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly() get_rate_yaw_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC); } +// Reduce attitude control gains while landed to stop ground resonance +void AC_AttitudeControl::landed_gain_reduction(bool landed) +{ + if (is_positive(_input_tc)) { + // use 2.0 x tc to match the response time to 86% commanded + const float spool_step = _dt / (2.0 * _input_tc); + if (landed) { + _landed_gain_ratio = MIN(1.0, _landed_gain_ratio + spool_step); + } else { + _landed_gain_ratio = MAX(0.0, _landed_gain_ratio - spool_step); + } + } else { + _landed_gain_ratio = landed ? 1.0 : 0.0; + } + Vector3f scale_mult = VECTORF_111 * (1.0 - _landed_gain_ratio) + Vector3f(_land_roll_mult, _land_pitch_mult, _land_yaw_mult) * _landed_gain_ratio; + set_PD_scale_mult(scale_mult); + set_angle_P_scale_mult(scale_mult); +} + // The attitude controller works around the concept of the desired attitude, target attitude // and measured attitude. The desired attitude is the attitude input into the attitude controller // that expresses where the higher level code would like the aircraft to move to. The target attitude is moved @@ -214,30 +285,35 @@ void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly() // remain very close together. // // All input functions below follow the same procedure -// 1. define the desired attitude the aircraft should attempt to achieve using the input variables -// 2. using the desired attitude and input variables, define the target angular velocity so that it should +// 1. define the desired attitude or attitude change based on the input variables +// 2. update the target attitude based on the angular velocity target and the time since the last loop +// 3. using the desired attitude and input variables, define the target angular velocity so that it should // move the target attitude towards the desired attitude -// 3. if _rate_bf_ff_enabled is not being used then make the target attitude +// 4. if _rate_bf_ff_enabled is not being used then make the target attitude // and target angular velocities equal to the desired attitude and desired angular velocities. -// 4. ensure _attitude_target, _euler_angle_target, _euler_rate_target and +// 5. ensure _attitude_target, _euler_angle_target, _euler_rate_target and // _ang_vel_target have been defined. This ensures input modes can be changed without discontinuity. -// 5. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and +// 6. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and // integrate them into the target attitude. Any errors between the target attitude and the measured attitude are // corrected by first correcting the thrust vector until the angle between the target thrust vector measured // 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 by the integral of the angular velocity -void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target) +// attitude_desired_quat: is updated on each time_step by the integral of the body frame angular velocity +void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body) { - Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat; - Vector3f attitude_error_angle; - attitude_error_quat.to_axis_angle(attitude_error_angle); + // update attitude target + update_attitude_target(); // Limit the angular velocity - ang_vel_limit(ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); + ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); + Vector3f ang_vel_target = attitude_desired_quat * ang_vel_body; if (_rate_bf_ff_enabled) { + Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat; + Vector3f attitude_error_angle; + attitude_error_quat.to_axis_angle(attitude_error_angle); + // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration // and an exponential decay specified by _input_tc at the end. @@ -253,7 +329,7 @@ void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vec _attitude_target.to_euler(_euler_angle_target); // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // rotate target and normalize Quaternion attitude_desired_update; @@ -273,6 +349,9 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f); float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f); + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); @@ -281,7 +360,7 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration @@ -294,11 +373,11 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler _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); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); // Limit the angular velocity ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. _euler_angle_target.x = euler_roll_angle; @@ -324,6 +403,9 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f); float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f); + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); @@ -333,7 +415,7 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle const float slew_yaw_max_rads = get_slew_yaw_max_rads(); if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration @@ -346,11 +428,11 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle } // 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); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); // Limit the angular velocity ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. _euler_angle_target.x = euler_roll_angle; @@ -383,12 +465,15 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c float euler_pitch_rate = radians(euler_pitch_rate_cds * 0.01f); float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f); + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing // the output rate towards the input rate. @@ -397,7 +482,7 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c _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); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. // Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities. @@ -417,6 +502,7 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c attitude_controller_run_quat(); } +// Fully stabilized acro // Command an angular velocity with angular velocity feedforward and smoothing void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) { @@ -425,6 +511,9 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f); float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f); + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); @@ -437,11 +526,11 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl _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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed. Quaternion attitude_target_update; - attitude_target_update.from_axis_angle(Vector3f{roll_rate_rads * _dt, pitch_rate_rads * _dt, yaw_rate_rads * _dt}); + attitude_target_update.from_axis_angle(Vector3f{roll_rate_rads, pitch_rate_rads, yaw_rate_rads} * _dt); _attitude_target = _attitude_target * attitude_target_update; _attitude_target.normalize(); @@ -454,6 +543,7 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl attitude_controller_run_quat(); } +// Rate-only acro with no attitude feedback - used only by Copter rate-only acro // Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) { @@ -473,10 +563,13 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, _ahrs.get_quat_body_to_ned(_attitude_target); _attitude_target.to_euler(_euler_angle_target); // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); + + // finally update the attitude target _ang_vel_body = _ang_vel_target; } +// Acro with attitude feedback that does not rely on attitude - used only by Plane acro // Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) { @@ -497,9 +590,10 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, _attitude_ang_error.from_axis_angle(attitude_error); } - Vector3f gyro_latest = _ahrs.get_gyro_latest(); - attitude_ang_error_update_quat.from_axis_angle(Vector3f{(_ang_vel_target.x-gyro_latest.x) * _dt, (_ang_vel_target.y-gyro_latest.y) * _dt, (_ang_vel_target.z-gyro_latest.z) * _dt}); + Vector3f gyro_latest = get_latest_gyro(); + attitude_ang_error_update_quat.from_axis_angle((_ang_vel_target - gyro_latest) * _dt); _attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error; + _attitude_ang_error.normalize(); // Compute acceleration-limited body frame rates // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing @@ -514,20 +608,21 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, // Update the unused targets attitude based on current attitude to condition mode change _attitude_target = attitude_body * _attitude_ang_error; + _attitude_target.normalize(); // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Compute the angular velocity target from the integrated rate error _attitude_ang_error.to_axis_angle(attitude_error); - _ang_vel_body = update_ang_vel_target_from_att_error(attitude_error); - _ang_vel_body += _ang_vel_target; + Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error); + ang_vel_body += _ang_vel_target; - // ensure Quaternions stay normalized - _attitude_ang_error.normalize(); + // finally update the attitude target + _ang_vel_body = ang_vel_body; } // Command an angular step (i.e change) in body frame angle @@ -556,6 +651,25 @@ void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(float roll_angle_ste attitude_controller_run_quat(); } +// Command an rate step (i.e change) in body frame rate +// Used to command a step in rate without exciting the orthogonal axis during autotune +// Done as a single thread-safe function to avoid intermediate zero values being seen by the attitude controller +void AC_AttitudeControl::input_rate_step_bf_roll_pitch_yaw(float roll_rate_step_bf_cd, float pitch_rate_step_bf_cd, float yaw_rate_step_bf_cd) +{ + // Update the unused targets attitude based on current attitude to condition mode change + _ahrs.get_quat_body_to_ned(_attitude_target); + _attitude_target.to_euler(_euler_angle_target); + // Set the target angular velocity to be zero to minimize target overshoot after the rate step finishes + _ang_vel_target.zero(); + // Convert body-frame angular velocity into euler angle derivative of desired attitude + _euler_rate_target.zero(); + + Vector3f ang_vel_body {roll_rate_step_bf_cd, pitch_rate_step_bf_cd, yaw_rate_step_bf_cd}; + ang_vel_body = ang_vel_body * 0.01f * DEG_TO_RAD; + // finally update the attitude target + _ang_vel_body = ang_vel_body; +} + // Command a thrust vector and heading rate void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw) { @@ -567,6 +681,9 @@ void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust heading_rate = constrain_float(heading_rate, -slew_yaw_max_rads, slew_yaw_max_rads); } + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); @@ -603,7 +720,7 @@ void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust } // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Call quaternion attitude controller attitude_controller_run_quat(); @@ -619,6 +736,9 @@ void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vect float heading_rate = constrain_float(radians(heading_rate_cds * 0.01f), -slew_yaw_max_rads, slew_yaw_max_rads); float heading_angle = radians(heading_angle_cd * 0.01f); + // update attitude target + update_attitude_target(); + // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target); @@ -651,7 +771,7 @@ void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vect } // 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); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Call quaternion attitude controller attitude_controller_run_quat(); @@ -704,6 +824,16 @@ Quaternion AC_AttitudeControl::attitude_from_thrust_vector(Vector3f thrust_vecto return thrust_vec_quat*yaw_quat; } +// Calculates the body frame angular velocities to follow the target attitude +void AC_AttitudeControl::update_attitude_target() +{ + // rotate target and normalize + Quaternion attitude_target_update; + attitude_target_update.from_axis_angle(_ang_vel_target * _dt); + _attitude_target *= attitude_target_update; + _attitude_target.normalize(); +} + // Calculates the body frame angular velocities to follow the target attitude void AC_AttitudeControl::attitude_controller_run_quat() { @@ -716,43 +846,35 @@ void AC_AttitudeControl::attitude_controller_run_quat() thrust_heading_rotation_angles(_attitude_target, attitude_body, attitude_error, _thrust_angle, _thrust_error_angle); // Compute the angular velocity corrections in the body frame from the attitude error - _ang_vel_body = update_ang_vel_target_from_att_error(attitude_error); + Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error); // ensure angular velocity does not go over configured limits - ang_vel_limit(_ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); + ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); // 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 * _ang_vel_target; - + Vector3f gyro = get_latest_gyro(); // Correct the thrust vector and smoothly add feedforward and yaw input _feedforward_scalar = 1.0f; if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) { - _ang_vel_body.z = _ahrs.get_gyro().z; + ang_vel_body.z = gyro.z; } else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) { _feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE); - _ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar; - _ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar; - _ang_vel_body.z += ang_vel_body_feedforward.z; - _ang_vel_body.z = _ahrs.get_gyro().z * (1.0 - _feedforward_scalar) + _ang_vel_body.z * _feedforward_scalar; + ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar; + ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar; + ang_vel_body.z += ang_vel_body_feedforward.z; + ang_vel_body.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body.z * _feedforward_scalar; } else { - _ang_vel_body += ang_vel_body_feedforward; - } - - if (_rate_bf_ff_enabled) { - // rotate target and normalize - Quaternion attitude_target_update; - attitude_target_update.from_axis_angle(Vector3f{_ang_vel_target.x * _dt, _ang_vel_target.y * _dt, _ang_vel_target.z * _dt}); - _attitude_target = _attitude_target * attitude_target_update; + ang_vel_body += ang_vel_body_feedforward; } - // ensure Quaternion stay normalised - _attitude_target.normalize(); - // Record error to handle EKF resets _attitude_ang_error = attitude_body.inverse() * _attitude_target; + // finally update the attitude target + _ang_vel_body = ang_vel_body; } // thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion. @@ -908,24 +1030,25 @@ void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_m } // translates body frame acceleration limits to the euler axis -Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel) +Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel) { - float sin_phi = constrain_float(fabsf(sinf(euler_rad.x)), 0.1f, 1.0f); - float cos_phi = constrain_float(fabsf(cosf(euler_rad.x)), 0.1f, 1.0f); - float sin_theta = constrain_float(fabsf(sinf(euler_rad.y)), 0.1f, 1.0f); - float cos_theta = constrain_float(fabsf(cosf(euler_rad.y)), 0.1f, 1.0f); - - Vector3f rot_accel; - if (is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) { - rot_accel.x = euler_accel.x; - rot_accel.y = euler_accel.y; - rot_accel.z = euler_accel.z; - } else { - rot_accel.x = euler_accel.x; - rot_accel.y = MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi); - rot_accel.z = MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta)); + if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) { + return Vector3f { euler_accel }; } - return rot_accel; + + const float phi = att.get_euler_roll(); + const float theta = att.get_euler_pitch(); + + const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f); + const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f); + const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f); + const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f); + + return Vector3f { + euler_accel.x, + MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi), + MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta)) + }; } // Sets attitude target to vehicle attitude and sets all rates to zero @@ -957,7 +1080,7 @@ void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate) _euler_rate_target.z = 0.0f; // 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); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); } } @@ -976,12 +1099,15 @@ void AC_AttitudeControl::inertial_frame_reset() } // Convert a 321-intrinsic euler angle derivative to an angular velocity vector -void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads) +void AC_AttitudeControl::euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads) { - float sin_theta = sinf(euler_rad.y); - float cos_theta = cosf(euler_rad.y); - float sin_phi = sinf(euler_rad.x); - float cos_phi = cosf(euler_rad.x); + const float theta = att.get_euler_pitch(); + const float phi = att.get_euler_roll(); + + const float sin_theta = sinf(theta); + const float cos_theta = cosf(theta); + const float sin_phi = sinf(phi); + const float cos_phi = cosf(phi); ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z; ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z; @@ -990,12 +1116,15 @@ void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const // Convert an angular velocity vector to a 321-intrinsic euler angle derivative // Returns false if the vehicle is pitched 90 degrees up or down -bool AC_AttitudeControl::ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads) +bool AC_AttitudeControl::ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads) { - float sin_theta = sinf(euler_rad.y); - float cos_theta = cosf(euler_rad.y); - float sin_phi = sinf(euler_rad.x); - float cos_phi = cosf(euler_rad.x); + const float theta = att.get_euler_pitch(); + const float phi = att.get_euler_roll(); + + const float sin_theta = sinf(theta); + const float cos_theta = cosf(theta); + const float sin_phi = sinf(phi); + const float cos_phi = cosf(phi); // When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false. if (is_zero(cos_theta)) { diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 29ec8eae60682a..319c2269d2471c 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -11,6 +11,7 @@ #include #include #include +#include #define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw @@ -120,12 +121,27 @@ class AC_AttitudeControl { // get the roll angular velocity limit in radians/s float get_ang_vel_roll_max_rads() const { return radians(_ang_vel_roll_max); } + // get the roll angular velocity limit in degrees/s + float get_ang_vel_roll_max_degs() const { return _ang_vel_roll_max; } + + // set the roll angular velocity limit in degrees/s + void set_ang_vel_roll_max_degs(float vel_roll_max) { _ang_vel_roll_max.set(vel_roll_max); } // get the pitch angular velocity limit in radians/s float get_ang_vel_pitch_max_rads() const { return radians(_ang_vel_pitch_max); } + // get the pitch angular velocity limit in degrees/s + float get_ang_vel_pitch_max_degs() const { return _ang_vel_pitch_max; } + + // set the pitch angular velocity limit in degrees/s + void set_ang_vel_pitch_max_degs(float vel_pitch_max) { _ang_vel_pitch_max.set(vel_pitch_max); } // get the yaw angular velocity limit in radians/s float get_ang_vel_yaw_max_rads() const { return radians(_ang_vel_yaw_max); } + // get the yaw angular velocity limit in degrees/s + float get_ang_vel_yaw_max_degs() const { return _ang_vel_yaw_max; } + + // set the yaw angular velocity limit in degrees/s + void set_ang_vel_yaw_max_degs(float vel_yaw_max) { _ang_vel_yaw_max.set(vel_yaw_max); } // get the slew yaw rate limit in deg/s float get_slew_yaw_max_degs() const; @@ -136,6 +152,7 @@ class AC_AttitudeControl { // set the rate control input smoothing time constant void set_input_tc(float input_tc) { _input_tc.set(constrain_float(input_tc, 0.0f, 1.0f)); } + // rate loop visible functions // Ensure attitude controller have zero errors to relax rate controller output void relax_attitude_controllers(); @@ -148,6 +165,9 @@ class AC_AttitudeControl { // reset rate controller I terms smoothly to zero in 0.5 seconds void reset_rate_controller_I_terms_smoothly(); + // Reduce attitude control gains while landed to stop ground resonance + void landed_gain_reduction(bool landed); + // Sets attitude target to vehicle attitude and sets all rates to zero // If reset_rate is false rates are not reset to allow the rate controllers to run void reset_target_and_rate(bool reset_rate = true); @@ -159,52 +179,80 @@ class AC_AttitudeControl { // handle reset of attitude from EKF since the last iteration void inertial_frame_reset(); + // Command euler yaw rate and pitch angle with roll angle specified in body frame + // (implemented only in AC_AttitudeControl_TS for tailsitter quadplanes) + virtual void input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float euler_roll_angle_cd, + float euler_pitch_angle_cd, float euler_yaw_rate_cds) {} + + ////// begin rate update functions ////// + // These functions all update _ang_vel_body which is used as the rate target by the rate controller. + // Since _ang_vel_body can be seen by the rate controller thread all these functions only set it + // at the end once all of the calculations have been performed. This avoids intermediate results being + // used by the rate controller when running concurrently. _ang_vel_body is accessed so commonly that + // locking proves to be moderately expensive, however since this is changing incrementally values combining + // previous and current elements are safe and do not have an impact on control. + // Any additional functions that are added to manipulate _ang_vel_body should follow this pattern. + + // Calculates the body frame angular velocities to follow the target attitude + // This is used by most of the subsequent functions + void attitude_controller_run_quat(); + // 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 - virtual void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target); + // attitude_desired_quat: is updated on each time_step (_dt) by the integral of the body frame angular velocity + virtual void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body); // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing virtual void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds); // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing virtual 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); - // Command euler yaw rate and pitch angle with roll angle specified in body frame - // (implemented only in AC_AttitudeControl_TS for tailsitter quadplanes) - virtual void input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float euler_roll_angle_cd, - float euler_pitch_angle_cd, float euler_yaw_rate_cds) {} - // Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing virtual void input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds); + // Fully stabilized acro // Command an angular velocity with angular velocity feedforward and smoothing virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds); - // Command an angular velocity with angular velocity feedforward and smoothing + // Rate-only acro with no attitude feedback - used only by Copter rate-only acro + // Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization virtual void input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds); + // Acro with attitude feedback that does not rely on attitude - used only by Plane acro // Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization virtual void input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds); // Command an angular step (i.e change) in body frame angle 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 an angular rate step (i.e change) in body frame rate + virtual void input_rate_step_bf_roll_pitch_yaw(float roll_rate_step_bf_cd, float pitch_rate_step_bf_cd, float yaw_rate_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, 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);} + ////// end rate update functions ////// + // Converts thrust vector and heading angle to quaternion rotation in the earth frame Quaternion attitude_from_thrust_vector(Vector3f thrust_vector, float heading_angle) const; // Run angular velocity controller and send outputs to the motors virtual void rate_controller_run() = 0; + // reset target loop rate modifications + virtual void rate_controller_target_reset() {} + + // optional variant to allow running with different dt + virtual void rate_controller_run_dt(const Vector3f& gyro, float dt) { AP_BoardConfig::config_error("rate_controller_run_dt() must be defined"); }; + // Convert a 321-intrinsic euler angle derivative to an angular velocity vector - void euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads); + void euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads); // Convert an angular velocity vector to a 321-intrinsic euler angle derivative // Returns false if the vehicle is pitched 90 degrees up or down - bool ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads); + bool ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads); // Specifies whether the attitude controller should use the square root controller in the attitude correction. // This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller. @@ -226,12 +274,6 @@ class AC_AttitudeControl { // Return the angle between the target thrust vector and the current thrust vector. float get_att_error_angle_deg() const { return degrees(_thrust_error_angle); } - // Set x-axis angular velocity in centidegrees/s - void rate_bf_roll_target(float rate_cds) { _ang_vel_body.x = radians(rate_cds * 0.01f); } - - // Set y-axis angular velocity in centidegrees/s - void rate_bf_pitch_target(float rate_cds) { _ang_vel_body.y = radians(rate_cds * 0.01f); } - // Set z-axis angular velocity in centidegrees/s void rate_bf_yaw_target(float rate_cds) { _ang_vel_body.z = radians(rate_cds * 0.01f); } @@ -326,10 +368,10 @@ class AC_AttitudeControl { void ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const; // translates body frame acceleration limits to the euler axis - Vector3f euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel); + Vector3f euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel); // Calculates the body frame angular velocities to follow the target attitude - void attitude_controller_run_quat(); + void update_attitude_target(); // thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion. // The maximum error in the yaw axis is limited based on the angle yaw P value and acceleration. @@ -379,6 +421,9 @@ class AC_AttitudeControl { // enable inverted flight on backends that support it virtual void set_inverted_flight(bool inverted) {} + // enable accessor for inverted flight flag on backends that support it + virtual bool get_inverted_flight() { return false;} + // 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); @@ -407,8 +452,11 @@ class AC_AttitudeControl { // purposes void set_PD_scale_mult(const Vector3f &pd_scale) { _pd_scale *= pd_scale; } - // get the value of the PD scale that was used in the last loop, for logging - const Vector3f &get_PD_scale_logging(void) const { return _pd_scale_used; } + // write RATE message + void Write_Rate(const AC_PosControl &pos_control) const; + + // write ANG message + void Write_ANG() const; // User settable parameters static const struct AP_Param::GroupInfo var_info[]; @@ -427,6 +475,9 @@ class AC_AttitudeControl { // Return the yaw slew rate limit in radians/s float get_slew_yaw_max_rads() const { return radians(get_slew_yaw_max_degs()); } + // get the latest gyro for the purposes of attitude control + const Vector3f get_latest_gyro() const; + // Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes AP_Float _slew_yaw; @@ -461,6 +512,16 @@ class AC_AttitudeControl { // rate controller input smoothing time constant AP_Float _input_tc; + // Controller gain multiplyer to be used when landed + AP_Float _land_roll_mult; + AP_Float _land_pitch_mult; + AP_Float _land_yaw_mult; + + // latest gyro value use by the rate_controller + Vector3f _rate_gyro; + // timestamp of the latest gyro value used by the rate controller + uint64_t _rate_gyro_time_us; + // Intersampling period in seconds float _dt; @@ -483,7 +544,7 @@ class AC_AttitudeControl { Vector3f _ang_vel_target; // This represents the angular velocity in radians per second in the body frame, used in the angular - // velocity controller. + // velocity controller and most importantly the rate controller. Vector3f _ang_vel_body; // This is the angular velocity in radians per second in the body frame, added to the output angular @@ -543,6 +604,9 @@ class AC_AttitudeControl { // PD scale used for last loop, used for logging Vector3f _pd_scale_used; + // ratio of normal gain to landed gain + float _landed_gain_ratio; + // References to external libraries const AP_AHRS_View& _ahrs; const AP_MultiCopter &_aparm; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 98b5df48f945cc..f44a7bca2d4d71 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -307,10 +307,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { }; AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, 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) + AC_AttitudeControl(ahrs, aparm, motors) { AP_Param::setup_object_defaults(this, var_info); @@ -361,7 +358,9 @@ void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_pass // convert angle error rotation vector into 321-intrinsic euler angle difference // NOTE: this results an an approximation linearized about the vehicle's attitude - if (ang_vel_to_euler_rate(Vector3f(_ahrs.roll, _ahrs.pitch, _ahrs.yaw), _att_error_rot_vec_rad, att_error_euler_rad)) { + Quaternion att; + _ahrs.get_quat_body_to_ned(att); + if (ang_vel_to_euler_rate(att, _att_error_rot_vec_rad, att_error_euler_rad)) { _euler_angle_target.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll); _euler_angle_target.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch); _euler_angle_target.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw); @@ -420,7 +419,8 @@ void AC_AttitudeControl_Heli::rate_controller_run() { _ang_vel_body += _sysid_ang_vel_body; - Vector3f gyro_latest = _ahrs.get_gyro_latest(); + _rate_gyro = _ahrs.get_gyro_latest(); + _rate_gyro_time_us = AP_HAL::micros64(); // call rate controllers and send output to motors object // if using a flybar passthrough roll and pitch directly to motors @@ -428,12 +428,12 @@ void AC_AttitudeControl_Heli::rate_controller_run() _motors.set_roll(_passthrough_roll / 4500.0f); _motors.set_pitch(_passthrough_pitch / 4500.0f); } else { - rate_bf_to_motor_roll_pitch(gyro_latest, _ang_vel_body.x, _ang_vel_body.y); + rate_bf_to_motor_roll_pitch(_rate_gyro, _ang_vel_body.x, _ang_vel_body.y); } if (_flags_heli.tail_passthrough) { _motors.set_yaw(_passthrough_yaw / 4500.0f); } else { - _motors.set_yaw(rate_target_to_motor_yaw(gyro_latest.z, _ang_vel_body.z)); + _motors.set_yaw(rate_target_to_motor_yaw(_rate_gyro.z, _ang_vel_body.z)); } _sysid_ang_vel_body.zero(); @@ -539,29 +539,46 @@ void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_ang _throttle_in = throttle_in; update_althold_lean_angle_max(throttle_in); - if (_transition_count > 0) { - _transition_count -= 1; + _motors.set_throttle_filter_cutoff(filter_cutoff); + if (apply_angle_boost && !((AP_MotorsHeli&)_motors).in_autorotation()) { + // Apply angle boost + throttle_in = get_throttle_boosted(throttle_in); } else { - _transition_count = 0; + // Clear angle_boost for logging purposes + _angle_boost = 0.0f; } - float throttle_out = 0.0f; - if (_transition_count > 0) { - if ((_ahrs.roll_sensor >= -3000 && _ahrs.roll_sensor <= 3000) || _ahrs.roll_sensor >= 15000 || _ahrs.roll_sensor <= -15000) { - throttle_out = (throttle_in - ((AP_MotorsHeli&)_motors).get_coll_mid()) / cosf(radians(_ahrs.roll_sensor * 0.01f)) + ((AP_MotorsHeli&)_motors).get_coll_mid(); - } else if ((_ahrs.roll_sensor > 3000 && _ahrs.roll_sensor < 15000) || (_ahrs.roll_sensor > -15000 && _ahrs.roll_sensor < -3000)) { - float scale_factor = cosf(radians(_ahrs.roll_sensor * 0.01f)) / cosf(radians(30.0f)); - throttle_out = scale_factor * (throttle_in - ((AP_MotorsHeli&)_motors).get_coll_mid())/ cosf(radians(30.0f)) + ((AP_MotorsHeli&)_motors).get_coll_mid(); - } - } else if (_inverted_flight) { - throttle_out = 1.0f - throttle_in; - } else { - throttle_out = throttle_in; + _motors.set_throttle(throttle_in); +} + +// returns a throttle including compensation for roll/pitch angle +// throttle value should be 0 ~ 1 +float AC_AttitudeControl_Heli::get_throttle_boosted(float throttle_in) +{ + if (!_angle_boost_enabled) { + _angle_boost = 0; + return throttle_in; } + // inverted_factor is 1 for tilt angles below 60 degrees + // inverted_factor changes from 1 to -1 for tilt angles between 60 and 120 degrees + + float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll(); + float inverted_factor = constrain_float(2.0f * cos_tilt, -1.0f, 1.0f); + float cos_tilt_target = fabsf(cosf(_thrust_angle)); + float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f); + + // angle boost and inverted factor applied about the zero thrust collective + const float coll_mid = ((AP_MotorsHeli&)_motors).get_coll_mid(); + float throttle_out = ((throttle_in - coll_mid) * inverted_factor * boost_factor) + coll_mid; + _angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f); + return throttle_out; +} - _motors.set_throttle_filter_cutoff(filter_cutoff); - _motors.set_throttle(throttle_out); - // Clear angle_boost for logging purposes - _angle_boost = 0.0f; +// get_roll_trim - angle in centi-degrees to be added to roll angle for learn hover collective. Used by helicopter to counter tail rotor thrust in hover +float AC_AttitudeControl_Heli::get_roll_trim_cd() +{ + // hover roll trim is given the opposite sign in inverted flight since the tail rotor thrust is pointed in the opposite direction. + float inverted_factor = constrain_float(2.0f * _ahrs.cos_roll(), -1.0f, 1.0f); + return constrain_float(_hover_roll_trim_scalar * _hover_roll_trim * inverted_factor, -1000.0f,1000.0f); } // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing @@ -591,11 +608,35 @@ void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate) #endif } -// enable/disable inverted flight -void AC_AttitudeControl_Heli::set_inverted_flight(bool inverted) +// Command a thrust vector and heading rate +void AC_AttitudeControl_Heli::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw) { - if (_inverted_flight != inverted) { - _transition_count = AC_ATTITUDE_HELI_INVERTED_TRANSITION_TIME * AP::scheduler().get_filtered_loop_rate_hz(); + + if (!_inverted_flight) { + AC_AttitudeControl::input_thrust_vector_rate_heading(thrust_vector, heading_rate_cds, slew_yaw); + return; } - _inverted_flight = inverted; + // convert thrust vector to a roll and pitch angles + // this negates the advantage of using thrust vector control, but works just fine + Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312(); + + float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f; + euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000); + AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_rate_cds); +} + +// Command a thrust vector, heading and heading rate +void AC_AttitudeControl_Heli::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds) +{ + if (!_inverted_flight) { + AC_AttitudeControl::input_thrust_vector_heading(thrust_vector, heading_angle_cd, heading_rate_cds); + return; + } + // convert thrust vector to a roll and pitch angles + Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312(); + + float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f; + euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000); + // note that we are throwing away heading rate here + AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_angle_cd, true); } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 974a404dee4e4b..7e25eef8998bf2 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -71,19 +71,29 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);} // get_roll_trim - angle in centi-degrees to be added to roll angle for learn hover collective. Used by helicopter to counter tail rotor thrust in hover - float get_roll_trim_cd() override { return constrain_float(_hover_roll_trim_scalar * _hover_roll_trim, -1000.0f,1000.0f);} + float get_roll_trim_cd() override; // Set output throttle void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override; + // calculate total body frame throttle required to produce the given earth frame throttle + float get_throttle_boosted(float throttle_in); + // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) override; // Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing 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, bool slew_yaw = true) override; + void input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds) override; + // enable/disable inverted flight - void set_inverted_flight(bool inverted) override; + void set_inverted_flight(bool inverted) override { _inverted_flight = inverted; } + + // accessor for inverted flight flag + bool get_inverted_flight() override { return _inverted_flight; } // set the PID notch sample rates void set_notch_sample_rate(float sample_rate) override; @@ -102,7 +112,6 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { // true in inverted flight mode bool _inverted_flight; - uint16_t _transition_count; // Integrate vehicle rate into _att_error_rot_vec_rad void integrate_bf_rate_error_to_angle_errors(); @@ -127,7 +136,7 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { float _passthrough_yaw; // get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover - float get_roll_trim_rad() override { return constrain_float(radians(_hover_roll_trim_scalar * _hover_roll_trim * 0.01f), -radians(10.0f),radians(10.0f));} + float get_roll_trim_rad() override { return radians(get_roll_trim_cd() * 0.01); } // internal variables float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim @@ -141,8 +150,38 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { // parameters AP_Int8 _piro_comp_enabled; // Flybar present or not. Affects attitude controller used during ACRO flight mode AP_Int16 _hover_roll_trim; // Angle in centi-degrees used to counter tail rotor thrust in hover - AC_HELI_PID _pid_rate_roll; - AC_HELI_PID _pid_rate_pitch; - AC_HELI_PID _pid_rate_yaw; + + // Roll and Pitch rate PIDs share the same defaults: + const AC_PID::Defaults rp_defaults { + AC_PID::Defaults{ + .p = AC_ATC_HELI_RATE_RP_P, + .i = AC_ATC_HELI_RATE_RP_I, + .d = AC_ATC_HELI_RATE_RP_D, + .ff = AC_ATC_HELI_RATE_RP_FF, + .imax = AC_ATC_HELI_RATE_RP_IMAX, + .filt_T_hz = AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, + .filt_E_hz = AC_ATC_HELI_RATE_RP_FILT_HZ, + .filt_D_hz = 0.0, + .srmax = 0, + .srtau = 1.0 + } + }; + AC_HELI_PID _pid_rate_roll { rp_defaults }; + AC_HELI_PID _pid_rate_pitch { rp_defaults }; + + AC_HELI_PID _pid_rate_yaw { + AC_PID::Defaults{ + .p = AC_ATC_HELI_RATE_YAW_P, + .i = AC_ATC_HELI_RATE_YAW_I, + .d = AC_ATC_HELI_RATE_YAW_D, + .ff = AC_ATC_HELI_RATE_YAW_FF, + .imax = AC_ATC_HELI_RATE_YAW_IMAX, + .filt_T_hz = AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, + .filt_E_hz = AC_ATC_HELI_RATE_YAW_FILT_HZ, + .filt_D_hz = 0.0, + .srmax = 0, + .srtau = 1.0 + } + }; }; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Logging.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Logging.cpp new file mode 100644 index 00000000000000..d9327f6abf382c --- /dev/null +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Logging.cpp @@ -0,0 +1,75 @@ +#include + +#if HAL_LOGGING_ENABLED + +#include "AC_AttitudeControl.h" +#include "AC_PosControl.h" +#include +#include +#include "LogStructure.h" + +// Write an ANG packet +void AC_AttitudeControl::Write_ANG() const +{ + Vector3f targets = get_att_target_euler_rad() * RAD_TO_DEG; + + const struct log_ANG pkt{ + LOG_PACKET_HEADER_INIT(LOG_ANG_MSG), + time_us : AP::scheduler().get_loop_start_time_us(), + control_roll : targets.x, + roll : degrees(_ahrs.roll), + control_pitch : targets.y, + pitch : degrees(_ahrs.pitch), + control_yaw : wrap_360(targets.z), + yaw : wrap_360(degrees(_ahrs.yaw)), + sensor_dt : AP::scheduler().get_last_loop_time_s() + }; + AP::logger().WriteBlock(&pkt, sizeof(pkt)); +} + +// Write a rate packet +void AC_AttitudeControl::Write_Rate(const AC_PosControl &pos_control) const +{ + const Vector3f rate_targets = rate_bf_targets() * RAD_TO_DEG; + const Vector3f &accel_target = pos_control.get_accel_target_cmss(); + const Vector3f gyro_rate = _rate_gyro * RAD_TO_DEG; + const struct log_Rate pkt_rate{ + LOG_PACKET_HEADER_INIT(LOG_RATE_MSG), + time_us : _rate_gyro_time_us, + control_roll : rate_targets.x, + roll : gyro_rate.x, + roll_out : _motors.get_roll()+_motors.get_roll_ff(), + control_pitch : rate_targets.y, + pitch : gyro_rate.y, + pitch_out : _motors.get_pitch()+_motors.get_pitch_ff(), + control_yaw : rate_targets.z, + yaw : gyro_rate.z, + yaw_out : _motors.get_yaw()+_motors.get_yaw_ff(), + control_accel : (float)accel_target.z, + accel : (float)(-(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f), + accel_out : _motors.get_throttle(), + throttle_slew : _motors.get_throttle_slew_rate() + }; + AP::logger().WriteBlock(&pkt_rate, sizeof(pkt_rate)); + + /* + log P/PD gain scale if not == 1.0 + */ + const Vector3f &scale = get_last_angle_P_scale(); + const Vector3f &pd_scale = _pd_scale_used; + if (scale != AC_AttitudeControl::VECTORF_111 || pd_scale != AC_AttitudeControl::VECTORF_111) { + const struct log_ATSC pkt_ATSC { + LOG_PACKET_HEADER_INIT(LOG_ATSC_MSG), + time_us : _rate_gyro_time_us, + scaleP_x : scale.x, + scaleP_y : scale.y, + scaleP_z : scale.z, + scalePD_x : pd_scale.x, + scalePD_y : pd_scale.y, + scalePD_z : pd_scale.z, + }; + AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC)); + } +} + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 947975a0a16868..5beb517fde739e 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -439,34 +439,49 @@ void AC_AttitudeControl_Multi::update_throttle_rpy_mix() _throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX); } -void AC_AttitudeControl_Multi::rate_controller_run() +void AC_AttitudeControl_Multi::rate_controller_run_dt(const Vector3f& gyro, float dt) { + // take a copy of the target so that it can't be changed from under us. + Vector3f ang_vel_body = _ang_vel_body; + // boost angle_p/pd each cycle on high throttle slew update_throttle_gain_boost(); // move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration) update_throttle_rpy_mix(); - _ang_vel_body += _sysid_ang_vel_body; + ang_vel_body += _sysid_ang_vel_body; - Vector3f gyro_latest = _ahrs.get_gyro_latest(); + _rate_gyro = gyro; + _rate_gyro_time_us = AP_HAL::micros64(); - _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, gyro_latest.x, _dt, _motors.limit.roll, _pd_scale.x) + _actuator_sysid.x); + _motors.set_roll(get_rate_roll_pid().update_all(ang_vel_body.x, gyro.x, dt, _motors.limit.roll, _pd_scale.x) + _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, _dt, _motors.limit.pitch, _pd_scale.y) + _actuator_sysid.y); + _motors.set_pitch(get_rate_pitch_pid().update_all(ang_vel_body.y, gyro.y, dt, _motors.limit.pitch, _pd_scale.y) + _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, _dt, _motors.limit.yaw, _pd_scale.z) + _actuator_sysid.z); + _motors.set_yaw(get_rate_yaw_pid().update_all(ang_vel_body.z, gyro.z, dt, _motors.limit.yaw, _pd_scale.z) + _actuator_sysid.z); _motors.set_yaw_ff(get_rate_yaw_pid().get_ff()*_feedforward_scalar); + _pd_scale_used = _pd_scale; + + control_monitor_update(); +} + +// reset the rate controller target loop updates +void AC_AttitudeControl_Multi::rate_controller_target_reset() +{ _sysid_ang_vel_body.zero(); _actuator_sysid.zero(); - - _pd_scale_used = _pd_scale; _pd_scale = VECTORF_111; +} - control_monitor_update(); +// run the rate controller using the configured _dt and latest gyro +void AC_AttitudeControl_Multi::rate_controller_run() +{ + Vector3f gyro_latest = _ahrs.get_gyro_latest(); + rate_controller_run_dt(gyro_latest, _dt); } // sanity check parameters. should be called once before takeoff diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index 55359a1edb6fb7..c1e9b15a250a35 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -76,6 +76,8 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl { bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f * _thr_mix_min); } // run lowest level body-frame rate controller and send outputs to the motors + void rate_controller_run_dt(const Vector3f& gyro, float dt) override; + void rate_controller_target_reset() override; void rate_controller_run() override; // sanity check parameters. should be called once before take-off diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp index c1fe903b698414..2fbf7e43e844d2 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp @@ -148,8 +148,7 @@ void AC_AttitudeControl_Multi_6DoF::input_angle_step_bf_roll_pitch_yaw(float rol // 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 -// not used anywhere in current code, panic in SITL so this implementation is not overlooked -void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target) { +void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("input_quaternion not implemented AC_AttitudeControl_Multi_6DoF"); #endif @@ -157,7 +156,7 @@ void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion& attitude_desire _motors.set_lateral(0.0f); _motors.set_forward(0.0f); - AC_AttitudeControl_Multi::input_quaternion(attitude_desired_quat, ang_vel_target); + AC_AttitudeControl_Multi::input_quaternion(attitude_desired_quat, ang_vel_body); } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h index 8023985eabb969..f8d58b50533282 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -20,8 +20,7 @@ class AC_AttitudeControl_Multi_6DoF : public AC_AttitudeControl_Multi { // 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 - // not used anywhere in current code, panic so this implementation is not overlooked - void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target) override; + void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body) override; /* override input functions to attitude controller and convert desired angles into thrust angles and substitute for offset angles */ diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index 7f2791c241a36f..56b9cca37a8b32 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -336,10 +336,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_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), - _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) + _motors_multi(motors) { AP_Param::setup_object_defaults(this, var_info); @@ -423,10 +420,12 @@ void AC_AttitudeControl_Sub::rate_controller_run() // move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration) 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, _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)); + _rate_gyro = _ahrs.get_gyro_latest(); + _rate_gyro_time_us = AP_HAL::micros64(); + + _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, _rate_gyro.x, _dt, _motors.limit.roll)); + _motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, _rate_gyro.y, _dt, _motors.limit.pitch)); + _motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, _rate_gyro.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 fb69f7094f0d67..c5a257016da506 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h @@ -83,9 +83,39 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { float get_throttle_avg_max(float throttle_in); AP_MotorsMulticopter& _motors_multi; - AC_PID _pid_rate_roll; - AC_PID _pid_rate_pitch; - AC_PID _pid_rate_yaw; + + // Roll and Pitch rate PIDs share the same defaults: + const AC_PID::Defaults rp_defaults { + AC_PID::Defaults{ + .p = AC_ATC_SUB_RATE_RP_P, + .i = AC_ATC_SUB_RATE_RP_I, + .d = AC_ATC_SUB_RATE_RP_D, + .ff = 0.0f, + .imax = AC_ATC_SUB_RATE_RP_IMAX, + .filt_T_hz = AC_ATC_SUB_RATE_RP_FILT_HZ, + .filt_E_hz = 0.0, + .filt_D_hz = AC_ATC_SUB_RATE_RP_FILT_HZ, + .srmax = 0, + .srtau = 1.0 + } + }; + AC_PID _pid_rate_roll { rp_defaults }; + AC_PID _pid_rate_pitch { rp_defaults }; + + AC_PID _pid_rate_yaw { + AC_PID::Defaults{ + .p = AC_ATC_SUB_RATE_YAW_P, + .i = AC_ATC_SUB_RATE_YAW_I, + .d = AC_ATC_SUB_RATE_YAW_D, + .ff = 0.0f, + .imax = AC_ATC_SUB_RATE_YAW_IMAX, + .filt_T_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ, + .filt_E_hz = 0.0f, + .filt_D_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ, + .srmax = 0, + .srtau = 1.0 + } + }; AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle) AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp index 3596d18b5dd688..05d23059dd53e8 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp @@ -42,7 +42,7 @@ void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch) // Initialize the roll and yaw angular rate variables to the current rate _ang_vel_target = _ahrs.get_gyro(); - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); _ang_vel_body.x = _ahrs.get_gyro().x; _ang_vel_body.z = _ahrs.get_gyro().z; diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.cpp b/libraries/AC_AttitudeControl/AC_CommandModel.cpp index caf06d826ebcea..14d4e6757be707 100644 --- a/libraries/AC_AttitudeControl/AC_CommandModel.cpp +++ b/libraries/AC_AttitudeControl/AC_CommandModel.cpp @@ -40,9 +40,9 @@ const AP_Param::GroupInfo AC_CommandModel::var_info[] = { // Constructor AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc) : + default_rate_tc(initial_tc), default_rate(initial_rate), - default_expo(initial_expo), - default_rate_tc(initial_tc) + default_expo(initial_expo) { AP_Param::setup_object_defaults(this, var_info); } diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 79e447e471bb07..c50c7581e866df 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -74,6 +74,11 @@ extern const AP_HAL::HAL& hal; #define POSCONTROL_VIBE_COMP_P_GAIN 0.250f #define POSCONTROL_VIBE_COMP_I_GAIN 0.125f +// velocity offset targets timeout if not updated within 3 seconds +#define POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS 3000 + +AC_PosControl *AC_PosControl::_singleton; + const AP_Param::GroupInfo AC_PosControl::var_info[] = { // 0 was used for HOVER @@ -331,20 +336,22 @@ AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, _inav(inav), _motors(motors), _attitude_control(attitude_control), + _p_pos_xy(POSCONTROL_POS_XY_P), _p_pos_z(POSCONTROL_POS_Z_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), _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), - _accel_max_z_cmss(POSCONTROL_ACCEL_Z), + _vel_max_up_cms(POSCONTROL_SPEED_UP), + _vel_max_down_cms(POSCONTROL_SPEED_DOWN), _accel_max_xy_cmss(POSCONTROL_ACCEL_XY), + _accel_max_z_cmss(POSCONTROL_ACCEL_Z), _jerk_max_xy_cmsss(POSCONTROL_JERK_XY * 100.0), _jerk_max_z_cmsss(POSCONTROL_JERK_Z * 100.0) { AP_Param::setup_object_defaults(this, var_info); + + _singleton = this; } @@ -358,30 +365,26 @@ AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, /// The jerk limit defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. /// The jerk limit also defines the time taken to achieve the maximum acceleration. /// The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time. -void AC_PosControl::input_pos_xyz(const Vector3p& pos, float pos_offset_z, float pos_offset_z_buffer) +void AC_PosControl::input_pos_xyz(const Vector3p& pos, float pos_terrain_target, float terrain_buffer) { // Terrain following velocity scalar must be calculated before we remove the position offset - const float offset_z_scaler = pos_offset_z_scaler(pos_offset_z, pos_offset_z_buffer); - - // remove terrain offsets for flat earth assumption - _pos_target.z -= _pos_offset_z; - _vel_desired.z -= _vel_offset_z; - _accel_desired.z -= _accel_offset_z; + const float offset_z_scaler = pos_offset_z_scaler(pos_terrain_target, terrain_buffer); + set_pos_terrain_target_cm(pos_terrain_target); // calculated increased maximum acceleration and jerk if over speed 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()); + update_pos_vel_accel_xy(_pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); // 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()); + update_pos_vel_accel(_pos_desired.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); // calculate the horizontal and vertical velocity limits to travel directly to the destination defined by pos float vel_max_xy_cms = 0.0f; float vel_max_z_cms = 0.0f; - Vector3f dest_vector = (pos - _pos_target).tofloat(); + Vector3f dest_vector = (pos - _pos_desired).tofloat(); if (is_positive(dest_vector.length_squared()) ) { dest_vector.normalize(); float dest_vector_xy_length = dest_vector.xy().length(); @@ -396,23 +399,15 @@ void AC_PosControl::input_pos_xyz(const Vector3p& pos, float pos_offset_z, float Vector2f vel; Vector2f accel; - shape_pos_vel_accel_xy(pos.xy(), vel, accel, _pos_target.xy(), _vel_desired.xy(), _accel_desired.xy(), + shape_pos_vel_accel_xy(pos.xy(), vel, accel, _pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), vel_max_xy_cms, _accel_max_xy_cmss, _jerk_max_xy_cmsss, _dt, false); float posz = pos.z; shape_pos_vel_accel(posz, 0, 0, - _pos_target.z, _vel_desired.z, _accel_desired.z, + _pos_desired.z, _vel_desired.z, _accel_desired.z, -vel_max_z_cms, vel_max_z_cms, -constrain_float(accel_max_z_cmss, 0.0f, 750.0f), accel_max_z_cmss, jerk_max_z_cmsss, _dt, false); - - // update the vertical position, velocity and acceleration offsets - update_pos_offset_z(pos_offset_z); - - // add terrain offsets - _pos_target.z += _pos_offset_z; - _vel_desired.z += _vel_offset_z; - _accel_desired.z += _accel_offset_z; } @@ -422,7 +417,7 @@ float AC_PosControl::pos_offset_z_scaler(float pos_offset_z, float pos_offset_z_ if (is_zero(pos_offset_z_buffer)) { return 1.0; } - float pos_offset_error_z = _inav.get_position_z_up_cm() - (_pos_target.z - _pos_offset_z + pos_offset_z); + float pos_offset_error_z = _inav.get_position_z_up_cm() - (_pos_target.z + (pos_offset_z - _pos_terrain)); return constrain_float((1.0 - (fabsf(pos_offset_error_z) - 0.5 * pos_offset_z_buffer) / (0.5 * pos_offset_z_buffer)), 0.01, 1.0); } @@ -466,12 +461,13 @@ void AC_PosControl::set_correction_speed_accel_xy(float speed_cms, float accel_c /// init_xy_controller_stopping_point - initialise the position controller to the stopping point with zero velocity and acceleration. /// This function should be used when the expected kinematic path assumes a stationary initial condition but does not specify a specific starting position. -/// The starting position can be retrieved by getting the position target using get_pos_target_cm() after calling this function. +/// The starting position can be retrieved by getting the position target using get_pos_desired_cm() after calling this function. void AC_PosControl::init_xy_controller_stopping_point() { init_xy_controller(); - get_stopping_point_xy_cm(_pos_target.xy()); + get_stopping_point_xy_cm(_pos_desired.xy()); + _pos_target.xy() = _pos_desired.xy() + _pos_offset.xy(); _vel_desired.xy().zero(); _accel_desired.xy().zero(); } @@ -496,6 +492,7 @@ 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)); + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); } // Prevent I term build up in xy velocity controller. @@ -507,6 +504,9 @@ void AC_PosControl::soften_for_landing_xy() /// This function is the default initialisation for any position control that provides position, velocity and acceleration. void AC_PosControl::init_xy_controller() { + // initialise offsets to target offsets and ensure offset targets are zero if they have not been updated. + init_offsets_xy(); + // set roll, pitch lean angle targets to current attitude const Vector3f &att_target_euler_cd = _attitude_control.get_att_target_euler_cd(); _roll_target = att_target_euler_cd.x; @@ -516,10 +516,10 @@ void AC_PosControl::init_xy_controller() _angle_max_override_cd = 0.0; _pos_target.xy() = _inav.get_position_xy_cm().topostype(); + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); - const Vector2f &curr_vel = _inav.get_velocity_xy_cms(); - _vel_desired.xy() = curr_vel; - _vel_target.xy() = curr_vel; + _vel_target.xy() = _inav.get_velocity_xy_cms(); + _vel_desired.xy() = _vel_target.xy() - _vel_offset.xy(); // Set desired accel to zero because raw acceleration is prone to noise _accel_desired.xy().zero(); @@ -553,11 +553,8 @@ void AC_PosControl::init_xy_controller() /// The jerk limit also defines the time taken to achieve the maximum acceleration. void AC_PosControl::input_accel_xy(const Vector3f& accel) { - // check for ekf xy position reset - handle_ekf_xy_reset(); - - 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()); - shape_accel_xy(accel, _accel_desired, _jerk_max_xy_cmsss, _dt); + update_pos_vel_accel_xy(_pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); + shape_accel_xy(accel.xy(), _accel_desired.xy(), _jerk_max_xy_cmsss, _dt); } /// input_vel_accel_xy - calculate a jerk limited path from the current position, velocity and acceleration to an input velocity and acceleration. @@ -567,7 +564,7 @@ void AC_PosControl::input_accel_xy(const Vector3f& 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. void AC_PosControl::input_vel_accel_xy(Vector2f& vel, const Vector2f& accel, bool limit_output) { - 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()); + update_pos_vel_accel_xy(_pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); shape_vel_accel_xy(vel, accel, _vel_desired.xy(), _accel_desired.xy(), _accel_max_xy_cmss, _jerk_max_xy_cmsss, _dt, limit_output); @@ -582,36 +579,58 @@ void AC_PosControl::input_vel_accel_xy(Vector2f& vel, const Vector2f& accel, boo /// 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_pos_vel_accel_xy(Vector2p& pos, Vector2f& vel, const Vector2f& accel, bool limit_output) { - 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()); + update_pos_vel_accel_xy(_pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); - shape_pos_vel_accel_xy(pos, vel, accel, _pos_target.xy(), _vel_desired.xy(), _accel_desired.xy(), + shape_pos_vel_accel_xy(pos, vel, accel, _pos_desired.xy(), _vel_desired.xy(), _accel_desired.xy(), _vel_max_xy_cms, _accel_max_xy_cmss, _jerk_max_xy_cmsss, _dt, limit_output); update_pos_vel_accel_xy(pos, vel, accel, _dt, Vector2f(), Vector2f(), Vector2f()); } +/// update the horizontal position and velocity offsets +/// this moves the offsets (e.g _pos_offset, _vel_offset, _accel_offset) towards the targets (e.g. _pos_offset_target, _vel_offset_target, _accel_offset_target) +void AC_PosControl::update_offsets_xy() +{ + // check for offset target timeout + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _posvelaccel_offset_target_xy_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) { + _pos_offset_target.xy().zero(); + _vel_offset_target.xy().zero(); + _accel_offset_target.xy().zero(); + } + + // update position, velocity, accel offsets for this iteration + update_pos_vel_accel_xy(_pos_offset_target.xy(), _vel_offset_target.xy(), _accel_offset_target.xy(), _dt, Vector2f(), Vector2f(), Vector2f()); + update_pos_vel_accel_xy(_pos_offset.xy(), _vel_offset.xy(), _accel_offset.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); + + // input shape horizontal position, velocity and acceleration offsets + shape_pos_vel_accel_xy(_pos_offset_target.xy(), _vel_offset_target.xy(), _accel_offset_target.xy(), + _pos_offset.xy(), _vel_offset.xy(), _accel_offset.xy(), + _vel_max_xy_cms, _accel_max_xy_cmss, _jerk_max_xy_cmsss, _dt, false); +} + /// stop_pos_xy_stabilisation - sets the target to the current position to remove any position corrections from the system void AC_PosControl::stop_pos_xy_stabilisation() { _pos_target.xy() = _inav.get_position_xy_cm().topostype(); + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); } /// stop_vel_xy_stabilisation - sets the target to the current position and velocity to the current velocity to remove any position and velocity corrections from the system void AC_PosControl::stop_vel_xy_stabilisation() { _pos_target.xy() = _inav.get_position_xy_cm().topostype(); - - const Vector2f &curr_vel = _inav.get_velocity_xy_cms(); - _vel_desired.xy() = curr_vel; - // with zero position error _vel_target = _vel_desired - _vel_target.xy() = curr_vel; + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); + + _vel_target.xy() = _inav.get_velocity_xy_cms();; + _vel_desired.xy() = _vel_target.xy() - _vel_offset.xy(); // initialise I terms from lean angles _pid_vel_xy.reset_filter(); _pid_vel_xy.reset_I(); } -// is_active_xy - returns true if the xy position controller has bee n run in the previous 5 loop times +// is_active_xy - returns true if the xy position controller has been run in the previous loop bool AC_PosControl::is_active_xy() const { const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_xy_ticks; @@ -640,31 +659,44 @@ void AC_PosControl::update_xy_controller() float ahrsGndSpdLimit, ahrsControlScaleXY; AP::ahrs().getControlLimits(ahrsGndSpdLimit, ahrsControlScaleXY); + // update the position, velocity and acceleration offsets + update_offsets_xy(); + // Position Controller + _pos_target.xy() = _pos_desired.xy() + _pos_offset.xy(); + + // determine the combined position of the actual position and the disturbance from system ID mode const Vector3f &curr_pos = _inav.get_position_neu_cm(); - Vector2f vel_target = _p_pos_xy.update_all(_pos_target.x, _pos_target.y, curr_pos); + Vector3f comb_pos = curr_pos; + comb_pos.xy() += _disturb_pos; + + Vector2f vel_target = _p_pos_xy.update_all(_pos_target.x, _pos_target.y, comb_pos); + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); + + // Velocity Controller // add velocity feed-forward scaled to compensate for optical flow measurement induced EKF noise vel_target *= ahrsControlScaleXY; - _vel_target.xy() = vel_target; - _vel_target.xy() += _vel_desired.xy(); - // Velocity Controller + _vel_target.xy() = vel_target; + _vel_target.xy() += _vel_desired.xy() + _vel_offset.xy(); + // determine the combined velocity of the actual velocity and the disturbance from system ID mode const Vector2f &curr_vel = _inav.get_velocity_xy_cms(); - Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), curr_vel, _dt, _limit_vector.xy()); + Vector2f comb_vel = curr_vel; + comb_vel += _disturb_vel; + + Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), comb_vel, _dt, _limit_vector.xy()); + + // Acceleration Controller // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise accel_target *= ahrsControlScaleXY; // pass the correction acceleration to the target acceleration output _accel_target.xy() = accel_target; - - // Add feed forward into the target acceleration output - _accel_target.xy() += _accel_desired.xy(); - - // Acceleration Controller + _accel_target.xy() += _accel_desired.xy() + _accel_offset.xy(); // limit acceleration using maximum lean angles float angle_max = MIN(_attitude_control.get_althold_lean_angle_max_cd(), get_lean_angle_max_cd()); @@ -686,6 +718,10 @@ void AC_PosControl::update_xy_controller() // update angle targets that will be passed to stabilize controller accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target); calculate_yaw_and_rate_yaw(); + + // reset the disturbance from system ID mode to zero + _disturb_pos.zero(); + _disturb_vel.zero(); } @@ -742,10 +778,14 @@ void AC_PosControl::init_z_controller_no_descent() init_z_controller(); // remove all descent if present - _vel_desired.z = MAX(0.0, _vel_desired.z); _vel_target.z = MAX(0.0, _vel_target.z); - _accel_desired.z = MAX(0.0, _accel_desired.z); + _vel_desired.z = MAX(0.0, _vel_desired.z); + _vel_terrain = MAX(0.0, _vel_terrain); + _vel_offset.z = MAX(0.0, _vel_offset.z); _accel_target.z = MAX(0.0, _accel_target.z); + _accel_desired.z = MAX(0.0, _accel_desired.z); + _accel_terrain = MAX(0.0, _accel_terrain); + _accel_offset.z = MAX(0.0, _accel_offset.z); } /// init_z_controller_stopping_point - initialise the position controller to the stopping point with zero velocity and acceleration. @@ -756,7 +796,8 @@ void AC_PosControl::init_z_controller_stopping_point() // Initialise the position controller to the current throttle, position, velocity and acceleration. init_z_controller(); - get_stopping_point_z_cm(_pos_target.z); + get_stopping_point_z_cm(_pos_desired.z); + _pos_target.z = _pos_desired.z + _pos_offset.z; _vel_desired.z = 0.0f; _accel_desired.z = 0.0f; } @@ -778,28 +819,26 @@ void AC_PosControl::relax_z_controller(float throttle_setting) /// This function is private and contains all the shared z axis initialisation functions void AC_PosControl::init_z_controller() { + // initialise terrain targets and offsets to zero + init_terrain(); + + // initialise offsets to target offsets and ensure offset targets are zero if they have not been updated. + init_offsets_z(); + _pos_target.z = _inav.get_position_z_up_cm(); + _pos_desired.z = _pos_target.z - _pos_offset.z; - const float curr_vel_z = _inav.get_velocity_z_up_cms(); - _vel_desired.z = curr_vel_z; - // with zero position error _vel_target = _vel_desired - _vel_target.z = curr_vel_z; + _vel_target.z = _inav.get_velocity_z_up_cms(); + _vel_desired.z = _vel_target.z - _vel_offset.z; // Reset I term of velocity PID _pid_vel_z.reset_filter(); _pid_vel_z.set_integrator(0.0f); - _accel_desired.z = constrain_float(get_z_accel_cmss(), -_accel_max_z_cmss, _accel_max_z_cmss); - // with zero position error _accel_target = _accel_desired - _accel_target.z = _accel_desired.z; + _accel_target.z = constrain_float(get_z_accel_cmss(), -_accel_max_z_cmss, _accel_max_z_cmss); + _accel_desired.z = _accel_target.z - (_accel_offset.z + _accel_terrain); _pid_accel_z.reset_filter(); - // initialise vertical offsets - _pos_offset_target_z = 0.0; - _pos_offset_z = 0.0; - _vel_offset_z = 0.0; - _accel_offset_z = 0.0; - // Set accel PID I term based on the current throttle // Remove the expected P term due to _accel_desired.z being constrained to _accel_max_z_cmss // Remove the expected FF term due to non-zero _accel_target.z @@ -822,7 +861,7 @@ void AC_PosControl::input_accel_z(float accel) float jerk_max_z_cmsss = _jerk_max_z_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()); + update_pos_vel_accel(_pos_desired.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); shape_accel(accel, _accel_desired.z, jerk_max_z_cmsss, _dt); } @@ -839,7 +878,7 @@ void AC_PosControl::input_vel_accel_z(float &vel, float accel, bool limit_output 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()); + update_pos_vel_accel(_pos_desired.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); shape_vel_accel(vel, accel, _vel_desired.z, _accel_desired.z, @@ -854,21 +893,7 @@ void AC_PosControl::input_vel_accel_z(float &vel, float accel, bool limit_output /// The zero target altitude is varied to follow pos_offset_z void AC_PosControl::set_pos_target_z_from_climb_rate_cm(float vel) { - // remove terrain offsets for flat earth assumption - _pos_target.z -= _pos_offset_z; - _vel_desired.z -= _vel_offset_z; - _accel_desired.z -= _accel_offset_z; - - float vel_temp = vel; - input_vel_accel_z(vel_temp, 0.0); - - // update the vertical position, velocity and acceleration offsets - update_pos_offset_z(_pos_offset_target_z); - - // add terrain offsets - _pos_target.z += _pos_offset_z; - _vel_desired.z += _vel_offset_z; - _accel_desired.z += _accel_offset_z; + input_vel_accel_z(vel, 0.0); } /// land_at_climb_rate_cm - adjusts target up or down using a commanded climb rate in cm/s @@ -897,10 +922,10 @@ void AC_PosControl::input_pos_vel_accel_z(float &pos, float &vel, float accel, b 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()); + update_pos_vel_accel(_pos_desired.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); shape_pos_vel_accel(pos, vel, accel, - _pos_target.z, _vel_desired.z, _accel_desired.z, + _pos_desired.z, _vel_desired.z, _accel_desired.z, _vel_max_down_cms, _vel_max_up_cms, -constrain_float(accel_max_z_cmss, 0.0f, 750.0f), accel_max_z_cmss, jerk_max_z_cmsss, _dt, limit_output); @@ -918,22 +943,35 @@ void AC_PosControl::set_alt_target_with_slew(float pos) input_pos_vel_accel_z(pos, zero, 0); } -/// update_pos_offset_z - updates the vertical offsets used by terrain following -void AC_PosControl::update_pos_offset_z(float pos_offset_z) +/// update_offsets_z - updates the vertical offsets used by terrain following +void AC_PosControl::update_offsets_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; + // check for offset target timeout + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _posvelaccel_offset_target_z_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) { + _pos_offset_target.z = 0.0; + _vel_offset_target.z = 0.0; + _accel_offset_target.z = 0.0; + } + + // update position, velocity, accel offsets for this iteration + 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; - // input shape the terrain offset - shape_pos_vel_accel(pos_offset_z, 0.0f, 0.0f, - _pos_offset_z, _vel_offset_z, _accel_offset_z, + // input shape vertical position, velocity and acceleration offsets + shape_pos_vel_accel(_pos_offset_target.z, _vel_offset_target.z, _accel_offset_target.z, + _pos_offset.z, _vel_offset.z, _accel_offset.z, get_max_speed_down_cms(), get_max_speed_up_cms(), -get_max_accel_z_cmss(), get_max_accel_z_cmss(), _jerk_max_z_cmsss, _dt, false); + + p_offset_z = _pos_offset_target.z; + update_pos_vel_accel(p_offset_z, _vel_offset_target.z, _accel_offset_target.z, _dt, 0.0, 0.0, 0.0); + _pos_offset_target.z = p_offset_z; } -// is_active_z - returns true if the z position controller has been run in the previous 5 loop times +// is_active_z - returns true if the z position controller has been run in the previous loop bool AC_PosControl::is_active_z() const { const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_z_ticks; @@ -959,6 +997,11 @@ void AC_PosControl::update_z_controller() } _last_update_z_ticks = AP::scheduler().ticks32(); + // update the position, velocity and acceleration offsets + update_offsets_z(); + update_terrain(); + _pos_target.z = _pos_desired.z + _pos_offset.z + _pos_terrain; + // calculate the target velocity correction float pos_target_zf = _pos_target.z; @@ -966,9 +1009,10 @@ void AC_PosControl::update_z_controller() _vel_target.z *= AP::ahrs().getControlScaleZ(); _pos_target.z = pos_target_zf; + _pos_desired.z = _pos_target.z - (_pos_offset.z + _pos_terrain); // add feed forward component - _vel_target.z += _vel_desired.z; + _vel_target.z += _vel_desired.z + _vel_offset.z + _vel_terrain; // Velocity Controller @@ -977,7 +1021,7 @@ void AC_PosControl::update_z_controller() _accel_target.z *= AP::ahrs().getControlScaleZ(); // add feed forward component - _accel_target.z += _accel_desired.z; + _accel_target.z += _accel_desired.z + _accel_offset.z + _accel_terrain; // Acceleration Controller @@ -986,7 +1030,7 @@ void AC_PosControl::update_z_controller() // ensure imax is always large enough to overpower hover throttle if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) { - _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f); + _pid_accel_z.set_imax(_motors.get_throttle_hover() * 1000.0f); } float thr_out; if (_vibe_comp_enabled) { @@ -1036,18 +1080,18 @@ float AC_PosControl::get_lean_angle_max_cd() const return _lean_angle_max * 100.0f; } -/// set position, velocity and acceleration targets +/// set the desired position, velocity and acceleration targets void AC_PosControl::set_pos_vel_accel(const Vector3p& pos, const Vector3f& vel, const Vector3f& accel) { - _pos_target = pos; + _pos_desired = pos; _vel_desired = vel; _accel_desired = accel; } -/// set position, velocity and acceleration targets +/// set the desired position, velocity and acceleration targets void AC_PosControl::set_pos_vel_accel_xy(const Vector2p& pos, const Vector2f& vel, const Vector2f& accel) { - _pos_target.xy() = pos; + _pos_desired.xy() = pos; _vel_desired.xy() = vel; _accel_desired.xy() = accel; } @@ -1070,6 +1114,136 @@ Vector3f AC_PosControl::lean_angles_to_accel(const Vector3f& att_target_euler) c }; } +/// Terrain + +/// set the terrain position, velocity and acceleration in cm, cms and cm/s/s from EKF origin in NE frame +/// this is used to initiate the offsets when initialise the position controller or do an offset reset +void AC_PosControl::init_terrain() +{ + // set terrain position and target to zero + _pos_terrain_target = 0.0; + _pos_terrain = 0.0; + + // set velocity offset to zero + _vel_terrain = 0.0; + + // set acceleration offset to zero + _accel_terrain = 0.0; +} + +// init_pos_terrain_cm - initialises the current terrain altitude and target altitude to pos_offset_terrain_cm +void AC_PosControl::init_pos_terrain_cm(float pos_terrain_cm) +{ + _pos_desired.z -= (pos_terrain_cm - _pos_terrain); + _pos_terrain_target = pos_terrain_cm; + _pos_terrain = pos_terrain_cm; +} + + +/// Offsets + +/// set the horizontal position, velocity and acceleration offsets in cm, cms and cm/s/s from EKF origin in NE frame +/// this is used to initiate the offsets when initialise the position controller or do an offset reset +void AC_PosControl::init_offsets_xy() +{ + // check for offset target timeout + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _posvelaccel_offset_target_xy_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) { + _pos_offset_target.xy().zero(); + _vel_offset_target.xy().zero(); + _accel_offset_target.xy().zero(); + } + + // set position offset to target + _pos_offset.xy() = _pos_offset_target.xy(); + + // set velocity offset to target + _vel_offset.xy() = _vel_offset_target.xy(); + + // set acceleration offset to target + _accel_offset.xy() = _accel_offset_target.xy(); +} + +/// set the horizontal position, velocity and acceleration offsets in cm, cms and cm/s/s from EKF origin in NE frame +/// this is used to initiate the offsets when initialise the position controller or do an offset reset +void AC_PosControl::init_offsets_z() +{ + // check for offset target timeout + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _posvelaccel_offset_target_z_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) { + _pos_offset_target.z = 0.0; + _vel_offset_target.z = 0.0; + _accel_offset_target.z = 0.0; + } + // set position offset to target + _pos_offset.z = _pos_offset_target.z; + + // set velocity offset to target + _vel_offset.z = _vel_offset_target.z; + + // set acceleration offset to target + _accel_offset.z = _accel_offset_target.z; +} + +#if AP_SCRIPTING_ENABLED +// add an additional offset to vehicle's target position, velocity and acceleration +// units are m, m/s and m/s/s in NED frame +// Z-axis is not currently supported and is ignored +bool AC_PosControl::set_posvelaccel_offset(const Vector3f &pos_offset_NED, const Vector3f &vel_offset_NED, const Vector3f &accel_offset_NED) +{ + set_posvelaccel_offset_target_xy_cm(pos_offset_NED.topostype().xy() * 100.0, vel_offset_NED.xy() * 100.0, accel_offset_NED.xy() * 100.0); + set_posvelaccel_offset_target_z_cm(-pos_offset_NED.topostype().z * 100.0, -vel_offset_NED.z * 100, -accel_offset_NED.z * 100.0); + return true; +} + +// get position and velocity offset to vehicle's target velocity and acceleration +// units are m and m/s in NED frame +bool AC_PosControl::get_posvelaccel_offset(Vector3f &pos_offset_NED, Vector3f &vel_offset_NED, Vector3f &accel_offset_NED) +{ + pos_offset_NED.xy() = _pos_offset_target.xy().tofloat() * 0.01; + pos_offset_NED.z = -_pos_offset_target.z * 0.01; + vel_offset_NED.xy() = _vel_offset_target.xy() * 0.01; + vel_offset_NED.z = -_vel_offset_target.z * 0.01; + accel_offset_NED.xy() = _accel_offset_target.xy() * 0.01; + accel_offset_NED.z = -_accel_offset_target.z * 0.01; + return true; +} +#endif + +/// set the horizontal position, velocity and acceleration offset targets in cm, cms and cm/s/s from EKF origin in NE frame +/// these must be set every 3 seconds (or less) or they will timeout and return to zero +void AC_PosControl::set_posvelaccel_offset_target_xy_cm(const Vector2p& pos_offset_target_xy_cm, const Vector2f& vel_offset_target_xy_cms, const Vector2f& accel_offset_target_xy_cmss) +{ + // set position offset target + _pos_offset_target.xy() = pos_offset_target_xy_cm; + + // set velocity offset target + _vel_offset_target.xy() = vel_offset_target_xy_cms; + + // set acceleration offset target + _accel_offset_target.xy() = accel_offset_target_xy_cmss; + + // record time of update so we can detect timeouts + _posvelaccel_offset_target_xy_ms = AP_HAL::millis(); +} + +/// set the vertical position, velocity and acceleration offset targets in cm, cms and cm/s/s from EKF origin in NE frame +/// these must be set every 3 seconds (or less) or they will timeout and return to zero +void AC_PosControl::set_posvelaccel_offset_target_z_cm(float pos_offset_target_z_cm, float vel_offset_target_z_cms, const float accel_offset_target_z_cmss) +{ + // set position offset target + _pos_offset_target.z = pos_offset_target_z_cm; + + // set velocity offset target + _vel_offset_target.z = vel_offset_target_z_cms; + + // set acceleration offset target + _accel_offset_target.z = accel_offset_target_z_cmss; + + // record time of update so we can detect timeouts + _posvelaccel_offset_target_z_ms = AP_HAL::millis(); +} + // returns the NED target acceleration vector for attitude control Vector3f AC_PosControl::get_thrust_vector() const { @@ -1082,10 +1256,12 @@ Vector3f AC_PosControl::get_thrust_vector() const /// function does not change the z axis void AC_PosControl::get_stopping_point_xy_cm(Vector2p &stopping_point) const { + // todo: we should use the current target position and velocity if we are currently running the position controller stopping_point = _inav.get_position_xy_cm().topostype(); - float kP = _p_pos_xy.kP(); + stopping_point -= _pos_offset.xy(); Vector2f curr_vel = _inav.get_velocity_xy_cms(); + curr_vel -= _vel_offset.xy(); // calculate current velocity float vel_total = curr_vel.length(); @@ -1093,7 +1269,8 @@ void AC_PosControl::get_stopping_point_xy_cm(Vector2p &stopping_point) const if (!is_positive(vel_total)) { return; } - + + float kP = _p_pos_xy.kP(); const float stopping_dist = stopping_distance(constrain_float(vel_total, 0.0, _vel_max_xy_cms), kP, _accel_max_xy_cmss); if (!is_positive(stopping_dist)) { return; @@ -1107,7 +1284,11 @@ void AC_PosControl::get_stopping_point_xy_cm(Vector2p &stopping_point) const /// get_stopping_point_z_cm - calculates stopping point in NEU cm based on current position, velocity, vehicle acceleration void AC_PosControl::get_stopping_point_z_cm(postype_t &stopping_point) const { - const float curr_pos_z = _inav.get_position_z_up_cm(); + float curr_pos_z = _inav.get_position_z_up_cm(); + curr_pos_z -= _pos_offset.z; + + float curr_vel_z = _inav.get_velocity_z_up_cms(); + curr_vel_z -= _vel_offset.z; // avoid divide by zero by using current position if kP is very low or acceleration is zero if (!is_positive(_p_pos_z.kP()) || !is_positive(_accel_max_z_cmss)) { @@ -1115,7 +1296,7 @@ void AC_PosControl::get_stopping_point_z_cm(postype_t &stopping_point) const return; } - stopping_point = curr_pos_z + constrain_float(stopping_distance(_inav.get_velocity_z_up_cms(), _p_pos_z.kP(), _accel_max_z_cmss), - POSCONTROL_STOPPING_DIST_DOWN_MAX, POSCONTROL_STOPPING_DIST_UP_MAX); + stopping_point = curr_pos_z + constrain_float(stopping_distance(curr_vel_z, _p_pos_z.kP(), _accel_max_z_cmss), - POSCONTROL_STOPPING_DIST_DOWN_MAX, POSCONTROL_STOPPING_DIST_UP_MAX); } /// get_bearing_to_target_cd - get bearing to target position in centi-degrees @@ -1167,18 +1348,32 @@ void AC_PosControl::write_log() if (is_active_xy()) { float accel_x, accel_y; lean_angles_to_accel_xy(accel_x, accel_y); - Write_PSCN(get_pos_target_cm().x, _inav.get_position_neu_cm().x, - get_vel_desired_cms().x, get_vel_target_cms().x, _inav.get_velocity_neu_cms().x, - _accel_desired.x, get_accel_target_cmss().x, accel_x); - Write_PSCE(get_pos_target_cm().y, _inav.get_position_neu_cm().y, - get_vel_desired_cms().y, get_vel_target_cms().y, _inav.get_velocity_neu_cms().y, - _accel_desired.y, get_accel_target_cmss().y, accel_y); + Write_PSCN(_pos_desired.x, _pos_target.x, _inav.get_position_neu_cm().x, + _vel_desired.x, _vel_target.x, _inav.get_velocity_neu_cms().x, + _accel_desired.x, _accel_target.x, accel_x); + Write_PSCE(_pos_desired.y, _pos_target.y, _inav.get_position_neu_cm().y, + _vel_desired.y, _vel_target.y, _inav.get_velocity_neu_cms().y, + _accel_desired.y, _accel_target.y, accel_y); + + // log offsets if they are being used + if (!_pos_offset.xy().is_zero()) { + Write_PSON(_pos_offset_target.x, _pos_offset.x, _vel_offset_target.x, _vel_offset.x, _accel_offset_target.x, _accel_offset.x); + Write_PSOE(_pos_offset_target.y, _pos_offset.y, _vel_offset_target.y, _vel_offset.y, _accel_offset_target.y, _accel_offset.y); + } } if (is_active_z()) { - Write_PSCD(-get_pos_target_cm().z, -_inav.get_position_z_up_cm(), - -get_vel_desired_cms().z, -get_vel_target_cms().z, -_inav.get_velocity_z_up_cms(), - -_accel_desired.z, -get_accel_target_cmss().z, -get_z_accel_cmss()); + Write_PSCD(-_pos_desired.z, -_pos_target.z, -_inav.get_position_z_up_cm(), + -_vel_desired.z, -_vel_target.z, -_inav.get_velocity_z_up_cms(), + -_accel_desired.z, -_accel_target.z, -get_z_accel_cmss()); + + // log down and terrain offsets if they are being used + if (!is_zero(_pos_offset.z)) { + Write_PSOD(-_pos_offset_target.z, -_pos_offset.z, -_vel_offset_target.z, -_vel_offset.z, -_accel_offset_target.z, -_accel_offset.z); + } + if (!is_zero(_pos_terrain)) { + Write_PSOT(-_pos_terrain_target, -_pos_terrain, 0, -_vel_terrain, 0, -_accel_terrain); + } } } #endif // HAL_LOGGING_ENABLED @@ -1204,6 +1399,27 @@ float AC_PosControl::crosstrack_error() const /// private methods /// +/// Terrain + +/// update_z_offsets - updates the vertical offsets used by terrain following +void AC_PosControl::update_terrain() +{ + // update position, velocity, accel offsets for this iteration + postype_t pos_terrain = _pos_terrain; + update_pos_vel_accel(pos_terrain, _vel_terrain, _accel_terrain, _dt, MIN(_limit_vector.z, 0.0f), _p_pos_z.get_error(), _pid_vel_z.get_error()); + _pos_terrain = pos_terrain; + + // input shape horizontal position, velocity and acceleration offsets + shape_pos_vel_accel(_pos_terrain_target, 0.0, 0.0, + _pos_terrain, _vel_terrain, _accel_terrain, + get_max_speed_down_cms(), get_max_speed_up_cms(), + -get_max_accel_z_cmss(), get_max_accel_z_cmss(), + _jerk_max_z_cmsss, _dt, false); + + // we do not have to update _pos_terrain_target because we assume the target velocity and acceleration are zero + // if we know how fast the terain altitude is changing we would add update_pos_vel_accel for _pos_terrain_target here +} + // get_lean_angles_to_accel - convert roll, pitch lean angles to NE frame accelerations in cm/s/s void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const { @@ -1285,8 +1501,14 @@ void AC_PosControl::handle_ekf_xy_reset() uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift); if (reset_ms != _ekf_xy_reset_ms) { + // ToDo: move EKF steps into the offsets for modes setting absolute position and velocity + // for this we need some sort of switch to select what type of EKF handling we want to use + + // To zero real position shift during relative position modes like Loiter, PosHold, Guided velocity and accleration control. _pos_target.xy() = (_inav.get_position_xy_cm() + _p_pos_xy.get_error()).topostype(); + _pos_desired.xy() = _pos_target.xy() - _pos_offset.xy(); _vel_target.xy() = _inav.get_velocity_xy_cms() + _pid_vel_xy.get_error(); + _vel_desired.xy() = _vel_target.xy() - _vel_offset.xy(); _ekf_xy_reset_ms = reset_ms; } @@ -1307,8 +1529,14 @@ void AC_PosControl::handle_ekf_z_reset() uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift); if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) { + // ToDo: move EKF steps into the offsets for modes setting absolute position and velocity + // for this we need some sort of switch to select what type of EKF handling we want to use + + // To zero real position shift during relative position modes like Loiter, PosHold, Guided velocity and accleration control. _pos_target.z = _inav.get_position_z_up_cm() + _p_pos_z.get_error(); + _pos_desired.z = _pos_target.z - (_pos_offset.z + _pos_terrain); _vel_target.z = _inav.get_velocity_z_up_cms() + _pid_vel_z.get_error(); + _vel_desired.z = _vel_target.z - (_vel_offset.z + _vel_terrain); _ekf_z_reset_ms = reset_ms; } diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 3463da0306b8ae..f52c7a9c5c9ea7 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -11,6 +11,7 @@ #include // PID library (1-axis) #include // PID library (2-axis) #include // Inertial Navigation library +#include #include "AC_AttitudeControl.h" // Attitude control library #include @@ -43,7 +44,8 @@ class AC_PosControl AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, const class AP_Motors& motors, AC_AttitudeControl& attitude_control); - + // do not allow copying + CLASS_NO_COPY(AC_PosControl); /// 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 @@ -52,7 +54,7 @@ class AC_PosControl 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 - float get_shaping_jerk_xy_cmsss() const { return _shaping_jerk_xy*100.0; } + float get_shaping_jerk_xy_cmsss() const { return _shaping_jerk_xy * 100.0; } /// @@ -62,7 +64,7 @@ class AC_PosControl /// input_pos_xyz - calculate a jerk limited path from the current position, velocity and acceleration to an input position. /// 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_xy. - void input_pos_xyz(const Vector3p& pos, float pos_offset_z, float pos_offset_z_buffer); + void input_pos_xyz(const Vector3p& pos, float pos_terrain_target, float terrain_buffer); /// pos_offset_z_scaler - calculates a multiplier used to reduce the horizontal velocity to allow the z position controller to stay within the provided buffer range float pos_offset_z_scaler(float pos_offset_z, float pos_offset_z_buffer) const; @@ -225,9 +227,6 @@ class AC_PosControl /// using the default position control kinematic path. void set_alt_target_with_slew(float pos); - /// update_pos_offset_z - updates the vertical offsets used by terrain following - void update_pos_offset_z(float pos_offset); - // is_active_z - returns true if the z position controller has been run in the previous 5 loop times bool is_active_z() const; @@ -250,32 +249,44 @@ class AC_PosControl /// Position - /// set_pos_target_xy_cm - sets the position target, frame NEU in cm relative to the EKF origin - void set_pos_target_xy_cm(float pos_x, float pos_y) { _pos_target.x = pos_x; _pos_target.y = pos_y; } - /// get_pos_target_cm - returns the position target, frame NEU in cm relative to the EKF origin const Vector3p& get_pos_target_cm() const { return _pos_target; } - /// set_pos_target_z_cm - set altitude target in cm above the EKF origin - void set_pos_target_z_cm(float pos_target) { _pos_target.z = pos_target; } + /// set_pos_desired_xy_cm - sets the position target, frame NEU in cm relative to the EKF origin + void set_pos_desired_xy_cm(const Vector2f& pos) { _pos_desired.xy() = pos.topostype(); } + + /// get_pos_desired_cm - returns the position desired, frame NEU in cm relative to the EKF origin + const Vector3p& get_pos_desired_cm() const { return _pos_desired; } /// get_pos_target_z_cm - get target altitude (in cm above the EKF origin) float get_pos_target_z_cm() const { return _pos_target.z; } + /// set_pos_desired_z_cm - set altitude target in cm above the EKF origin + void set_pos_desired_z_cm(float pos_z) { _pos_desired.z = pos_z; } + + /// get_pos_desired_z_cm - get target altitude (in cm above the EKF origin) + float get_pos_desired_z_cm() const { return _pos_desired.z; } + + + /// Stopping Point + /// get_stopping_point_xy_cm - calculates stopping point in NEU cm based on current position, velocity, vehicle acceleration void get_stopping_point_xy_cm(Vector2p &stopping_point) const; /// get_stopping_point_z_cm - calculates stopping point in NEU cm based on current position, velocity, vehicle acceleration void get_stopping_point_z_cm(postype_t &stopping_point) const; + + /// Position Error + /// get_pos_error_cm - get position error vector between the current and target position - const Vector3f get_pos_error_cm() const { return (_pos_target - _inav.get_position_neu_cm().topostype()).tofloat(); } + const Vector3f get_pos_error_cm() const { return Vector3f(_p_pos_xy.get_error().x, _p_pos_xy.get_error().y, _p_pos_z.get_error()); } /// get_pos_error_xy_cm - get the length of the position error vector in the xy plane - float get_pos_error_xy_cm() const { return get_horizontal_distance_cm(_inav.get_position_xy_cm().topostype(), _pos_target.xy()); } + float get_pos_error_xy_cm() const { return _p_pos_xy.get_error().length(); } /// get_pos_error_z_cm - returns altitude error in cm - float get_pos_error_z_cm() const { return (_pos_target.z - _inav.get_position_z_up_cm()); } + float get_pos_error_z_cm() const { return _p_pos_z.get_error(); } /// Velocity @@ -286,7 +297,7 @@ class AC_PosControl /// set_vel_desired_xy_cms - sets horizontal desired velocity in NEU cm/s void set_vel_desired_xy_cms(const Vector2f &vel) {_vel_desired.xy() = vel; } - /// get_vel_desired_cms - returns desired velocity (i.e. feed forward) in cm/s in NEU + /// get_vel_desired_cms - returns desired velocity in cm/s in NEU const Vector3f& get_vel_desired_cms() { return _vel_desired; } // get_vel_target_cms - returns the target velocity in NEU cm/s @@ -301,30 +312,56 @@ class AC_PosControl /// Acceleration - // set_accel_desired_xy_cmss set desired acceleration in cm/s in xy axis + // set_accel_desired_xy_cmss - set desired acceleration in cm/s in xy axis void set_accel_desired_xy_cmss(const Vector2f &accel_cms) { _accel_desired.xy() = accel_cms; } // get_accel_target_cmss - returns the target acceleration in NEU cm/s/s const Vector3f& get_accel_target_cmss() const { return _accel_target; } + /// Terrain + + // set_pos_terrain_target_cm - set target terrain altitude in cm + void set_pos_terrain_target_cm(float pos_terrain_target) {_pos_terrain_target = pos_terrain_target;} + + // init_pos_terrain_cm - initialises the current terrain altitude and target altitude to pos_offset_terrain_cm + void init_pos_terrain_cm(float pos_offset_terrain_cm); + + // get_pos_terrain_cm - returns the current terrain altitude in cm + float get_pos_terrain_cm() { return _pos_terrain; } + + /// Offset - /// set_pos_offset_target_z_cm - set altitude offset target in cm above the EKF origin - void set_pos_offset_target_z_cm(float pos_offset_target_z) { _pos_offset_target_z = pos_offset_target_z; } +#if AP_SCRIPTING_ENABLED + // position, velocity and acceleration offset target (only used by scripting) + // gets or sets an additional offset to the vehicle's target position, velocity and acceleration + // units are m, m/s and m/s/s in NED frame + bool set_posvelaccel_offset(const Vector3f &pos_offset_NED, const Vector3f &vel_offset_NED, const Vector3f &accel_offset_NED); + bool get_posvelaccel_offset(Vector3f &pos_offset_NED, Vector3f &vel_offset_NED, Vector3f &accel_offset_NED); +#endif + + /// set the horizontal position, velocity and acceleration offset targets in cm, cms and cm/s/s from EKF origin in NE frame + /// these must be set every 3 seconds (or less) or they will timeout and return to zero + void set_posvelaccel_offset_target_xy_cm(const Vector2p& pos_offset_target_xy_cm, const Vector2f& vel_offset_target_xy_cms, const Vector2f& accel_offset_target_xy_cmss); + void set_posvelaccel_offset_target_z_cm(float pos_offset_target_z_cm, float vel_offset_target_z_cms, float accel_offset_target_z_cmss); + + /// get the position, velocity or acceleration offets in cm from EKF origin in NEU frame + const Vector3p& get_pos_offset_cm() const { return _pos_offset; } + const Vector3f& get_vel_offset_cms() const { return _vel_offset; } + const Vector3f& get_accel_offset_cmss() const { return _accel_offset; } /// set_pos_offset_z_cm - set altitude offset in cm above the EKF origin - void set_pos_offset_z_cm(float pos_offset_z) { _pos_offset_z = pos_offset_z; } + void set_pos_offset_z_cm(float pos_offset_z) { _pos_offset.z = pos_offset_z; } /// get_pos_offset_z_cm - returns altitude offset in cm above the EKF origin - float get_pos_offset_z_cm() const { return _pos_offset_z; } + float get_pos_offset_z_cm() const { return _pos_offset.z; } /// get_vel_offset_z_cm - returns current vertical offset speed in cm/s - float get_vel_offset_z_cms() const { return _vel_offset_z; } + float get_vel_offset_z_cms() const { return _vel_offset.z; } /// get_accel_offset_z_cm - returns current vertical offset acceleration in cm/s/s - float get_accel_offset_z_cmss() const { return _accel_offset_z; } - + float get_accel_offset_z_cmss() const { return _accel_offset.z; } /// Outputs @@ -398,12 +435,25 @@ class AC_PosControl /// returns true when the forward pitch demand is limited by the maximum allowed tilt bool get_fwd_pitch_is_limited() const { return _fwd_pitch_is_limited; } + + // set disturbance north + void set_disturb_pos_cm(Vector2f disturb_pos) {_disturb_pos = disturb_pos;} + + // set disturbance north + void set_disturb_vel_cms(Vector2f disturb_vel) {_disturb_vel = disturb_vel;} static const struct AP_Param::GroupInfo var_info[]; - static void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); - static void Write_PSCE(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); - static void Write_PSCD(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + static void Write_PSCN(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + static void Write_PSCE(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + static void Write_PSCD(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + static void Write_PSON(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss); + static void Write_PSOE(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss); + static void Write_PSOD(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss); + static void Write_PSOT(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss); + + // singleton + static AC_PosControl *get_singleton(void) { return _singleton; } protected: @@ -422,6 +472,32 @@ class AC_PosControl // calculate_overspeed_gain - calculated increased maximum acceleration and jerk if over speed condition is detected float calculate_overspeed_gain(); + + /// Terrain Following + + /// set the position, velocity and acceleration offsets in cm, cms and cm/s/s from EKF origin in NE frame + /// this is used to initiate the offsets when initialise the position controller or do an offset reset + /// note that this sets the actual offsets, not the offset targets + void init_terrain(); + + /// update_terrain - updates the terrain position, velocity and acceleration estimation + /// this moves the estimated terrain position _pos_terrain towards the target _pos_terrain_target + void update_terrain(); + + + /// Offsets + + /// init_offsets - set the position, velocity and acceleration offsets in cm, cms and cm/s/s from EKF origin in NE frame + /// this is used to initiate the offsets when initialise the position controller or do an offset reset + /// note that this sets the actual offsets, not the offset targets + void init_offsets_xy(); + void init_offsets_z(); + + /// update_offsets - update the position and velocity offsets + /// this moves the offsets (e.g _pos_offset, _vel_offset, _accel_offset) towards the targets (e.g. _pos_offset_target or _vel_offset_target) + void update_offsets_xy(); + void update_offsets_z(); + /// initialise and check for ekf position resets void init_ekf_xy_reset(); void handle_ekf_xy_reset(); @@ -456,6 +532,8 @@ class AC_PosControl float _jerk_max_xy_cmsss; // Jerk limit of the xy kinematic path generation in cm/s^3 used to determine how quickly the aircraft varies the acceleration target float _jerk_max_z_cmsss; // Jerk limit of the z kinematic path generation in cm/s^3 used to determine how quickly the aircraft varies the acceleration target float _vel_z_control_ratio = 2.0f; // confidence that we have control in the vertical axis + Vector2f _disturb_pos; // position disturbance generated by system ID mode + Vector2f _disturb_vel; // velocity disturbance generated by system ID mode // output from controller float _roll_target; // desired roll angle in centi-degrees calculated by position controller @@ -464,7 +542,8 @@ class AC_PosControl float _yaw_rate_target; // desired yaw rate in centi-degrees per second calculated by position controller // position controller internal variables - Vector3p _pos_target; // target location, frame NEU in cm relative to the EKF origin + Vector3p _pos_desired; // desired location, frame NEU in cm relative to the EKF origin. This is equal to the _pos_target minus offsets + Vector3p _pos_target; // target location, frame NEU in cm relative to the EKF origin. This is equal to the _pos_desired plus offsets Vector3f _vel_desired; // desired velocity in NEU cm/s Vector3f _vel_target; // velocity target in NEU cm/s calculated by pos_to_rate step Vector3f _accel_desired; // desired acceleration in NEU cm/s/s (feed forward) @@ -473,10 +552,21 @@ class AC_PosControl bool _fwd_pitch_is_limited; // true when the forward pitch demand is being limited to meet acceleration limits - float _pos_offset_target_z; // vertical position offset target, frame NEU in cm relative to the EKF origin - float _pos_offset_z; // vertical position offset, frame NEU in cm relative to the EKF origin - float _vel_offset_z; // vertical velocity offset in NEU cm/s calculated by pos_to_rate step - float _accel_offset_z; // vertical acceleration offset in NEU cm/s/s + // terrain handling variables + float _pos_terrain_target; // position terrain target in cm relative to the EKF origin in NEU frame + float _pos_terrain; // position terrain in cm from the EKF origin in NEU frame. this terrain moves towards _pos_terrain_target + float _vel_terrain; // velocity terrain in NEU cm/s calculated by pos_to_rate step. this terrain moves towards _vel_terrain_target + float _accel_terrain; // acceleration terrain in NEU cm/s/s + + // offset handling variables + Vector3p _pos_offset_target; // position offset target in cm relative to the EKF origin in NEU frame + Vector3p _pos_offset; // position offset in cm from the EKF origin in NEU frame. this offset moves towards _pos_offset_target + Vector3f _vel_offset_target; // velocity offset target in cm/s in NEU frame + Vector3f _vel_offset; // velocity offset in NEU cm/s calculated by pos_to_rate step. this offset moves towards _vel_offset_target + Vector3f _accel_offset_target; // acceleration offset target in cm/s/s in NEU frame + Vector3f _accel_offset; // acceleration offset in NEU cm/s/s + uint32_t _posvelaccel_offset_target_xy_ms; // system time that pos, vel, accel targets were set (used to implement timeouts) + uint32_t _posvelaccel_offset_target_z_ms; // system time that pos, vel, accel targets were set (used to implement timeouts) // ekf reset handling uint32_t _ekf_xy_reset_ms; // system time of last recorded ekf xy position reset @@ -494,6 +584,13 @@ class AC_PosControl private: // convenience method for writing out the identical PSCE, PSCN, PSCD - and // to save bytes - static void Write_PSCx(LogMessages ID, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + static void Write_PSCx(LogMessages ID, float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); + + // a convenience function for writing out the position controller offsets + static void Write_PSOx(LogMessages id, float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss); + // singleton + static AC_PosControl *_singleton; }; diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp b/libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp index d02760cdeb62ec..7be5f91ed74855 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp @@ -8,11 +8,12 @@ #include "LogStructure.h" // a convenience function for writing out the position controller PIDs -void AC_PosControl::Write_PSCx(LogMessages id, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) +void AC_PosControl::Write_PSCx(LogMessages id, float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) { const struct log_PSCx pkt{ LOG_PACKET_HEADER_INIT(id), time_us : AP_HAL::micros64(), + pos_desired : pos_desired * 0.01f, pos_target : pos_target * 0.01f, pos : pos * 0.01f, vel_desired : vel_desired * 0.01f, @@ -25,19 +26,65 @@ void AC_PosControl::Write_PSCx(LogMessages id, float pos_target, float pos, floa AP::logger().WriteBlock(&pkt, sizeof(pkt)); } -void AC_PosControl::Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) +void AC_PosControl::Write_PSCN(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) { - Write_PSCx(LOG_PSCN_MSG, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); + Write_PSCx(LOG_PSCN_MSG, pos_desired, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); } -void AC_PosControl::Write_PSCE(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) +void AC_PosControl::Write_PSCE(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) { - Write_PSCx(LOG_PSCE_MSG, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); + Write_PSCx(LOG_PSCE_MSG, pos_desired, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); } -void AC_PosControl::Write_PSCD(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) +void AC_PosControl::Write_PSCD(float pos_desired, float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel) { - Write_PSCx(LOG_PSCD_MSG, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); + Write_PSCx(LOG_PSCD_MSG, pos_desired, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); +} + +// a convenience function for writing out the position controller offsets +void AC_PosControl::Write_PSOx(LogMessages id, float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss) +{ + const struct log_PSOx pkt{ + LOG_PACKET_HEADER_INIT(id), + time_us : AP_HAL::micros64(), + pos_target_offset : pos_target_offset_cm * 0.01f, + pos_offset : pos_offset_cm * 0.01f, + vel_target_offset : vel_target_offset_cms * 0.01f, + vel_offset : vel_offset_cms * 0.01f, + accel_target_offset : accel_target_offset_cmss * 0.01f, + accel_offset : accel_offset_cmss * 0.01f, + }; + AP::logger().WriteBlock(&pkt, sizeof(pkt)); +} + +void AC_PosControl::Write_PSON(float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss) +{ + Write_PSOx(LOG_PSON_MSG, pos_target_offset_cm, pos_offset_cm, vel_target_offset_cms, vel_offset_cms, accel_target_offset_cmss, accel_offset_cmss); +} + +void AC_PosControl::Write_PSOE(float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss) +{ + Write_PSOx(LOG_PSOE_MSG, pos_target_offset_cm, pos_offset_cm, vel_target_offset_cms, vel_offset_cms, accel_target_offset_cmss, accel_offset_cmss); +} + +void AC_PosControl::Write_PSOD(float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss) +{ + Write_PSOx(LOG_PSOD_MSG, pos_target_offset_cm, pos_offset_cm, vel_target_offset_cms, vel_offset_cms, accel_target_offset_cmss, accel_offset_cmss); +} + +void AC_PosControl::Write_PSOT(float pos_target_offset_cm, float pos_offset_cm, + float vel_target_offset_cms, float vel_offset_cms, + float accel_target_offset_cmss, float accel_offset_cmss) +{ + Write_PSOx(LOG_PSOT_MSG, pos_target_offset_cm, pos_offset_cm, vel_target_offset_cms, vel_offset_cms, accel_target_offset_cmss, accel_offset_cmss); } #endif // HAL_LOGGING_ENABLED diff --git a/libraries/AC_AttitudeControl/LogStructure.h b/libraries/AC_AttitudeControl/LogStructure.h index 9b5fe8df95bb3c..9b263e790f52f0 100644 --- a/libraries/AC_AttitudeControl/LogStructure.h +++ b/libraries/AC_AttitudeControl/LogStructure.h @@ -5,11 +5,17 @@ #define LOG_IDS_FROM_AC_ATTITUDECONTROL \ LOG_PSCN_MSG, \ LOG_PSCE_MSG, \ - LOG_PSCD_MSG + LOG_PSCD_MSG, \ + LOG_PSON_MSG, \ + LOG_PSOE_MSG, \ + LOG_PSOD_MSG, \ + LOG_PSOT_MSG, \ + LOG_ANG_MSG // @LoggerMessage: PSCN // @Description: Position Control North // @Field: TimeUS: Time since system startup +// @Field: DPN: Desired position relative to EKF origin // @Field: TPN: Target position relative to EKF origin // @Field: PN: Position relative to EKF origin // @Field: DVN: Desired velocity North @@ -22,6 +28,7 @@ // @LoggerMessage: PSCE // @Description: Position Control East // @Field: TimeUS: Time since system startup +// @Field: DPE: Desired position relative to EKF origin + Offsets // @Field: TPE: Target position relative to EKF origin // @Field: PE: Position relative to EKF origin // @Field: DVE: Desired velocity East @@ -34,6 +41,7 @@ // @LoggerMessage: PSCD // @Description: Position Control Down // @Field: TimeUS: Time since system startup +// @Field: DPD: Desired position relative to EKF origin + Offsets // @Field: TPD: Target position relative to EKF origin // @Field: PD: Position relative to EKF origin // @Field: DVD: Desired velocity Down @@ -48,6 +56,7 @@ struct PACKED log_PSCx { LOG_PACKET_HEADER; uint64_t time_us; + float pos_desired; float pos_target; float pos; float vel_desired; @@ -58,14 +67,138 @@ struct PACKED log_PSCx { float accel; }; -#define PSCx_FMT "Qffffffff" -#define PSCx_UNITS "smmnnnooo" -#define PSCx_MULTS "F00000000" +// @LoggerMessage: PSON +// @Description: Position Control Offsets North +// @Field: TimeUS: Time since system startup +// @Field: TPON: Target position offset North +// @Field: PON: Position offset North +// @Field: TVON: Target velocity offset North +// @Field: VON: Velocity offset North +// @Field: TAON: Target acceleration offset North +// @Field: AON: Acceleration offset North + +// @LoggerMessage: PSOE +// @Description: Position Control Offsets East +// @Field: TimeUS: Time since system startup +// @Field: TPOE: Target position offset East +// @Field: POE: Position offset East +// @Field: TVOE: Target velocity offset East +// @Field: VOE: Velocity offset East +// @Field: TAOE: Target acceleration offset East +// @Field: AOE: Acceleration offset East + +// @LoggerMessage: PSOD +// @Description: Position Control Offsets Down +// @Field: TimeUS: Time since system startup +// @Field: TPOD: Target position offset Down +// @Field: POD: Position offset Down +// @Field: TVOD: Target velocity offset Down +// @Field: VOD: Velocity offset Down +// @Field: TAOD: Target acceleration offset Down +// @Field: AOD: Acceleration offset Down + +// @LoggerMessage: PSOT +// @Description: Position Control Offsets Terrain (Down) +// @Field: TimeUS: Time since system startup +// @Field: TPOT: Target position offset Terrain +// @Field: POT: Position offset Terrain +// @Field: TVOT: Target velocity offset Terrain +// @Field: VOT: Velocity offset Terrain +// @Field: TAOT: Target acceleration offset Terrain +// @Field: AOT: Acceleration offset Terrain + +// position controller per-axis offset logging +struct PACKED log_PSOx { + LOG_PACKET_HEADER; + uint64_t time_us; + float pos_target_offset; + float pos_offset; + float vel_target_offset; + float vel_offset; + float accel_target_offset; + float accel_offset; +}; + +// @LoggerMessage: RATE +// @Description: Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes. +// @Field: TimeUS: Time since system startup +// @Field: RDes: vehicle desired roll rate +// @Field: R: achieved vehicle roll rate +// @Field: ROut: normalized output for Roll +// @Field: PDes: vehicle desired pitch rate +// @Field: P: vehicle pitch rate +// @Field: POut: normalized output for Pitch +// @Field: Y: achieved vehicle yaw rate +// @Field: YOut: normalized output for Yaw +// @Field: YDes: vehicle desired yaw rate +// @Field: ADes: desired vehicle vertical acceleration +// @Field: A: achieved vehicle vertical acceleration +// @Field: AOut: percentage of vertical thrust output current being used +// @Field: AOutSlew: vertical thrust output slew rate +struct PACKED log_Rate { + LOG_PACKET_HEADER; + uint64_t time_us; + float control_roll; + float roll; + float roll_out; + float control_pitch; + float pitch; + float pitch_out; + float control_yaw; + float yaw; + float yaw_out; + float control_accel; + float accel; + float accel_out; + float throttle_slew; +}; + +// @LoggerMessage: ANG +// @Description: Attitude control attitude +// @Field: TimeUS: Timestamp of the current Attitude loop +// @Field: DesRoll: vehicle desired roll +// @Field: Roll: achieved vehicle roll +// @Field: DesPitch: vehicle desired pitch +// @Field: Pitch: achieved vehicle pitch +// @Field: DesYaw: vehicle desired yaw +// @Field: Yaw: achieved vehicle yaw +// @Field: Dt: attitude delta time +struct PACKED log_ANG { + LOG_PACKET_HEADER; + uint64_t time_us; + float control_roll; + float roll; + float control_pitch; + float pitch; + float control_yaw; + float yaw; + float sensor_dt; +}; + +#define PSCx_FMT "Qfffffffff" +#define PSCx_UNITS "smmmnnnooo" +#define PSCx_MULTS "F000000000" + +#define PSOx_FMT "Qffffff" +#define PSOx_UNITS "smmnnoo" +#define PSOx_MULTS "F000000" #define LOG_STRUCTURE_FROM_AC_ATTITUDECONTROL \ { LOG_PSCN_MSG, sizeof(log_PSCx), \ - "PSCN", PSCx_FMT, "TimeUS,TPN,PN,DVN,TVN,VN,DAN,TAN,AN", PSCx_UNITS, PSCx_MULTS }, \ + "PSCN", PSCx_FMT, "TimeUS,DPN,TPN,PN,DVN,TVN,VN,DAN,TAN,AN", PSCx_UNITS, PSCx_MULTS }, \ { LOG_PSCE_MSG, sizeof(log_PSCx), \ - "PSCE", PSCx_FMT, "TimeUS,TPE,PE,DVE,TVE,VE,DAE,TAE,AE", PSCx_UNITS, PSCx_MULTS }, \ + "PSCE", PSCx_FMT, "TimeUS,DPE,TPE,PE,DVE,TVE,VE,DAE,TAE,AE", PSCx_UNITS, PSCx_MULTS }, \ { LOG_PSCD_MSG, sizeof(log_PSCx), \ - "PSCD", PSCx_FMT, "TimeUS,TPD,PD,DVD,TVD,VD,DAD,TAD,AD", PSCx_UNITS, PSCx_MULTS } + "PSCD", PSCx_FMT, "TimeUS,DPD,TPD,PD,DVD,TVD,VD,DAD,TAD,AD", PSCx_UNITS, PSCx_MULTS }, \ + { LOG_PSON_MSG, sizeof(log_PSOx), \ + "PSON", PSOx_FMT, "TimeUS,TPON,PON,TVON,VON,TAON,AON", PSOx_UNITS, PSOx_MULTS }, \ + { LOG_PSOE_MSG, sizeof(log_PSOx), \ + "PSOE", PSOx_FMT, "TimeUS,TPOE,POE,TVOE,VOE,TAOE,AOE", PSOx_UNITS, PSOx_MULTS }, \ + { LOG_PSOD_MSG, sizeof(log_PSOx), \ + "PSOD", PSOx_FMT, "TimeUS,TPOD,POD,TVOD,VOD,TAOD,AOD", PSOx_UNITS, PSOx_MULTS }, \ + { LOG_PSOT_MSG, sizeof(log_PSOx), \ + "PSOT", PSOx_FMT, "TimeUS,TPOT,POT,TVOT,VOT,TAOT,AOT", PSOx_UNITS, PSOx_MULTS }, \ + { LOG_RATE_MSG, sizeof(log_Rate), \ + "RATE", "Qfffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut,AOutSlew", "skk-kk-kk-oo--", "F?????????BB--" , true }, \ + { LOG_ANG_MSG, sizeof(log_ANG),\ + "ANG", "Qfffffff", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,Dt", "sddddhhs", "F0000000" , true } diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index 998297d0219877..213ae21551507a 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -10,19 +10,18 @@ #include #include -#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds +#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) - # define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg) - # define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec) + # define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg) + # define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec) #else - # define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level - # define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch + # define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level + # define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch #endif -#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw -#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 500 // time we require the aircraft to be level -#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level -#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users -#define AUTOTUNE_ANGLE_MAX_RLLPIT 30.0f // maximum allowable angle in degrees during testing +#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw +#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 250 // time we require the aircraft to be level before starting next test +#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level +#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users AC_AutoTune::AC_AutoTune() { @@ -41,6 +40,7 @@ bool AC_AutoTune::init_internals(bool _use_poshold, ahrs_view = _ahrs_view; inertial_nav = _inertial_nav; motors = AP_Motors::get_singleton(); + const uint32_t now = AP_HAL::millis(); // exit immediately if motor are not armed if ((motors == nullptr) || !motors->armed()) { @@ -71,8 +71,8 @@ bool AC_AutoTune::init_internals(bool _use_poshold, // we are restarting tuning so restart where we left off step = WAITING_FOR_LEVEL; - step_start_time_ms = AP_HAL::millis(); - level_start_time_ms = step_start_time_ms; + step_start_time_ms = now; + level_start_time_ms = now; // reset gains to tuning-start gains (i.e. low I term) load_gains(GAIN_INTRA_TEST); LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART); @@ -109,6 +109,51 @@ void AC_AutoTune::stop() // we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch } +// Autotune aux function trigger +void AC_AutoTune::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag) +{ + if (mode != TuneMode::SUCCESS) { + if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) { + gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: must be complete to test gains"); + } + return; + } + + switch(ch_flag) { + case RC_Channel::AuxSwitchPos::LOW: + // load original gains + load_gains(GainType::GAIN_ORIGINAL); + update_gcs(AUTOTUNE_MESSAGE_TESTING_END); + break; + case RC_Channel::AuxSwitchPos::MIDDLE: + // Middle position is unused for now + break; + case RC_Channel::AuxSwitchPos::HIGH: + // Load tuned gains + load_gains(GainType::GAIN_TUNED); + update_gcs(AUTOTUNE_MESSAGE_TESTING); + break; + } + + have_pilot_testing_command = true; +} + +// Possibly save gains, called on disarm +void AC_AutoTune::disarmed(const bool in_autotune_mode) +{ + // True if pilot is testing tuned gains + const bool testing_tuned = have_pilot_testing_command && (loaded_gains == GainType::GAIN_TUNED); + + // True if in autotune mode and no pilot testing commands have been received + const bool tune_complete_no_testing = !have_pilot_testing_command && in_autotune_mode; + + if (tune_complete_no_testing || testing_tuned) { + save_tuning_gains(); + } else { + reset(); + } +} + // initialise position controller bool AC_AutoTune::init_position_controller(void) { @@ -124,21 +169,24 @@ bool AC_AutoTune::init_position_controller(void) void AC_AutoTune::send_step_string() { if (pilot_override) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active"); return; } switch (step) { case WAITING_FOR_LEVEL: - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Leveling"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Leveling"); return; case UPDATE_GAINS: - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Updating Gains"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Updating Gains"); + return; + case ABORT: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Aborting Test"); return; case TESTING: - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Testing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Testing"); return; } - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: unknown step"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: unknown step"); } const char *AC_AutoTune::type_string() const @@ -172,13 +220,13 @@ const char *AC_AutoTune::type_string() const const char *AC_AutoTune::axis_string() const { switch (axis) { - case ROLL: + case AxisType::ROLL: return "Roll"; - case PITCH: + case AxisType::PITCH: return "Pitch"; - case YAW: + case AxisType::YAW: return "Yaw(E)"; - case YAW_D: + case AxisType::YAW_D: return "Yaw(D)"; } return ""; @@ -239,7 +287,7 @@ void AC_AutoTune::run() } if (pilot_override) { if (now - last_pilot_override_warning > 1000) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active"); last_pilot_override_warning = now; } } @@ -270,39 +318,35 @@ void AC_AutoTune::run() // return true if vehicle is close to level bool AC_AutoTune::currently_level() { - float threshold_mul = 1.0; - - uint32_t now_ms = AP_HAL::millis(); - if (now_ms - level_start_time_ms > AUTOTUNE_LEVEL_TIMEOUT_MS) { - // after a long wait we use looser threshold, to allow tuning - // with poor initial gains - threshold_mul *= 2; + // abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually"); + mode = FAILED; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); } - // display warning if vehicle fails to level - if ((now_ms - level_start_time_ms > AUTOTUNE_LEVEL_WARNING_INTERVAL_MS) && - (now_ms - level_fail_warning_time_ms > AUTOTUNE_LEVEL_WARNING_INTERVAL_MS)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: failing to level, please tune manually"); - level_fail_warning_time_ms = now_ms; - } + // slew threshold to ensure sufficient settling time for aircraft unable to obtain small thresholds + // relax threshold if we pass AUTOTUNE_LEVEL_TIMEOUT_MS + const float threshold_mul = constrain_float((float)(now_ms - level_start_time_ms) / (float)AUTOTUNE_LEVEL_TIMEOUT_MS, 0.0, 2.0); - if (fabsf(ahrs_view->roll_sensor - roll_cd) > threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD) { + if (fabsf(ahrs_view->roll_sensor - roll_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) { return false; } - if (fabsf(ahrs_view->pitch_sensor - pitch_cd) > threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD) { + if (fabsf(ahrs_view->pitch_sensor - pitch_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) { return false; } - if (fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)) > threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD) { + if (fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) { return false; } - if ((ToDeg(ahrs_view->get_gyro().x) * 100.0f) > threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD) { + if ((ToDeg(ahrs_view->get_gyro().x) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) { return false; } - if ((ToDeg(ahrs_view->get_gyro().y) * 100.0f) > threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD) { + if ((ToDeg(ahrs_view->get_gyro().y) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) { return false; } - if ((ToDeg(ahrs_view->get_gyro().z) * 100.0f) > threshold_mul*AUTOTUNE_LEVEL_RATE_Y_CD) { + if ((ToDeg(ahrs_view->get_gyro().z) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_Y_CD) { return false; } return true; @@ -344,13 +388,6 @@ void AC_AutoTune::control_attitude() step_start_time_ms = now; step_time_limit_ms = get_testing_step_timeout_ms(); // set gains to their to-be-tested values - twitch_first_iter = true; - test_rate_max = 0.0f; - test_rate_min = 0.0f; - test_angle_max = 0.0f; - test_angle_min = 0.0f; - rotation_rate_filt.reset(0.0f); - rate_max = 0.0f; load_gains(GAIN_TEST); } else { // when waiting for level we use the intra-test gains @@ -359,19 +396,16 @@ void AC_AutoTune::control_attitude() // Initialize test-specific variables switch (axis) { - case ROLL: - abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD; + case AxisType::ROLL: start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f; start_angle = ahrs_view->roll_sensor; break; - case PITCH: - abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD; + case AxisType::PITCH: start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f; start_angle = ahrs_view->pitch_sensor; break; - case YAW: - case YAW_D: - abort_angle = AUTOTUNE_TARGET_ANGLE_YAW_CD; + case AxisType::YAW: + case AxisType::YAW_D: start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f; start_angle = ahrs_view->yaw_sensor; break; @@ -391,22 +425,31 @@ void AC_AutoTune::control_attitude() test_run(axis, direction_sign); // Check for failure causing reverse response - if (lean_angle <= -AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD) { + if (lean_angle <= -angle_lim_neg_rpy_cd()) { step = WAITING_FOR_LEVEL; + positive_direction = twitch_reverse_direction(); + step_start_time_ms = now; + level_start_time_ms = now; } // protect from roll over - float resultant_angle = degrees(acosf(ahrs_view->cos_roll() * ahrs_view->cos_pitch())); - if (resultant_angle > AUTOTUNE_ANGLE_MAX_RLLPIT) { + if (attitude_control->lean_angle_deg() * 100 > angle_lim_max_rp_cd()) { step = WAITING_FOR_LEVEL; + positive_direction = twitch_reverse_direction(); + step_start_time_ms = now; + level_start_time_ms = now; } #if HAL_LOGGING_ENABLED // log this iterations lean angle and rotation rate Log_AutoTuneDetails(); - ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); + attitude_control->Write_Rate(*pos_control); log_pids(); #endif + + if (axis == AxisType::YAW || axis == AxisType::YAW_D) { + desired_yaw_cd = ahrs_view->yaw_sensor; + } break; } @@ -483,37 +526,37 @@ void AC_AutoTune::control_attitude() // advance to the next axis bool complete = false; switch (axis) { - case ROLL: + case AxisType::ROLL: axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL; if (pitch_enabled()) { - axis = PITCH; + axis = AxisType::PITCH; } else if (yaw_enabled()) { - axis = YAW; + axis = AxisType::YAW; } else if (yaw_d_enabled()) { - axis = YAW_D; + axis = AxisType::YAW_D; } else { complete = true; } break; - case PITCH: + case AxisType::PITCH: axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH; if (yaw_enabled()) { - axis = YAW; + axis = AxisType::YAW; } else if (yaw_d_enabled()) { - axis = YAW_D; + axis = AxisType::YAW_D; } else { complete = true; } break; - case YAW: + case AxisType::YAW: axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW; if (yaw_d_enabled()) { - axis = YAW_D; + axis = AxisType::YAW_D; } else { complete = true; } break; - case YAW_D: + case AxisType::YAW_D: axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW_D; complete = true; break; @@ -526,17 +569,20 @@ void AC_AutoTune::control_attitude() update_gcs(AUTOTUNE_MESSAGE_SUCCESS); LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS); AP_Notify::events.autotune_complete = true; + + // Return to original gains for landing + load_gains(GainType::GAIN_ORIGINAL); } else { AP_Notify::events.autotune_next_axis = true; reset_update_gain_variables(); } } } + FALLTHROUGH; - // reverse direction for multicopter twitch test - positive_direction = twitch_reverse_direction(); - - if (axis == YAW || axis == YAW_D) { + case ABORT: + if (axis == AxisType::YAW || axis == AxisType::YAW_D) { + // todo: check to make sure we need this attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false); } @@ -545,8 +591,9 @@ void AC_AutoTune::control_attitude() // reset testing step step = WAITING_FOR_LEVEL; + positive_direction = twitch_reverse_direction(); step_start_time_ms = now; - level_start_time_ms = step_start_time_ms; + level_start_time_ms = now; step_time_limit_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS; break; } @@ -556,15 +603,17 @@ void AC_AutoTune::control_attitude() // called before tuning starts to backup original gains void AC_AutoTune::backup_gains_and_initialise() { + const uint32_t now = AP_HAL::millis(); + // initialise state because this is our first time if (roll_enabled()) { - axis = ROLL; + axis = AxisType::ROLL; } else if (pitch_enabled()) { - axis = PITCH; + axis = AxisType::PITCH; } else if (yaw_enabled()) { - axis = YAW; + axis = AxisType::YAW; } else if (yaw_d_enabled()) { - axis = YAW_D; + axis = AxisType::YAW_D; } // no axes are complete axes_completed = 0; @@ -575,10 +624,10 @@ void AC_AutoTune::backup_gains_and_initialise() // start at the beginning of tune sequence next_tune_type(tune_type, true); - positive_direction = false; step = WAITING_FOR_LEVEL; - step_start_time_ms = AP_HAL::millis(); - level_start_time_ms = step_start_time_ms; + positive_direction = false; + step_start_time_ms = now; + level_start_time_ms = now; step_scaler = 1.0f; desired_yaw_cd = ahrs_view->yaw_sensor; @@ -589,6 +638,12 @@ void AC_AutoTune::backup_gains_and_initialise() */ void AC_AutoTune::load_gains(enum GainType gain_type) { + if (loaded_gains == gain_type) { + // Loaded gains are already of correct type + return; + } + loaded_gains = gain_type; + switch (gain_type) { case GAIN_ORIGINAL: load_orig_gains(); @@ -610,27 +665,29 @@ void AC_AutoTune::update_gcs(uint8_t message_id) const { switch (message_id) { case AUTOTUNE_MESSAGE_STARTED: - gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Started"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Started"); break; case AUTOTUNE_MESSAGE_STOPPED: - gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Stopped"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Stopped"); break; case AUTOTUNE_MESSAGE_SUCCESS: - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Success"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Success"); break; case AUTOTUNE_MESSAGE_FAILED: - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Failed"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Failed"); break; case AUTOTUNE_MESSAGE_TESTING: - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Pilot Testing"); - break; case AUTOTUNE_MESSAGE_SAVED_GAINS: - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Saved gains for %s%s%s%s", + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s gains for %s%s%s%s", + (message_id == AUTOTUNE_MESSAGE_SAVED_GAINS) ? "Saved" : "Pilot Testing", (axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"", (axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"", (axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw(E)":"", (axes_completed&AUTOTUNE_AXIS_BITMASK_YAW_D)?"Yaw(D)":""); break; + case AUTOTUNE_MESSAGE_TESTING_END: + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: original gains restored"); + break; } } @@ -737,7 +794,7 @@ void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, more than 2.5 degrees of attitude on the axis it is tuning */ float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100; - if (axis == PITCH) { + if (axis == AxisType::PITCH) { // for roll and yaw tuning we point along the wind, for pitch // we point across the wind target_yaw_cd += 9000; diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 4c2198c11ac88c..167e4b2a5288d4 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -25,6 +25,7 @@ #include #include #include +#include #include "AC_AutoTune_FreqResp.h" #define AUTOTUNE_AXIS_BITMASK_ROLL 1 @@ -41,13 +42,10 @@ #define AUTOTUNE_MESSAGE_FAILED 3 #define AUTOTUNE_MESSAGE_SAVED_GAINS 4 #define AUTOTUNE_MESSAGE_TESTING 5 +#define AUTOTUNE_MESSAGE_TESTING_END 6 #define AUTOTUNE_ANNOUNCE_INTERVAL_MS 2000 -#define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step -#define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step -#define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step - class AC_AutoTune { public: @@ -57,21 +55,29 @@ class AC_AutoTune // main run loop virtual void run(); - // save gained, called on disarm - virtual void save_tuning_gains() = 0; + // Possibly save gains, called on disarm + void disarmed(const bool in_autotune_mode); // stop tune, reverting gains void stop(); + // Autotune aux function trigger + void do_aux_function(const RC_Channel::AuxSwitchPos ch_flag); + +protected: + + virtual void save_tuning_gains() = 0; + + // reset Autotune so that gains are not saved again and autotune can be run again. void reset() { mode = UNINITIALISED; axes_completed = 0; + have_pilot_testing_command = false; } -protected: // axis that can be tuned - enum AxisType { + enum class AxisType { ROLL = 0, // roll axis is being tuned (either angle or rate) PITCH = 1, // pitch axis is being tuned (either angle or rate) YAW = 2, // yaw axis is being tuned using FLTE (either angle or rate) @@ -201,7 +207,8 @@ class AC_AutoTune enum StepType { WAITING_FOR_LEVEL = 0, // autotune is waiting for vehicle to return to level before beginning the next twitch TESTING = 1, // autotune has begun a test and is watching the resulting vehicle movement - UPDATE_GAINS = 2 // autotune has completed a test and is updating the gains based on the results + UPDATE_GAINS = 2, // autotune has completed a test and is updating the gains based on the results + ABORT = 3 // load normal gains and return to WAITING_FOR_LEVEL }; // mini steps performed while in Tuning mode, Testing step @@ -210,8 +217,8 @@ class AC_AutoTune RD_DOWN = 1, // rate D is being tuned down RP_UP = 2, // rate P is being tuned up RFF_UP = 3, // rate FF is being tuned up - SP_UP = 4, // angle P is being tuned up - SP_DOWN = 5, // angle P is being tuned down + SP_DOWN = 4, // angle P is being tuned down + SP_UP = 5, // angle P is being tuned up MAX_GAINS = 6, // max allowable stable gains are determined TUNE_CHECK = 7, // frequency sweep with tuned gains TUNE_COMPLETE = 8 // Reached end of tuning @@ -240,7 +247,7 @@ class AC_AutoTune GAIN_TEST = 1, GAIN_INTRA_TEST = 2, GAIN_TUNED = 3, - }; + } loaded_gains; void load_gains(enum GainType gain_type); // autotune modes (high level states) @@ -263,32 +270,24 @@ class AC_AutoTune bool positive_direction; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll) StepType step; // see StepType for what steps are performed TuneType tune_type; // see TuneType - bool ignore_next; // true = ignore the next test bool twitch_first_iter; // true on first iteration of a twitch (used to signal we must step the attitude or rate target) uint8_t axes_completed; // bitmask of completed axes - float test_rate_min; // the minimum angular rate achieved during TESTING_RATE step-multi only - float test_rate_max; // the maximum angular rate achieved during TESTING_RATE step-multi only - float test_angle_min; // the minimum angle achieved during TESTING_ANGLE step-multi only - float test_angle_max; // the maximum angle achieved during TESTING_ANGLE step-multi only uint32_t step_start_time_ms; // start time of current tuning step (used for timeout checks) uint32_t step_time_limit_ms; // time limit of current autotune process + uint32_t level_start_time_ms; // start time of waiting for level int8_t counter; // counter for tuning gains - float target_rate; // target rate-multi only - float target_angle; // target angle-multi only - float start_rate; // start rate - parent and multi float start_angle; // start angle - float rate_max; // maximum rate variable - parent and multi + float start_rate; // start rate - parent and multi float test_accel_max; // maximum acceleration variable - float step_scaler; // scaler to reduce maximum target step - parent and multi - float abort_angle; // Angle that test is aborted- parent and multi float desired_yaw_cd; // yaw heading during tune - parent and Tradheli + float step_scaler; // scaler to reduce maximum target step - parent and multi LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second // backup of currently being tuned parameter values - float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel; - float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel; - float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel; + float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_dff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel, orig_roll_rate; + float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_dff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel, orig_pitch_rate; + float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_dff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel, orig_yaw_rate; bool orig_bf_feedforward; // currently being tuned parameter values @@ -303,15 +302,31 @@ class AC_AutoTune float roll_cd, pitch_cd; // heli specific variables - uint8_t freq_cnt; // dwell test iteration counter float start_freq; //start freq for dwell test float stop_freq; //ending freq for dwell test - bool ff_up_first_iter; // true on first iteration of ff up testing private: // return true if we have a good position estimate virtual bool position_ok(); + // methods subclasses must implement to specify max/min test angles: + virtual float target_angle_max_rp_cd() const = 0; + + // methods subclasses must implement to specify max/min test angles: + virtual float target_angle_max_y_cd() const = 0; + + // methods subclasses must implement to specify max/min test angles: + virtual float target_angle_min_rp_cd() const = 0; + + // methods subclasses must implement to specify max/min test angles: + virtual float target_angle_min_y_cd() const = 0; + + // methods subclasses must implement to specify max/min test angles: + virtual float angle_lim_max_rp_cd() const = 0; + + // methods subclasses must implement to specify max/min test angles: + virtual float angle_lim_neg_rpy_cd() const = 0; + // initialise position controller bool init_position_controller(); @@ -329,12 +344,14 @@ class AC_AutoTune // variables uint32_t override_time; // the last time the pilot overrode the controls - uint32_t level_start_time_ms; // start time of waiting for level - uint32_t level_fail_warning_time_ms; // last time level failure warning message was sent to GCS // time in ms of last pilot override warning uint32_t last_pilot_override_warning; + // True if we ever got a pilot testing command of tuned gains. + // If true then disarming will save if the tuned gains are currently active. + bool have_pilot_testing_command; + }; #endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp index 599b2a36cae9bd..c85aa33f6591aa 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp @@ -6,7 +6,7 @@ This library receives time history data (angular rate or angle) during a dwell t #include "AC_AutoTune_FreqResp.h" // Initialize the Frequency Response Object. Must be called before running dwell or frequency sweep tests -void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type) +void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type, uint8_t cycles) { excitation = input_type; response = response_type; @@ -25,6 +25,7 @@ void AC_AutoTune_FreqResp::init(InputType input_type, ResponseType response_type max_accel = 0.0f; max_meas_rate = 0.0f; max_command = 0.0f; + dwell_cycles = cycles; meas_peak_info_buffer.clear(); tgt_peak_info_buffer.clear(); cycle_complete = false; @@ -71,7 +72,7 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp } // cycles are complete! determine gain and phase and exit - if (max_meas_cnt > AUTOTUNE_DWELL_CYCLES + 1 && max_target_cnt > AUTOTUNE_DWELL_CYCLES + 1 && excitation == DWELL) { + if (max_meas_cnt > dwell_cycles + 1 && max_target_cnt > dwell_cycles + 1 && excitation == DWELL) { float delta_time = 0.0f; float sum_gain = 0.0f; uint8_t cnt = 0; @@ -81,14 +82,13 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp float tgt_ampl = 0.0f; uint32_t meas_time = 0; uint32_t tgt_time = 0; - for (uint8_t i = 0; i < AUTOTUNE_DWELL_CYCLES; i++) { + for (uint8_t i = 0; i < dwell_cycles; i++) { meas_cnt=0; tgt_cnt=0; pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time); pull_from_tgt_buffer(tgt_cnt, tgt_ampl, tgt_time); push_to_meas_buffer(0, 0.0f, 0); push_to_tgt_buffer(0, 0.0f, 0); - // gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: tgt_cnt=%f meas_cnt=%f", (double)(tgt_cnt), (double)(meas_cnt)); if (meas_cnt == tgt_cnt && meas_cnt != 0) { if (tgt_ampl > 0.0f) { @@ -106,8 +106,7 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp } else if (meas_cnt < tgt_cnt) { pull_from_meas_buffer(meas_cnt, meas_ampl, meas_time); push_to_meas_buffer(0, 0.0f, 0); - } - + } } if (gcnt > 0) { curr_test_gain = sum_gain / gcnt; @@ -135,7 +134,6 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp curr_test_freq = tgt_freq; cycle_complete = true; - // gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: cycles completed"); return; } @@ -155,7 +153,9 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp sweep_tgt.count_m1 = min_target_cnt - 1; sweep_tgt.amplitude_m1 = temp_tgt_ampl; temp_tgt_ampl = temp_max_target - temp_min_target; - push_to_tgt_buffer(min_target_cnt,temp_tgt_ampl,temp_max_tgt_time); + if (excitation == DWELL) { + push_to_tgt_buffer(min_target_cnt,temp_tgt_ampl,temp_max_tgt_time); + } } } else if (((response == ANGLE && !is_positive(prev_target) && is_positive(target_rate)) @@ -184,8 +184,9 @@ void AC_AutoTune_FreqResp::update(float command, float tgt_resp, float meas_resp sweep_meas.count_m1 = min_meas_cnt - 1; sweep_meas.amplitude_m1 = temp_meas_ampl; temp_meas_ampl = temp_max_meas - temp_min_meas; - push_to_meas_buffer(min_meas_cnt,temp_meas_ampl,temp_max_meas_time); - + if (excitation == DWELL) { + push_to_meas_buffer(min_meas_cnt,temp_meas_ampl,temp_max_meas_time); + } if (excitation == SWEEP) { float tgt_period = 0.001f * (temp_max_tgt_time - sweep_tgt.max_time_m1); if (!is_zero(tgt_period)) { @@ -282,7 +283,6 @@ void AC_AutoTune_FreqResp::push_to_tgt_buffer(uint16_t count, float amplitude, u sample.amplitude = amplitude; sample.time_ms = time_ms; tgt_peak_info_buffer.push(sample); - } // pull target peak info from buffer @@ -297,3 +297,4 @@ void AC_AutoTune_FreqResp::pull_from_tgt_buffer(uint16_t &count, float &litud amplitude = sample.amplitude; time_ms = sample.time_ms; } + diff --git a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h index 95e18567659ac7..ada80e103ad510 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h +++ b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h @@ -6,8 +6,6 @@ #include -#define AUTOTUNE_DWELL_CYCLES 6 - class AC_AutoTune_FreqResp { public: // Constructor @@ -29,7 +27,7 @@ class AC_AutoTune_FreqResp { // Initialize the Frequency Response Object. // Must be called before running dwell or frequency sweep tests - void init(InputType input_type, ResponseType response_type); + void init(InputType input_type, ResponseType response_type, uint8_t cycles); // Determines the gain and phase based on angle response for a dwell or sweep void update(float command, float tgt_resp, float meas_resp, float tgt_freq); @@ -137,6 +135,9 @@ class AC_AutoTune_FreqResp { // flag indicating when one oscillation cycle is complete bool cycle_complete = false; + // number of dwell cycles to complete for dwell excitation + uint8_t dwell_cycles; + // current test frequency, gain, and phase float curr_test_freq; float curr_test_gain; @@ -179,10 +180,10 @@ class AC_AutoTune_FreqResp { }; // Buffer object for measured peak data - ObjectBuffer meas_peak_info_buffer{AUTOTUNE_DWELL_CYCLES}; + ObjectBuffer meas_peak_info_buffer{12}; // Buffer object for target peak data - ObjectBuffer tgt_peak_info_buffer{AUTOTUNE_DWELL_CYCLES}; + ObjectBuffer tgt_peak_info_buffer{12}; // Push data into measured peak data buffer object void push_to_meas_buffer(uint16_t count, float amplitude, uint32_t time_ms); diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index 0f972a48938076..27e9406039b45e 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -60,6 +60,14 @@ #define AUTOTUNE_SEQ_BITMASK_MAX_GAIN 8 #define AUTOTUNE_SEQ_BITMASK_TUNE_CHECK 16 +// angle limits preserved from previous behaviour as Multi changed: +#define AUTOTUNE_ANGLE_TARGET_MAX_RP_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_ANGLE_TARGET_MIN_RP_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_ANGLE_TARGET_MAX_Y_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_ANGLE_TARGET_MIN_Y_CD 500 // target angle during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_ANGLE_MAX_RP_CD 3000 // maximum allowable angle in degrees during testing +#define AUTOTUNE_ANGLE_NEG_RPY_CD 1000 // maximum allowable angle in degrees during testing + const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = { // @Param: AXES @@ -104,6 +112,20 @@ const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = { // @User: Standard AP_GROUPINFO("VELXY_P", 6, AC_AutoTune_Heli, vel_hold_gain, 0.1f), + // @Param: ACC_MAX + // @DisplayName: AutoTune maximum allowable angular acceleration + // @Description: maximum angular acceleration in deg/s/s allowed during autotune maneuvers + // @Range: 1 4000 + // @User: Standard + AP_GROUPINFO("ACC_MAX", 7, AC_AutoTune_Heli, accel_max, 0.0f), + + // @Param: RAT_MAX + // @DisplayName: Autotune maximum allowable angular rate + // @Description: maximum angular rate in deg/s allowed during autotune maneuvers + // @Range: 0 500 + // @User: Standard + AP_GROUPINFO("RAT_MAX", 8, AC_AutoTune_Heli, rate_max, 0.0f), + AP_GROUPEND }; @@ -117,116 +139,128 @@ AC_AutoTune_Heli::AC_AutoTune_Heli() // initialize tests for each tune type void AC_AutoTune_Heli::test_init() { + AC_AutoTune_FreqResp::ResponseType resp_type = AC_AutoTune_FreqResp::ResponseType::RATE; + FreqRespCalcType calc_type = RATE; + FreqRespInput freq_resp_input = TARGET; + float freq_resp_amplitude = 5.0f; // amplitude in deg + float filter_freq = 10.0f; switch (tune_type) { case RFF_UP: - rate_ff_test_init(); - step_time_limit_ms = 10000; + if (!is_positive(next_test_freq)) { + start_freq = 0.25f * M_2PI; + } else { + start_freq = next_test_freq; + } + stop_freq = start_freq; + filter_freq = start_freq; + + attitude_control->bf_feedforward(false); + + // variables needed to initialize frequency response object and test method + resp_type = AC_AutoTune_FreqResp::ResponseType::RATE; + calc_type = RATE; + freq_resp_input = TARGET; + pre_calc_cycles = 1.0f; + num_dwell_cycles = 3; break; case MAX_GAINS: - case RP_UP: - case RD_UP: - // initialize start frequency - if (is_zero(start_freq)) { - if (tune_type == RP_UP) { - // continue using frequency where testing left off or RD_UP completed - 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)) { - freq_cnt = 12; - 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; - - // 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)) { - 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; - if (tune_type == MAX_GAINS) { - reset_maxgains_update_gain_variables(); - } - } else { - start_freq = min_sweep_freq; - stop_freq = max_sweep_freq; - } - } - } - if (!is_equal(start_freq,stop_freq)) { - // initialize determine_gain function whenever test is initialized - freqresp.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::RATE); - dwell_test_init(start_freq, stop_freq, stop_freq, RATE); + // initialize start frequency for sweep + if (!is_positive(next_test_freq)) { + start_freq = min_sweep_freq; + stop_freq = max_sweep_freq; + sweep_complete = true; } else { - // initialize determine_gain function whenever test is initialized - 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. - step_time_limit_ms = (uint32_t)(4000 + (float)(AUTOTUNE_DWELL_CYCLES + 2) * 1000.0f * M_2PI / start_freq); + start_freq = next_test_freq; + stop_freq = start_freq; + test_accel_max = 0.0f; } + filter_freq = start_freq; + + attitude_control->bf_feedforward(false); + + // variables needed to initialize frequency response object and test method + resp_type = AC_AutoTune_FreqResp::ResponseType::RATE; + calc_type = RATE; + freq_resp_input = MOTOR; + pre_calc_cycles = 6.25f; + num_dwell_cycles = 6; break; - case SP_UP: + case RP_UP: + case RD_UP: // initialize start frequency - if (is_zero(start_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_accel_max = 0.0f; + if (!is_positive(next_test_freq)) { + // continue using frequency where testing left off with RD_UP completed + if (curr_data.phase > 150.0f && curr_data.phase < 180.0f && tune_type == RP_UP) { + start_freq = curr_data.freq; + // start with freq found for sweep where phase was 180 deg + } else if (!is_zero(sweep_tgt.ph180.freq)) { + start_freq = sweep_tgt.ph180.freq; + // otherwise start at min freq to step up in dwell frequency until phase > 160 deg } else { start_freq = min_sweep_freq; - stop_freq = max_sweep_freq; } + } else { + start_freq = next_test_freq; } + stop_freq = start_freq; + filter_freq = start_freq; + attitude_control->bf_feedforward(false); - if (!is_equal(start_freq,stop_freq)) { - // initialize determine gain function - freqresp.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::ANGLE); - dwell_test_init(start_freq, stop_freq, stop_freq, DRB); + // variables needed to initialize frequency response object and test method + resp_type = AC_AutoTune_FreqResp::ResponseType::RATE; + calc_type = RATE; + freq_resp_input = TARGET; + pre_calc_cycles = 6.25f; + num_dwell_cycles = 6; + break; + case SP_UP: + // initialize start frequency for sweep + if (!is_positive(next_test_freq)) { + start_freq = min_sweep_freq; + stop_freq = max_sweep_freq; + sweep_complete = true; } else { - // initialize determine gain function - freqresp.init(AC_AutoTune_FreqResp::InputType::DWELL, AC_AutoTune_FreqResp::ResponseType::ANGLE); - dwell_test_init(start_freq, stop_freq, start_freq, DRB); + start_freq = next_test_freq; + stop_freq = start_freq; + test_accel_max = 0.0f; } + filter_freq = start_freq; + attitude_control->bf_feedforward(false); - // TODO add time limit for sweep test - if (!is_zero(start_freq)) { - // 1 seconds is added for a little buffer. Then the time to conduct the dwells is added to it. - step_time_limit_ms = (uint32_t)(2000 + (float)(AUTOTUNE_DWELL_CYCLES + 7) * 1000.0f * M_2PI / start_freq); - } + // variables needed to initialize frequency response object and test method + resp_type = AC_AutoTune_FreqResp::ResponseType::ANGLE; + calc_type = DRB; + freq_resp_input = TARGET; + pre_calc_cycles = 6.25f; + num_dwell_cycles = 6; break; case TUNE_CHECK: // initialize start frequency - if (is_zero(start_freq)) { - start_freq = min_sweep_freq; - stop_freq = max_sweep_freq; - } - // initialize determine gain function - freqresp.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::ANGLE); - dwell_test_init(start_freq, stop_freq, stop_freq, ANGLE); - // TODO add time limit for sweep test - if (!is_zero(start_freq)) { - // 1 seconds is added for a little buffer. Then the time to conduct the dwells is added to it. - step_time_limit_ms = (uint32_t)(2000 + (float)(AUTOTUNE_DWELL_CYCLES + 7) * 1000.0f * M_2PI / start_freq); - } + start_freq = min_sweep_freq; + stop_freq = max_sweep_freq; + test_accel_max = 0.0f; + filter_freq = start_freq; + + // variables needed to initialize frequency response object and test method + resp_type = AC_AutoTune_FreqResp::ResponseType::ANGLE; + calc_type = ANGLE; + freq_resp_input = TARGET; break; default: break; } + if (!is_equal(start_freq,stop_freq)) { + input_type = AC_AutoTune_FreqResp::InputType::SWEEP; + } else { + input_type = AC_AutoTune_FreqResp::InputType::DWELL; + } + + + // initialize dwell test method + dwell_test_init(start_freq, stop_freq, freq_resp_amplitude, filter_freq, freq_resp_input, calc_type, resp_type, input_type); + start_angles = Vector3f(roll_cd, pitch_cd, desired_yaw_cd); // heli specific } @@ -248,12 +282,12 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true); 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"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed"); mode = FAILED; 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"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Exceeded frequency range"); mode = FAILED; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); update_gcs(AUTOTUNE_MESSAGE_FAILED); @@ -264,27 +298,8 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) return; } - switch (tune_type) { - case RFF_UP: - rate_ff_test_run(AUTOTUNE_HELI_TARGET_ANGLE_RLLPIT_CD, AUTOTUNE_HELI_TARGET_RATE_RLLPIT_CDS, 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], RATE); - break; - case MAX_GAINS: - dwell_test_run(0, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], RATE); - break; - case SP_UP: - dwell_test_run(1, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], DRB); - break; - case TUNE_CHECK: - dwell_test_run(1, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], ANGLE); - break; - default: - step = UPDATE_GAINS; - break; - } + dwell_test_run(curr_data); + } // heli specific gcs announcements @@ -295,20 +310,21 @@ void AC_AutoTune_Heli::do_gcs_announcements() return; } - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: %s %s", axis_string(), type_string()); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: %s %s", axis_string(), type_string()); send_step_string(); switch (tune_type) { + case RFF_UP: case RD_UP: case RP_UP: case MAX_GAINS: case SP_UP: case TUNE_CHECK: if (is_equal(start_freq,stop_freq)) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Dwell"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Dwell"); } else { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Sweep"); + 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; @@ -328,22 +344,22 @@ void AC_AutoTune_Heli::do_post_test_gcs_announcements() { float tune_accel = 0.0f; switch (axis) { - case ROLL: + case AxisType::ROLL: tune_rp = tune_roll_rp; tune_rd = tune_roll_rd; tune_rff = tune_roll_rff; tune_sp = tune_roll_sp; tune_accel = tune_roll_accel; break; - case PITCH: + case AxisType::PITCH: tune_rp = tune_pitch_rp; tune_rd = tune_pitch_rd; tune_rff = tune_pitch_rff; tune_sp = tune_pitch_sp; tune_accel = tune_pitch_accel; break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_rp = tune_yaw_rp; tune_rd = tune_yaw_rd; tune_rff = tune_yaw_rff; @@ -355,27 +371,26 @@ void AC_AutoTune_Heli::do_post_test_gcs_announcements() { if (step == UPDATE_GAINS) { switch (tune_type) { case RFF_UP: - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: target=%f rotation=%f command=%f", (double)(test_tgt_rate_filt*57.3f), (double)(test_rate_filt*57.3f), (double)(test_command_filt)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ff=%f", (double)tune_rff); - break; case RP_UP: case RD_UP: case SP_UP: case MAX_GAINS: 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", (double)(test_phase[freq_cnt])); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(curr_data.freq), (double)(curr_data.gain)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f", (double)(curr_data.phase)); if (tune_type == RP_UP) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rate_p=%f", (double)(tune_rp)); + 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)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: rate_d=%f", (double)(tune_rd)); + } else if (tune_type == RFF_UP) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: rate_ff=%f", (double)(tune_rff)); } 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)); + 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_tgt.maxgain.freq), (double)(sweep_tgt.maxgain.gain)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep_tgt.ph180.freq), (double)(sweep_tgt.ph180.gain)); } break; default: @@ -391,7 +406,7 @@ void AC_AutoTune_Heli::backup_gains_and_initialise() AC_AutoTune::backup_gains_and_initialise(); // initializes dwell test sequence for rate_p_up and rate_d_up tests for tradheli - freq_cnt = 0; + next_test_freq = 0.0f; start_freq = 0.0f; stop_freq = 0.0f; @@ -406,6 +421,7 @@ void AC_AutoTune_Heli::backup_gains_and_initialise() orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); orig_roll_accel = attitude_control->get_accel_roll_max_cdss(); + orig_roll_rate = attitude_control->get_ang_vel_roll_max_degs(); tune_roll_rp = attitude_control->get_rate_roll_pid().kP(); tune_roll_rd = attitude_control->get_rate_roll_pid().kD(); tune_roll_rff = attitude_control->get_rate_roll_pid().ff(); @@ -420,6 +436,7 @@ void AC_AutoTune_Heli::backup_gains_and_initialise() orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss(); + orig_pitch_rate = attitude_control->get_ang_vel_pitch_max_degs(); tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP(); tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); tune_pitch_rff = attitude_control->get_rate_pitch_pid().ff(); @@ -435,6 +452,7 @@ void AC_AutoTune_Heli::backup_gains_and_initialise() orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz(); orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss(); orig_yaw_sp = attitude_control->get_angle_yaw_p().kP(); + orig_yaw_rate = attitude_control->get_ang_vel_yaw_max_degs(); tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP(); tune_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); tune_yaw_rff = attitude_control->get_rate_yaw_pid().ff(); @@ -451,13 +469,13 @@ void AC_AutoTune_Heli::load_orig_gains() { attitude_control->bf_feedforward(orig_bf_feedforward); if (roll_enabled()) { - 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); + load_gain_set(AxisType::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, orig_roll_rate); } if (pitch_enabled()) { - 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); + load_gain_set(AxisType::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, orig_pitch_rate); } if (yaw_enabled()) { - 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); + load_gain_set(AxisType::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, orig_yaw_rate); } } @@ -469,16 +487,14 @@ void AC_AutoTune_Heli::load_tuned_gains() attitude_control->set_accel_roll_max_cdss(0.0f); attitude_control->set_accel_pitch_max_cdss(0.0f); } - if (roll_enabled()) { - 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 ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled()) { + load_gain_set(AxisType::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, orig_roll_rate); } - if (pitch_enabled()) { - 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 ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled()) { + load_gain_set(AxisType::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, orig_pitch_rate); } - if (yaw_enabled()) { - if (!is_zero(tune_yaw_rp)) { - 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); - } + if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) { + load_gain_set(AxisType::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, orig_yaw_rate); } } @@ -490,13 +506,13 @@ void AC_AutoTune_Heli::load_intra_test_gains() // sanity check the gains attitude_control->bf_feedforward(true); if (roll_enabled()) { - 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); + load_gain_set(AxisType::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, orig_roll_rate); } if (pitch_enabled()) { - 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); + load_gain_set(AxisType::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, orig_pitch_rate); } if (yaw_enabled()) { - 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); + load_gain_set(AxisType::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, orig_yaw_rate); } } @@ -504,9 +520,18 @@ 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; + float rate_p, rate_i, rate_d, rate_test_max, accel_test_max; switch (axis) { - case ROLL: + case AxisType::ROLL: + + if (tune_type == TUNE_CHECK) { + rate_test_max = orig_roll_rate; + accel_test_max = tune_roll_accel; + } else { + // have attitude controller use accel and rate limit parameter + rate_test_max = rate_max; + accel_test_max = accel_max; + } if (tune_type == SP_UP || tune_type == TUNE_CHECK) { rate_i = tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL; } else { @@ -520,9 +545,17 @@ void AC_AutoTune_Heli::load_test_gains() rate_p = tune_roll_rp; rate_d = tune_roll_rd; } - 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); + load_gain_set(AxisType::ROLL, rate_p, rate_i, rate_d, tune_roll_rff, tune_roll_sp, accel_test_max, orig_roll_fltt, 0.0f, 0.0f, rate_test_max); break; - case PITCH: + case AxisType::PITCH: + if (tune_type == TUNE_CHECK) { + rate_test_max = orig_pitch_rate; + accel_test_max = tune_pitch_accel; + } else { + // have attitude controller use accel and rate limit parameter + rate_test_max = rate_max; + accel_test_max = accel_max; + } if (tune_type == SP_UP || tune_type == TUNE_CHECK) { rate_i = tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL; } else { @@ -536,56 +569,67 @@ void AC_AutoTune_Heli::load_test_gains() rate_p = tune_pitch_rp; rate_d = tune_pitch_rd; } - 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); + load_gain_set(AxisType::PITCH, rate_p, rate_i, rate_d, tune_pitch_rff, tune_pitch_sp, accel_test_max, orig_pitch_fltt, 0.0f, 0.0f, rate_test_max); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: + if (tune_type == TUNE_CHECK) { + rate_test_max = orig_yaw_rate; + accel_test_max = tune_yaw_accel; + } else { + // have attitude controller use accel and rate limit parameter + rate_test_max = rate_max; + accel_test_max = accel_max; + } if (tune_type == SP_UP || tune_type == TUNE_CHECK) { rate_i = tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL; } else { // freeze integrator to hold trim by making i term small during rate controller tuning rate_i = 0.01f * orig_yaw_ri; } - load_gain_set(YAW, tune_yaw_rp, rate_i, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, tune_yaw_rLPF, 0.0f); + load_gain_set(AxisType::YAW, tune_yaw_rp, rate_i, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, accel_test_max, orig_yaw_fltt, tune_yaw_rLPF, 0.0f, rate_test_max); 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) +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, float max_rate) { 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); + case AxisType::ROLL: + attitude_control->get_rate_roll_pid().set_kP(rate_p); + attitude_control->get_rate_roll_pid().set_kI(rate_i); + attitude_control->get_rate_roll_pid().set_kD(rate_d); + attitude_control->get_rate_roll_pid().set_ff(rate_ff); + attitude_control->get_rate_roll_pid().set_filt_T_hz(rate_fltt); + attitude_control->get_rate_roll_pid().set_slew_limit(smax); + attitude_control->get_angle_roll_p().set_kP(angle_p); attitude_control->set_accel_roll_max_cdss(max_accel); + attitude_control->set_ang_vel_roll_max_degs(max_rate); 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); + case AxisType::PITCH: + attitude_control->get_rate_pitch_pid().set_kP(rate_p); + attitude_control->get_rate_pitch_pid().set_kI(rate_i); + attitude_control->get_rate_pitch_pid().set_kD(rate_d); + attitude_control->get_rate_pitch_pid().set_ff(rate_ff); + attitude_control->get_rate_pitch_pid().set_filt_T_hz(rate_fltt); + attitude_control->get_rate_pitch_pid().set_slew_limit(smax); + attitude_control->get_angle_pitch_p().set_kP(angle_p); attitude_control->set_accel_pitch_max_cdss(max_accel); + attitude_control->set_ang_vel_pitch_max_degs(max_rate); break; - case YAW: - case YAW_D: - 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); + case AxisType::YAW: + case AxisType::YAW_D: + attitude_control->get_rate_yaw_pid().set_kP(rate_p); + attitude_control->get_rate_yaw_pid().set_kI(rate_i); + attitude_control->get_rate_yaw_pid().set_kD(rate_d); + attitude_control->get_rate_yaw_pid().set_ff(rate_ff); + attitude_control->get_rate_yaw_pid().set_filt_T_hz(rate_fltt); + attitude_control->get_rate_yaw_pid().set_slew_limit(smax); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(rate_flte); + attitude_control->get_angle_yaw_p().set_kP(angle_p); attitude_control->set_accel_yaw_max_cdss(max_accel); + attitude_control->set_ang_vel_yaw_max_degs(max_rate); break; } } @@ -607,7 +651,7 @@ void AC_AutoTune_Heli::save_tuning_gains() // sanity check the rate P values if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled()) { - 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); + load_gain_set(AxisType::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, orig_roll_rate); // save rate roll gains attitude_control->get_rate_roll_pid().save_gains(); @@ -624,7 +668,7 @@ void AC_AutoTune_Heli::save_tuning_gains() } if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled()) { - 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); + load_gain_set(AxisType::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, orig_pitch_rate); // save rate pitch gains attitude_control->get_rate_pitch_pid().save_gains(); @@ -641,7 +685,7 @@ void AC_AutoTune_Heli::save_tuning_gains() } if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) { - 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); + load_gain_set(AxisType::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, orig_yaw_rate); // save rate yaw gains attitude_control->get_rate_yaw_pid().save_gains(); @@ -669,14 +713,14 @@ void AC_AutoTune_Heli::save_tuning_gains() void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const { switch (test_axis) { - case ROLL: + case AxisType::ROLL: report_axis_gains("Roll", tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel); break; - case PITCH: + case AxisType::PITCH: report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: report_axis_gains("Yaw", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel); break; } @@ -685,210 +729,38 @@ void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const // report gain formatting helper void AC_AutoTune_Heli::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const { - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.4f, I:%0.4f, D:%0.5f, FF:%0.4f",axis_string,rate_P,rate_I,rate_D,rate_ff); - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.2f, Max Accel:%0.0f",axis_string,angle_P,max_accel); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.4f, I:%0.4f, D:%0.5f, FF:%0.4f",axis_string,rate_P,rate_I,rate_D,rate_ff); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.2f, Max Accel:%0.0f",axis_string,angle_P,max_accel); } - -void AC_AutoTune_Heli::rate_ff_test_init() +void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float amplitude, float filt_freq, FreqRespInput freq_resp_input, FreqRespCalcType calc_type, AC_AutoTune_FreqResp::ResponseType resp_type, AC_AutoTune_FreqResp::InputType waveform_input_type) { - ff_test_phase = 0; - rotation_rate_filt.reset(0); - rotation_rate_filt.set_cutoff_frequency(5.0f); - command_filt.reset(0); - command_filt.set_cutoff_frequency(5.0f); - target_rate_filt.reset(0); - target_rate_filt.set_cutoff_frequency(5.0f); - test_command_filt = 0.0f; - test_rate_filt = 0.0f; - test_tgt_rate_filt = 0.0f; - filt_target_rate = 0.0f; - settle_time = 200; - phase_out_time = 500; - rate_request_cds.reset(0); - rate_request_cds.set_cutoff_frequency(1.0f); - angle_request_cd.reset(0); - angle_request_cd.set_cutoff_frequency(1.0f); -} - -void AC_AutoTune_Heli::rate_ff_test_run(float max_angle_cd, float target_rate_cds, float dir_sign) -{ - float gyro_reading = 0.0f; - float command_reading =0.0f; - float tgt_rate_reading = 0.0f; - const uint32_t now = AP_HAL::millis(); - - target_rate_cds = dir_sign * target_rate_cds; - - 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) { - settle_time--; - trim_command_reading = motors->get_roll(); - rate_request_cds.reset(gyro_reading); - } else if (((ahrs_view->roll_sensor <= max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->roll_sensor >= -max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 0) { - rate_request_cds.apply(target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(rate_request_cds.get(), 0.0f, 0.0f); - } else if (((ahrs_view->roll_sensor > max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->roll_sensor < -max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 0) { - ff_test_phase = 1; - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(rate_request_cds.get(), 0.0f, 0.0f); - attitude_control->rate_bf_roll_target(rate_request_cds.get()); - } else if (((ahrs_view->roll_sensor >= -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->roll_sensor <= max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(rate_request_cds.get(), 0.0f, 0.0f); - attitude_control->rate_bf_roll_target(rate_request_cds.get()); - } else if (((ahrs_view->roll_sensor < -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->roll_sensor > max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - ff_test_phase = 2; - attitude_control->reset_target_and_rate(false); - angle_request_cd.reset(ahrs_view->roll_sensor); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(angle_request_cd.get(), start_angles.y, 0.0f); - } else if (ff_test_phase == 2 ) { - angle_request_cd.apply(start_angles.x, AP::scheduler().get_loop_period_s()); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(angle_request_cd.get(), start_angles.y, 0.0f); - phase_out_time--; - } - 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) { - settle_time--; - trim_command_reading = motors->get_pitch(); - rate_request_cds.reset(gyro_reading); - } else if (((ahrs_view->pitch_sensor <= max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->pitch_sensor >= -max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 0) { - rate_request_cds.apply(target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, rate_request_cds.get(), 0.0f); - } else if (((ahrs_view->pitch_sensor > max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->pitch_sensor < -max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 0) { - ff_test_phase = 1; - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, rate_request_cds.get(), 0.0f); - attitude_control->rate_bf_pitch_target(rate_request_cds.get()); - } else if (((ahrs_view->pitch_sensor >= -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->pitch_sensor <= max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, rate_request_cds.get(), 0.0f); - attitude_control->rate_bf_pitch_target(rate_request_cds.get()); - } else if (((ahrs_view->pitch_sensor < -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->pitch_sensor > max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - ff_test_phase = 2; - attitude_control->reset_target_and_rate(false); - angle_request_cd.reset(ahrs_view->pitch_sensor); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(start_angles.x, angle_request_cd.get(), 0.0f); - } else if (ff_test_phase == 2 ) { - angle_request_cd.apply(start_angles.y, AP::scheduler().get_loop_period_s()); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(start_angles.x, angle_request_cd.get(), 0.0f); - phase_out_time--; - } - break; - case YAW: - case YAW_D: - 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) { - settle_time--; - trim_command_reading = motors->get_yaw(); - trim_heading = ahrs_view->yaw_sensor; - rate_request_cds.reset(gyro_reading); - } else if (((wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) <= 2.0f * max_angle_cd && is_positive(dir_sign)) - || (wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) >= -2.0f * max_angle_cd && !is_positive(dir_sign))) - && ff_test_phase == 0) { - rate_request_cds.apply(target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, rate_request_cds.get()); - } else if (((wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) > 2.0f * max_angle_cd && is_positive(dir_sign)) - || (wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) < -2.0f * max_angle_cd && !is_positive(dir_sign))) - && ff_test_phase == 0) { - ff_test_phase = 1; - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, rate_request_cds.get()); - attitude_control->rate_bf_yaw_target(rate_request_cds.get()); - } else if (((wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) >= -2.0f * max_angle_cd && is_positive(dir_sign)) - || (wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) <= 2.0f * max_angle_cd && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - rate_request_cds.apply(-target_rate_cds, AP::scheduler().get_loop_period_s()); - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, rate_request_cds.get()); - attitude_control->rate_bf_yaw_target(rate_request_cds.get()); - } else if (((wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) < -2.0f * max_angle_cd && is_positive(dir_sign)) - || (wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) > 2.0f * max_angle_cd && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - ff_test_phase = 2; - attitude_control->reset_yaw_target_and_rate(false); - angle_request_cd.reset(wrap_180_cd(ahrs_view->yaw_sensor - trim_heading)); - attitude_control->input_euler_angle_roll_pitch_yaw(start_angles.x, start_angles.y, angle_request_cd.get(), false); - } else if (ff_test_phase == 2 ) { - angle_request_cd.apply(0.0f, AP::scheduler().get_loop_period_s()); - attitude_control->input_euler_angle_roll_pitch_yaw(start_angles.x, start_angles.y, wrap_360_cd(trim_heading + angle_request_cd.get()), false); - } - break; - } - - rotation_rate = rotation_rate_filt.apply(gyro_reading, - AP::scheduler().get_loop_period_s()); - command_out = command_filt.apply((command_reading - trim_command_reading), - AP::scheduler().get_loop_period_s()); - filt_target_rate = target_rate_filt.apply(tgt_rate_reading, - AP::scheduler().get_loop_period_s()); - - // record steady state rate and motor command - switch (axis) { - case ROLL: - if (((ahrs_view->roll_sensor >= -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->roll_sensor <= max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - test_rate_filt = rotation_rate; - test_command_filt = command_out; - test_tgt_rate_filt = filt_target_rate; - } - break; - case PITCH: - if (((ahrs_view->pitch_sensor >= -max_angle_cd + start_angle && is_positive(dir_sign)) - || (ahrs_view->pitch_sensor <= max_angle_cd + start_angle && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - test_rate_filt = rotation_rate; - test_command_filt = command_out; - test_tgt_rate_filt = filt_target_rate; - } - break; - case YAW: - case YAW_D: - if (((wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) >= -2.0f * max_angle_cd && is_positive(dir_sign)) - || (wrap_180_cd(ahrs_view->yaw_sensor - trim_heading) <= 2.0f * max_angle_cd && !is_positive(dir_sign))) - && ff_test_phase == 1 ) { - test_rate_filt = rotation_rate; - test_command_filt = command_out; - test_tgt_rate_filt = filt_target_rate; + test_input_type = waveform_input_type; + test_freq_resp_input = freq_resp_input; + test_calc_type = calc_type; + test_start_freq = start_frq; + //target attitude magnitude + tgt_attitude = radians(amplitude); + + // initialize frequency response object + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + step_time_limit_ms = sweep_time_ms + 500; + reset_sweep_variables(); + curr_test.gain = 0.0f; + curr_test.phase = 0.0f; + chirp_input.init(0.001f * sweep_time_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * sweep_time_ms, 0.0f); + } else { + if (!is_zero(start_frq)) { + // time limit set by adding the pre calc cycles with the dwell cycles. 500 ms added to account for settling with buffer. + step_time_limit_ms = (uint32_t) (2000 + ((float)num_dwell_cycles + pre_calc_cycles + 2.0f) * 1000.0f * M_2PI / start_frq); } - break; - } - if (now - step_start_time_ms >= step_time_limit_ms || (ff_test_phase == 2 && phase_out_time == 0)) { - // we have passed the maximum stop time - step = UPDATE_GAINS; + chirp_input.init(0.001f * step_time_limit_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * step_time_limit_ms, 0.0f); } -} - -void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float filt_freq, DwellType dwell_type) -{ + freqresp_tgt.init(test_input_type, resp_type, num_dwell_cycles); + freqresp_mtr.init(test_input_type, resp_type, num_dwell_cycles); + dwell_start_time_ms = 0.0f; settle_time = 200; @@ -904,82 +776,33 @@ void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float fi filt_target_rate = 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_att_fdbk_from_velxy_cd.set_cutoff_frequency(0.2f * start_frq); - - 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: - case YAW_D: - 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; - } + filt_command_reading.set_cutoff_frequency(0.2f * filt_freq); + filt_gyro_reading.set_cutoff_frequency(0.05f * filt_freq); + filt_tgt_rate_reading.set_cutoff_frequency(0.05f * filt_freq); + filt_att_fdbk_from_velxy_cd.set_cutoff_frequency(0.2f * filt_freq); - 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); + curr_test_mtr = {}; + curr_test_tgt = {}; + cycle_complete_tgt = false; + cycle_complete_mtr = false; + sweep_complete = false; } -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) +void AC_AutoTune_Heli::dwell_test_run(sweep_info &test_data) { float gyro_reading = 0.0f; float command_reading = 0.0f; float tgt_rate_reading = 0.0f; - float tgt_attitude; const uint32_t now = AP_HAL::millis(); float target_angle_cd = 0.0f; - float target_rate_cds = 0.0f; - float dwell_freq = start_frq; - float target_rate_mag_cds; - const float att_hold_gain = 4.5f; + float dwell_freq = test_start_freq; float cycle_time_ms = 0; if (!is_zero(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); - } - // body frame calculation of velocity Vector3f velocity_ned, velocity_bf; if (ahrs_view->get_velocity_NED(velocity_ned)) { @@ -987,149 +810,72 @@ void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, velocity_bf.y = -velocity_ned.x * ahrs_view->sin_yaw() + velocity_ned.y * ahrs_view->cos_yaw(); } - Vector3f attitude_cd = Vector3f((float)ahrs_view->roll_sensor, (float)ahrs_view->pitch_sensor, (float)ahrs_view->yaw_sensor); if (settle_time == 0) { - 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 { - target_angle_cd = -chirp_input.update((now - dwell_start_time_ms) * 0.001, tgt_attitude * 5730.0f); - } + target_angle_cd = -chirp_input.update((now - dwell_start_time_ms) * 0.001, degrees(tgt_attitude) * 100.0f); + dwell_freq = chirp_input.get_frequency_rads(); 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 { - 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; - } + target_angle_cd = 0.0f; + trim_yaw_tgt_reading_cd = (float)attitude_control->get_att_target_euler_cd().z; + trim_yaw_heading_reading_cd = (float)ahrs_view->yaw_sensor; dwell_start_time_ms = now; filt_att_fdbk_from_velxy_cd.reset(Vector2f(0.0f,0.0f)); settle_time--; } - 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(); + 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 AxisType::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(); + if (test_calc_type == DRB) { + tgt_rate_reading = radians(target_angle_cd * 0.01f); + gyro_reading = radians(((float)ahrs_view->roll_sensor + trim_angle_cd.x - target_angle_cd) * 0.01f); + } else if (test_calc_type == RATE) { 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(); + gyro_reading = ahrs_view->get_gyro().x; + } else { + tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().x * 0.01f); + gyro_reading = radians((float)ahrs_view->roll_sensor * 0.01f); + } + break; + case AxisType::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(); + if (test_calc_type == DRB) { + tgt_rate_reading = radians(target_angle_cd * 0.01f); + gyro_reading = radians(((float)ahrs_view->pitch_sensor + trim_angle_cd.y - target_angle_cd) * 0.01f); + } else if (test_calc_type == RATE) { 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); - } - } - break; - case YAW: - case YAW_D: - 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; + gyro_reading = ahrs_view->get_gyro().y; + } else { + tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().y * 0.01f); + gyro_reading = radians((float)ahrs_view->pitch_sensor * 0.01f); } - } 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(); - if (dwell_type == DRB) { - tgt_rate_reading = (target_angle_cd) / 5730.0f; - gyro_reading = ((float)ahrs_view->roll_sensor + trim_angle_cd.x - target_angle_cd) / 5730.0f; - } else { - 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(); - if (dwell_type == DRB) { - tgt_rate_reading = (target_angle_cd) / 5730.0f; - gyro_reading = ((float)ahrs_view->pitch_sensor + trim_angle_cd.y - target_angle_cd) / 5730.0f; - } else { - 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: - case YAW_D: - command_reading = motors->get_yaw(); - if (dwell_type == DRB) { - tgt_rate_reading = (target_angle_cd) / 5730.0f; - gyro_reading = (wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading - target_angle_cd)) / 5730.0f; - } else { - 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; + case AxisType::YAW: + case AxisType::YAW_D: + attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading_cd + target_angle_cd), false); + command_reading = motors->get_yaw(); + if (test_calc_type == DRB) { + tgt_rate_reading = radians(target_angle_cd * 0.01f); + gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd - target_angle_cd)) * 0.01f); + } else if (test_calc_type == RATE) { + tgt_rate_reading = attitude_control->rate_bf_targets().z; + gyro_reading = ahrs_view->get_gyro().z; + } else { + tgt_rate_reading = radians((wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading_cd)) * 0.01f); + gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd)) * 0.01f); } + break; } if (settle_time == 0) { @@ -1150,57 +896,125 @@ void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, command_out = command_filt.apply((command_reading - filt_command_reading.get()), AP::scheduler().get_loop_period_s()); + float dwell_gain_mtr = 0.0f; + float dwell_phase_mtr = 0.0f; + float dwell_gain_tgt = 0.0f; + float dwell_phase_tgt = 0.0f; // 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.update(command_out,filt_target_rate,rotation_rate, dwell_freq); - } else { - freqresp.update(command_out,command_out,rotation_rate, dwell_freq); + if ((float)(now - dwell_start_time_ms) > pre_calc_cycles * cycle_time_ms || (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP && settle_time == 0)) { + freqresp_mtr.update(command_out,command_out,rotation_rate, dwell_freq); + freqresp_tgt.update(command_out,filt_target_rate,rotation_rate, dwell_freq); + + if (freqresp_mtr.is_cycle_complete()) { + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + if (is_zero(curr_test_mtr.freq) && freqresp_mtr.get_freq() < test_start_freq) { + // don't set data since captured frequency is below the start frequency + } else { + curr_test_mtr.freq = freqresp_mtr.get_freq(); + curr_test_mtr.gain = freqresp_mtr.get_gain(); + curr_test_mtr.phase = freqresp_mtr.get_phase(); + } + // reset cycle_complete to allow indication of next cycle + freqresp_mtr.reset_cycle_complete(); +#if HAL_LOGGING_ENABLED + // log sweep data + Log_AutoTuneSweep(); +#endif + } else { + dwell_gain_mtr = freqresp_mtr.get_gain(); + dwell_phase_mtr = freqresp_mtr.get_phase(); + cycle_complete_mtr = true; + } } - if (freqresp.is_cycle_complete()) { - if (!is_equal(start_frq,stop_frq)) { - curr_test.freq = freqresp.get_freq(); - curr_test.gain = freqresp.get_gain(); - curr_test.phase = freqresp.get_phase(); - if (dwell_type == DRB) {test_accel_max = freqresp.get_accel_max();} + if (freqresp_tgt.is_cycle_complete()) { + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + if (is_zero(curr_test_tgt.freq) && freqresp_tgt.get_freq() < test_start_freq) { + // don't set data since captured frequency is below the start frequency + } else { + curr_test_tgt.freq = freqresp_tgt.get_freq(); + curr_test_tgt.gain = freqresp_tgt.get_gain(); + curr_test_tgt.phase = freqresp_tgt.get_phase(); + if (test_calc_type == DRB) {test_accel_max = freqresp_tgt.get_accel_max();} + } // reset cycle_complete to allow indication of next cycle - freqresp.reset_cycle_complete(); + freqresp_tgt.reset_cycle_complete(); #if HAL_LOGGING_ENABLED // log sweep data Log_AutoTuneSweep(); #endif } else { - dwell_gain = freqresp.get_gain(); - dwell_phase = freqresp.get_phase(); - if (dwell_type == DRB) {test_accel_max = freqresp.get_accel_max();} + dwell_gain_tgt = freqresp_tgt.get_gain(); + dwell_phase_tgt = freqresp_tgt.get_phase(); + if (test_calc_type == DRB) {test_accel_max = freqresp_tgt.get_accel_max();} + cycle_complete_tgt = true; + } + } + + if (test_freq_resp_input == TARGET) { + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + curr_test = curr_test_tgt; + } else { + test_data.freq = test_start_freq; + test_data.gain = dwell_gain_tgt; + test_data.phase = dwell_phase_tgt; + } + } else { + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + curr_test = curr_test_mtr; + } else { + test_data.freq = test_start_freq; + test_data.gain = dwell_gain_mtr; + test_data.phase = dwell_phase_mtr; } } } // 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) { + if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP && (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) { - sweep.progress = 1; - } else if (curr_test.phase > 270.0f && sweep.progress == 1) { - sweep.progress = 2; + if (curr_test_tgt.phase > 180.0f && sweep_tgt.progress == 0) { + sweep_tgt.progress = 1; + } else if (curr_test_tgt.phase > 270.0f && sweep_tgt.progress == 1) { + sweep_tgt.progress = 2; } - if (curr_test.phase <= 160.0f && curr_test.phase >= 150.0f && sweep.progress == 0) { - sweep.ph180 = curr_test; + if (curr_test_tgt.phase <= 160.0f && curr_test_tgt.phase >= 150.0f && sweep_tgt.progress == 0) { + sweep_tgt.ph180 = curr_test_tgt; } - if (curr_test.phase <= 250.0f && curr_test.phase >= 240.0f && sweep.progress == 1) { - sweep.ph270 = curr_test; + if (curr_test_tgt.phase <= 250.0f && curr_test_tgt.phase >= 240.0f && sweep_tgt.progress == 1) { + sweep_tgt.ph270 = curr_test_tgt; } - if (curr_test.gain > sweep.maxgain.gain) { - sweep.maxgain = curr_test; + if (curr_test_tgt.gain > sweep_tgt.maxgain.gain) { + sweep_tgt.maxgain = curr_test_tgt; } + // Determine sweep info for motor input to response output + if (curr_test_mtr.phase > 180.0f && sweep_mtr.progress == 0) { + sweep_mtr.progress = 1; + } else if (curr_test_mtr.phase > 270.0f && sweep_mtr.progress == 1) { + sweep_mtr.progress = 2; + } + if (curr_test_mtr.phase <= 160.0f && curr_test_mtr.phase >= 150.0f && sweep_mtr.progress == 0) { + sweep_mtr.ph180 = curr_test_mtr; + } + if (curr_test_mtr.phase <= 250.0f && curr_test_mtr.phase >= 240.0f && sweep_mtr.progress == 1) { + sweep_mtr.ph270 = curr_test_mtr; + } + if (curr_test_mtr.gain > sweep_mtr.maxgain.gain) { + sweep_mtr.maxgain = curr_test_mtr; + } + if (now - step_start_time_ms >= sweep_time_ms + 200) { // we have passed the maximum stop time + sweep_complete = true; step = UPDATE_GAINS; } } else { - if (now - step_start_time_ms >= step_time_limit_ms || freqresp.is_cycle_complete()) { + if (now - step_start_time_ms >= step_time_limit_ms || (freqresp_tgt.is_cycle_complete() && freqresp_mtr.is_cycle_complete())) { + if (now - step_start_time_ms >= step_time_limit_ms) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Step time limit exceeded"); + } + cycle_complete_tgt = false; + cycle_complete_tgt = false; // we have passed the maximum stop time step = UPDATE_GAINS; } @@ -1211,15 +1025,15 @@ void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, void AC_AutoTune_Heli::updating_rate_p_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: - updating_rate_p_up(tune_roll_rp, test_freq, test_gain, test_phase, freq_cnt, max_rate_p); + case AxisType::ROLL: + updating_rate_p_up(tune_roll_rp, curr_data, next_test_freq, max_rate_p); break; - case PITCH: - updating_rate_p_up(tune_pitch_rp, test_freq, test_gain, test_phase, freq_cnt, max_rate_p); + case AxisType::PITCH: + updating_rate_p_up(tune_pitch_rp, curr_data, next_test_freq, max_rate_p); break; - case YAW: - case YAW_D: - updating_rate_p_up(tune_yaw_rp, test_freq, test_gain, test_phase, freq_cnt, max_rate_p); + case AxisType::YAW: + case AxisType::YAW_D: + updating_rate_p_up(tune_yaw_rp, curr_data, next_test_freq, max_rate_p); break; } } @@ -1228,15 +1042,15 @@ void AC_AutoTune_Heli::updating_rate_p_up_all(AxisType test_axis) void AC_AutoTune_Heli::updating_rate_d_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: - updating_rate_d_up(tune_roll_rd, test_freq, test_gain, test_phase, freq_cnt, max_rate_d); + case AxisType::ROLL: + updating_rate_d_up(tune_roll_rd, curr_data, next_test_freq, max_rate_d); break; - case PITCH: - updating_rate_d_up(tune_pitch_rd, test_freq, test_gain, test_phase, freq_cnt, max_rate_d); + case AxisType::PITCH: + updating_rate_d_up(tune_pitch_rd, curr_data, next_test_freq, max_rate_d); break; - case YAW: - case YAW_D: - updating_rate_d_up(tune_yaw_rd, test_freq, test_gain, test_phase, freq_cnt, max_rate_d); + case AxisType::YAW: + case AxisType::YAW_D: + updating_rate_d_up(tune_yaw_rd, curr_data, next_test_freq, max_rate_d); break; } } @@ -1245,15 +1059,15 @@ void AC_AutoTune_Heli::updating_rate_d_up_all(AxisType test_axis) void AC_AutoTune_Heli::updating_rate_ff_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: - updating_rate_ff_up(tune_roll_rff, test_tgt_rate_filt*5730.0f, test_rate_filt*5730.0f, test_command_filt); + case AxisType::ROLL: + updating_rate_ff_up(tune_roll_rff, curr_data, next_test_freq); break; - case PITCH: - updating_rate_ff_up(tune_pitch_rff, test_tgt_rate_filt*5730.0f, test_rate_filt*5730.0f, test_command_filt); + case AxisType::PITCH: + updating_rate_ff_up(tune_pitch_rff, curr_data, next_test_freq); break; - case YAW: - case YAW_D: - updating_rate_ff_up(tune_yaw_rff, test_tgt_rate_filt*5730.0f, test_rate_filt*5730.0f, test_command_filt); + case AxisType::YAW: + case AxisType::YAW_D: + updating_rate_ff_up(tune_yaw_rff, curr_data, next_test_freq); // TODO make FF updating routine determine when to set rff gain to zero based on A/C response if (tune_yaw_rff <= AUTOTUNE_RFF_MIN && counter == AUTOTUNE_SUCCESS_COUNT) { tune_yaw_rff = 0.0f; @@ -1267,16 +1081,32 @@ void AC_AutoTune_Heli::updating_angle_p_up_all(AxisType test_axis) { attitude_control->bf_feedforward(orig_bf_feedforward); + // sweep doesn't require gain update so return immediately after setting next test freq + // determine next_test_freq for dwell testing + if (sweep_complete && input_type == AC_AutoTune_FreqResp::InputType::SWEEP){ + // if a max gain frequency was found then set the start of the dwells to that freq otherwise start at min frequency + if (!is_zero(sweep_tgt.maxgain.freq)) { + next_test_freq = constrain_float(sweep_tgt.maxgain.freq, min_sweep_freq, max_sweep_freq); + freq_max = next_test_freq; + sp_prev_gain = sweep_tgt.maxgain.gain; + phase_max = sweep_tgt.maxgain.phase; + found_max_gain_freq = true; + } else { + next_test_freq = min_sweep_freq; + } + return; + } + switch (test_axis) { - case ROLL: - updating_angle_p_up(tune_roll_sp, test_freq, test_gain, test_phase, freq_cnt); + case AxisType::ROLL: + updating_angle_p_up(tune_roll_sp, curr_data, next_test_freq); break; - case PITCH: - updating_angle_p_up(tune_pitch_sp, test_freq, test_gain, test_phase, freq_cnt); + case AxisType::PITCH: + updating_angle_p_up(tune_pitch_sp, curr_data, next_test_freq); break; - case YAW: - case YAW_D: - updating_angle_p_up(tune_yaw_sp, test_freq, test_gain, test_phase, freq_cnt); + case AxisType::YAW: + case AxisType::YAW_D: + updating_angle_p_up(tune_yaw_sp, curr_data, next_test_freq); break; } } @@ -1284,16 +1114,29 @@ void AC_AutoTune_Heli::updating_angle_p_up_all(AxisType test_axis) // update gains for the max gain tune type void AC_AutoTune_Heli::updating_max_gains_all(AxisType test_axis) { + // sweep doesn't require gain update so return immediately after setting next test freq + // determine next_test_freq for dwell testing + if (sweep_complete && input_type == AC_AutoTune_FreqResp::InputType::SWEEP) { + // if a max gain frequency was found then set the start of the dwells to that freq otherwise start at min frequency + if (!is_zero(sweep_mtr.ph180.freq)) { + next_test_freq = constrain_float(sweep_mtr.ph180.freq, min_sweep_freq, max_sweep_freq); + reset_maxgains_update_gain_variables(); + } else { + next_test_freq = min_sweep_freq; + } + return; + } + switch (test_axis) { - case ROLL: - updating_max_gains(&test_freq[0], &test_gain[0], &test_phase[0], freq_cnt, max_rate_p, max_rate_d, tune_roll_rp, tune_roll_rd); + case AxisType::ROLL: + updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_roll_rp, tune_roll_rd); break; - case PITCH: - updating_max_gains(&test_freq[0], &test_gain[0], &test_phase[0], freq_cnt, max_rate_p, max_rate_d, tune_pitch_rp, tune_pitch_rd); + case AxisType::PITCH: + updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_pitch_rp, tune_pitch_rd); break; - case YAW: - case YAW_D: - updating_max_gains(&test_freq[0], &test_gain[0], &test_phase[0], freq_cnt, max_rate_p, max_rate_d, tune_yaw_rp, tune_yaw_rd); + case AxisType::YAW: + case AxisType::YAW_D: + updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_yaw_rp, tune_yaw_rd); // rate P and rate D can be non zero for yaw and need to be included in the max allowed gain if (!is_zero(max_rate_p.max_allowed) && counter == AUTOTUNE_SUCCESS_COUNT) { max_rate_p.max_allowed += tune_yaw_rp; @@ -1311,42 +1154,42 @@ void AC_AutoTune_Heli::set_gains_post_tune(AxisType test_axis) switch (tune_type) { case RD_UP: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_rd = MAX(0.0f, tune_roll_rd * AUTOTUNE_RD_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_rd = MAX(0.0f, tune_pitch_rd * AUTOTUNE_RD_BACKOFF); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_yaw_rd = MAX(0.0f, tune_yaw_rd * AUTOTUNE_RD_BACKOFF); break; } break; case RP_UP: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_rp = MAX(0.0f, tune_roll_rp * AUTOTUNE_RP_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_rp = MAX(0.0f, tune_pitch_rp * AUTOTUNE_RP_BACKOFF); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF); break; } break; case SP_UP: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF); break; } @@ -1360,385 +1203,326 @@ void AC_AutoTune_Heli::set_gains_post_tune(AxisType test_axis) // updating_rate_ff_up - adjust FF to ensure the target is reached // FF is adjusted until rate requested is achieved -void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command) +void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, sweep_info &test_data, float &next_freq) { + float tune_tgt = 0.95; + float tune_tol = 0.025; + next_freq = test_data.freq; - if (ff_up_first_iter) { - if (!is_zero(meas_rate)) { - tune_ff = 5730.0f * meas_command / meas_rate; - } - tune_ff = constrain_float(tune_ff, AUTOTUNE_RFF_MIN, AUTOTUNE_RFF_MAX); - ff_up_first_iter = false; - } else if (is_positive(rate_target * meas_rate) && fabsf(meas_rate) < 1.05f * fabsf(rate_target) && - fabsf(meas_rate) > 0.95f * fabsf(rate_target)) { - if (!first_dir_complete) { - first_dir_rff = tune_ff; - first_dir_complete = true; - positive_direction = !positive_direction; + // handle axes where FF gain is initially zero + if (test_data.gain < tune_tgt - tune_tol && !is_positive(tune_ff)) { + tune_ff = 0.03f; + return; + } + + if (test_data.gain < tune_tgt - 0.2 || test_data.gain > tune_tgt + 0.2) { + tune_ff = tune_ff * constrain_float(tune_tgt / test_data.gain, 0.75, 1.25); //keep changes less than 25% + } else if (test_data.gain < tune_tgt - 0.1 || test_data.gain > tune_tgt + 0.1) { + if (test_data.gain < tune_tgt - 0.1) { + tune_ff *= 1.05; } else { - counter = AUTOTUNE_SUCCESS_COUNT; - tune_ff = 0.95f * 0.5 * (tune_ff + first_dir_rff); - tune_ff = constrain_float(tune_ff, AUTOTUNE_RFF_MIN, AUTOTUNE_RFF_MAX); - } - } else if (is_positive(rate_target * meas_rate) && fabsf(meas_rate) > 1.05f * fabsf(rate_target)) { - tune_ff = 0.98f * tune_ff; - if (tune_ff <= AUTOTUNE_RFF_MIN) { - tune_ff = AUTOTUNE_RFF_MIN; - counter = AUTOTUNE_SUCCESS_COUNT; - LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); - } - } else if (is_positive(rate_target * meas_rate) && fabsf(meas_rate) < 0.95f * fabsf(rate_target)) { - tune_ff = 1.02f * tune_ff; - if (tune_ff >= AUTOTUNE_RFF_MAX) { - tune_ff = AUTOTUNE_RFF_MAX; - counter = AUTOTUNE_SUCCESS_COUNT; - LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + tune_ff *= 0.95; } - } else { - if (!is_zero(meas_rate)) { - tune_ff = 5730.0f * meas_command / meas_rate; + } else if (test_data.gain < tune_tgt - tune_tol || test_data.gain > tune_tgt + tune_tol) { + if (test_data.gain < tune_tgt - tune_tol) { + tune_ff *= 1.02; + } else { + tune_ff *= 0.98; } - tune_ff = constrain_float(tune_ff, AUTOTUNE_RFF_MIN, AUTOTUNE_RFF_MAX); + } else if (test_data.gain >= tune_tgt - tune_tol && test_data.gain <= tune_tgt + tune_tol) { + counter = AUTOTUNE_SUCCESS_COUNT; + // reset next_freq for next test + next_freq = 0.0f; + tune_ff = constrain_float(tune_ff,0.0f,1.0f); } } -// updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not exceed exceed max response gain -void AC_AutoTune_Heli::updating_rate_p_up(float &tune_p, float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_p) +// updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not +// exceed max response gain. A phase of 161 deg is used to conduct the tuning as this phase is where analytically +// max gain to 6db gain margin is determined for a unity feedback controller. +void AC_AutoTune_Heli::updating_rate_p_up(float &tune_p, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p) { - float test_freq_incr = 0.25f * 3.14159f * 2.0f; - - if (frq_cnt < 12 && is_equal(start_freq,stop_freq)) { - if (phase[frq_cnt] <= 180.0f && !is_zero(phase[frq_cnt])) { - rp_prev_good_frq_cnt = frq_cnt; - } else if (frq_cnt > 1 && phase[frq_cnt] > phase[frq_cnt-1] + 360.0f && !is_zero(phase[frq_cnt])) { - if (phase[frq_cnt] - 360.0f < 180.0f) { - rp_prev_good_frq_cnt = frq_cnt; - } - } else if (frq_cnt > 1 && phase[frq_cnt] > 200.0f && !is_zero(phase[frq_cnt])) { - frq_cnt = 11; - } - frq_cnt++; - if (frq_cnt == 12) { - freq[frq_cnt] = freq[rp_prev_good_frq_cnt]; - curr_test.freq = freq[frq_cnt]; + float test_freq_incr = 0.25f * M_2PI; + next_freq = test_data.freq; + + sweep_info data_at_ph161; + float sugg_freq; + if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_ph161, sugg_freq)) { + if (data_at_ph161.gain < max_resp_gain && tune_p < 0.6f * max_gain_p.max_allowed) { + tune_p += 0.05f * max_gain_p.max_allowed; + next_freq = data_at_ph161.freq; } else { - freq[frq_cnt] = freq[frq_cnt-1] + test_freq_incr; - 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; - } else if (phase[frq_cnt] < 160.0f) { - 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]; - 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); - } + counter = AUTOTUNE_SUCCESS_COUNT; + // reset next_freq for next test + next_freq = 0.0f; + tune_p -= 0.05f * max_gain_p.max_allowed; + tune_p = constrain_float(tune_p,0.0f,0.6f * max_gain_p.max_allowed); } - } - - 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; + next_freq = sugg_freq; } } -// updating_rate_d_up - uses maximum allowable gain determined from max_gain test to determine rate d gain where the response gain is at a minimum -void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_d) +// updating_rate_d_up - uses maximum allowable gain determined from max_gain test to determine rate d gain where the response +// gain is at a minimum. A phase of 161 deg is used to conduct the tuning as this phase is where analytically +// max gain to 6db gain margin is determined for a unity feedback controller. +void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_d) { - float test_freq_incr = 0.25f * 3.14159f * 2.0f; // set for 1/4 hz increments - - // 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; - frq_cnt = 12; - freq_cnt_max = frq_cnt; - } else { - frq_cnt = 1; - freq[frq_cnt] = min_sweep_freq; - } - 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)) { - if (phase[frq_cnt] <= 180.0f && !is_zero(phase[frq_cnt])) { - rd_prev_good_frq_cnt = frq_cnt; - } else if (frq_cnt > 1 && phase[frq_cnt] > phase[frq_cnt-1] + 360.0f && !is_zero(phase[frq_cnt])) { - if (phase[frq_cnt] - 360.0f < 180.0f) { - rd_prev_good_frq_cnt = frq_cnt; - } - } else if (frq_cnt > 1 && phase[frq_cnt] > 200.0f && !is_zero(phase[frq_cnt])) { - frq_cnt = 11; - } - frq_cnt++; - if (frq_cnt == 12) { - freq[frq_cnt] = freq[rd_prev_good_frq_cnt]; - curr_test.freq = freq[frq_cnt]; + float test_freq_incr = 0.25f * M_2PI; // set for 1/4 hz increments + next_freq = test_data.freq; + + sweep_info data_at_ph161; + float sugg_freq; + if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_ph161, sugg_freq)) { + if ((data_at_ph161.gain < 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 = data_at_ph161.gain; + next_freq = data_at_ph161.freq; } else { - freq[frq_cnt] = freq[frq_cnt-1] + test_freq_incr; - 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; - } else if (phase[frq_cnt] < 160.0f) { - 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]; - frq_cnt = 0; - rd_prev_gain = 0.0f; - tune_d -= 0.05f * max_gain_d.max_allowed; - tune_d = constrain_float(tune_d,0.0f,0.6f * max_gain_d.max_allowed); - } + counter = AUTOTUNE_SUCCESS_COUNT; + // reset next freq and rd_prev_gain for next test + next_freq = 0; + rd_prev_gain = 0.0f; + tune_d -= 0.05f * max_gain_d.max_allowed; + tune_d = constrain_float(tune_d,0.0f,0.6f * max_gain_d.max_allowed); } - } - if (counter == AUTOTUNE_SUCCESS_COUNT) { - 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; + next_freq = sugg_freq; } } -// updating_angle_p_up - determines maximum angle p gain for pitch and roll -void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *gain, float *phase, uint8_t &frq_cnt) +// updating_angle_p_up - determines maximum angle p gain for pitch and roll. This is accomplished by determining the frequency +// for the maximum response gain that is the disturbance rejection peak. +void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, sweep_info &test_data, float &next_freq) { - float test_freq_incr = 0.5f * 3.14159f * 2.0f; + float test_freq_incr = 0.5f * M_2PI; float gain_incr = 0.5f; - if (!is_equal(start_freq,stop_freq)) { - if (!is_zero(sweep.maxgain.freq)) { - frq_cnt = 12; - 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]; + if (is_zero(test_data.phase)) { + // bad test point. increase slightly in hope of getting better result + next_freq += 0.5f * test_freq_incr; + return; } - if (freq_cnt < 12 && is_equal(start_freq,stop_freq)) { - if (gain[freq_cnt] > max_resp_gain && tune_p > AUTOTUNE_SP_MIN) { + + if (!found_max_gain_freq) { + if (test_data.gain > max_resp_gain && tune_p > AUTOTUNE_SP_MIN) { // exceeded max response gain already, reduce tuning gain to remain under max response gain tune_p -= gain_incr; // force counter to stay on frequency - freq_cnt -= 1; - } else if (gain[freq_cnt] > max_resp_gain && tune_p <= AUTOTUNE_SP_MIN) { + next_freq = test_data.freq; + return; + } else if (test_data.gain > max_resp_gain && tune_p <= AUTOTUNE_SP_MIN) { // exceeded max response gain at the minimum allowable tuning gain. terminate testing. tune_p = AUTOTUNE_SP_MIN; counter = AUTOTUNE_SUCCESS_COUNT; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); - } else if (gain[freq_cnt] > gain[freq_cnt_max]) { - freq_cnt_max = freq_cnt; - phase_max = phase[freq_cnt]; - sp_prev_gain = gain[freq_cnt]; - } else if (freq[freq_cnt] > max_sweep_freq || (gain[freq_cnt] > 0.0f && gain[freq_cnt] < 0.5f)) { - // must be past peak, continue on to determine angle p - freq_cnt = 11; - } - freq_cnt++; - if (freq_cnt == 12) { - freq[freq_cnt] = freq[freq_cnt_max]; - curr_test.freq = freq[freq_cnt]; + } else if (test_data.gain > sp_prev_gain) { + freq_max = test_data.freq; + phase_max = test_data.phase; + sp_prev_gain = test_data.gain; + next_freq = test_data.freq + test_freq_incr; + return; + // Gain is expected to continue decreasing past gain peak. declare max gain freq found and refine search. + } else if (test_data.gain < 0.95f * sp_prev_gain) { + found_max_gain_freq = true; + next_freq = freq_max + 0.5 * test_freq_incr; + return; + } else { + next_freq = test_data.freq + test_freq_incr; + return; + } + } + + // refine peak + if (!found_peak) { + // look at frequency above max gain freq found + if (test_data.freq > freq_max && test_data.gain > sp_prev_gain) { + // found max at frequency greater than initial max gain frequency + found_peak = true; + } else if (test_data.freq > freq_max && test_data.gain < sp_prev_gain) { + // look at frequency below initial max gain frequency + next_freq = test_data.freq - 0.5 * test_freq_incr; + return; + } else if (test_data.freq < freq_max && test_data.gain > sp_prev_gain) { + // found max at frequency less than initial max gain frequency + found_peak = true; } else { - freq[freq_cnt] = freq[freq_cnt-1] + test_freq_incr; - curr_test.freq = freq[freq_cnt]; + found_peak = true; + test_data.freq = freq_max; + test_data.gain = sp_prev_gain; } + sp_prev_gain = test_data.gain; } - // once finished with sweep of frequencies, cnt = 12 is used to then tune for max response gain - if (freq_cnt >= 12 && is_equal(start_freq,stop_freq)) { - if (gain[freq_cnt] < max_resp_gain && tune_p < AUTOTUNE_SP_MAX && !find_peak) { - // keep increasing tuning gain unless phase changes or max response gain is achieved - if (phase[freq_cnt]-phase_max > 20.0f && phase[freq_cnt] < 210.0f) { - freq[freq_cnt] += 0.5 * test_freq_incr; - find_peak = true; - } else { - tune_p += gain_incr; - freq[freq_cnt] = freq[freq_cnt_max]; - if (tune_p >= AUTOTUNE_SP_MAX) { - tune_p = AUTOTUNE_SP_MAX; - counter = AUTOTUNE_SUCCESS_COUNT; - LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); - } + // start increasing gain + if (found_max_gain_freq && found_peak) { + if (test_data.gain < max_resp_gain && tune_p < AUTOTUNE_SP_MAX) { + tune_p += gain_incr; + next_freq = test_data.freq; + if (tune_p >= AUTOTUNE_SP_MAX) { + tune_p = AUTOTUNE_SP_MAX; + counter = AUTOTUNE_SUCCESS_COUNT; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } - 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) { + sp_prev_gain = test_data.gain; + } else if (test_data.gain > 1.1f * max_resp_gain && tune_p > AUTOTUNE_SP_MIN) { tune_p -= gain_incr; - } else if (find_peak) { - // find the frequency where the response gain is maximum - if (gain[freq_cnt] > sp_prev_gain) { - freq[freq_cnt] += 0.5 * test_freq_incr; - } else { - find_peak = false; - phase_max = phase[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 - if (sp_prev_gain < max_resp_gain && gain[freq_cnt] > max_resp_gain) { - float adj_factor = (max_resp_gain - gain[freq_cnt]) / (gain[freq_cnt] - sp_prev_gain); + if (sp_prev_gain < max_resp_gain && test_data.gain > max_resp_gain) { + float adj_factor = (max_resp_gain - test_data.gain) / (test_data.gain - sp_prev_gain); tune_p = tune_p + gain_incr * adj_factor; } counter = AUTOTUNE_SUCCESS_COUNT; } } if (counter == AUTOTUNE_SUCCESS_COUNT) { - start_freq = 0.0f; //initializes next test that uses dwell test + next_freq = 0.0f; //initializes next test that uses dwell test + sweep_complete = false; reset_sweep_variables(); - curr_test.freq = freq[0]; - freq_cnt = 0; - } else { - start_freq = curr_test.freq; - stop_freq = curr_test.freq; } } -// updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur -void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d) +// updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur. This uses the frequency +// response of motor class input to rate response to determine the max allowable gain for rate P gain. A phase of 161 deg is used to +// determine analytically the max gain to 6db gain margin for a unity feedback controller. Since acceleration can be more noisy, the +// response of the motor class input to rate response to determine the max allowable gain for rate D gain. A phase of 251 deg is used +// to determine analytically the max gain to 6db gain margin for a unity feedback controller. +void AC_AutoTune_Heli::updating_max_gains(sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d) { - float test_freq_incr = 1.0f * M_PI * 2.0f; - - 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; - } else { - freq[frq_cnt] = min_sweep_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 && - !find_middle && !found_max_p) { - find_middle = true; - } else if (find_middle && !found_max_p) { - if (phase[frq_cnt] > 161.0f) { - // interpolate between frq_cnt-2 and frq_cnt - max_gain_p.freq = linear_interpolate(freq[frq_cnt-2],freq[frq_cnt],161.0f,phase[frq_cnt-2],phase[frq_cnt]); - max_gain_p.gain = linear_interpolate(gain[frq_cnt-2],gain[frq_cnt],161.0f,phase[frq_cnt-2],phase[frq_cnt]); - } else { - // interpolate between frq_cnt-1 and frq_cnt - max_gain_p.freq = linear_interpolate(freq[frq_cnt],freq[frq_cnt-1],161.0f,phase[frq_cnt],phase[frq_cnt-1]); - max_gain_p.gain = linear_interpolate(gain[frq_cnt],gain[frq_cnt-1],161.0f,phase[frq_cnt],phase[frq_cnt-1]); - } - max_gain_p.phase = 161.0f; + float test_freq_incr = 0.5f * M_2PI; + next_freq = test_data.freq; + + sweep_info data_at_phase; + float sugg_freq; + if (!found_max_p) { + if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_phase, sugg_freq)) { + max_gain_p.freq = data_at_phase.freq; + max_gain_p.gain = data_at_phase.gain; + max_gain_p.phase = data_at_phase.phase; max_gain_p.max_allowed = powf(10.0f,-1 * (log10f(max_gain_p.gain) * 20.0f + 2.42) / 20.0f); // limit max gain allowed to be no more than 2x the max p gain limit to keep initial gains bounded max_gain_p.max_allowed = constrain_float(max_gain_p.max_allowed, 0.0f, 2.0f * AUTOTUNE_RP_MAX); found_max_p = true; - find_middle = false; - - 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; - } - } - if (frq_cnt > 2 && phase[frq_cnt] > 251.0f && phase[frq_cnt] < 360.0f && - !find_middle && !found_max_d && found_max_p) { - find_middle = true; - } else if (find_middle && found_max_p && !found_max_d) { - if (phase[frq_cnt] > 251.0f) { - // interpolate between frq_cnt-2 and frq_cnt - max_gain_d.freq = linear_interpolate(freq[frq_cnt-2],freq[frq_cnt],251.0f,phase[frq_cnt-2],phase[frq_cnt]); - max_gain_d.gain = linear_interpolate(gain[frq_cnt-2],gain[frq_cnt],251.0f,phase[frq_cnt-2],phase[frq_cnt]); + if (!is_zero(sweep_mtr.ph270.freq)) { + next_freq = sweep_mtr.ph270.freq; } else { - // interpolate between frq_cnt-1 and frq_cnt - max_gain_d.freq = linear_interpolate(freq[frq_cnt],freq[frq_cnt-1],251.0f,phase[frq_cnt],phase[frq_cnt-1]); - max_gain_d.gain = linear_interpolate(gain[frq_cnt],gain[frq_cnt-1],251.0f,phase[frq_cnt],phase[frq_cnt-1]); + next_freq = data_at_phase.freq; } - max_gain_d.phase = 251.0f; + } else { + next_freq = sugg_freq; + } + } else if (!found_max_d) { + if (freq_search_for_phase(test_data, 251.0f, test_freq_incr, data_at_phase, sugg_freq)) { + max_gain_d.freq = data_at_phase.freq; + max_gain_d.gain = data_at_phase.gain; + max_gain_d.phase = data_at_phase.phase; max_gain_d.max_allowed = powf(10.0f,-1 * (log10f(max_gain_d.freq * max_gain_d.gain) * 20.0f + 2.42) / 20.0f); // limit max gain allowed to be no more than 2x the max d gain limit to keep initial gains bounded max_gain_d.max_allowed = constrain_float(max_gain_d.max_allowed, 0.0f, 2.0f * AUTOTUNE_RD_MAX); found_max_d = true; - find_middle = false; - } - // stop progression in frequency. - if ((frq_cnt > 1 && phase[frq_cnt] > 330.0f && !is_zero(phase[frq_cnt])) || found_max_d) { - frq_cnt = 11; - } - frq_cnt++; - if (frq_cnt == 12) { - counter = AUTOTUNE_SUCCESS_COUNT; - // reset variables for next test - curr_test.freq = freq[0]; - frq_cnt = 0; - start_freq = 0.0f; //initializes next test that uses dwell test - reset_sweep_variables(); } else { - if (frq_cnt == 3 && phase[2] >= 161.0f && !found_max_p) { - // phase greater than 161 deg won't allow max p to be found - // reset freq cnt to 2 and lower dwell freq to push phase below 161 deg - frq_cnt = 2; - freq[frq_cnt] = freq[frq_cnt] - 0.5f * test_freq_incr; - } else if (frq_cnt == 3 && phase[2] >= 251.0f && !found_max_d) { - // phase greater than 161 deg won't allow max p to be found - // reset freq cnt to 2 and lower dwell freq to push phase below 161 deg - frq_cnt = 2; - freq[frq_cnt] = freq[frq_cnt] - 0.5f * test_freq_incr; - } else if (find_middle) { - freq[frq_cnt] = freq[frq_cnt-1] - 0.5f * test_freq_incr; - } 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; + next_freq = sugg_freq; } } + if (found_max_p && found_max_d) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max rate P freq=%f gain=%f", (double)(max_rate_p.freq), (double)(max_rate_p.gain)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_p=%f", (double)(max_rate_p.phase), (double)(max_rate_p.max_allowed)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Rate D freq=%f gain=%f", (double)(max_rate_d.freq), (double)(max_rate_d.gain)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_d=%f", (double)(max_rate_d.phase), (double)(max_rate_d.max_allowed)); + counter = AUTOTUNE_SUCCESS_COUNT; + // reset variables for next test + next_freq = 0.0f; //initializes next test that uses dwell test + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max rate P freq=%f gain=%f", (double)(max_rate_p.freq), (double)(max_rate_p.gain)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_p=%f", (double)(max_rate_p.phase), (double)(max_rate_p.max_allowed)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max Rate D freq=%f gain=%f", (double)(max_rate_d.freq), (double)(max_rate_d.gain)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_d=%f", (double)(max_rate_d.phase), (double)(max_rate_d.max_allowed)); } } +float AC_AutoTune_Heli::target_angle_max_rp_cd() const +{ + return AUTOTUNE_ANGLE_TARGET_MAX_RP_CD; +} + +float AC_AutoTune_Heli::target_angle_max_y_cd() const +{ + return AUTOTUNE_ANGLE_TARGET_MAX_Y_CD; +} + +float AC_AutoTune_Heli::target_angle_min_rp_cd() const +{ + return AUTOTUNE_ANGLE_TARGET_MIN_RP_CD; +} + +float AC_AutoTune_Heli::target_angle_min_y_cd() const +{ + return AUTOTUNE_ANGLE_TARGET_MIN_Y_CD; +} + +float AC_AutoTune_Heli::angle_lim_max_rp_cd() const +{ + return AUTOTUNE_ANGLE_MAX_RP_CD; +} + +float AC_AutoTune_Heli::angle_lim_neg_rpy_cd() const +{ + return AUTOTUNE_ANGLE_NEG_RPY_CD; +} + +// freq_search_for_phase: general search strategy for specified phase. interpolation done once specified phase has been bounded. +bool AC_AutoTune_Heli::freq_search_for_phase(sweep_info test, float desired_phase, float freq_incr, sweep_info &est_data, float &new_freq) +{ + new_freq = test.freq; + float phase_delta = 20.0f; // delta from desired phase below and above which full steps are taken + if (is_zero(test.phase)) { + // bad test point. increase slightly in hope of getting better result + new_freq += 0.1f * freq_incr; + return false; + } + + // test to see if desired phase is bounded with a 0.5 freq_incr delta in freq + float freq_delta = fabsf(prev_test.freq - test.freq); + if (test.phase > desired_phase && prev_test.phase < desired_phase && freq_delta < 0.75f * freq_incr && is_positive(prev_test.freq)) { + est_data.freq = linear_interpolate(prev_test.freq,test.freq,desired_phase,prev_test.phase,test.phase); + est_data.gain = linear_interpolate(prev_test.gain,test.gain,desired_phase,prev_test.phase,test.phase); + est_data.phase = desired_phase; + prev_test = {}; + return true; + } else if (test.phase < desired_phase && prev_test.phase > desired_phase && freq_delta < 0.75f * freq_incr && is_positive(prev_test.freq)) { + est_data.freq = linear_interpolate(test.freq,prev_test.freq,desired_phase,test.phase,prev_test.phase); + est_data.gain = linear_interpolate(test.gain,prev_test.gain,desired_phase,test.phase,prev_test.phase); + est_data.phase = desired_phase; + prev_test = {}; + return true; + } + + if (test.phase < desired_phase - phase_delta) { + new_freq += freq_incr; + } else if (test.phase > desired_phase + phase_delta) { + new_freq -= freq_incr; + } else if (test.phase >= desired_phase - phase_delta && test.phase < desired_phase) { + new_freq += 0.5f * freq_incr; + } else if (test.phase <= desired_phase + phase_delta && test.phase >= desired_phase) { + new_freq -= 0.5f * freq_incr; + } + prev_test = test; + return false; +} + #if HAL_LOGGING_ENABLED // log autotune summary data void AC_AutoTune_Heli::Log_AutoTune() { switch (axis) { - case ROLL: - Log_Write_AutoTune(axis, tune_type, test_freq[freq_cnt], test_gain[freq_cnt], test_phase[freq_cnt], tune_roll_rff, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max); + case AxisType::ROLL: + Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_roll_rff, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max); break; - case PITCH: - Log_Write_AutoTune(axis, tune_type, test_freq[freq_cnt], test_gain[freq_cnt], test_phase[freq_cnt], tune_pitch_rff, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max); + case AxisType::PITCH: + Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_pitch_rff, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max); break; - case YAW: - case YAW_D: - Log_Write_AutoTune(axis, tune_type, test_freq[freq_cnt], test_gain[freq_cnt], test_phase[freq_cnt], tune_yaw_rff, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max); + case AxisType::YAW: + case AxisType::YAW_D: + Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_yaw_rff, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max); break; } } @@ -1746,7 +1530,7 @@ void AC_AutoTune_Heli::Log_AutoTune() // log autotune time history results for command, angular rate, and attitude void AC_AutoTune_Heli::Log_AutoTuneDetails() { - if (tune_type == SP_UP) { + if (tune_type == SP_UP || tune_type == TUNE_CHECK) { Log_Write_AutoTuneDetails(command_out, 0.0f, 0.0f, filt_target_rate, rotation_rate); } else { Log_Write_AutoTuneDetails(command_out, filt_target_rate, rotation_rate, 0.0f, 0.0f); @@ -1756,7 +1540,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_mtr.freq, curr_test_mtr.gain, curr_test_mtr.phase,curr_test_tgt.freq, curr_test_tgt.gain, curr_test_tgt.phase); } // @LoggerMessage: ATNH @@ -1775,7 +1559,7 @@ void AC_AutoTune_Heli::Log_AutoTuneSweep() // @Field: ACC: new max accel term // Write an Autotune summary data packet -void AC_AutoTune_Heli::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel) +void AC_AutoTune_Heli::Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel) { AP::logger().Write( "ATNH", @@ -1784,7 +1568,7 @@ void AC_AutoTune_Heli::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, floa "F--000-----", "QBBffffffff", AP_HAL::micros64(), - axis, + (uint8_t)axis, tune_step, dwell_freq, meas_gain, @@ -1823,25 +1607,31 @@ void AC_AutoTune_Heli::Log_Write_AutoTuneDetails(float motor_cmd, float tgt_rate } // Write an Autotune frequency response data packet -void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq, float gain, float phase) +void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq_mtr, float gain_mtr, float phase_mtr, float freq_tgt, float gain_tgt, float phase_tgt) { // @LoggerMessage: ATSH // @Description: Heli AutoTune Sweep packet // @Vehicles: Copter // @Field: TimeUS: Time since system startup - // @Field: freq: current frequency - // @Field: gain: current response gain - // @Field: phase: current response phase + // @Field: freq_m: current frequency for motor input to rate + // @Field: gain_m: current response gain for motor input to rate + // @Field: phase_m: current response phase for motor input to rate + // @Field: freq_t: current frequency for target rate to rate + // @Field: gain_t: current response gain for target rate to rate + // @Field: phase_t: current response phase for target rate to rate AP::logger().WriteStreaming( "ATSH", - "TimeUS,freq,gain,phase", - "sE-d", - "F000", - "Qfff", + "TimeUS,freq_m,gain_m,phase_m,freq_t,gain_t,phase_t", + "sE-dE-d", + "F000000", + "Qffffff", AP_HAL::micros64(), - freq, - gain, - phase); + freq_mtr, + gain_mtr, + phase_mtr, + freq_tgt, + gain_tgt, + phase_tgt); } #endif // HAL_LOGGING_ENABLED @@ -1850,33 +1640,28 @@ void AC_AutoTune_Heli::reset_vehicle_test_variables() { // reset dwell test variables if sweep was interrupted in order to restart sweep if (!is_equal(start_freq, stop_freq)) { - freq_cnt = 0; start_freq = 0.0f; stop_freq = 0.0f; + next_test_freq = 0.0f; + sweep_complete = false; } } // reset the update gain variables for heli void AC_AutoTune_Heli::reset_update_gain_variables() { - // reset feedforward update gain variables - ff_up_first_iter = true; - first_dir_complete = false; - - // reset max gain variables + // reset max gain variables reset_maxgains_update_gain_variables(); // reset rd_up variables - rd_prev_good_frq_cnt = 0; rd_prev_gain = 0.0f; - // reset rp_up variables - rp_prev_good_frq_cnt = 0; - // reset sp_up variables phase_max = 0.0f; + freq_max = 0.0f; sp_prev_gain = 0.0f; - find_peak = false; + found_max_gain_freq = false; + found_peak = false; } @@ -1885,20 +1670,26 @@ void AC_AutoTune_Heli::reset_maxgains_update_gain_variables() { max_rate_p = {}; max_rate_d = {}; + found_max_p = false; found_max_d = false; - find_middle = false; } // reset the max_gains update gain variables void AC_AutoTune_Heli::reset_sweep_variables() { - sweep.ph180 = {}; - sweep.ph270 = {}; - sweep.maxgain = {}; + sweep_tgt.ph180 = {}; + sweep_tgt.ph270 = {}; + sweep_tgt.maxgain = {}; + sweep_tgt.progress = 0; + + sweep_mtr.ph180 = {}; + sweep_mtr.ph270 = {}; + sweep_mtr.maxgain = {}; + + sweep_mtr.progress = 0; - sweep.progress = 0; } // set the tuning test sequence diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index 4890a0da8e2cef..4bb400a66c2f6d 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -50,7 +50,7 @@ class AC_AutoTune_Heli : public AC_AutoTune 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); + 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, float max_rate); // switch to use original gains void load_orig_gains() override; @@ -106,7 +106,7 @@ class AC_AutoTune_Heli : public AC_AutoTune #if HAL_LOGGING_ENABLED // methods to log autotune summary data void Log_AutoTune() override; - void Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel); + void Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel); // methods to log autotune time history results for command, angular rate, and attitude. void Log_AutoTuneDetails() override; @@ -114,7 +114,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // methods to log autotune frequency response results void Log_AutoTuneSweep() override; - void Log_Write_AutoTuneSweep(float freq, float gain, float phase); + void Log_Write_AutoTuneSweep(float freq_mtr, float gain_mtr, float phase_mtr, float freq_tgt, float gain_tgt, float phase_tgt); #endif // send intermittent updates to user on status of tune @@ -136,6 +136,13 @@ class AC_AutoTune_Heli : public AC_AutoTune uint32_t get_testing_step_timeout_ms() const override; private: + // sweep_info contains information about a specific test's sweep results + struct sweep_info { + float freq; + float gain; + float phase; + }; + // max_gain_data type stores information from the max gain test struct max_gain_data { float freq; @@ -144,43 +151,54 @@ class AC_AutoTune_Heli : public AC_AutoTune float max_allowed; }; - // max gain data for rate p tuning - max_gain_data max_rate_p; - // 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 { + // FreqRespCalcType is the type of calculation done for the frequency response + enum FreqRespCalcType { RATE = 0, ANGLE = 1, DRB = 2, }; - // 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); + enum FreqRespInput { + MOTOR = 0, + TARGET = 1, + }; + + float target_angle_max_rp_cd() const override; + + float target_angle_max_y_cd() const override; + + float target_angle_min_rp_cd() const override; + + float target_angle_min_y_cd() const override; + + float angle_lim_max_rp_cd() const override; + + float angle_lim_neg_rpy_cd() const override; // initialize dwell test or angle dwell test variables - void dwell_test_init(float start_frq, float stop_frq, float filt_freq, DwellType dwell_type); + void dwell_test_init(float start_frq, float stop_frq, float amplitude, float filt_freq, FreqRespInput freq_resp_input, FreqRespCalcType calc_type, AC_AutoTune_FreqResp::ResponseType resp_type, AC_AutoTune_FreqResp::InputType waveform_input_type); // 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); + void dwell_test_run(sweep_info &test_data); // updating_rate_ff_up - adjust FF to ensure the target is reached // FF is adjusted until rate requested is achieved - void updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command); + void updating_rate_ff_up(float &tune_ff, sweep_info &test_data, float &next_freq); // updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not exceed exceed max response gain - void updating_rate_p_up(float &tune_p, float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_p); + void updating_rate_p_up(float &tune_p, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p); // updating_rate_d_up - uses maximum allowable gain determined from max_gain test to determine rate d gain where the response gain is at a minimum - void updating_rate_d_up(float &tune_d, float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_d); + void updating_rate_d_up(float &tune_d, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_d); // updating_angle_p_up - determines maximum angle p gain for pitch and roll - void updating_angle_p_up(float &tune_p, float *freq, float *gain, float *phase, uint8_t &frq_cnt); + void updating_angle_p_up(float &tune_p, sweep_info &test_data, float &next_freq); // updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur - void updating_max_gains(float *freq, float *gain, float *phase, uint8_t &frq_cnt, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d); + void updating_max_gains(sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d); + + // freq_search_for_phase: general search strategy for specified phase. interpolation done once specified phase has been bounded. + bool freq_search_for_phase(sweep_info test, float desired_phase, float freq_incr, sweep_info &est_data, float &new_freq); // reset the max_gains update gain variables void reset_maxgains_update_gain_variables(); @@ -194,83 +212,65 @@ class AC_AutoTune_Heli : public AC_AutoTune // report gain formatting helper void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const; - // updating rate FF variables - // flag for completion of the initial direction for the feedforward test - bool first_dir_complete; - // feedforward gain resulting from testing in the initial direction - float first_dir_rff; + // define input type as Dwell or Sweep. Used through entire class + AC_AutoTune_FreqResp::InputType input_type; + + sweep_info curr_data; // frequency response test results + float next_test_freq; // next test frequency for next test cycle setup + + // max gain data for rate p tuning + max_gain_data max_rate_p; + // max gain data for rate d tuning + max_gain_data max_rate_d; // updating max gain variables // flag for finding maximum p gain bool found_max_p; // flag for finding maximum d gain bool found_max_d; - // flag for interpolating to find max response gain - bool find_middle; // updating angle P up variables - // track the maximum phase - float phase_max; - // previous gain - float sp_prev_gain; - // flag for finding the peak of the gain response - bool find_peak; - - // updating rate P up - // counter value of previous good frequency - uint8_t rp_prev_good_frq_cnt; + float phase_max; // track the maximum phase and freq + float freq_max; + float sp_prev_gain; // previous gain + bool found_max_gain_freq; // flag for finding max gain frequency + bool found_peak; // flag for finding the peak of the gain response // updating rate D up - // counter value of previous good frequency - uint8_t rd_prev_good_frq_cnt; - // previous gain - float rd_prev_gain; - - uint8_t ff_test_phase; // phase of feedforward test - float test_command_filt; // filtered commanded output for FF test analysis - float test_rate_filt; // filtered rate output for FF test analysis + float rd_prev_gain; // previous gain + + // freq search for phase + sweep_info prev_test; // data from previous dwell + + // Dwell Test variables + AC_AutoTune_FreqResp::InputType test_input_type; + FreqRespCalcType test_calc_type; + FreqRespInput test_freq_resp_input; + uint8_t num_dwell_cycles; + float test_start_freq; + float tgt_attitude; + + float pre_calc_cycles; // number of cycles to complete before running frequency response calculations float command_out; // test axis command output - float test_tgt_rate_filt; // filtered target rate for FF test analysis float filt_target_rate; // filtered target rate - float test_gain[20]; // frequency response gain for each dwell test iteration - float test_freq[20]; // frequency of each dwell test iteration - 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 - // sweep_info contains information about a specific test's sweep results - struct sweep_info { - float freq; - float gain; - float phase; - }; sweep_info curr_test; + sweep_info curr_test_mtr; + sweep_info curr_test_tgt; 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 - float trim_pff_out; // trim output of the PID rate controller for P, I and FF terms - float trim_meas_rate; // trim measured gyro rate - - //variables from rate FF test - float trim_command_reading; - float trim_heading; - LowPassFilterFloat rate_request_cds; - LowPassFilterFloat angle_request_cd; // variables from dwell test - LowPassFilterVector2f filt_pit_roll_cd; // filtered pitch and roll attitude for dwell rate method - LowPassFilterFloat filt_heading_error_cd; // filtered heading error for dwell rate method LowPassFilterVector2f filt_att_fdbk_from_velxy_cd; LowPassFilterFloat filt_command_reading; // filtered command reading to keep oscillation centered LowPassFilterFloat filt_gyro_reading; // filtered gyro reading to keep oscillation centered LowPassFilterFloat filt_tgt_rate_reading; // filtered target rate reading to keep oscillation centered // trim variables for determining trim state prior to test starting - Vector3f trim_attitude_cd; // trim attitude before starting test - float trim_command; // trim target yaw reading before starting test - float trim_yaw_tgt_reading; // trim target yaw reading before starting test - float trim_yaw_heading_reading; // trim heading reading before starting test + float trim_yaw_tgt_reading_cd; // trim target yaw reading before starting test + float trim_yaw_heading_reading_cd; // trim heading reading before starting test LowPassFilterFloat command_filt; // filtered command - filtering intended to remove noise LowPassFilterFloat target_rate_filt; // filtered target rate in radians/second - filtering intended to remove noise @@ -280,15 +280,15 @@ class AC_AutoTune_Heli : public AC_AutoTune 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; + sweep_data sweep_mtr; + sweep_data sweep_tgt; + bool sweep_complete; // 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 @@ -296,9 +296,16 @@ class AC_AutoTune_Heli : public AC_AutoTune AP_Float max_sweep_freq; // maximum sweep frequency AP_Float max_resp_gain; // maximum response gain AP_Float vel_hold_gain; // gain for velocity hold + AP_Float accel_max; // maximum autotune angular acceleration + AP_Float rate_max; // maximum autotune angular rate // freqresp object for the frequency response tests - AC_AutoTune_FreqResp freqresp; + AC_AutoTune_FreqResp freqresp_mtr; // frequency response of output to motor mixer input + AC_AutoTune_FreqResp freqresp_tgt; // frequency response of output to target input + + // allow tracking of cycles complete for frequency response object + bool cycle_complete_tgt; + bool cycle_complete_mtr; Chirp chirp_input; }; diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index f304c3e70acb91..5e7aa6c5d98367 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -44,40 +44,47 @@ * */ -#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step - -#define AUTOTUNE_RD_STEP 0.05f // minimum increment when increasing/decreasing Rate D term -#define AUTOTUNE_RP_STEP 0.05f // minimum increment when increasing/decreasing Rate P term -#define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term -#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing -#define AUTOTUNE_PI_RATIO_FINAL 1.0f // I is set 1x P after testing -#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f // I is set 1x P after testing -#define AUTOTUNE_RD_MAX 0.200f // maximum Rate D value -#define AUTOTUNE_RLPF_MIN 1.0f // minimum Rate Yaw filter value -#define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value -#define AUTOTUNE_FLTE_MIN 2.5f // minimum Rate Yaw error 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 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 -#define AUTOTUNE_Y_FILT_FREQ 10.0f // Autotune filter frequency when testing Yaw -#define AUTOTUNE_D_UP_DOWN_MARGIN 0.2f // The margin below the target that we tune D in -#define AUTOTUNE_RD_BACKOFF 1.0f // Rate D gains are reduced to 50% of their maximum value discovered during tuning -#define AUTOTUNE_RP_BACKOFF 1.0f // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning -#define AUTOTUNE_SP_BACKOFF 0.9f // Stab P gains are reduced to 90% of their maximum value discovered during tuning -#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f // back off from maximum acceleration -#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f // back off from maximum acceleration +#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 2000U // timeout for tuning mode's testing step + +#define AUTOTUNE_RD_STEP 0.05 // minimum increment when increasing/decreasing Rate D term +#define AUTOTUNE_RP_STEP 0.05 // minimum increment when increasing/decreasing Rate P term +#define AUTOTUNE_SP_STEP 0.05 // minimum increment when increasing/decreasing Stab P term +#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1 // I is set 10x smaller than P during testing +#define AUTOTUNE_PI_RATIO_FINAL 1.0 // I is set 1x P after testing +#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1 // I is set 1x P after testing +#define AUTOTUNE_RD_MAX 0.200 // maximum Rate D value +#define AUTOTUNE_RLPF_MIN 1.0 // minimum Rate Yaw filter value +#define AUTOTUNE_RLPF_MAX 5.0 // maximum Rate Yaw filter value +#define AUTOTUNE_FLTE_MIN 2.5 // minimum Rate Yaw error filter value +#define AUTOTUNE_RP_MIN 0.01 // minimum Rate P value +#define AUTOTUNE_RP_MAX 2.0 // maximum Rate P value +#define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value +#define AUTOTUNE_SP_MIN 0.5 // maximum Stab P value +#define AUTOTUNE_RP_ACCEL_MIN 4000.0 // Minimum acceleration for Roll and Pitch +#define AUTOTUNE_Y_ACCEL_MIN 1000.0 // Minimum acceleration for Yaw +#define AUTOTUNE_Y_FILT_FREQ 10.0 // Autotune filter frequency when testing Yaw +#define AUTOTUNE_D_UP_DOWN_MARGIN 0.2 // The margin below the target that we tune D in +#define AUTOTUNE_RD_BACKOFF 1.0 // Rate D gains are reduced to 50% of their maximum value discovered during tuning +#define AUTOTUNE_RP_BACKOFF 1.0 // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning +#define AUTOTUNE_SP_BACKOFF 0.9 // Stab P gains are reduced to 90% of their maximum value discovered during tuning +#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0 // back off from maximum acceleration +#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0 // back off from maximum acceleration // roll and pitch axes #define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step -#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step +#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target min roll/pitch rate during AUTOTUNE_STEP_TWITCHING step // yaw axis -#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step -#define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500 // minimum target angle during TESTING_RATE step that will cause us to move to next step -#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step +#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step +#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step + +#define AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE 1.0 / 2.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE 1.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE 1.0 / 3.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE 1.0 / 6.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step +#define AUTOTUNE_ANGLE_ABORT_RP_SCALE 2.5 / 3.0 // maximum allowable angle during testing, as a fraction of angle_max +#define AUTOTUNE_ANGLE_MAX_Y_SCALE 1.0 // maximum allowable angle during testing, as a fraction of angle_max +#define AUTOTUNE_ANGLE_NEG_RP_SCALE 1.0 / 5.0 // maximum allowable angle during testing, as a fraction of angle_max // second table of user settable parameters for quadplanes, this // allows us to go beyond the 64 parameter limit @@ -95,14 +102,14 @@ const AP_Param::GroupInfo AC_AutoTune_Multi::var_info[] = { // @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term. // @Range: 0.05 0.10 // @User: Standard - AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.1f), + AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.075f), // @Param: MIN_D // @DisplayName: AutoTune minimum D // @Description: Defines the minimum D gain - // @Range: 0.001 0.006 + // @Range: 0.0001 0.005 // @User: Standard - AP_GROUPINFO("MIN_D", 3, AC_AutoTune_Multi, min_d, 0.001f), + AP_GROUPINFO("MIN_D", 3, AC_AutoTune_Multi, min_d, 0.0005f), AP_GROUPEND }; @@ -120,7 +127,7 @@ void AC_AutoTune_Multi::do_gcs_announcements() if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) { return; } - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: %s %s %u%%", axis_string(), type_string(), (counter * (100/AUTOTUNE_SUCCESS_COUNT))); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: %s %s %u%%", axis_string(), type_string(), (counter * (100/AUTOTUNE_SUCCESS_COUNT))); announce_time = now; } @@ -140,7 +147,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() { AC_AutoTune::backup_gains_and_initialise(); - aggressiveness.set(constrain_float(aggressiveness, 0.05f, 0.2f)); + aggressiveness.set(constrain_float(aggressiveness, 0.05, 0.2)); orig_bf_feedforward = attitude_control->get_bf_feedforward(); @@ -149,6 +156,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); orig_roll_rd = attitude_control->get_rate_roll_pid().kD(); orig_roll_rff = attitude_control->get_rate_roll_pid().ff(); + orig_roll_dff = attitude_control->get_rate_roll_pid().kDff(); orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz(); orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); @@ -162,6 +170,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff(); + orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff(); orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz(); orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); @@ -175,6 +184,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI(); orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff(); + orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff(); orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz(); orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit(); orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz(); @@ -202,38 +212,41 @@ void AC_AutoTune_Multi::load_orig_gains() attitude_control->bf_feedforward(orig_bf_feedforward); if (roll_enabled()) { if (!is_zero(orig_roll_rp)) { - 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->get_rate_roll_pid().set_kP(orig_roll_rp); + attitude_control->get_rate_roll_pid().set_kI(orig_roll_ri); + attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd); + attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff); + attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt); + attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax); + attitude_control->get_angle_roll_p().set_kP(orig_roll_sp); attitude_control->set_accel_roll_max_cdss(orig_roll_accel); } } if (pitch_enabled()) { if (!is_zero(orig_pitch_rp)) { - 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->get_rate_pitch_pid().set_kP(orig_pitch_rp); + attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_ri); + attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd); + attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff); + attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt); + attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax); + attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp); attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel); } } if (yaw_enabled() || yaw_d_enabled()) { if (!is_zero(orig_yaw_rp)) { - 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->get_rate_yaw_pid().set_kP(orig_yaw_rp); + attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_ri); + attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd); + attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF); + attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt); + attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax); + attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp); attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel); } } @@ -244,43 +257,41 @@ void AC_AutoTune_Multi::load_tuned_gains() { if (!attitude_control->get_bf_feedforward()) { attitude_control->bf_feedforward(true); - attitude_control->set_accel_roll_max_cdss(0.0f); - attitude_control->set_accel_pitch_max_cdss(0.0f); + attitude_control->set_accel_roll_max_cdss(0.0); + attitude_control->set_accel_pitch_max_cdss(0.0); } - if (roll_enabled()) { - if (!is_zero(tune_roll_rp)) { - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); - attitude_control->get_rate_roll_pid().kD(tune_roll_rd); - attitude_control->get_rate_roll_pid().ff(orig_roll_rff); - attitude_control->get_angle_roll_p().kP(tune_roll_sp); - attitude_control->set_accel_roll_max_cdss(tune_roll_accel); - } + if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) { + attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp); + attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); + attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd); + attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff); + attitude_control->get_angle_roll_p().set_kP(tune_roll_sp); + attitude_control->set_accel_roll_max_cdss(tune_roll_accel); } - if (pitch_enabled()) { - if (!is_zero(tune_pitch_rp)) { - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); - attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); - attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel); - } + if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) { + attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp); + attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); + attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd); + attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff); + attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp); + attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel); } - if (yaw_enabled() || yaw_d_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); - if (yaw_d_enabled()) { - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); - } - if (yaw_enabled()) { - attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); - } - attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); - attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel); + if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled()) + || ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) { + attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp); + attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL); + if (yaw_d_enabled()) { + attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd); } + if (yaw_enabled()) { + attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF); + } + attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff); + attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp); + attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel); } } @@ -292,32 +303,35 @@ void AC_AutoTune_Multi::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_rp*AUTOTUNE_PI_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->get_rate_roll_pid().set_kP(orig_roll_rp); + attitude_control->get_rate_roll_pid().set_kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); + attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd); + attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff); + attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt); + attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax); + attitude_control->get_angle_roll_p().set_kP(orig_roll_sp); } if (pitch_enabled()) { - attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(orig_pitch_rp*AUTOTUNE_PI_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->get_rate_pitch_pid().set_kP(orig_pitch_rp); + attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); + attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd); + attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff); + attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt); + attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax); + attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp); } if (yaw_enabled() || yaw_d_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->get_rate_yaw_pid().set_kP(orig_yaw_rp); + attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); + attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd); + attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff); + attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt); + attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF); + attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp); } } @@ -326,37 +340,41 @@ void AC_AutoTune_Multi::load_intra_test_gains() void AC_AutoTune_Multi::load_test_gains() { switch (axis) { - case ROLL: - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f); - attitude_control->get_rate_roll_pid().kD(tune_roll_rd); - attitude_control->get_rate_roll_pid().ff(0.0f); - attitude_control->get_rate_roll_pid().filt_T_hz(0.0f); - attitude_control->get_rate_roll_pid().slew_limit(0.0f); - attitude_control->get_angle_roll_p().kP(tune_roll_sp); + case AxisType::ROLL: + attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp); + attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp * 0.01); + attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd); + attitude_control->get_rate_roll_pid().set_ff(0.0); + attitude_control->get_rate_roll_pid().set_kDff(0.0); + attitude_control->get_rate_roll_pid().set_filt_T_hz(0.0); + attitude_control->get_rate_roll_pid().set_slew_limit(0.0); + attitude_control->get_angle_roll_p().set_kP(tune_roll_sp); break; - case PITCH: - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f); - attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(0.0f); - attitude_control->get_rate_pitch_pid().filt_T_hz(0.0f); - attitude_control->get_rate_pitch_pid().slew_limit(0.0f); - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); + case AxisType::PITCH: + attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp); + attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp * 0.01); + attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd); + attitude_control->get_rate_pitch_pid().set_ff(0.0); + attitude_control->get_rate_pitch_pid().set_kDff(0.0); + attitude_control->get_rate_pitch_pid().set_filt_T_hz(0.0); + attitude_control->get_rate_pitch_pid().set_slew_limit(0.0); + attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp); break; - case YAW: - case YAW_D: - 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().ff(0.0f); - if (axis == YAW_D) { - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); + case AxisType::YAW: + case AxisType::YAW_D: + attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp); + attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp * 0.01); + attitude_control->get_rate_yaw_pid().set_ff(0.0); + attitude_control->get_rate_yaw_pid().set_kDff(0.0); + if (axis == AxisType::YAW_D) { + attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd); } else { - attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); + attitude_control->get_rate_yaw_pid().set_kD(0.0); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF); } - attitude_control->get_rate_yaw_pid().filt_T_hz(0.0f); - attitude_control->get_rate_yaw_pid().slew_limit(0.0f); - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); + attitude_control->get_rate_yaw_pid().set_filt_T_hz(0.0); + attitude_control->get_rate_yaw_pid().set_slew_limit(0.0); + attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp); break; } } @@ -372,23 +390,24 @@ void AC_AutoTune_Multi::save_tuning_gains() if (!attitude_control->get_bf_feedforward()) { attitude_control->bf_feedforward_save(true); - attitude_control->save_accel_roll_max_cdss(0.0f); - attitude_control->save_accel_pitch_max_cdss(0.0f); + attitude_control->save_accel_roll_max_cdss(0.0); + attitude_control->save_accel_pitch_max_cdss(0.0); } // sanity check the rate P values if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) { // rate roll gains - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); - attitude_control->get_rate_roll_pid().kD(tune_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_rate_roll_pid().set_kP(tune_roll_rp); + attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); + attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd); + attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff); + attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt); + attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax); attitude_control->get_rate_roll_pid().save_gains(); // stabilize roll - attitude_control->get_angle_roll_p().kP(tune_roll_sp); + attitude_control->get_angle_roll_p().set_kP(tune_roll_sp); attitude_control->get_angle_roll_p().save_gains(); // acceleration roll @@ -399,22 +418,24 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); orig_roll_rd = attitude_control->get_rate_roll_pid().kD(); orig_roll_rff = attitude_control->get_rate_roll_pid().ff(); + orig_roll_dff = attitude_control->get_rate_roll_pid().kDff(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); orig_roll_accel = attitude_control->get_accel_roll_max_cdss(); } if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) { // rate pitch gains - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); - attitude_control->get_rate_pitch_pid().kD(tune_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_rate_pitch_pid().set_kP(tune_pitch_rp); + attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); + attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd); + attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff); + attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt); + attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax); attitude_control->get_rate_pitch_pid().save_gains(); // stabilize pitch - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); + attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp); attitude_control->get_angle_pitch_p().save_gains(); // acceleration pitch @@ -425,6 +446,7 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff(); + orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss(); } @@ -432,21 +454,22 @@ void AC_AutoTune_Multi::save_tuning_gains() if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled()) || ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_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().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().set_kP(tune_yaw_rp); + attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL); + attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff); + attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt); + attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax); if (yaw_d_enabled()) { - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); + attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd); } if (yaw_enabled()) { - attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); + attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF); } attitude_control->get_rate_yaw_pid().save_gains(); // stabilize yaw - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); + attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp); attitude_control->get_angle_yaw_p().save_gains(); // acceleration yaw @@ -457,6 +480,7 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI(); orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff(); + orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff(); orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz(); orig_yaw_sp = attitude_control->get_angle_yaw_p().kP(); orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss(); @@ -473,16 +497,16 @@ void AC_AutoTune_Multi::save_tuning_gains() void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const { switch (test_axis) { - case ROLL: + case AxisType::ROLL: report_axis_gains("Roll", tune_roll_rp, tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL, tune_roll_rd, tune_roll_sp, tune_roll_accel); break; - case PITCH: + case AxisType::PITCH: report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL, tune_pitch_rd, tune_pitch_sp, tune_pitch_accel); break; - case YAW: + case AxisType::YAW: report_axis_gains("Yaw(E)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, 0, tune_yaw_sp, tune_yaw_accel); break; - case YAW_D: + case AxisType::YAW_D: report_axis_gains("Yaw(D)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_sp, tune_yaw_accel); break; } @@ -491,14 +515,14 @@ void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const // report gain formatting helper void AC_AutoTune_Multi::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const { - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.3f, I:%0.3f, D:%0.4f",axis_string,rate_P,rate_I,rate_D); - gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.3f, Max Accel:%0.0f",axis_string,angle_P,max_accel); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.3f, I:%0.3f, D:%0.4f",axis_string,rate_P,rate_I,rate_D); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.3f, Max Accel:%0.0f",axis_string,angle_P,max_accel); } // twitching_test_rate - twitching tests // update min and max and test for end conditions -void AC_AutoTune_Multi::twitching_test_rate(float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max) +void AC_AutoTune_Multi::twitching_test_rate(float angle, float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max, float &meas_angle_min) { const uint32_t now = AP_HAL::millis(); @@ -507,17 +531,19 @@ void AC_AutoTune_Multi::twitching_test_rate(float rate, float rate_target_max, f // the measurement is continuing to increase without stopping meas_rate_max = rate; meas_rate_min = rate; + meas_angle_min = angle; } // capture minimum measurement after the measurement has peaked (aka "bounce back") - if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.5f)) { + if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.25)) { // the measurement is bouncing back meas_rate_min = rate; + meas_angle_min = angle; } - // calculate early stopping time based on the time it takes to get to 75% - if (meas_rate_max < rate_target_max * 0.75f) { - // the measurement not reached the 75% threshold yet + // calculate early stopping time based on the time it takes to get to 63.21% + if (meas_rate_max < rate_target_max * 0.6321) { + // the measurement not reached the 63.21% threshold yet step_time_limit_ms = (now - step_start_time_ms) * 3; step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS); } @@ -527,7 +553,7 @@ void AC_AutoTune_Multi::twitching_test_rate(float rate, float rate_target_max, f step = UPDATE_GAINS; } - if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) { + if (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) { // the measurement has passed 50% of the maximum rate and bounce back is larger than the threshold step = UPDATE_GAINS; } @@ -540,15 +566,22 @@ void AC_AutoTune_Multi::twitching_test_rate(float rate, float rate_target_max, f // twitching_test_rate - twitching tests // update min and max and test for end conditions -void AC_AutoTune_Multi::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min) +void AC_AutoTune_Multi::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min, float angle_min) { if (angle >= angle_max) { - if (is_equal(rate, meas_rate_min) && step_scaler > 0.5f) { + if (is_equal(rate, meas_rate_min) || (angle_min > 0.95 * angle_max)) { // we have reached the angle limit before completing the measurement of maximum and minimum // reduce the maximum target rate - step_scaler *= 0.9f; + if (step_scaler > 0.2f) { + step_scaler *= 0.9f; + } else { + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Twitch Size Determination Failed"); + mode = FAILED; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); + } // ignore result and start test again - step = WAITING_FOR_LEVEL; + step = ABORT; } else { step = UPDATE_GAINS; } @@ -569,7 +602,7 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl } // capture minimum angle after we have reached a reasonable maximum angle - if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.5f)) { + if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.25)) { // the measurement is bouncing back meas_angle_min = angle; } @@ -587,9 +620,9 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl meas_rate_min = rate; } - // calculate early stopping time based on the time it takes to get to 75% - if (meas_angle_max < angle_target_max * 0.75f) { - // the measurement not reached the 75% threshold yet + // calculate early stopping time based on the time it takes to get to 63.21% + if (meas_angle_max < angle_target_max * 0.6321) { + // the measurement not reached the 63.21% threshold yet step_time_limit_ms = (now - step_start_time_ms) * 3; step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS); } @@ -599,7 +632,7 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl step = UPDATE_GAINS; } - if (meas_angle_max-meas_angle_min > meas_angle_max*aggressiveness) { + if (meas_angle_max - meas_angle_min > meas_angle_max * aggressiveness) { // the measurement has passed 50% of the maximum angle and bounce back is larger than the threshold step = UPDATE_GAINS; } @@ -611,11 +644,11 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl } // twitching_measure_acceleration - measure rate of change of measurement -void AC_AutoTune_Multi::twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max) const +void AC_AutoTune_Multi::twitching_measure_acceleration(float &accel_average, float rate, float rate_max) const { - if (rate_measurement_max < rate_measurement) { - rate_measurement_max = rate_measurement; - rate_of_change = (1000.0f*rate_measurement_max)/(AP_HAL::millis() - step_start_time_ms); + if (rate_max < rate) { + rate_max = rate; + accel_average = (1000.0 * rate_max) / (AP_HAL::millis() - step_start_time_ms); } } @@ -623,16 +656,16 @@ void AC_AutoTune_Multi::twitching_measure_acceleration(float &rate_of_change, fl void AC_AutoTune_Multi::updating_rate_p_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: + case AxisType::ROLL: updating_rate_p_up_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case PITCH: + case AxisType::PITCH: updating_rate_p_up_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case YAW: - updating_rate_p_up_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); + case AxisType::YAW: + updating_rate_p_up_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max, false); break; - case YAW_D: + case AxisType::YAW_D: updating_rate_p_up_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; } @@ -642,16 +675,16 @@ void AC_AutoTune_Multi::updating_rate_p_up_all(AxisType test_axis) void AC_AutoTune_Multi::updating_rate_d_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: + case AxisType::ROLL: updating_rate_d_up(tune_roll_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case PITCH: + case AxisType::PITCH: updating_rate_d_up(tune_pitch_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case YAW: + case AxisType::YAW: updating_rate_d_up(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RLPF_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case YAW_D: + case AxisType::YAW_D: updating_rate_d_up(tune_yaw_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; } @@ -661,16 +694,16 @@ void AC_AutoTune_Multi::updating_rate_d_up_all(AxisType test_axis) void AC_AutoTune_Multi::updating_rate_d_down_all(AxisType test_axis) { switch (test_axis) { - case ROLL: + case AxisType::ROLL: updating_rate_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case PITCH: + case AxisType::PITCH: updating_rate_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case YAW: + case AxisType::YAW: updating_rate_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; - case YAW_D: + case AxisType::YAW_D: updating_rate_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max); break; } @@ -680,14 +713,14 @@ void AC_AutoTune_Multi::updating_rate_d_down_all(AxisType test_axis) void AC_AutoTune_Multi::updating_angle_p_up_all(AxisType test_axis) { switch (test_axis) { - case ROLL: + case AxisType::ROLL: updating_angle_p_up(tune_roll_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; - case PITCH: + case AxisType::PITCH: updating_angle_p_up(tune_pitch_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: updating_angle_p_up(tune_yaw_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; } @@ -697,14 +730,14 @@ void AC_AutoTune_Multi::updating_angle_p_up_all(AxisType test_axis) void AC_AutoTune_Multi::updating_angle_p_down_all(AxisType test_axis) { switch (test_axis) { - case ROLL: + case AxisType::ROLL: updating_angle_p_down(tune_roll_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; - case PITCH: + case AxisType::PITCH: updating_angle_p_down(tune_pitch_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: updating_angle_p_down(tune_yaw_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max); break; } @@ -718,19 +751,19 @@ void AC_AutoTune_Multi::set_gains_post_tune(AxisType test_axis) break; case RD_DOWN: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_rd = MAX(min_d, tune_roll_rd * AUTOTUNE_RD_BACKOFF); tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_rd = MAX(min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF); tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF); break; - case YAW: + case AxisType::YAW: tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF); tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF); break; - case YAW_D: + case AxisType::YAW_D: tune_yaw_rd = MAX(min_d, tune_yaw_rd * AUTOTUNE_RD_BACKOFF); tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF); break; @@ -738,14 +771,14 @@ void AC_AutoTune_Multi::set_gains_post_tune(AxisType test_axis) break; case RP_UP: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RP_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF); break; } @@ -754,16 +787,16 @@ void AC_AutoTune_Multi::set_gains_post_tune(AxisType test_axis) break; case SP_UP: switch (test_axis) { - case ROLL: + case AxisType::ROLL: tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF); tune_roll_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF); break; - case PITCH: + case AxisType::PITCH: tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF); tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF); tune_yaw_accel = MAX(AUTOTUNE_Y_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_Y_BACKOFF); break; @@ -787,29 +820,31 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa if (meas_rate_max > rate_target) { // if maximum measurement was higher than target // reduce P gain (which should reduce maximum) - tune_p -= tune_p*tune_p_step_ratio; + tune_p -= tune_p * tune_p_step_ratio; if (tune_p < tune_p_min) { // P gain is at minimum so start reducing D tune_p = tune_p_min; - tune_d -= tune_d*tune_d_step_ratio; + tune_d -= tune_d * tune_d_step_ratio; if (tune_d <= tune_d_min) { // We have reached minimum D gain so stop tuning tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + // This may be mean AGGR should be increased or MIN_D decreased + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached"); } } - } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { + } else if ((meas_rate_max < rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { // we have not achieved a high enough maximum to get a good measurement of bounce back. // increase P gain (which should increase maximum) - tune_p += tune_p*tune_p_step_ratio; + tune_p += tune_p * tune_p_step_ratio; if (tune_p >= tune_p_max) { tune_p = tune_p_max; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { // we have a good measurement of bounce back - if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) { + if (meas_rate_max-meas_rate_min > meas_rate_max * aggressiveness) { // ignore the next result unless it is the same as this one ignore_next = true; // bounce back is bigger than our threshold so increment the success counter @@ -821,7 +856,7 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa counter--; } // increase D gain (which should increase bounce back) - tune_d += tune_d*tune_d_step_ratio*2.0f; + tune_d += tune_d*tune_d_step_ratio * 2.0; // stop tuning if we hit maximum D if (tune_d >= tune_d_max) { tune_d = tune_d_max; @@ -852,19 +887,21 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + // This may be mean AGGR should be increased or MIN_D decreased + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached"); } } - } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { + } else if ((meas_rate_max < rate_target*(1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { // we have not achieved a high enough maximum to get a good measurement of bounce back. // increase P gain (which should increase maximum) - tune_p += tune_p*tune_p_step_ratio; + tune_p += tune_p * tune_p_step_ratio; if (tune_p >= tune_p_max) { tune_p = tune_p_max; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { // we have a good measurement of bounce back - if (meas_rate_max-meas_rate_min < meas_rate_max*aggressiveness) { + if (meas_rate_max - meas_rate_min < meas_rate_max * aggressiveness) { if (ignore_next == false) { // bounce back is less than our threshold so increment the success counter counter++; @@ -879,12 +916,14 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl counter--; } // decrease D gain (which should decrease bounce back) - tune_d -= tune_d*tune_d_step_ratio; + tune_d -= tune_d * tune_d_step_ratio; // stop tuning if we hit minimum D if (tune_d <= tune_d_min) { tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + // This may be mean AGGR should be increased or MIN_D decreased + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached"); } } } @@ -892,34 +931,39 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl // updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing // P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold -void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max) +void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max, bool fail_min_d) { - if (meas_rate_max > rate_target*(1+0.5f*aggressiveness)) { + if (meas_rate_max > rate_target * (1.0 + 0.5 * aggressiveness)) { // ignore the next result unless it is the same as this one ignore_next = true; // if maximum measurement was greater than target so increment the success counter counter++; - } else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) && (tune_d > tune_d_min)) { + } else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) && (tune_d > tune_d_min)) { // if bounce back was larger than the threshold so decrement the success counter if (counter > 0) { counter--; } // decrease D gain (which should decrease bounce back) - tune_d -= tune_d*tune_d_step_ratio; + tune_d -= tune_d * tune_d_step_ratio; // do not decrease the D term past the minimum if (tune_d <= tune_d_min) { tune_d = tune_d_min; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + if (fail_min_d) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate D Gain Determination Failed"); + mode = FAILED; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); + } } // decrease P gain to match D gain reduction - tune_p -= tune_p*tune_p_step_ratio; + tune_p -= tune_p * tune_p_step_ratio; // do not decrease the P term past the minimum if (tune_p <= tune_p_min) { tune_p = tune_p_min; - LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate P Gain Determination Failed"); + mode = FAILED; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); } - // cancel change in direction - positive_direction = !positive_direction; } else { if (ignore_next == false) { // if maximum measurement was lower than target so decrement the success counter @@ -927,7 +971,7 @@ void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_mi counter--; } // increase P gain (which should increase the maximum) - tune_p += tune_p*tune_p_step_ratio; + tune_p += tune_p * tune_p_step_ratio; // stop tuning if we hit maximum P if (tune_p >= tune_p_max) { tune_p = tune_p_max; @@ -944,7 +988,7 @@ void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_mi // P is decreased to ensure we are not overshooting the target void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max) { - if (meas_angle_max < angle_target*(1+0.5f*aggressiveness)) { + if (meas_angle_max < angle_target * (1 + 0.5 * aggressiveness)) { if (ignore_next == false) { // if maximum measurement was lower than target so increment the success counter counter++; @@ -965,6 +1009,9 @@ void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, f tune_p = tune_p_min; counter = AUTOTUNE_SUCCESS_COUNT; LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Angle P Gain Determination Failed"); + mode = FAILED; + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); } } } @@ -973,8 +1020,8 @@ void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, f // P is increased until we achieve our target within a reasonable time void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max) { - if ((meas_angle_max > angle_target*(1+0.5f*aggressiveness)) || - ((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max*aggressiveness))) { + if ((meas_angle_max > angle_target * (1 + 0.5 * aggressiveness)) || + ((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max * aggressiveness))) { // ignore the next result unless it is the same as this one ignore_next = true; // if maximum measurement was greater than target so increment the success counter @@ -986,7 +1033,7 @@ void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, flo counter--; } // increase P gain (which should increase the maximum) - tune_p += tune_p*tune_p_step_ratio; + tune_p += tune_p * tune_p_step_ratio; // stop tuning if we hit maximum P if (tune_p >= tune_p_max) { tune_p = tune_p_max; @@ -1004,31 +1051,31 @@ void AC_AutoTune_Multi::Log_AutoTune() { if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) { switch (axis) { - case ROLL: + case AxisType::ROLL: Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max); break; - case PITCH: + case AxisType::PITCH: Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max); break; - case YAW: + case AxisType::YAW: Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max); break; - case YAW_D: + case AxisType::YAW_D: Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max); break; } } else { switch (axis) { - case ROLL: + case AxisType::ROLL: Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max); break; - case PITCH: + case AxisType::PITCH: Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max); break; - case YAW: + case AxisType::YAW: Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max); break; - case YAW_D: + case AxisType::YAW_D: Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max); break; } @@ -1056,7 +1103,7 @@ void AC_AutoTune_Multi::Log_AutoTuneDetails() // @Field: ddt: maximum measured twitching acceleration // Write an Autotune data packet -void AC_AutoTune_Multi::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt) +void AC_AutoTune_Multi::Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt) { AP::logger().Write( "ATUN", @@ -1067,9 +1114,9 @@ void AC_AutoTune_Multi::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, flo AP_HAL::micros64(), axis, tune_step, - meas_target*0.01f, - meas_min*0.01f, - meas_max*0.01f, + meas_target*0.01, + meas_min*0.01, + meas_max*0.01, new_gain_rp, new_gain_rd, new_gain_sp, @@ -1091,49 +1138,89 @@ void AC_AutoTune_Multi::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds "F00", "Qff", AP_HAL::micros64(), - angle_cd*0.01f, - rate_cds*0.01f); + angle_cd*0.01, + rate_cds*0.01); } #endif // HAL_LOGGING_ENABLED +float AC_AutoTune_Multi::target_angle_max_rp_cd() const +{ + return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE; +} + +float AC_AutoTune_Multi::target_angle_max_y_cd() const +{ + // Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size + return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE; +} + +float AC_AutoTune_Multi::target_angle_min_rp_cd() const +{ + return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE; +} + +float AC_AutoTune_Multi::target_angle_min_y_cd() const +{ + // Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size + return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE; +} + +float AC_AutoTune_Multi::angle_lim_max_rp_cd() const +{ + return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_ABORT_RP_SCALE; +} + +float AC_AutoTune_Multi::angle_lim_neg_rpy_cd() const +{ + return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_NEG_RP_SCALE; +} + void AC_AutoTune_Multi::twitch_test_init() { float target_max_rate; switch (axis) { - case ROLL: { - target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS); - target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate); - target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD); - rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz()*2.0f); + case AxisType::ROLL: + angle_abort = target_angle_max_rp_cd(); + target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS); + target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate); + target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd()); + rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz() * 2.0); break; - } - case PITCH: { - target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS); - target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate); - target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD); - rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz()*2.0f); + + case AxisType::PITCH: + angle_abort = target_angle_max_rp_cd(); + target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS); + target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate); + target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd()); + rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz() * 2.0); break; - } - case YAW: - case YAW_D: { + + case AxisType::YAW: + case AxisType::YAW_D: + angle_abort = target_angle_max_y_cd(); target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS); - target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate); - target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD); - if (axis == YAW_D) { - rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_yaw_pid().filt_D_hz()*2.0f); + target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw() * 0.75) * 100.0, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate); + target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw() * 0.75) * 100.0, target_angle_min_y_cd(), target_angle_max_y_cd()); + if (axis == AxisType::YAW_D) { + rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_yaw_pid().filt_D_hz() * 2.0); } else { rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ); } break; } - } if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) { + // todo: consider if this should be done for other axis rotation_rate_filt.reset(start_rate); } else { - rotation_rate_filt.reset(0); + rotation_rate_filt.reset(0.0); } - + twitch_first_iter = true; + test_rate_max = 0.0; + test_rate_min = 0.0; + test_angle_max = 0.0; + test_angle_min = 0.0; + accel_measure_rate_max = 0.0; } //run twitch test @@ -1142,7 +1229,6 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign // disable rate limits attitude_control->use_sqrt_controller(false); // hold current attitude - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) { // step angle targets on first iteration @@ -1150,38 +1236,40 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign twitch_first_iter = false; // Testing increasing stabilize P gain so will set lean angle target switch (test_axis) { - case ROLL: + case AxisType::ROLL: // request roll to 20deg - attitude_control->input_angle_step_bf_roll_pitch_yaw(dir_sign * target_angle, 0.0f, 0.0f); + attitude_control->input_angle_step_bf_roll_pitch_yaw(dir_sign * target_angle, 0.0, 0.0); break; - case PITCH: + case AxisType::PITCH: // request pitch to 20deg - attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, dir_sign * target_angle, 0.0f); + attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, dir_sign * target_angle, 0.0); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: // request yaw to 20deg - attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, 0.0f, dir_sign * target_angle); + attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, 0.0, dir_sign * target_angle); break; - } + } + } else { + attitude_control->input_rate_bf_roll_pitch_yaw(0.0, 0.0, 0.0); } } else { // Testing rate P and D gains so will set body-frame rate targets. // Rate controller will use existing body-frame rates and convert to motor outputs // for all axes except the one we override here. switch (test_axis) { - case ROLL: + case AxisType::ROLL: // override body-frame roll rate - attitude_control->rate_bf_roll_target(dir_sign * target_rate + start_rate); + attitude_control->input_rate_step_bf_roll_pitch_yaw(dir_sign * target_rate + start_rate, 0.0f, 0.0f); break; - case PITCH: + case AxisType::PITCH: // override body-frame pitch rate - attitude_control->rate_bf_pitch_target(dir_sign * target_rate + start_rate); + attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, dir_sign * target_rate + start_rate, 0.0f); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: // override body-frame yaw rate - attitude_control->rate_bf_yaw_target(dir_sign * target_rate + start_rate); + attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, 0.0f, dir_sign * target_rate + start_rate); break; } } @@ -1189,16 +1277,16 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign // capture this iteration's rotation rate and lean angle float gyro_reading = 0; switch (test_axis) { - case ROLL: + case AxisType::ROLL: gyro_reading = ahrs_view->get_gyro().x; lean_angle = dir_sign * (ahrs_view->roll_sensor - (int32_t)start_angle); break; - case PITCH: + case AxisType::PITCH: gyro_reading = ahrs_view->get_gyro().y; lean_angle = dir_sign * (ahrs_view->pitch_sensor - (int32_t)start_angle); break; - case YAW: - case YAW_D: + case AxisType::YAW: + case AxisType::YAW_D: gyro_reading = ahrs_view->get_gyro().z; lean_angle = dir_sign * wrap_180_cd(ahrs_view->yaw_sensor-(int32_t)start_angle); break; @@ -1209,10 +1297,10 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign switch (tune_type) { case SP_DOWN: case SP_UP: - filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0f); + filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0); break; default: - filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0f - start_rate); + filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0 - start_rate); break; } rotation_rate = rotation_rate_filt.apply(filter_value, @@ -1221,19 +1309,19 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign switch (tune_type) { case RD_UP: case RD_DOWN: - twitching_test_rate(rotation_rate, target_rate, test_rate_min, test_rate_max); - twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max); - twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min); + twitching_test_rate(lean_angle, rotation_rate, target_rate, test_rate_min, test_rate_max, test_angle_min); + twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max); + twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min); break; case RP_UP: - twitching_test_rate(rotation_rate, target_rate*(1+0.5f*aggressiveness), test_rate_min, test_rate_max); - twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max); - twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min); + twitching_test_rate(lean_angle, rotation_rate, target_rate * (1 + 0.5 * aggressiveness), test_rate_min, test_rate_max, test_angle_min); + twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max); + twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min); break; case SP_DOWN: case SP_UP: - twitching_test_angle(lean_angle, rotation_rate, target_angle*(1+0.5f*aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max); - twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, rate_max); + twitching_test_angle(lean_angle, rotation_rate, target_angle * (1 + 0.5 * aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max); + twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, accel_measure_rate_max); break; case RFF_UP: case MAX_GAINS: diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.h b/libraries/AC_AutoTune/AC_AutoTune_Multi.h index ac2a0c6892a0e0..e89dd4c5893c5c 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.h @@ -63,6 +63,18 @@ class AC_AutoTune_Multi : public AC_AutoTune // reset the update gain variables for multi void reset_update_gain_variables() override {}; + float target_angle_max_rp_cd() const override; + + float target_angle_max_y_cd() const override; + + float target_angle_min_rp_cd() const override; + + float target_angle_min_y_cd() const override; + + float angle_lim_max_rp_cd() const override; + + float angle_lim_neg_rpy_cd() const override; + void test_init() override; void test_run(AxisType test_axis, const float dir_sign) override; @@ -115,7 +127,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // this should never happen INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } - void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); + void Log_Write_AutoTune(AxisType axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds); #endif @@ -139,12 +151,12 @@ class AC_AutoTune_Multi : public AC_AutoTune void twitch_test_init(); void twitch_test_run(AxisType test_axis, const float dir_sign); - void twitching_test_rate(float rate, float rate_target, float &meas_rate_min, float &meas_rate_max); - void twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min); + void twitching_test_rate(float angle, float rate, float rate_target, float &meas_rate_min, float &meas_rate_max, float &meas_angle_min); + void twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min, float angle_min); void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max); // measure acceleration during twitch test - void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max) const; + void twitching_measure_acceleration(float &accel_average, float rate, float rate_max) const; // updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back // optimize D term while keeping the maximum just below the target by adjusting P @@ -156,7 +168,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing // P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold - void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max); + void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max, bool fail_min_d = true); // updating_angle_p_down - decrease P until we don't reach the target before time out // P is decreased to ensure we are not overshooting the target @@ -170,9 +182,18 @@ class AC_AutoTune_Multi : public AC_AutoTune void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const; // parameters - AP_Int8 axis_bitmask; // axes to be tuned - AP_Float aggressiveness; // aircraft response aggressiveness to be tuned - AP_Float min_d; // minimum rate d gain allowed during tuning + AP_Int8 axis_bitmask; // axes to be tuned + AP_Float aggressiveness; // aircraft response aggressiveness to be tuned + AP_Float min_d; // minimum rate d gain allowed during tuning + bool ignore_next; // ignore the results of the next test when true + float target_angle; // target angle for the test + float target_rate; // target rate for the test + float angle_abort; // Angle that test is aborted + float test_rate_min; // the minimum angular rate achieved during TESTING_RATE + float test_rate_max; // the maximum angular rate achieved during TESTING_RATE + float test_angle_min; // the minimum angle achieved during TESTING_ANGLE + float test_angle_max; // the maximum angle achieved during TESTING_ANGLE + float accel_measure_rate_max; // the maximum rate used to measure average acceleration during twitch }; #endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 627dd7894ec317..1dbcccd29423ad 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -3,9 +3,7 @@ #include #include -//Autorotation controller defaults -#define AROT_BAIL_OUT_TIME 2.0f // Default time for bail out controller to run (unit: s) - +// Autorotation controller defaults // Head Speed (HS) controller specific default definitions #define HS_CONTROLLER_COLLECTIVE_CUTOFF_FREQ 2.0f // low-pass filter on accel error (unit: hz) #define HS_CONTROLLER_HEADSPEED_P 0.7f // Default P gain for head speed controller (unit: -) @@ -81,15 +79,6 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @User: Advanced AP_GROUPINFO("AS_ACC_MAX", 7, AC_Autorotation, _param_accel_max, FWD_SPD_CONTROLLER_MAX_ACCEL), - // @Param: BAIL_TIME - // @DisplayName: Bail Out Timer - // @Description: Time in seconds from bail out initiated to the exit of autorotation flight mode. - // @Units: s - // @Range: 0.5 4 - // @Increment: 0.1 - // @User: Advanced - AP_GROUPINFO("BAIL_TIME", 8, AC_Autorotation, _param_bail_time, AROT_BAIL_OUT_TIME), - // @Param: HS_SENSOR // @DisplayName: Main Rotor RPM Sensor // @Description: Allocate the RPM sensor instance to use for measuring head speed. RPM1 = 0. RPM2 = 1. @@ -97,7 +86,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @Range: 0.5 3 // @Increment: 0.1 // @User: Advanced - AP_GROUPINFO("HS_SENSOR", 9, AC_Autorotation, _param_rpm_instance, 0), + AP_GROUPINFO("HS_SENSOR", 8, AC_Autorotation, _param_rpm_instance, 0), // @Param: FW_V_P // @DisplayName: Velocity (horizontal) P gain @@ -105,7 +94,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @Range: 0.1 6.0 // @Increment: 0.1 // @User: Advanced - AP_SUBGROUPINFO(_p_fw_vel, "FW_V_", 10, AC_Autorotation, AC_P), + AP_SUBGROUPINFO(_p_fw_vel, "FW_V_", 9, AC_Autorotation, AC_P), // @Param: FW_V_FF // @DisplayName: Velocity (horizontal) feed forward @@ -113,7 +102,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @Range: 0 1 // @Increment: 0.01 // @User: Advanced - AP_GROUPINFO("FW_V_FF", 11, AC_Autorotation, _param_fwd_k_ff, AP_FW_VEL_FF), + AP_GROUPINFO("FW_V_FF", 10, AC_Autorotation, _param_fwd_k_ff, AP_FW_VEL_FF), AP_GROUPEND }; diff --git a/libraries/AC_Autorotation/AC_Autorotation.h b/libraries/AC_Autorotation/AC_Autorotation.h index d5cfa52097b3f1..612986662ecf47 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.h +++ b/libraries/AC_Autorotation/AC_Autorotation.h @@ -28,7 +28,6 @@ class AC_Autorotation int16_t get_hs_set_point(void) { return _param_head_speed_set_point; } float get_col_entry_freq(void) { return _param_col_entry_cutoff_freq; } float get_col_glide_freq(void) { return _param_col_glide_cutoff_freq; } - float get_bail_time(void) { return _param_bail_time; } float get_last_collective() const { return _collective_out; } bool is_enable(void) { return _param_enable; } void Log_Write_Autorotation(void) const; @@ -81,7 +80,6 @@ class AC_Autorotation AP_Float _param_col_entry_cutoff_freq; AP_Float _param_col_glide_cutoff_freq; AP_Int16 _param_accel_max; - AP_Float _param_bail_time; AP_Int8 _param_rpm_instance; AP_Float _param_fwd_k_ff; diff --git a/libraries/AC_Autorotation/RSC_Autorotation.cpp b/libraries/AC_Autorotation/RSC_Autorotation.cpp new file mode 100644 index 00000000000000..53992de1a0467e --- /dev/null +++ b/libraries/AC_Autorotation/RSC_Autorotation.cpp @@ -0,0 +1,159 @@ +#include "RSC_Autorotation.h" +#include +#include + +#define RSC_AROT_RAMP_TIME_DEFAULT 2 // time in seconds to ramp motors when bailing out of autorotation + +extern const AP_HAL::HAL& hal; + +// RSC autorotation state specific parameters +const AP_Param::GroupInfo RSC_Autorotation::var_info[] = { + + // @Param: ENBL + // @DisplayName: Enable autorotation handling in RSC + // @Description: Allows you to enable (1) or disable (0) the autorotation functionality within the Rotor Speed Controller. + // @Values: 0:Disabled,1:Enabled + // @User: Standard + AP_GROUPINFO_FLAGS("ENBL", 1, RSC_Autorotation, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: RAMP + // @DisplayName: Time for in-flight power re-engagement when exiting autorotations + // @Description: When exiting an autorotation in a bailout manoeuvre, this is the time in seconds for the throttle output (HeliRSC servo) to ramp from idle (H_RSC_AROT_IDLE) to flight throttle setting when motor interlock is re-enabled. When using an ESC with an autorotation bailout function, this parameter should be set to 0.1 (minimum value). + // @Range: 0.1 10 + // @Units: s + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("RAMP", 2, RSC_Autorotation, bailout_throttle_time, RSC_AROT_RAMP_TIME_DEFAULT), + + // @Param: IDLE + // @DisplayName: Idle throttle percentage during autorotation + // @Description: Idle throttle used for during autotoration. For external governors, this would be set to a value that is within the autorotation window of the governer/ESC to enable fast spool-up, when bailing out of an autorotation. Set 0 to disable. + // @Range: 0 40 + // @Units: % + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("IDLE", 3, RSC_Autorotation, idle_output, 0.0), + + // @Param: RUNUP + // @DisplayName: Time allowed for in-flight power re-engagement + // @Description: When exiting an autorotation in a bailout manoeuvre, this is the expected time in seconds for the main rotor to reach full speed after motor interlock is enabled. Must be at least one second longer than the H_RSC_AROT_RAMP time that is set. This timer should be set for at least the amount of time it takes to get your helicopter to full flight power. Failure to heed this warning could result in early entry into autonomously controlled collective modes (e.g. alt hold, loiter, etc), whereby the collective could be raised before the engine has reached full power, with a subsequently dangerous slowing of head speed. + // @Range: 1 10 + // @Units: s + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("RUNUP", 4, RSC_Autorotation, bailout_runup_time, RSC_AROT_RAMP_TIME_DEFAULT+1), + + AP_GROUPEND +}; + +RSC_Autorotation::RSC_Autorotation(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// set the desired autorotation state +// this state machine handles the transition from active to deactivated via the bailout logic +// to force the state to be immediately deactivated, then the force_state bool is used +void RSC_Autorotation::set_active(bool active, bool force_state) +{ + if (enable.get() != 1) { + return; + } + + // set the desired state based on the bool. We only set either ACTIVE or DEACTIVATED + // here and let the autorotation state machine and RSC runup code handle the bail out case + RSC_Autorotation::State desired_state = active ? RSC_Autorotation::State::ACTIVE : RSC_Autorotation::State::DEACTIVATED; + + // don't do anything if desired state is already set + if (desired_state == state) { + return; + } + + // Handle the transition from the ACTIVE to DEACTIVATED states via the BAILING_OUT case + // set the bailout case if deactivated has just been requested + if ((state == State::ACTIVE) && (desired_state == State::DEACTIVATED) && !force_state) { + desired_state = State::BAILING_OUT; + bail_out_started_ms = AP_HAL::millis(); + } + + // Wait for allocated autorotation run up time before we allow progression of state to deactivated + if ((state == State::BAILING_OUT) && + (desired_state == State::DEACTIVATED) && + (bail_out_started_ms > 0) && + (AP_HAL::millis() - bail_out_started_ms < uint32_t(get_runup_time()*1000))) + { + return; + } + + // handle GCS messages + switch (desired_state) + { + case State::DEACTIVATED: + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "RSC: Autorotation Stopped"); + break; + + case State::BAILING_OUT: + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "RSC: Bailing Out"); + break; + + case State::ACTIVE: + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "RSC: In Autorotation"); + break; + + default: + // do nothing + break; + } + + // Actually set the state + state = desired_state; +} + +bool RSC_Autorotation::get_idle_throttle(float& idle_throttle) +{ + if (state != State::ACTIVE) { + // We do not want to use autorotation idle throttle + return false; + } + + if (idle_output.get() <= 0) { + // If autorotation idle is not set, do not modify idle throttle as we just use H_RSC_IDLE + // Heli with an ICE engine is an example of this type of config + return true; + } + + // if we are autorotating and the autorotation idle throttle param is set we want to + // to output this as the idle throttle for ESCs with an autorotation window + idle_throttle = constrain_float(idle_output.get()*0.01, 0.0, 0.4); + + return true; +} + +float RSC_Autorotation::get_bailout_ramp(void) const +{ + // Allow ramp times as quick as 0.1 of a second for ESCs with autorotation windows + return MAX(float(bailout_throttle_time.get()), 0.1); +} + +float RSC_Autorotation::get_runup_time(void) const +{ + // If we are in the autorotation state we want the rotor speed model to ramp down rapidly to zero, ensuring we get past + // the critical rotor speed, and therefore triggering a proper bailout should we re-engage the interlock at any point + if (state == State::ACTIVE) { + return 0.1; + } + + // Never let the runup timer be less than the throttle ramp time + return (float) MAX(bailout_throttle_time.get() + 1, bailout_runup_time.get()); +} + +// sanity check of parameters, should be called only whilst disarmed +bool RSC_Autorotation::arming_checks(size_t buflen, char *buffer) const +{ + // throttle runup must be larger than ramp, keep the params up to date to not confuse users + if (bailout_throttle_time.get() + 1 > bailout_runup_time.get()) { + hal.util->snprintf(buffer, buflen, "H_RSC_AROT_RUNUP must be > H_RSC_AROT_RAMP"); + return false; + } + return true; +} diff --git a/libraries/AC_Autorotation/RSC_Autorotation.h b/libraries/AC_Autorotation/RSC_Autorotation.h new file mode 100644 index 00000000000000..8c0bd230a7849f --- /dev/null +++ b/libraries/AC_Autorotation/RSC_Autorotation.h @@ -0,0 +1,52 @@ +// Class supporting autorotation state within the heli rotor speed controller + +#pragma once + +#include + +// helper class to manage autorotation state and variables within RSC +class RSC_Autorotation +{ +public: + + RSC_Autorotation(void); + + enum class State { + DEACTIVATED, + BAILING_OUT, + ACTIVE, + }; + + // state accessors + bool active(void) const { return state == State::ACTIVE; } + bool bailing_out(void) const { return state == State::BAILING_OUT; } + + // update idle throttle when in autorotation + bool get_idle_throttle(float& idle_throttle); + + // get the throttle ramp rate needed when bailing out of autorotation + float get_bailout_ramp(void) const; + + // get the allowed run-up time that we expect the rotor to need to complete a bailout + float get_runup_time(void) const; + + // request changes in autorotation state + void set_active(bool active, bool force_state); + + // sanity check of parameters, should be called only whilst disarmed + bool arming_checks(size_t buflen, char *buffer) const; + + // var_info for holding Parameter information + static const struct AP_Param::GroupInfo var_info[]; + +private: + + AP_Int8 idle_output; // (percent) rsc output used when in autorotation, used for setting autorotation window on ESCs + AP_Int8 bailout_throttle_time; // (seconds) time for in-flight power re-engagement when bailing-out of an autorotation + AP_Int8 bailout_runup_time; // (seconds) expected time for the motor to fully engage and for the rotor to regain safe head speed if necessary + AP_Int8 enable; // enables autorotation state within the RSC + + State state; + uint32_t bail_out_started_ms; // (milliseconds) time that bailout started, used to time transition from "bailing out" to "autorotation stopped" + +}; diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index f508d59484ca77..6169ad161d1fe1 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -80,12 +80,12 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { 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 - // @Description: Maximum speed that will be used to back away from obstacles in GPS modes (m/s). Set zero to disable + // @DisplayName: Avoidance maximum horizontal backup speed + // @Description: Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup. // @Units: m/s // @Range: 0 2 // @User: Standard - AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_max, 0.75f), + AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_xy_max, 0.75f), // @Param{Copter}: ALT_MIN // @DisplayName: Avoidance minimum altitude @@ -111,6 +111,14 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { // @User: Standard AP_GROUPINFO("BACKUP_DZ", 9, AC_Avoid, _backup_deadzone, 0.10f), + // @Param: BACKZ_SPD + // @DisplayName: Avoidance maximum vertical backup speed + // @Description: Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup. + // @Units: m/s + // @Range: 0 2 + // @User: Standard + AP_GROUPINFO("BACKZ_SPD", 10, AC_Avoid, _backup_speed_z_max, 0.75), + AP_GROUPEND }; @@ -224,14 +232,12 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa const float desired_backup_vel_z = back_vel_down + back_vel_up; Vector3f desired_backup_vel{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z}; - const float max_back_spd_cms = _backup_speed_max * 100.0f; - if (!desired_backup_vel.is_zero() && is_positive(max_back_spd_cms)) { + const float max_back_spd_xy_cms = _backup_speed_xy_max * 100.0; + if (!desired_backup_vel.xy().is_zero() && is_positive(max_back_spd_xy_cms)) { backing_up = true; - // Constrain backing away speed - if (desired_backup_vel.length() > max_back_spd_cms) { - desired_backup_vel = desired_backup_vel.normalized() * max_back_spd_cms; - } - + // Constrain horizontal backing away speed + desired_backup_vel.xy().limit_length(max_back_spd_xy_cms); + // let user take control if they are backing away at a greater speed than what we have calculated // this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y". if (!is_zero(desired_backup_vel.x)) { @@ -248,6 +254,15 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa desired_vel_cms.y = MIN(desired_vel_cms.y, desired_backup_vel.y); } } + } + + const float max_back_spd_z_cms = _backup_speed_z_max * 100.0; + if (!is_zero(desired_backup_vel.z) && is_positive(max_back_spd_z_cms)) { + backing_up = true; + + // Constrain vertical backing away speed + desired_backup_vel.z = constrain_float(desired_backup_vel.z, -max_back_spd_z_cms, max_back_spd_z_cms); + if (!is_zero(desired_backup_vel.z)) { if (is_positive(desired_backup_vel.z)) { desired_vel_cms.z = MAX(desired_vel_cms.z, desired_backup_vel.z); @@ -256,6 +271,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa } } } + // limit acceleration limit_accel(desired_vel_cms_original, desired_vel_cms, dt); @@ -353,6 +369,19 @@ void AC_Avoid::adjust_speed(float kP, float accel, float heading, float &speed, } } +// adjust vertical climb rate so vehicle does not break the vertical fence +void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt) { + float backup_speed = 0.0f; + adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed, dt); + if (!is_zero(backup_speed)) { + if (is_negative(backup_speed)) { + climb_rate_cms = MIN(climb_rate_cms, backup_speed); + } else { + climb_rate_cms = MAX(climb_rate_cms, backup_speed); + } + } +} + // adjust vertical climb rate so vehicle does not break the vertical fence void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt) { @@ -363,29 +392,36 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c return; } - // do not adjust climb_rate if level or descending - if (climb_rate_cms <= 0.0f) { + // do not adjust climb_rate if level + if (is_zero(climb_rate_cms)) { return; } + const AP_AHRS &_ahrs = AP::ahrs(); // limit acceleration const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX); - bool limit_alt = false; - float alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit) - - const AP_AHRS &_ahrs = AP::ahrs(); - + bool limit_min_alt = false; + bool limit_max_alt = false; + float max_alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit) + float min_alt_diff = 0.0f; #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) { + if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0 && fence) { // calculate distance from vehicle to safe altitude float veh_alt; _ahrs.get_relative_position_D_home(veh_alt); - // _fence.get_safe_alt_max() is UP, veh_alt is DOWN: - alt_diff = fence->get_safe_alt_max() + veh_alt; - limit_alt = true; + if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) > 0) { + // fence.get_safe_alt_max() is UP, veh_alt is DOWN: + min_alt_diff = -(fence->get_safe_alt_min() + veh_alt); + limit_min_alt = true; + } + if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) { + // fence.get_safe_alt_max() is UP, veh_alt is DOWN: + max_alt_diff = fence->get_safe_alt_max() + veh_alt; + limit_max_alt = true; + } } #endif @@ -397,9 +433,9 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c _ahrs.get_relative_position_D_origin(curr_alt)) { // alt_limit is UP, curr_alt is DOWN: const float ctrl_alt_diff = alt_limit + curr_alt; - if (!limit_alt || ctrl_alt_diff < alt_diff) { - alt_diff = ctrl_alt_diff; - limit_alt = true; + if (!limit_max_alt || ctrl_alt_diff < max_alt_diff) { + max_alt_diff = ctrl_alt_diff; + limit_max_alt = true; } } @@ -409,28 +445,52 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c AP_Proximity *proximity = AP::proximity(); if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff)) { proximity_alt_diff -= _margin; - if (!limit_alt || proximity_alt_diff < alt_diff) { - alt_diff = proximity_alt_diff; - limit_alt = true; + if (!limit_max_alt || proximity_alt_diff < max_alt_diff) { + max_alt_diff = proximity_alt_diff; + limit_max_alt = true; } } #endif // limit climb rate - if (limit_alt) { + if (limit_max_alt || limit_min_alt) { + const float max_back_spd_cms = _backup_speed_z_max * 100.0; // do not allow climbing if we've breached the safe altitude - if (alt_diff <= 0.0f) { + if (max_alt_diff <= 0.0f && limit_max_alt) { climb_rate_cms = MIN(climb_rate_cms, 0.0f); // also calculate backup speed that will get us back to safe altitude - backup_speed = -1*(get_max_speed(kP, accel_cmss_limited, -alt_diff*100.0f, dt)); + if (is_positive(max_back_spd_cms)) { + backup_speed = -1*(get_max_speed(kP, accel_cmss_limited, -max_alt_diff*100.0f, dt)); + + // Constrain to max backup speed + backup_speed = MAX(backup_speed, -max_back_spd_cms); + } + return; + // do not allow descending if we've breached the safe altitude + } else if (min_alt_diff <= 0.0f && limit_min_alt) { + climb_rate_cms = MAX(climb_rate_cms, 0.0f); + // also calculate backup speed that will get us back to safe altitude + if (is_positive(max_back_spd_cms)) { + backup_speed = get_max_speed(kP, accel_cmss_limited, -min_alt_diff*100.0f, dt); + + // Constrain to max backup speed + backup_speed = MIN(backup_speed, max_back_spd_cms); + } return; } // limit climb rate - const float max_speed = get_max_speed(kP, accel_cmss_limited, alt_diff*100.0f, dt); - climb_rate_cms = MIN(max_speed, climb_rate_cms); + if (limit_max_alt) { + const float max_alt_max_speed = get_max_speed(kP, accel_cmss_limited, max_alt_diff*100.0f, dt); + climb_rate_cms = MIN(max_alt_max_speed, climb_rate_cms); + } + + if (limit_min_alt) { + const float max_alt_min_speed = get_max_speed(kP, accel_cmss_limited, min_alt_diff*100.0f, dt); + climb_rate_cms = MAX(-max_alt_min_speed, climb_rate_cms); + } } -# endif +#endif } // adjust roll-pitch to push vehicle away from objects diff --git a/libraries/AC_Avoidance/AC_Avoid.h b/libraries/AC_Avoidance/AC_Avoid.h index 0d99b5e1977d54..aae55725ec1a14 100644 --- a/libraries/AC_Avoidance/AC_Avoid.h +++ b/libraries/AC_Avoidance/AC_Avoid.h @@ -68,14 +68,7 @@ class AC_Avoid { // adjust vertical climb rate so vehicle does not break the vertical fence void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt); - void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt) { - float backup_speed = 0.0f; - adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed, dt); - if (!is_zero(backup_speed)) { - climb_rate_cms = MIN(climb_rate_cms, backup_speed); - } - } - + void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt); // adjust roll-pitch to push vehicle away from objects // roll and pitch value are in centi-degrees @@ -211,14 +204,15 @@ class AC_Avoid { // parameters AP_Int8 _enabled; - AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes) - AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes - AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes - AP_Int8 _behavior; // avoidance behaviour (slide or stop) - AP_Float _backup_speed_max; // Maximum speed that will be used to back away (in m/s) - AP_Float _alt_min; // alt below which Proximity based avoidance is turned off - AP_Float _accel_max; // maximum acceleration while simple avoidance is active - AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles + AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes) + AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes + AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes + AP_Int8 _behavior; // avoidance behaviour (slide or stop) + AP_Float _backup_speed_xy_max; // Maximum speed that will be used to back away horizontally (in m/s) + AP_Float _backup_speed_z_max; // Maximum speed that will be used to back away verticality (in m/s) + AP_Float _alt_min; // alt below which Proximity based avoidance is turned off + AP_Float _accel_max; // maximum acceleration while simple avoidance is active + AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable) bool _proximity_alt_enabled = true; // true if proximity sensor based avoidance is enabled based on altitude diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index 20bc48f594807b..ac3c7d02c1042d 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -190,7 +190,7 @@ void AP_OADatabase::init_queue() return; } - _queue.items = new ObjectBuffer(_queue.size); + _queue.items = NEW_NOTHROW ObjectBuffer(_queue.size); if (_queue.items != nullptr && _queue.items->get_size() == 0) { // allocation failed delete _queue.items; @@ -205,7 +205,7 @@ void AP_OADatabase::init_database() return; } - _database.items = new OA_DbItem[_database.size]; + _database.items = NEW_NOTHROW OA_DbItem[_database.size]; } // get bitmask of gcs channels item should be sent to based on its importance diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index e2cd63ec4d1e31..efe5c240511e31 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -34,12 +34,12 @@ /// Constructor AP_OADijkstra::AP_OADijkstra(AP_Int16 &options) : - _options(options), _inclusion_polygon_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK), _exclusion_polygon_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK), _exclusion_circle_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK), _short_path_data(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK), - _path(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK) + _path(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK), + _options(options) { } diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index a702ed6de52e12..a7aa671190b96c 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -92,25 +92,25 @@ void AP_OAPathPlanner::init() return; case OA_PATHPLAN_BENDYRULER: if (_oabendyruler == nullptr) { - _oabendyruler = new AP_OABendyRuler(); + _oabendyruler = NEW_NOTHROW AP_OABendyRuler(); AP_Param::load_object_from_eeprom(_oabendyruler, AP_OABendyRuler::var_info); } break; case OA_PATHPLAN_DIJKSTRA: #if AP_FENCE_ENABLED if (_oadijkstra == nullptr) { - _oadijkstra = new AP_OADijkstra(_options); + _oadijkstra = NEW_NOTHROW AP_OADijkstra(_options); } #endif break; case OA_PATHPLAN_DJIKSTRA_BENDYRULER: #if AP_FENCE_ENABLED if (_oadijkstra == nullptr) { - _oadijkstra = new AP_OADijkstra(_options); + _oadijkstra = NEW_NOTHROW AP_OADijkstra(_options); } #endif if (_oabendyruler == nullptr) { - _oabendyruler = new AP_OABendyRuler(); + _oabendyruler = NEW_NOTHROW AP_OABendyRuler(); AP_Param::load_object_from_eeprom(_oabendyruler, AP_OABendyRuler::var_info); } break; diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp index 903d854c127a92..407b9db249b4a4 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -55,11 +55,11 @@ void AC_CustomControl::init(void) 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 = NEW_NOTHROW 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 = NEW_NOTHROW AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt); _backend_var_info[get_type()] = AC_CustomControl_PID::var_info; break; default: diff --git a/libraries/AC_CustomControl/AC_CustomControl_Backend.h b/libraries/AC_CustomControl/AC_CustomControl_Backend.h index 391353585ae4fa..10dfb4b41bbcd4 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Backend.h +++ b/libraries/AC_CustomControl/AC_CustomControl_Backend.h @@ -10,10 +10,10 @@ class AC_CustomControl_Backend { public: AC_CustomControl_Backend(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) : - _frontend(frontend), _ahrs(ahrs), _att_control(att_control), - _motors(motors) + _motors(motors), + _frontend(frontend) {} // empty destructor to suppress compiler warning diff --git a/libraries/AC_CustomControl/README.md b/libraries/AC_CustomControl/README.md index 2d2d4a892d1350..771f3b4e839179 100644 --- a/libraries/AC_CustomControl/README.md +++ b/libraries/AC_CustomControl/README.md @@ -217,6 +217,13 @@ default: return; } ``` +Add the following lines in the `AC_CustomControl_config.h` file. + +``` +#ifndef AP_CUSTOMCONTROL_XYZ_ENABLED +#define AP_CUSTOMCONTROL_XYZ_ENABLED AP_CUSTOMCONTROL_BACKEND_DEFAULT_ENABLED +#endif +``` 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. diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index 04a238196f58fe..db214b2e494e17 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -36,26 +36,30 @@ extern const AP_HAL::HAL& hal; #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 100m further out +#define AC_FENCE_OPTIONS_DEFAULT OPTIONS::DISABLE_MODE_CHANGE #else #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out +#define AC_FENCE_OPTIONS_DEFAULT 0 #endif +//#define AC_FENCE_DEBUG const AP_Param::GroupInfo AC_Fence::var_info[] = { + // @Param: ENABLE // @DisplayName: Fence enable/disable - // @Description: Allows you to enable (1) or disable (0) the fence functionality + // @Description: Allows you to enable (1) or disable (0) the fence functionality. Fences can still be enabled and disabled via mavlink or an RC option, but these changes are not persisted. // @Values: 0:Disabled,1:Enabled // @User: Standard AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0), // @Param: TYPE // @DisplayName: Fence Type - // @Description: Enabled fence types held as bitmask + // @Description: Configured fence types held as bitmask. Max altitide, Circle and Polygon fences will be immediately enabled if configured. Min altitude fence will only be enabled once the minimum altitude is reached. // @Bitmask{Rover}: 1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons // @Bitmask{Copter, Plane, Sub}: 0:Max altitude,1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons,3:Min altitude // @User: Standard - AP_GROUPINFO("TYPE", 1, AC_Fence, _enabled_fences, AC_FENCE_TYPE_DEFAULT), + AP_GROUPINFO("TYPE", 1, AC_Fence, _configured_fences, AC_FENCE_TYPE_DEFAULT), // @Param: ACTION // @DisplayName: Fence Action @@ -126,21 +130,21 @@ 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{Plane}: AUTOENABLE + // @Param{Plane, Copter}: AUTOENABLE // @DisplayName: Fence Auto-Enable - // @Description: Auto-enable of fences. AutoEnableOnTakeoff enables all configured fences after autotakeoffs reach altitude. During autolandings the fences will be disabled. AutoEnableDisableFloorOnLanding enables all configured fences after autotakeoffs reach altitude. During autolandings only the Minimum Altitude fence will be disabled. AutoEnableOnlyWhenArmed enables all configured fences, but no fences are disabled during autolandings. However, fence breaches are ignored while executing prior breach recovery actions which may include autolandings. - // @Values: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed + // @Description: Auto-enable of fences. AutoEnableOnTakeoff enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings the fences will be disabled. AutoEnableDisableFloorOnLanding enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings only the Minimum Altitude fence will be disabled. AutoEnableOnlyWhenArmed enables all configured fences on arming, except the minimum altitude fence (which is enabled when the minimum altitude is reached), but no fences are disabled during autolandings. However, fence breaches are ignored while executing prior breach recovery actions which may include autolandings. + // @Values{Plane, Copter}: 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), + AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI), - // @Param{Plane}: OPTIONS + // @Param{Plane, Copter}: OPTIONS // @DisplayName: Fence options - // @Description: 0:Disable mode change following fence action until fence breach is cleared. When bit 1 is set the allowable flight areas is the union of all polygon and circle fence areas instead of the intersection, which means a fence breach occurs only if you are outside all of the fence areas. + // @Description: When bit 0 is set sisable mode change following fence action until fence breach is cleared. When bit 1 is set the allowable flight areas is the union of all polygon and circle fence areas instead of the intersection, which means a fence breach occurs only if you are outside all of the fence areas. // @Bitmask: 0:Disable mode change following fence action until fence breach is cleared, 1:Allow union of inclusion areas // @User: Standard - AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast(OPTIONS::DISABLE_MODE_CHANGE), AP_PARAM_FRAME_PLANE), + AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast(AC_FENCE_OPTIONS_DEFAULT), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI), AP_GROUPEND }; @@ -155,49 +159,167 @@ AC_Fence::AC_Fence() #endif _singleton = this; AP_Param::setup_object_defaults(this, var_info); + if (_enabled) { + _enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN; + } +} + +// get a user-friendly list of fences +void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg) +{ + if (!fences) { + return; + } + static const char* FENCE_NAMES[] = { + "Max Alt", + "Circle", + "Polygon", + "Min Alt", + }; + uint8_t i = 0; + uint8_t nfences = 0; + while (fences !=0) { + if (fences & 0x1) { + if (nfences > 0) { + if (!(fences & ~1U)) { + msg.printf(" and "); + } else { + msg.printf(", "); + } + } + msg.printf("%s", FENCE_NAMES[i]); + nfences++; + } + fences >>= 1; + i++; + } + msg.printf(" fence"); + if (nfences>1) { + msg.printf("s"); + } +} + +// print a message about the passed in fences +void AC_Fence::print_fence_message(const char* message, uint8_t fences) const +{ + if (!fences) { + return; + } + + char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; + ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); + AC_Fence::get_fence_names(fences, e); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s %s", e.get_writeable_string(), message); } -/// enable the Fence code generally; a master switch for all fences -void AC_Fence::enable(bool value) +// should be called @10Hz to handle loading from eeprom +void AC_Fence::update() { + _poly_loader.update(); + // if someone changes the parameter we want to enable or disable everything + if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) { + // reset the auto mask since we just reconfigured all of fencing + _auto_enable_mask = AC_FENCE_ALL_FENCES; + _last_enabled = _enabled; + _last_auto_enabled = _auto_enabled; + if (_enabled) { + _enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN; + } else { + _enabled_fences = 0; + } + } +#ifdef AC_FENCE_DEBUG + static uint32_t last_msg_count = 0; + if (get_enabled_fences() && last_msg_count++ % 10 == 0) { + print_fence_message("active", get_enabled_fences()); + print_fence_message("breached", get_breaches()); + } +#endif +} + +// enable or disable configured fences present in fence_types +// also updates the bitmask of auto enabled fences if update_auto_mask is true +// returns a bitmask of fences that were changed +uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_mask) +{ + uint8_t fences = _configured_fences.get() & fence_types; + uint8_t enabled_fences = _enabled_fences; + if (value) { + enabled_fences |= fences; + } else { + enabled_fences &= ~fences; + } + + // fences that were manually changed are no longer eligible for auto-enablement or disablement + if (update_auto_mask) { + _auto_enable_mask &= ~fences; + } + + uint8_t fences_to_change = _enabled_fences ^ enabled_fences; + + if (!fences_to_change) { + return 0; + } #if HAL_LOGGING_ENABLED - if (_enabled && !value) { - AP::logger().Write_Event(LogEvent::FENCE_DISABLE); - } else if (!_enabled && value) { - AP::logger().Write_Event(LogEvent::FENCE_ENABLE); + AP::logger().Write_Event(value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE); + if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) { + AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MAX_ENABLE : LogEvent::FENCE_ALT_MAX_DISABLE); + } + if (fences_to_change & AC_FENCE_TYPE_CIRCLE) { + AP::logger().Write_Event(value ? LogEvent::FENCE_CIRCLE_ENABLE : LogEvent::FENCE_CIRCLE_DISABLE); + } + if (fences_to_change & AC_FENCE_TYPE_ALT_MIN) { + AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MIN_ENABLE : LogEvent::FENCE_ALT_MIN_DISABLE); + } + if (fences_to_change & AC_FENCE_TYPE_POLYGON) { + AP::logger().Write_Event(value ? LogEvent::FENCE_POLYGON_ENABLE : LogEvent::FENCE_POLYGON_DISABLE); } #endif - _enabled.set(value); + + _enabled_fences = enabled_fences; + if (!value) { - clear_breach(AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON); - disable_floor(); - } else { - enable_floor(); + clear_breach(fences_to_change); } + + return fences_to_change; } /// enable/disable fence floor only void AC_Fence::enable_floor() { -#if HAL_LOGGING_ENABLED - if (!_floor_enabled) { - // Floor is currently disabled, enable it - AP::logger().Write_Event(LogEvent::FENCE_FLOOR_ENABLE); - } -#endif - _floor_enabled = true; + enable(true, AC_FENCE_TYPE_ALT_MIN); } void AC_Fence::disable_floor() { -#if HAL_LOGGING_ENABLED - if (_floor_enabled) { - // Floor is currently enabled, disable it - AP::logger().Write_Event(LogEvent::FENCE_FLOOR_DISABLE); + enable(false, AC_FENCE_TYPE_ALT_MIN); +} + +/* + called on arming +*/ +void AC_Fence::auto_enable_fence_on_arming(void) +{ + if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { + return; } -#endif - _floor_enabled = false; - clear_breach(AC_FENCE_TYPE_ALT_MIN); + + const uint8_t fences = enable(true, _auto_enable_mask & ~AC_FENCE_TYPE_ALT_MIN, false); + print_fence_message("auto-enabled", fences); +} + +/* + called on disarming +*/ +void AC_Fence::auto_disable_fence_on_disarming(void) +{ + if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { + return; + } + + const uint8_t fences = enable(false, _auto_enable_mask, false); + print_fence_message("auto-disabled", fences); } /* @@ -205,82 +327,63 @@ void AC_Fence::disable_floor() */ void AC_Fence::auto_enable_fence_after_takeoff(void) { - if (_enabled) { + if (auto_enabled() != AutoEnable::ENABLE_ON_AUTO_TAKEOFF && + auto_enabled() != AutoEnable::ENABLE_DISABLE_FLOOR_ONLY) { return; - } - switch(auto_enabled()) { - case AC_Fence::AutoEnable::ALWAYS_ENABLED: - case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY: - enable(true); - GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence enabled (auto enabled)"); - break; - default: - // fence does not auto-enable in other takeoff conditions - break; } + + const uint8_t fences = enable(true, _auto_enable_mask, false); + print_fence_message("auto-enabled", fences); } -/* - called when performing an auto landing - */ -void AC_Fence::auto_disable_fence_for_landing(void) +// return fences that should be auto-disabled when requested +uint8_t AC_Fence::get_auto_disable_fences(void) const { + uint8_t auto_disable = 0; switch (auto_enabled()) { - case AC_Fence::AutoEnable::ALWAYS_ENABLED: - enable(false); - GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence disabled (auto disable)"); + case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF: + auto_disable = _auto_enable_mask; break; case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY: - disable_floor(); - GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence floor disabled (auto disable)"); - break; - default: - // fence does not auto-disable in other landing conditions + case AC_Fence::AutoEnable::ONLY_WHEN_ARMED: + default: // when auto disable is not set we still need to disable the altmin fence on landing + auto_disable = _auto_enable_mask & AC_FENCE_TYPE_ALT_MIN; break; } + return auto_disable; } -bool AC_Fence::present() const +uint8_t AC_Fence::present() const { - const auto enabled_fences = _enabled_fences.get(); - // A fence is present if any of the conditions are true. - // * tin can (circle) is enabled - // * min or max alt is enabled - // * polygon fences are enabled and any fence has been uploaded - if (enabled_fences & AC_FENCE_TYPE_CIRCLE || - enabled_fences & AC_FENCE_TYPE_ALT_MIN || - enabled_fences & AC_FENCE_TYPE_ALT_MAX || - ((enabled_fences & AC_FENCE_TYPE_POLYGON) && _poly_loader.total_fence_count() > 0)) { - return true; + uint8_t mask = AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX; + if (_poly_loader.total_fence_count() > 0) { + mask |= AC_FENCE_TYPE_POLYGON; } - return false; + return _configured_fences.get() & mask; } /// get_enabled_fences - returns bitmask of enabled fences uint8_t AC_Fence::get_enabled_fences() const { - if (!_enabled && !_auto_enabled) { - return 0; - } - return _enabled_fences; + return _enabled_fences & present(); } // additional checks for the polygon fence: -bool AC_Fence::pre_arm_check_polygon(const char* &fail_msg) const +bool AC_Fence::pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const { - if (!(_enabled_fences & AC_FENCE_TYPE_POLYGON)) { + if (!(_configured_fences & AC_FENCE_TYPE_POLYGON)) { // not enabled; all good return true; } if (! _poly_loader.loaded()) { - fail_msg = "Fences invalid"; + hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence(s) invalid"); return false; } if (!_poly_loader.check_inclusion_circle_margin(_margin)) { - fail_msg = "Margin is less than inclusion circle radius"; + hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence margin is less than inclusion circle radius"); return false; } @@ -288,14 +391,14 @@ bool AC_Fence::pre_arm_check_polygon(const char* &fail_msg) const } // additional checks for the circle fence: -bool AC_Fence::pre_arm_check_circle(const char* &fail_msg) const +bool AC_Fence::pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const { if (_circle_radius < 0) { - fail_msg = "Invalid FENCE_RADIUS value"; + hal.util->snprintf(failure_msg, failure_msg_len, "Invalid Circle FENCE_RADIUS value"); return false; } if (_circle_radius < _margin) { - fail_msg = "FENCE_MARGIN is less than FENCE_RADIUS"; + hal.util->snprintf(failure_msg, failure_msg_len, "Circle FENCE_MARGIN is less than FENCE_RADIUS"); return false; } @@ -303,15 +406,15 @@ bool AC_Fence::pre_arm_check_circle(const char* &fail_msg) const } // additional checks for the alt fence: -bool AC_Fence::pre_arm_check_alt(const char* &fail_msg) const +bool AC_Fence::pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const { if (_alt_max < 0.0f) { - fail_msg = "Invalid FENCE_ALT_MAX value"; + hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MAX value"); return false; } if (_alt_min < -100.0f) { - fail_msg = "Invalid FENCE_ALT_MIN value"; + hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MIN value"); return false; } return true; @@ -319,63 +422,75 @@ bool AC_Fence::pre_arm_check_alt(const char* &fail_msg) const /// pre_arm_check - returns true if all pre-takeoff checks have completed successfully -bool AC_Fence::pre_arm_check(const char* &fail_msg) const +bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { - fail_msg = nullptr; - // if fences are enabled but none selected fail pre-arm check - if (enabled() && !present()) { - fail_msg = "Fences enabled, but none selected"; + if (_enabled && !present()) { + hal.util->snprintf(failure_msg, failure_msg_len, "Fences enabled, but none selected"); return false; } + + // if AUTOENABLE = 1 or 2 warn now, but fail in a later release + // PARAMETER_CONVERSION - Added: Jul-2024 for ArduPilot-4.6 + if (_auto_enabled == 1 || _auto_enabled == 2) { + static uint32_t last_autoenable_warn_ms; + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_autoenable_warn_ms > 60000) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FENCE_AUTOENABLE is %u, will be removed in 4.7, use 3", unsigned(_auto_enabled)); + last_autoenable_warn_ms = now_ms; + } + } // if not enabled or not fence set-up always return true - if ((!_enabled && !_auto_enabled) || !_enabled_fences) { + if ((!enabled() && !_auto_enabled) || !_configured_fences) { return true; } // if we have horizontal limits enabled, check we can get a // relative position from the AHRS - if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) || - (_enabled_fences & AC_FENCE_TYPE_POLYGON)) { + if ((_configured_fences & AC_FENCE_TYPE_CIRCLE) || + (_configured_fences & AC_FENCE_TYPE_POLYGON)) { Vector2f position; if (!AP::ahrs().get_relative_position_NE_home(position)) { - fail_msg = "Fence requires position"; + hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position"); return false; } } - if (!pre_arm_check_polygon(fail_msg)) { + if (!pre_arm_check_polygon(failure_msg, failure_msg_len)) { return false; } - if (!pre_arm_check_circle(fail_msg)) { + if (!pre_arm_check_circle(failure_msg, failure_msg_len)) { return false; } - if (!pre_arm_check_alt(fail_msg)) { + if (!pre_arm_check_alt(failure_msg, failure_msg_len)) { return false; } // check no limits are currently breached if (_breached_fences) { - fail_msg = "vehicle outside fence"; + char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; + ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); + AC_Fence::get_fence_names(_breached_fences, e); + hal.util->snprintf(failure_msg, failure_msg_len, "Vehicle breaching %s", e.get_writeable_string()); return false; } // validate FENCE_MARGIN parameter range if (_margin < 0.0f) { - fail_msg = "Invalid FENCE_MARGIN value"; + hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_MARGIN value"); return false; } if (_alt_max < _alt_min) { - fail_msg = "FENCE_ALT_MAX < FENCE_ALT_MIN"; + hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_ALT_MAX < FENCE_ALT_MIN"); return false; } if (_alt_max - _alt_min <= 2.0f * _margin) { - fail_msg = "FENCE_MARGIN too big"; + hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_MARGIN too big"); return false; } @@ -389,13 +504,14 @@ bool AC_Fence::pre_arm_check(const char* &fail_msg) const bool AC_Fence::check_fence_alt_max() { // altitude fence check - if (!(_enabled_fences & AC_FENCE_TYPE_ALT_MAX)) { + if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) { // not enabled; no breach return false; } - AP::ahrs().get_relative_position_D_home(_curr_alt); - _curr_alt = -_curr_alt; // translate Down to Up + float alt; + AP::ahrs().get_relative_position_D_home(alt); + _curr_alt = -alt; // translate Down to Up // check if we are over the altitude fence if (_curr_alt >= _alt_max) { @@ -437,13 +553,14 @@ bool AC_Fence::check_fence_alt_max() bool AC_Fence::check_fence_alt_min() { // altitude fence check - if (!(_enabled_fences & AC_FENCE_TYPE_ALT_MIN)) { + if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) { // not enabled; no breach return false; } - AP::ahrs().get_relative_position_D_home(_curr_alt); - _curr_alt = -_curr_alt; // translate Down to Up + float alt; + AP::ahrs().get_relative_position_D_home(alt); + _curr_alt = -alt; // translate Down to Up // check if we are under the altitude fence if (_curr_alt <= _alt_min) { @@ -479,15 +596,47 @@ bool AC_Fence::check_fence_alt_min() return false; } + +/// auto enable fence floor +bool AC_Fence::auto_enable_fence_floor() +{ + // altitude fence check + if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN) // not configured + || (get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) // already enabled + || !(_auto_enable_mask & AC_FENCE_TYPE_ALT_MIN) // has been manually disabled + || (!_enabled && (auto_enabled() == AC_Fence::AutoEnable::ALWAYS_DISABLED + || auto_enabled() == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) { + // not enabled + return false; + } + + float alt; + AP::ahrs().get_relative_position_D_home(alt); + _curr_alt = -alt; // translate Down to Up + + // check if we are over the altitude fence + if (!floor_enabled() && _curr_alt >= _alt_min + _margin) { + enable(true, AC_FENCE_TYPE_ALT_MIN, false); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Min Alt fence enabled (auto enable)"); + return true; + } + + return false; +} + // check_fence_polygon - returns true if the poly fence is freshly // breached. That includes being inside exclusion zones and outside // inclusions zones bool AC_Fence::check_fence_polygon() { + if (!(get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) { + // not enabled; no breach + clear_breach(AC_FENCE_TYPE_POLYGON); + return false; + } + const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON; - const bool breached = ((_enabled_fences & AC_FENCE_TYPE_POLYGON) && - _poly_loader.breached()); - if (breached) { + if (_poly_loader.breached()) { if (!was_breached) { record_breach(AC_FENCE_TYPE_POLYGON); return true; @@ -506,7 +655,7 @@ bool AC_Fence::check_fence_polygon() /// fence is breached. bool AC_Fence::check_fence_circle() { - if (!(_enabled_fences & AC_FENCE_TYPE_CIRCLE)) { + if (!(get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) { // not enabled; no breach return false; } @@ -549,49 +698,68 @@ bool AC_Fence::check_fence_circle() /// check - returns bitmask of fence types breached (if any) -uint8_t AC_Fence::check() +uint8_t AC_Fence::check(bool disable_auto_fences) { uint8_t ret = 0; + uint8_t disabled_fences = disable_auto_fences ? get_auto_disable_fences() : 0; + uint8_t fences_to_disable = disabled_fences & _enabled_fences; // clear any breach from a non-enabled fence - clear_breach(~_enabled_fences); + clear_breach(~_configured_fences); + // clear any breach from disabled fences + clear_breach(fences_to_disable); + + // report on any fences that were auto-disabled + if (fences_to_disable) { + print_fence_message("auto-disabled", fences_to_disable); + } // return immediately if disabled - if ((!_enabled && !_auto_enabled) || !_enabled_fences) { + if ((!enabled() && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) { return 0; } - // 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 - if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) { - return 0; - } - // recovery period has passed so reset manual recovery time - // and continue with fence breach checks - _manual_recovery_start_ms = 0; - } + // disable the (temporarily) disabled fences + enable(false, disabled_fences, false); // maximum altitude fence check - if (check_fence_alt_max()) { + if (!(disabled_fences & AC_FENCE_TYPE_ALT_MAX) && check_fence_alt_max()) { ret |= AC_FENCE_TYPE_ALT_MAX; } - // minimum altitude fence check - if (_floor_enabled && check_fence_alt_min()) { + // minimum altitude fence check, do this before auto-disabling (e.g. because falling) + // so that any action can be taken + if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN) && check_fence_alt_min()) { ret |= AC_FENCE_TYPE_ALT_MIN; } + // auto enable floor unless auto enable on auto takeoff has been set (which means other behaviour is required) + if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN)) { + auto_enable_fence_floor(); + } + // circle fence check - if (check_fence_circle()) { + if (!(disabled_fences & AC_FENCE_TYPE_CIRCLE) && check_fence_circle()) { ret |= AC_FENCE_TYPE_CIRCLE; } // polygon fence check - if (check_fence_polygon()) { + if (!(disabled_fences & AC_FENCE_TYPE_POLYGON) && check_fence_polygon()) { ret |= AC_FENCE_TYPE_POLYGON; } + // check if pilot is attempting to recover manually + // this is done last so that _breached_fences is correct + if (_manual_recovery_start_ms != 0) { + // we ignore any fence breaches during the manual recovery period which is about 10 seconds + if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) { + return 0; + } + // recovery period has passed so reset manual recovery time + // and continue with fence breach checks + _manual_recovery_start_ms = 0; + } + // return any new breaches that have occurred return ret; } @@ -695,6 +863,8 @@ void AC_Fence::manual_recovery_start() // record time pilot began manual recovery _manual_recovery_start_ms = AP_HAL::millis(); + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Manual recovery started"); } // methods for mavlink SYS_STATUS message (send_sys_status) @@ -712,7 +882,7 @@ bool AC_Fence::sys_status_enabled() const return false; } // Fence is only enabled when the flag is enabled - return _enabled; + return enabled(); } bool AC_Fence::sys_status_failed() const @@ -742,22 +912,27 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND }; AC_Fence::AC_Fence() {}; -void AC_Fence::enable(bool value) {}; +uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable) { return 0; } -void AC_Fence::disable_floor() {}; +void AC_Fence::enable_floor() {} +void AC_Fence::disable_floor() {} +void AC_Fence::update() {} -void AC_Fence::auto_enable_fence_after_takeoff() {}; -void AC_Fence::auto_disable_fence_for_landing() {}; +void AC_Fence::auto_enable_fence_after_takeoff() {} +void AC_Fence::auto_enable_fence_on_arming() {} +void AC_Fence::auto_disable_fence_on_disarming() {} -bool AC_Fence::present() const { return false; } +uint8_t AC_Fence::present() const { return 0; } uint8_t AC_Fence::get_enabled_fences() const { return 0; } -bool AC_Fence::pre_arm_check(const char* &fail_msg) const { return true; } +bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { return true; } -uint8_t AC_Fence::check() { return 0; } +uint8_t AC_Fence::check(bool disable_auto_fences) { 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::get_fence_names(uint8_t fences, ExpandingString& msg) { } +void AC_Fence::print_fence_message(const char* msg, uint8_t fences) const {} void AC_Fence::manual_recovery_start() {} diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index e8eb88943e133c..3165d7b73d4d33 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -6,6 +6,7 @@ #include #include +#include #include #include #include @@ -15,6 +16,8 @@ #define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL) #define AC_FENCE_TYPE_POLYGON 4 // polygon horizontal fence #define AC_FENCE_TYPE_ALT_MIN 8 // low alt fence which usually initiates an RTL +#define AC_FENCE_ARMING_FENCES (AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON) +#define AC_FENCE_ALL_FENCES (AC_FENCE_ARMING_FENCES | AC_FENCE_TYPE_ALT_MIN) // valid actions should a fence be breached #define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action @@ -34,12 +37,19 @@ class AC_Fence public: friend class AC_PolyFence_loader; - enum class AutoEnable + enum class AutoEnable : uint8_t { ALWAYS_DISABLED = 0, - ALWAYS_ENABLED = 1, - ENABLE_DISABLE_FLOOR_ONLY = 2, - ONLY_WHEN_ARMED = 3 + ENABLE_ON_AUTO_TAKEOFF = 1, // enable on auto takeoff + ENABLE_DISABLE_FLOOR_ONLY = 2, // enable on takeoff but disable floor on landing + ONLY_WHEN_ARMED = 3 // enable on arming + }; + + enum class MavlinkFenceActions : uint16_t + { + DISABLE_FENCE = 0, + ENABLE_FENCE = 1, + DISABLE_ALT_MIN_FENCE = 2 }; AC_Fence(); @@ -55,10 +65,15 @@ class AC_Fence static AC_Fence *get_singleton() { return _singleton; } /// enable - allows fence to be enabled/disabled. - void enable(bool value); + /// returns a bitmask of fences that were changed + uint8_t enable(bool value, uint8_t fence_types, bool update_auto_mask = true); + + /// enable_configured - allows configured fences to be enabled/disabled. + /// returns a bitmask of fences that were changed + uint8_t enable_configured(bool value) { return enable(value, _configured_fences, true); } /// auto_enabled - automaticaly enable/disable fence depending of flight status - AutoEnable auto_enabled() { return static_cast(_auto_enabled.get()); } + AutoEnable auto_enabled() const { return static_cast(_auto_enabled.get()); } /// enable_floor - allows fence floor to be enabled/disabled. Note this does not update the eeprom saved value void enable_floor(); @@ -69,32 +84,39 @@ class AC_Fence /// auto_enable_fence_on_takeoff - auto enables the fence. Called after takeoff conditions met void auto_enable_fence_after_takeoff(); - /// auto_disable_fence_for_landing - auto disables respective fence. Called prior to landing. - void auto_disable_fence_for_landing(); + /// auto_enable_fences_on_arming - auto enables all applicable fences on arming + void auto_enable_fence_on_arming(); + + /// auto_disable_fences_on_disarming - auto disables all applicable fences on disarming + void auto_disable_fence_on_disarming(); - /// enabled - returns true if fence is enabled - bool enabled() const { return _enabled; } + uint8_t get_auto_disable_fences(void) const; - /// present - returns true if fence is present - bool present() const; + /// auto_enable_fence_floor - auto enables fence floor once desired altitude has been reached. + bool auto_enable_fence_floor(); + + /// enabled - returns whether fencing is enabled or not + bool enabled() const { return _enabled_fences; } + + /// present - returns true if any of the provided types is present + uint8_t present() const; /// get_enabled_fences - returns bitmask of enabled fences uint8_t get_enabled_fences() const; // should be called @10Hz to handle loading from eeprom - void update() { - _poly_loader.update(); - } + void update(); /// pre_arm_check - returns true if all pre-takeoff checks have completed successfully - bool pre_arm_check(const char* &fail_msg) const; + bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const; /// /// methods to check we are within the boundaries and recover /// /// check - returns the fence type that has been breached (if any) - uint8_t check(); + /// disabled_fences can be used to disable fences for certain conditions (e.g. landing) + uint8_t check(bool disable_auto_fence = false); // returns true if the destination is within fence (used to reject waypoints outside the fence) bool check_destination_within_fence(const class Location& loc); @@ -133,6 +155,12 @@ class AC_Fence /// get_return_rally - returns whether returning to fence return point or rally point float get_return_altitude() const { return _ret_altitude; } + /// get a user-friendly list of fences + static void get_fence_names(uint8_t fences, ExpandingString& msg); + + // print a message about the fences to the GCS + void print_fence_message(const char* msg, uint8_t fences) const; + /// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds /// should be called whenever the pilot changes the flight mode /// has no effect if no breaches have occurred @@ -187,14 +215,19 @@ class AC_Fence void clear_breach(uint8_t fence_type); // additional checks for the different fence types: - bool pre_arm_check_polygon(const char* &fail_msg) const; - bool pre_arm_check_circle(const char* &fail_msg) const; - bool pre_arm_check_alt(const char* &fail_msg) const; + bool pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const; + bool pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const; + bool pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const; + // fence floor is enabled + bool floor_enabled() const { return _enabled_fences & AC_FENCE_TYPE_ALT_MIN; } // parameters - AP_Int8 _enabled; // fence enable/disable control + uint8_t _enabled_fences; // fences that are currently enabled/disabled + bool _last_enabled; // value of enabled last time we checked + AP_Int8 _enabled; // overall feature control AP_Int8 _auto_enabled; // top level flag for auto enabling fence - AP_Int8 _enabled_fences; // bit mask holding which fences are enabled + uint8_t _last_auto_enabled; // value of auto_enabled last time we checked + AP_Int8 _configured_fences; // bit mask holding which fences are enabled AP_Int8 _action; // recovery action specified by user AP_Float _alt_max; // altitude upper limit in meters AP_Float _alt_min; // altitude lower limit in meters @@ -216,7 +249,7 @@ class AC_Fence float _circle_breach_distance; // distance beyond the circular fence // other internal variables - bool _floor_enabled; // fence floor is enabled + uint8_t _auto_enable_mask = AC_FENCE_ALL_FENCES; // fences that can be auto-enabled or auto-disabled float _home_distance; // distance from home in meters (provided by main code) float _curr_alt; diff --git a/libraries/AC_Fence/AC_Fence_config.h b/libraries/AC_Fence/AC_Fence_config.h index 4abb471eac8319..3e10480711ab85 100644 --- a/libraries/AC_Fence/AC_Fence_config.h +++ b/libraries/AC_Fence/AC_Fence_config.h @@ -12,6 +12,10 @@ #define AP_FENCE_ENABLED 2 #endif +// CODE_REMOVAL +// ArduPilot 4.6 sends deprecation warnings for FENCE_POINT/FENCE_FETCH_POINT +// ArduPilot 4.7 stops compiling them in +// ArduPilot 4.8 removes the code entirely #ifndef AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT -#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT HAL_GCS_ENABLED && AP_FENCE_ENABLED +#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 0 #endif diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index ba38dea63a2aa2..1ed5ecce921d32 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -227,7 +227,7 @@ bool AC_PolyFence_loader::breached() const // returns true if location is outside the boundary bool AC_PolyFence_loader::breached(const Location& loc) const { - if (!loaded()) { + if (!loaded() || total_fence_count() == 0) { return false; } @@ -306,7 +306,7 @@ bool AC_PolyFence_loader::formatted() const uint16_t AC_PolyFence_loader::max_items() const { // this is 84 items on PixHawk - return MIN(255U, fence_storage.size() / sizeof(Vector2l)); + return fence_storage.size() / sizeof(Vector2l); } bool AC_PolyFence_loader::format() @@ -493,16 +493,18 @@ bool AC_PolyFence_loader::index_eeprom() if (!count_eeprom_fences()) { return false; } + + void_index(); + if (_eeprom_fence_count == 0) { + _num_fences = 0; _load_attempted = false; return true; } - void_index(); - Debug("Fence: Allocating %u bytes for index", (unsigned)(_eeprom_fence_count*sizeof(FenceIndex))); - _index = new FenceIndex[_eeprom_fence_count]; + _index = NEW_NOTHROW FenceIndex[_eeprom_fence_count]; if (_index == nullptr) { return false; } @@ -636,8 +638,8 @@ bool AC_PolyFence_loader::load_from_eeprom() const uint16_t count = sum_of_polygon_point_counts_and_returnpoint(); Debug("Fence: Allocating %u bytes for points", (unsigned)(count * sizeof(Vector2f))); - _loaded_offsets_from_origin = new Vector2f[count]; - _loaded_points_lla = new Vector2l[count]; + _loaded_offsets_from_origin = NEW_NOTHROW Vector2f[count]; + _loaded_points_lla = NEW_NOTHROW Vector2l[count]; if (_loaded_offsets_from_origin == nullptr || _loaded_points_lla == nullptr) { unload(); get_loaded_fence_semaphore().give(); @@ -648,10 +650,10 @@ bool AC_PolyFence_loader::load_from_eeprom() // FIXME: find some way of factoring out all of these allocation routines. { // allocate storage for inclusion polyfences: - const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION); + const auto count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION); Debug("Fence: Allocating %u bytes for inc. fences", (unsigned)(count * sizeof(InclusionBoundary))); - _loaded_inclusion_boundary = new InclusionBoundary[count]; + _loaded_inclusion_boundary = NEW_NOTHROW InclusionBoundary[count]; if (_loaded_inclusion_boundary == nullptr) { unload(); get_loaded_fence_semaphore().give(); @@ -660,10 +662,10 @@ bool AC_PolyFence_loader::load_from_eeprom() } { // allocate storage for exclusion polyfences: - const uint8_t count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION); + const auto count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION); Debug("Fence: Allocating %u bytes for exc. fences", (unsigned)(count * sizeof(ExclusionBoundary))); - _loaded_exclusion_boundary = new ExclusionBoundary[count]; + _loaded_exclusion_boundary = NEW_NOTHROW ExclusionBoundary[count]; if (_loaded_exclusion_boundary == nullptr) { unload(); get_loaded_fence_semaphore().give(); @@ -672,11 +674,11 @@ bool AC_PolyFence_loader::load_from_eeprom() } { // allocate storage for circular inclusion fences: - uint8_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION); + uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION); count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT) Debug("Fence: Allocating %u bytes for circ. inc. fences", (unsigned)(count * sizeof(InclusionCircle))); - _loaded_circle_inclusion_boundary = new InclusionCircle[count]; + _loaded_circle_inclusion_boundary = NEW_NOTHROW InclusionCircle[count]; if (_loaded_circle_inclusion_boundary == nullptr) { unload(); get_loaded_fence_semaphore().give(); @@ -685,11 +687,11 @@ bool AC_PolyFence_loader::load_from_eeprom() } { // allocate storage for circular exclusion fences: - uint8_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION); + uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION); count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT) Debug("Fence: Allocating %u bytes for circ. exc. fences", (unsigned)(count * sizeof(ExclusionCircle))); - _loaded_circle_exclusion_boundary = new ExclusionCircle[count]; + _loaded_circle_exclusion_boundary = NEW_NOTHROW ExclusionCircle[count]; if (_loaded_circle_exclusion_boundary == nullptr) { unload(); get_loaded_fence_semaphore().give(); @@ -1058,7 +1060,7 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_ return false; } - uint8_t total_vertex_count = 0; + uint16_t total_vertex_count = 0; uint16_t offset = 4; // skipping magic uint8_t vertex_count = 0; for (uint16_t i=0; isetup_notch_filter(*_target_notch, sample_rate)) { @@ -174,7 +174,7 @@ void AC_PID::set_notch_sample_rate(float sample_rate) if (_notch_E_filter != 0) { if (_error_notch == nullptr) { - _error_notch = new NotchFilterFloat(); + _error_notch = NEW_NOTHROW NotchFilterFloat(); } AP_Filter* filter = AP::filters().get_filter(_notch_E_filter); if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) { @@ -201,34 +201,48 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, _pid_info.reset = _flags._reset_filter; if (_flags._reset_filter) { _flags._reset_filter = false; + + // Reset target filter _target = target; - _error = _target - measurement; - _derivative = 0.0f; - _target_derivative = 0.0f; #if AP_FILTER_ENABLED if (_target_notch != nullptr) { _target_notch->reset(); _target = _target_notch->apply(_target); } +#endif + + // Calculate error and reset error filter + _error = _target - measurement; +#if AP_FILTER_ENABLED if (_error_notch != nullptr) { _error_notch->reset(); _error = _error_notch->apply(_error); } #endif + // Zero derivatives + _derivative = 0.0f; + _target_derivative = 0.0f; + } else { - float error_last = _error; - float target_last = _target; - float error = _target - measurement; + + // Apply target filters + const float target_last = _target; #if AP_FILTER_ENABLED // apply notch filters before FTLD/FLTE to avoid shot noise if (_target_notch != nullptr) { target = _target_notch->apply(target); } +#endif + _target += get_filt_T_alpha(dt) * (target - _target); + + // Calculate error and apply error filter + const float error_last = _error; + float error = _target - measurement; +#if AP_FILTER_ENABLED if (_error_notch != nullptr) { error = _error_notch->apply(error); } #endif - _target += get_filt_T_alpha(dt) * (target - _target); _error += get_filt_E_alpha(dt) * (error - _error); // calculate and filter derivative @@ -376,20 +390,6 @@ void AC_PID::save_gains() _filt_D_hz.save(); } -/// 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 dff_val) -{ - _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); - _kdff.set(dff_val); -} - // get_filt_T_alpha - get the target filter alpha float AC_PID::get_filt_T_alpha(float dt) const { diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index fbbebcac7db783..d11107cf306453 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -92,9 +92,6 @@ class AC_PID { // save gain to eeprom 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 dff_val=0); - // get accessors const AP_Float &kP() const { return _kp; } AP_Float &kP() { return _kp; } @@ -117,17 +114,17 @@ class AC_PID { float get_filt_D_alpha(float dt) const; // set accessors - void kP(const float v) { _kp.set(v); } - void kI(const float v) { _ki.set(v); } - void kD(const float v) { _kd.set(v); } - void ff(const float v) { _kff.set(v); } - void imax(const float v) { _kimax.set(fabsf(v)); } - void pdmax(const float v) { _kpdmax.set(fabsf(v)); } - void filt_T_hz(const float v); - void filt_E_hz(const float v); - void filt_D_hz(const float v); - void slew_limit(const float v); - void kDff(const float v) { _kdff.set(v); } + void set_kP(const float v) { _kp.set(v); } + void set_kI(const float v) { _ki.set(v); } + void set_kD(const float v) { _kd.set(v); } + void set_ff(const float v) { _kff.set(v); } + void set_imax(const float v) { _kimax.set(fabsf(v)); } + void set_pdmax(const float v) { _kpdmax.set(fabsf(v)); } + void set_filt_T_hz(const float v); + void set_filt_E_hz(const float v); + void set_filt_D_hz(const float v); + void set_slew_limit(const float v); + void set_kDff(const float v) { _kdff.set(v); } // set the desired and actual rates (for logging purposes) void set_target_rate(float target) { _pid_info.target = target; } diff --git a/libraries/AC_PID/AC_PID_2D.h b/libraries/AC_PID/AC_PID_2D.h index 8213997df1f84d..129c07f2e93af1 100644 --- a/libraries/AC_PID/AC_PID_2D.h +++ b/libraries/AC_PID/AC_PID_2D.h @@ -59,13 +59,13 @@ class AC_PID_2D { float get_filt_D_alpha(float dt) const; // set accessors - void kP(float v) { _kp.set(v); } - void kI(float v) { _ki.set(v); } - void kD(float v) { _kd.set(v); } - void ff(float v) { _kff.set(v); } - void imax(float v) { _kimax.set(fabsf(v)); } - void filt_E_hz(float hz) { _filt_E_hz.set(fabsf(hz)); } - void filt_D_hz(float hz) { _filt_D_hz.set(fabsf(hz)); } + void set_kP(float v) { _kp.set(v); } + void set_kI(float v) { _ki.set(v); } + void set_kD(float v) { _kd.set(v); } + void set_ff(float v) { _kff.set(v); } + void set_imax(float v) { _kimax.set(fabsf(v)); } + void set_filt_E_hz(float hz) { _filt_E_hz.set(fabsf(hz)); } + void set_filt_D_hz(float hz) { _filt_D_hz.set(fabsf(hz)); } // integrator setting functions void set_integrator(const Vector2f& target, const Vector2f& measurement, const Vector2f& i); diff --git a/libraries/AC_PID/AC_PID_Basic.h b/libraries/AC_PID/AC_PID_Basic.h index c9342593fbab4b..9d59a27f7afd67 100644 --- a/libraries/AC_PID/AC_PID_Basic.h +++ b/libraries/AC_PID/AC_PID_Basic.h @@ -54,13 +54,13 @@ class AC_PID_Basic { float get_filt_D_alpha(float dt) const WARN_IF_UNUSED; // set accessors - void kP(float v) { _kp.set(v); } - void kI(float v) { _ki.set(v); } - void kD(float v) { _kd.set(v); } - void ff(float v) { _kff.set(v); } - void imax(float v) { _kimax.set(fabsf(v)); } - void filt_E_hz(float hz) { _filt_E_hz.set(fabsf(hz)); } - void filt_D_hz(float hz) { _filt_D_hz.set(fabsf(hz)); } + void set_kP(float v) { _kp.set(v); } + void set_kI(float v) { _ki.set(v); } + void set_kD(float v) { _kd.set(v); } + void set_ff(float v) { _kff.set(v); } + void set_imax(float v) { _kimax.set(fabsf(v)); } + void set_filt_E_hz(float hz) { _filt_E_hz.set(fabsf(hz)); } + void set_filt_D_hz(float hz) { _filt_D_hz.set(fabsf(hz)); } // integrator setting functions void set_integrator(float target, float measurement, float i); diff --git a/libraries/AC_PID/AC_PI_2D.cpp b/libraries/AC_PID/AC_PI_2D.cpp index e6c6362464073e..386982e6a60f5b 100644 --- a/libraries/AC_PID/AC_PI_2D.cpp +++ b/libraries/AC_PID/AC_PI_2D.cpp @@ -151,18 +151,6 @@ void AC_PI_2D::save_gains() _filt_hz.save(); } -/// 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.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(); -} - // calc_filt_alpha - recalculate the input filter alpha void AC_PI_2D::calc_filt_alpha() { diff --git a/libraries/AC_PID/AC_PI_2D.h b/libraries/AC_PID/AC_PI_2D.h index c031104531b5f5..f70d766fd76561 100644 --- a/libraries/AC_PID/AC_PI_2D.h +++ b/libraries/AC_PID/AC_PI_2D.h @@ -47,9 +47,6 @@ class AC_PI_2D { // save gain to eeprom void save_gains(); - /// operator function call for easy initialisation - void operator() (float p, float i, float imaxval, float input_filt_hz, float dt); - // get accessors AP_Float &kP() { return _kp; } AP_Float &kI() { return _ki; } diff --git a/libraries/AC_PID/AC_P_1D.h b/libraries/AC_PID/AC_P_1D.h index 482e5ca27a425d..ea040016d79563 100644 --- a/libraries/AC_PID/AC_P_1D.h +++ b/libraries/AC_PID/AC_P_1D.h @@ -42,7 +42,7 @@ class AC_P_1D { float get_error() const { return _error; } // set accessors - void kP(float v) { _kp.set(v); } + void set_kP(float v) { _kp.set(v); } // parameter var table static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AC_PID/AC_P_2D.h b/libraries/AC_PID/AC_P_2D.h index 8d1afc67989f67..dad0168e25bf1a 100644 --- a/libraries/AC_PID/AC_P_2D.h +++ b/libraries/AC_PID/AC_P_2D.h @@ -44,7 +44,7 @@ class AC_P_2D { const Vector2f& get_error() const { return _error; } // set accessors - void kP(float v) { _kp.set(v); } + void set_kP(float v) { _kp.set(v); } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -55,7 +55,7 @@ class AC_P_2D { AP_Float _kp; // internal variables - Vector2f _error; // time step in seconds + Vector2f _error; // error between target and measured float _error_max; // error limit in positive direction float _D1_max; // maximum first derivative of output 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 ad193a4aa33aaf..0053c9b22e0aa5 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 = new AC_PID(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER); - // AC_HELI_PID *heli_pid= new AC_HELI_PID(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER); + AC_PID *pid = NEW_NOTHROW AC_PID(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER); + // AC_HELI_PID *heli_pid= NEW_NOTHROW AC_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()); diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 07932c61adef85..c97742a855c2db 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -4,7 +4,6 @@ #include "AC_PrecLand.h" #include -#include #include #include "AC_PrecLand_Backend.h" @@ -41,7 +40,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @Param: TYPE // @DisplayName: Precision Land Type // @Description: Precision Land Type - // @Values: 0:None, 1:CompanionComputer, 2:IRLock, 3:SITL_Gazebo, 4:SITL + // @Values: 0:None, 1:MAVLink, 2:IRLock, 3:SITL_Gazebo, 4:SITL // @User: Advanced AP_GROUPINFO("TYPE", 1, AC_PrecLand, _type, 0), @@ -226,10 +225,10 @@ void AC_PrecLand::init(uint16_t update_rate_hz) _lag.set(constrain_float(_lag, 0.02f, 0.25f)); // must match LAG parameter range at line 124 // 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); + const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * update_rate_hz), 1); // instantiate ring buffer to hold inertial history, return on failure so no backends are created - _inertial_history = new ObjectArray(inertial_buffer_size); + _inertial_history = NEW_NOTHROW ObjectArray(inertial_buffer_size); if (_inertial_history == nullptr) { return; } @@ -243,23 +242,23 @@ void AC_PrecLand::init(uint16_t update_rate_hz) // companion computer #if AC_PRECLAND_COMPANION_ENABLED case Type::COMPANION: - _backend = new AC_PrecLand_Companion(*this, _backend_state); + _backend = NEW_NOTHROW AC_PrecLand_Companion(*this, _backend_state); break; // IR Lock #endif #if AC_PRECLAND_IRLOCK_ENABLED case Type::IRLOCK: - _backend = new AC_PrecLand_IRLock(*this, _backend_state); + _backend = NEW_NOTHROW AC_PrecLand_IRLock(*this, _backend_state); break; #endif #if AC_PRECLAND_SITL_GAZEBO_ENABLED case Type::SITL_GAZEBO: - _backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state); + _backend = NEW_NOTHROW AC_PrecLand_SITL_Gazebo(*this, _backend_state); break; #endif #if AC_PRECLAND_SITL_ENABLED case Type::SITL: - _backend = new AC_PrecLand_SITL(*this, _backend_state); + _backend = NEW_NOTHROW AC_PrecLand_SITL(*this, _backend_state); break; #endif } diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index c6b026eb5628df..5b903fac63102d 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -1,7 +1,8 @@ -#include "AC_Sprayer.h" +#include "AC_Sprayer_config.h" #if HAL_SPRAYER_ENABLED +#include "AC_Sprayer.h" #include #include #include diff --git a/libraries/AC_Sprayer/AC_Sprayer.h b/libraries/AC_Sprayer/AC_Sprayer.h index 240e354d22070f..e4f0ba425ac6a9 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.h +++ b/libraries/AC_Sprayer/AC_Sprayer.h @@ -14,6 +14,10 @@ **/ #pragma once +#include "AC_Sprayer_config.h" + +#if HAL_SPRAYER_ENABLED + #include #include #include @@ -25,12 +29,6 @@ #define AC_SPRAYER_DEFAULT_TURN_ON_DELAY 100 ///< delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump #define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY 1000 ///< shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump -#ifndef HAL_SPRAYER_ENABLED -#define HAL_SPRAYER_ENABLED 1 -#endif - -#if HAL_SPRAYER_ENABLED - /// @class AC_Sprayer /// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm class AC_Sprayer { diff --git a/libraries/AC_Sprayer/AC_Sprayer_config.h b/libraries/AC_Sprayer/AC_Sprayer_config.h new file mode 100644 index 00000000000000..4bb39f35fdf5f6 --- /dev/null +++ b/libraries/AC_Sprayer/AC_Sprayer_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_SPRAYER_ENABLED +#define HAL_SPRAYER_ENABLED 1 +#endif diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index b1f88a40947f3b..33d6964d6912aa 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -43,13 +43,7 @@ const AP_Param::GroupInfo AC_Circle::var_info[] = { AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control) : _inav(inav), _ahrs(ahrs), - _pos_control(pos_control), - _yaw(0.0f), - _angle(0.0f), - _angle_total(0.0f), - _angular_vel(0.0f), - _angular_vel_max(0.0f), - _angular_accel(0.0f) + _pos_control(pos_control) { AP_Param::setup_object_defaults(this, var_info); @@ -92,7 +86,7 @@ void AC_Circle::init() _pos_control.init_z_controller_stopping_point(); // get stopping point - const Vector3p& stopping_point = _pos_control.get_pos_target_cm(); + const Vector3p& stopping_point = _pos_control.get_pos_desired_cm(); // set circle center to circle_radius ahead of stopping point _center = stopping_point; @@ -191,7 +185,7 @@ bool AC_Circle::update(float climb_rate_cms) if (_terrain_alt) { target_z_cm = _center.z + terr_offset; } else { - target_z_cm = _pos_control.get_pos_target_z_cm(); + target_z_cm = _pos_control.get_pos_desired_z_cm(); } // if the circle_radius is zero we are doing panorama so no need to update loiter target @@ -206,7 +200,7 @@ bool AC_Circle::update(float climb_rate_cms) target.y += - _radius * sinf(-_angle); // heading is from vehicle to center of circle - _yaw = get_bearing_cd(_inav.get_position_xy_cm(), _center.tofloat().xy()); + _yaw = get_bearing_cd(_pos_control.get_pos_desired_cm().xy().tofloat(), _center.tofloat().xy()); if ((_options.get() & CircleOptions::FACE_DIRECTION_OF_TRAVEL) != 0) { _yaw += is_positive(_rate)?-9000.0f:9000.0f; @@ -240,27 +234,28 @@ bool AC_Circle::update(float climb_rate_cms) // get_closest_point_on_circle - returns closest point on the circle // circle's center should already have been set -// closest point on the circle will be placed in result +// closest point on the circle will be placed in result, dist_cm will be updated with the 3D distance to the center // result's altitude (i.e. z) will be set to the circle_center's altitude // if vehicle is at the center of the circle, the edge directly behind vehicle will be returned -void AC_Circle::get_closest_point_on_circle(Vector3f &result) const +void AC_Circle::get_closest_point_on_circle(Vector3f& result, float& dist_cm) const { + // get current position + Vector3p stopping_point; + _pos_control.get_stopping_point_xy_cm(stopping_point.xy()); + _pos_control.get_stopping_point_z_cm(stopping_point.z); + + // calc vector from stopping point to circle center + Vector3f vec = (stopping_point - _center).tofloat(); + dist_cm = vec.length(); + // return center if radius is zero - if (_radius <= 0) { + if (!is_positive(_radius)) { result = _center.tofloat(); return; } - // get current position - Vector2p stopping_point; - _pos_control.get_stopping_point_xy_cm(stopping_point); - - // calc vector from stopping point to circle center - Vector2f vec = (stopping_point - _center.xy()).tofloat(); - float dist = vec.length(); - // if current location is exactly at the center of the circle return edge directly behind vehicle - if (is_zero(dist)) { + if (is_zero(dist_cm)) { result.x = _center.x - _radius * _ahrs.cos_yaw(); result.y = _center.y - _radius * _ahrs.sin_yaw(); result.z = _center.z; @@ -268,8 +263,8 @@ void AC_Circle::get_closest_point_on_circle(Vector3f &result) const } // calculate closest point on edge of circle - result.x = _center.x + vec.x / dist * _radius; - result.y = _center.y + vec.y / dist * _radius; + result.x = _center.x + vec.x / dist_cm * _radius; + result.y = _center.y + vec.y / dist_cm * _radius; result.z = _center.z; } @@ -319,12 +314,13 @@ void AC_Circle::init_start_angle(bool use_heading) _angle = wrap_PI(_ahrs.yaw-M_PI); } else { // if we are exactly at the center of the circle, init angle to directly behind vehicle (so vehicle will backup but not change heading) - const Vector3f &curr_pos = _inav.get_position_neu_cm(); - if (is_equal(curr_pos.x,float(_center.x)) && is_equal(curr_pos.y,float(_center.y))) { + // curr_pos_desired is the position before we add offsets and terrain + const Vector3f &curr_pos_desired= _pos_control.get_pos_desired_cm().tofloat(); + if (is_equal(curr_pos_desired.x,float(_center.x)) && is_equal(curr_pos_desired.y,float(_center.y))) { _angle = wrap_PI(_ahrs.yaw-M_PI); } else { // get bearing from circle center to vehicle in radians - float bearing_rad = atan2f(curr_pos.y-_center.y,curr_pos.x-_center.x); + float bearing_rad = atan2f(curr_pos_desired.y-_center.y, curr_pos_desired.x-_center.x); _angle = wrap_PI(bearing_rad); } } diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index d76fcc90ce64e6..a03b23e1788163 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -75,10 +75,10 @@ class AC_Circle // get_closest_point_on_circle - returns closest point on the circle // circle's center should already have been set - // closest point on the circle will be placed in result + // closest point on the circle will be placed in result, dist_cm will be updated with the distance to the center // result's altitude (i.e. z) will be set to the circle_center's altitude // if vehicle is at the center of the circle, the edge directly behind vehicle will be returned - void get_closest_point_on_circle(Vector3f &result) const; + void get_closest_point_on_circle(Vector3f& result, float& dist_cm) const; /// get horizontal distance to loiter target in cm float get_distance_to_target() const { return _pos_control.get_pos_error_xy_cm(); } diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index aab6fa27f3ea1d..3b7f9690a8dd73 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -107,7 +107,7 @@ void AC_Loiter::init_target(const Vector2f& position) _brake_accel = 0.0f; // set target position - _pos_control.set_pos_target_xy_cm(position.x, position.y); + _pos_control.set_pos_desired_xy_cm(position); } /// initialize's position and feed-forward velocity from current pos and velocity @@ -123,8 +123,7 @@ void AC_Loiter::init_target() _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; - _predicted_accel.y = _pos_control.get_accel_target_cmss().y; + _predicted_accel = _pos_control.get_accel_target_cmss().xy(); _predicted_euler_angle.x = radians(_pos_control.get_roll_cd()*0.01f); _predicted_euler_angle.y = radians(_pos_control.get_pitch_cd()*0.01f); _brake_accel = 0.0f; @@ -222,12 +221,10 @@ void AC_Loiter::calc_desired_velocity(bool avoidance_on) } // get loiters desired velocity from the position controller where it is being stored. - const Vector3f &desired_vel_3d = _pos_control.get_vel_desired_cms(); - Vector2f desired_vel{desired_vel_3d.x,desired_vel_3d.y}; + Vector2f desired_vel = _pos_control.get_vel_desired_cms().xy(); // update the desired velocity using our predicted acceleration - desired_vel.x += _predicted_accel.x * dt; - desired_vel.y += _predicted_accel.y * dt; + desired_vel += _predicted_accel * dt; Vector2f loiter_accel_brake; float desired_speed = desired_vel.length(); @@ -262,8 +259,7 @@ void AC_Loiter::calc_desired_velocity(bool avoidance_on) // Apply EKF limit to desired velocity - this limit is calculated by the EKF and adjusted as required to ensure certain sensor limits are respected (eg optical flow sensing) float horizSpdDem = desired_vel.length(); if (horizSpdDem > gnd_speed_limit_cms) { - desired_vel.x = desired_vel.x * gnd_speed_limit_cms / horizSpdDem; - desired_vel.y = desired_vel.y * gnd_speed_limit_cms / horizSpdDem; + desired_vel = desired_vel * gnd_speed_limit_cms / horizSpdDem; } #if AP_AVOIDANCE_ENABLED && !APM_BUILD_TYPE(APM_BUILD_ArduPlane) @@ -280,11 +276,11 @@ void AC_Loiter::calc_desired_velocity(bool avoidance_on) #endif // !APM_BUILD_ArduPlane // get loiters desired velocity from the position controller where it is being stored. - Vector2p target_pos = _pos_control.get_pos_target_cm().xy(); + Vector2p desired_pos = _pos_control.get_pos_desired_cm().xy(); - // update the target position using our predicted velocity - target_pos += (desired_vel * dt).topostype(); + // update the desired position using our desired velocity and acceleration + desired_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); + _pos_control.set_pos_vel_accel_xy(desired_pos, desired_vel, _desired_accel); } diff --git a/libraries/AC_WPNav/AC_Loiter.h b/libraries/AC_WPNav/AC_Loiter.h index 02e8085877b1f6..81bc70dc80cde6 100644 --- a/libraries/AC_WPNav/AC_Loiter.h +++ b/libraries/AC_WPNav/AC_Loiter.h @@ -33,7 +33,9 @@ class AC_Loiter Vector2f get_pilot_desired_acceleration() const { return Vector2f{_desired_accel.x, _desired_accel.y}; } /// clear pilot desired acceleration - void clear_pilot_desired_acceleration() { _desired_accel.zero(); } + void clear_pilot_desired_acceleration() { + set_pilot_desired_acceleration(0, 0); + } /// get vector to stopping point based on a horizontal position and velocity void get_stopping_point_xy(Vector2f& stopping_point) const; diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 318bccc1a50558..b21f77b18828af 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -5,7 +5,7 @@ extern const AP_HAL::HAL& hal; // maximum velocities and accelerations #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_SPEED_MIN 10.0f // minimum horizontal speed between waypoints in cm/s #define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm #define WPNAV_WP_RADIUS_MIN 5.0f // minimum waypoint radius in cm #define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity @@ -19,7 +19,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @DisplayName: Waypoint Horizontal Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission // @Units: cm/s - // @Range: 20 2000 + // @Range: 10 2000 // @Increment: 50 // @User: Standard AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED), @@ -323,11 +323,11 @@ bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt) if (terrain_alt) { // new destination is alt-above-terrain, previous destination was alt-above-ekf-origin _origin.z -= origin_terr_offset; - _pos_control.set_pos_offset_z_cm(_pos_control.get_pos_offset_z_cm() + origin_terr_offset); + _pos_control.init_pos_terrain_cm(origin_terr_offset); } else { // new destination is alt-above-ekf-origin, previous destination was alt-above-terrain _origin.z += origin_terr_offset; - _pos_control.set_pos_offset_z_cm(_pos_control.get_pos_offset_z_cm() - origin_terr_offset); + _pos_control.init_pos_terrain_cm(0.0); } } @@ -435,7 +435,7 @@ void AC_WPNav::shift_wp_origin_and_destination_to_stopping_point_xy() _destination.xy() = stopping_point; // move pos controller target horizontally - _pos_control.set_pos_target_xy_cm(stopping_point.x, stopping_point.y); + _pos_control.set_pos_desired_xy_cm(stopping_point); } /// get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and velocity @@ -466,10 +466,14 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) const float offset_z_scaler = _pos_control.pos_offset_z_scaler(terr_offset, get_terrain_margin() * 100.0); // input shape the terrain offset - _pos_control.update_pos_offset_z(terr_offset); + _pos_control.set_pos_terrain_target_cm(terr_offset); + + // get position controller's position offset (post input shaping) so it can be used in position error calculation + const Vector3p& psc_pos_offset = _pos_control.get_pos_offset_cm(); // 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}; + Vector3f curr_pos = _inav.get_position_neu_cm() - psc_pos_offset.tofloat(); + curr_pos.z -= terr_offset; Vector3f curr_target_vel = _pos_control.get_vel_desired_cms(); curr_target_vel.z -= _pos_control.get_vel_offset_z_cms(); @@ -528,11 +532,6 @@ bool AC_WPNav::advance_wp_target_along_track(float 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(); - target_vel.z += _pos_control.get_vel_offset_z_cms(); - target_accel.z += _pos_control.get_accel_offset_z_cmss(); - // pass new target to the position controller _pos_control.set_pos_vel_accel(target_pos.topostype(), target_vel, target_accel); @@ -778,11 +777,11 @@ bool AC_WPNav::set_spline_destination(const Vector3f& destination, bool terrain_ if (terrain_alt) { // new destination is alt-above-terrain, previous destination was alt-above-ekf-origin _origin.z -= origin_terr_offset; - _pos_control.set_pos_offset_z_cm(_pos_control.get_pos_offset_z_cm() + origin_terr_offset); + _pos_control.init_pos_terrain_cm(origin_terr_offset); } else { // new destination is alt-above-ekf-origin, previous destination was alt-above-terrain _origin.z += origin_terr_offset; - _pos_control.set_pos_offset_z_cm(_pos_control.get_pos_offset_z_cm() - origin_terr_offset); + _pos_control.init_pos_terrain_cm(0.0); } } diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index d1d817cb3d8636..24a8611bacf58d 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -28,6 +28,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -250,7 +251,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) #if HAL_LOGGING_ENABLED if (now - last_log_ms >= 40) { // log at 25Hz - struct log_ATRP pkt = { + const struct log_ATRP pkt { LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG), time_us : AP_HAL::micros64(), type : uint8_t(type), diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 67b6cf07f9036f..a1312bc4c9d712 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include #include @@ -128,9 +127,9 @@ class AP_AutoTune // 5 point mode filter for FF estimate ModeFilterFloat_Size5 ff_filter; - LowPassFilterFloat actuator_filter; - LowPassFilterFloat rate_filter; - LowPassFilterFloat target_filter; + LowPassFilterConstDtFloat actuator_filter; + LowPassFilterConstDtFloat rate_filter; + LowPassFilterConstDtFloat target_filter; // separate slew limiters for P and D float slew_limit_max, slew_limit_tau; diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 0dda072cdd3302..0bd2e9417e590b 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -412,7 +412,7 @@ void AP_PitchController::convert_pid() void AP_PitchController::autotune_start(void) { if (autotune == nullptr) { - autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid); + autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid); if (autotune == nullptr) { if (!failed_autotune_alloc) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation"); diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 8717828cda403b..6f16fd2b0245db 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -313,7 +313,7 @@ void AP_RollController::convert_pid() void AP_RollController::autotune_start(void) { if (autotune == nullptr) { - autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid); + autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid); if (autotune == nullptr) { if (!failed_autotune_alloc) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed roll allocation"); diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 15f42c2fb505bd..0da792112bef9a 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -391,7 +391,7 @@ void AP_YawController::autotune_start(void) gains.tau.set(0.5); gains.rmax_pos.set(90); - autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid); + autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid); if (autotune == nullptr) { if (!failed_autotune_alloc) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed yaw allocation"); diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index c537a05868774a..126250669309a6 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -1058,15 +1058,14 @@ float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, f float AR_AttitudeControl::get_stopping_distance(float speed) const { // get maximum vehicle deceleration - const float accel_max = get_accel_max(); + const float decel_max = get_decel_max(); - // avoid divide by zero - if ((accel_max <= 0.0f) || is_zero(speed)) { + if ((decel_max <= 0.0f) || is_zero(speed)) { return 0.0f; } // assume linear deceleration - return 0.5f * sq(speed) / accel_max; + return 0.5f * sq(speed) / decel_max; } // relax I terms of throttle and steering controllers diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 194c2e95c45b4a..ea862bc099ff53 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -389,7 +389,8 @@ void AR_PosControl::write_log() Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0; // reuse logging from AC_PosControl: - AC_PosControl::Write_PSCN(pos_target_2d_cm.x, // position target + AC_PosControl::Write_PSCN(0.0, // position desired + 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 @@ -397,7 +398,8 @@ void AR_PosControl::write_log() _accel_desired.x * 100.0, // desired accel _accel_target.x * 100.0, // target accel curr_accel_NED.x); // accel - AC_PosControl::Write_PSCE(pos_target_2d_cm.y, // position target + AC_PosControl::Write_PSCE(0.0, // position desired + 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 diff --git a/libraries/AP_ADC/AP_ADC_ADS1115.cpp b/libraries/AP_ADC/AP_ADC_ADS1115.cpp index 21f124a88d1816..96ab43244fb498 100644 --- a/libraries/AP_ADC/AP_ADC_ADS1115.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS1115.cpp @@ -113,7 +113,7 @@ AP_ADC_ADS1115::AP_ADC_ADS1115() , _gain(ADS1115_PGA_4P096) , _channel_to_read(0) { - _samples = new adc_report_s[_channels_number]; + _samples = NEW_NOTHROW adc_report_s[_channels_number]; } AP_ADC_ADS1115::~AP_ADC_ADS1115() diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 5d1508873149ad..dc0cb16b2ec8dc 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -204,7 +204,7 @@ void AP_ADSB::init(void) // sanity check param 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]; + in_state.vehicle_list = NEW_NOTHROW adsb_vehicle_t[in_state.list_size_param]; if (in_state.vehicle_list == nullptr) { // dynamic RAM allocation of in_state.vehicle_list[] failed @@ -272,7 +272,7 @@ void AP_ADSB::detect_instance(uint8_t instance) case Type::uAvionix_MAVLink: #if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED if (AP_ADSB_uAvionix_MAVLink::detect()) { - _backend[instance] = new AP_ADSB_uAvionix_MAVLink(*this, instance); + _backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_MAVLink(*this, instance); } #endif break; @@ -280,7 +280,7 @@ void AP_ADSB::detect_instance(uint8_t instance) case Type::uAvionix_UCP: #if HAL_ADSB_UCP_ENABLED if (AP_ADSB_uAvionix_UCP::detect()) { - _backend[instance] = new AP_ADSB_uAvionix_UCP(*this, instance); + _backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_UCP(*this, instance); } #endif break; @@ -288,7 +288,7 @@ void AP_ADSB::detect_instance(uint8_t instance) case Type::Sagetech: #if HAL_ADSB_SAGETECH_ENABLED if (AP_ADSB_Sagetech::detect()) { - _backend[instance] = new AP_ADSB_Sagetech(*this, instance); + _backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech(*this, instance); } #endif break; @@ -296,7 +296,7 @@ void AP_ADSB::detect_instance(uint8_t instance) 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); + _backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech_MXS(*this, instance); } #endif break; diff --git a/libraries/AP_ADSB/AP_ADSB_Backend.cpp b/libraries/AP_ADSB/AP_ADSB_Backend.cpp index 3797694300deab..3bee658a01f8c6 100644 --- a/libraries/AP_ADSB/AP_ADSB_Backend.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Backend.cpp @@ -21,8 +21,8 @@ base class constructor. */ AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &frontend, uint8_t instance) : - _frontend(frontend), - _instance(instance) + _instance(instance), + _frontend(frontend) { } diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp index 6f0803d2796fda..67d3e73e25d8ce 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -621,8 +621,10 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() 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)); + if (!is_zero(speed_knots)) { + cog = wrap_360(degrees(speed.angle())); + } + snprintf((char*)&gps.grdTrack, 9, "%03u.%04u", unsigned(cog), unsigned((cog - (int)cog) * 1.0E4)); gps.latNorth = (latitude >= 0 ? true: false); diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h index 5e8c841039bfeb..fe8dd0d822b56c 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h @@ -266,6 +266,10 @@ class AP_ADSB_Sagetech_MXS : public AP_ADSB_Backend { void populate_op_climbrate(const struct AP_ADSB::Loc &loc); void populate_op_airspeed_and_heading(const struct AP_ADSB::Loc &loc); + // last course-over-ground calculated from groundspeed vector. + // This is cached so we don't flip to a COG of 90-degrees when + // we stop moving. + float cog; }; #endif // HAL_ADSB_SAGETECH_MXS_ENABLED diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp index e23ee23499d509..0f92293c519f24 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp @@ -32,6 +32,8 @@ #include #include +#include + extern const AP_HAL::HAL &hal; #define AP_ADSB_UAVIONIX_HEALTH_TIMEOUT_MS (5000UL) @@ -57,8 +59,10 @@ bool AP_ADSB_uAvionix_UCP::init() return false; } - request_msg(GDL90_ID_IDENTIFICATION); - request_msg(GDL90_ID_TRANSPONDER_CONFIG); + _frontend.out_state.ctrl.squawkCode = 1200; + _frontend.out_state.tx_status.squawk = 1200; + _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; + return true; } @@ -86,9 +90,32 @@ void AP_ADSB_uAvionix_UCP::update() } } // while nbytes + + if (run_state.last_packet_Transponder_Id_ms == 0 && run_state.request_Transponder_Id_tries < 5) { + if (now_ms - run_state.last_packet_Request_Transponder_Id_ms >= 1000) + { + request_msg(GDL90_ID_IDENTIFICATION); + run_state.request_Transponder_Id_tries++; + } + } + + if (run_state.last_packet_Transponder_Config_ms == 0 && run_state.request_Transponder_Config_tries < 5) { + if (now_ms - run_state.last_packet_Request_Transponder_Config_ms >= 1000) + { + request_msg(GDL90_ID_TRANSPONDER_CONFIG); + run_state.request_Transponder_Config_tries++; + } + } + if (now_ms - run_state.last_packet_Transponder_Control_ms >= 1000) { run_state.last_packet_Transponder_Control_ms = now_ms; - send_Transponder_Control(); + + // We want to use the defaults stored on the ping200X, if possible. + // Until we get the config message (or we've tried requesting it several times), + // don't send the control message. + if (run_state.last_packet_Transponder_Config_ms != 0 || run_state.request_Transponder_Config_tries >= 5) { + send_Transponder_Control(); + } } if ((now_ms - run_state.last_packet_GPS_ms >= 200) && (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Ping200X_Send_GPS)) != 0) { @@ -96,12 +123,11 @@ void AP_ADSB_uAvionix_UCP::update() send_GPS_Data(); } - // if the transponder has stopped giving us the data needed to - // fill the transponder status mavlink message, reset that data. - if ((now_ms - run_state.last_packet_Transponder_Status_ms >= 10000 && run_state.last_packet_Transponder_Status_ms != 0) - && (now_ms - run_state.last_packet_Transponder_Heartbeat_ms >= 10000 && run_state.last_packet_Transponder_Heartbeat_ms != 0) - && (now_ms - run_state.last_packet_Transponder_Ownship_ms >= 10000 && run_state.last_packet_Transponder_Ownship_ms != 0)) - { + // if the transponder has stopped giving us the data needed to + // fill the transponder status mavlink message, indicate status unavailable. + if ((now_ms - run_state.last_packet_Transponder_Status_ms >= 10000) + && (now_ms - run_state.last_packet_Transponder_Heartbeat_ms >= 10000) + && (now_ms - run_state.last_packet_Transponder_Ownship_ms >= 10000)) { _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; } } @@ -116,9 +142,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) // protocol. memcpy(&rx.decoded.heartbeat, msg.raw, sizeof(rx.decoded.heartbeat)); run_state.last_packet_Transponder_Heartbeat_ms = AP_HAL::millis(); - - // this is always true. The "ground/air bit place" is set meaning we're always in the air - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND; + _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; if (rx.decoded.heartbeat.status.one.maintenanceRequired) { _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ; @@ -143,13 +167,11 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) } else { _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL; } - - _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; - } break; case GDL90_ID_IDENTIFICATION: + run_state.last_packet_Transponder_Id_ms = AP_HAL::millis(); // The Identification message contains information used to identify the connected device. The // Identification message will be transmitted with a period of one second regardless of data status // or update for the UCP protocol and will be transmitted upon request for the UCP-HD protocol. @@ -162,7 +184,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) char primaryFwPartNumber[str_len+1]; memcpy(&primaryFwPartNumber, rx.decoded.identification.primaryFwPartNumber, str_len); primaryFwPartNumber[str_len] = 0; - + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"ADSB:Detected %s v%u.%u.%u SN:%u %s", get_hardware_name(rx.decoded.identification.primary.hwId), (unsigned)rx.decoded.identification.primary.fwMajorVersion, @@ -174,11 +196,13 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) break; case GDL90_ID_TRANSPONDER_CONFIG: + run_state.last_packet_Transponder_Config_ms = AP_HAL::millis(); memcpy(&rx.decoded.transponder_config, msg.raw, sizeof(rx.decoded.transponder_config)); break; #if AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS case GDL90_ID_OWNSHIP_REPORT: + _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; // The Ownship message contains information on the GNSS position. If the Ownship GNSS // position fix is invalid, the Latitude, Longitude, and NIC fields will all have the ZERO value. The // Ownship message will be transmitted with a period of one second regardless of data status or @@ -187,7 +211,6 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) run_state.last_packet_Transponder_Ownship_ms = AP_HAL::millis(); _frontend.out_state.tx_status.NIC_NACp = rx.decoded.ownship_report.report.NIC | (rx.decoded.ownship_report.report.NACp << 4); memcpy(_frontend.out_state.tx_status.flight_id, rx.decoded.ownship_report.report.callsign, sizeof(_frontend.out_state.tx_status.flight_id)); - //_frontend.out_state.tx_status.temperature = rx.decoded.ownship_report.report.temperature; // there is no message in the vocabulary of the 200x that has board temperature break; case GDL90_ID_OWNSHIP_GEOMETRIC_ALTITUDE: @@ -202,61 +225,142 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) break; case GDL90_ID_TRANSPONDER_STATUS: - memcpy(&rx.decoded.transponder_status, msg.raw, sizeof(rx.decoded.transponder_status)); - if (rx.decoded.transponder_status.identActive) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; - } - - if (rx.decoded.transponder_status.modeAEnabled) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; - } + { + _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; + switch (msg.payload[0]) { + case 1: { + // version 1 of the transponder status message is sent at 1 Hz (if UCP protocol out is enabled on the transponder) + memcpy(&rx.decoded.transponder_status, msg.raw, sizeof(rx.decoded.transponder_status)); + if (rx.decoded.transponder_status.identActive) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; + } - if (rx.decoded.transponder_status.modeCEnabled) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; - } + if (rx.decoded.transponder_status.modeAEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; + } - if (rx.decoded.transponder_status.modeSEnabled) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; - } + if (rx.decoded.transponder_status.modeCEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; + } - if (rx.decoded.transponder_status.es1090TxEnabled) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; - } + if (rx.decoded.transponder_status.modeSEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; + } - if (rx.decoded.transponder_status.x_bit) { - _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; - } else { - _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; + if (rx.decoded.transponder_status.es1090TxEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; + } + + if (rx.decoded.transponder_status.x_bit) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED; + } + + _frontend.out_state.tx_status.squawk = rx.decoded.transponder_status.squawkCode; + + if (run_state.last_packet_Transponder_Status_ms == 0 && run_state.last_packet_Transponder_Config_ms == 0) { + // If this is the first time we've seen a status message, + // and we haven't initialized the control message from the config message, + // set initial control message contents to match transponder's current behavior. + _frontend.out_state.ctrl.modeAEnabled = rx.decoded.transponder_status.modeAEnabled; + _frontend.out_state.ctrl.modeCEnabled = rx.decoded.transponder_status.modeCEnabled; + _frontend.out_state.ctrl.modeSEnabled = rx.decoded.transponder_status.modeSEnabled; + _frontend.out_state.ctrl.es1090TxEnabled = rx.decoded.transponder_status.es1090TxEnabled; + _frontend.out_state.ctrl.squawkCode = rx.decoded.transponder_status.squawkCode; + _frontend.out_state.ctrl.x_bit = rx.decoded.transponder_status.x_bit; + } + run_state.last_packet_Transponder_Status_ms = AP_HAL::millis(); +#if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED + GCS_SEND_MESSAGE(MSG_UAVIONIX_ADSB_OUT_STATUS); + run_state.last_gcs_send_message_Transponder_Status_ms = AP_HAL::millis(); +#endif + break; } + case 2: + // deprecated + break; + case 3: { + // Version 3 of the transponder status message is sent in response to the transponder control message (if UCP-HD protocol out is enabled on the transponder) + memcpy(&rx.decoded.transponder_status_v3, msg.raw, sizeof(rx.decoded.transponder_status_v3)); + + if (rx.decoded.transponder_status_v3.indicatingOnGround) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND; + } - _frontend.out_state.tx_status.squawk = rx.decoded.transponder_status.squawkCode; + if (rx.decoded.transponder_status_v3.fault) { + // unsure what fault is indicated, query heartbeat for more info + request_msg(GDL90_ID_HEARTBEAT); + } - _frontend.out_state.tx_status.fault &= ~UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL; + if (rx.decoded.transponder_status_v3.identActive) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE; + } - if (run_state.last_packet_Transponder_Status_ms == 0) { - // set initial control message contents to transponder defaults - _frontend.out_state.ctrl.modeAEnabled = rx.decoded.transponder_status.modeAEnabled; - _frontend.out_state.ctrl.modeCEnabled = rx.decoded.transponder_status.modeCEnabled; - _frontend.out_state.ctrl.modeSEnabled = rx.decoded.transponder_status.modeSEnabled; - _frontend.out_state.ctrl.es1090TxEnabled = rx.decoded.transponder_status.es1090TxEnabled; - _frontend.out_state.ctrl.squawkCode = rx.decoded.transponder_status.squawkCode; - _frontend.out_state.ctrl.x_bit = rx.decoded.transponder_status.x_bit; - } - run_state.last_packet_Transponder_Status_ms = AP_HAL::millis(); + if (rx.decoded.transponder_status_v3.modeAEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED; + } + + if (rx.decoded.transponder_status_v3.modeCEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED; + } + + if (rx.decoded.transponder_status_v3.modeSEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED; + } + + if (rx.decoded.transponder_status_v3.es1090TxEnabled) { + _frontend.out_state.tx_status.state |= UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; + } else { + _frontend.out_state.tx_status.state &= ~UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED; + } + + _frontend.out_state.tx_status.squawk = rx.decoded.transponder_status_v3.squawkCode; + _frontend.out_state.tx_status.NIC_NACp = rx.decoded.transponder_status_v3.NIC | (rx.decoded.transponder_status_v3.NACp << 4); + _frontend.out_state.tx_status.boardTemp = rx.decoded.transponder_status_v3.temperature; + + if (run_state.last_packet_Transponder_Status_ms == 0 && run_state.last_packet_Transponder_Config_ms == 0) { + // If this is the first time we've seen a status message, + // and we haven't initialized the control message from the config message, + // set initial control message contents to match transponder's current behavior. + _frontend.out_state.ctrl.modeAEnabled = rx.decoded.transponder_status_v3.modeAEnabled; + _frontend.out_state.ctrl.modeCEnabled = rx.decoded.transponder_status_v3.modeCEnabled; + _frontend.out_state.ctrl.modeSEnabled = rx.decoded.transponder_status_v3.modeSEnabled; + _frontend.out_state.ctrl.es1090TxEnabled = rx.decoded.transponder_status_v3.es1090TxEnabled; + _frontend.out_state.ctrl.squawkCode = rx.decoded.transponder_status_v3.squawkCode; + } + run_state.last_packet_Transponder_Status_ms = AP_HAL::millis(); #if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED - GCS_SEND_MESSAGE(MSG_UAVIONIX_ADSB_OUT_STATUS); + GCS_SEND_MESSAGE(MSG_UAVIONIX_ADSB_OUT_STATUS); + run_state.last_gcs_send_message_Transponder_Status_ms = AP_HAL::millis(); #endif + break; + } + default: + break; + } break; + } #endif // AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS case GDL90_ID_TRANSPONDER_CONTROL: @@ -337,7 +441,6 @@ void AP_ADSB_uAvionix_UCP::send_Transponder_Control() gdl90Transmit((GDL90_TX_MESSAGE&)msg, sizeof(msg)); } - void AP_ADSB_uAvionix_UCP::send_GPS_Data() { GDL90_GPS_DATA_V2 msg {}; @@ -356,12 +459,19 @@ void AP_ADSB_uAvionix_UCP::send_GPS_Data() msg.altitudeGnss_mm = fix_is_good ? (_frontend._my_loc.alt * 10): INT32_MAX; // Protection Limits. FD or SBAS-based depending on state bits - msg.HPL_mm = UINT32_MAX; - msg.VPL_cm = UINT32_MAX; + // Estimate HPL based on horizontal accuracy/HFOM to a probability of 10^-7: + // Using the central limit theorem for a Gaussian distribution, + // this is 5.326724*stdDev. + // Conservatively round up to 6 as a scaling factor, + // and asssume HFOM of 95% was calculated as 2*stdDev*HDOP. + // This yields a factor of 3 to estimate HPL from horizontal accuracy. + float accHoriz; + bool gotAccHoriz = gps.horizontal_accuracy(accHoriz); + msg.HPL_mm = gotAccHoriz ? 3 * accHoriz * 1E3 : UINT32_MAX; // required to calculate NIC + msg.VPL_cm = UINT32_MAX; // unused by ping200X // Figure of Merits - float accHoriz; - msg.horizontalFOM_mm = gps.horizontal_accuracy(accHoriz) ? accHoriz * 1E3 : UINT32_MAX; + msg.horizontalFOM_mm = gotAccHoriz ? accHoriz * 1E3 : UINT32_MAX; float accVert; msg.verticalFOM_cm = gps.vertical_accuracy(accVert) ? accVert * 1E2 : UINT16_MAX; float accVel; @@ -418,14 +528,14 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui // Set flag byte in frame buffer gdl90FrameBuffer[0] = GDL90_FLAG_BYTE; uint16_t frameIndex = 1; - + // Copy and stuff all payload bytes into frame buffer for (uint16_t i = 0; i < length+2; i++) { // Check for overflow of frame buffer if (frameIndex >= GDL90_TX_MAX_FRAME_LENGTH) { return 0; } - + uint8_t data; // Append CRC to payload if (i == length) { @@ -433,7 +543,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui } else if (i == length+1) { data = HIGHBYTE(frameCrc); } else { - data = message.raw[i]; + data = message.raw[i]; } if (data == GDL90_FLAG_BYTE || data == GDL90_CONTROL_ESCAPE_BYTE) { @@ -441,7 +551,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui if (frameIndex + 2 > GDL90_TX_MAX_FRAME_LENGTH) { return 0; } - + // Set control break and stuff this byte gdl90FrameBuffer[frameIndex++] = GDL90_CONTROL_ESCAPE_BYTE; gdl90FrameBuffer[frameIndex++] = data ^ GDL90_STUFF_BYTE; @@ -449,7 +559,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui gdl90FrameBuffer[frameIndex++] = data; } } - + // Add end of frame indication gdl90FrameBuffer[frameIndex++] = GDL90_FLAG_BYTE; @@ -457,7 +567,7 @@ uint16_t AP_ADSB_uAvionix_UCP::gdl90Transmit(GDL90_TX_MESSAGE &message, const ui if (hostTransmit(gdl90FrameBuffer, frameIndex)) { return frameIndex; } - + return 0; } diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.h b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.h index 7b32a5cc2e5de4..abf76569aa3a16 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.h +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.h @@ -24,11 +24,6 @@ #define AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS 1 - -#include -#include -#include - #include "GDL90_protocol/GDL90_Message_Structs.h" #include "GDL90_protocol/hostGDL90Support.h" @@ -69,6 +64,7 @@ class AP_ADSB_uAvionix_UCP : public AP_ADSB_Backend { GDL90_TRANSPONDER_CONFIG_MSG_V4_V5 transponder_config; GDL90_HEARTBEAT heartbeat; GDL90_TRANSPONDER_STATUS_MSG transponder_status; + GDL90_TRANSPONDER_STATUS_MSG_V3 transponder_status_v3; #if AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS GDL90_OWNSHIP_REPORT ownship_report; GDL90_OWNSHIP_GEO_ALTITUDE ownship_geometric_altitude; @@ -78,11 +74,19 @@ class AP_ADSB_uAvionix_UCP : public AP_ADSB_Backend { } rx; struct { - uint32_t last_packet_GPS_ms; - uint32_t last_packet_Transponder_Control_ms; - uint32_t last_packet_Transponder_Status_ms; - uint32_t last_packet_Transponder_Heartbeat_ms; - uint32_t last_packet_Transponder_Ownship_ms; + uint32_t last_packet_GPS_ms; // out + uint32_t last_packet_Transponder_Control_ms; // out + uint32_t last_packet_Transponder_Status_ms; // in + uint32_t last_packet_Transponder_Heartbeat_ms; // in + uint32_t last_packet_Transponder_Ownship_ms; // in + uint32_t last_gcs_send_message_Transponder_Status_ms; // out + uint32_t last_packet_Request_Transponder_Config_ms; // out + uint32_t last_packet_Transponder_Config_ms; // in + uint32_t request_Transponder_Config_tries; + uint32_t last_packet_Request_Transponder_Id_ms; // out + uint32_t last_packet_Transponder_Id_ms; // in + uint32_t request_Transponder_Id_tries; + } run_state; }; diff --git a/libraries/AP_ADSB/GDL90_protocol/GDL90_Message_Structs.h b/libraries/AP_ADSB/GDL90_protocol/GDL90_Message_Structs.h index 4a386c73865f78..36a549d8af6c92 100644 --- a/libraries/AP_ADSB/GDL90_protocol/GDL90_Message_Structs.h +++ b/libraries/AP_ADSB/GDL90_protocol/GDL90_Message_Structs.h @@ -1,22 +1,22 @@ /* - Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved. + Copyright (C) 2021 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 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. + 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 . + You should have received a copy of the GNU General Public License + along with this program. If not, see . - - Author: GDL90/UCP protocol by uAvionix, 2021. - Implemented by: Tom Pittenger + + Author: GDL90/UCP protocol by uAvionix, 2021. + Implemented by: Tom Pittenger */ #include @@ -25,632 +25,629 @@ typedef enum __attribute__((__packed__)) { - GDL90_ID_HEARTBEAT = 0, - GDL90_ID_OWNSHIP_REPORT = 10, // 0x0A - GDL90_ID_OWNSHIP_GEOMETRIC_ALTITUDE = 11, // 0x0B - GDL90_ID_IDENTIFICATION = 37, // 0x25 - GDL90_ID_SENSOR_MESSAGE = 40, // 0x28 - GDL90_ID_TRANSPONDER_CONFIG = 43, // 0x2B - GDL90_ID_MESSAGE_REQUEST = 44, // 0x2C - GDL90_ID_TRANSPONDER_CONTROL = 45, // 0x2D - GDL90_ID_GPS_DATA = 46, // 0x2E - GDL90_ID_TRANSPONDER_STATUS = 47, // 0x2F + GDL90_ID_HEARTBEAT = 0, + GDL90_ID_OWNSHIP_REPORT = 10, // 0x0A + GDL90_ID_OWNSHIP_GEOMETRIC_ALTITUDE = 11, // 0x0B + GDL90_ID_IDENTIFICATION = 37, // 0x25 + GDL90_ID_SENSOR_MESSAGE = 40, // 0x28 + GDL90_ID_TRANSPONDER_CONFIG = 43, // 0x2B + GDL90_ID_MESSAGE_REQUEST = 44, // 0x2C + GDL90_ID_TRANSPONDER_CONTROL = 45, // 0x2D + GDL90_ID_GPS_DATA = 46, // 0x2E + GDL90_ID_TRANSPONDER_STATUS = 47, // 0x2F } GDL90_MESSAGE_ID; -typedef enum __attribute__((__packed__)) +typedef enum __attribute__((__packed__)) { - ADSB_NIC_BARO_UNVERIFIED = 0, // Baro is Gilman bases, and not cross checked - ADSB_NIC_BARO_VERIFIED = 1, // Baro is cross-checked, or not Gilman based + ADSB_NIC_BARO_UNVERIFIED = 0, // Baro is Gilman bases, and not cross checked + ADSB_NIC_BARO_VERIFIED = 1, // Baro is cross-checked, or not Gilman based } ADSB_NIC_BARO; // Barometric Altitude Integrity Code typedef enum __attribute__((__packed__)) { - ADSB_AIRBORNE_SUBSONIC = 0, - ADSB_AIRBORNE_SUPERSONIC = 1, - ADSB_ON_GROUND = 2, - // 3 Reserved + ADSB_AIRBORNE_SUBSONIC = 0, + ADSB_AIRBORNE_SUPERSONIC = 1, + ADSB_ON_GROUND = 2, + // 3 Reserved } ADSB_AIR_GROUND_STATE; // Determines how horizontal velocity fields are processed in UAT -typedef enum __attribute__((__packed__)) -{ - ADSB_EMERGENCY_NONE = 0, - ADSB_EMERGENCY_GENERAL = 1, - ADSB_EMERGENCY_MEDICAL = 2, - ADSB_EMERGENCY_MINIMUM_FUEL = 3, - ADSB_EMERGENCY_NO_COMMUNICATION = 4, - ADSB_EMERGNECY_INTERFERENCE = 5, - ADSB_EMERGENCY_DOWNED_AIRCRAFT = 6, - ADSB_EMERGENCY_UAS_LOST_LINK = 7, - // 7 Reserved +typedef enum __attribute__((__packed__)) +{ + ADSB_EMERGENCY_NONE = 0, + ADSB_EMERGENCY_GENERAL = 1, + ADSB_EMERGENCY_MEDICAL = 2, + ADSB_EMERGENCY_MINIMUM_FUEL = 3, + ADSB_EMERGENCY_NO_COMMUNICATION = 4, + ADSB_EMERGNECY_INTERFERENCE = 5, + ADSB_EMERGENCY_DOWNED_AIRCRAFT = 6, + ADSB_EMERGENCY_UAS_LOST_LINK = 7, + // 7 Reserved } ADSB_EMERGENCY_STATUS; #define GDL90_TRANSPONDER_CONTROL_VERSION (2) #if GDL90_TRANSPONDER_CONTROL_VERSION == 1 typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - ADSB_NIC_BARO baroCrossChecked : 1; - ADSB_AIR_GROUND_STATE airGroundState : 2; - uint8_t identActive : 1; - uint8_t modeAEnabled : 1; - uint8_t modeCEnabled : 1; - uint8_t modeSEnabled : 1; - uint8_t es1090TxEnabled : 1; - int32_t externalBaroAltitude_mm; - uint16_t squawkCode; - ADSB_EMERGENCY_STATUS emergencyState; - uint8_t callsign[8]; + GDL90_MESSAGE_ID messageId; + uint8_t version; + ADSB_NIC_BARO baroCrossChecked : 1; + ADSB_AIR_GROUND_STATE airGroundState : 2; + uint8_t identActive : 1; + uint8_t modeAEnabled : 1; + uint8_t modeCEnabled : 1; + uint8_t modeSEnabled : 1; + uint8_t es1090TxEnabled : 1; + int32_t externalBaroAltitude_mm; + uint16_t squawkCode; + ADSB_EMERGENCY_STATUS emergencyState; + uint8_t callsign[8]; } GDL90_TRANSPONDER_CONTROL_MSG; #elif GDL90_TRANSPONDER_CONTROL_VERSION == 2 typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - ADSB_NIC_BARO baroCrossChecked : 1; - ADSB_AIR_GROUND_STATE airGroundState : 2; - uint8_t identActive : 1; - uint8_t modeAEnabled : 1; - uint8_t modeCEnabled : 1; - uint8_t modeSEnabled : 1; - uint8_t es1090TxEnabled : 1; - int32_t externalBaroAltitude_mm; - uint16_t squawkCode; - ADSB_EMERGENCY_STATUS emergencyState; - uint8_t callsign[8]; - uint8_t rfu : 7; - uint8_t x_bit : 1; + GDL90_MESSAGE_ID messageId; + uint8_t version; + ADSB_NIC_BARO baroCrossChecked : 1; + ADSB_AIR_GROUND_STATE airGroundState : 2; + uint8_t identActive : 1; + uint8_t modeAEnabled : 1; + uint8_t modeCEnabled : 1; + uint8_t modeSEnabled : 1; + uint8_t es1090TxEnabled : 1; + int32_t externalBaroAltitude_mm; + uint16_t squawkCode; + ADSB_EMERGENCY_STATUS emergencyState; + uint8_t callsign[8]; + uint8_t rfu : 7; + uint8_t x_bit : 1; } GDL90_TRANSPONDER_CONTROL_MSG; #endif -#define GDL90_TRANSPONDER_STATUS_VERSION (1) // Version 1 is the correct UCP format; version 3 is half-duplex and not used by the ping200x #define GDL90_STATUS_MAX_ALTITUDE_FT (101338) #define GDL90_STATUS_MIN_ALTITUDE_FT (-1000) -#if GDL90_TRANSPONDER_STATUS_VERSION == 1 typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - uint8_t rfu : 2; - uint8_t x_bit : 1; - uint8_t identActive : 1; - uint8_t modeAEnabled : 1; - uint8_t modeCEnabled : 1; - uint8_t modeSEnabled : 1; - uint8_t es1090TxEnabled : 1; - uint16_t modeARepliesPerSecond; - uint16_t modecRepliesPerSecond; - uint16_t modeSRepliesPerSecond; - uint16_t squawkCode; + GDL90_MESSAGE_ID messageId; + uint8_t version; + uint8_t rfu : 2; + uint8_t x_bit : 1; + uint8_t identActive : 1; + uint8_t modeAEnabled : 1; + uint8_t modeCEnabled : 1; + uint8_t modeSEnabled : 1; + uint8_t es1090TxEnabled : 1; + uint16_t modeARepliesPerSecond; + uint16_t modecRepliesPerSecond; + uint16_t modeSRepliesPerSecond; + uint16_t squawkCode; + uint16_t crc; } GDL90_TRANSPONDER_STATUS_MSG; -#endif -#if GDL90_TRANSPONDER_STATUS_VERSION == 3 + typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - uint8_t indicatingOnGround : 1; - uint8_t interrogatedSinceLast : 1; - uint8_t fault : 1; - uint8_t identActive : 1; - uint8_t modeAEnabled : 1; - uint8_t modeCEnabled : 1; - uint8_t modeSEnabled : 1; - uint8_t es1090TxEnabled : 1; - uint8_t latitude[3]; - uint8_t longitude[3]; - uint32_t track_Heading : 8; - uint32_t horizontalVelocity :12; - uint32_t altitude :12; - uint16_t squawkCode; - uint8_t NIC : 4; - uint8_t NACp : 4; - uint8_t temperature; - uint16_t crc; -} GDL90_TRANSPONDER_STATUS_MSG; -#endif + GDL90_MESSAGE_ID messageId; + uint8_t version; + uint8_t indicatingOnGround : 1; + uint8_t interrogatedSinceLast : 1; + uint8_t fault : 1; + uint8_t identActive : 1; + uint8_t modeAEnabled : 1; + uint8_t modeCEnabled : 1; + uint8_t modeSEnabled : 1; + uint8_t es1090TxEnabled : 1; + uint8_t latitude[3]; + uint8_t longitude[3]; + uint32_t track_Heading : 8; + uint32_t horizontalVelocity :12; + uint32_t altitude :12; + uint16_t squawkCode; + uint8_t NIC : 4; + uint8_t NACp : 4; + uint8_t temperature; + uint16_t crc; +} GDL90_TRANSPONDER_STATUS_MSG_V3; typedef struct __attribute__((__packed__)) { - uint8_t HPLfdeActive : 1; - uint8_t fault : 1; - uint8_t HrdMagNorth : 1; - uint8_t reserved : 5; + uint8_t HPLfdeActive : 1; + uint8_t fault : 1; + uint8_t HrdMagNorth : 1; + uint8_t reserved : 5; } GDL90_GPS_NAV_STATE; typedef enum __attribute__((__packed__)) { - GPS_FIX_NONE = 0, - GPS_FIX_NO_FIX = 1, - GPS_FIX_2D = 2, - GPS_FIX_3D = 3, - GPS_FIX_DIFFERENTIAL = 4, - GPS_FIX_RTK = 5, + GPS_FIX_NONE = 0, + GPS_FIX_NO_FIX = 1, + GPS_FIX_2D = 2, + GPS_FIX_3D = 3, + GPS_FIX_DIFFERENTIAL = 4, + GPS_FIX_RTK = 5, } GPS_FIX; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - uint32_t utcTime_s; // Time since GPS epoch - int32_t latitude_ddE7; - int32_t longitude_ddE7; - int32_t altitudeGnss_mm; // Height about WGS84 ellipsoid - // Protection Limits. FD or SBAS-based depending on state bits - uint32_t HPL_mm; - uint32_t VPL_cm; - // FOMS - uint32_t horizontalFOM_mm; - uint16_t verticalFOM_cm; - uint16_t horizontalVelocityFOM_mmps; - uint16_t verticalVelocityFOM_mmps; - // Velocities - int16_t verticalVelocity_cmps; - int32_t northVelocity_mmps; // millimeter/s - int32_t eastVelocity_mmps; - // State - GPS_FIX fixType; - GDL90_GPS_NAV_STATE navState; - uint8_t satsUsed; + GDL90_MESSAGE_ID messageId; + uint8_t version; + uint32_t utcTime_s; // Time since GPS epoch + int32_t latitude_ddE7; + int32_t longitude_ddE7; + int32_t altitudeGnss_mm; // Height about WGS84 ellipsoid + // Protection Limits. FD or SBAS-based depending on state bits + uint32_t HPL_mm; + uint32_t VPL_cm; + // FOMS + uint32_t horizontalFOM_mm; + uint16_t verticalFOM_cm; + uint16_t horizontalVelocityFOM_mmps; + uint16_t verticalVelocityFOM_mmps; + // Velocities + int16_t verticalVelocity_cmps; + int32_t northVelocity_mmps; // millimeter/s + int32_t eastVelocity_mmps; + // State + GPS_FIX fixType; + GDL90_GPS_NAV_STATE navState; + uint8_t satsUsed; } GDL90_GPS_DATA_V2; -#define GDL90_GPS_DATA_VERSION (2) +#define GDL90_GPS_DATA_VERSION (2) typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - GDL90_MESSAGE_ID reqMsgId; + GDL90_MESSAGE_ID messageId; + uint8_t version; + GDL90_MESSAGE_ID reqMsgId; } GDL90_TRANSPONDER_MESSAGE_REQUEST_V2; typedef enum __attribute__((__packed__)) { - GDL90_BARO_DATA_SOURCE_INTERNAL = 0, - GDL90_BARO_DATA_SOURCE_EXTERNAL, + GDL90_BARO_DATA_SOURCE_INTERNAL = 0, + GDL90_BARO_DATA_SOURCE_EXTERNAL, }GDL90_BARO_DATA_SOURCE; -typedef enum __attribute__((__packed__)) +typedef enum __attribute__((__packed__)) { - ADSB_SDA_UNKNOWN = 0, - ADSB_SDA_10_NEG3 = 1, - ADSB_SDA_10_NEG5 = 2, - ADSB_SDA_10_NEG7 = 3, + ADSB_SDA_UNKNOWN = 0, + ADSB_SDA_10_NEG3 = 1, + ADSB_SDA_10_NEG5 = 2, + ADSB_SDA_10_NEG7 = 3, } ADSB_SDA; // System Design Assurance typedef enum __attribute__((__packed__)) { - ADSB_SIL_UNKNOWN = 0, - ADSB_SIL_10_NEG3 = 1, - ADSB_SIL_10_NEG5 = 2, - ADSB_SIL_10_NEG7 = 3, + ADSB_SIL_UNKNOWN = 0, + ADSB_SIL_10_NEG3 = 1, + ADSB_SIL_10_NEG5 = 2, + ADSB_SIL_10_NEG7 = 3, } ADSB_SIL; // Source Integrity Level typedef enum __attribute__((__packed__)) { - ADSB_AV_LW_NO_DATA = 0, - ADSB_AV_LW_15M_23M = 1, - ADSB_AV_LW_25M_28P5M = 2, - ADSB_AV_LW_25M_34M = 3, - ADSB_AV_LW_35M_33M = 4, - ADSB_AV_LW_35M_38M = 5, - ADSB_AV_LW_45M_39P5M = 6, - ADSB_AV_LW_45M_45M = 7, - ADSB_AV_LW_55M_45M = 8, - ADSB_AV_LW_55M_52M = 9, - ADSB_AV_LW_65M_59P5M = 10, - ADSB_AV_LW_65M_67M = 11, - ADSB_AV_LW_75M_72P5M = 12, - ADSB_AV_LW_75M_80M = 13, - ADSB_AV_LW_85M_80M = 14, - ADSB_AV_LW_85M_90M = 15, + ADSB_AV_LW_NO_DATA = 0, + ADSB_AV_LW_15M_23M = 1, + ADSB_AV_LW_25M_28P5M = 2, + ADSB_AV_LW_25M_34M = 3, + ADSB_AV_LW_35M_33M = 4, + ADSB_AV_LW_35M_38M = 5, + ADSB_AV_LW_45M_39P5M = 6, + ADSB_AV_LW_45M_45M = 7, + ADSB_AV_LW_55M_45M = 8, + ADSB_AV_LW_55M_52M = 9, + ADSB_AV_LW_65M_59P5M = 10, + ADSB_AV_LW_65M_67M = 11, + ADSB_AV_LW_75M_72P5M = 12, + ADSB_AV_LW_75M_80M = 13, + ADSB_AV_LW_85M_80M = 14, + ADSB_AV_LW_85M_90M = 15, } ADSB_AIRCRAFT_LENGTH_WIDTH; typedef enum __attribute__((__packed__)) { - ADSB_NOT_UAT_IN_CAPABLE = 0, - ADSB_UAT_IN_CAPABLE = 1 + ADSB_NOT_UAT_IN_CAPABLE = 0, + ADSB_UAT_IN_CAPABLE = 1 } ADSB_UAT_IN_CAPABILITY; typedef enum __attribute__((__packed__)) { - ADSB_NOT_1090ES_IN_CAPABLE = 0, - ADSB_1090ES_IN_CAPABLE = 1 + ADSB_NOT_1090ES_IN_CAPABLE = 0, + ADSB_1090ES_IN_CAPABLE = 1 } ADSB_1090ES_IN_CAPABILITY; typedef enum __attribute__((__packed__)) { - ADSB_GPS_LON_NO_DATA = 0, - ADSB_GPS_LON_FROM_SENSOR = 1, - // 2 - 31 valid values in 2 meter increments + ADSB_GPS_LON_NO_DATA = 0, + ADSB_GPS_LON_FROM_SENSOR = 1, + // 2 - 31 valid values in 2 meter increments } ADSB_GPS_LONGITUDINAL_OFFSET; typedef enum __attribute__((__packed__)) { - ADSB_GPS_LAT_NO_DATA = 0, - ADSB_GPS_LAT_LEFT_2M = 1, - ADSB_GPS_LAT_LEFT_4M = 2, - ADSB_GPS_LAT_LEFT_6M = 3, - ADSB_GPS_LAT_0M = 4, - ADSB_GPS_LAT_RIGHT_2M = 5, - ADSB_GPS_LAT_RIGHT_4M = 6, - ADSB_GPS_LAT_RIGHT_6M = 7, + ADSB_GPS_LAT_NO_DATA = 0, + ADSB_GPS_LAT_LEFT_2M = 1, + ADSB_GPS_LAT_LEFT_4M = 2, + ADSB_GPS_LAT_LEFT_6M = 3, + ADSB_GPS_LAT_0M = 4, + ADSB_GPS_LAT_RIGHT_2M = 5, + ADSB_GPS_LAT_RIGHT_4M = 6, + ADSB_GPS_LAT_RIGHT_6M = 7, } ADSB_GPS_LATERAL_OFFSET; typedef enum __attribute__((__packed__)) { - ADSB_EMITTER_NO_INFO = 0, - ADSB_EMITTER_LIGHT = 1, - ADSB_EMITTER_SMALL = 2, - ADSB_EMITTER_LARGE = 3, - ADSB_EMITTER_HIGH_VORTEX_LARGE = 4, - ADSB_EMITTER_HEAVY = 5, - ADSB_EMITTER_HIGHLY_MANUV = 6, - ADSB_EMITTER_ROTOCRAFT = 7, - // 8 Unassigned - ADSB_EMITTER_GLIDER = 9, - ADSB_EMITTER_LIGHTER_AIR = 10, - ADSB_EMITTER_PARACHUTE = 11, - ADSB_EMITTER_ULTRA_LIGHT = 12, - // 13 Unassigned - ADSB_EMITTER_UAV = 14, - ADSB_EMITTER_SPACE = 15, - // 16 Unassigned - - // Surface types - ADSB_EMITTER_EMERGENCY_SURFACE = 17, - ADSB_EMITTER_SERVICE_SURFACE = 18, - - // Obstacle types - ADSB_EMITTER_POINT_OBSTACLE = 19, - ADSB_EMITTER_CLUSTER_OBSTACLE = 20, - ADSB_EMITTER_LINE_OBSTACLE = 21, - // 22 - 39 Reserved + ADSB_EMITTER_NO_INFO = 0, + ADSB_EMITTER_LIGHT = 1, + ADSB_EMITTER_SMALL = 2, + ADSB_EMITTER_LARGE = 3, + ADSB_EMITTER_HIGH_VORTEX_LARGE = 4, + ADSB_EMITTER_HEAVY = 5, + ADSB_EMITTER_HIGHLY_MANUV = 6, + ADSB_EMITTER_ROTOCRAFT = 7, + // 8 Unassigned + ADSB_EMITTER_GLIDER = 9, + ADSB_EMITTER_LIGHTER_AIR = 10, + ADSB_EMITTER_PARACHUTE = 11, + ADSB_EMITTER_ULTRA_LIGHT = 12, + // 13 Unassigned + ADSB_EMITTER_UAV = 14, + ADSB_EMITTER_SPACE = 15, + // 16 Unassigned + + // Surface types + ADSB_EMITTER_EMERGENCY_SURFACE = 17, + ADSB_EMITTER_SERVICE_SURFACE = 18, + + // Obstacle types + ADSB_EMITTER_POINT_OBSTACLE = 19, + ADSB_EMITTER_CLUSTER_OBSTACLE = 20, + ADSB_EMITTER_LINE_OBSTACLE = 21, + // 22 - 39 Reserved } ADSB_EMITTER; // ADSB Emitter Category typedef enum __attribute__((__packed__)) { - PING_COM_1200_BAUD = 0, - PING_COM_2400_BAUD = 1, - PING_COM_4800_BAUD = 2, - PING_COM_9600_BAUD = 3, - PING_COM_19200_BAUD = 4, - PING_COM_38400_BAUD = 5, - PING_COM_57600_BAUD = 6, - PING_COM_115200_BAUD = 7, - PING_COM_921600_BAUD = 8, + PING_COM_1200_BAUD = 0, + PING_COM_2400_BAUD = 1, + PING_COM_4800_BAUD = 2, + PING_COM_9600_BAUD = 3, + PING_COM_19200_BAUD = 4, + PING_COM_38400_BAUD = 5, + PING_COM_57600_BAUD = 6, + PING_COM_115200_BAUD = 7, + PING_COM_921600_BAUD = 8, } PING_COM_RATE; typedef enum __attribute__((__packed__)) { - CONFIG_VALIDITY_ICAO = 1 << 0, - CONFIG_VALIDITY_SIL = 1 << 1, - CONFIG_VALIDITY_SDA = 1 << 2, - CONFIG_VALIDITY_BARO_ALT_SOURCE = 1 << 3, - CONFIG_VALIDITY_AIRCRAFT_MAX_SPEED = 1 << 4, - CONFIG_VALIDITY_TEST_MODE = 1 << 5, - CONFIG_VALIDITY_ADSB_IN_CAP = 1 << 6, - CONFIG_VALIDITY_AIRCRAFT_LEN_WIDTH = 1 << 7, - CONFIG_VALIDITY_ANT_LAT_OFFSET = 1 << 8, - CONFIG_VALIDITY_ANT_LONG_OFFSET = 1 << 9, - CONFIG_VALIDITY_AIRCRAFT_REG = 1 << 10, - CONFIG_VALIDITY_AIRCRAFT_STALL_SPEED = 1 << 11, - CONFIG_VALIDITY_AIRCRAFT_EMITTER_TYPE = 1 << 12, - CONFIG_VALIDITY_DEF_1090ES_TX_MODE = 1 << 13, - CONFIG_VALIDITY_DEF_MODES_REPLY_MODE = 1 << 14, - CONFIG_VALIDITY_DEF_MODEC_REPLY_MODE = 1 << 15, - CONFIG_VALIDITY_DEF_MODEA_REPLY_MODE = 1 << 16, - CONFIG_VALIDITY_SERIAL_BAUD_RATE = 1 << 17, - CONFIG_VALIDITY_DEF_MODEA_SQUAWK = 1 << 18, - CONFIG_VALIDITY_BARO_100 = 1 << 19, - CONFIG_VALIDITY_IN_PROTOCOL = 1 << 20, - CONFIG_VALIDITY_OUT_PROTOCOL = 1 << 21, + CONFIG_VALIDITY_ICAO = 1 << 0, + CONFIG_VALIDITY_SIL = 1 << 1, + CONFIG_VALIDITY_SDA = 1 << 2, + CONFIG_VALIDITY_BARO_ALT_SOURCE = 1 << 3, + CONFIG_VALIDITY_AIRCRAFT_MAX_SPEED = 1 << 4, + CONFIG_VALIDITY_TEST_MODE = 1 << 5, + CONFIG_VALIDITY_ADSB_IN_CAP = 1 << 6, + CONFIG_VALIDITY_AIRCRAFT_LEN_WIDTH = 1 << 7, + CONFIG_VALIDITY_ANT_LAT_OFFSET = 1 << 8, + CONFIG_VALIDITY_ANT_LONG_OFFSET = 1 << 9, + CONFIG_VALIDITY_AIRCRAFT_REG = 1 << 10, + CONFIG_VALIDITY_AIRCRAFT_STALL_SPEED = 1 << 11, + CONFIG_VALIDITY_AIRCRAFT_EMITTER_TYPE = 1 << 12, + CONFIG_VALIDITY_DEF_1090ES_TX_MODE = 1 << 13, + CONFIG_VALIDITY_DEF_MODES_REPLY_MODE = 1 << 14, + CONFIG_VALIDITY_DEF_MODEC_REPLY_MODE = 1 << 15, + CONFIG_VALIDITY_DEF_MODEA_REPLY_MODE = 1 << 16, + CONFIG_VALIDITY_SERIAL_BAUD_RATE = 1 << 17, + CONFIG_VALIDITY_DEF_MODEA_SQUAWK = 1 << 18, + CONFIG_VALIDITY_BARO_100 = 1 << 19, + CONFIG_VALIDITY_IN_PROTOCOL = 1 << 20, + CONFIG_VALIDITY_OUT_PROTOCOL = 1 << 21, } CONFIG_VALIDITY; typedef union __attribute__((__packed__)) { - struct __attribute__((__packed__)) - { - uint32_t icaoValid : 1; - uint32_t silValid : 1; - uint32_t sdaValid : 1; - uint32_t baroAltSourceValid : 1; - uint32_t aircraftMaxSpeedValid : 1; - uint32_t testModeValid : 1; - uint32_t adsbInCapValid : 1; - uint32_t aircraftLenWidthValid : 1; - uint32_t aircraftLatOffsetValid : 1; - uint32_t aircraftLongOffsetValid : 1; - uint32_t aircraftRegValid : 1; - uint32_t aircraftStallSpeedValid : 1; - uint32_t aircraftEmitterCatValid : 1; - uint32_t default1090ExTxModeValid : 1; - uint32_t defaultModeSReplyModeValid : 1; - uint32_t defaultModeCReplyModeValid : 1; - uint32_t defaultModeAReplyModeValid : 1; - uint32_t serialBaudRateValid : 1; - uint32_t defaultModeASquawkValid : 1; - uint32_t baro100Valid : 1; - uint32_t inProtocolValid : 1; - uint32_t outProtocolValid : 1; - uint32_t reserved : 10; - }; - CONFIG_VALIDITY raw; + struct __attribute__((__packed__)) + { + uint32_t icaoValid : 1; + uint32_t silValid : 1; + uint32_t sdaValid : 1; + uint32_t baroAltSourceValid : 1; + uint32_t aircraftMaxSpeedValid : 1; + uint32_t testModeValid : 1; + uint32_t adsbInCapValid : 1; + uint32_t aircraftLenWidthValid : 1; + uint32_t aircraftLatOffsetValid : 1; + uint32_t aircraftLongOffsetValid : 1; + uint32_t aircraftRegValid : 1; + uint32_t aircraftStallSpeedValid : 1; + uint32_t aircraftEmitterCatValid : 1; + uint32_t default1090ExTxModeValid : 1; + uint32_t defaultModeSReplyModeValid : 1; + uint32_t defaultModeCReplyModeValid : 1; + uint32_t defaultModeAReplyModeValid : 1; + uint32_t serialBaudRateValid : 1; + uint32_t defaultModeASquawkValid : 1; + uint32_t baro100Valid : 1; + uint32_t inProtocolValid : 1; + uint32_t outProtocolValid : 1; + uint32_t reserved : 10; + }; + CONFIG_VALIDITY raw; } CONFIG_VALIDITY_BITMASK; typedef enum __attribute__((__packed__)) { - PING_PROTOCOL_NONE = 0, - PING_PROTOCOL_MAVLINK = 1 << 0, - PING_PROTOCOL_UCP = 1 << 1, - PING_PROTOCOL_APOLLO = 1 << 9, - PING_PROTOCOL_UCP_HD = 1 << 10, + PING_PROTOCOL_NONE = 0, + PING_PROTOCOL_MAVLINK = 1 << 0, + PING_PROTOCOL_UCP = 1 << 1, + PING_PROTOCOL_APOLLO = 1 << 9, + PING_PROTOCOL_UCP_HD = 1 << 10, } PING_PROTOCOL; typedef union { - struct __attribute__((__packed__)) - { - uint16_t mavlink : 1; - uint16_t ucp : 1; - uint16_t reserved1 : 7; - uint16_t apollo : 1; - uint16_t ucphd : 1; - uint16_t reserved2 : 5; - }; - PING_PROTOCOL raw; + struct __attribute__((__packed__)) + { + uint16_t mavlink : 1; + uint16_t ucp : 1; + uint16_t reserved1 : 7; + uint16_t apollo : 1; + uint16_t ucphd : 1; + uint16_t reserved2 : 5; + }; + PING_PROTOCOL raw; } PING_PROTOCOL_MASK; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t version; - uint8_t icaoAddress[3]; - uint8_t maxSpeed : 3; - GDL90_BARO_DATA_SOURCE baroAltSource : 1; - ADSB_SDA SDA : 2; - ADSB_SIL SIL : 2; - ADSB_AIRCRAFT_LENGTH_WIDTH lengthWidth : 4; - ADSB_1090ES_IN_CAPABILITY es1090InCapable : 1; - ADSB_UAT_IN_CAPABILITY uatInCapable : 1; - uint8_t testMode : 2; - ADSB_GPS_LONGITUDINAL_OFFSET longitudinalOffset : 5; - ADSB_GPS_LATERAL_OFFSET lateralOffset : 3; - uint8_t registration[8]; - uint16_t stallSpeed_cmps; - ADSB_EMITTER emitterType; - PING_COM_RATE baudRate : 4; - uint8_t modeAEnabled : 1; - uint8_t modeCEnabled : 1; - uint8_t modeSEnabled : 1; - uint8_t es1090TxEnabled : 1; - uint16_t defaultSquawk; - CONFIG_VALIDITY_BITMASK valdityBitmask; - uint8_t rfu : 7; - uint8_t baro100 : 1; - PING_PROTOCOL_MASK inProtocol; - PING_PROTOCOL_MASK outProtocol; - uint16_t crc; + GDL90_MESSAGE_ID messageId; + uint8_t version; + uint8_t icaoAddress[3]; + uint8_t maxSpeed : 3; + GDL90_BARO_DATA_SOURCE baroAltSource : 1; + ADSB_SDA SDA : 2; + ADSB_SIL SIL : 2; + ADSB_AIRCRAFT_LENGTH_WIDTH lengthWidth : 4; + ADSB_1090ES_IN_CAPABILITY es1090InCapable : 1; + ADSB_UAT_IN_CAPABILITY uatInCapable : 1; + uint8_t testMode : 2; + ADSB_GPS_LONGITUDINAL_OFFSET longitudinalOffset : 5; + ADSB_GPS_LATERAL_OFFSET lateralOffset : 3; + uint8_t registration[8]; + uint16_t stallSpeed_cmps; + ADSB_EMITTER emitterType; + PING_COM_RATE baudRate : 4; + uint8_t modeAEnabled : 1; + uint8_t modeCEnabled : 1; + uint8_t modeSEnabled : 1; + uint8_t es1090TxEnabled : 1; + uint16_t defaultSquawk; + CONFIG_VALIDITY_BITMASK valdityBitmask; + uint8_t rfu : 7; + uint8_t baro100 : 1; + PING_PROTOCOL_MASK inProtocol; + PING_PROTOCOL_MASK outProtocol; + uint16_t crc; } GDL90_TRANSPONDER_CONFIG_MSG_V4_V5; typedef struct __attribute__((__packed__)) { - uint8_t fwMajorVersion; - uint8_t fwMinorVersion; - uint8_t fwBuildVersion; - uint8_t hwId; // TODO Ugh should be 16 bits - uint64_t serialNumber; + uint8_t fwMajorVersion; + uint8_t fwMinorVersion; + uint8_t fwBuildVersion; + uint8_t hwId; // TODO Ugh should be 16 bits + uint64_t serialNumber; } GDL90_DEVICE_ID; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint8_t protocolVersion; - GDL90_DEVICE_ID primary; - GDL90_DEVICE_ID secondary; - uint8_t primaryFWID; - uint32_t primaryCRC; - uint8_t secondaryFWID; - uint32_t secondaryCRC; - uint8_t primaryFwPartNumber[15]; - uint8_t secondaryFwPartNumber[15]; - uint16_t crc; + GDL90_MESSAGE_ID messageId; + uint8_t protocolVersion; + GDL90_DEVICE_ID primary; + GDL90_DEVICE_ID secondary; + uint8_t primaryFWID; + uint32_t primaryCRC; + uint8_t secondaryFWID; + uint32_t secondaryCRC; + uint8_t primaryFwPartNumber[15]; + uint8_t secondaryFwPartNumber[15]; + uint16_t crc; } GDL90_IDENTIFICATION_V3; #define GDL90_IDENT_PROTOCOL_VERSION (3) typedef struct __attribute__((__packed__)) { - struct - { - uint8_t uatInitialized : 1; - - // GDL90 public spec defines next bit as reserved - // uAvionix maps extra failure condition - uint8_t functionFailureGnssDataFrequency : 1; - - uint8_t ratcs : 1; - uint8_t gpsBatteryLow : 1; - uint8_t addressType : 1; - uint8_t ident : 1; - uint8_t maintenanceRequired : 1; - uint8_t gpsPositionValid : 1; - } one; - struct __attribute__((__packed__)) - { - - uint8_t utcOk : 1; - - // GDL90 public spec defines next four bits as reserved - // uAvionix maps extra failure conditions - uint8_t functionFailureGnssUnavailable : 1; - uint8_t functionFailureGnssNo3dFix : 1; - uint8_t functionFailureBroadcastMonitor : 1; - uint8_t functionFailureTransmitSystem : 1; - - uint8_t csaNotAvailable : 1; - uint8_t csaRequested : 1; - uint8_t timestampMsb : 1; - } two; + struct + { + uint8_t uatInitialized : 1; + + // GDL90 public spec defines next bit as reserved + // uAvionix maps extra failure condition + uint8_t functionFailureGnssDataFrequency : 1; + + uint8_t ratcs : 1; + uint8_t gpsBatteryLow : 1; + uint8_t addressType : 1; + uint8_t ident : 1; + uint8_t maintenanceRequired : 1; + uint8_t gpsPositionValid : 1; + } one; + struct __attribute__((__packed__)) + { + + uint8_t utcOk : 1; + + // GDL90 public spec defines next four bits as reserved + // uAvionix maps extra failure conditions + uint8_t functionFailureGnssUnavailable : 1; + uint8_t functionFailureGnssNo3dFix : 1; + uint8_t functionFailureBroadcastMonitor : 1; + uint8_t functionFailureTransmitSystem : 1; + + uint8_t csaNotAvailable : 1; + uint8_t csaRequested : 1; + uint8_t timestampMsb : 1; + } two; } GDL90_HEARTBEAT_STATUS; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - GDL90_HEARTBEAT_STATUS status; - uint16_t timestamp; + GDL90_MESSAGE_ID messageId; + GDL90_HEARTBEAT_STATUS status; + uint16_t timestamp; - // Need to flip before TX - union - { - struct __attribute__((__packed__)) + // Need to flip before TX + union { - uint16_t uatMessages : 10; - uint16_t rfu : 1; - uint16_t uplinkMessages : 5; + struct __attribute__((__packed__)) + { + uint16_t uatMessages : 10; + uint16_t rfu : 1; + uint16_t uplinkMessages : 5; + }; + uint16_t messageCount; }; - uint16_t messageCount; - }; - uint16_t crc; + uint16_t crc; } GDL90_HEARTBEAT; typedef enum __attribute__((__packed__)) { - GDL90_ADDRESS_ADSB_ICAO, - GDL90_ADDRESS_ADSB_SELF_ASSIGNED, - GDL90_ADDRESS_TISB_ICAO, - GDL90_ADDRESS_TISB_TRACK_ID, - GDL90_ADDRESS_SURFACE, - GDL90_ADDRESS_GROUND_BEACON, + GDL90_ADDRESS_ADSB_ICAO, + GDL90_ADDRESS_ADSB_SELF_ASSIGNED, + GDL90_ADDRESS_TISB_ICAO, + GDL90_ADDRESS_TISB_TRACK_ID, + GDL90_ADDRESS_SURFACE, + GDL90_ADDRESS_GROUND_BEACON, } GDL90_ADDRESS_TYPE; typedef enum __attribute__((__packed__)) { - GDL90_NO_ALERT, - GDL90_ALERT, + GDL90_NO_ALERT, + GDL90_ALERT, } GDL90_TRAFFIC_ALERT; typedef enum __attribute__((__packed__)) { - GDL90_MISC_INVALID, - GDL90_MISC_TRUE_TRACK, - GDL90_MISC_HEADING_MAGNETIC, - GDL90_MISC_HEADING_TRUE, + GDL90_MISC_INVALID, + GDL90_MISC_TRUE_TRACK, + GDL90_MISC_HEADING_MAGNETIC, + GDL90_MISC_HEADING_TRUE, } GDL90_MISC_TRACK_TYPE; typedef enum __attribute__((__packed__)) { - GDL90_MISC_REPORT_UPDATED, - GDL90_MISC_REPORT_EXTRAPOLATED, + GDL90_MISC_REPORT_UPDATED, + GDL90_MISC_REPORT_EXTRAPOLATED, } GDL90_MISC_REPORT_TYPE; typedef enum __attribute__((__packed__)) { - GDL90_MISC_ON_GROUND, - GDL90_MISC_AIRBORNE, + GDL90_MISC_ON_GROUND, + GDL90_MISC_AIRBORNE, } GDL90_MISC_AG_STATE; typedef union { - struct __attribute__((__packed__)) - { - GDL90_MISC_TRACK_TYPE track : 2; - GDL90_MISC_REPORT_TYPE reportType : 1; - GDL90_MISC_AG_STATE agState : 1; - }; - uint8_t data; + struct __attribute__((__packed__)) + { + GDL90_MISC_TRACK_TYPE track : 2; + GDL90_MISC_REPORT_TYPE reportType : 1; + GDL90_MISC_AG_STATE agState : 1; + }; + uint8_t data; } GDL90_MISCELLANEOUS; typedef struct __attribute__((__packed__)) { - GDL90_ADDRESS_TYPE addressType: 4; - GDL90_TRAFFIC_ALERT trafficAlert : 4; + GDL90_ADDRESS_TYPE addressType: 4; + GDL90_TRAFFIC_ALERT trafficAlert : 4; - uint8_t address[3]; + uint8_t address[3]; - uint8_t latitude[3]; // 180 deg / 2^23 - uint8_t longitude[3]; // 180 deg / 2^23 + uint8_t latitude[3]; // 180 deg / 2^23 + uint8_t longitude[3]; // 180 deg / 2^23 - // Byte order must be flipped before TX - union - { - struct __attribute__((__packed__)) + // Byte order must be flipped before TX + union { - uint16_t misc : 4; - uint16_t altitude : 12; + struct __attribute__((__packed__)) + { + uint16_t misc : 4; + uint16_t altitude : 12; + }; + uint16_t altitudeMisc; }; - uint16_t altitudeMisc; - }; - uint8_t NACp : 4; - uint8_t NIC : 4; + uint8_t NACp : 4; + uint8_t NIC : 4; - // Byte order must be flipped before TX - union - { - struct __attribute__((__packed__)) + // Byte order must be flipped before TX + union { - uint32_t heading : 8; - uint32_t verticalVelocity : 12; - uint32_t horizontalVelocity : 12; + struct __attribute__((__packed__)) + { + uint32_t heading : 8; + uint32_t verticalVelocity : 12; + uint32_t horizontalVelocity : 12; + }; + uint32_t velocities; }; - uint32_t velocities; - }; - uint8_t emitterCategory; - uint8_t callsign[8]; + uint8_t emitterCategory; + uint8_t callsign[8]; - uint8_t rfu : 4; - uint8_t emergencyCode : 4; + uint8_t rfu : 4; + uint8_t emergencyCode : 4; } GDL90_REPORT; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - GDL90_REPORT report; - uint16_t crc; + GDL90_MESSAGE_ID messageId; + GDL90_REPORT report; + uint16_t crc; } GDL90_OWNSHIP_REPORT; typedef GDL90_OWNSHIP_REPORT GDL90_TRAFFIC_REPORT; typedef enum __attribute__((__packed__)) { - GDL90_NO_WARNING, - GDL90_WARNING, + GDL90_NO_WARNING, + GDL90_WARNING, } GDL90_VERTICAL_WARNING; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - uint16_t geometricAltitude; // 5 ft resolution + GDL90_MESSAGE_ID messageId; + uint16_t geometricAltitude; // 5 ft resolution - // Must be endian swapped before TX - union - { - struct __attribute__((__packed__)) + // Must be endian swapped before TX + union { - uint16_t verticalFOM : 15; - GDL90_VERTICAL_WARNING verticalWarning : 1; + struct __attribute__((__packed__)) + { + uint16_t verticalFOM : 15; + GDL90_VERTICAL_WARNING verticalWarning : 1; + }; + uint16_t veritcalMetrics; }; - uint16_t veritcalMetrics; - }; - uint16_t crc; + uint16_t crc; } GDL90_OWNSHIP_GEO_ALTITUDE; typedef enum __attribute__((__packed__)) { - GDL90_SENSOR_AHRS = 0, - GDL90_SENSOR_BARO = 1, - GDL90_SENSOR_CO = 2, - GDL90_SENSOR_DEVICE = 3 + GDL90_SENSOR_AHRS = 0, + GDL90_SENSOR_BARO = 1, + GDL90_SENSOR_CO = 2, + GDL90_SENSOR_DEVICE = 3 } GDL90_SENSOR_TYPE; typedef struct __attribute__((__packed__)) { - GDL90_MESSAGE_ID messageId; - GDL90_SENSOR_TYPE sensorType; - uint32_t pressure_mbarE2; - int32_t pressureAlt_mm; - int16_t temperature_cE2; - uint16_t crc; + GDL90_MESSAGE_ID messageId; + GDL90_SENSOR_TYPE sensorType; + uint32_t pressure_mbarE2; + int32_t pressureAlt_mm; + int16_t temperature_cE2; + uint16_t crc; } GDL90_SENSOR_BARO_MESSAGE; diff --git a/libraries/AP_ADSB/GDL90_protocol/hostGDL90Support.h b/libraries/AP_ADSB/GDL90_protocol/hostGDL90Support.h index 2020ab437b49a2..0d4d07d0aa4314 100644 --- a/libraries/AP_ADSB/GDL90_protocol/hostGDL90Support.h +++ b/libraries/AP_ADSB/GDL90_protocol/hostGDL90Support.h @@ -1,22 +1,22 @@ /* - Copyright (C) 2021 Kraus Hamdani Aerospace Inc. All rights reserved. + Copyright (C) 2021 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 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. + 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 . + You should have received a copy of the GNU General Public License + along with this program. If not, see . - - Author: GDL90/UCP protocol by uAvionix, 2021. - Implemented by: Tom Pittenger + + Author: GDL90/UCP protocol by uAvionix, 2021. + Implemented by: Tom Pittenger */ #ifndef _GDL90_H_ @@ -24,60 +24,57 @@ #include -#define GDL90_QUEUE_LENGTH (2) +#define GDL90_QUEUE_LENGTH (2) -#define GDL90_FLAG_BYTE (0x7E) -#define GDL90_CONTROL_ESCAPE_BYTE (0x7D) -#define GDL90_STUFF_BYTE (0x20) -#define GDL90_OVERHEAD_LENGTH (3) // Not counting framing bytes +#define GDL90_FLAG_BYTE (0x7E) +#define GDL90_CONTROL_ESCAPE_BYTE (0x7D) +#define GDL90_STUFF_BYTE (0x20) +#define GDL90_OVERHEAD_LENGTH (3) // Not counting framing bytes // Transmit message sizes -#define GDL90_TX_MAX_PAYLOAD_LENGTH (552) -#define GDL90_TX_MAX_PACKET_LENGTH (GDL90_TX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) -#define GDL90_TX_MAX_FRAME_LENGTH (2 + ((15 * GDL90_TX_MAX_PACKET_LENGTH) / 10)) // IF every other byte was stuffed +#define GDL90_TX_MAX_PAYLOAD_LENGTH (552) +#define GDL90_TX_MAX_PACKET_LENGTH (GDL90_TX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) +#define GDL90_TX_MAX_FRAME_LENGTH (2 + ((15 * GDL90_TX_MAX_PACKET_LENGTH) / 10)) // IF every other byte was stuffed // Receive message sizes -#define GDL90_RX_MAX_PAYLOAD_LENGTH (128) -#define GDL90_RX_MAX_PACKET_LENGTH (GDL90_RX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) +#define GDL90_RX_MAX_PAYLOAD_LENGTH (128) +#define GDL90_RX_MAX_PACKET_LENGTH (GDL90_RX_MAX_PAYLOAD_LENGTH + GDL90_OVERHEAD_LENGTH) typedef union __attribute__((__packed__)) { - struct __attribute__((__packed__)) - { - GDL90_MESSAGE_ID messageId; - uint8_t payload[GDL90_TX_MAX_PAYLOAD_LENGTH]; - uint16_t crc; // Actually CRC location varies. This is a placeholder - }; - uint8_t raw[GDL90_TX_MAX_PACKET_LENGTH]; + struct __attribute__((__packed__)) + { + GDL90_MESSAGE_ID messageId; + uint8_t payload[GDL90_TX_MAX_PAYLOAD_LENGTH]; + uint16_t crc; // Actually CRC location varies. This is a placeholder + }; + uint8_t raw[GDL90_TX_MAX_PACKET_LENGTH]; } GDL90_TX_MESSAGE; typedef union __attribute__((__packed__)) { - struct __attribute__((__packed__)) - { - GDL90_MESSAGE_ID messageId; - uint8_t payload[GDL90_RX_MAX_PAYLOAD_LENGTH]; - uint16_t crc; // Actually CRC location varies. This is a placeholder - }; - uint8_t raw[GDL90_RX_MAX_PACKET_LENGTH]; + struct __attribute__((__packed__)) + { + GDL90_MESSAGE_ID messageId; + uint8_t payload[GDL90_RX_MAX_PAYLOAD_LENGTH]; + uint16_t crc; // Actually CRC location varies. This is a placeholder + }; + uint8_t raw[GDL90_RX_MAX_PACKET_LENGTH]; } GDL90_RX_MESSAGE; typedef enum { - GDL90_RX_IDLE, - GDL90_RX_IN_PACKET, - GDL90_RX_UNSTUFF, - //GDL90_RX_END, + GDL90_RX_IDLE, + GDL90_RX_IN_PACKET, + GDL90_RX_UNSTUFF, } GDL90_RX_STATE; typedef struct { - GDL90_RX_STATE state; - uint16_t length; - //uint32_t overflow; - //uint32_t complete; - uint8_t prev_data; + GDL90_RX_STATE state; + uint16_t length; + uint8_t prev_data; } GDL90_RX_STATUS; #endif diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 4780b75043a730..945ad67d414b6e 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -42,6 +42,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #endif +#include #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10) #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20) @@ -188,8 +189,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Param: OPTIONS // @DisplayName: Optional AHRS behaviour - // @Description: This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. - // @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL + // @Description: This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. Setting DontDisableAirspeedUsingEKF disables the EKF based innovation check for airspeed consistency + // @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL, 2:DontDisableAirspeedUsingEKF // @User: Advanced AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0), @@ -591,8 +592,8 @@ void AP_AHRS::update_EKF2(void) // Use the primary EKF to select the primary gyro const AP_InertialSensor &_ins = AP::ins(); const int8_t primary_imu = EKF2.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(); + const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth @@ -616,6 +617,22 @@ void AP_AHRS::update_EKF2(void) EKF2.getFilterStatus(filt_state); update_notify_from_filter_status(filt_state); } + + /* + if we now have an origin then set in all backends + */ + if (!done_common_origin) { + Location new_origin; + if (EKF2.getOriginLLH(new_origin)) { + done_common_origin = true; +#if HAL_NAVEKF3_AVAILABLE + EKF3.setOriginLLH(new_origin); +#endif +#if AP_AHRS_EXTERNAL_ENABLED + external.set_origin(new_origin); +#endif + } + } } } #endif @@ -660,8 +677,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(); + const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_first_usable_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_first_usable_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth @@ -685,6 +702,21 @@ void AP_AHRS::update_EKF3(void) EKF3.getFilterStatus(filt_state); update_notify_from_filter_status(filt_state); } + /* + if we now have an origin then set in all backends + */ + if (!done_common_origin) { + Location new_origin; + if (EKF3.getOriginLLH(new_origin)) { + done_common_origin = true; +#if HAL_NAVEKF2_AVAILABLE + EKF2.setOriginLLH(new_origin); +#endif +#if AP_AHRS_EXTERNAL_ENABLED + external.set_origin(new_origin); +#endif + } + } } } #endif @@ -698,6 +730,22 @@ void AP_AHRS::update_external(void) if (_active_EKF_type() == EKFType::EXTERNAL) { copy_estimates_from_backend_estimates(external_estimates); } + + /* + if we now have an origin then set in all backends + */ + if (!done_common_origin) { + Location new_origin; + if (external.get_origin(new_origin)) { + done_common_origin = true; +#if HAL_NAVEKF2_AVAILABLE + EKF2.setOriginLLH(new_origin); +#endif +#if HAL_NAVEKF3_AVAILABLE + EKF3.setOriginLLH(new_origin); +#endif + } + } } #endif // AP_AHRS_EXTERNAL_ENABLED @@ -867,7 +915,8 @@ bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const return false; } nav_filter_status filter_status; - if (fly_forward && + if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) && + fly_forward && hal.util->get_soft_armed() && get_filter_status(filter_status) && (filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) { @@ -1411,6 +1460,9 @@ bool AP_AHRS::set_origin(const Location &loc) #if HAL_NAVEKF3_AVAILABLE const bool ret3 = EKF3.setOriginLLH(loc); #endif +#if AP_AHRS_EXTERNAL_ENABLED + const bool ret_ext = external.set_origin(loc); +#endif // return success if active EKF's origin was set bool success = false; @@ -1440,7 +1492,7 @@ bool AP_AHRS::set_origin(const Location &loc) #endif #if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: - // don't allow origin set with external AHRS + success = ret_ext; break; #endif } @@ -1822,7 +1874,7 @@ void AP_AHRS::get_relative_position_D_home(float &posD) const const auto &gps = AP::gps(); if (_gps_use == GPSUse::EnableWithHeight && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { - posD = (get_home().alt - gps.location().alt) * 0.01; + posD = (_home.alt - gps.location().alt) * 0.01; return; } #endif @@ -2338,7 +2390,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra #if HAL_NAVEKF2_AVAILABLE EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride); #endif -#if HAL_NAVEKF3_AVAILABLE +#if EK3_FEATURE_OPTFLOW_FUSION EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride); #endif } @@ -2346,7 +2398,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra // retrieve latest corrected optical flow samples (used for calibration) bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const { -#if HAL_NAVEKF3_AVAILABLE +#if EK3_FEATURE_OPTFLOW_FUSION return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred); #endif return false; @@ -3112,7 +3164,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 #if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: - return false; + return external.get_variances(velVar, posVar, hgtVar, magVar, tasVar); #endif } @@ -3170,7 +3222,7 @@ uint8_t AP_AHRS::get_active_airspeed_index() const #if HAL_NAVEKF3_AVAILABLE if (active_EKF_type() == EKFType::THREE) { uint8_t ret = EKF3.getActiveAirspeed(); - if (ret != 255 && airspeed->healthy(ret) && airspeed->use(ret)) { + if (ret != UINT8_MAX && airspeed->healthy(ret) && airspeed->use(ret)) { return ret; } } @@ -3215,7 +3267,7 @@ uint8_t AP_AHRS::_get_primary_IMU_index() const #endif } if (imu == -1) { - imu = AP::ins().get_primary_gyro(); + imu = AP::ins().get_first_usable_gyro(); } return imu; } @@ -3334,10 +3386,10 @@ void AP_AHRS::request_yaw_reset(void) } // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary -void AP_AHRS::set_posvelyaw_source_set(uint8_t source_set_idx) +void AP_AHRS::set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx) { #if HAL_NAVEKF3_AVAILABLE - EKF3.setPosVelYawSourceSet(source_set_idx); + EKF3.setPosVelYawSourceSet((uint8_t)source_set_idx); #endif } @@ -3536,7 +3588,7 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const // return location corresponding to vector relative to the // vehicle's origin -bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const +bool AP_AHRS::get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const { if (!get_origin(loc)) { return false; @@ -3548,7 +3600,7 @@ bool AP_AHRS::get_location_from_origin_offset(Location &loc, const Vector3p &off // return location corresponding to vector relative to the // vehicle's home location -bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const +bool AP_AHRS::get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const { if (!home_is_set()) { return false; @@ -3559,6 +3611,24 @@ bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offse return true; } +/* + get EAS to TAS scaling + */ +float AP_AHRS::get_EAS2TAS(void) const +{ + if (is_positive(state.EAS2TAS)) { + return state.EAS2TAS; + } + return 1.0; +} + +// get air density / sea level density - decreases as altitude climbs +float AP_AHRS::get_air_density_ratio(void) const +{ + const float eas2tas = get_EAS2TAS(); + return 1.0 / sq(eas2tas); +} + // singleton instance AP_AHRS *AP_AHRS::_singleton; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 31130035514442..10f9deed01df92 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -131,6 +131,12 @@ class AP_AHRS { #endif } +#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED + void set_external_wind_estimate(float speed, float direction) { + dcm.set_external_wind_estimate(speed, direction); + } +#endif + // return the parameter AHRS_WIND_MAX in metres per second uint8_t get_max_wind() const { return _wind_max; @@ -141,10 +147,11 @@ class AP_AHRS { */ // get apparent to true airspeed ratio - float get_EAS2TAS(void) const { - return state.EAS2TAS; - } + float get_EAS2TAS(void) const; + // get air density / sea level density - decreases as altitude climbs + float get_air_density_ratio(void) const; + // return an airspeed estimate if available. return true // if we have an estimate bool airspeed_estimate(float &airspeed_ret) const; @@ -276,8 +283,8 @@ class AP_AHRS { // return location corresponding to vector relative to the // vehicle's origin - bool get_location_from_origin_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; - bool get_location_from_home_offset(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; + bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; + bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED; // Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops. // This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for. @@ -410,7 +417,7 @@ class AP_AHRS { void request_yaw_reset(void); // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary - void set_posvelyaw_source_set(uint8_t source_set_idx); + void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx); //returns index of active source set used, 0=primary, 1=secondary, 2=tertiary uint8_t get_posvelyaw_source_set() const; @@ -611,9 +618,9 @@ class AP_AHRS { // return current vibration vector for primary IMU Vector3f get_vibration(void) const; - // return primary accels, for lua + // return primary accels const Vector3f &get_accel(void) const { - return AP::ins().get_accel(); + return AP::ins().get_accel(_get_primary_accel_index()); } // return primary accel bias. This should be subtracted from @@ -1011,12 +1018,16 @@ class AP_AHRS { enum class Options : uint16_t { DISABLE_DCM_FALLBACK_FW=(1U<<0), DISABLE_DCM_FALLBACK_VTOL=(1U<<1), + DISABLE_AIRSPEED_EKF_CHECK=(1U<<2), }; AP_Int16 _options; bool option_set(Options option) const { return (_options & uint16_t(option)) != 0; } + + // true when we have completed the common origin setup + bool done_common_origin; }; namespace AP { diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index 5075f824ef44dd..aac74a5a23e148 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -167,7 +167,7 @@ AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg) // can only have one return nullptr; } - _view = new AP_AHRS_View(*this, rotation, pitch_trim_deg); + _view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg); return _view; } @@ -257,7 +257,7 @@ void AP_AHRS::Log_Write_Home_And_Origin() Write_Origin(LogOriginType::ekf_origin, ekf_orig); } - if (home_is_set()) { + if (_home_is_set) { Write_Origin(LogOriginType::ahrs_home, _home); } } @@ -265,7 +265,7 @@ void AP_AHRS::Log_Write_Home_And_Origin() // get apparent to true airspeed ratio float AP_AHRS_Backend::get_EAS2TAS(void) { - return AP::baro().get_EAS2TAS(); + return AP::baro()._get_EAS2TAS(); } // return current vibration vector for primary IMU diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index ae71df9c0a0124..0e70ce96620ab3 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -25,6 +25,7 @@ #include #include #include +#include #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 @@ -77,7 +78,7 @@ class AP_AHRS_Backend // get the index of the current primary accelerometer sensor virtual uint8_t get_primary_accel_index(void) const { #if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_primary_accel(); + return AP::ins().get_first_usable_accel(); #else return 0; #endif @@ -86,7 +87,7 @@ class AP_AHRS_Backend // get the index of the current primary gyro sensor virtual uint8_t get_primary_gyro_index(void) const { #if AP_INERTIALSENSOR_ENABLED - return AP::ins().get_primary_gyro(); + return AP::ins().get_first_usable_gyro(); #else return 0; #endif @@ -117,7 +118,7 @@ class AP_AHRS_Backend virtual void request_yaw_reset(void) {} // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary - virtual void set_posvelyaw_source_set(uint8_t source_set_idx) {} + virtual void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx) {} // reset the current gyro drift estimate // should be called if gyro offsets are recalculated diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index b26bdeb472714a..d7aa5c7cd3da50 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -107,14 +107,34 @@ AP_AHRS_DCM::update() if (now_ms - last_log_ms >= 100) { // log DCM at 10Hz last_log_ms = now_ms; - AP::logger().WriteStreaming("DCM", "TimeUS,Roll,Pitch,Yaw", - "sddd", - "F000", - "Qfff", - AP_HAL::micros64(), - degrees(roll), - degrees(pitch), - wrap_360(degrees(yaw))); + +// @LoggerMessage: DCM +// @Description: DCM Estimator Data +// @Field: TimeUS: Time since system startup +// @Field: Roll: estimated roll +// @Field: Pitch: estimated pitch +// @Field: Yaw: estimated yaw +// @Field: ErrRP: lowest estimated gyro drift error +// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate +// @Field: VWN: wind velocity, to-the-North component +// @Field: VWE: wind velocity, to-the-East component +// @Field: VWD: wind velocity, Up-to-Down component + AP::logger().WriteStreaming( + "DCM", + "TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD", + "s" "d" "d" "d" "d" "h" "n" "n" "n", + "F" "0" "0" "0" "0" "0" "0" "0" "0", + "Q" "f" "f" "f" "f" "f" "f" "f" "f", + AP_HAL::micros64(), + degrees(roll), + degrees(pitch), + wrap_360(degrees(yaw)), + get_error_rp(), + get_error_yaw(), + _wind.x, + _wind.y, + _wind.z + ); } #endif // HAL_LOGGING_ENABLED } @@ -414,7 +434,7 @@ AP_AHRS_DCM::_yaw_gain(void) const // return true if we have and should use GPS bool AP_AHRS_DCM::have_gps(void) const { - if (AP::gps().status() <= AP_GPS::NO_FIX || _gps_use == GPSUse::Disable) { + if (_gps_use == GPSUse::Disable || AP::gps().status() <= AP_GPS::NO_FIX) { return false; } return true; @@ -987,11 +1007,10 @@ void AP_AHRS_DCM::estimate_wind(void) if (diff_length > 0.2f) { // when turning, use the attitude response to estimate // wind speed - float V; const Vector3f velocityDiff = velocity - _last_vel; // estimate airspeed it using equation 6 - V = velocityDiff.length() / diff_length; + const float V = velocityDiff.length() / diff_length; const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse; const Vector3f velocitySum = velocity + _last_vel; @@ -1003,10 +1022,11 @@ void AP_AHRS_DCM::estimate_wind(void) const float sintheta = sinf(theta); const float costheta = cosf(theta); - Vector3f wind = Vector3f(); - wind.x = velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y); - wind.y = velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y); - wind.z = velocitySum.z - V * fuselageDirectionSum.z; + Vector3f wind{ + velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y), + velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y), + velocitySum.z - V * fuselageDirectionSum.z + }; wind *= 0.5f; if (wind.length() < _wind.length() + 20) { @@ -1028,6 +1048,13 @@ void AP_AHRS_DCM::estimate_wind(void) #endif } +#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED +void AP_AHRS_DCM::set_external_wind_estimate(float speed, float direction) { + _wind.x = -cosf(radians(direction)) * speed; + _wind.y = -sinf(radians(direction)) * speed; + _wind.z = 0; +} +#endif // return our current position estimate using // dead-reckoning or GPS diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 0d3dedc5b54d96..e4e13ded40fa40 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -41,8 +41,8 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { _kp(kp), gps_gain(_gps_gain), beta(_beta), - _gps_use(gps_use), - _gps_minsats(gps_minsats) + _gps_minsats(gps_minsats), + _gps_use(gps_use) { _dcm_matrix.identity(); } @@ -78,6 +78,8 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { return true; } + void set_external_wind_estimate(float speed, float direction); + // return an airspeed estimate if available. return true // if we have an estimate bool airspeed_estimate(float &airspeed_ret) const override; @@ -266,8 +268,6 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { // estimated wind in m/s Vector3f _wind; - float _imu1_weight{0.5f}; - // last time AHRS failed in milliseconds uint32_t _last_failure_ms; diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index a5d77476238d53..1530a19b3d367c 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -48,20 +48,18 @@ void AP_AHRS::Write_AOA_SSA(void) const AP::logger().WriteBlock(&aoa_ssa, sizeof(aoa_ssa)); } -// Write an attitude packet +// Write an attitude packet, targets in degrees void AP_AHRS::Write_Attitude(const Vector3f &targets) const { const struct log_Attitude pkt{ LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG), time_us : AP_HAL::micros64(), - control_roll : (int16_t)targets.x, - roll : (int16_t)roll_sensor, - control_pitch : (int16_t)targets.y, - pitch : (int16_t)pitch_sensor, - control_yaw : (uint16_t)wrap_360_cd(targets.z), - yaw : (uint16_t)wrap_360_cd(yaw_sensor), - error_rp : (uint16_t)(get_error_rp() * 100), - error_yaw : (uint16_t)(get_error_yaw() * 100), + control_roll : targets.x, + roll : degrees(roll), + control_pitch : targets.y, + pitch : degrees(pitch), + control_yaw : wrap_360(targets.z), + yaw : wrap_360(degrees(yaw)), active : uint8_t(active_EKF_type()), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); @@ -124,69 +122,21 @@ void AP_AHRS::write_video_stabilisation() const AP::logger().WriteBlock(&pkt, sizeof(pkt)); } -// Write an attitude view packet +// Write an attitude view packet, targets in degrees void AP_AHRS_View::Write_AttitudeView(const Vector3f &targets) const { const struct log_Attitude pkt{ LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG), time_us : AP_HAL::micros64(), - control_roll : (int16_t)targets.x, - roll : (int16_t)roll_sensor, - control_pitch : (int16_t)targets.y, - pitch : (int16_t)pitch_sensor, - control_yaw : (uint16_t)wrap_360_cd(targets.z), - yaw : (uint16_t)wrap_360_cd(yaw_sensor), - error_rp : (uint16_t)(get_error_rp() * 100), - error_yaw : (uint16_t)(get_error_yaw() * 100), + control_roll : targets.x, + roll : degrees(roll), + control_pitch : targets.y, + pitch : degrees(pitch), + control_yaw : wrap_360(targets.z), + yaw : wrap_360(degrees(yaw)), active : uint8_t(AP::ahrs().active_EKF_type()), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } -// Write a rate packet -void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl &attitude_control, - const AC_PosControl &pos_control) const -{ - 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 : timeus, - control_roll : degrees(rate_targets.x), - roll : degrees(get_gyro().x), - roll_out : motors.get_roll()+motors.get_roll_ff(), - control_pitch : degrees(rate_targets.y), - pitch : degrees(get_gyro().y), - pitch_out : motors.get_pitch()+motors.get_pitch_ff(), - control_yaw : degrees(rate_targets.z), - 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().z + GRAVITY_MSS) * 100.0f), - accel_out : motors.get_throttle(), - throttle_slew : motors.get_throttle_slew_rate() - }; - AP::logger().WriteBlock(&pkt_rate, sizeof(pkt_rate)); - - /* - log P/PD gain scale if not == 1.0 - */ - const Vector3f &scale = attitude_control.get_last_angle_P_scale(); - const Vector3f &pd_scale = attitude_control.get_PD_scale_logging(); - if (scale != AC_AttitudeControl::VECTORF_111 || pd_scale != AC_AttitudeControl::VECTORF_111) { - 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, - scalePD_x : pd_scale.x, - scalePD_y : pd_scale.y, - scalePD_z : pd_scale.z, - }; - AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC)); - } -} - #endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_AHRS/AP_AHRS_View.h b/libraries/AP_AHRS/AP_AHRS_View.h index ff0f2293c16510..1090e112f89beb 100644 --- a/libraries/AP_AHRS/AP_AHRS_View.h +++ b/libraries/AP_AHRS/AP_AHRS_View.h @@ -174,9 +174,6 @@ class AP_AHRS_View // Logging Functions void Write_AttitudeView(const Vector3f &targets) const; - void Write_Rate(const class AP_Motors &motors, - const class AC_AttitudeControl &attitude_control, - const AC_PosControl &pos_control) const; float roll; float pitch; diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 3b27e786065181..c7b96306bc2811 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -8,6 +8,10 @@ #define AP_AHRS_ENABLED 1 #endif +#ifndef AP_HOME_ENABLED +#define AP_HOME_ENABLED AP_AHRS_ENABLED +#endif + #ifndef AP_AHRS_BACKEND_DEFAULT_ENABLED #define AP_AHRS_BACKEND_DEFAULT_ENABLED AP_AHRS_ENABLED #endif @@ -37,3 +41,6 @@ #define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_ENABLED) #endif +#ifndef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED +#define AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_DCM_ENABLED) +#endif diff --git a/libraries/AP_AHRS/LogStructure.h b/libraries/AP_AHRS/LogStructure.h index 618ade0a5c78cb..af0c4c36d1fa4e 100644 --- a/libraries/AP_AHRS/LogStructure.h +++ b/libraries/AP_AHRS/LogStructure.h @@ -57,20 +57,16 @@ struct PACKED log_AOA_SSA { // @Field: Pitch: achieved vehicle pitch // @Field: DesYaw: vehicle desired yaw // @Field: Yaw: achieved vehicle yaw -// @Field: ErrRP: lowest estimated gyro drift error -// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate // @Field: AEKF: active EKF type struct PACKED log_Attitude { LOG_PACKET_HEADER; uint64_t time_us; - int16_t control_roll; - int16_t roll; - int16_t control_pitch; - int16_t pitch; - uint16_t control_yaw; - uint16_t yaw; - uint16_t error_rp; - uint16_t error_yaw; + float control_roll; + float roll; + float control_pitch; + float pitch; + float control_yaw; + float yaw; uint8_t active; }; @@ -109,40 +105,6 @@ struct PACKED log_POS { float rel_origin_alt; }; -// @LoggerMessage: RATE -// @Description: Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes. -// @Field: TimeUS: Time since system startup -// @Field: RDes: vehicle desired roll rate -// @Field: R: achieved vehicle roll rate -// @Field: ROut: normalized output for Roll -// @Field: PDes: vehicle desired pitch rate -// @Field: P: vehicle pitch rate -// @Field: POut: normalized output for Pitch -// @Field: Y: achieved vehicle yaw rate -// @Field: YOut: normalized output for Yaw -// @Field: YDes: vehicle desired yaw rate -// @Field: ADes: desired vehicle vertical acceleration -// @Field: A: achieved vehicle vertical acceleration -// @Field: AOut: percentage of vertical thrust output current being used -// @Field: AOutSlew: vertical thrust output slew rate -struct PACKED log_Rate { - LOG_PACKET_HEADER; - uint64_t time_us; - float control_roll; - float roll; - float roll_out; - float control_pitch; - float pitch; - float pitch_out; - float control_yaw; - float yaw; - float yaw_out; - float control_accel; - float accel; - float accel_out; - float throttle_slew; -}; - // @LoggerMessage: VSTB // @Description: Log message for video stabilisation software such as Gyroflow // @Field: TimeUS: Time since system startup @@ -199,13 +161,11 @@ struct PACKED log_ATSC { { LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA), \ "AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" , true }, \ { LOG_ATTITUDE_MSG, sizeof(log_Attitude),\ - "ATT", "QccccCCCCB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw,AEKF", "sddddhhdh-", "FBBBBBBBB-" , true }, \ + "ATT", "QffffffB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,AEKF", "sddddhh-", "F000000-" , true }, \ { LOG_ORGN_MSG, sizeof(log_ORGN), \ "ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s#DUm", "F-GGB" }, \ { LOG_POS_MSG, sizeof(log_POS), \ "POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" , true }, \ - { LOG_RATE_MSG, sizeof(log_Rate), \ - "RATE", "Qfffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut,AOutSlew", "skk-kk-kk-oo--", "F?????????BB--" , true }, \ { LOG_ATSC_MSG, sizeof(log_ATSC), \ "ATSC", "Qffffff", "TimeUS,AngPScX,AngPScY,AngPScZ,PDScX,PDScY,PDScZ", "s------", "F000000" , true }, \ { LOG_VIDEO_STABILISATION_MSG, sizeof(log_Video_Stabilisation), \ diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index a47c57ee6fc315..afb141ec5356a9 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -285,7 +285,7 @@ void AP_AIS::buffer_shift(uint8_t i) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // Functions related to the vessel list -// find vessel index in existing list, if not then return new index if possible +// find vessel index in existing list, if not then return NEW_NOTHROW index if possible bool AP_AIS::get_vessel_index(uint32_t mmsi, uint16_t &index, uint32_t lat, uint32_t lon) { const uint16_t list_size = _list.max_items(); diff --git a/libraries/AP_AIS/AP_AIS.h b/libraries/AP_AIS/AP_AIS.h index d55a08c82f8beb..2d81c37d1d3537 100644 --- a/libraries/AP_AIS/AP_AIS.h +++ b/libraries/AP_AIS/AP_AIS.h @@ -97,7 +97,7 @@ class AP_AIS // removed the given index from the AIVDM buffer shift following elements void buffer_shift(uint8_t i); - // find vessel in existing list, if not then return new index if possible + // find vessel in existing list, if not then return NEW_NOTHROW index if possible bool get_vessel_index(uint32_t mmsi, uint16_t &index, uint32_t lat = 0, uint32_t lon = 0) WARN_IF_UNUSED; void clear_list_item(uint16_t index); diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index 2c71ba01589a7a..b3dae75667bcee 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -195,7 +195,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) const AC_Fence *ap_fence = AP::fence(); if ((ap_fence != nullptr && ap_fence->get_breaches() != 0) || check_altlimit()) { if (!_terminate) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach"); _terminate.set_and_notify(1); } } @@ -213,7 +213,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) (mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) && _rc_fail_time_seconds > 0 && (AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure"); _terminate.set_and_notify(1); } @@ -241,7 +241,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) // we startup in preflight mode. This mode ends when // we first enter auto. if (mode == AFS_AUTO) { - gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO"); _state = STATE_AUTO; } break; @@ -249,7 +249,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) case STATE_AUTO: // this is the normal mode. if (!gcs_link_ok) { - gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS"); _state = STATE_DATA_LINK_LOSS; if (_wp_comms_hold) { _saved_wp = mission.get_current_nav_cmd().index; @@ -266,7 +266,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) break; } if (!gps_lock_ok) { - gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS"); _state = STATE_GPS_LOSS; if (_wp_gps_loss) { _saved_wp = mission.get_current_nav_cmd().index; @@ -287,13 +287,13 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) // leads to termination if AFS_DUAL_LOSS is 1 if(_enable_dual_loss) { if (!_terminate) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss"); _terminate.set_and_notify(1); } } } else if (gcs_link_ok) { _state = STATE_AUTO; - gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK"); if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) { break; @@ -314,11 +314,11 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) // losing GCS link when GPS lock lost // leads to termination if AFS_DUAL_LOSS is 1 if (!_terminate && _enable_dual_loss) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss"); _terminate.set_and_notify(1); } } else if (gps_lock_ok) { - gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK"); _state = STATE_AUTO; // we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS if (_saved_wp != 0 && @@ -428,7 +428,7 @@ bool AP_AdvancedFailsafe::should_crash_vehicle(void) // returns true if AFS is in the desired termination state bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { if (!_enable) { - gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle"); return false; } @@ -439,13 +439,13 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reaso if(should_terminate == is_terminating) { if (is_terminating) { - gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to %s", reason); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Terminating due to %s", reason); } else { - gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason); } return true; } else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) { - gcs().send_text(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured"); } return false; } @@ -482,7 +482,7 @@ void AP_AdvancedFailsafe::max_range_update(void) if (distance_km > _max_range_km) { uint32_t now = AP_HAL::millis(); if (now - _term_range_notice_ms > 5000) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km); _term_range_notice_ms = now; } _terminate.set_and_notify(1); diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index ac6a7b2d34b28e..e8991ca98fe879 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -157,7 +157,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _OFF_PCNT // @DisplayName: Maximum offset cal speed error - // @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered. + // @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered. // @Range: 0.0 10.0 // @Units: % // @User: Advanced @@ -356,67 +356,67 @@ void AP_Airspeed::allocate() break; case TYPE_I2C_MS4525: #if AP_AIRSPEED_MS4525_ENABLED - sensor[i] = new AP_Airspeed_MS4525(*this, i); + sensor[i] = NEW_NOTHROW AP_Airspeed_MS4525(*this, i); #endif break; case TYPE_SITL: #if AP_AIRSPEED_SITL_ENABLED - sensor[i] = new AP_Airspeed_SITL(*this, i); + sensor[i] = NEW_NOTHROW AP_Airspeed_SITL(*this, i); #endif break; case TYPE_ANALOG: #if AP_AIRSPEED_ANALOG_ENABLED - sensor[i] = new AP_Airspeed_Analog(*this, i); + sensor[i] = NEW_NOTHROW 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); + sensor[i] = NEW_NOTHROW 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); + sensor[i] = NEW_NOTHROW 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); + sensor[i] = NEW_NOTHROW 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); + sensor[i] = NEW_NOTHROW AP_Airspeed_SDP3X(*this, i); #endif break; case TYPE_I2C_DLVR_5IN: #if AP_AIRSPEED_DLVR_ENABLED - sensor[i] = new AP_Airspeed_DLVR(*this, i, 5); + sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 5); #endif break; case TYPE_I2C_DLVR_10IN: #if AP_AIRSPEED_DLVR_ENABLED - sensor[i] = new AP_Airspeed_DLVR(*this, i, 10); + sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 10); #endif break; case TYPE_I2C_DLVR_20IN: #if AP_AIRSPEED_DLVR_ENABLED - sensor[i] = new AP_Airspeed_DLVR(*this, i, 20); + sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 20); #endif break; case TYPE_I2C_DLVR_30IN: #if AP_AIRSPEED_DLVR_ENABLED - sensor[i] = new AP_Airspeed_DLVR(*this, i, 30); + sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 30); #endif break; case TYPE_I2C_DLVR_60IN: #if AP_AIRSPEED_DLVR_ENABLED - sensor[i] = new AP_Airspeed_DLVR(*this, i, 60); + sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 60); #endif // AP_AIRSPEED_DLVR_ENABLED break; case TYPE_I2C_ASP5033: #if AP_AIRSPEED_ASP5033_ENABLED - sensor[i] = new AP_Airspeed_ASP5033(*this, i); + sensor[i] = NEW_NOTHROW AP_Airspeed_ASP5033(*this, i); #endif break; case TYPE_UAVCAN: @@ -427,18 +427,18 @@ void AP_Airspeed::allocate() 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); + sensor[i] = NEW_NOTHROW AP_Airspeed_NMEA(*this, i); #endif #endif break; case TYPE_MSP: #if AP_AIRSPEED_MSP_ENABLED - sensor[i] = new AP_Airspeed_MSP(*this, i, 0); + sensor[i] = NEW_NOTHROW AP_Airspeed_MSP(*this, i, 0); #endif break; case TYPE_EXTERNAL: #if AP_AIRSPEED_EXTERNAL_ENABLED - sensor[i] = new AP_Airspeed_External(*this, i); + sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i); #endif break; } @@ -876,7 +876,10 @@ bool AP_Airspeed::enabled(uint8_t i) const { // return health status of sensor bool AP_Airspeed::healthy(uint8_t i) const { - bool ok = state[i].healthy && enabled(i) && sensor[i] != nullptr; + if (!enabled(i)) { + return false; + } + bool ok = state[i].healthy && 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); diff --git a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp index e727d5924c7fa5..279919f2e1bc61 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp @@ -78,7 +78,7 @@ bool AP_Airspeed_ASP5033::confirm_sensor_id(void) { uint8_t part_id; if (!dev->read_registers(REG_PART_ID_SET, &part_id, 1) || - part_id != REG_WHOAMI_DEFAULT_ID) { + ( (part_id != REG_WHOAMI_DEFAULT_ID) && (part_id != REG_WHOAMI_RECHECK_ID) ) ) { return false; } if (!dev->write_register(REG_PART_ID_SET, REG_WHOAMI_RECHECK_ID)) { diff --git a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp index 211c36e3283bcc..75db53a9ad1a26 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp @@ -50,7 +50,7 @@ AP_Airspeed_Backend *AP_Airspeed_DLVR::probe(AP_Airspeed &_frontend, if (!_dev) { return nullptr; } - AP_Airspeed_DLVR *sensor = new AP_Airspeed_DLVR(_frontend, _instance, _range_inH2O); + AP_Airspeed_DLVR *sensor = NEW_NOTHROW AP_Airspeed_DLVR(_frontend, _instance, _range_inH2O); if (!sensor) { return nullptr; } diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp index fc143b11c00d70..8d3dff897ae543 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -13,21 +13,15 @@ extern const AP_HAL::HAL& hal; AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[]; HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry; -void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("airspeed_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, driver_index) != nullptr) #if AP_AIRSPEED_HYGROMETER_ENABLE - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("hygrometer_sub"); - } + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, driver_index) != nullptr) #endif + ; } AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid) @@ -45,7 +39,7 @@ AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t // match with previous ID only continue; } - backend = new AP_Airspeed_DroneCAN(_frontend, _instance); + backend = NEW_NOTHROW AP_Airspeed_DroneCAN(_frontend, _instance); if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h index 2167f9f061521a..7d92c27f9555ed 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -26,7 +26,7 @@ class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend { bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override; #endif - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_Airspeed_Backend* probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid); diff --git a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp index 749fa9d6121641..97403e88b13586 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp @@ -75,7 +75,8 @@ const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = { // @Param: PIN // @DisplayName: Airspeed pin - // @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port. + // @Description: The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins". + // @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1 // @User: Advanced AP_GROUPINFO("PIN", 5, AP_Airspeed_Params, pin, 0), #endif // HAL_BUILD_AP_PERIPH diff --git a/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp index 92ab4357ccfec4..ea3e13fef2a2c1 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp @@ -33,11 +33,8 @@ bool AP_Airspeed_SITL::get_temperature(float &temperature) // 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; + temperature = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); return true; } diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 1cafcfc6e45f96..0a416d2150e1ff 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include "AP_Airspeed.h" @@ -131,7 +131,7 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t // calculate true airspeed, assuming a airspeed ratio of 1.0 float dpress = MAX(get_differential_pressure(i), 0); - float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS(); + float true_airspeed = sqrtf(dpress) * AP::ahrs().get_EAS2TAS(); float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal); @@ -177,7 +177,7 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground) vy: vground.y, vz: vground.z, diff_pressure: get_differential_pressure(primary), - EAS2TAS: AP::baro().get_EAS2TAS(), + EAS2TAS: AP::ahrs().get_EAS2TAS(), ratio: param[primary].ratio.get(), state_x: state[primary].calibration.state.x, state_y: state[primary].calibration.state.y, diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index c834d51de1f5fe..4b058abe53605e 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_Arming_config.h" + +#if AP_ARMING_ENABLED + #include "AP_Arming.h" #include #include @@ -40,7 +44,6 @@ #include #include #include -#include #include #include #include @@ -112,7 +115,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // index 4 was VOLT_MIN, moved to AP_BattMonitor // index 5 was VOLT2_MIN, moved to AP_BattMonitor - // @Param: RUDDER + // @Param{Plane,Rover,Copter,Blimp}: RUDDER // @DisplayName: Arming with Rudder enable/disable // @Description: Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode! // @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm @@ -172,7 +175,7 @@ extern AP_IOMCU iomcu; #endif #pragma GCC diagnostic push -#if defined (__clang__) +#if defined(__clang_major__) && __clang_major__ >= 14 #pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical" #endif @@ -539,7 +542,7 @@ bool AP_Arming::compass_checks(bool report) if (!_compass.learn_offsets_enabled()) #endif { - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg); return false; @@ -579,11 +582,11 @@ bool AP_Arming::compass_checks(bool report) (double)MAX(fabsf(diff_mgauss.x), (double)fabsf(diff_mgauss.y)), (int)magfield_error_threshold); return false; } - if (fabsf(diff_mgauss.x) > magfield_error_threshold*2.0) { + if (fabsf(diff_mgauss.z) > magfield_error_threshold*2.0) { check_failed(ARMING_CHECK_COMPASS, report, "Check mag field (z diff:%.0f>%d)", (double)fabsf(diff_mgauss.z), (int)magfield_error_threshold*2); return false; - } + } } #endif // AP_AHRS_ENABLED } @@ -598,8 +601,8 @@ bool AP_Arming::gps_checks(bool report) if (check_enabled(ARMING_CHECK_GPS)) { // Any failure messages from GPS backends - char failure_msg[50] = {}; - if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) { + char failure_msg[100] = {}; + if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) { if (failure_msg[0] != '\0') { check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); } @@ -645,12 +648,6 @@ bool AP_Arming::gps_checks(bool report) (double)distance_m); return false; } -#if AP_GPS_BLENDED_ENABLED - if (!gps.blend_health_check()) { - check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy"); - return false; - } -#endif // check AHRS and GPS are within 10m of each other if (gps.num_sensors() > 0) { @@ -738,19 +735,21 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method) check_failed(ARMING_CHECK_PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number()); check_passed = false; } - const RCMapper * rcmap = AP::rcmap(); - if (rcmap != nullptr) { + { if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) { - const char *names[3] = {"Roll", "Pitch", "Yaw"}; - const uint8_t channels[3] = {rcmap->roll(), rcmap->pitch(), rcmap->yaw()}; - for (uint8_t i = 0; i < ARRAY_SIZE(channels); i++) { - const RC_Channel *c = rc().channel(channels[i] - 1); - if (c == nullptr) { - continue; - } + const struct { + const char *name; + const RC_Channel *channel; + } channels_to_check[] { + { "Roll", &rc().get_roll_channel(), }, + { "Pitch", &rc().get_pitch_channel(), }, + { "Yaw", &rc().get_yaw_channel(), }, + }; + for (const auto &channel_to_check : channels_to_check) { + const auto *c = channel_to_check.channel; if (c->get_control_in() != 0) { if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming - check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", names[i], channels[i]); + check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", channel_to_check.name, c->ch()); check_passed = false; } } @@ -759,13 +758,11 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method) // if throttle check is enabled, require zero input if (rc().arming_check_throttle()) { - RC_Channel *c = rc().channel(rcmap->throttle() - 1); - if (c != nullptr) { + const RC_Channel *c = &rc().get_throttle_channel(); if (c->get_control_in() != 0) { - check_failed(ARMING_CHECK_RC, true, "Throttle (RC%d) is not neutral", rcmap->throttle()); + check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", "Throttle", c->ch()); check_passed = false; } - } c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR); if (c != nullptr) { uint8_t fwd_thr = c->percent_input(); @@ -912,6 +909,7 @@ bool AP_Arming::mission_checks(bool report) bool AP_Arming::rangefinder_checks(bool report) { +#if AP_RANGEFINDER_ENABLED if (check_enabled(ARMING_CHECK_RANGEFINDER)) { RangeFinder *range = RangeFinder::get_singleton(); if (range == nullptr) { @@ -924,6 +922,7 @@ bool AP_Arming::rangefinder_checks(bool report) return false; } } +#endif return true; } @@ -1042,6 +1041,11 @@ bool AP_Arming::system_checks(bool report) return false; } + if (AP_Param::get_eeprom_full()) { + check_failed(ARMING_CHECK_PARAMETERS, report, "parameter storage full"); + return false; + } + // check main loop rate is at least 90% of expected value const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz(); const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz(); @@ -1200,7 +1204,7 @@ bool AP_Arming::proximity_checks(bool report) const bool AP_Arming::can_checks(bool report) { if (check_enabled(ARMING_CHECK_SYSTEM)) { - char fail_msg[50] = {}; + char fail_msg[100] = {}; (void)fail_msg; // might be left unused uint8_t num_drivers = AP::can().get_num_drivers(); @@ -1269,16 +1273,12 @@ bool AP_Arming::fence_checks(bool display_failure) } // check fence is ready - const char *fail_msg = nullptr; - if (fence->pre_arm_check(fail_msg)) { + char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; + if (fence->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) { return true; } - if (fail_msg == nullptr) { - check_failed(display_failure, "Check fence"); - } else { - check_failed(display_failure, "%s", fail_msg); - } + check_failed(display_failure, "%s", fail_msg); #if AP_SDCARD_STORAGE_ENABLED if (fence->failed_sdcard_storage() || StorageManager::storage_failed()) { @@ -1493,7 +1493,7 @@ bool AP_Arming::generator_checks(bool display_failure) const if (generator == nullptr) { return true; } - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "Generator: %s", failure_msg); return false; @@ -1508,7 +1508,7 @@ bool AP_Arming::opendroneid_checks(bool display_failure) { auto &opendroneid = AP::opendroneid(); - char failure_msg[50] {}; + char failure_msg[100] {}; if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "OpenDroneID: %s", failure_msg); return false; @@ -1786,11 +1786,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) 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"); - } + fence->auto_enable_fence_on_arming(); } } #endif @@ -1833,9 +1829,7 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks) #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); - } + fence->auto_disable_fence_on_disarming(); } #endif #if defined(HAL_ARM_GPIO_PIN) @@ -2042,3 +2036,5 @@ AP_Arming &arming() }; #pragma GCC diagnostic pop + +#endif // AP_ARMING_ENABLED diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index be59921be16843..69e693835b0e48 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -96,6 +96,7 @@ class AP_Arming { // these functions should not be used by Copter which holds the armed state in the motors library Required arming_required() const; virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true); + virtual bool arm_force(AP_Arming::Method method) { return arm(method, false); } virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true); bool is_armed() const; bool is_armed_and_safety_off() const; diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 14e0d286283e0b..60dd149b473652 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -144,7 +144,7 @@ void AP_Avoidance::init(void) { debug("ADSB initialisation: %d obstacles", _obstacles_max.get()); if (_obstacles == nullptr) { - _obstacles = new AP_Avoidance::Obstacle[_obstacles_max]; + _obstacles = NEW_NOTHROW AP_Avoidance::Obstacle[_obstacles_max]; if (_obstacles == nullptr) { // dynamic RAM allocation of _obstacles[] failed, disable gracefully diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 93cf7926f0d7bb..3b0a32c89896f2 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -128,7 +128,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @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 + // @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. Do not use for channels selected with SERVO_BLH_RVMASK. // @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 @@ -137,7 +137,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { #if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_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. + // @Description: Mask of channels which support bi-directional dshot telemetry. 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, 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 @@ -145,7 +145,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { #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 + // @Description: Mask of channels which are reversed. This is used to configure ESCs to reverse motor direction for unidirectional rotation. Do not use for channels selected with SERVO_BLH_3DMASK. // @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 @@ -400,13 +400,17 @@ void AP_BLHeli::msp_process_command(void) msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12); break; + // a literal "4" is used for the PWMType here to allow Rover + // to use the same number for the same protocol. At time of + // writing the AP_MotorsUGV::PWMType has not been unified with + // AP_Motors::PWMType. case MSP_ADVANCED_CONFIG: { debug("MSP_ADVANCED_CONFIG"); uint8_t buf[10]; buf[0] = 1; // gyro sync denom buf[1] = 4; // pid process denom buf[2] = 0; // use unsynced pwm - buf[3] = (uint8_t)PWM_TYPE_DSHOT150; // motor PWM protocol + buf[3] = 4; // (uint8_t)AP_Motors::PWMType::DSHOT150; putU16(&buf[4], 480); // motor PWM Rate putU16(&buf[6], 450); // idle offset value buf[8] = 0; // use 32kHz diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 84bfbadc9fd989..1f4c397718ef13 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -34,6 +34,8 @@ #include "AP_Baro_SITL.h" #include "AP_Baro_BMP085.h" #include "AP_Baro_BMP280.h" +#include "AP_Baro_BMP388.h" +#include "AP_Baro_BMP581.h" #include "AP_Baro_SPL06.h" #include "AP_Baro_KellerLD.h" #include "AP_Baro_MS5611.h" @@ -41,7 +43,6 @@ #include "AP_Baro_LPS2XH.h" #include "AP_Baro_FBM320.h" #include "AP_Baro_DPS280.h" -#include "AP_Baro_BMP388.h" #include "AP_Baro_Dummy.h" #include "AP_Baro_DroneCAN.h" #include "AP_Baro_MSP.h" @@ -74,6 +75,10 @@ #define HAL_BARO_ALLOW_INIT_NO_BARO #endif +#ifndef AP_FIELD_ELEVATION_ENABLED +#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub) +#endif + extern const AP_HAL::HAL& hal; // table of user settable parameters @@ -169,11 +174,11 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Increment: 1 AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT), -#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES || AP_BARO_MSP_ENABLED +#if AP_BARO_PROBE_EXT_PARAMETER_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 BARO_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 BARO_EXT_BUS. - // @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP + // @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP,13:BMP581 // @User: Advanced AP_GROUPINFO("_PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT), #endif @@ -213,13 +218,14 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Path: AP_Baro_Wind.cpp AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff), #endif - #if BARO_MAX_INSTANCES > 2 // @Group: 3_WCF_ // @Path: AP_Baro_Wind.cpp AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff), #endif -#ifndef HAL_BUILD_AP_PERIPH +#endif // HAL_BARO_WIND_COMP_ENABLED + +#if AP_FIELD_ELEVATION_ENABLED // @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. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level. @@ -229,7 +235,6 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @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 @@ -255,12 +260,6 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // singleton instance AP_Baro *AP_Baro::_singleton; -#if HAL_GCS_ENABLED -#define BARO_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args) -#else -#define BARO_SEND_TEXT(severity, format, args...) -#endif - /* AP_Baro constructor */ @@ -283,7 +282,7 @@ void AP_Baro::calibrate(bool save) } if (hal.util->was_watchdog_reset()) { - BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: skipping calibration after WDG reset"); return; } @@ -295,12 +294,12 @@ void AP_Baro::calibrate(bool save) #ifdef HAL_BARO_ALLOW_INIT_NO_BARO if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) { - BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration"); return; } #endif - BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibrating barometer"); // reset the altitude offset when we calibrate. The altitude // offset is supposed to be for within a flight @@ -347,7 +346,7 @@ void AP_Baro::calibrate(bool save) sensors[i].calibrated = false; } else { if (save) { - float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i]); + float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i], _field_elevation_active); sensors[i].ground_pressure.set_and_save(p0_sealevel); } } @@ -359,7 +358,7 @@ void AP_Baro::calibrate(bool save) uint8_t num_calibrated = 0; for (uint8_t i=0; i<_num_sensors; i++) { if (sensors[i].calibrated) { - BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer %u calibration complete", i+1); num_calibrated++; } } @@ -383,7 +382,7 @@ void AP_Baro::update_calibration() } for (uint8_t i=0; i<_num_sensors; i++) { if (healthy(i)) { - float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction); + float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction, _field_elevation_active); sensors[i].ground_pressure.set(corrected_pressure); } @@ -395,71 +394,13 @@ void AP_Baro::update_calibration() // always update the guessed ground temp _guessed_ground_temperature = get_external_temperature(); - - // force EAS2TAS to recalculate - _EAS2TAS = 0; -} - -// return altitude difference in meters between current pressure and a -// given base_pressure in Pascal -float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const -{ - float temp = C_TO_KELVIN(get_ground_temperature()); - float scaling = pressure / base_pressure; - - // This is an exact calculation that is within +-2.5m of the standard - // atmosphere tables in the troposphere (up to 11,000 m amsl). - return 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active; } -// 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 -// assumes standard atmosphere lapse rate -float AP_Baro::get_EAS2TAS(void) -{ - float altitude = get_altitude(); - if ((fabsf(altitude - _last_altitude_EAS2TAS) < 25.0f) && !is_zero(_EAS2TAS)) { - // not enough change to require re-calculating - return _EAS2TAS; - } - - float pressure = get_pressure(); - if (is_zero(pressure)) { - return 1.0f; - } - - // only estimate lapse rate for the difference from the ground location - // provides a more consistent reading then trying to estimate a complete - // ISA model atmosphere - float tempK = C_TO_KELVIN(get_ground_temperature()) - ISA_LAPSE_RATE * altitude; - const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); - if (!is_positive(eas2tas_squared)) { - return 1.0f; - } - _EAS2TAS = sqrtf(eas2tas_squared); - _last_altitude_EAS2TAS = altitude; - return _EAS2TAS; -} // return air density / sea level density - decreases as altitude climbs -float AP_Baro::get_air_density_ratio(void) +float AP_Baro::_get_air_density_ratio(void) { - const float eas2tas = get_EAS2TAS(); + const float eas2tas = _get_EAS2TAS(); if (eas2tas > 0.0f) { return 1.0f/(sq(eas2tas)); } else { @@ -601,7 +542,7 @@ void AP_Baro::init(void) #if !AP_TEST_DRONECAN_DRIVERS // use dronecan instances instead of SITL instances for(uint8_t i = 0; i < sitl->baro_count; i++) { - ADD_BACKEND(new AP_Baro_SITL(*this)); + ADD_BACKEND(NEW_NOTHROW AP_Baro_SITL(*this)); } #endif #endif @@ -616,7 +557,7 @@ void AP_Baro::init(void) #if AP_BARO_EXTERNALAHRS_ENABLED const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::BARO); if (serial_port >= 0) { - ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port)); + ADD_BACKEND(NEW_NOTHROW AP_Baro_ExternalAHRS(*this, serial_port)); } #endif @@ -770,7 +711,7 @@ void AP_Baro::init(void) } for (uint8_t i=0; i<8; i++) { if (msp_instance_mask & (1U<get_soft_armed(); @@ -1025,7 +974,7 @@ void AP_Baro::update_field_elevation(void) } else { _field_elevation.set(_field_elevation_active); _field_elevation.notify(); - BARO_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed"); + GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed"); } } } @@ -1033,18 +982,9 @@ void AP_Baro::update_field_elevation(void) _field_elevation_last_ms = now_ms; AP::ahrs().resetHeightDatum(); update_calibration(); - BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active); - } -} - -/* - call accumulate on all drivers - */ -void AP_Baro::accumulate(void) -{ - for (uint8_t i=0; i<_num_drivers; i++) { - drivers[i]->accumulate(); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active); } +#endif } @@ -1130,7 +1070,7 @@ bool AP_Baro::arming_checks(size_t buflen, char *buffer) const 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 alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()); 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); diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 4b1055fff92213..6fdbb02880e629 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -56,12 +56,8 @@ class AP_Baro // healthy - returns true if sensor and derived altitude are good bool healthy(void) const { return healthy(_primary); } -#ifdef HAL_BUILD_AP_PERIPH - // calibration and alt check not valid for AP_Periph - bool healthy(uint8_t instance) const; -#else + bool healthy(uint8_t instance) const; -#endif // check if all baros are healthy - used for SYS_STATUS report bool all_healthy(void) const; @@ -87,10 +83,6 @@ class AP_Baro // get pressure correction in Pascal. Divide by 100 for millibars or hectopascals float get_pressure_correction(void) const { return get_pressure_correction(_primary); } float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; } - - // accumulate a reading on sensors. Some backends without their - // own thread or a timer may need this. - void accumulate(void); // calibrate the barometer. This must be called on startup if the // altitude/climb_rate/acceleration interfaces are ever used @@ -105,22 +97,53 @@ class AP_Baro float get_altitude(void) const { return get_altitude(_primary); } float get_altitude(uint8_t instance) const { return sensors[instance].altitude; } + // get altitude above mean sea level + float get_altitude_AMSL(uint8_t instance) const { return get_altitude(instance) + _field_elevation_active; } + float get_altitude_AMSL(void) const { return get_altitude_AMSL(_primary); } + // returns which i2c bus is considered "the" external bus uint8_t external_bus() const { return _ext_bus; } + // Atmospheric Model Functions + static float geometric_alt_to_geopotential(float alt); + static float geopotential_alt_to_geometric(float alt); + + float get_temperature_from_altitude(float alt) const; + float get_altitude_from_pressure(float pressure) const; + + // EAS2TAS for SITL + static float get_EAS2TAS_for_alt_amsl(float alt_amsl); + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + // lookup expected pressure for a given altitude. Used for SITL backend + static void get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K); +#endif + + // lookup expected temperature in degrees C for a given altitude. Used for SITL backend + static float get_temperatureC_for_alt_amsl(const float alt_amsl); + + // lookup expected pressure in Pa for a given altitude. Used for SITL backend + static float get_pressure_for_alt_amsl(const float alt_amsl); + + // get air density for SITL + static float get_air_density_for_alt_amsl(float alt_amsl); + // get altitude difference in meters relative given a base // 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; + float get_sealevel_pressure(float pressure, float altitude) const; - // get scale factor required to convert equivalent to true airspeed - float get_EAS2TAS(void); + // get scale factor required to convert equivalent to true + // airspeed. This should only be used to update the AHRS value + // once per loop. Please use AP::ahrs().get_EAS2TAS() + float _get_EAS2TAS(void) const; // get air density / sea level density - decreases as altitude climbs - float get_air_density_ratio(void); + // please use AP::ahrs()::get_air_density_ratio() + float _get_air_density_ratio(void); // get current climb rate in meters/s. A positive number means // going up @@ -172,9 +195,6 @@ class AP_Baro // get baro drift amount float get_baro_drift_offset(void) const { return _alt_offset_active; } - // simple atmospheric model - static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta); - // simple underwater atmospheric model static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta); @@ -244,6 +264,7 @@ class AP_Baro PROBE_BMP388=(1<<10), PROBE_SPL06 =(1<<11), PROBE_MSP =(1<<12), + PROBE_BMP581=(1<<13), }; #if HAL_BARO_WIND_COMP_ENABLED @@ -287,8 +308,6 @@ class AP_Baro 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; - float _EAS2TAS; float _external_temperature; uint32_t _last_external_temperature_ms; DerivativeFilterFloat_Size7 _climb_rate_filter; @@ -327,6 +346,14 @@ class AP_Baro void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance); void update_field_elevation(); + + // atmosphere model functions + float get_altitude_difference_extended(float base_pressure, float pressure) const; + float get_EAS2TAS_extended(float pressure) const; + static float get_temperature_by_altitude_layer(float alt, int8_t idx); + + float get_altitude_difference_simple(float base_pressure, float pressure) const; + float get_EAS2TAS_simple(float altitude, float pressure) const; }; namespace AP { diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index d2fed889da6991..17de815349b43c 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -48,7 +48,7 @@ AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr_init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_BMP280.cpp b/libraries/AP_Baro/AP_Baro_BMP280.cpp index 1c89ac0a4b9557..bf2cd51e340b99 100644 --- a/libraries/AP_Baro/AP_Baro_BMP280.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP280.cpp @@ -60,7 +60,7 @@ AP_Baro_Backend *AP_Baro_BMP280::probe(AP_Baro &baro, return nullptr; } - AP_Baro_BMP280 *sensor = new AP_Baro_BMP280(baro, std::move(dev)); + AP_Baro_BMP280 *sensor = NEW_NOTHROW AP_Baro_BMP280(baro, std::move(dev)); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_BMP388.cpp b/libraries/AP_Baro/AP_Baro_BMP388.cpp index 6b48d9e7831676..8cf39a5f36b341 100644 --- a/libraries/AP_Baro/AP_Baro_BMP388.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP388.cpp @@ -66,7 +66,7 @@ AP_Baro_Backend *AP_Baro_BMP388::probe(AP_Baro &baro, return nullptr; } - AP_Baro_BMP388 *sensor = new AP_Baro_BMP388(baro, std::move(_dev)); + AP_Baro_BMP388 *sensor = NEW_NOTHROW AP_Baro_BMP388(baro, std::move(_dev)); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_BMP581.cpp b/libraries/AP_Baro/AP_Baro_BMP581.cpp new file mode 100644 index 00000000000000..fda6e32a78ed86 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_BMP581.cpp @@ -0,0 +1,193 @@ +/* + 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_BMP581.h" + +#if AP_BARO_BMP581_ENABLED + +#include +#include + +extern const AP_HAL::HAL &hal; + +#define BMP581_ID 0x50 + +#define BMP581_REG_CHIP_ID 0x01 +#define BMP581_REG_REV_ID 0x02 +#define BMP581_REG_CHIP_STATUS 0x11 +#define BMP581_REG_DRIVE_CONFIG 0x13 +#define BMP581_REG_INT_CONFIG 0x14 +#define BMP581_REG_INT_SOURCE 0x15 +#define BMP581_REG_FIFO_CONFIG 0x16 +#define BMP581_REG_FIFO_COUNT 0x17 +#define BMP581_REG_FIFO_SEL 0x18 +#define BMP581_REG_TEMP_DATA_XLSB 0x1D +#define BMP581_REG_TEMP_DATA_LSB 0x1E +#define BMP581_REG_TEMP_DATA_MSB 0x1F +#define BMP581_REG_PRESS_DATA_XLSB 0x20 +#define BMP581_REG_PRESS_DATA_LSB 0x21 +#define BMP581_REG_PRESS_DATA_MSB 0x22 +#define BMP581_REG_INT_STATUS 0x27 +#define BMP581_REG_STATUS 0x28 +#define BMP581_REG_FIFO_DATA 0x29 +#define BMP581_REG_NVM_ADDR 0x2B +#define BMP581_REG_NVM_DATA_LSB 0x2C +#define BMP581_REG_NVM_DATA_MSB 0x2D +#define BMP581_REG_DSP_CONFIG 0x30 +#define BMP581_REG_DSP_IIR 0x31 +#define BMP581_REG_OOR_THR_P_LSB 0x32 +#define BMP581_REG_OOR_THR_P_MSB 0x33 +#define BMP581_REG_OOR_RANGE 0x34 +#define BMP581_REG_OOR_CONFIG 0x35 +#define BMP581_REG_OSR_CONFIG 0x36 +#define BMP581_REG_ODR_CONFIG 0x37 +#define BMP581_REG_OSR_EFF 0x38 +#define BMP581_REG_CMD 0x7E + +AP_Baro_BMP581::AP_Baro_BMP581(AP_Baro &baro, AP_HAL::OwnPtr dev) + : AP_Baro_Backend(baro) + , _dev(std::move(dev)) +{ +} + +AP_Baro_Backend *AP_Baro_BMP581::probe(AP_Baro &baro, + AP_HAL::OwnPtr dev) +{ + if (!dev) { + return nullptr; + } + + AP_Baro_BMP581 *sensor = NEW_NOTHROW AP_Baro_BMP581(baro, std::move(dev)); + if (!sensor || !sensor->init()) { + delete sensor; + return nullptr; + } + return sensor; +} + +bool AP_Baro_BMP581::init() +{ + if (!_dev) { + return false; + } + + WITH_SEMAPHORE(_dev->get_semaphore()); + + _dev->set_speed(AP_HAL::Device::SPEED_HIGH); + + uint8_t whoami; + + // setup to allow reads on SPI + if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) { + _dev->set_read_flag(0x80); + + if (!_dev->read_registers(BMP581_REG_CHIP_ID, &whoami, 1)) { + return false; + } + } + + if (!_dev->read_registers(BMP581_REG_CHIP_ID, &whoami, 1)) { + return false; + } + + switch (whoami) { + case BMP581_ID: + _dev->set_device_type(DEVTYPE_BARO_BMP581); + break; + default: + return false; + } + + uint8_t status; + if (!_dev->read_registers(BMP581_REG_STATUS, &status, 1)) { + return false; + } + + if ((status & 0b10) == 0 || (status & 0b100) == 1) { + return false; + } + + uint8_t int_status; + if (!_dev->read_registers(BMP581_REG_INT_STATUS, &int_status, 1)) { + return false; + } + + if ((int_status & 0x10) == 0) { + return false; + } + + _dev->setup_checked_registers(4); + + // Standby mode + _dev->write_register(BMP581_REG_ODR_CONFIG, 0, true); + + // Press EN | osr_p 64X | osr_t 4X + _dev->write_register(BMP581_REG_OSR_CONFIG, 0b01110010, true); + + // ORD 50Hz | Normal Mode + _dev->write_register(BMP581_REG_ODR_CONFIG, 0b0111101, true); + + instance = _frontend.register_sensor(); + + set_bus_id(instance, _dev->get_bus_id()); + + // request 50Hz update + _dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP581::timer, void)); + + return true; +} + +// acumulate a new sensor reading +void AP_Baro_BMP581::timer(void) +{ + uint8_t buf[6]; + + if (!_dev->read_registers(BMP581_REG_TEMP_DATA_XLSB, buf, sizeof(buf))) { + return; + } + + WITH_SEMAPHORE(_sem); + + if (buf[0] != 0x7f || buf[1] != 0x7f || buf[2] != 0x7f) { + // we have temperature data + temperature = (float)((int32_t)(((uint32_t)buf[2] << 24) | ((uint32_t)buf[1] << 16) | ((uint32_t)buf[0] << 8)) >> 8) * (1.0f / 65536.0f); + } + + if (buf[3] != 0x7f || buf[4] != 0x7f || buf[5] != 0x7f) { + // we have pressure data + pressure_sum += (float)(((uint32_t)buf[5] << 16) | ((uint32_t)buf[4] << 8) | (uint32_t)buf[3]) * (1.0f / 64.0f); + pressure_count++; + } + + _dev->check_next_register(); +} + +// transfer data to the frontend +void AP_Baro_BMP581::update(void) +{ + WITH_SEMAPHORE(_sem); + + if (pressure_count == 0) { + return; + } + + _copy_to_frontend(instance, + pressure_sum/pressure_count, + temperature); + + pressure_sum = 0; + pressure_count = 0; +} + +#endif // AP_BARO_BMP581_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP581.h b/libraries/AP_Baro/AP_Baro_BMP581.h new file mode 100644 index 00000000000000..0c50f1ab988727 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_BMP581.h @@ -0,0 +1,41 @@ +#pragma once + +#include "AP_Baro_Backend.h" + +#if AP_BARO_BMP581_ENABLED + +#include +#include +#include + +#ifndef HAL_BARO_BMP581_I2C_ADDR + #define HAL_BARO_BMP581_I2C_ADDR (0x46) +#endif +#ifndef HAL_BARO_BMP581_I2C_ADDR2 + #define HAL_BARO_BMP581_I2C_ADDR2 (0x47) +#endif + +class AP_Baro_BMP581 : public AP_Baro_Backend +{ +public: + AP_Baro_BMP581(AP_Baro &baro, AP_HAL::OwnPtr dev); + + /* AP_Baro public interface: */ + void update() override; + + static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev); + +private: + + bool init(void); + void timer(void); + + AP_HAL::OwnPtr _dev; + + uint8_t instance; + float pressure_sum; + uint32_t pressure_count; + float temperature; +}; + +#endif // AP_BARO_BMP581_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 94b155e4836bd7..6b661bb1ec6ae7 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -12,11 +12,6 @@ class AP_Baro_Backend // data to the frontend virtual void update() = 0; - // accumulate function. This is used for backends that don't use a - // timer, and need to be called regularly by the main code to - // trigger them to read the sensor - virtual void accumulate(void) {} - void backend_update(uint8_t instance); // Check that the baro valid by using a mean filter. @@ -58,6 +53,7 @@ class AP_Baro_Backend DEVTYPE_BARO_MS5837 = 0x12, DEVTYPE_BARO_MS5637 = 0x13, DEVTYPE_BARO_BMP390 = 0x14, + DEVTYPE_BARO_BMP581 = 0x15, }; protected: diff --git a/libraries/AP_Baro/AP_Baro_DPS280.cpp b/libraries/AP_Baro/AP_Baro_DPS280.cpp index fe34ca0bd048f0..82cfec5319bddd 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.cpp +++ b/libraries/AP_Baro/AP_Baro_DPS280.cpp @@ -56,7 +56,7 @@ AP_Baro_Backend *AP_Baro_DPS280::probe(AP_Baro &baro, return nullptr; } - AP_Baro_DPS280 *sensor = new AP_Baro_DPS280(baro, std::move(_dev)); + AP_Baro_DPS280 *sensor = NEW_NOTHROW AP_Baro_DPS280(baro, std::move(_dev)); if (sensor) { sensor->is_dps310 = _is_dps310; } diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index 6812480d7a0ef0..07975e10823230 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -21,18 +21,13 @@ AP_Baro_DroneCAN::AP_Baro_DroneCAN(AP_Baro &baro) : AP_Baro_Backend(baro) {} -void AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("pressure_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("temperature_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, driver_index) != nullptr) + ; } AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) @@ -42,7 +37,7 @@ AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) AP_Baro_DroneCAN* backend = nullptr; for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { - backend = new AP_Baro_DroneCAN(baro); + backend = NEW_NOTHROW AP_Baro_DroneCAN(baro); if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.h b/libraries/AP_Baro/AP_Baro_DroneCAN.h index 3040b97ab6b36b..5aa3a1fa4c4e69 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.h +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.h @@ -15,7 +15,7 @@ class AP_Baro_DroneCAN : public AP_Baro_Backend { void update() override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_Baro_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); static AP_Baro_Backend* probe(AP_Baro &baro); diff --git a/libraries/AP_Baro/AP_Baro_Dummy.h b/libraries/AP_Baro/AP_Baro_Dummy.h index 7c76ebe414147a..f862c788a8ded1 100644 --- a/libraries/AP_Baro/AP_Baro_Dummy.h +++ b/libraries/AP_Baro/AP_Baro_Dummy.h @@ -14,7 +14,7 @@ class AP_Baro_Dummy : public AP_Baro_Backend AP_Baro_Dummy(AP_Baro &baro); void update(void) override; static AP_Baro_Backend *probe(AP_Baro &baro) { - return new AP_Baro_Dummy(baro); + return NEW_NOTHROW AP_Baro_Dummy(baro); } private: diff --git a/libraries/AP_Baro/AP_Baro_FBM320.cpp b/libraries/AP_Baro/AP_Baro_FBM320.cpp index 7ad9a7b0c89ae6..738b63ee1bb307 100644 --- a/libraries/AP_Baro/AP_Baro_FBM320.cpp +++ b/libraries/AP_Baro/AP_Baro_FBM320.cpp @@ -48,7 +48,7 @@ AP_Baro_Backend *AP_Baro_FBM320::probe(AP_Baro &baro, return nullptr; } - AP_Baro_FBM320 *sensor = new AP_Baro_FBM320(baro, std::move(_dev)); + AP_Baro_FBM320 *sensor = NEW_NOTHROW AP_Baro_FBM320(baro, std::move(_dev)); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_HIL.cpp b/libraries/AP_Baro/AP_Baro_HIL.cpp index 985133e0b8a1de..1442635a0ceaac 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.cpp +++ b/libraries/AP_Baro/AP_Baro_HIL.cpp @@ -8,33 +8,6 @@ extern const AP_HAL::HAL& hal; // ========================================================================== // based on tables.cpp from http://www.pdas.com/atmosdownload.html -/* - Compute the temperature, density, and pressure in the standard atmosphere - Correct to 20 km. Only approximate thereafter. -*/ -void AP_Baro::SimpleAtmosphere( - const float alt, // geometric altitude, km. - float& sigma, // density/sea-level standard density - float& delta, // pressure/sea-level standard pressure - float& theta) // temperature/sea-level standard temperature -{ - const float REARTH = 6369.0f; // radius of the Earth (km) - const float GMR = 34.163195f; // gas constant - float h=alt*REARTH/(alt+REARTH); // geometric to geopotential altitude - - if (h < 11.0f) { - // Troposphere - theta = (SSL_AIR_TEMPERATURE - 6.5f * h) / SSL_AIR_TEMPERATURE; - delta = powf(theta, GMR / 6.5f); - } else { - // Stratosphere - theta = 216.65f / SSL_AIR_TEMPERATURE; - delta = 0.2233611f * expf(-GMR * (h - 11.0f) / 216.65f); - } - - sigma = delta/theta; -} - void AP_Baro::SimpleUnderWaterAtmosphere( float alt, // depth, km. float& rho, // density/sea-level diff --git a/libraries/AP_Baro/AP_Baro_ICM20789.cpp b/libraries/AP_Baro/AP_Baro_ICM20789.cpp index cb978356b14cf5..b0918f3f35c881 100644 --- a/libraries/AP_Baro/AP_Baro_ICM20789.cpp +++ b/libraries/AP_Baro/AP_Baro_ICM20789.cpp @@ -80,7 +80,7 @@ AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro, if (!dev || !dev_imu) { return nullptr; } - AP_Baro_ICM20789 *sensor = new AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu)); + AP_Baro_ICM20789 *sensor = NEW_NOTHROW AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu)); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_ICP101XX.cpp b/libraries/AP_Baro/AP_Baro_ICP101XX.cpp index f06df354d050a7..487214ccb30248 100644 --- a/libraries/AP_Baro/AP_Baro_ICP101XX.cpp +++ b/libraries/AP_Baro/AP_Baro_ICP101XX.cpp @@ -61,7 +61,7 @@ AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro, if (!dev) { return nullptr; } - AP_Baro_ICP101XX *sensor = new AP_Baro_ICP101XX(baro, std::move(dev)); + AP_Baro_ICP101XX *sensor = NEW_NOTHROW AP_Baro_ICP101XX(baro, std::move(dev)); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -109,7 +109,7 @@ bool AP_Baro_ICP101XX::init() dev->get_semaphore()->give(); - dev->register_periodic_callback(measure_interval/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void)); + dev->register_periodic_callback(measure_interval, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void)); return true; @@ -312,4 +312,4 @@ void AP_Baro_ICP101XX::update() } } -#endif // AP_BARO_ICP101XX_ENABLED \ No newline at end of file +#endif // AP_BARO_ICP101XX_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ICP201XX.cpp b/libraries/AP_Baro/AP_Baro_ICP201XX.cpp index 6811e8c66b33a4..45b2277090b12b 100644 --- a/libraries/AP_Baro/AP_Baro_ICP201XX.cpp +++ b/libraries/AP_Baro/AP_Baro_ICP201XX.cpp @@ -87,7 +87,7 @@ AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro, if (!dev) { return nullptr; } - AP_Baro_ICP201XX *sensor = new AP_Baro_ICP201XX(baro, std::move(dev)); + AP_Baro_ICP201XX *sensor = NEW_NOTHROW AP_Baro_ICP201XX(baro, std::move(dev)); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_KellerLD.cpp b/libraries/AP_Baro/AP_Baro_KellerLD.cpp index 3532b484d0c904..4a2fd8160bd5c6 100644 --- a/libraries/AP_Baro/AP_Baro_KellerLD.cpp +++ b/libraries/AP_Baro/AP_Baro_KellerLD.cpp @@ -55,7 +55,7 @@ AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::OwnPtr_init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp index 6db9acdc3d5447..f8294573b321cf 100644 --- a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp +++ b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp @@ -69,7 +69,7 @@ AP_Baro_Backend *AP_Baro_LPS2XH::probe(AP_Baro &baro, return nullptr; } - AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev)); + AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev)); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; @@ -86,7 +86,7 @@ AP_Baro_Backend *AP_Baro_LPS2XH::probe_InvensenseIMU(AP_Baro &baro, return nullptr; } - AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev)); + AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev)); if (sensor) { if (!sensor->_imu_i2c_init(imu_address)) { delete sensor; diff --git a/libraries/AP_Baro/AP_Baro_Logging.cpp b/libraries/AP_Baro/AP_Baro_Logging.cpp index 91c622aaa0f207..e0e38f9becf896 100644 --- a/libraries/AP_Baro/AP_Baro_Logging.cpp +++ b/libraries/AP_Baro/AP_Baro_Logging.cpp @@ -13,6 +13,7 @@ void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance) time_us : time_us, instance : baro_instance, altitude : get_altitude(baro_instance), + altitude_AMSL : get_altitude_AMSL(baro_instance), pressure : get_pressure(baro_instance), temperature : (int16_t)(get_temperature(baro_instance) * 100 + 0.5f), climbrate : get_climb_rate(), diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index 295cd2e9e4c66f..46e3d8d2c39f0d 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -71,7 +71,7 @@ AP_Baro_Backend *AP_Baro_MS56XX::probe(AP_Baro &baro, if (!dev) { return nullptr; } - AP_Baro_MS56XX *sensor = new AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type); + AP_Baro_MS56XX *sensor = NEW_NOTHROW AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Baro/AP_Baro_SITL.cpp b/libraries/AP_Baro/AP_Baro_SITL.cpp index 9b41e336459d72..cd914632a390df 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.cpp +++ b/libraries/AP_Baro/AP_Baro_SITL.cpp @@ -11,9 +11,9 @@ extern const AP_HAL::HAL& hal; constructor - registers instance at top Baro driver */ AP_Baro_SITL::AP_Baro_SITL(AP_Baro &baro) : + AP_Baro_Backend(baro), _sitl(AP::sitl()), - _has_sample(false), - AP_Baro_Backend(baro) + _has_sample(false) { if (_sitl != nullptr) { _instance = _frontend.register_sensor(); @@ -66,7 +66,11 @@ void AP_Baro_SITL::_timer() return; } - sim_alt += _sitl->baro[_instance].drift * now * 0.001f; + const auto drift_delta_t_ms = now - last_drift_delta_t_ms; + last_drift_delta_t_ms = now; + total_alt_drift += _sitl->baro[_instance].drift * drift_delta_t_ms * 0.001f; + + sim_alt += total_alt_drift; sim_alt += _sitl->baro[_instance].noise * rand_float(); // add baro glitch @@ -114,12 +118,9 @@ void AP_Baro_SITL::_timer() } #if !APM_BUILD_TYPE(APM_BUILD_ArduSub) - float sigma, delta, theta; - - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - float p = SSL_AIR_PRESSURE * delta; - float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); - + float p, T_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K); + float T = KELVIN_TO_C(T_K); temperature_adjustment(p, T); #else float rho, delta, theta; @@ -139,7 +140,7 @@ void AP_Baro_SITL::_timer() // unhealthy if baro is turned off or beyond supported instances bool AP_Baro_SITL::healthy(uint8_t instance) { - return !_sitl->baro[instance].disable; + return _last_sample_time != 0 && !_sitl->baro[instance].disable; } // Read the sensor @@ -185,7 +186,7 @@ float AP_Baro_SITL::wind_pressure_correction(uint8_t instance) error += bp.wcof_zn * sqz; } - return error * 0.5 * SSL_AIR_DENSITY * AP::baro().get_air_density_ratio(); + return error * 0.5 * SSL_AIR_DENSITY * AP::baro()._get_air_density_ratio(); } #endif // AP_SIM_BARO_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_SITL.h b/libraries/AP_Baro/AP_Baro_SITL.h index 68ba04d016ac0b..7d724aeaebfa96 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.h +++ b/libraries/AP_Baro/AP_Baro_SITL.h @@ -48,5 +48,7 @@ class AP_Baro_SITL : public AP_Baro_Backend { float _recent_press; float _last_altitude; + uint32_t last_drift_delta_t_ms; // allows for integration of drift over time + float total_alt_drift; // integrated altitude drift in metres }; #endif // AP_SIM_BARO_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_SPL06.cpp b/libraries/AP_Baro/AP_Baro_SPL06.cpp index baca15dee2d20f..6ca52a2f0286e3 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.cpp +++ b/libraries/AP_Baro/AP_Baro_SPL06.cpp @@ -17,11 +17,13 @@ #if AP_BARO_SPL06_ENABLED #include +#include #include extern const AP_HAL::HAL &hal; #define SPL06_CHIP_ID 0x10 +#define SPA06_CHIP_ID 0x11 #define SPL06_REG_PRESSURE_B2 0x00 // Pressure MSB Register #define SPL06_REG_PRESSURE_B1 0x01 // Pressure middle byte Register @@ -43,15 +45,19 @@ extern const AP_HAL::HAL &hal; #define SPL06_REG_CHIP_ID 0x0D // Chip ID Register #define SPL06_REG_CALIB_COEFFS_START 0x10 #define SPL06_REG_CALIB_COEFFS_END 0x21 +#define SPA06_REG_CALIB_COEFFS_END 0x24 -#define SPL06_CALIB_COEFFS_LEN (SPL06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1) +// PRESSURE_CFG_REG +#define SPL06_PRES_RATE_32HZ (0x05 << 4) // TEMPERATURE_CFG_REG #define SPL06_TEMP_USE_EXT_SENSOR (1<<7) +#define SPL06_TEMP_RATE_32HZ (0x05 << 4) // MODE_AND_STATUS_REG #define SPL06_MEAS_PRESSURE (1<<0) // measure pressure #define SPL06_MEAS_TEMPERATURE (1<<1) // measure temperature +#define SPL06_MEAS_CON_PRE_TEM 0x07 #define SPL06_MEAS_CFG_CONTINUOUS (1<<2) #define SPL06_MEAS_CFG_PRESSURE_RDY (1<<4) @@ -69,6 +75,13 @@ extern const AP_HAL::HAL &hal; #define SPL06_OVERSAMPLING_TO_REG_VALUE(n) (ffs(n)-1) +#define SPL06_BACKGROUND_SAMPLE_RATE 32 + +// enable Background Mode for continuous measurement +#ifndef AP_BARO_SPL06_BACKGROUND_ENABLE +#define AP_BARO_SPL06_BACKGROUND_ENABLE 0 +#endif + AP_Baro_SPL06::AP_Baro_SPL06(AP_Baro &baro, AP_HAL::OwnPtr dev) : AP_Baro_Backend(baro) , _dev(std::move(dev)) @@ -86,7 +99,7 @@ AP_Baro_Backend *AP_Baro_SPL06::probe(AP_Baro &baro, dev->set_read_flag(0x80); } - AP_Baro_SPL06 *sensor = new AP_Baro_SPL06(baro, std::move(dev)); + AP_Baro_SPL06 *sensor = NEW_NOTHROW AP_Baro_SPL06(baro, std::move(dev)); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; @@ -107,21 +120,43 @@ bool AP_Baro_SPL06::_init() // Sometimes SPL06 has init problems, that's due to failure of reading using SPI for the first time. The SPL06 is a dual // protocol sensor(I2C and SPI), sometimes it takes one SPI operation to convert it to SPI mode after it starts up. - bool is_SPL06 = false; for (uint8_t i=0; i<5; i++) { - if (_dev->read_registers(SPL06_REG_CHIP_ID, &whoami, 1) && - whoami == SPL06_CHIP_ID) { - is_SPL06=true; - break; + if (_dev->read_registers(SPL06_REG_CHIP_ID, &whoami, 1)) { + switch(whoami) { + case SPL06_CHIP_ID: + type = Type::SPL06; + break; + case SPA06_CHIP_ID: + type = Type::SPA06; + break; + default: + type = Type::UNKNOWN; + break; + } } + + if (type != Type::UNKNOWN) + break; } - if(!is_SPL06) { + if (type == Type::UNKNOWN) { return false; } // read the calibration data + uint8_t SPL06_CALIB_COEFFS_LEN = 18; + switch(type) { + case Type::SPL06: + SPL06_CALIB_COEFFS_LEN = SPL06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1; + break; + case Type::SPA06: + SPL06_CALIB_COEFFS_LEN = SPA06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1; + break; + default: + break; + } + uint8_t buf[SPL06_CALIB_COEFFS_LEN]; _dev->read_registers(SPL06_REG_CALIB_COEFFS_START, buf, sizeof(buf)); @@ -134,12 +169,25 @@ bool AP_Baro_SPL06::_init() _c20 = ((uint16_t)buf[12] << 8) | (uint16_t)buf[13]; _c21 = ((uint16_t)buf[14] << 8) | (uint16_t)buf[15]; _c30 = ((uint16_t)buf[16] << 8) | (uint16_t)buf[17]; + if(type == Type::SPA06) { + _c31 = (buf[18] & 0x80 ? 0xF000 : 0) | ((uint16_t)buf[18] << 4) | (((uint16_t)buf[19] & 0xF0) >> 4); + _c40 = ((buf[19] & 0x8 ? 0xF000 : 0) | ((uint16_t)buf[19] & 0x0F) << 8) | (uint16_t)buf[20]; + } // setup temperature and pressure measurements _dev->setup_checked_registers(3, 20); +#if AP_BARO_SPL06_BACKGROUND_ENABLE + //set rate and oversampling + _dev->write_register(SPL06_REG_TEMPERATURE_CFG, SPL06_TEMP_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true); + _dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_PRES_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true); + + //enable background mode + _dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_CON_PRE_TEM, true); +#else _dev->write_register(SPL06_REG_TEMPERATURE_CFG, SPL06_TEMP_USE_EXT_SENSOR | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true); _dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true); +#endif //AP_BARO_SPL06_BACKGROUND_ENABLE uint8_t int_and_fifo_reg_value = 0; if (SPL06_TEMPERATURE_OVERSAMPLING > 8) { @@ -157,7 +205,11 @@ bool AP_Baro_SPL06::_init() // request 50Hz update _timer_counter = -1; +#if AP_BARO_SPL06_BACKGROUND_ENABLE + _dev->register_periodic_callback(1000000/SPL06_BACKGROUND_SAMPLE_RATE, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void)); +#else _dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void)); +#endif //AP_BARO_SPL06_BACKGROUND_ENABLE return true; } @@ -184,7 +236,15 @@ void AP_Baro_SPL06::_timer(void) { uint8_t buf[3]; - if ((_timer_counter == -1) || (_timer_counter == 49)) { +#if AP_BARO_SPL06_BACKGROUND_ENABLE + _dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf)); + _update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2])); + + _dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf)); + _update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2])); +#else + //command mode + if ((_timer_counter == -1) || (_timer_counter == 49)) { // First call and every second start a temperature measurement (50Hz call) _dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_TEMPERATURE, false); _timer_counter = 0; // Next cycle we are reading the temperature @@ -201,6 +261,7 @@ void AP_Baro_SPL06::_timer(void) _dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false); _timer_counter += 1; } +#endif //AP_BARO_SPL06_BACKGROUND_ENABLE _dev->check_next_register(); } @@ -235,8 +296,21 @@ void AP_Baro_SPL06::_update_temperature(int32_t temp_raw) void AP_Baro_SPL06::_update_pressure(int32_t press_raw) { const float press_raw_sc = (float)press_raw / raw_value_scale_factor(SPL06_PRESSURE_OVERSAMPLING); - const float pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * _c30)); - const float press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * _c21)); + float pressure_cal = 0; + float press_temp_comp = 0; + + switch(type) { + case Type::SPL06: + pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * _c30)); + press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * _c21)); + break; + case Type::SPA06: + pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * ((float)_c30 + press_raw_sc * _c40))); + press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * ((float)_c21) + press_raw_sc * _c31)); + break; + default: + break; + } const float press_comp = pressure_cal + press_temp_comp; diff --git a/libraries/AP_Baro/AP_Baro_SPL06.h b/libraries/AP_Baro/AP_Baro_SPL06.h index 7dcba34ee804c4..1cdda4762fd4cf 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.h +++ b/libraries/AP_Baro/AP_Baro_SPL06.h @@ -18,6 +18,11 @@ class AP_Baro_SPL06 : public AP_Baro_Backend { public: + enum class Type { + UNKNOWN, + SPL06, + SPA06, + }; AP_Baro_SPL06(AP_Baro &baro, AP_HAL::OwnPtr dev); /* AP_Baro public interface: */ @@ -45,7 +50,9 @@ class AP_Baro_SPL06 : public AP_Baro_Backend // Internal calibration registers int32_t _c00, _c10; - int16_t _c0, _c1, _c01, _c11, _c20, _c21, _c30; + int16_t _c0, _c1, _c01, _c11, _c20, _c21, _c30, _c31, _c40; + + Type type; }; #endif // AP_BARO_SPL06_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Wind.cpp b/libraries/AP_Baro/AP_Baro_Wind.cpp index 17ad6b12dda042..67b33e6a65a5fc 100644 --- a/libraries/AP_Baro/AP_Baro_Wind.cpp +++ b/libraries/AP_Baro/AP_Baro_Wind.cpp @@ -76,15 +76,17 @@ float AP_Baro::wind_pressure_correction(uint8_t instance) return 0; } + auto &ahrs = AP::ahrs(); + // correct for static pressure position errors Vector3f airspeed_vec_bf; - if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) { + if (!ahrs.airspeed_vector_true(airspeed_vec_bf)) { return 0; } float error = 0.0; - const float kp = 0.5 * SSL_AIR_DENSITY * get_air_density_ratio(); + const float kp = 0.5 * SSL_AIR_DENSITY * ahrs.get_air_density_ratio(); const float sqxp = sq(airspeed_vec_bf.x) * kp; const float sqyp = sq(airspeed_vec_bf.y) * kp; const float sqzp = sq(airspeed_vec_bf.z) * kp; diff --git a/libraries/AP_Baro/AP_Baro_atmosphere.cpp b/libraries/AP_Baro/AP_Baro_atmosphere.cpp new file mode 100644 index 00000000000000..ed26927cb9f890 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_atmosphere.cpp @@ -0,0 +1,358 @@ +#include "AP_Baro.h" +#include + +/* + 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 . + */ + +/* 1976 U.S. Standard Atmosphere: https://ntrs.nasa.gov/api/citations/19770009539/downloads/19770009539.pdf?attachment=true + +The US Standard Atmosphere defines the atmopshere in terms of whether the temperature is an iso-thermal or gradient layer. +Ideal gas laws apply thus P = rho * R_specific * T : P = pressure, rho = density, R_specific = air gas constant, T = temperature + +Note: the 1976 model is the same as the 1962 US Standard Atomsphere up to 51km. +R_universal: the universal gas constant is slightly off in the 1976 model and thus R_specific is different than today's value + +*/ + +/* Model Constants +R_universal = 8.31432e-3; // Universal gas constant (J/(kmol-K)) incorrect to the redefined 2019 value of 8.31446261815324 Jâ‹…K−1â‹…mol−1 +M_air = (0.78084 * 28.0134 + 0.209476 * 31.9988 + 9.34e-3 * 39.948 + 3.14e-4 * 44.00995 + 1.818e-5 * 20.183 + 5.24E-6 * 4.0026 + 1.14E-6 * 83.8 + 8.7E-7 * 131.30 + 2E-6 * 16.04303 + 5E-7 * 2.01594) * 1E-3; (kg/mol) +M_air = 28.9644 // Molecular weight of air (kg/kmol) see page 3 +R_specific = 287.053072 // air specifc gas constant (Jâ‹…kg−1â‹…K−1), R_universal / M_air; +gama = 1.4; // specific heat ratio of air used to determine the speed of sound + +R0 = 6356.766E3; // Earth's radius (in m) +g0 = 9.80665; // gravity (m/s^2) + +Sea-Level Constants +H_asml = 0 meters +T0 = 288.150 K +P0 = 101325 Pa +rho0 = 1.2250 kg/m^3 +T0_slope = -6.5E-3 (K/m') + +The tables list altitudes -5 km to 0 km using the same equations as 0 km to 11 km. +*/ + +/* + return altitude difference in meters between current pressure and a + given base_pressure in Pascal. This is a simple atmospheric model + good to about 11km AMSL. +*/ +float AP_Baro::get_altitude_difference_simple(float base_pressure, float pressure) const +{ + float ret; + float temp_K = C_TO_KELVIN(get_ground_temperature()); + float scaling = pressure / base_pressure; + + // 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_K * (1.0f - expf(0.190259f * logf(scaling))); + + return ret; +} + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED + +/* + Note parameters are as defined in the 1976 model. + These are slightly different from the ones in definitions.h +*/ +static const float radius_earth = 6356.766E3; // Earth's radius (in m) +static const float R_specific = 287.053072; // air specifc gas constant (Jâ‹…kg−1â‹…K−1) in 1976 model, R_universal / M_air; + +static const struct { + float amsl_m; // geopotential height above mean sea-level (km') + float temp_K; // Temperature (K) + float pressure_Pa; // Pressure (Pa) + float density; // Density (Pa/kg) + float temp_lapse; // Temperature gradients rates (K/m'), see page 3 +} atmospheric_1976_consts[] = { + { -5000, 320.650, 177687, 1.930467, -6.5E-3 }, + { 11000, 216.650, 22632.1, 0.363918, 0 }, + { 20000, 216.650, 5474.89, 8.80349E-2, 1E-3 }, + { 32000, 228.650, 868.019, 1.32250E-2, 2.8E-3 }, + { 47000, 270.650, 110.906, 1.42753E-3, 0 }, + { 51000, 270.650, 66.9389, 8.61606E-4, -2.8E-3 }, + { 71000, 214.650, 3.95642, 6.42110E-5, -2.0E-3 }, + { 84852, 186.946, 0.37338, 6.95788E-6, 0 }, +}; + +/* + find table entry given geopotential altitude in meters. This returns at least 1 + */ +static uint8_t find_atmosphere_layer_by_altitude(float alt_m) +{ + for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) { + if(alt_m < atmospheric_1976_consts[idx].amsl_m) { + return idx - 1; + } + } + + // Over the largest altitude return the last index + return ARRAY_SIZE(atmospheric_1976_consts) - 1; +} + +/* + find table entry given pressure (Pa). This returns at least 1 + */ +static uint8_t find_atmosphere_layer_by_pressure(float pressure) +{ + for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) { + if (atmospheric_1976_consts[idx].pressure_Pa < pressure) { + return idx - 1; + } + } + + // pressure is less than the smallest pressure return the last index + return ARRAY_SIZE(atmospheric_1976_consts) - 1; + +} + +// Convert geopotential altitude to geometric altitude +// +float AP_Baro::geopotential_alt_to_geometric(float alt) +{ + return (radius_earth * alt) / (radius_earth - alt); +} + +float AP_Baro::geometric_alt_to_geopotential(float alt) +{ + return (radius_earth * alt) / (radius_earth + alt); +} + +/* + Compute expected temperature for a given geometric altitude and altitude layer. +*/ +float AP_Baro::get_temperature_from_altitude(float alt) const +{ + alt = geometric_alt_to_geopotential(alt); + const uint8_t idx = find_atmosphere_layer_by_altitude(alt); + return get_temperature_by_altitude_layer(alt, idx); +} + +/* + Compute expected temperature for a given geopotential altitude and altitude layer. +*/ +float AP_Baro::get_temperature_by_altitude_layer(float alt, int8_t idx) +{ + if (is_zero(atmospheric_1976_consts[idx].temp_lapse)) { + return atmospheric_1976_consts[idx].temp_K; + } + return atmospheric_1976_consts[idx].temp_K + atmospheric_1976_consts[idx].temp_lapse * (alt - atmospheric_1976_consts[idx].amsl_m); +} + +/* + return geometric altitude (m) given a pressure (Pa) +*/ +float AP_Baro::get_altitude_from_pressure(float pressure) const +{ + const uint8_t idx = find_atmosphere_layer_by_pressure(pressure); + const float pressure_ratio = pressure / atmospheric_1976_consts[idx].pressure_Pa; + + // Pressure ratio is nonsensical return an error?? + if (!is_positive(pressure_ratio)) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return get_altitude_AMSL(); + } + + float alt; + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = -(atmospheric_1976_consts[idx].temp_K * R_specific) / GRAVITY_MSS; + alt = atmospheric_1976_consts[idx].amsl_m + fac * logf(pressure_ratio); + } else { // Gradient temperature layer + const float fac = -(temp_slope * R_specific) / GRAVITY_MSS; + alt = atmospheric_1976_consts[idx].amsl_m + (atmospheric_1976_consts[idx].temp_K / atmospheric_1976_consts[idx].temp_lapse) * (powf(pressure_ratio, fac) - 1); + } + + return geopotential_alt_to_geometric(alt); +} + +/* + Compute expected pressure and temperature for a given geometric altitude. Used for SITL +*/ +void AP_Baro::get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K) +{ + alt_amsl = geometric_alt_to_geopotential(alt_amsl); + + const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl); + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + temperature_K = get_temperature_by_altitude_layer(alt_amsl, idx); + + // Previous versions used the current baro temperature instead of an estimate we could try to incorporate this??? non-standard atmosphere + // const float temp = get_temperature(); + + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = expf(-GRAVITY_MSS / (temperature_K * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m)); + pressure = atmospheric_1976_consts[idx].pressure_Pa * fac; + } else { // Gradient temperature layer + const float fac = GRAVITY_MSS / (temp_slope * R_specific); + const float temp_ratio = temperature_K / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless] + pressure = atmospheric_1976_consts[idx].pressure_Pa * powf(temp_ratio, -fac); + } +} + +/* + return air density (kg/m^3), given geometric altitude (m) +*/ +float AP_Baro::get_air_density_for_alt_amsl(float alt_amsl) +{ + alt_amsl = geometric_alt_to_geopotential(alt_amsl); + + const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl); + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + const float temp = get_temperature_by_altitude_layer(alt_amsl, idx); + // const float temp = get_temperature(); + + float rho; + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = expf(-GRAVITY_MSS / (temp * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m)); + rho = atmospheric_1976_consts[idx].density * fac; + } else { // Gradient temperature layer + const float fac = GRAVITY_MSS / (temp_slope * R_specific); + const float temp_ratio = temp / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless] + rho = atmospheric_1976_consts[idx].density * powf(temp_ratio, -(fac + 1)); + } + return rho; +} + +/* + return current scale factor that converts from equivalent to true airspeed +*/ +float AP_Baro::get_EAS2TAS_extended(float altitude) const +{ + float density = get_air_density_for_alt_amsl(altitude); + if (!is_positive(density)) { + // above this height we are getting closer to spacecraft territory... + const uint8_t table_size = ARRAY_SIZE(atmospheric_1976_consts); + density = atmospheric_1976_consts[table_size-1].density; + } + return sqrtf(SSL_AIR_DENSITY / density); +} + +/* + Given the geometric altitude (m) + return scale factor that converts from equivalent to true airspeed + used by SITL only +*/ +float AP_Baro::get_EAS2TAS_for_alt_amsl(float alt_amsl) +{ + const float density = get_air_density_for_alt_amsl(alt_amsl); + return sqrtf(SSL_AIR_DENSITY / MAX(0.00001,density)); +} + +#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED + +/* + return geometric altitude difference in meters between current pressure and a + given base_pressure in Pascal. +*/ +float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const +{ +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + const float alt1 = get_altitude_from_pressure(base_pressure); + const float alt2 = get_altitude_from_pressure(pressure); + return alt2 - alt1; +#else + return get_altitude_difference_simple(base_pressure, pressure); +#endif +} + +/* + return current scale factor that converts from equivalent to true airspeed + valid for altitudes up to 11km AMSL + assumes USA 1976 standard atmosphere lapse rate +*/ +float AP_Baro::get_EAS2TAS_simple(float altitude, float pressure) const +{ + if (is_zero(pressure)) { + return 1.0f; + } + + // only estimate lapse rate for the difference from the ground location + // provides a more consistent reading then trying to estimate a complete + // ISA model atmosphere + float tempK = C_TO_KELVIN(get_ground_temperature()) - ISA_LAPSE_RATE * altitude; + const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); + if (!is_positive(eas2tas_squared)) { + return 1.0f; + } + return sqrtf(eas2tas_squared); +} + +/* + return current scale factor that converts from equivalent to true airspeed +*/ +float AP_Baro::_get_EAS2TAS(void) const +{ + const float altitude = get_altitude_AMSL(); + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + return get_EAS2TAS_extended(altitude); +#else + // otherwise use function + return get_EAS2TAS_simple(altitude, get_pressure()); +#endif +} + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED +// lookup expected temperature in degrees C for a given altitude. Used for SITL backend +float AP_Baro::get_temperatureC_for_alt_amsl(const float alt_amsl) +{ + float pressure, temp_K; + get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K); + return KELVIN_TO_C(temp_K); +} + +// lookup expected pressure in Pa for a given altitude. Used for SITL backend +float AP_Baro::get_pressure_for_alt_amsl(const float alt_amsl) +{ + float pressure, temp_K; + get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K); + return pressure; +} +#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + +/* + return sea level pressure given a current altitude and pressure reading + this is the pressure p0 such that + get_altitude_difference(p0, pressure) == altitude + this function is used during calibration +*/ +float AP_Baro::get_sealevel_pressure(float pressure, float altitude) const +{ + const float min_pressure = 0.01; + const float max_pressure = 1e6; + float p0 = pressure; + /* + use a simple numerical gradient descent method so we don't need + the inverse function. This typically converges in about 5 steps, + we limit it to 20 steps to prevent possible high CPU usage + */ + uint16_t count = 20; + while (count--) { + const float delta = 0.1; + const float err1 = get_altitude_difference(p0, pressure) - altitude; + const float err2 = get_altitude_difference(p0+delta, pressure) - altitude; + const float dalt = err2 - err1; + if (fabsf(err1) < 0.01) { + break; + } + p0 -= err1 * delta / dalt; + p0 = constrain_float(p0, min_pressure, max_pressure); + } + return p0; +} diff --git a/libraries/AP_Baro/AP_Baro_config.h b/libraries/AP_Baro/AP_Baro_config.h index 0da6757a733846..643ec9202385be 100644 --- a/libraries/AP_Baro/AP_Baro_config.h +++ b/libraries/AP_Baro/AP_Baro_config.h @@ -29,6 +29,10 @@ #define AP_BARO_BMP388_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_BARO_BMP581_ENABLED +#define AP_BARO_BMP581_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_BARO_DPS280_ENABLED #define AP_BARO_DPS280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED #endif @@ -89,3 +93,13 @@ #ifndef AP_BARO_PROBE_EXTERNAL_I2C_BUSES #define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 1 #endif + +#ifndef AP_BARO_PROBE_EXT_PARAMETER_ENABLED +#define AP_BARO_PROBE_EXT_PARAMETER_ENABLED AP_BARO_PROBE_EXTERNAL_I2C_BUSES || AP_BARO_MSP_ENABLED +#endif + +#ifndef AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED +// default to using the extended functions when doing double precision EKF (which implies more flash space and faster MCU) +// this allows for using the simple model with the --ekf-single configure option +#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE || AP_SIM_ENABLED +#endif diff --git a/libraries/AP_Baro/LogStructure.h b/libraries/AP_Baro/LogStructure.h index 791cf33a55a503..d67b6be3c4b78f 100644 --- a/libraries/AP_Baro/LogStructure.h +++ b/libraries/AP_Baro/LogStructure.h @@ -11,6 +11,7 @@ // @Field: TimeUS: Time since system startup // @Field: I: barometer sensor instance number // @Field: Alt: calculated altitude +// @Field: AltAMSL: altitude AMSL // @Field: Press: measured atmospheric pressure // @Field: Temp: measured atmospheric temperature // @Field: CRt: derived climb rate from primary barometer @@ -23,6 +24,7 @@ struct PACKED log_BARO { uint64_t time_us; uint8_t instance; float altitude; + float altitude_AMSL; float pressure; int16_t temperature; float climbrate; @@ -51,10 +53,10 @@ struct PACKED log_BARD { #define LOG_STRUCTURE_FROM_BARO \ { LOG_BARO_MSG, sizeof(log_BARO), \ "BARO", \ - "Q" "B" "f" "f" "c" "f" "I" "f" "f" "B", \ - "TimeUS," "I," "Alt," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \ - "s" "#" "m" "P" "O" "n" "s" "m" "O" "-", \ - "F" "-" "0" "0" "B" "0" "C" "?" "0" "-", \ + "Q" "B" "f" "f" "f" "c" "f" "I" "f" "f" "B", \ + "TimeUS," "I," "Alt," "AltAMSL," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \ + "s" "#" "m" "m" "P" "O" "n" "s" "m" "O" "-", \ + "F" "-" "0" "0" "0" "B" "0" "C" "?" "0" "-", \ true \ }, \ { LOG_BARD_MSG, sizeof(log_BARD), \ diff --git a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp index f25875ad62a116..ebcee731afccd1 100644 --- a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp +++ b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp @@ -22,18 +22,24 @@ #include #include #include - +#include +#include const AP_HAL::HAL &hal = AP_HAL::get_HAL(); // create barometer object static AP_Baro barometer; + +// creating other objects +static AP_Int32 log_bitmask; +static AP_Logger logger; +static AP_AHRS ahrs; + #if HAL_EXTERNAL_AHRS_ENABLED static AP_ExternalAHRS eAHRS; #endif // HAL_EXTERNAL_AHRS_ENABLED static uint32_t timer; -static uint8_t counter; static AP_BoardConfig board_config; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -69,14 +75,9 @@ void loop() return; } - // run accumulate() at 50Hz and update() at 10Hz - if ((AP_HAL::micros() - timer) > 20 * 1000UL) { + // run update() at 10Hz + if ((AP_HAL::micros() - timer) > 100 * 1000UL) { timer = AP_HAL::micros(); - barometer.accumulate(); - if (counter++ < 5) { - return; - } - counter = 0; barometer.update(); //calculate time taken for barometer readings to update diff --git a/libraries/AP_Baro/tests/test_baro_atmosphere.cpp b/libraries/AP_Baro/tests/test_baro_atmosphere.cpp new file mode 100644 index 00000000000000..132d27372e0e5a --- /dev/null +++ b/libraries/AP_Baro/tests/test_baro_atmosphere.cpp @@ -0,0 +1,130 @@ +/* + test atmospheric model + to build, use: + ./waf configure --board sitl --debug + ./waf --target tests/test_baro_atmosphere + */ +#include + +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +TEST(AP_Baro, get_air_density_for_alt_amsl) +{ + float accuracy = 1E-6; + + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(-4000), 1.7697266, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(6000), 0.66011156, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(17500), 131.5688E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(25000), 40.08393E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(40000), 3.99567824728293E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(49000), 1.16276961471707E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(65000), 163.210100967015E-6, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(78000), 25.2385188936996E-6, accuracy); +} + +TEST(AP_Baro, get_altitude_from_pressure) +{ + AP_Baro baro; + float accuracy = 1.5E-1; + + EXPECT_NEAR(baro.get_altitude_from_pressure(159598.2), -4000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(47217.6), 6000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(8182.3), 17500, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(2549.2), 25000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(287.1441), 40000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(90.3365), 49000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(10.9297), 65000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(1.4674), 78000, accuracy); +} + +TEST(AP_Baro, get_temperature_from_altitude) +{ + AP_Baro baro; + + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(-4000), 314.166370821781); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(6000), 249.186776458540); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(17500), 216.650000000000); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(25000), 221.552064726284); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(40000), 250.349646102421); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(49000), 270.650000000000); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(65000), 233.292172386848); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(78000), 202.540977853740); +} + +TEST(AP_Baro, geopotential_alt_to_geometric) +{ + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(-4002.51858796625), -4000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(5994.34208330151), 6000.0); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(17451.9552525734), 17500); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(24902.0647262842), 25000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(39749.8736080075), 40000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(48625.1814380981), 49000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(64342.0812904114), 65000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(77054.5110731299), 78000); +} + +TEST(AP_Baro, geometric_alt_to_geopotential) +{ + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(-4000), -4002.51858796625); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(6000), 5994.34208330151); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(17500), 17451.9552525734); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(25000), 24902.0647262842); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(40000), 39749.8736080075); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(49000), 48625.1814380981); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(65000), 64342.0812904114); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(78000), 77054.5110731299); +} + +TEST(AP_Baro, get_pressure_temperature_for_alt_amsl) +{ + float accuracy = 1E-6; + + // layer 0 -4000 m + float pressure, temperature_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(-4000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 159598.164433755); // Matlab + EXPECT_FLOAT_EQ(pressure, 159598.09375); + EXPECT_FLOAT_EQ(temperature_K, 314.166370821781); + + // layer 0: 6000 m + AP_Baro::get_pressure_temperature_for_alt_amsl(6000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 47217.6489854302); + EXPECT_FLOAT_EQ(temperature_K, 249.186776458540); + + // layer 1: 17500 m + AP_Baro::get_pressure_temperature_for_alt_amsl(17500, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 8182.27857345022); + EXPECT_FLOAT_EQ(temperature_K, 216.650000000000); + + // layer 2: 25000m + AP_Baro::get_pressure_temperature_for_alt_amsl(25000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 2549.22361148236); // Matlab + EXPECT_FLOAT_EQ(pressure, 2549.2251); + EXPECT_FLOAT_EQ(temperature_K, 221.552064726284); + + // layer 3: 40000m + AP_Baro::get_pressure_temperature_for_alt_amsl(40000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 287.144059695555); + EXPECT_FLOAT_EQ(temperature_K, 250.349646102421); + + // layer 4: 49000m + AP_Baro::get_pressure_temperature_for_alt_amsl(49000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 90.3365441635632); + EXPECT_FLOAT_EQ(temperature_K, 270.650000000000); + + // layer 5: 65000m + AP_Baro::get_pressure_temperature_for_alt_amsl(65000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 10.9297197424037); // Matlab + EXPECT_FLOAT_EQ(pressure, 10.929715); + EXPECT_FLOAT_EQ(temperature_K, 233.292172386848); + + // layer 6: 78000m + AP_Baro::get_pressure_temperature_for_alt_amsl(78000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 1.46736727632119); // matlab + EXPECT_NEAR(pressure, 1.4673687, accuracy); + EXPECT_FLOAT_EQ(temperature_K, 202.540977853740); +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_Baro/tests/wscript b/libraries/AP_Baro/tests/wscript new file mode 100644 index 00000000000000..cd3e5e3ce7c9d9 --- /dev/null +++ b/libraries/AP_Baro/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_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index d929b8182a06df..10a14fd1f39de0 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -66,6 +66,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: _ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: _ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[0], "_", 41, AP_BattMonitor, backend_var_info[0]), #if AP_BATT_MONITOR_MAX_INSTANCES > 1 @@ -87,6 +89,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 2_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 2_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[1], "2_", 42, AP_BattMonitor, backend_var_info[1]), #endif @@ -109,6 +113,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 3_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 3_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[2], "3_", 43, AP_BattMonitor, backend_var_info[2]), #endif @@ -131,6 +137,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 4_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 4_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[3], "4_", 44, AP_BattMonitor, backend_var_info[3]), #endif @@ -153,6 +161,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 5_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 5_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[4], "5_", 45, AP_BattMonitor, backend_var_info[4]), #endif @@ -175,6 +185,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 6_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 6_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[5], "6_", 46, AP_BattMonitor, backend_var_info[5]), #endif @@ -197,6 +209,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 7_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 7_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[6], "7_", 47, AP_BattMonitor, backend_var_info[6]), #endif @@ -219,6 +233,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 8_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 8_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[7], "8_", 48, AP_BattMonitor, backend_var_info[7]), #endif @@ -241,6 +257,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 9_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 9_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_var_info[8]), #endif @@ -263,6 +281,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: A_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: A_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[9], "A_", 50, AP_BattMonitor, backend_var_info[9]), #endif @@ -285,6 +305,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: B_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: B_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[10], "B_", 51, AP_BattMonitor, backend_var_info[10]), #endif @@ -307,6 +329,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: C_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: C_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[11], "C_", 52, AP_BattMonitor, backend_var_info[11]), #endif @@ -329,6 +353,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: D_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: D_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[12], "D_", 53, AP_BattMonitor, backend_var_info[12]), #endif @@ -351,6 +377,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: E_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: E_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[13], "E_", 54, AP_BattMonitor, backend_var_info[13]), #endif @@ -373,6 +401,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: F_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: F_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[14], "F_", 55, AP_BattMonitor, backend_var_info[14]), #endif @@ -395,6 +425,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: G_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: G_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[15], "G_", 56, AP_BattMonitor, backend_var_info[15]), #endif @@ -448,134 +480,137 @@ AP_BattMonitor::init() memset(&state[instance].cell_voltages, 0xFF, sizeof(cells)); state[instance].instance = instance; - switch (get_type(instance)) { + const auto allocation_type = configured_type(instance); + switch (allocation_type) { #if AP_BATTERY_ANALOG_ENABLED case Type::ANALOG_VOLTAGE_ONLY: case Type::ANALOG_VOLTAGE_AND_CURRENT: - drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Analog(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SMBUS_SOLO_ENABLED case Type::SOLO: - drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SMBUS_GENERIC_ENABLED case Type::SMBus_Generic: - drivers[instance] = new AP_BattMonitor_SMBus_Generic(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_Generic(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SMBUS_SUI_ENABLED case Type::SUI3: - drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 3); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 3); break; case Type::SUI6: - drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 6); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 6); break; #endif #if AP_BATTERY_SMBUS_MAXELL_ENABLED case Type::MAXELL: - drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SMBUS_ROTOYE_ENABLED case Type::Rotoye: - drivers[instance] = new AP_BattMonitor_SMBus_Rotoye(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_Rotoye(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SMBUS_NEODESIGN_ENABLED case Type::NeoDesign: - drivers[instance] = new AP_BattMonitor_SMBus_NeoDesign(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_SMBus_NeoDesign(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_BEBOP_ENABLED case Type::BEBOP: - drivers[instance] = new AP_BattMonitor_Bebop(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Bebop(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED case Type::UAVCAN_BatteryInfo: - drivers[instance] = new AP_BattMonitor_DroneCAN(*this, state[instance], AP_BattMonitor_DroneCAN::UAVCAN_BATTERY_INFO, _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_DroneCAN(*this, state[instance], AP_BattMonitor_DroneCAN::UAVCAN_BATTERY_INFO, _params[instance]); break; #endif #if AP_BATTERY_ESC_ENABLED case Type::BLHeliESC: - drivers[instance] = new AP_BattMonitor_ESC(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_ESC(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SUM_ENABLED case Type::Sum: - drivers[instance] = new AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance); break; #endif #if AP_BATTERY_FUELFLOW_ENABLED case Type::FuelFlow: - drivers[instance] = new AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_FUELFLOW_ENABLED #if AP_BATTERY_FUELLEVEL_PWM_ENABLED case Type::FuelLevel_PWM: - drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_FUELLEVEL_PWM_ENABLED #if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED case Type::FuelLevel_Analog: - drivers[instance] = new AP_BattMonitor_FuelLevel_Analog(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_FuelLevel_Analog(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED #if HAL_GENERATOR_ENABLED case Type::GENERATOR_ELEC: - drivers[instance] = new AP_BattMonitor_Generator_Elec(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Generator_Elec(*this, state[instance], _params[instance]); break; case Type::GENERATOR_FUEL: - drivers[instance] = new AP_BattMonitor_Generator_FuelLevel(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Generator_FuelLevel(*this, state[instance], _params[instance]); break; #endif // HAL_GENERATOR_ENABLED #if AP_BATTERY_INA2XX_ENABLED case Type::INA2XX: - drivers[instance] = new AP_BattMonitor_INA2XX(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_INA2XX(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_LTC2946_ENABLED case Type::LTC2946: - drivers[instance] = new AP_BattMonitor_LTC2946(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_LTC2946(*this, state[instance], _params[instance]); break; #endif #if HAL_TORQEEDO_ENABLED case Type::Torqeedo: - drivers[instance] = new AP_BattMonitor_Torqeedo(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Torqeedo(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_SYNTHETIC_CURRENT_ENABLED case Type::Analog_Volt_Synthetic_Current: - drivers[instance] = new AP_BattMonitor_Synthetic_Current(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Synthetic_Current(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_INA239_ENABLED case Type::INA239_SPI: - drivers[instance] = new AP_BattMonitor_INA239(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_INA239(*this, state[instance], _params[instance]); break; #endif #if AP_BATTERY_EFI_ENABLED case Type::EFI: - drivers[instance] = new AP_BattMonitor_EFI(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_EFI(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_EFI_ENABLED #if AP_BATTERY_AD7091R5_ENABLED case Type::AD7091R5: - drivers[instance] = new AP_BattMonitor_AD7091R5(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_AD7091R5(*this, state[instance], _params[instance]); break; #endif// AP_BATTERY_AD7091R5_ENABLED #if AP_BATTERY_SCRIPTING_ENABLED case Type::Scripting: - drivers[instance] = new AP_BattMonitor_Scripting(*this, state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_BattMonitor_Scripting(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_SCRIPTING_ENABLED case Type::NONE: default: break; } - + if (drivers[instance] != nullptr) { + state[instance].type = allocation_type; + } // 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; @@ -666,8 +701,18 @@ void AP_BattMonitor::read() } #endif + const uint32_t now_ms = AP_HAL::millis(); for (uint8_t i=0; i<_num_instances; i++) { - if (drivers[i] != nullptr && get_type(i) != Type::NONE) { + if (drivers[i] == nullptr) { + continue; + } + if (allocated_type(i) != configured_type(i)) { + continue; + } + // allow run-time disabling; this is technically redundant + if (configured_type(i) == Type::NONE) { + continue; + } drivers[i]->read(); drivers[i]->update_resistance_estimate(); @@ -675,6 +720,11 @@ void AP_BattMonitor::read() drivers[i]->update_esc_telem_outbound(); #endif + // Update last heathy timestamp + if (state[i].healthy) { + state[i].last_healthy_ms = now_ms; + } + #if HAL_LOGGING_ENABLED if (logger != nullptr && logger->should_log(_log_battery_bit)) { const uint64_t time_us = AP_HAL::micros64(); @@ -682,7 +732,6 @@ void AP_BattMonitor::read() drivers[i]->Log_Write_BCL(i, time_us); } #endif - } } check_failsafes(); @@ -728,6 +777,14 @@ float AP_BattMonitor::gcs_voltage(uint8_t instance) const return state[instance].voltage; } +bool AP_BattMonitor::option_is_set(uint8_t instance, AP_BattMonitor_Params::Options option) const +{ + if (instance >= _num_instances || drivers[instance] == nullptr) { + return false; + } + return drivers[instance]->option_is_set(option); +} + /// 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()) { @@ -809,6 +866,11 @@ void AP_BattMonitor::check_failsafes(void) switch (type) { case Failsafe::None: continue; // should not have been called in this case + case Failsafe::Unhealthy: + // Report only for unhealthy, could add action param in the future + action = 0; + type_str = "missing, last:"; + break; case Failsafe::Low: action = _params[i]._failsafe_low_action; type_str = "low"; @@ -957,8 +1019,29 @@ bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const { char temp_buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; - for (uint8_t i = 0; i < _num_instances; i++) { - if (drivers[i] != nullptr && !(drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer)))) { + for (uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) { + const auto expected_type = configured_type(i); + + if (drivers[i] == nullptr && expected_type == Type::NONE) { + continue; + } + +#if !AP_BATTERY_SUM_ENABLED + // CONVERSION - Added Sep 2024 for ArduPilot 4.6 as we are + // removing the SUM backend on 1MB boards. Give a + // more-specific error for the sum backend: + if (expected_type == Type::Sum) { + hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, "feature BATTERY_SUM not available"); + return false; + } +#endif + + if (drivers[i] == nullptr || allocated_type(i) != expected_type) { + hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, "unhealthy"); + return false; + } + + if (!drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer))) { hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, temp_buffer); return false; } @@ -983,7 +1066,7 @@ void AP_BattMonitor::checkPoweringOff(void) cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED; cmd_msg.param1 = i+1; GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg)); - gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1); #endif // only send this once @@ -1036,6 +1119,7 @@ MAV_BATTERY_CHARGE_STATE AP_BattMonitor::get_mavlink_charge_state(const uint8_t switch (state[instance].failsafe) { case Failsafe::None: + case Failsafe::Unhealthy: if (get_mavlink_fault_bitmask(instance) != 0 || !healthy()) { return MAV_BATTERY_CHARGE_STATE_UNHEALTHY; } @@ -1094,7 +1178,14 @@ void AP_BattMonitor::MPPT_set_powered_state(const uint8_t instance, const bool p bool AP_BattMonitor::healthy() const { for (uint8_t i=0; i< _num_instances; i++) { - if (get_type(i) != Type::NONE && !healthy(i)) { + if (allocated_type(i) != configured_type(i)) { + return false; + } + // allow run-time disabling; this is technically redundant + if (configured_type(i) == Type::NONE) { + continue; + } + if (!healthy(i)) { return false; } } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 67c138e5f779fa..0b55e2846dd917 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -81,6 +81,7 @@ class AP_BattMonitor // battery failsafes must be defined in levels of severity so that vehicles wont fall backwards enum class Failsafe : uint8_t { None = 0, + Unhealthy, Low, Critical }; @@ -153,6 +154,7 @@ class AP_BattMonitor float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage Failsafe failsafe; // stage failsafe the battery is in bool healthy; // battery monitor is communicating correctly + uint32_t last_healthy_ms; // Time when monitor was last healthy bool is_powering_off; // true when power button commands power off bool powerOffNotified; // only send powering off notification once uint32_t time_remaining; // remaining battery time @@ -160,6 +162,7 @@ class AP_BattMonitor uint8_t state_of_health_pct; // state of health (SOH) in percent bool has_state_of_health_pct; // state_of_health_pct is only valid if this is true uint8_t instance; // instance number of this backend + Type type; // allocated instance type const struct AP_Param::GroupInfo *var_info; }; @@ -219,11 +222,14 @@ class AP_BattMonitor /// returns the highest failsafe action that has been triggered int8_t get_highest_failsafe_priority(void) const { return _highest_failsafe_priority; }; - /// get_type - returns battery monitor type - enum Type get_type() const { return get_type(AP_BATT_PRIMARY_INSTANCE); } - enum Type get_type(uint8_t instance) const { + /// configured_type - returns battery monitor type as configured in parameters + enum Type configured_type(uint8_t instance) const { return (Type)_params[instance]._type.get(); } + /// allocated_type - returns battery monitor type as allocated + enum Type allocated_type(uint8_t instance) const { + return state[instance].type; + } /// get_serial_number - returns battery serial number int32_t get_serial_number() const { return get_serial_number(AP_BATT_PRIMARY_INSTANCE); } @@ -256,6 +262,8 @@ class AP_BattMonitor void MPPT_set_powered_state_to_all(const bool power_on); void MPPT_set_powered_state(const uint8_t instance, const bool power_on); + bool option_is_set(uint8_t instance, AP_BattMonitor_Params::Options option) const; + // cycle count bool get_cycle_count(uint8_t instance, uint16_t &cycles) const; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 195dbded04047e..728e3b918adca3 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -168,6 +168,11 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Backend::update_failsafes(void) return AP_BattMonitor::Failsafe::Low; } + // 5 second health timeout + if ((now - _state.last_healthy_ms) > 5000) { + return AP_BattMonitor::Failsafe::Unhealthy; + } + // if we've gotten this far then battery is ok return AP_BattMonitor::Failsafe::None; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 3c7d35fd9e5b9a..d505dcc20d93ac 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = { // @User: Advanced AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0), - // Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + // Param indexes must be between 30 and 35 to avoid conflict with other battery monitor param tables loaded by pointer AP_GROUPEND }; @@ -42,23 +42,14 @@ AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMon _state.healthy = false; } -void AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("battinfo_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("battinfo_aux_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mppt_stream_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, driver_index) != nullptr) + ; } /* @@ -79,7 +70,7 @@ AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneC const auto &batt = AP::battery(); for (uint8_t i = 0; i < batt._num_instances; i++) { if (batt.drivers[i] == nullptr || - batt.get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { + batt.allocated_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { continue; } AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)batt.drivers[i]; @@ -90,7 +81,7 @@ AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneC // find empty uavcan driver for (uint8_t i = 0; i < batt._num_instances; i++) { if (batt.drivers[i] != nullptr && - batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && + batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && match_battery_id(i, battery_id)) { AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i]; @@ -241,7 +232,7 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap for (uint8_t i = 0; i < batt._num_instances; i++) { const auto *drv = batt.drivers[i]; if (drv != nullptr && - batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && + batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) && batt.get_serial_number(i) == int32_t(msg.battery_id)) { driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i]; @@ -405,7 +396,7 @@ void AP_BattMonitor_DroneCAN::mppt_set_powered_state(bool power_on) request.disable = !request.enable; if (mppt_outputenable_client == nullptr) { - mppt_outputenable_client = new Canard::Client{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb}; + mppt_outputenable_client = NEW_NOTHROW Canard::Client{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb}; if (mppt_outputenable_client == nullptr) { return; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index a25ef9667855c8..7d34b91acf1faa 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -47,7 +47,7 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend // return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) uint32_t get_mavlink_fault_bitmask() const override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_BattMonitor_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp index c633217f531aeb..7b76295f3b5a2a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp @@ -20,6 +20,32 @@ #include "AP_BattMonitor_ESC.h" +const AP_Param::GroupInfo AP_BattMonitor_ESC::var_info[] = { + + // Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + + // @Param: ESC_MASK + // @DisplayName: ESC mask + // @Description: If 0 all connected ESCs will be used. If non-zero, only those selected in will be used. + // @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: Standard + AP_GROUPINFO("ESC_MASK", 36, AP_BattMonitor_ESC, _mask, 0), + + // Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + + AP_GROUPEND +}; + +// constructor. This incorporates initialisation as well. +AP_BattMonitor_ESC::AP_BattMonitor_ESC(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; +}; + void AP_BattMonitor_ESC::init(void) { } @@ -33,10 +59,16 @@ void AP_BattMonitor_ESC::read(void) float voltage_sum = 0; float current_sum = 0; float temperature_sum = 0; + float consumed_mah_sum = 0.0; uint32_t highest_ms = 0; - _state.consumed_mah = delta_mah; + const bool all_enabled = _mask == 0; for (uint8_t i=0; i 0) { - // if we have ever got a current value then we know we have a - // current sensor - have_current = true; + const uint32_t now_us = AP_HAL::micros(); + const uint32_t dt_us = now_us - last_read_us; + last_read_us = now_us; + + if (have_consumed_mah) { + // Report the cumulative consumed mah as reported by the ESCs + // delta_mah allows reset_remaining to function without being able to reset the values sent by the ESCs + _state.consumed_mah = delta_mah + consumed_mah_sum; + + } else if (have_current) { + // ESCs provide current but not consumed mah, integrate manually + update_consumed(_state, dt_us); + } } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.h b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.h index 40aaedffa64eed..400520dfbe979f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.h @@ -25,9 +25,7 @@ class AP_BattMonitor_ESC :public AP_BattMonitor_Backend { public: // constructor. This incorporates initialisation as well. - AP_BattMonitor_ESC(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms): - AP_BattMonitor_Backend(mon, mon_state, params) - {}; + AP_BattMonitor_ESC(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms); virtual ~AP_BattMonitor_ESC(void) {}; @@ -46,10 +44,18 @@ class AP_BattMonitor_ESC :public AP_BattMonitor_Backend // reset remaining percentage to given value virtual bool reset_remaining(float percentage) override; + static const struct AP_Param::GroupInfo var_info[]; + private: + + AP_Int32 _mask; + bool have_current; + bool have_consumed_mah; bool have_temperature; float delta_mah; + + uint32_t last_read_us; }; #endif // AP_BATTERY_ESC_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp index f1dfead2bba7bf..d5d6c324bf7e82 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp @@ -54,8 +54,8 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = { // @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 + // @Description: Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins". + // @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1 AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1), // index 44 unused and available @@ -63,28 +63,28 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = { // @Param: FL_FF // @DisplayName: First order term // @Description: First order polynomial fit term - // @Range: 0 10 + // @Range: -10 10 // @User: Advanced AP_GROUPINFO("FL_FF", 45, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_first_order_coeff, 1), // @Param: FL_FS // @DisplayName: Second order term // @Description: Second order polynomial fit term - // @Range: 0 10 + // @Range: -10 10 // @User: Advanced AP_GROUPINFO("FL_FS", 46, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_second_order_coeff, 0), // @Param: FL_FT // @DisplayName: Third order term // @Description: Third order polynomial fit term - // @Range: 0 10 + // @Range: -10 10 // @User: Advanced AP_GROUPINFO("FL_FT", 47, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_third_order_coeff, 0), // @Param: FL_OFF // @DisplayName: Offset term // @Description: Offset polynomial fit term - // @Range: 0 10 + // @Range: -10 10 // @User: Advanced AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0), diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h index 5f3e0530c40cb8..bba898860e5369 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h @@ -40,8 +40,8 @@ class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend // 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 false; } + // returns true if battery monitor provides current info (or capacity) + bool has_current() const override { return true; } void init(void) override {} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp index 94be30abc7b9f2..cf25c819740bec 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp @@ -46,6 +46,17 @@ extern const AP_HAL::HAL& hal; #define REG_238_DIETEMP 0x06 #define INA_238_TEMP_C_LSB 7.8125e-3 // need to mask bottom 4 bits +// INA231 specific registers +#define REG_231_CONFIG 0x00 +#define REG_231_SHUNT_VOLTAGE 0x01 +#define REG_231_BUS_VOLTAGE 0x02 +#define REG_231_POWER 0x03 +#define REG_231_CURRENT 0x04 +#define REG_231_CALIBRATION 0x05 +#define REG_231_MASK 0x06 +#define REG_231_ALERT 0x07 + + #ifndef DEFAULT_BATTMON_INA2XX_MAX_AMPS #define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.0 #endif @@ -144,7 +155,7 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) case DevType::INA228: { // configure for MAX_AMPS voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB - current_LSB = max_amps / (1<<19); + current_LSB = max_amps / (1U<<19); const uint16_t shunt_cal = uint16_t(13107.2e6 * current_LSB * rShunt) & 0x7FFF; if (write_word(REG_228_CONFIG, REG_228_CONFIG_RESET) && // reset write_word(REG_228_CONFIG, 0) && @@ -158,7 +169,7 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) case DevType::INA238: { // configure for MAX_AMPS voltage_LSB = 3.125e-3; // 3.125mV/LSB - current_LSB = max_amps / (1<<15); + current_LSB = max_amps / (1U<<15); const uint16_t shunt_cal = uint16_t(819.2e6 * current_LSB * rShunt) & 0x7FFF; if (write_word(REG_238_CONFIG, REG_238_CONFIG_RESET) && // reset write_word(REG_238_CONFIG, 0) && @@ -168,6 +179,16 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) } break; } + + case DevType::INA231: { + // no configuration needed + voltage_LSB = 1.25e-3; + current_LSB = max_amps / (1U<<15); + const uint16_t cal = 0.00512 / (current_LSB * rShunt); + if (write_word(REG_231_CALIBRATION, cal)) { + return true; + } + } } return false; @@ -281,6 +302,11 @@ bool AP_BattMonitor_INA2XX::detect_device(void) id == REG_226_CONFIG_DEFAULT) { return configure(DevType::INA226); } + if (read_word16(REG_231_CONFIG, id) && id == 0x4127) { + // no manufacturer ID for 231 + return configure(DevType::INA231); + } + return false; } @@ -351,6 +377,22 @@ void AP_BattMonitor_INA2XX::timer(void) temperature = (temp16&0xFFF0) * INA_238_TEMP_C_LSB; break; } + + case DevType::INA231: { + int16_t bus_voltage16, current16; + if (!read_word16(REG_231_SHUNT_VOLTAGE, bus_voltage16) || + !read_word16(REG_231_CURRENT, current16)) { + failed_reads++; + if (failed_reads > 10) { + // device has disconnected, we need to reconfigure it + dev_type = DevType::UNKNOWN; + } + return; + } + voltage = bus_voltage16 * voltage_LSB; + current = current16 * current_LSB; + break; + } } failed_reads = 0; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h index b23b4420eacfc8..4c5b5dfbf5af45 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h @@ -35,6 +35,7 @@ class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend INA226, INA228, INA238, + INA231, }; static const uint8_t i2c_probe_addresses[]; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 60cdf5ad769bc5..aceee7c05b373e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -143,21 +143,23 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: ARM_MAH // @DisplayName: Required arming remaining capacity - // @Description: Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the @PREFIX@_ARM_VOLT parameter. + // @Description: Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the @PREFIX@ARM_VOLT parameter. // @Units: mAh // @Increment: 50 // @User: Advanced AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0), // 20 was BUS +#endif // HAL_BUILD_AP_PERIPH +#if AP_BATTERY_OPTIONS_PARAM_ENABLED // @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, 6:Send resistance compensated voltage to GCS, 7:Allow DroneCAN InfoAux to be from a different CAN node + // @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, 7:Allow DroneCAN InfoAux to be from a different CAN node, 9:Sum monitor measures minimum voltage instead of average // @User: Advanced AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0), -#endif // HAL_BUILD_AP_PERIPH +#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED #if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED // @Param: ESC_INDEX diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 2088845c39f62d..4665e0eeaa46a6 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -17,7 +17,7 @@ class AP_BattMonitor_Params { BattMonitor_LowVoltageSource_Raw = 0, BattMonitor_LowVoltageSource_SagCompensated = 1 }; - enum class Options : uint8_t { + enum class Options : uint16_t { Ignore_UAVCAN_SoC = (1U<<0), // Ignore UAVCAN State-of-Charge (charge %) supplied value from the device and use the internally calculated one MPPT_Use_Input_Value = (1U<<1), // MPPT reports voltage and current from Input (usually solar panel) instead of the output MPPT_Power_Off_At_Disarm = (1U<<2), // MPPT Disabled when vehicle is disarmed, if HW supports it @@ -26,6 +26,8 @@ class AP_BattMonitor_Params { 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 AllowSplitAuxInfo = (1U<<7), // allow different node to provide aux info for DroneCAN + InternalUseOnly = (1U<<8), // for use internally to ArduPilot, not to be (eg.) sent via MAVLink BATTERY_STATUS + Minimum_Voltage = (1U<<9), // sum monitor measures minimum voltage rather than average }; 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_Sum.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp index 2a7401d3267a83..dcc37cc27838b6 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp @@ -50,10 +50,17 @@ void AP_BattMonitor_Sum::read() { float voltage_sum = 0; + float voltage_min = 0; uint8_t voltage_count = 0; float current_sum = 0; uint8_t current_count = 0; + float temperature_sum = 0.0; + uint8_t temperature_count = 0; + + float consumed_mah_sum = 0; + float consumed_wh_sum = 0; + for (uint8_t i=0; i<_mon.num_instances(); i++) { if (i == _instance) { // never include self @@ -70,27 +77,55 @@ AP_BattMonitor_Sum::read() if (!_mon.healthy(i)) { continue; } - voltage_sum += _mon.voltage(i); + const float voltage = _mon.voltage(i); + if (voltage_count == 0 || voltage < voltage_min) { + voltage_min = voltage; + } + voltage_sum += voltage; voltage_count++; float current; if (_mon.current_amps(current, i)) { current_sum += current; current_count++; } + + float temperature; + if (_mon.get_temperature(temperature, i)) { + temperature_sum += temperature; + temperature_count++; + } + + float consumed_mah; + if (_mon.consumed_mah(consumed_mah, i)) { + consumed_mah_sum += consumed_mah; + } + + float consumed_wh; + if (_mon.consumed_wh(consumed_wh, i)) { + consumed_wh_sum += consumed_wh; + } } 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; + if (option_is_set(AP_BattMonitor_Params::Options::Minimum_Voltage)) { + _state.voltage = voltage_min; + } else { + _state.voltage = voltage_sum / voltage_count; + } } if (current_count > 0) { _state.current_amps = current_sum; + _state.consumed_mah = consumed_mah_sum; + _state.consumed_wh = consumed_wh_sum; + } + if (temperature_count > 0) { + _state.temperature = temperature_sum / temperature_count; + _state.temperature_time = AP_HAL::millis(); } - - update_consumed(_state, dt_us); _has_current = (current_count > 0); + _has_temperature = (temperature_count > 0); _state.healthy = (voltage_count > 0); if (_state.healthy) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.h b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.h index 1e882bb3339ffa..000ceb5d2561c3 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.h @@ -22,6 +22,9 @@ class AP_BattMonitor_Sum : public AP_BattMonitor_Backend /// returns true if battery monitor provides current info bool has_current() const override { return _has_current; } + /// returns true if battery monitor provides temperature info + bool has_temperature() const override { return _has_temperature; } + void init(void) override {} static const struct AP_Param::GroupInfo var_info[]; @@ -31,6 +34,7 @@ class AP_BattMonitor_Sum : public AP_BattMonitor_Backend AP_Int16 _sum_mask; uint8_t _instance; bool _has_current; + bool _has_temperature; }; #endif // AP_BATTERY_SUM_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp index dfb7921abe5ebe..5bd3e8aba0528f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp @@ -35,10 +35,11 @@ void AP_BattMonitor_Torqeedo::read(void) } // get voltage, current, temp and remaining capacity percentage + // assumes battery monitor instance matches torqeedo instance float volts; float current_amps; float temp_C; - if (torqeedo->get_batt_info(volts, current_amps, temp_C, remaining_pct)) { + if (torqeedo->get_batt_info(_state.instance, volts, current_amps, temp_C, remaining_pct)) { have_info = true; _state.voltage = volts; _state.current_amps = current_amps; @@ -56,9 +57,10 @@ void AP_BattMonitor_Torqeedo::read(void) } // read battery pack capacity + // assumes battery monitor instance matches torqeedo instance if (!have_capacity) { uint16_t batt_capacity_ah; - if (torqeedo->get_batt_capacity_Ah(batt_capacity_ah)) { + if (torqeedo->get_batt_capacity_Ah(_state.instance, batt_capacity_ah)) { have_capacity = true; if (batt_capacity_ah * 1000 != _params._pack_capacity) { _params._pack_capacity.set_and_notify(batt_capacity_ah * 1000); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index e15909c1435794..3159b075d6b1c5 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -83,7 +83,7 @@ #endif #ifndef AP_BATTERY_SUM_ENABLED -#define AP_BATTERY_SUM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED +#define AP_BATTERY_SUM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024) #endif #ifndef AP_BATTERY_TORQEEDO_ENABLED @@ -119,3 +119,7 @@ #ifndef AP_BATTERY_SCRIPTING_ENABLED #define AP_BATTERY_SCRIPTING_ENABLED (AP_SCRIPTING_ENABLED && AP_BATTERY_BACKEND_DEFAULT_ENABLED) #endif + +#ifndef AP_BATTERY_OPTIONS_PARAM_ENABLED +#define AP_BATTERY_OPTIONS_PARAM_ENABLED (!defined(HAL_BUILD_AP_PERIPH) || AP_BATTERY_SUM_ENABLED) +#endif diff --git a/libraries/AP_Beacon/AP_Beacon.cpp b/libraries/AP_Beacon/AP_Beacon.cpp index 0a2a04e71cb983..c2044ad7585e52 100644 --- a/libraries/AP_Beacon/AP_Beacon.cpp +++ b/libraries/AP_Beacon/AP_Beacon.cpp @@ -28,6 +28,10 @@ extern const AP_HAL::HAL &hal; +#ifndef AP_BEACON_MINIMUM_FENCE_BEACONS +#define AP_BEACON_MINIMUM_FENCE_BEACONS 3 +#endif + // table of user settable parameters const AP_Param::GroupInfo AP_Beacon::var_info[] = { @@ -97,24 +101,30 @@ void AP_Beacon::init(void) } // create backend - if (_type == AP_BeaconType_Pozyx) { - _driver = new AP_Beacon_Pozyx(*this); - } else if (_type == AP_BeaconType_Marvelmind) { - _driver = new AP_Beacon_Marvelmind(*this); - } else if (_type == AP_BeaconType_Nooploop) { - _driver = new AP_Beacon_Nooploop(*this); - } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - if (_type == AP_BeaconType_SITL) { - _driver = new AP_Beacon_SITL(*this); - } + switch ((Type)_type) { + case Type::Pozyx: + _driver = NEW_NOTHROW AP_Beacon_Pozyx(*this); + break; + case Type::Marvelmind: + _driver = NEW_NOTHROW AP_Beacon_Marvelmind(*this); + break; + case Type::Nooploop: + _driver = NEW_NOTHROW AP_Beacon_Nooploop(*this); + break; +#if AP_BEACON_SITL_ENABLED + case Type::SITL: + _driver = NEW_NOTHROW AP_Beacon_SITL(*this); + break; #endif + case Type::None: + break; + } } // return true if beacon feature is enabled bool AP_Beacon::enabled(void) const { - return (_type != AP_BeaconType_None); + return (_type != Type::None); } // return true if sensor is basically healthy (we are receiving data) @@ -236,7 +246,7 @@ Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const // return last update time from beacon in milliseconds uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const { - if (_type == AP_BeaconType_None || beacon_instance >= num_beacons) { + if (_type == Type::None || beacon_instance >= num_beacons) { return 0; } return beacon_state[beacon_instance].distance_update_ms; @@ -388,7 +398,7 @@ const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const // check if the device is ready bool AP_Beacon::device_ready(void) const { - return ((_driver != nullptr) && (_type != AP_BeaconType_None)); + return ((_driver != nullptr) && (_type != Type::None)); } #if HAL_LOGGING_ENABLED diff --git a/libraries/AP_Beacon/AP_Beacon.h b/libraries/AP_Beacon/AP_Beacon.h index be7766d4227064..aaebfa86ad7c33 100644 --- a/libraries/AP_Beacon/AP_Beacon.h +++ b/libraries/AP_Beacon/AP_Beacon.h @@ -25,10 +25,6 @@ class AP_Beacon_Backend; -#define AP_BEACON_MAX_BEACONS 4 -#define AP_BEACON_TIMEOUT_MS 300 -#define AP_BEACON_MINIMUM_FENCE_BEACONS 3 - class AP_Beacon { public: @@ -40,12 +36,14 @@ class AP_Beacon static AP_Beacon *get_singleton() { return _singleton; } // external position backend types (used by _TYPE parameter) - enum AP_BeaconType { - AP_BeaconType_None = 0, - AP_BeaconType_Pozyx = 1, - AP_BeaconType_Marvelmind = 2, - AP_BeaconType_Nooploop = 3, - AP_BeaconType_SITL = 10 + enum class Type : uint8_t { + None = 0, + Pozyx = 1, + Marvelmind = 2, + Nooploop = 3, +#if AP_BEACON_SITL_ENABLED + SITL = 10 +#endif }; // The AP_BeaconState structure is filled in by the backend driver @@ -125,7 +123,7 @@ class AP_Beacon static bool get_next_boundary_point(const Vector2f* boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle); // parameters - AP_Int8 _type; + AP_Enum _type; AP_Float origin_lat; AP_Float origin_lon; AP_Float origin_alt; diff --git a/libraries/AP_Beacon/AP_Beacon_Marvelmind.cpp b/libraries/AP_Beacon/AP_Beacon_Marvelmind.cpp index 4154b5edd99944..1029d66800a73c 100644 --- a/libraries/AP_Beacon/AP_Beacon_Marvelmind.cpp +++ b/libraries/AP_Beacon/AP_Beacon_Marvelmind.cpp @@ -37,7 +37,7 @@ extern const AP_HAL::HAL& hal; #if MM_DEBUG_LEVEL #include - #define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0) + #define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } } while (0) #else #define Debug(level, fmt, args ...) #endif diff --git a/libraries/AP_Beacon/AP_Beacon_config.h b/libraries/AP_Beacon/AP_Beacon_config.h index 38d35331421df9..d3d866015f7357 100644 --- a/libraries/AP_Beacon/AP_Beacon_config.h +++ b/libraries/AP_Beacon/AP_Beacon_config.h @@ -6,6 +6,14 @@ #define AP_BEACON_ENABLED 1 #endif +#ifndef AP_BEACON_MAX_BEACONS +#define AP_BEACON_MAX_BEACONS 4 +#endif + +#ifndef AP_BEACON_TIMEOUT_MS +#define AP_BEACON_TIMEOUT_MS 300 +#endif + #ifndef AP_BEACON_BACKEND_DEFAULT_ENABLED #define AP_BEACON_BACKEND_DEFAULT_ENABLED AP_BEACON_ENABLED #endif diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 1457d86b6235d5..b3af55da949d32 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -115,7 +115,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Param: SER1_RTSCTS // @DisplayName: Serial 1 flow control // @Description: Enable flow control on serial 1 (telemetry 1). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled. - // @Values: 0:Disabled,1:Enabled,2:Auto + // @Values: 0:Disabled,1:Enabled,2:Auto,3:RS-485 Driver enable RTS pin // @RebootRequired: True // @User: Advanced AP_GROUPINFO("SER1_RTSCTS", 1, AP_BoardConfig, state.ser_rtscts[1], BOARD_SER1_RTSCTS_DEFAULT), @@ -123,41 +123,33 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #ifdef HAL_HAVE_RTSCTS_SERIAL2 // @Param: SER2_RTSCTS + // @CopyFieldsFrom: BRD_SER1_RTSCTS // @DisplayName: Serial 2 flow control // @Description: Enable flow control on serial 2 (telemetry 2). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. - // @Values: 0:Disabled,1:Enabled,2:Auto - // @RebootRequired: True - // @User: Advanced AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser_rtscts[2], 2), #endif #ifdef HAL_HAVE_RTSCTS_SERIAL3 // @Param: SER3_RTSCTS + // @CopyFieldsFrom: BRD_SER1_RTSCTS // @DisplayName: Serial 3 flow control // @Description: Enable flow control on serial 3. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. - // @Values: 0:Disabled,1:Enabled,2:Auto - // @RebootRequired: True - // @User: Advanced AP_GROUPINFO("SER3_RTSCTS", 26, AP_BoardConfig, state.ser_rtscts[3], 2), #endif #ifdef HAL_HAVE_RTSCTS_SERIAL4 // @Param: SER4_RTSCTS + // @CopyFieldsFrom: BRD_SER1_RTSCTS // @DisplayName: Serial 4 flow control // @Description: Enable flow control on serial 4. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. - // @Values: 0:Disabled,1:Enabled,2:Auto - // @RebootRequired: True - // @User: Advanced AP_GROUPINFO("SER4_RTSCTS", 27, AP_BoardConfig, state.ser_rtscts[4], 2), #endif #ifdef HAL_HAVE_RTSCTS_SERIAL5 // @Param: SER5_RTSCTS + // @CopyFieldsFrom: BRD_SER1_RTSCTS // @DisplayName: Serial 5 flow control // @Description: Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. - // @Values: 0:Disabled,1:Enabled,2:Auto - // @RebootRequired: True - // @User: Advanced AP_GROUPINFO("SER5_RTSCTS", 25, AP_BoardConfig, state.ser_rtscts[5], 2), #endif #endif @@ -225,7 +217,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1), #endif -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED // @Group: RADIO // @Path: ../AP_Radio/AP_Radio.cpp AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio), @@ -289,7 +281,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Param: OPTIONS // @DisplayName: Board options // @Description: Board specific option flags - // @Bitmask: 0:Enable hardware watchdog, 1:Disable MAVftp, 2:Enable set of internal parameters, 3:Enable Debug Pins, 4:Unlock flash on reboot, 5:Write protect firmware flash on reboot, 6:Write protect bootloader flash on reboot, 7:Skip board validation, 8:Disable board arming gpio output change on arm/disarm + // @Bitmask: 0:Enable hardware watchdog, 1:Disable MAVftp, 2:Enable set of internal parameters, 3:Enable Debug Pins, 4:Unlock flash on reboot, 5:Write protect firmware flash on reboot, 6:Write protect bootloader flash on reboot, 7:Skip board validation, 8:Disable board arming gpio output change on arm/disarm, 9:Use safety pins as profiled // @User: Advanced AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT), diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index 938180a238bb95..1ff4e2038e7ce5 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -5,8 +5,9 @@ #include #include #include +#include -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED #include #endif @@ -157,7 +158,8 @@ class AP_BoardConfig { WRITE_PROTECT_FLASH = (1<<5), WRITE_PROTECT_BOOTLOADER = (1<<6), SKIP_BOARD_VALIDATION = (1<<7), - DISABLE_ARMING_GPIO = (1<<8) + DISABLE_ARMING_GPIO = (1<<8), + IO_SAFETY_PINS_AS_PROFILED = (1<<9), }; //return true if arming gpio output is disabled @@ -199,6 +201,12 @@ class AP_BoardConfig { return _singleton?(_singleton->_options & ALLOW_SET_INTERNAL_PARM)!=0:false; } +#if HAL_WITH_IO_MCU + static bool use_safety_as_led(void) { + return _singleton?(_singleton->_options & IO_SAFETY_PINS_AS_PROFILED)!=0:false; + } +#endif + // handle press of safety button. Return true if safety state // should be toggled bool safety_button_handle_pressed(uint8_t press_count); @@ -292,7 +300,7 @@ class AP_BoardConfig { } heater; #endif -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED // direct attached radio AP_Radio _radio; #endif diff --git a/libraries/AP_BoardConfig/IMU_heater.cpp b/libraries/AP_BoardConfig/IMU_heater.cpp index 151136d17252b7..fa3314159083c8 100644 --- a/libraries/AP_BoardConfig/IMU_heater.cpp +++ b/libraries/AP_BoardConfig/IMU_heater.cpp @@ -108,7 +108,7 @@ void AP_BoardConfig::set_imu_temp(float current) #endif // HAL_LOGGING_ENABLED #if 0 - gcs().send_text(MAV_SEVERITY_INFO, "Heater: Out=%.1f Temp=%.1f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Heater: Out=%.1f Temp=%.1f", double(heater.output), double(avg)); #endif diff --git a/libraries/AP_CANManager/AP_CANDriver.h b/libraries/AP_CANManager/AP_CANDriver.h index f93e96cec0e7a8..5f1c4f74a2a76c 100644 --- a/libraries/AP_CANManager/AP_CANDriver.h +++ b/libraries/AP_CANManager/AP_CANDriver.h @@ -40,5 +40,5 @@ class AP_CANDriver virtual bool add_11bit_driver(CANSensor *sensor) { return false; } // handler for outgoing frames for auxillary drivers - virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) { return false; } + virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { return false; } }; diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index c89bc67e8daa91..ebf574df99236b 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -129,7 +129,7 @@ void AP_CANManager::init() #endif // We only allocate log buffer only when under debug if (_loglevel != AP_CANManager::LOG_NONE) { - _log_buf = new char[LOG_BUFFER_SIZE]; + _log_buf = NEW_NOTHROW char[LOG_BUFFER_SIZE]; _log_pos = 0; } @@ -152,7 +152,7 @@ void AP_CANManager::init() if (hal_mutable.can[i] == nullptr) { // So if this interface is not allocated allocate it here, // also pass the index of the CANBus - hal_mutable.can[i] = new HAL_CANIface(i); + hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i); } // Initialise the interface we just allocated @@ -199,9 +199,10 @@ void AP_CANManager::init() } // Allocate the set type of Driver + switch (drv_type[drv_num]) { #if HAL_ENABLE_DRONECAN_DRIVERS - if (drv_type[drv_num] == AP_CAN::Protocol::DroneCAN) { - _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_DroneCAN(drv_num); + case AP_CAN::Protocol::DroneCAN: + _drivers[drv_num] = _drv_param[drv_num]._uavcan = NEW_NOTHROW AP_DroneCAN(drv_num); if (_drivers[drv_num] == nullptr) { AP_BoardConfig::allocation_error("uavcan %d", i + 1); @@ -209,11 +210,11 @@ void AP_CANManager::init() } AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info); - } else + break; #endif #if HAL_PICCOLO_CAN_ENABLE - if (drv_type[drv_num] == AP_CAN::Protocol::PiccoloCAN) { - _drivers[drv_num] = _drv_param[drv_num]._piccolocan = new AP_PiccoloCAN; + case AP_CAN::Protocol::PiccoloCAN: + _drivers[drv_num] = _drv_param[drv_num]._piccolocan = NEW_NOTHROW AP_PiccoloCAN; if (_drivers[drv_num] == nullptr) { AP_BoardConfig::allocation_error("PiccoloCAN %d", drv_num + 1); @@ -221,9 +222,9 @@ void AP_CANManager::init() } AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info); - } else + break; #endif - { + default: continue; } @@ -266,7 +267,7 @@ void AP_CANManager::init() WITH_SEMAPHORE(_sem); for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { if ((AP_CAN::Protocol) _drv_param[i]._driver_type.get() == AP_CAN::Protocol::DroneCAN) { - _drivers[i] = _drv_param[i]._uavcan = new AP_DroneCAN(i); + _drivers[i] = _drv_param[i]._uavcan = NEW_NOTHROW AP_DroneCAN(i); if (_drivers[i] == nullptr) { AP_BoardConfig::allocation_error("uavcan %d", i + 1); @@ -312,7 +313,7 @@ bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver if (hal_mutable.can[i] == nullptr) { // if this interface is not allocated allocate it here, // also pass the index of the CANBus - hal_mutable.can[i] = new HAL_CANIface(i); + hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i); } // Initialise the interface we just allocated @@ -425,33 +426,43 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com { WITH_SEMAPHORE(can_forward.sem); const int8_t bus = int8_t(packet.param1)-1; + if (bus == -1) { - for (auto can_iface : hal.can) { - if (can_iface) { - can_iface->register_frame_callback(nullptr); - } + /* + a request to stop forwarding + */ + if (can_forward.callback_id != 0) { + hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id); + can_forward.callback_id = 0; } return true; } + if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) { return false; } - if (!hal.can[bus]->register_frame_callback( - FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &))) { + + if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) { + /* + the client is changing which bus they are monitoring, unregister from the previous bus + */ + hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id); + can_forward.callback_id = 0; + } + + if (can_forward.callback_id == 0 && + !hal.can[bus]->register_frame_callback( + FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), can_forward.callback_id)) { + // failed to register the callback return false; } + + can_forward.callback_bus = bus; can_forward.last_callback_enable_ms = AP_HAL::millis(); can_forward.chan = chan; can_forward.system_id = msg.sysid; can_forward.component_id = msg.compid; - // remove registration on other buses, allowing for bus change in the GUI tool - for (uint8_t i=0; iregister_frame_callback(nullptr); - } - } - return true; } @@ -467,7 +478,7 @@ void AP_CANManager::handle_can_frame(const mavlink_message_t &msg) 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); + frame_buffer = NEW_NOTHROW ObjectBuffer(buffer_size); if (frame_buffer != nullptr && frame_buffer->get_size() != 0) { // 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)); @@ -577,7 +588,7 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg) // common case of replacing with identical list return; } - new_ids = new uint16_t[p.num_ids]; + new_ids = NEW_NOTHROW uint16_t[p.num_ids]; if (new_ids != nullptr) { num_new_ids = p.num_ids; memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t)); @@ -590,7 +601,7 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg) // nothing changing return; } - new_ids = new uint16_t[can_forward.num_filter_ids+p.num_ids]; + new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids]; if (new_ids == nullptr) { return; } @@ -638,12 +649,18 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg) void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) { WITH_SEMAPHORE(can_forward.sem); + if (bus != can_forward.callback_bus) { + // we are not registered for forwarding this bus, discard frame + return; + } if (can_forward.frame_counter++ == 100) { // check every 100 frames for disabling CAN_FRAME send // we stop sending after 5s if the client stops // sending MAV_CMD_CAN_FORWARD requests - if (AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) { - hal.can[bus]->register_frame_callback(nullptr); + if (can_forward.callback_id != 0 && + AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) { + hal.can[bus]->unregister_frame_callback(can_forward.callback_id); + can_forward.callback_id = 0; return; } can_forward.frame_counter = 0; diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 4a891320aa7d99..f820d8317482de 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -185,6 +185,8 @@ class AP_CANManager HAL_Semaphore sem; uint16_t num_filter_ids; uint16_t *filter_ids; + uint8_t callback_id; + uint8_t callback_bus; } can_forward; // buffer for MAVCAN frames diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index 17b46d1d308709..ffa9bf3cc6d9ff 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -135,7 +135,7 @@ bool CANSensor::add_interface(AP_HAL::CANIface* can_iface) return true; } -bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { if (!_initialized) { debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame"); @@ -171,12 +171,12 @@ void CANSensor::loop() #endif while (true) { - uint64_t timeout = AP_HAL::micros64() + LOOP_INTERVAL_US; + uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US; // wait to receive frame bool read_select = true; bool write_select = false; - bool ret = _can_iface->select(read_select, write_select, nullptr, timeout); + bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us); if (ret && read_select) { uint64_t time; AP_HAL::CANIface::CanIOFlags flags {}; @@ -197,7 +197,7 @@ MultiCAN::MultiCAN(ForwardCanFrame cf, AP_CAN::Protocol can_type, const char *dr CANSensor(driver_name) { if (callbacks == nullptr) { - callbacks = new MultiCANLinkedList(); + callbacks = NEW_NOTHROW MultiCANLinkedList(); } if (callbacks == nullptr) { AP_BoardConfig::allocation_error("Failed to create multican callback"); @@ -220,7 +220,7 @@ void MultiCAN::handle_frame(AP_HAL::CANFrame &frame) // register a callback for a CAN frame by adding it to the linked list void MultiCAN::MultiCANLinkedList::register_callback(ForwardCanFrame callback) { - CANSensor_Multi* newNode = new CANSensor_Multi(); + CANSensor_Multi* newNode = NEW_NOTHROW CANSensor_Multi(); if (newNode == nullptr) { AP_BoardConfig::allocation_error("Failed to create multican node"); } diff --git a/libraries/AP_CANManager/AP_CANSensor.h b/libraries/AP_CANManager/AP_CANSensor.h index 7ba0021bb13460..b5ac4ee3b0b0ff 100644 --- a/libraries/AP_CANManager/AP_CANSensor.h +++ b/libraries/AP_CANManager/AP_CANSensor.h @@ -36,11 +36,14 @@ class CANSensor : public AP_CANDriver { void init(uint8_t driver_index, bool enable_filters) override; bool add_interface(AP_HAL::CANIface* can_iface) override; + // Return true if this sensor has been successfully registered to a driver and initialized. + bool initialized() const { return _initialized; } + // handler for incoming frames virtual void handle_frame(AP_HAL::CANFrame &frame) = 0; // handler for outgoing frames - bool write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us); + bool write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us); #ifdef HAL_BUILD_AP_PERIPH static void set_periph(const uint8_t i, const AP_CAN::Protocol protocol, AP_HAL::CANIface* iface) { diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index 496e8850ed2c1e..b7a3b5a51a4cfd 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -82,24 +82,7 @@ static uint8_t nibble2hex(uint8_t x) static uint8_t hex2nibble(char c) { - // Must go into RAM, not flash, because flash is slow - static uint8_t NumConversionTable[] = { - 0, 1, 2, 3, 4, 5, 6, 7, 8, 9 - }; - - static uint8_t AlphaConversionTable[] = { - 10, 11, 12, 13, 14, 15 - }; - - uint8_t out = 255; - - if (c >= '0' && c <= '9') { - out = NumConversionTable[int(c) - int('0')]; - } else if (c >= 'a' && c <= 'f') { - out = AlphaConversionTable[int(c) - int('a')]; - } else if (c >= 'A' && c <= 'F') { - out = AlphaConversionTable[int(c) - int('A')]; - } + uint8_t out = char_to_hex(c); if (out == 255) { hex2nibble_error = true; diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 4b2182388b0742..288b0506bb54ee 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -2,10 +2,10 @@ #if AP_CAMERA_ENABLED +#include #include #include #include -#include #include "AP_Camera_Backend.h" #include "AP_Camera_Servo.h" #include "AP_Camera_Relay.h" @@ -201,42 +201,42 @@ void AP_Camera::init() switch ((CameraType)_params[instance].type.get()) { #if AP_CAMERA_SERVO_ENABLED case CameraType::SERVO: - _backends[instance] = new AP_Camera_Servo(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_Servo(*this, _params[instance], instance); break; #endif #if AP_CAMERA_RELAY_ENABLED case CameraType::RELAY: - _backends[instance] = new AP_Camera_Relay(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_Relay(*this, _params[instance], instance); break; #endif #if AP_CAMERA_SOLOGIMBAL_ENABLED // check for GoPro in Solo camera case CameraType::SOLOGIMBAL: - _backends[instance] = new AP_Camera_SoloGimbal(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_SoloGimbal(*this, _params[instance], instance); break; #endif #if AP_CAMERA_MOUNT_ENABLED // check for Mount camera case CameraType::MOUNT: - _backends[instance] = new AP_Camera_Mount(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_Mount(*this, _params[instance], instance); break; #endif #if AP_CAMERA_MAVLINK_ENABLED // check for MAVLink enabled camera driver case CameraType::MAVLINK: - _backends[instance] = new AP_Camera_MAVLink(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_MAVLink(*this, _params[instance], instance); break; #endif #if AP_CAMERA_MAVLINKCAMV2_ENABLED // check for MAVLink Camv2 driver case CameraType::MAVLINK_CAMV2: - _backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_MAVLinkCamV2(*this, _params[instance], instance); break; #endif #if AP_CAMERA_SCRIPTING_ENABLED // check for Scripting driver case CameraType::SCRIPTING: - _backends[instance] = new AP_Camera_Scripting(*this, _params[instance], instance); + _backends[instance] = NEW_NOTHROW AP_Camera_Scripting(*this, _params[instance], instance); break; #endif case CameraType::NONE: @@ -432,6 +432,56 @@ MAV_RESULT AP_Camera::handle_command(const mavlink_command_int_t &packet) } } +// send a mavlink message; returns false if there was not space to +// send the message, true otherwise +bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message msg_id) +{ + const auto chan = link.get_chan(); + + switch (msg_id) { + case MSG_CAMERA_FEEDBACK: + CHECK_PAYLOAD_SIZE2(CAMERA_FEEDBACK); + send_feedback(chan); + break; + case MSG_CAMERA_INFORMATION: + CHECK_PAYLOAD_SIZE2(CAMERA_INFORMATION); + send_camera_information(chan); + break; + case MSG_CAMERA_SETTINGS: + CHECK_PAYLOAD_SIZE2(CAMERA_SETTINGS); + send_camera_settings(chan); + break; +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED + case MSG_CAMERA_FOV_STATUS: + CHECK_PAYLOAD_SIZE2(CAMERA_FOV_STATUS); + send_camera_fov_status(chan); + break; +#endif + case MSG_CAMERA_CAPTURE_STATUS: + CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS); + send_camera_capture_status(chan); + break; +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + case MSG_CAMERA_THERMAL_RANGE: + CHECK_PAYLOAD_SIZE2(CAMERA_THERMAL_RANGE); + send_camera_thermal_range(chan); + break; +#endif +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + case MSG_VIDEO_STREAM_INFORMATION: + CHECK_PAYLOAD_SIZE2(VIDEO_STREAM_INFORMATION); + send_video_stream_information(chan); + break; +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + + default: + // should not reach this; should only be called for specific IDs + break; + } + + return true; +} + // set camera trigger distance in a mission void AP_Camera::set_trigger_distance(uint8_t instance, float distance_m) { @@ -536,6 +586,21 @@ void AP_Camera::send_camera_information(mavlink_channel_t chan) } } +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED +// send video stream information message to GCS +void AP_Camera::send_video_stream_information(mavlink_channel_t chan) +{ + WITH_SEMAPHORE(_rsem); + + // call each instance + for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->send_video_stream_information(chan); + } + } +} +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + // send camera settings message to GCS void AP_Camera::send_camera_settings(mavlink_channel_t chan) { @@ -577,6 +642,21 @@ void AP_Camera::send_camera_capture_status(mavlink_channel_t chan) } } +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Camera::send_camera_thermal_range(mavlink_channel_t chan) +{ + WITH_SEMAPHORE(_rsem); + + // call each instance + for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->send_camera_thermal_range(chan); + } + } +} +#endif + /* update; triggers by distance moved and camera trigger */ @@ -742,8 +822,70 @@ bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state) } return backend->get_state(cam_state); } + +// change camera settings not normally used by autopilot +bool AP_Camera::change_setting(uint8_t instance, CameraSetting setting, float value) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->change_setting(setting, value); +} + #endif // #if AP_CAMERA_SCRIPTING_ENABLED + +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +void AP_Camera::set_camera_information(mavlink_camera_information_t camera_info) +{ + WITH_SEMAPHORE(_rsem); + + if (primary == nullptr) { + return; + } + return primary->set_camera_information(camera_info); +} + +void AP_Camera::set_camera_information(uint8_t instance, mavlink_camera_information_t camera_info) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + + // call instance + backend->set_camera_information(camera_info); +} + +void AP_Camera::set_stream_information(mavlink_video_stream_information_t stream_info) +{ + WITH_SEMAPHORE(_rsem); + + if (primary == nullptr) { + return; + } + return primary->set_stream_information(stream_info); +} + +void AP_Camera::set_stream_information(uint8_t instance, mavlink_video_stream_information_t stream_info) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + + // call instance + backend->set_stream_information(stream_info); +} +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + // return backend for instance number AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const { diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index ee9f142cecbb92..a7b7f602ac43e2 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -8,6 +8,7 @@ #include #include +#include #include "AP_Camera_Params.h" #include "AP_Camera_shareddefs.h" @@ -86,22 +87,9 @@ class AP_Camera { // handle MAVLink command from GCS to control the camera MAV_RESULT handle_command(const mavlink_command_int_t &packet); - // send camera feedback message to GCS - void send_feedback(mavlink_channel_t chan); - - // send camera information message to GCS - void send_camera_information(mavlink_channel_t chan); - - // send camera settings message to GCS - void send_camera_settings(mavlink_channel_t chan); - -#if AP_CAMERA_SEND_FOV_STATUS_ENABLED - // send camera field of view status - void send_camera_fov_status(mavlink_channel_t chan); -#endif - - // send camera capture status message to GCS - void send_camera_capture_status(mavlink_channel_t chan); + // send a mavlink message; returns false if there was not space to + // send the message, true otherwise + bool send_mavlink_message(class GCS_MAVLINK &link, const enum ap_message id); // configure camera void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); @@ -193,8 +181,19 @@ class AP_Camera { // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in bool get_state(uint8_t instance, camera_state_t& cam_state); + + // change camera settings not normally used by autopilot + bool change_setting(uint8_t instance, CameraSetting setting, float value); #endif +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + void set_camera_information(mavlink_camera_information_t camera_info); + void set_camera_information(uint8_t instance, mavlink_camera_information_t camera_info); + + void set_stream_information(mavlink_video_stream_information_t camera_info); + void set_stream_information(uint8_t instance, mavlink_video_stream_information_t camera_info); +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + // Return true and the relay index if relay camera backend is selected, used for conversion to relay functions bool get_legacy_relay_index(int8_t &index) const; @@ -232,6 +231,32 @@ class AP_Camera { // perform any required parameter conversion void convert_params(); + // send camera feedback message to GCS + void send_feedback(mavlink_channel_t chan); + + // send camera information message to GCS + void send_camera_information(mavlink_channel_t chan); + +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + void send_video_stream_information(mavlink_channel_t chan); +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + + // send camera settings message to GCS + void send_camera_settings(mavlink_channel_t chan); + +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED + // send camera field of view status + void send_camera_fov_status(mavlink_channel_t chan); +#endif + + // send camera capture status message to GCS + void send_camera_capture_status(mavlink_channel_t chan); + +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(mavlink_channel_t chan); +#endif + HAL_Semaphore _rsem; // semaphore for multi-thread access AP_Camera_Backend *primary; // primary camera backed bool _is_in_auto_mode; // true if in AUTO mode diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index fafe4546aa2535..c2d5868c10acac 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -1,9 +1,13 @@ -#include "AP_Camera_Backend.h" +#include "AP_Camera_config.h" #if AP_CAMERA_ENABLED + +#include "AP_Camera_Backend.h" + #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -14,11 +18,22 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ _instance(instance) {} +void AP_Camera_Backend::init() +{ +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + _camera_info.focal_length = NaNf; + _camera_info.sensor_size_h = NaNf; + _camera_info.sensor_size_v = NaNf; + + _camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE; +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +} + // update - should be called at 50hz void AP_Camera_Backend::update() { // Check camera options and start/stop recording based on arm/disarm - if ((_params.options.get() & (uint8_t)Options::RecordWhileArmed) != 0) { + if (option_is_enabled(Option::RecordWhileArmed)) { if (hal.util->get_soft_armed() != last_is_armed) { last_is_armed = hal.util->get_soft_armed(); if (!record_video(last_is_armed)) { @@ -57,8 +72,10 @@ void AP_Camera_Backend::update() return; } - // check GPS status - if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) { + const AP_AHRS &ahrs = AP::ahrs(); + + Location current_loc; + if (!ahrs.get_location(current_loc)) { return; } @@ -68,15 +85,10 @@ void AP_Camera_Backend::update() } // check vehicle roll angle is less than configured maximum - const AP_AHRS &ahrs = AP::ahrs(); - if ((_frontend.get_roll_max() > 0) && (fabsf(AP::ahrs().roll_sensor * 1e-2f) > _frontend.get_roll_max())) { + if ((_frontend.get_roll_max() > 0) && (fabsf(ahrs.roll_sensor * 1e-2f) > _frontend.get_roll_max())) { return; } - // get current location. ignore failure because AHRS will provide its best guess - Location current_loc; - IGNORE_RETURN(ahrs.get_location(current_loc)); - // initialise last location to current location if (last_location.lat == 0 && last_location.lng == 0) { last_location = current_loc; @@ -211,44 +223,72 @@ void AP_Camera_Backend::send_camera_feedback(mavlink_channel_t chan) // send camera information message to GCS void AP_Camera_Backend::send_camera_information(mavlink_channel_t chan) const { - // prepare vendor, model and cam definition strings - const uint8_t vendor_name[32] {}; - const uint8_t model_name[32] {}; - const char cam_definition_uri[140] {}; - const uint32_t cap_flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE; - const float NaN = nanf("0x4152"); - - // send CAMERA_INFORMATION message - mavlink_msg_camera_information_send( - chan, - AP_HAL::millis(), // time_boot_ms - vendor_name, // vendor_name uint8_t[32] - model_name, // model_name uint8_t[32] - 0, // firmware version uint32_t - NaN, // focal_length float (mm) - NaN, // sensor_size_h float (mm) - NaN, // sensor_size_v float (mm) - 0, // resolution_h uint16_t (pix) - 0, // resolution_v uint16_t (pix) - 0, // lens_id, uint8_t - cap_flags, // flags uint32_t (CAMERA_CAP_FLAGS) - 0, // cam_definition_version uint16_t - cam_definition_uri, // cam_definition_uri char[140] - get_gimbal_device_id());// gimbal_device_id uint8_t + mavlink_camera_information_t camera_info; +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + + camera_info = _camera_info; + +#else + + memset(&camera_info, 0, sizeof(camera_info)); + + camera_info.focal_length = NaNf; + camera_info.sensor_size_h = NaNf; + camera_info.sensor_size_v = NaNf; + + camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE; + +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + + // Set fixed fields + // lens_id is populated with the instance number, to disambiguate multiple cameras + camera_info.lens_id = _instance; + camera_info.gimbal_device_id = get_gimbal_device_id(); + camera_info.time_boot_ms = AP_HAL::millis(); + + // Send CAMERA_INFORMATION message + mavlink_msg_camera_information_send_struct(chan, &camera_info); +} + +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +void AP_Camera_Backend::set_camera_information(mavlink_camera_information_t camera_info) +{ + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera %u CAMERA_INFORMATION (%s %s) set from script", _instance, camera_info.vendor_name, camera_info.model_name); + _camera_info = camera_info; +}; +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED +// send video stream information message to GCS +void AP_Camera_Backend::send_video_stream_information(mavlink_channel_t chan) const +{ +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + + // Send VIDEO_STREAM_INFORMATION message + mavlink_msg_video_stream_information_send_struct(chan, &_stream_info); + +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED } +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +void AP_Camera_Backend::set_stream_information(mavlink_video_stream_information_t stream_info) +{ + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera %u VIDEO_STREAM_INFORMATION (%s) set from script", _instance, stream_info.name); + _stream_info = stream_info; +}; +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED // send camera settings message to GCS void AP_Camera_Backend::send_camera_settings(mavlink_channel_t chan) const { - const float NaN = nanf("0x4152"); - // send CAMERA_SETTINGS message mavlink_msg_camera_settings_send( chan, AP_HAL::millis(), // time_boot_ms CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) - NaN, // zoomLevel float, percentage from 0 to 100, NaN if unknown - NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown + NaNf, // zoomLevel float, percentage from 0 to 100, NaN if unknown + NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown } #if AP_CAMERA_SEND_FOV_STATUS_ENABLED @@ -267,7 +307,6 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const return; } // send camera fov status message only if the last calculated values aren't stale - const float NaN = nanf("0x4152"); const float quat_array[4] = { quat.q1, quat.q2, @@ -279,13 +318,13 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const AP_HAL::millis(), loc.lat, loc.lng, - loc.alt, + loc.alt * 10, poi_loc.lat, poi_loc.lng, - poi_loc.alt, + poi_loc.alt * 10, quat_array, - horizontal_fov() > 0 ? horizontal_fov() : NaN, - vertical_fov() > 0 ? vertical_fov() : NaN + horizontal_fov() > 0 ? horizontal_fov() : NaNf, + vertical_fov() > 0 ? vertical_fov() : NaNf ); } #endif @@ -293,8 +332,6 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const // send camera capture status message to GCS void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const { - const float NaN = nanf("0x4152"); - // Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) const uint8_t image_status = (time_interval_settings.num_remaining > 0) ? 2 : 0; @@ -306,7 +343,7 @@ void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const 0, // current status of video capturing (0: idle, 1: capture in progress) static_cast(time_interval_settings.time_interval_ms) / 1000.0, // image capture interval (s) 0, // elapsed time since recording started (ms) - NaN, // available storage capacity (ms) + NaNf, // available storage capacity (ms) image_index); // total number of images captured } diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 41d383527ec4b5..7d52b6831f9a96 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -37,12 +37,15 @@ class AP_Camera_Backend CLASS_NO_COPY(AP_Camera_Backend); // camera options parameter values - enum class Options : int8_t { + enum class Option : uint8_t { RecordWhileArmed = (1 << 0U) }; + bool option_is_enabled(Option option) const { + return ((uint8_t)_params.options.get() & (uint8_t)option) != 0; + } // init - performs any required initialisation - virtual void init() {}; + virtual void init(); // update - should be called at 50hz virtual void update(); @@ -112,6 +115,16 @@ class AP_Camera_Backend // send camera information message to GCS virtual void send_camera_information(mavlink_channel_t chan) const; +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + // send video stream information message to GCS + virtual void send_video_stream_information(mavlink_channel_t chan) const; +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + void set_camera_information(mavlink_camera_information_t camera_info); + void set_stream_information(mavlink_video_stream_information_t stream_info); +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + // send camera settings message to GCS virtual void send_camera_settings(mavlink_channel_t chan) const; @@ -123,10 +136,18 @@ class AP_Camera_Backend // send camera capture status message to GCS virtual void send_camera_capture_status(mavlink_channel_t chan) const; +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + virtual void send_camera_thermal_range(mavlink_channel_t chan) const {}; +#endif + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in virtual bool get_state(AP_Camera::camera_state_t& cam_state) { return false; } + + // change camera settings not normally used by autopilot + virtual bool change_setting(CameraSetting setting, float value) { return false; } #endif protected: @@ -170,6 +191,11 @@ class AP_Camera_Backend // get mavlink gimbal device id which is normally mount_instance+1 uint8_t get_gimbal_device_id() const; +#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + mavlink_camera_information_t _camera_info; + mavlink_video_stream_information_t _stream_info; +#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED + // internal members uint8_t _instance; // this instance's number bool timer_installed; // true if feedback pin change detected using timer diff --git a/libraries/AP_Camera/AP_Camera_Logging.cpp b/libraries/AP_Camera/AP_Camera_Logging.cpp index 08da836d21217b..47cc4798952949 100644 --- a/libraries/AP_Camera/AP_Camera_Logging.cpp +++ b/libraries/AP_Camera/AP_Camera_Logging.cpp @@ -6,6 +6,7 @@ #include #include +#include // Write a Camera packet. Also writes a Mount packet if available void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us) diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index 7a1caa214fbb9d..a47816c70e1d01 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -141,7 +141,7 @@ void AP_Camera_MAVLinkCamV2::handle_message(mavlink_channel_t chan, const mavlin const uint8_t fw_ver_build = (_cam_info.firmware_version & 0xFF000000) >> 24; // display camera info to user - gcs().send_text(MAV_SEVERITY_INFO, "Camera: %s.32 %s.32 fw:%u.%u.%u.%u", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera: %.32s %.32s fw:%u.%u.%u.%u", _cam_info.vendor_name, _cam_info.model_name, (unsigned)fw_ver_major, diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index 29f07591165c8c..9599097d8ce1c1 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -109,4 +109,29 @@ void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const } } +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Camera_Mount::send_camera_thermal_range(mavlink_channel_t chan) const +{ +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + mount->send_camera_thermal_range(get_mount_instance(), chan); + } +#endif +} +#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + +#if AP_CAMERA_SCRIPTING_ENABLED +// change camera settings not normally used by autopilot +bool AP_Camera_Mount::change_setting(CameraSetting setting, float value) +{ + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->change_setting(get_mount_instance(), setting, value); + } + return false; +} +#endif + #endif // AP_CAMERA_MOUNT_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index d001cb979d3c9a..19e56ff3c078b1 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -69,6 +69,16 @@ class AP_Camera_Mount : public AP_Camera_Backend // send camera capture status message to GCS void send_camera_capture_status(mavlink_channel_t chan) const override; + +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(mavlink_channel_t chan) const override; +#endif + +#if AP_CAMERA_SCRIPTING_ENABLED + // change camera settings not normally used by autopilot + bool change_setting(CameraSetting setting, float value) override; +#endif }; #endif // AP_CAMERA_MOUNT_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index 7fb915082c991e..749d2985f0ab40 100644 --- a/libraries/AP_Camera/AP_Camera_Params.cpp +++ b/libraries/AP_Camera/AP_Camera_Params.cpp @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @Param: _TYPE // @DisplayName: Camera shutter (trigger) type // @Description: how to trigger the camera to take a picture - // @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting + // @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi/Topotek/Viewpro/Xacti), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp index 06ecf6ee3ae268..c2cb2d400a37fe 100644 --- a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp +++ b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp @@ -12,7 +12,7 @@ bool AP_Camera_SoloGimbal::trigger_pic() { if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Not Available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available"); return false; } @@ -21,21 +21,21 @@ bool AP_Camera_SoloGimbal::trigger_pic() if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) { // Trigger shutter start to take a photo - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Photo Trigger"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Photo Trigger"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start); } else if (gopro_capture_mode == GOPRO_CAPTURE_MODE_VIDEO) { if (gopro_is_recording) { // GoPro is recording, so stop recording - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Recording Stop"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Stop"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_stop); } else { // GoPro is not recording, so start recording - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Recording Start"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Start"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start); } } else { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode"); return false; } @@ -52,7 +52,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() uint8_t gopro_capture_mode_values[4] = { }; if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Not Available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available"); return; } @@ -60,12 +60,12 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() case GOPRO_CAPTURE_MODE_VIDEO: if (gopro_is_recording) { // GoPro is recording, cannot change modes - gcs().send_text(MAV_SEVERITY_INFO, "GoPro recording, can't change modes"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro recording, can't change modes"); } else { // Change to camera mode gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_PHOTO; mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values); - gcs().send_text(MAV_SEVERITY_INFO, "GoPro changing to mode photo"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode photo"); } break; @@ -74,7 +74,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() // Change to video mode gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_VIDEO; mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values); - gcs().send_text(MAV_SEVERITY_INFO, "GoPro changing to mode video"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode video"); break; } } diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index 83e5417e7c43e7..90f69ea7da44c8 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -49,3 +49,16 @@ #ifndef AP_CAMERA_SET_CAMERA_SOURCE_ENABLED #define AP_CAMERA_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED #endif + +// send thermal range is supported on a few thermal cameras but all are within mounts +#ifndef AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +#define AP_CAMERA_SEND_THERMAL_RANGE_ENABLED AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +#endif + +#ifndef HAL_RUNCAM_ENABLED +#define HAL_RUNCAM_ENABLED 1 +#endif + +#ifndef AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +#define AP_CAMERA_INFO_FROM_SCRIPT_ENABLED AP_CAMERA_SCRIPTING_ENABLED +#endif diff --git a/libraries/AP_Camera/AP_Camera_shareddefs.h b/libraries/AP_Camera/AP_Camera_shareddefs.h index 6543eff0bc8605..7579878c54b3c6 100644 --- a/libraries/AP_Camera/AP_Camera_shareddefs.h +++ b/libraries/AP_Camera/AP_Camera_shareddefs.h @@ -36,3 +36,9 @@ enum class TrackingType : uint8_t { TRK_RECTANGLE = 2 // tracking a rectangle }; +// camera settings not normally used by the autopilot +enum class CameraSetting { + THERMAL_PALETTE = 0, // set thermal palette + THERMAL_GAIN = 1, // set thermal gain, value of 0:low gain, 1:high gain + THERMAL_RAW_DATA = 2, // enable/disable thermal raw data +}; diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 86e7dee57c6af8..fadecee6d03098 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -451,10 +451,10 @@ void AP_RunCam::handle_in_menu(Event ev) // map rc input to an event AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const { - const RC_Channel::AuxSwitchPos throttle = rc().get_channel_pos(AP::rcmap()->throttle()); - const RC_Channel::AuxSwitchPos yaw = rc().get_channel_pos(AP::rcmap()->yaw()); - const RC_Channel::AuxSwitchPos roll = rc().get_channel_pos(AP::rcmap()->roll()); - const RC_Channel::AuxSwitchPos pitch = rc().get_channel_pos(AP::rcmap()->pitch()); + const RC_Channel::AuxSwitchPos throttle = rc().get_throttle_channel().get_aux_switch_pos(); + const RC_Channel::AuxSwitchPos yaw = rc().get_yaw_channel().get_aux_switch_pos(); + const RC_Channel::AuxSwitchPos roll = rc().get_roll_channel().get_aux_switch_pos(); + const RC_Channel::AuxSwitchPos pitch = rc().get_pitch_channel().get_aux_switch_pos(); Event result = Event::NONE; @@ -1024,13 +1024,13 @@ bool AP_RunCam::request_pending(uint32_t now) AP_RunCam::Request::Request(AP_RunCam* device, Command commandID, uint8_t param, uint32_t timeout, uint16_t maxRetryTimes, parse_func_t parserFunc) : _recv_buf(device->_recv_buf), - _command(commandID), - _max_retry_times(maxRetryTimes), - _timeout_ms(timeout), _device(device), + _command(commandID), _param(param), - _parser_func(parserFunc), _recv_response_length(0), + _timeout_ms(timeout), + _max_retry_times(maxRetryTimes), + _parser_func(parserFunc), _result(RequestStatus::PENDING) { _request_timestamp_ms = AP_HAL::millis(); diff --git a/libraries/AP_Camera/AP_RunCam.h b/libraries/AP_Camera/AP_RunCam.h index b689a8108e3818..9eb62999236644 100644 --- a/libraries/AP_Camera/AP_RunCam.h +++ b/libraries/AP_Camera/AP_RunCam.h @@ -21,17 +21,12 @@ */ #pragma once -#include - -#ifndef HAL_RUNCAM_ENABLED -#define HAL_RUNCAM_ENABLED 1 -#endif +#include "AP_Camera_config.h" #if HAL_RUNCAM_ENABLED #include #include -#include #include #include diff --git a/libraries/AP_Camera/examples/README.md b/libraries/AP_Camera/examples/README.md new file mode 100644 index 00000000000000..90a0fa2bae0ce6 --- /dev/null +++ b/libraries/AP_Camera/examples/README.md @@ -0,0 +1,106 @@ +# AP_Camera examples + + +## GStreamer examples + +The following examples demonstrate how to manipulate GStreamer pipelines to +capture and display video streams from a UDP or RTSP source. They are useful +for providing test images to camera algorithms, or forwarding streams from +simulators such as Gazebo to ground control stations. + +For further details see: + +- [GStreamer tutorials](https://gstreamer.freedesktop.org/documentation/tutorials/index.html?gi-language=c) + + +### Install dependencies + +#### Ubuntu + +```bash +sudo apt install libopencv-dev libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev gstreamer1.0-plugins-bad gstreamer1.0-libav gstreamer1.0-gl gstreamer1.0-tools gstreamer1.0-plugins-ugly libgstrtspserver-1.0-dev +``` + +#### macOS + +```bash +brew install gstreamer opencv +``` + +### `gst_rtsp_server.py` + +The example provides a number of test images as an RTSP stream that may be accessed at: + +- rtsp://127.0.0.1:8554/camera +- rtsp://127.0.0.1:8554/ball +- rtsp://127.0.0.1:8554/snow + + +Start the RTSP server: + +```bash +python ./gst_rtsp_server.py +``` + +Display the RTSP stream: + +```bash +gst-launch-1.0 rtspsrc location=rtsp://localhost:8554/camera latency=50 ! decodebin ! autovideosink +``` + +### `gst_rtsp_to_wx.py` + +The example displays an RTSP stream in a wxPython application. + +Start the RTSP server: + +```bash +python ./gst_rtsp_server.py +``` + +Display the RTSP stream in wxPython + +```bash +python ./gst_rtsp_to_wx.py +``` + +### `gst_udp_to_rtsp.py` + +Convert a UDP stream to RTSP. This example is configured to use the same UDP +pipeline provided by the ArduPilot Gazebo [`GstCameraPlugin`](https://github.com/ArduPilot/ardupilot_gazebo?tab=readme-ov-file#3-streaming-camera-video). By converting the +UDP stream to RTSP is may be consumed by multiple applications +(e.g. a camera tracking algorithm and a GCS). + +Create a UDP video stream + +```bash +gst-launch-1.0 -v videotestsrc ! 'video/x-raw,format=I420,width=640,height=480,framerate=50/1' ! queue ! videoconvert ! x264enc bitrate=800 speed-preset=6 tune=4 key-int-max=10 ! rtph264pay ! udpsink host=127.0.0.1 port=5600 +``` + +Convert to RTSP: + +```bash +python ./gst_udp_to_rtsp.py +``` + +Display the RTSP stream: + +```bash +gst-launch-1.0 rtspsrc location=rtsp://localhost:8554/camera latency=50 ! decodebin ! autovideosink +``` + +### `gst_udp_to_wx.py` + +The example displays a UDP video stream in a wxPython application. + +Create a UDP video stream: + +```bash +gst-launch-1.0 -v videotestsrc ! 'video/x-raw,format=I420,width=640,height=480,framerate=50/1' ! queue ! videoconvert ! x264enc bitrate=800 speed-preset=6 tune=4 key-int-max=10 ! rtph264pay ! udpsink host=127.0.0.1 port=5600 +``` + +Display the UDP video stream in wxPython: + +```bash +python ./gst_udp_to_wx.py +``` \ No newline at end of file diff --git a/libraries/AP_Camera/examples/gst_rtsp_server.py b/libraries/AP_Camera/examples/gst_rtsp_server.py new file mode 100644 index 00000000000000..2a451504de38b6 --- /dev/null +++ b/libraries/AP_Camera/examples/gst_rtsp_server.py @@ -0,0 +1,115 @@ +""" +GST RTSP Server Example + +Usage +----- + +1. Start the server: + +python ./gst_rtsp_server.py + +2. Display the RTSP stream + +gst-launch-1.0 rtspsrc location=rtsp://localhost:8554/camera latency=50 ! decodebin ! autovideosink + + +Acknowledgments +--------------- + +GStreamer RTSP server example adapted from code by Jerome Carretero (Tamaggo) + +https://github.com/tamaggo/gstreamer-examples +https://github.com/tamaggo/gstreamer-examples/blob/master/test_gst_rtsp_server.py +""" + +# Copyright (c) 2015 Tamaggo Inc. +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# + +import sys +import gi + +gi.require_version("Gst", "1.0") +gi.require_version("GstRtspServer", "1.0") +from gi.repository import Gst +from gi.repository import GstRtspServer +from gi.repository import GLib + + +class VideoTestMediaFactory(GstRtspServer.RTSPMediaFactory): + """ + Create a GStreamer pipeline for a videotestsrc source. + + The default videotestsrc uses the smpte test pattern. Other test patterns + may be specified when initialising the class. + """ + def __init__(self, pattern="smpte"): + GstRtspServer.RTSPMediaFactory.__init__(self) + self.pattern = pattern + + def do_create_element(self, url): + s_src = f"videotestsrc pattern={self.pattern} ! video/x-raw,rate=30,width=640,height=480,format=I420" + s_h264 = "x264enc tune=zerolatency" + pipeline_str = f"( {s_src} ! queue max-size-buffers=1 name=q_enc ! {s_h264} ! rtph264pay name=pay0 pt=96 )" + if len(sys.argv) > 1: + pipeline_str = " ".join(sys.argv[1:]) + print(pipeline_str) + return Gst.parse_launch(pipeline_str) + + +class GstServer: + """ + A GStreamer RTSP server streaming three different test patterns: + + rtsp://127.0.0.1:8554/camera + rtsp://127.0.0.1:8554/ball + rtsp://127.0.0.1:8554/snow + """ + def __init__(self): + self.server = GstRtspServer.RTSPServer() + self.server.set_address("127.0.0.1") + self.server.set_service("8554") + + media_factory1 = VideoTestMediaFactory() + media_factory1.set_shared(True) + + media_factory2 = VideoTestMediaFactory("ball") + media_factory2.set_shared(True) + + media_factory3 = VideoTestMediaFactory("snow") + media_factory3.set_shared(True) + + mount_points = self.server.get_mount_points() + mount_points.add_factory("/camera", media_factory1) + mount_points.add_factory("/ball", media_factory2) + mount_points.add_factory("/snow", media_factory3) + + self.server.attach(None) + + +def main(): + Gst.init(None) + server = GstServer() + loop = GLib.MainLoop() + loop.run() + + +if __name__ == "__main__": + main() diff --git a/libraries/AP_Camera/examples/gst_rtsp_to_wx.py b/libraries/AP_Camera/examples/gst_rtsp_to_wx.py new file mode 100755 index 00000000000000..795891a0598049 --- /dev/null +++ b/libraries/AP_Camera/examples/gst_rtsp_to_wx.py @@ -0,0 +1,233 @@ +"""" +Capture a RTSP video stream and display in wxpython + +Usage +----- + +1. rtsp server + +python ./gst_rtsp_server.py + +3. display in wxpython + +python ./gst_rtsp_to_wx.py + +Acknowledgments +--------------- + +Video class to capture GStreamer frames + https://www.ardusub.com/developers/opencv.html + +ImagePanel class to display openCV images in wxWidgets + https://stackoverflow.com/questions/14804741/opencv-integration-with-wxpython +""" + +import copy +import cv2 +import gi +import numpy as np +import threading +import wx + + +gi.require_version("Gst", "1.0") +from gi.repository import Gst + + +class VideoStream: + """BlueRov video capture class constructor - adapted to capture rtspsrc + + Attributes: + address (string): RTSP address + port (int): RTSP port + mount_point (string): video stream mount point + video_decode (string): Transform YUV (12bits) to BGR (24bits) + video_pipe (object): GStreamer top-level pipeline + video_sink (object): Gstreamer sink element + video_sink_conf (string): Sink configuration + video_source (string): Udp source ip and port + latest_frame (np.ndarray): Latest retrieved video frame + """ + + def __init__( + self, address="127.0.0.1", port=8554, mount_point="/camera", latency=50 + ): + Gst.init(None) + + self.address = address + self.port = port + self.mount_point = mount_point + self.latency = latency + + self.latest_frame = self._new_frame = None + + self.video_source = ( + f"rtspsrc location=rtsp://{address}:{port}{mount_point} latency={latency}" + ) + + # Python does not have nibble, convert YUV nibbles (4-4-4) to OpenCV standard BGR bytes (8-8-8) + self.video_decode = ( + "! decodebin ! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert" + ) + # Create a sink to get data + self.video_sink_conf = ( + "! appsink emit-signals=true sync=false max-buffers=2 drop=true" + ) + + self.video_pipe = None + self.video_sink = None + + self.run() + + def start_gst(self, config=None): + """ Start gstreamer pipeline and sink + Pipeline description list e.g: + [ + 'videotestsrc ! decodebin', \ + '! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert', + '! appsink' + ] + + Args: + config (list, optional): Gstreamer pileline description list + """ + + if not config: + config = [ + "videotestsrc ! decodebin", + "! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert", + "! appsink", + ] + + command = " ".join(config) + self.video_pipe = Gst.parse_launch(command) + self.video_pipe.set_state(Gst.State.PLAYING) + self.video_sink = self.video_pipe.get_by_name("appsink0") + + @staticmethod + def gst_to_opencv(sample): + """Transform byte array into np array + + Args: + sample (TYPE): Description + + Returns: + TYPE: Description + """ + buf = sample.get_buffer() + caps_structure = sample.get_caps().get_structure(0) + array = np.ndarray( + (caps_structure.get_value("height"), caps_structure.get_value("width"), 3), + buffer=buf.extract_dup(0, buf.get_size()), + dtype=np.uint8, + ) + return array + + def frame(self): + """Get Frame + + Returns: + np.ndarray: latest retrieved image frame + """ + if self.frame_available: + self.latest_frame = self._new_frame + # reset to indicate latest frame has been 'consumed' + self._new_frame = None + return self.latest_frame + + def frame_available(self): + """Check if a new frame is available + + Returns: + bool: true if a new frame is available + """ + return self._new_frame is not None + + def run(self): + """Get frame to update _new_frame""" + + self.start_gst( + [ + self.video_source, + self.video_decode, + self.video_sink_conf, + ] + ) + + self.video_sink.connect("new-sample", self.callback) + + def callback(self, sink): + sample = sink.emit("pull-sample") + self._new_frame = self.gst_to_opencv(sample) + + return Gst.FlowReturn.OK + + +class ImagePanel(wx.Panel): + def __init__(self, parent, video_stream, fps=30): + wx.Panel.__init__(self, parent) + + self._video_stream = video_stream + + # Shared between threads + self._frame_lock = threading.Lock() + self._latest_frame = None + + print("Waiting for video stream...") + waited = 0 + while not self._video_stream.frame_available(): + waited += 1 + print("\r Frame not available (x{})".format(waited), end="") + cv2.waitKey(30) + print("\nSuccess! Video stream available") + + if self._video_stream.frame_available(): + # Only retrieve and display a frame if it's new + frame = copy.deepcopy(self._video_stream.frame()) + + # Frame size + height, width, _ = frame.shape + + parent.SetSize((width, height)) + frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB) + + self.bmp = wx.Bitmap.FromBuffer(width, height, frame) + + self.timer = wx.Timer(self) + self.timer.Start(int(1000 / fps)) + + self.Bind(wx.EVT_PAINT, self.OnPaint) + self.Bind(wx.EVT_TIMER, self.NextFrame) + + def OnPaint(self, evt): + dc = wx.BufferedPaintDC(self) + dc.DrawBitmap(self.bmp, 0, 0) + + def NextFrame(self, event): + if self._video_stream.frame_available(): + frame = copy.deepcopy(self._video_stream.frame()) + + # Convert frame to bitmap for wxFrame + frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB) + self.bmp.CopyFromBuffer(frame) + self.Refresh() + + +def main(): + + # create the video stream + video_stream = VideoStream(mount_point="/camera") + + # app must run on the main thread + app = wx.App() + wx_frame = wx.Frame(None) + + # create the image panel + image_panel = ImagePanel(wx_frame, video_stream, fps=30) + + wx_frame.Show() + app.MainLoop() + + +if __name__ == "__main__": + main() diff --git a/libraries/AP_Camera/examples/gst_udp_to_rtsp.py b/libraries/AP_Camera/examples/gst_udp_to_rtsp.py new file mode 100644 index 00000000000000..282971439e2777 --- /dev/null +++ b/libraries/AP_Camera/examples/gst_udp_to_rtsp.py @@ -0,0 +1,132 @@ +""" +Capture a UDP video stream and pipe to an GStreamer RTSP server + +The Gazebo GStreamerPlugin with 1 +has elements: + +source: appsrc + caps='video/x-raw, format=I420, width=640, height=480, framerate=50' + is-live=1 + do-timestamp=1 + stream-type=0 +queue: queue +converter: videoconvert +encoder: x264enc bitrate=800 speed-preset=6 tune=4 key-int-max=10 +payloader: rtph264pay +sink: udpsink host=127.0.0.1 port=5600 + + +A udpsink example streaming a test pattern using the same settings as the basic +pipeline in the Gazebo GstCameraPlugin. + +1. udpsink + +gst-launch-1.0 -v videotestsrc ! 'video/x-raw,format=I420,width=640,height=480,framerate=50/1' ! queue ! videoconvert ! x264enc bitrate=800 speed-preset=6 tune=4 key-int-max=10 ! rtph264pay ! udpsink host=127.0.0.1 port=5600 + +2a. Display the udpsink directly + +udpsrc + +gst-launch-1.0 -v udpsrc address=127.0.0.1 port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! videoconvert ! autovideosink sync=false + +2b. Or run the udpsink, this script to convert to RTSP, and view the RTSP stream: + +python ./gst_udp_to_rtsp.py + +3. rtspsrc + +gst-launch-1.0 rtspsrc location=rtsp://localhost:8554/camera latency=50 ! decodebin ! autovideosink + + +Acknowledgments +--------------- + +GStreamer RTSP server example adapted from code by Jerome Carretero (Tamaggo) + +https://github.com/tamaggo/gstreamer-examples +https://github.com/tamaggo/gstreamer-examples/blob/master/test_gst_rtsp_server.py +""" + +# Copyright (c) 2015 Tamaggo Inc. +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# + +import gi + +gi.require_version("Gst", "1.0") +gi.require_version("GstRtspServer", "1.0") +from gi.repository import Gst +from gi.repository import GstRtspServer +from gi.repository import GLib + + +class GstUdpMediaFactory(GstRtspServer.RTSPMediaFactory): + """ + Create a GStreamer pipeline for a udpsrc source. + """ + + def __init__(self, address="127.0.0.1", port="5600"): + GstRtspServer.RTSPMediaFactory.__init__(self) + + # udpsrc options + self.address = address + self.port = port + + def do_create_element(self, url): + source = f"udpsrc address={self.address} port={self.port}" + + codec = "application/x-rtp, payload=96 ! rtph264depay ! h264parse ! avdec_h264" + + s_h264 = "x264enc tune=zerolatency" + pipeline_str = f"( {source} ! {codec} ! queue max-size-buffers=1 name=q_enc ! {s_h264} ! rtph264pay name=pay0 pt=96 )" + print(pipeline_str) + return Gst.parse_launch(pipeline_str) + + +class GstServer: + """ + A GStreamer RTSP server streaming a udpsrc to: + + rtsp://127.0.0.1:8554/camera + """ + + def __init__(self): + self.server = GstRtspServer.RTSPServer() + self.server.set_address("127.0.0.1") + self.server.set_service("8554") + + media_factory = GstUdpMediaFactory(address="127.0.0.1", port="5600") + media_factory.set_shared(True) + + mount_points = self.server.get_mount_points() + mount_points.add_factory("/camera", media_factory) + + self.server.attach(None) + + +def main(): + Gst.init(None) + server = GstServer() + loop = GLib.MainLoop() + loop.run() + + +if __name__ == "__main__": + main() diff --git a/libraries/AP_Camera/examples/gst_udp_to_wx.py b/libraries/AP_Camera/examples/gst_udp_to_wx.py new file mode 100755 index 00000000000000..54faad5b8327f9 --- /dev/null +++ b/libraries/AP_Camera/examples/gst_udp_to_wx.py @@ -0,0 +1,237 @@ +"""" +Capture a UDP video stream and display in wxpython + +Usage +----- + +1. udpsink + +gst-launch-1.0 -v videotestsrc ! 'video/x-raw,format=I420,width=640,height=480,framerate=50/1' ! queue ! videoconvert ! x264enc bitrate=800 speed-preset=6 tune=4 key-int-max=10 ! rtph264pay ! udpsink host=127.0.0.1 port=5600 + +2. display in wxpython + +python ./gst_udp_to_wx.py + +Acknowledgments +--------------- + +Video class to capture GStreamer frames + https://www.ardusub.com/developers/opencv.html + +ImagePanel class to display openCV images in wxWidgets + https://stackoverflow.com/questions/14804741/opencv-integration-with-wxpython +""" + +import copy +import cv2 +import gi +import numpy as np +import threading +import wx + + +gi.require_version("Gst", "1.0") +from gi.repository import Gst + + +class VideoStream: + """BlueRov video capture class constructor + + Attributes: + port (int): Video UDP port + video_codec (string): Source h264 parser + video_decode (string): Transform YUV (12bits) to BGR (24bits) + video_pipe (object): GStreamer top-level pipeline + video_sink (object): Gstreamer sink element + video_sink_conf (string): Sink configuration + video_source (string): Udp source ip and port + latest_frame (np.ndarray): Latest retrieved video frame + """ + + def __init__(self, port=5600): + """Summary + + Args: + port (int, optional): UDP port + """ + + Gst.init(None) + + self.port = port + self.latest_frame = self._new_frame = None + + # [Software component diagram](https://www.ardusub.com/software/components.html) + # UDP video stream (:5600) + self.video_source = "udpsrc port={}".format(self.port) + # [Rasp raw image](http://picamera.readthedocs.io/en/release-0.7/recipes2.html#raw-image-capture-yuv-format) + # Cam -> CSI-2 -> H264 Raw (YUV 4-4-4 (12bits) I420) + self.video_codec = ( + "! application/x-rtp, payload=96 ! rtph264depay ! h264parse ! avdec_h264" + ) + # Python don't have nibble, convert YUV nibbles (4-4-4) to OpenCV standard BGR bytes (8-8-8) + self.video_decode = ( + "! decodebin ! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert" + ) + # Create a sink to get data + self.video_sink_conf = ( + "! appsink emit-signals=true sync=false max-buffers=2 drop=true" + ) + + self.video_pipe = None + self.video_sink = None + + self.run() + + def start_gst(self, config=None): + """ Start gstreamer pipeline and sink + Pipeline description list e.g: + [ + 'videotestsrc ! decodebin', \ + '! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert', + '! appsink' + ] + + Args: + config (list, optional): Gstreamer pileline description list + """ + + if not config: + config = [ + "videotestsrc ! decodebin", + "! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert", + "! appsink", + ] + + command = " ".join(config) + self.video_pipe = Gst.parse_launch(command) + self.video_pipe.set_state(Gst.State.PLAYING) + self.video_sink = self.video_pipe.get_by_name("appsink0") + + @staticmethod + def gst_to_opencv(sample): + """Transform byte array into np array + + Args: + sample (TYPE): Description + + Returns: + TYPE: Description + """ + buf = sample.get_buffer() + caps_structure = sample.get_caps().get_structure(0) + array = np.ndarray( + (caps_structure.get_value("height"), caps_structure.get_value("width"), 3), + buffer=buf.extract_dup(0, buf.get_size()), + dtype=np.uint8, + ) + return array + + def frame(self): + """Get Frame + + Returns: + np.ndarray: latest retrieved image frame + """ + if self.frame_available: + self.latest_frame = self._new_frame + # reset to indicate latest frame has been 'consumed' + self._new_frame = None + return self.latest_frame + + def frame_available(self): + """Check if a new frame is available + + Returns: + bool: true if a new frame is available + """ + return self._new_frame is not None + + def run(self): + """Get frame to update _new_frame""" + + self.start_gst( + [ + self.video_source, + self.video_codec, + self.video_decode, + self.video_sink_conf, + ] + ) + + self.video_sink.connect("new-sample", self.callback) + + def callback(self, sink): + sample = sink.emit("pull-sample") + self._new_frame = self.gst_to_opencv(sample) + + return Gst.FlowReturn.OK + + +class ImagePanel(wx.Panel): + def __init__(self, parent, video_stream, fps=30): + wx.Panel.__init__(self, parent) + + self._video_stream = video_stream + + # Shared between threads + self._frame_lock = threading.Lock() + self._latest_frame = None + + print("Waiting for video stream...") + waited = 0 + while not self._video_stream.frame_available(): + waited += 1 + print("\r Frame not available (x{})".format(waited), end="") + cv2.waitKey(30) + print("\nSuccess! Video stream available") + + if self._video_stream.frame_available(): + # Only retrieve and display a frame if it's new + frame = copy.deepcopy(self._video_stream.frame()) + + # Frame size + height, width, _ = frame.shape + + parent.SetSize((width, height)) + frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB) + + self.bmp = wx.Bitmap.FromBuffer(width, height, frame) + + self.timer = wx.Timer(self) + self.timer.Start(int(1000 / fps)) + + self.Bind(wx.EVT_PAINT, self.OnPaint) + self.Bind(wx.EVT_TIMER, self.NextFrame) + + def OnPaint(self, evt): + dc = wx.BufferedPaintDC(self) + dc.DrawBitmap(self.bmp, 0, 0) + + def NextFrame(self, event): + if self._video_stream.frame_available(): + frame = copy.deepcopy(self._video_stream.frame()) + + # Convert frame to bitmap for wxFrame + frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB) + self.bmp.CopyFromBuffer(frame) + self.Refresh() + + +def main(): + + # create the video stream + video_stream = VideoStream(port=5600) + + # app must run on the main thread + app = wx.App() + wx_frame = wx.Frame(None) + + # create the image panel + image_panel = ImagePanel(wx_frame, video_stream, fps=30) + + wx_frame.Show() + app.MainLoop() + + +if __name__ == "__main__": + main() diff --git a/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp b/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp index 0357c42e728d5e..8668e88c96b0e0 100644 --- a/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp +++ b/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp @@ -77,7 +77,7 @@ static bool empty_1k(const uint8_t *data) AP_CheckFirmware::bl_data *AP_CheckFirmware::read_bootloader(void) { #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - struct bl_data *bld = new bl_data; + struct bl_data *bld = NEW_NOTHROW bl_data; if (bld == nullptr) { return nullptr; } @@ -95,7 +95,7 @@ AP_CheckFirmware::bl_data *AP_CheckFirmware::read_bootloader(void) } bld->length1 += block_size; } - bld->data1 = new uint8_t[bld->length1]; + bld->data1 = NEW_NOTHROW uint8_t[bld->length1]; if (bld->data1 == nullptr) { delete bld; return nullptr; @@ -118,7 +118,7 @@ AP_CheckFirmware::bl_data *AP_CheckFirmware::read_bootloader(void) if (num_blocks > 0) { // we have persistent data to save bld->length2 = num_blocks * block_size; - bld->data2 = new uint8_t[bld->length2]; + bld->data2 = NEW_NOTHROW uint8_t[bld->length2]; if (bld->data2 == nullptr) { delete bld; return nullptr; @@ -365,7 +365,7 @@ void AP_CheckFirmware::handle_secure_command(mavlink_channel_t chan, const mavli reply.result = MAV_RESULT_FAILED; goto send_reply; } - uint8_t *data = new uint8_t[num_keys*AP_PUBLIC_KEY_LEN]; + uint8_t *data = NEW_NOTHROW uint8_t[num_keys*AP_PUBLIC_KEY_LEN]; if (data == nullptr) { reply.result = MAV_RESULT_FAILED; goto send_reply; diff --git a/libraries/AP_Common/AP_Common.cpp b/libraries/AP_Common/AP_Common.cpp index 19f2002ac41214..8acdc2a76acb85 100644 --- a/libraries/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/AP_Common.cpp @@ -93,14 +93,16 @@ size_t strncpy_noterm(char *dest, const char *src, size_t n) * return the numeric value of an ascii hex character * * @param[in] a Hexadecimal character - * @return Returns a binary value + * @return Returns a binary value. If 'a' is not a valid hex character 255 (AKA -1) is returned */ -int16_t char_to_hex(char a) +uint8_t char_to_hex(char a) { - if (a >= 'A' && a <= 'F') + if (a >= 'A' && a <= 'F') { return a - 'A' + 10; - else if (a >= 'a' && a <= 'f') + } else if (a >= 'a' && a <= 'f') { return a - 'a' + 10; - else + } else if (a >= '0' && a <= '9') { return a - '0'; + } + return 255; } diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index 65a5648ad66aa4..177a24c0fce7ad 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -23,6 +23,7 @@ #include #include #include +#include // used to pack structures #define PACKED __attribute__((__packed__)) @@ -168,7 +169,7 @@ bool hex_to_uint8(uint8_t a, uint8_t &res); // return the uint8 value of an asc size_t strncpy_noterm(char *dest, const char *src, size_t n); // return the numeric value of an ascii hex character -int16_t char_to_hex(char a); +uint8_t char_to_hex(char a); /* Bit manipulation @@ -184,3 +185,10 @@ template void BIT_CLEAR (T& value, uint8_t bitnumber) noexcept { ((value) &= ~((T)(1U) << (bitnumber))); } +/* + See the comments in libraries/AP_Common/c++.cpp + */ +#ifndef NEW_NOTHROW +#define NEW_NOTHROW new(std::nothrow) +#endif + diff --git a/libraries/AP_Common/AP_ExpandingArray.cpp b/libraries/AP_Common/AP_ExpandingArray.cpp index b5327c6f91f7be..99b95896c77387 100644 --- a/libraries/AP_Common/AP_ExpandingArray.cpp +++ b/libraries/AP_Common/AP_ExpandingArray.cpp @@ -16,6 +16,8 @@ #include "AP_ExpandingArray.h" #include +#ifndef HAL_BOOTLOADER_BUILD + extern const AP_HAL::HAL& hal; AP_ExpandingArrayGeneric::~AP_ExpandingArrayGeneric(void) @@ -75,3 +77,5 @@ bool AP_ExpandingArrayGeneric::expand_to_hold(uint16_t num_items) uint16_t chunks_required = ((num_items - max_items()) / chunk_size) + 1; return expand(chunks_required); } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/Bitmask.h b/libraries/AP_Common/Bitmask.h index 233d1b3e26f69c..ed4443d294353e 100644 --- a/libraries/AP_Common/Bitmask.h +++ b/libraries/AP_Common/Bitmask.h @@ -23,26 +23,28 @@ #include -template +template class Bitmask { + static constexpr uint16_t NUMWORDS = ((NUMBITS+31)/32); + + static_assert(NUMBITS > 0, "must store something"); + // for first_set()'s return value + static_assert(NUMBITS <= INT16_MAX, "must fit in int16_t"); + // so that 1U << bits is in range + static_assert(sizeof(unsigned int) >= sizeof(uint32_t), "int too small"); + public: - Bitmask() : - numbits(num_bits), - numwords((num_bits+31)/32) { + Bitmask() { clearall(); } Bitmask &operator=(const Bitmask&other) { - memcpy(bits, other.bits, sizeof(bits[0])*other.numwords); + memcpy(bits, other.bits, sizeof(bits[0])*NUMWORDS); return *this; } bool operator==(const Bitmask&other) { - if (other.numbits != numbits) { - return false; - } else { - return memcmp(bits, other.bits, sizeof(bits[0])*numwords) == 0; - } + return memcmp(bits, other.bits, sizeof(bits[0])*NUMWORDS) == 0; } bool operator!=(const Bitmask&other) { @@ -53,10 +55,8 @@ class Bitmask { // set given bitnumber void set(uint16_t bit) { - // ignore an invalid bit number - if (bit >= numbits) { - INTERNAL_ERROR(AP_InternalError::error_t::bitmask_range); - return; + if (!validate(bit)) { + return; // ignore access of invalid bit } uint16_t word = bit/32; uint8_t ofs = bit & 0x1f; @@ -65,17 +65,22 @@ class Bitmask { // set all bits void setall(void) { - // set all words to 111... except the last one. - for (uint16_t i=0; i= numbits) { - INTERNAL_ERROR(AP_InternalError::error_t::bitmask_range); - return false; - } -#endif return (bits[word] & (1U << ofs)) != 0; } // return true if all bits are clear bool empty(void) const { - for (uint16_t i=0; i= NUMBITS) { + INTERNAL_ERROR(AP_InternalError::error_t::bitmask_range); + return false; + } + return true; + } + + uint32_t bits[NUMWORDS]; }; diff --git a/libraries/AP_Common/ExpandingString.cpp b/libraries/AP_Common/ExpandingString.cpp index 31420d95fe0559..a3e7a8b4019580 100644 --- a/libraries/AP_Common/ExpandingString.cpp +++ b/libraries/AP_Common/ExpandingString.cpp @@ -17,13 +17,21 @@ */ #include "ExpandingString.h" - #include +#ifndef HAL_BOOTLOADER_BUILD + extern const AP_HAL::HAL& hal; #define EXPAND_INCREMENT 512 +ExpandingString::ExpandingString(char* s, uint32_t total_len) : buf(0) +{ + set_buffer(s, total_len, 0); + memset(buf, 0, buflen); +} + + /* expand the string buffer */ @@ -127,3 +135,5 @@ void ExpandingString::set_buffer(char *s, uint32_t total_len, uint32_t used_len) allocation_failed = false; external_buffer = true; } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/ExpandingString.h b/libraries/AP_Common/ExpandingString.h index 2561332f3e89d8..d92882e1b3af6f 100644 --- a/libraries/AP_Common/ExpandingString.h +++ b/libraries/AP_Common/ExpandingString.h @@ -24,6 +24,8 @@ class ExpandingString { public: + ExpandingString() : buf(0), buflen(0), used(0), allocation_failed(false), external_buffer(false) {} + ExpandingString(char* s, uint32_t total_len); const char *get_string(void) const { return buf; diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index e1a1ec578c51d3..dc08944af3d3e0 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -4,15 +4,11 @@ #include "Location.h" +#ifndef HAL_BOOTLOADER_BUILD + #include #include -/// constructors -Location::Location() -{ - zero(); -} - const Location definitely_zero{}; bool Location::is_zero(void) const { @@ -209,9 +205,21 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const } return false; // LCOV_EXCL_LINE - not reachable } +bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const +{ + int32_t ret_alt_cm; + if (!get_alt_cm(desired_frame, ret_alt_cm)) { + return false; + } + ret_alt = ret_alt_cm * 0.01; + return true; +} #if AP_AHRS_ENABLED -bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const +// converts location to a vector from origin; if this method returns +// false then vec_ne is unmodified +template +bool Location::get_vector_xy_from_origin_NE(T &vec_ne) const { Location ekf_origin; if (!AP::ahrs().get_origin(ekf_origin)) { @@ -222,22 +230,39 @@ bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const return true; } -bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const -{ - // convert lat, lon - if (!get_vector_xy_from_origin_NE(vec_neu.xy())) { - return false; - } +// define for float and position vectors +template bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const; +#if HAL_WITH_POSTYPE_DOUBLE +template bool Location::get_vector_xy_from_origin_NE(Vector2p &vec_ne) const; +#endif +// converts location to a vector from origin; if this method returns +// false then vec_neu is unmodified +template +bool Location::get_vector_from_origin_NEU(T &vec_neu) const +{ // convert altitude int32_t alt_above_origin_cm = 0; if (!get_alt_cm(AltFrame::ABOVE_ORIGIN, alt_above_origin_cm)) { return false; } + + // convert lat, lon + if (!get_vector_xy_from_origin_NE(vec_neu.xy())) { + return false; + } + vec_neu.z = alt_above_origin_cm; return true; } + +// define for float and position vectors +template bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const; +#if HAL_WITH_POSTYPE_DOUBLE +template bool Location::get_vector_from_origin_NEU(Vector3p &vec_neu) const; +#endif + #endif // AP_AHRS_ENABLED // return horizontal distance in meters between two locations @@ -285,6 +310,19 @@ Vector3d Location::get_distance_NED_double(const Location &loc2) const (alt - loc2.alt) * 0.01); } +// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2 considering alt frame, if altitude cannot be resolved down distance is 0 +Vector3f Location::get_distance_NED_alt_frame(const Location &loc2) const +{ + int32_t alt1, alt2 = 0; + if (!get_alt_cm(AltFrame::ABSOLUTE, alt1) || !loc2.get_alt_cm(AltFrame::ABSOLUTE, alt2)) { + // one or both of the altitudes are invalid, don't do alt distance calc + alt1 = 0, alt2 = 0; + } + return Vector3f((loc2.lat - lat) * LOCATION_SCALING_FACTOR, + diff_longitude(loc2.lng,lng) * LOCATION_SCALING_FACTOR * longitude_scale((loc2.lat+lat)/2), + (alt1 - alt2) * 0.01); +} + Vector2d Location::get_distance_NE_double(const Location &loc2) const { return Vector2d((loc2.lat - lat) * double(LOCATION_SCALING_FACTOR), @@ -505,3 +543,5 @@ void Location::linearly_interpolate_alt(const Location &point1, const Location & // new target's distance along the original track and then linear interpolate between the original origin and destination altitudes set_alt_cm(point1.alt + (point2.alt - point1.alt) * constrain_float(line_path_proportion(point1, point2), 0.0f, 1.0f), point2.get_alt_frame()); } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index eab834e2d427f3..72558024a0a876 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -28,13 +28,17 @@ class Location }; /// constructors - Location(); + Location() { zero(); } Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame); Location(const Vector3f &ekf_offset_neu, AltFrame frame); Location(const Vector3d &ekf_offset_neu, AltFrame frame); // set altitude void set_alt_cm(int32_t alt_cm, AltFrame frame); + // set_alt_m - set altitude in metres + void set_alt_m(float alt_m, AltFrame frame) { + set_alt_cm(alt_m*100, 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: @@ -42,6 +46,8 @@ class Location // - 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; + // same as get_alt_cm but in metres: + bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED; // get altitude frame AltFrame get_alt_frame() const; @@ -53,12 +59,17 @@ class Location // - 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) - // return false on failure to get the vector which can only - // happen if the EKF origin has not been set yet - // x, y and z are in centimetres - 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; + // get position as a vector (in cm) from origin (x,y only or + // x,y,z) return false on failure to get the vector which can only + // happen if the EKF origin has not been set yet x, y and z are in + // centimetres. If this method returns false then vec_ne is + // unmodified. + template + bool get_vector_xy_from_origin_NE(T &vec_ne) const WARN_IF_UNUSED; + // converts location to a vector from origin; if this method returns + // false then vec_neu is unmodified + template + bool get_vector_from_origin_NEU(T &vec_neu) const WARN_IF_UNUSED; // return horizontal distance in meters between two locations ftype get_distance(const Location &loc2) const; @@ -71,6 +82,9 @@ class Location Vector3f get_distance_NED(const Location &loc2) const; Vector3d get_distance_NED_double(const Location &loc2) const; + // return the distance in meters in North/East/Down plane as a N/E/D vector to loc2 considering alt frame, if altitude cannot be resolved down distance is 0 + Vector3f get_distance_NED_alt_frame(const Location &loc2) const; + // return the distance in meters in North/East plane as a N/E vector to loc2 Vector2f get_distance_NE(const Location &loc2) const; Vector2d get_distance_NE_double(const Location &loc2) const; diff --git a/libraries/AP_Common/MultiHeap.cpp b/libraries/AP_Common/MultiHeap.cpp deleted file mode 100644 index 75033db1a156c6..00000000000000 --- a/libraries/AP_Common/MultiHeap.cpp +++ /dev/null @@ -1,143 +0,0 @@ -/* - multiple heap interface, allowing for an allocator that uses - multiple underlying heaps to cope with multiple memory regions on - STM32 boards - */ - -#include -#include -#include - -#include "MultiHeap.h" - -/* - on ChibiOS allow up to 4 heaps. On other HALs only allow a single - heap. This is needed as hal.util->heap_realloc() needs to have the - property that heap_realloc(heap, ptr, 0) must not care if ptr comes - from the given heap. This is true on ChibiOS, but is not true on - other HALs - */ -#ifndef MAX_HEAPS -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#define MAX_HEAPS 4 -#else -#define MAX_HEAPS 1 -#endif -#endif - -extern const AP_HAL::HAL &hal; - -/* - create heaps with a total memory size, splitting over at most - max_heaps - */ -bool MultiHeap::create(uint32_t total_size, uint8_t max_heaps) -{ - max_heaps = MIN(MAX_HEAPS, max_heaps); - if (heaps != nullptr) { - // don't allow double allocation - return false; - } - heaps = new void*[max_heaps]; - if (heaps == nullptr) { - return false; - } - num_heaps = max_heaps; - for (uint8_t i=0; i 0) { - heaps[i] = hal.util->allocate_heap_memory(alloc_size); - if (heaps[i] != nullptr) { - total_size -= alloc_size; - break; - } - alloc_size *= 0.9; - } - if (total_size == 0) { - break; - } - } - if (total_size != 0) { - destroy(); - return false; - } - return true; -} - -// destroy heap -void MultiHeap::destroy(void) -{ - if (!available()) { - return; - } - for (uint8_t i=0; iheap_realloc(heaps[i], nullptr, 0, size); - if (newptr != nullptr) { - return newptr; - } - } - return nullptr; -} - -/* - free memory from a heap - */ -void MultiHeap::deallocate(void *ptr) -{ - if (!available()) { - return; - } - // NOTE! this relies on either there being a single heap or heap_realloc() - // not using the first argument when size is zero. - hal.util->heap_realloc(heaps[0], ptr, 0, 0); -} - -/* - change size of an allocation - */ -void *MultiHeap::change_size(void *ptr, uint32_t old_size, uint32_t new_size) -{ - if (new_size == 0) { - deallocate(ptr); - return nullptr; - } - if (old_size == 0 || ptr == nullptr) { - return allocate(new_size); - } - /* - we cannot know which heap this came from, so we rely on the fact - that on ChibiOS the underlying call doesn't use the heap - argument and on other HALs we only have one heap. We pass - through old_size and new_size so that we can validate the lua - old_size value - */ - return hal.util->heap_realloc(heaps[0], ptr, old_size, new_size); -} diff --git a/libraries/AP_Common/MultiHeap.h b/libraries/AP_Common/MultiHeap.h deleted file mode 100644 index e7aaff15b65394..00000000000000 --- a/libraries/AP_Common/MultiHeap.h +++ /dev/null @@ -1,29 +0,0 @@ -/* - multiple heap interface, allowing for an allocator that uses - multiple underlying heaps to cope with multiple memory regions on - STM32 boards - */ - -class MultiHeap { -public: - /* - allocate/deallocate heaps - */ - bool create(uint32_t total_size, uint8_t max_heaps); - void destroy(void); - - // return true if the heap is available for operations - bool available(void) const; - - // allocate memory within heaps - void *allocate(uint32_t size); - void deallocate(void *ptr); - - // change allocated size of a pointer - this requires the old - // size, unlike realloc() - void *change_size(void *ptr, uint32_t old_size, uint32_t new_size); - -private: - uint8_t num_heaps; - void **heaps; -}; diff --git a/libraries/AP_Common/c++.cpp b/libraries/AP_Common/c++.cpp index b9804818e85cbc..e51294647b4ef2 100644 --- a/libraries/AP_Common/c++.cpp +++ b/libraries/AP_Common/c++.cpp @@ -1,17 +1,43 @@ -// -// C++ runtime support not provided by Arduino -// -// Note: use new/delete with caution. The heap is small and -// easily fragmented. +/* + wrapper around new for C++ to ensure we always get zero filled memory + */ #include #include +#include +#include /* globally override new and delete to ensure that we always start with zero memory. This ensures consistent behaviour. + + Note that new comes in multiple different variants. When new is used + without std::nothrow the compiler is free to assume it will not fail + as it assumes exceptions are enabled. This makes code like this + unsafe when using -fno-exceptions: + + a = new b; + if (a == nullptr) { + handle_error() + } + + the compiler may remove the error handling. With g++ you can use + -fcheck-new to avoid this, but on clang++ the compiler accepts + -fcheck-new as a valid flag, but doesn't implement it, and may elide + the error checking. That makes using clang++ unsafe with + -fno-exceptions if you ever call new without std::nothrow. + + To avoid this we define NEW_NOTHROW as new(std::nothrow) and use it + everywhere in ArduPilot, then we catch any missing cases with both + an internal error and with a check of the elf for the symbols we + want to avoid +*/ + +/* + variant for new(std::nothrow), which is all that should be used in + ArduPilot */ -void * operator new(size_t size) +void * operator new(size_t size, std::nothrow_t const ¬hrow) { if (size < 1) { size = 1; @@ -19,11 +45,27 @@ void * operator new(size_t size) return(calloc(size, 1)); } -void operator delete(void *p) +void * operator new[](size_t size, std::nothrow_t const ¬hrow) { - if (p) free(p); + if (size < 1) { + size = 1; + } + return(calloc(size, 1)); } +/* + These variants are for new without std::nothrow. We don't want to ever + use this from ArduPilot code + */ +void * operator new(size_t size) +{ + if (size < 1) { + size = 1; + } + return(calloc(size, 1)); +} + + void * operator new[](size_t size) { if (size < 1) { @@ -32,7 +74,59 @@ void * operator new[](size_t size) return(calloc(size, 1)); } +void operator delete(void *p) +{ + if (p) free(p); +} + void operator delete[](void * ptr) { if (ptr) free(ptr); } + +#if defined(CYGWIN_BUILD) && CONFIG_HAL_BOARD == HAL_BOARD_SITL +/* + wrapper around malloc to ensure all memory is initialised as zero + cygwin needs to wrap _malloc_r + */ +#undef _malloc_r +extern "C" { + void *__wrap__malloc_r(_reent *r, size_t size); + void *__real__malloc_r(_reent *r, size_t size); + void *_malloc_r(_reent *r, size_t size); +} +void *__wrap__malloc_r(_reent *r, size_t size) +{ + void *ret = __real__malloc_r(r, size); + if (ret != nullptr) { + memset(ret, 0, size); + } + return ret; +} +void *_malloc_r(_reent *x, size_t size) +{ + void *ret = __real__malloc_r(x, size); + if (ret != nullptr) { + memset(ret, 0, size); + } + return ret; +} + +#elif CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS && CONFIG_HAL_BOARD != HAL_BOARD_QURT +/* + wrapper around malloc to ensure all memory is initialised as zero + ChibiOS and QURT have their own wrappers + */ +extern "C" { + void *__wrap_malloc(size_t size); + void *__real_malloc(size_t size); +} +void *__wrap_malloc(size_t size) +{ + void *ret = __real_malloc(size); + if (ret != nullptr) { + memset(ret, 0, size); + } + return ret; +} +#endif diff --git a/libraries/AP_Common/float16.cpp b/libraries/AP_Common/float16.cpp index e4ac982f48308c..c5def290149e94 100644 --- a/libraries/AP_Common/float16.cpp +++ b/libraries/AP_Common/float16.cpp @@ -2,6 +2,8 @@ /* float16 implementation + Note that this is IEEE half-precision 16-bit float, *not* bfloat16 + algorithm with thanks to libcanard: https://github.com/dronecan/libcanard */ diff --git a/libraries/AP_Common/tests/test_bitmask.cpp b/libraries/AP_Common/tests/test_bitmask.cpp index 525ab9dd660fd8..23ba357cc5b23f 100644 --- a/libraries/AP_Common/tests/test_bitmask.cpp +++ b/libraries/AP_Common/tests/test_bitmask.cpp @@ -5,9 +5,10 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -TEST(Bitmask, Tests) +template +void bitmask_tests(void) { - Bitmask<49> x; + Bitmask x; EXPECT_EQ(0, x.count()); EXPECT_EQ(-1, x.first_set()); x.set(5); @@ -18,16 +19,16 @@ TEST(Bitmask, Tests) EXPECT_EQ(-1, x.first_set()); EXPECT_EQ(-1, x.first_set()); - x.set(42); - EXPECT_EQ(42, x.first_set()); - x.clear(42); + x.set(N-7); + EXPECT_EQ(N-7, x.first_set()); + x.clear(N-7); EXPECT_EQ(-1, x.first_set()); EXPECT_EQ(-1, x.first_set()); x.set(0); x.set(5); x.set(6); - x.set(48); + x.set(N-1); EXPECT_EQ(4, x.count()); EXPECT_EQ(0, x.first_set()); EXPECT_EQ(0, x.first_set()); @@ -38,66 +39,110 @@ TEST(Bitmask, Tests) EXPECT_EQ(6, x.first_set()); EXPECT_EQ(6, x.first_set()); x.clear(6); - EXPECT_EQ(48, x.first_set()); - EXPECT_EQ(48, x.first_set()); - x.clear(48); + EXPECT_EQ(N-1, x.first_set()); + EXPECT_EQ(N-1, x.first_set()); + x.clear(N-1); EXPECT_EQ(-1, x.first_set()); - Bitmask<49> x2; + Bitmask x2; x2 = x; #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX - x.set(50); + x.clear(N+1); #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL - EXPECT_EXIT(x.set(50), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range"); + EXPECT_EXIT(x.clear(N+1), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range"); #endif - for (uint8_t i=0; i<49; i++) { +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX + x.set(N+1); +#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL + EXPECT_EXIT(x.set(N+1), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range"); +#endif + + for (uint8_t i=0; i(); } +TEST(Bitmask, Tests32) { bitmask_tests<32>(); } +TEST(Bitmask, Tests33) { bitmask_tests<33>(); } +TEST(Bitmask, Tests47) { bitmask_tests<47>(); } +TEST(Bitmask, Tests48) { bitmask_tests<48>(); } +TEST(Bitmask, Tests49) { bitmask_tests<49>(); } +TEST(Bitmask, Tests63) { bitmask_tests<63>(); } +TEST(Bitmask, Tests64) { bitmask_tests<64>(); } +TEST(Bitmask, Tests65) { bitmask_tests<65>(); } + +template +void bitmask_setall(void) { - Bitmask<49> x; + Bitmask x; EXPECT_EQ(-1, x.first_set()); - EXPECT_EQ(false, x.get(45)); + EXPECT_EQ(false, x.get(N-4)); + EXPECT_EQ(0, x.count()); x.setall(); EXPECT_EQ(0, x.first_set()); + EXPECT_EQ(N, x.count()); x.clear(0); EXPECT_EQ(1, x.first_set()); x.clear(1); EXPECT_EQ(2, x.first_set()); - EXPECT_EQ(true, x.get(45)); + EXPECT_EQ(true, x.get(N-4)); EXPECT_EQ(false, x.empty()); x.clearall(); EXPECT_EQ(-1, x.first_set()); - EXPECT_EQ(false, x.get(45)); + EXPECT_EQ(false, x.get(N-4)); EXPECT_EQ(true, x.empty()); + EXPECT_EQ(0, x.count()); } -TEST(Bitmask, Assignment) +TEST(Bitmask, SetAll31) { bitmask_setall<31>(); } +TEST(Bitmask, SetAll32) { bitmask_setall<32>(); } +TEST(Bitmask, SetAll33) { bitmask_setall<33>(); } +TEST(Bitmask, SetAll47) { bitmask_setall<47>(); } +TEST(Bitmask, SetAll48) { bitmask_setall<48>(); } +TEST(Bitmask, SetAll49) { bitmask_setall<49>(); } +TEST(Bitmask, SetAll63) { bitmask_setall<63>(); } +TEST(Bitmask, SetAll64) { bitmask_setall<64>(); } +TEST(Bitmask, SetAll65) { bitmask_setall<65>(); } + +template +void bitmask_assignment(void) { - Bitmask<49> x; + Bitmask x; x.set(0); x.set(5); x.set(6); - x.set(48); + x.set(N-1); - Bitmask<49> y; + Bitmask y; y = x; + EXPECT_EQ(true, x == y); x.clear(0); EXPECT_EQ(true, y.get(0)); EXPECT_EQ(true, y.get(5)); EXPECT_EQ(true, y.get(6)); - EXPECT_EQ(true, y.get(48)); + EXPECT_EQ(true, y.get(N-1)); } +TEST(Bitmask, Assignment31) { bitmask_assignment<31>(); } +TEST(Bitmask, Assignment32) { bitmask_assignment<32>(); } +TEST(Bitmask, Assignment33) { bitmask_assignment<33>(); } +TEST(Bitmask, Assignment47) { bitmask_assignment<47>(); } +TEST(Bitmask, Assignment48) { bitmask_assignment<48>(); } +TEST(Bitmask, Assignment49) { bitmask_assignment<49>(); } +TEST(Bitmask, Assignment63) { bitmask_assignment<63>(); } +TEST(Bitmask, Assignment64) { bitmask_assignment<64>(); } +TEST(Bitmask, Assignment65) { bitmask_assignment<65>(); } + AP_GTEST_PANIC() AP_GTEST_MAIN() diff --git a/libraries/AP_Common/tests/test_cpp.cpp b/libraries/AP_Common/tests/test_cpp.cpp index 9ffe282bbd4c7f..5374814fe66e15 100644 --- a/libraries/AP_Common/tests/test_cpp.cpp +++ b/libraries/AP_Common/tests/test_cpp.cpp @@ -1,4 +1,5 @@ #include +#include int hal = 0; @@ -10,7 +11,7 @@ class DummyDummy { TEST(AP_Common, TEST_CPP) { - DummyDummy * test_new = new DummyDummy[1]; + DummyDummy * test_new = NEW_NOTHROW DummyDummy[1]; EXPECT_FALSE(test_new == nullptr); EXPECT_TRUE(sizeof(test_new) == 8); EXPECT_FLOAT_EQ(test_new->count, 1); @@ -22,7 +23,7 @@ TEST(AP_Common, TEST_CPP) EXPECT_EQ(test_d->count, 0); // constructor isn't called EXPECT_FLOAT_EQ(test_d->d, 0.0); - DummyDummy * test_d2 = new DummyDummy; + DummyDummy * test_d2 = NEW_NOTHROW DummyDummy; EXPECT_TRUE(sizeof(test_d2) == 8); EXPECT_EQ(test_d2->count, 1); EXPECT_FLOAT_EQ(test_d2->d, 42.0); diff --git a/libraries/AP_Common/tests/test_expandingstring.cpp b/libraries/AP_Common/tests/test_expandingstring.cpp index 99cd16e4e6cdea..6b8451305bd33b 100644 --- a/libraries/AP_Common/tests/test_expandingstring.cpp +++ b/libraries/AP_Common/tests/test_expandingstring.cpp @@ -6,7 +6,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); TEST(ExpandingString, Tests) { - ExpandingString *test_string = new ExpandingString(); + ExpandingString *test_string = NEW_NOTHROW ExpandingString(); test_string->printf("Test\n"); EXPECT_STREQ("Test\n", test_string->get_string()); EXPECT_STREQ("Test\n", test_string->get_writeable_string()); @@ -15,7 +15,7 @@ TEST(ExpandingString, Tests) EXPECT_TRUE(test_string->append("Test2\n", 6)); test_string->~ExpandingString(); EXPECT_STRNE("Test\n", test_string->get_string()); - test_string = new ExpandingString(); + test_string = NEW_NOTHROW ExpandingString(); char long_string[2048]; std::fill(std::begin(long_string),std::end(long_string),'a'); test_string->printf("%s", long_string); diff --git a/libraries/AP_Common/tests/test_expandingstring_failure.cpp b/libraries/AP_Common/tests/test_expandingstring_failure.cpp index 81b54f132cba29..0e1c440855a9ee 100644 --- a/libraries/AP_Common/tests/test_expandingstring_failure.cpp +++ b/libraries/AP_Common/tests/test_expandingstring_failure.cpp @@ -70,21 +70,21 @@ void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) { TEST(ExpandingString, Tests) { // Test print_vprintf failure. - ExpandingString *test_string = new ExpandingString(); + ExpandingString *test_string = NEW_NOTHROW ExpandingString(); test_string->printf("Test\n"); EXPECT_STREQ("", test_string->get_string()); EXPECT_STREQ("", test_string->get_writeable_string()); EXPECT_EQ(0u, test_string->get_length()); EXPECT_FALSE(test_string->has_failed_allocation()); // test failure on second printf expand() - test_string = new ExpandingString(); + test_string = NEW_NOTHROW ExpandingString(); test_string->printf("Test\n"); EXPECT_STREQ("", test_string->get_string()); EXPECT_STREQ("", test_string->get_writeable_string()); EXPECT_EQ(0u, test_string->get_length()); EXPECT_TRUE(test_string->has_failed_allocation()); // Test realloc failure - test_string = new ExpandingString(); + test_string = NEW_NOTHROW ExpandingString(); test_string->printf("Test\n"); EXPECT_STREQ(nullptr, test_string->get_string()); EXPECT_STREQ(nullptr, test_string->get_writeable_string()); @@ -99,7 +99,7 @@ TEST(ExpandingString, Tests) EXPECT_EQ(0u, test_string->get_length()); EXPECT_TRUE(test_string->has_failed_allocation()); // test failure on append realloc - test_string = new ExpandingString(); + test_string = NEW_NOTHROW ExpandingString(); EXPECT_FALSE(test_string->append("Test2\n", 6)); EXPECT_TRUE(test_string->has_failed_allocation()); EXPECT_STREQ(nullptr, test_string->get_string()); diff --git a/libraries/AP_Common/tests/test_location.cpp b/libraries/AP_Common/tests/test_location.cpp index d545c2c754df14..f97bc769c678ea 100644 --- a/libraries/AP_Common/tests/test_location.cpp +++ b/libraries/AP_Common/tests/test_location.cpp @@ -280,8 +280,16 @@ TEST(Location, Tests) EXPECT_EQ(0, test_location4.loiter_xtrack); EXPECT_TRUE(test_location4.initialised()); - const Location test_location_empty{test_vect, Location::AltFrame::ABOVE_HOME}; - EXPECT_FALSE(test_location_empty.get_vector_from_origin_NEU(test_vec3)); + // test set_alt_m API: + Location loc = test_home; + loc.set_alt_m(1.71, Location::AltFrame::ABSOLUTE); + int32_t alt_in_cm_from_m; + EXPECT_TRUE(loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_in_cm_from_m)); + EXPECT_EQ(171, alt_in_cm_from_m); + + // can't create a Location using a vector here as there's no origin for the vector to be relative to: + // const Location test_location_empty{test_vect, Location::AltFrame::ABOVE_HOME}; + // EXPECT_FALSE(test_location_empty.get_vector_from_origin_NEU(test_vec3)); } TEST(Location, Distance) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 039ade2d5a70e2..7738ac7f7447ed 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include "AP_Compass_config.h" @@ -20,6 +21,7 @@ #include "AP_Compass_AK8963.h" #include "AP_Compass_Backend.h" #include "AP_Compass_BMM150.h" +#include "AP_Compass_BMM350.h" #include "AP_Compass_HMC5843.h" #include "AP_Compass_IST8308.h" #include "AP_Compass_IST8310.h" @@ -97,6 +99,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0), // @Param: DEC @@ -168,6 +171,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss/A // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0), #endif @@ -213,6 +217,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0), // @Param: MOT2_X @@ -240,6 +245,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss/A // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0), #endif // COMPASS_MAX_INSTANCES @@ -270,6 +276,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0), // @Param: MOT3_X @@ -297,6 +304,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Units: mGauss/A // @Increment: 1 // @User: Advanced + // @Calibration: 1 AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0), #endif // COMPASS_MAX_INSTANCES @@ -388,6 +396,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 + // @Calibration: 1 AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0), // @Param: ODI_X @@ -406,6 +415,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass soft-iron off-diagonal Z component // @Description: ODI_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 + // @Calibration: 1 AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0), #if COMPASS_MAX_INSTANCES > 1 @@ -425,6 +435,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 + // @Calibration: 1 AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0), // @Param: ODI2_X @@ -443,6 +454,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass2 soft-iron off-diagonal Z component // @Description: ODI_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 + // @Calibration: 1 AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0), #endif // COMPASS_MAX_INSTANCES @@ -463,6 +475,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 + // @Calibration: 1 AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0), // @Param: ODI3_X @@ -481,6 +494,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass3 soft-iron off-diagonal Z component // @Description: ODI_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 + // @Calibration: 1 AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0), #endif // COMPASS_MAX_INSTANCES #endif // AP_COMPASS_DIAGONALS_ENABLED @@ -515,7 +529,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: DISBLMSK // @DisplayName: Compass disable driver type mask // @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup - // @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:DroneCAN,12:QMC5883,14:MAG3110,15:IST8308,16:RM3100,17:MSP,18:ExternalAHRS + // @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:DroneCAN,12:QMC5883,14:MAG3110,15:IST8308,16:RM3100,17:MSP,18:ExternalAHRS,19:MMC5XX3,20:QMC5883P,21:BMM350 // @User: Advanced AP_GROUPINFO("DISBLMSK", 33, Compass, _driver_type_mask, 0), @@ -1313,6 +1327,23 @@ void Compass::_probe_external_i2c_compasses(void) } } #endif // AP_COMPASS_BMM150_ENABLED + +#if AP_COMPASS_BMM350_ENABLED + // BMM350 on I2C + FOREACH_I2C_EXTERNAL(i) { + for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) { + ADD_BACKEND(DRIVER_BMM350, + AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE)); + } + } +#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) + FOREACH_I2C_INTERNAL(i) { + for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) { + ADD_BACKEND(DRIVER_BMM350, AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), all_external, ROTATION_NONE)); + } + } +#endif +#endif // AP_COMPASS_BMM350_ENABLED } /* @@ -1323,7 +1354,7 @@ void Compass::_detect_backends(void) #if AP_COMPASS_EXTERNALAHRS_ENABLED const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::COMPASS); if (serial_port >= 0) { - ADD_BACKEND(DRIVER_EXTERNALAHRS, new AP_Compass_ExternalAHRS(serial_port)); + ADD_BACKEND(DRIVER_EXTERNALAHRS, NEW_NOTHROW AP_Compass_ExternalAHRS(serial_port)); } #endif @@ -1337,7 +1368,7 @@ void Compass::_detect_backends(void) #endif #if AP_COMPASS_SITL_ENABLED && !AP_TEST_DRONECAN_DRIVERS - ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL()); + ADD_BACKEND(DRIVER_SITL, NEW_NOTHROW AP_Compass_SITL()); #endif #if AP_COMPASS_DRONECAN_ENABLED @@ -1356,7 +1387,7 @@ void Compass::_detect_backends(void) #if AP_COMPASS_MSP_ENABLED for (uint8_t i=0; i<8; i++) { if (msp_instance_mask & (1U<update(); diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index f08a63e81c96b6..6498c1d31cd435 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -162,9 +162,6 @@ friend class AP_Compass_Backend; /// Return true if we have set a scale factor for a compass bool have_scale_factor(uint8_t i) const; - // compass calibrator interface - void cal_update(); - #if COMPASS_MOT_ENABLED // per-motor calibration access void per_motor_calibration_start(void) { @@ -178,6 +175,10 @@ friend class AP_Compass_Backend; } #endif +#if COMPASS_CAL_ENABLED + // compass calibrator interface + void cal_update(); + // start_calibration_all will only return false if there are no // compasses to calibrate. bool start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot = false); @@ -187,9 +188,7 @@ friend class AP_Compass_Backend; bool compass_cal_requires_reboot() const { return _cal_requires_reboot; } bool is_calibrating() const; - // indicate which bit in LOG_BITMASK indicates we should log compass readings - void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; } - +#if HAL_MAVLINK_BINDINGS_ENABLED /* handle an incoming MAG_CAL command */ @@ -197,6 +196,11 @@ friend class AP_Compass_Backend; bool send_mag_cal_progress(const class GCS_MAVLINK& link); bool send_mag_cal_report(const class GCS_MAVLINK& link); +#endif // HAL_MAVLINK_BINDINGS_ENABLED +#endif // COMPASS_CAL_ENABLED + + // indicate which bit in LOG_BITMASK indicates we should log compass readings + void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; } // check if the compasses are pointing in the same direction bool consistent() const; @@ -391,6 +395,7 @@ friend class AP_Compass_Backend; void probe_dronecan_compasses(void); #endif +#if COMPASS_CAL_ENABLED // compass cal void _update_calibration_trampoline(); bool _accept_calibration(uint8_t i); @@ -401,8 +406,11 @@ friend class AP_Compass_Backend; bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f); bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false); bool _auto_reboot() const { return _compass_cal_autoreboot; } +#if HAL_MAVLINK_BINDINGS_ENABLED Priority next_cal_progress_idx[MAVLINK_COMM_NUM_BUFFERS]; Priority next_cal_report_idx[MAVLINK_COMM_NUM_BUFFERS]; +#endif +#endif // COMPASS_CAL_ENABLED // 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; @@ -419,12 +427,12 @@ friend class AP_Compass_Backend; //keep track of which calibrators have been saved RestrictIDTypeArray _cal_saved; bool _cal_autosave; -#endif //autoreboot after compass calibration bool _compass_cal_autoreboot; bool _cal_requires_reboot; bool _cal_has_run; +#endif // COMPASS_CAL_ENABLED // enum of drivers for COMPASS_DISBLMSK enum DriverType { @@ -488,6 +496,9 @@ friend class AP_Compass_Backend; #if AP_COMPASS_QMC5883P_ENABLED DRIVER_QMC5883P =20, #endif +#if AP_COMPASS_BMM350_ENABLED + DRIVER_BMM350 =21, +#endif }; bool _driver_enabled(enum DriverType driver_type); diff --git a/libraries/AP_Compass/AP_Compass_AK09916.cpp b/libraries/AP_Compass/AP_Compass_AK09916.cpp index 8630da5e9747b2..6ac853dd67bb62 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.cpp +++ b/libraries/AP_Compass/AP_Compass_AK09916.cpp @@ -79,12 +79,12 @@ AP_Compass_Backend *AP_Compass_AK09916::probe(AP_HAL::OwnPtr if (!dev) { return nullptr; } - AP_AK09916_BusDriver *bus = new AP_AK09916_BusDriver_HALDevice(std::move(dev)); + AP_AK09916_BusDriver *bus = NEW_NOTHROW AP_AK09916_BusDriver_HALDevice(std::move(dev)); if (!bus) { return nullptr; } - AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(bus, force_external, rotation); + AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -179,12 +179,12 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_SPI(uint8_t inv2_instance AP_InertialSensor &ins = AP::ins(); AP_AK09916_BusDriver *bus = - new AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR); + NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_SPI, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR); if (!bus) { return nullptr; } - AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(bus, false, rotation); + AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -202,12 +202,12 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948_I2C(uint8_t inv2_instance AP_InertialSensor &ins = AP::ins(); AP_AK09916_BusDriver *bus = - new AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_I2C, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR); + NEW_NOTHROW AP_AK09916_BusDriver_Auxiliary(ins, HAL_INS_INV2_I2C, inv2_instance, HAL_COMPASS_AK09916_I2C_ADDR); if (!bus) { return nullptr; } - AP_Compass_AK09916 *sensor = new AP_Compass_AK09916(bus, false, rotation); + AP_Compass_AK09916 *sensor = NEW_NOTHROW AP_Compass_AK09916(bus, false, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index ad6a8c6d234efd..c4dc7e66f88c3d 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -69,12 +69,12 @@ AP_Compass_Backend *AP_Compass_AK8963::probe(AP_HAL::OwnPtr d if (!dev) { return nullptr; } - AP_AK8963_BusDriver *bus = new AP_AK8963_BusDriver_HALDevice(std::move(dev)); + AP_AK8963_BusDriver *bus = NEW_NOTHROW AP_AK8963_BusDriver_HALDevice(std::move(dev)); if (!bus) { return nullptr; } - AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation); + AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -106,12 +106,12 @@ AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(uint8_t mpu9250_instance, AP_InertialSensor &ins = *AP_InertialSensor::get_singleton(); AP_AK8963_BusDriver *bus = - new AP_AK8963_BusDriver_Auxiliary(ins, HAL_INS_MPU9250_SPI, mpu9250_instance, AK8963_I2C_ADDR); + NEW_NOTHROW AP_AK8963_BusDriver_Auxiliary(ins, HAL_INS_MPU9250_SPI, mpu9250_instance, AK8963_I2C_ADDR); if (!bus) { return nullptr; } - AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(bus, rotation); + AP_Compass_AK8963 *sensor = NEW_NOTHROW AP_Compass_AK8963(bus, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_BMM150.cpp b/libraries/AP_Compass/AP_Compass_BMM150.cpp index 7be066c66fc52a..eb4dcd0b36de6c 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.cpp +++ b/libraries/AP_Compass/AP_Compass_BMM150.cpp @@ -70,7 +70,7 @@ AP_Compass_Backend *AP_Compass_BMM150::probe(AP_HAL::OwnPtr d if (!dev) { return nullptr; } - AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(std::move(dev), force_external, rotation); + AP_Compass_BMM150 *sensor = NEW_NOTHROW AP_Compass_BMM150(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_BMM350.cpp b/libraries/AP_Compass/AP_Compass_BMM350.cpp new file mode 100644 index 00000000000000..d5f83419b8af54 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_BMM350.cpp @@ -0,0 +1,492 @@ +/* + * 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 . + */ +#include "AP_Compass_BMM350.h" + +#if AP_COMPASS_BMM350_ENABLED + +#include + +#include + +#include +#include + +#define BMM350_REG_CHIP_ID 0x00 +#define BMM350_REG_PMU_CMD_AGGR_SET 0x04 +#define BMM350_REG_PMU_CMD_AXIS_EN 0x05 +#define BMM350_REG_PMU_CMD 0x06 +#define BMM350_REG_PMU_CMD_STATUS_0 0x07 +#define BMM350_REG_INT_CTRL 0x2E +#define BMM350_REG_MAG_X_XLSB 0x31 +#define BMM350_REG_OTP_CMD 0x50 +#define BMM350_REG_OTP_DATA_MSB 0x52 +#define BMM350_REG_OTP_DATA_LSB 0x53 +#define BMM350_REG_OTP_STATUS 0x55 +#define BMM350_REG_CMD 0x7E + +// OTP(one-time programmable memory) +#define BMM350_OTP_CMD_DIR_READ (0x01<<5U) +#define BMM350_OTP_CMD_PWR_OFF_OTP (0x04<<5U) + +#define BMM350_OTP_STATUS_ERROR_MASK 0xE0 +#define BMM350_OTP_STATUS_CMD_DONE 0x01 + +#define BMM350_TEMP_OFF_SENS 0x0D +#define BMM350_MAG_OFFSET_X 0x0E +#define BMM350_MAG_OFFSET_Y 0x0F +#define BMM350_MAG_OFFSET_Z 0x10 +#define BMM350_MAG_SENS_X 0x10 +#define BMM350_MAG_SENS_Y 0x11 +#define BMM350_MAG_SENS_Z 0x11 +#define BMM350_MAG_TCO_X 0x12 +#define BMM350_MAG_TCO_Y 0x13 +#define BMM350_MAG_TCO_Z 0x14 +#define BMM350_MAG_TCS_X 0x12 +#define BMM350_MAG_TCS_Y 0x13 +#define BMM350_MAG_TCS_Z 0x14 +#define BMM350_MAG_DUT_T_0 0x18 +#define BMM350_CROSS_X_Y 0x15 +#define BMM350_CROSS_Y_X 0x15 +#define BMM350_CROSS_Z_X 0x16 +#define BMM350_CROSS_Z_Y 0x16 +#define BMM350_SENS_CORR_Y 0.01f +#define BMM350_TCS_CORR_Z 0.0001f + +#define BMM350_CMD_SOFTRESET 0xB6 +#define BMM350_INT_MODE_PULSED (0<<0U) +#define BMM350_INT_POL_ACTIVE_HIGH (1<<1U) +#define BMM350_INT_OD_PUSHPULL (1<<2U) +#define BMM350_INT_OUTPUT_DISABLE (0<<3U) +#define BMM350_INT_DRDY_EN (1<<7U) + +// Averaging performance +#define BMM350_AVERAGING_4 (0x02 << 4U) +#define BMM350_AVERAGING_8 (0x03 << 4U) + +// Output data rate +#define BMM350_ODR_100HZ 0x04 +#define BMM350_ODR_50HZ 0x05 + +// Power modes +#define BMM350_PMU_CMD_SUSPEND_MODE 0x00 +#define BMM350_PMU_CMD_NORMAL_MODE 0x01 +#define BMM350_PMU_CMD_UPD_OAE 0x02 +#define BMM350_PMU_CMD_FGR 0x05 +#define BMM350_PMU_CMD_BR 0x07 + +// OTP data length +#define BMM350_OTP_DATA_LENGTH 32U + +// Chip ID of BMM350 +#define BMM350_CHIP_ID 0x33 + +#define BMM350_XY_SENSITIVE 14.55f +#define BMM350_Z_SENSITIVE 9.0f +#define BMM350_TEMP_SENSITIVE 0.00204f +#define BMM350_XY_INA_GAIN 19.46f +#define BMM350_Z_INA_GAIN 31.0f +#define BMM350_ADC_GAIN (1.0f / 1.5f) +#define BMM350_LUT_GAIN 0.714607238769531f +#define BMM350_POWER ((float)(1000000.0 / 1048576.0)) + +#define BMM350_XY_SCALE (BMM350_POWER / (BMM350_XY_SENSITIVE * BMM350_XY_INA_GAIN * BMM350_ADC_GAIN * BMM350_LUT_GAIN)) +#define BMM350_Z_SCALE (BMM350_POWER / (BMM350_Z_SENSITIVE * BMM350_Z_INA_GAIN * BMM350_ADC_GAIN * BMM350_LUT_GAIN)) +#define BMM350_TEMP_SCALE (1.0f / (BMM350_TEMP_SENSITIVE * BMM350_ADC_GAIN * BMM350_LUT_GAIN * 1048576)) + +extern const AP_HAL::HAL &hal; + +AP_Compass_Backend *AP_Compass_BMM350::probe(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation) +{ + if (!dev) { + return nullptr; + } + AP_Compass_BMM350 *sensor = NEW_NOTHROW AP_Compass_BMM350(std::move(dev), force_external, rotation); + if (!sensor || !sensor->init()) { + delete sensor; + return nullptr; + } + + return sensor; +} + +AP_Compass_BMM350::AP_Compass_BMM350(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation) + : _dev(std::move(dev)) + , _force_external(force_external) + , _rotation(rotation) +{ +} + +/** + * @brief Read out OTP(one-time programmable memory) data of sensor which is the compensation coefficients + * @see https://github.com/boschsensortec/BMM350-SensorAPI + */ +bool AP_Compass_BMM350::read_otp_data() +{ + uint16_t otp_data[BMM350_OTP_DATA_LENGTH]; + + for (uint8_t index = 0; index < BMM350_OTP_DATA_LENGTH; index++) { + // Set OTP address + if (!_dev->write_register(BMM350_REG_OTP_CMD, (BMM350_OTP_CMD_DIR_READ | index))) { + return false; + } + + // Wait for OTP status be ready + int8_t tries = 3; // Try polling 3 times + while (tries--) + { + uint8_t status; + hal.scheduler->delay_microseconds(300); + // Read OTP status + if (!read_bytes(BMM350_REG_OTP_STATUS, &status, 1) || ((status & BMM350_OTP_STATUS_ERROR_MASK) != 0)) { + return false; + } + if (status & BMM350_OTP_STATUS_CMD_DONE) { + break; + } + } + + if (tries == -1) { + return false; + } + + // Read OTP data + be16_t reg_data; + if (!read_bytes(BMM350_REG_OTP_DATA_MSB, (uint8_t *)®_data, 2)) { + return false; + } + + otp_data[index] = be16toh(reg_data); + } + + // Update magnetometer offset and sensitivity data. + // 12-bit unsigned integer to be left-aligned in a 16-bit integer + _mag_comp.offset_coef.x = float(int16_t((otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF) << 4) >> 4); + _mag_comp.offset_coef.y = float(int16_t((((otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) + + (otp_data[BMM350_MAG_OFFSET_Y] & 0x00FF)) << 4) >> 4); + _mag_comp.offset_coef.z = float(int16_t(((otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) + + (otp_data[BMM350_MAG_OFFSET_Z] & 0x00FF)) << 4) >> 4); + _mag_comp.offset_coef.temp = float(int8_t(otp_data[BMM350_TEMP_OFF_SENS])) * (1.0f / 5.0f); + + _mag_comp.sensit_coef.x = float(int8_t((otp_data[BMM350_MAG_SENS_X] & 0xFF00) >> 8)) * (1.0f / 256.0f); + _mag_comp.sensit_coef.y = float(int8_t(otp_data[BMM350_MAG_SENS_Y])) * (1.0f / 256.0f) + BMM350_SENS_CORR_Y; + _mag_comp.sensit_coef.z = float(int8_t((otp_data[BMM350_MAG_SENS_Z] & 0xFF00) >> 8)) * (1.0f / 256.0f); + _mag_comp.sensit_coef.temp = float(int8_t((otp_data[BMM350_TEMP_OFF_SENS] & 0xFF00) >> 8)) * (1.0f / 512.0f); + + _mag_comp.tco.x = float(int8_t(otp_data[BMM350_MAG_TCO_X])) * (1.0f / 32.0f); + _mag_comp.tco.y = float(int8_t(otp_data[BMM350_MAG_TCO_Y])) * (1.0f / 32.0f); + _mag_comp.tco.z = float(int8_t(otp_data[BMM350_MAG_TCO_Z])) * (1.0f / 32.0f); + + _mag_comp.tcs.x = float(int8_t((otp_data[BMM350_MAG_TCS_X] & 0xFF00) >> 8)) * (1.0f / 16384.0f); + _mag_comp.tcs.y = float(int8_t((otp_data[BMM350_MAG_TCS_Y] & 0xFF00) >> 8)) * (1.0f / 16384.0f); + _mag_comp.tcs.z = float(int8_t((otp_data[BMM350_MAG_TCS_Z] & 0xFF00) >> 8)) * (1.0f / 16384.0f) - BMM350_TCS_CORR_Z; + + _mag_comp.t0_reading = float(int16_t(otp_data[BMM350_MAG_DUT_T_0])) * (1.0f / 512.0f) + 23.0f; + + _mag_comp.cross_axis.cross_x_y = float(int8_t(otp_data[BMM350_CROSS_X_Y])) * (1.0f / 800.0f); + _mag_comp.cross_axis.cross_y_x = float(int8_t((otp_data[BMM350_CROSS_Y_X] & 0xFF00) >> 8)) * (1.0f / 800.0f); + _mag_comp.cross_axis.cross_z_x = float(int8_t(otp_data[BMM350_CROSS_Z_X])) * (1.0f / 800.0f); + _mag_comp.cross_axis.cross_z_y = float(int8_t((otp_data[BMM350_CROSS_Z_Y] & 0xFF00) >> 8)) * (1.0f / 800.0f); + + return true; +} + +/** + * @brief Wait PMU_CMD register operation completed. Need to specify which command just sent + */ +bool AP_Compass_BMM350::wait_pmu_cmd_ready(const uint8_t cmd, const uint32_t timeout) +{ + const uint32_t start_tick = AP_HAL::millis(); + + do { + hal.scheduler->delay(1); + uint8_t status; + if (!read_bytes(BMM350_REG_PMU_CMD_STATUS_0, &status, 1)) { + return false; + } + if (((status & 0x01) == 0x00) && (((status & 0xE0) >> 5) == cmd)) { + return true; + } + } while ((AP_HAL::millis() - start_tick) < timeout); + + return false; +} + +/** + * @brief Reset bit of magnetic register and wait for change to normal mode + */ +bool AP_Compass_BMM350::mag_reset_and_wait() +{ + uint8_t data; + + // Get PMU command status 0 data + if (!read_bytes(BMM350_REG_PMU_CMD_STATUS_0, &data, 1)) { + return false; + } + + // Check whether the power mode is Normal + if (data & 0x08) { + // Set PMU command to suspend mode + if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_SUSPEND_MODE)) { + return false; + } + wait_pmu_cmd_ready(BMM350_PMU_CMD_SUSPEND_MODE, 6); + } + + // Set BR(bit reset) to PMU_CMD register + // In offical example, it wait for 14ms. But it may not be enough, so we wait an extra 5ms + if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_BR) || + !wait_pmu_cmd_ready(BMM350_PMU_CMD_BR, 19)) { + return false; + } + + // Set FGR(flux-guide reset) to PMU_CMD register + // 18ms got from offical example, we wait an extra 5ms + if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_FGR) || + !wait_pmu_cmd_ready(BMM350_PMU_CMD_FGR, 23)) { + return false; + } + + // Switch to normal mode + if (!set_power_mode(POWER_MODE_NORMAL)) { + return false; + } + + return true; +} + +/** + * @brief Switch sensor power mode + */ +bool AP_Compass_BMM350::set_power_mode(const enum power_mode mode) +{ + uint8_t pmu_cmd; + + // Get PMU register data as current mode + if (!read_bytes(BMM350_REG_PMU_CMD, &pmu_cmd, 1)) { + return false; + } + + if (pmu_cmd == BMM350_PMU_CMD_NORMAL_MODE || pmu_cmd == BMM350_PMU_CMD_UPD_OAE) { + // Set PMU command to suspend mode + if (!_dev->write_register(BMM350_REG_PMU_CMD, POWER_MODE_SUSPEND)) { + return false; + } + // Wait for sensor switch to suspend mode + // Wait for maximum 6ms, it got from the official example, not explained in datasheet + wait_pmu_cmd_ready(POWER_MODE_SUSPEND, 6); + } + + // Set PMU command to target mode + if (!_dev->write_register(BMM350_REG_PMU_CMD, mode)) { + return false; + } + + // Wait for mode change. When switch from suspend mode to normal mode, we wait for at most 38ms. + // It got from official example too + wait_pmu_cmd_ready(mode, 38); + + return true; +} + +/** + * @brief Read bytes from sensor + */ +bool AP_Compass_BMM350::read_bytes(const uint8_t reg, uint8_t *out, const uint16_t read_len) +{ + uint8_t data[read_len + 2]; + + if (!_dev->read_registers(reg, data, read_len + 2)) { + return false; + } + + memcpy(out, &data[2], read_len); + + return true; +} + +bool AP_Compass_BMM350::init() +{ + _dev->get_semaphore()->take_blocking(); + + // 10 retries for init + _dev->set_retries(10); + + // Use checked registers to cope with bus errors + _dev->setup_checked_registers(4); + + int8_t boot_retries = 5; + while (boot_retries--) { + // Soft reset + if (!_dev->write_register(BMM350_REG_CMD, BMM350_CMD_SOFTRESET)) { + continue; + } + hal.scheduler->delay(24); // Wait 24ms for soft reset complete, it got from offical example + + // Read and verify chip ID + uint8_t chip_id; + if (!read_bytes(BMM350_REG_CHIP_ID, &chip_id, 1)) { + continue; + } + if (chip_id == BMM350_CHIP_ID) { + break; + } + } + + if (boot_retries == -1) { + goto err; + } + + // Read out OTP data + if (!read_otp_data()) { + goto err; + } + + // Power off OTP + if (!_dev->write_register(BMM350_REG_OTP_CMD, BMM350_OTP_CMD_PWR_OFF_OTP)) { + goto err; + } + + // Magnetic reset + if (!mag_reset_and_wait()) { + goto err; + } + + // Configure interrupt settings and enable DRDY + // Set INT mode as PULSED | active_high polarity | PUSH_PULL | unmap | DRDY interrupt + if (!_dev->write_register(BMM350_REG_INT_CTRL, (BMM350_INT_MODE_PULSED | + BMM350_INT_POL_ACTIVE_HIGH | + BMM350_INT_OD_PUSHPULL | + BMM350_INT_OUTPUT_DISABLE | + BMM350_INT_DRDY_EN))) { + goto err; + } + + // Setup ODR and performance. 100Hz ODR and 4 average for lownoise + if (!_dev->write_register(BMM350_REG_PMU_CMD_AGGR_SET, (BMM350_AVERAGING_4 | BMM350_ODR_100HZ))) { + goto err; + } + + // Update ODR and avg parameter + if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE)) { + goto err; + } + // Wait at most 20ms for update ODR and avg paramter + wait_pmu_cmd_ready(BMM350_PMU_CMD_UPD_OAE, 20); + + // Enable measurement of 3 axis + if (!_dev->write_register(BMM350_REG_PMU_CMD_AXIS_EN, 0x07)) { + goto err; + } + + // Switch power mode to normal mode + if (!set_power_mode(POWER_MODE_NORMAL)) { + goto err; + } + + // Lower retries for run + _dev->set_retries(3); + + _dev->get_semaphore()->give(); + + /* Register the compass instance in the frontend */ + _dev->set_device_type(DEVTYPE_BMM350); + if (!register_compass(_dev->get_bus_id(), _compass_instance)) { + return false; + } + set_dev_id(_compass_instance, _dev->get_bus_id()); + + // printf("BMM350: Found at address 0x%x as compass %u\n", _dev->get_bus_address(), _compass_instance); + + set_rotation(_compass_instance, _rotation); + + if (_force_external) { + set_external(_compass_instance, true); + } + + // Call timer() at 100Hz + _dev->register_periodic_callback(1000000U/100U, FUNCTOR_BIND_MEMBER(&AP_Compass_BMM350::timer, void)); + + return true; + +err: + _dev->get_semaphore()->give(); + return false; +} + +void AP_Compass_BMM350::timer() +{ + struct PACKED { + uint8_t magx[3]; + uint8_t magy[3]; + uint8_t magz[3]; + uint8_t temp[3]; + } data; + + // Read out measurement data + if (!read_bytes(BMM350_REG_MAG_X_XLSB, (uint8_t *)&data, sizeof(data))) { + return; + } + + // Converts 24-bit raw data to signed integer value + const int32_t magx_raw = int32_t(((uint32_t)data.magx[0] << 8) + ((uint32_t)data.magx[1] << 16) + ((uint32_t)data.magx[2] << 24)) >> 8; + const int32_t magy_raw = int32_t(((uint32_t)data.magy[0] << 8) + ((uint32_t)data.magy[1] << 16) + ((uint32_t)data.magy[2] << 24)) >> 8; + const int32_t magz_raw = int32_t(((uint32_t)data.magz[0] << 8) + ((uint32_t)data.magz[1] << 16) + ((uint32_t)data.magz[2] << 24)) >> 8; + const int32_t temp_raw = int32_t(((uint32_t)data.temp[0] << 8) + ((uint32_t)data.temp[1] << 16) + ((uint32_t)data.temp[2] << 24)) >> 8; + + // Convert mag lsb to uT and temp lsb to degC + float magx = (float)magx_raw * BMM350_XY_SCALE; + float magy = (float)magy_raw * BMM350_XY_SCALE; + float magz = (float)magz_raw * BMM350_Z_SCALE; + float temp = (float)temp_raw * BMM350_TEMP_SCALE; + + if (temp > 0.0f) { + temp -= 25.49f; + } else if (temp < 0.0f) { + temp += 25.49f; + } + + // Apply compensation + temp = ((1 + _mag_comp.sensit_coef.temp) * temp) + _mag_comp.offset_coef.temp; + // Compensate raw magnetic data + magx = ((1 + _mag_comp.sensit_coef.x) * magx) + _mag_comp.offset_coef.x + (_mag_comp.tco.x * (temp - _mag_comp.t0_reading)); + magx /= 1 + _mag_comp.tcs.x * (temp - _mag_comp.t0_reading); + + magy = ((1 + _mag_comp.sensit_coef.y) * magy) + _mag_comp.offset_coef.y + (_mag_comp.tco.y * (temp - _mag_comp.t0_reading)); + magy /= 1 + _mag_comp.tcs.y * (temp - _mag_comp.t0_reading); + + magz = ((1 + _mag_comp.sensit_coef.z) * magz) + _mag_comp.offset_coef.z + (_mag_comp.tco.z * (temp - _mag_comp.t0_reading)); + magz /= 1 + _mag_comp.tcs.z * (temp - _mag_comp.t0_reading); + + const float cr_ax_comp_x = (magx - _mag_comp.cross_axis.cross_x_y * magy) / (1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y); + const float cr_ax_comp_y = (magy - _mag_comp.cross_axis.cross_y_x * magx) / (1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y); + const float cr_ax_comp_z = (magz + (magx * (_mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_z_y - _mag_comp.cross_axis.cross_z_x) - + magy * (_mag_comp.cross_axis.cross_z_y - _mag_comp.cross_axis.cross_x_y * _mag_comp.cross_axis.cross_z_x)) / + (1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y)); + + // Store in field vector and convert uT to milligauss + Vector3f field { cr_ax_comp_x * 10.0f, cr_ax_comp_y * 10.0f, cr_ax_comp_z * 10.0f }; + accumulate_sample(field, _compass_instance); +} + +void AP_Compass_BMM350::read() +{ + drain_accumulated_samples(_compass_instance); +} + +#endif // AP_COMPASS_BMM350_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_BMM350.h b/libraries/AP_Compass/AP_Compass_BMM350.h new file mode 100644 index 00000000000000..4cf5fdf55507d8 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_BMM350.h @@ -0,0 +1,112 @@ +/* + * 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 "AP_Compass_config.h" + +#if AP_COMPASS_BMM350_ENABLED + +#include +#include +#include +#include + +#include "AP_Compass.h" +#include "AP_Compass_Backend.h" + +#define BMM350_I2C_ADDR_MIN 0x14 +#define BMM350_I2C_ADDR_MAX 0x17 + + +class AP_Compass_BMM350 : public AP_Compass_Backend +{ +public: + static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation); + + void read() override; + + static constexpr const char *name = "BMM350"; + +private: + AP_Compass_BMM350(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation); + + AP_HAL::OwnPtr _dev; + + /** + * @brief BMM350 offset/sensitivity coefficient structure + */ + struct vector4f + { + float x; // x axis + float y; // y axis + float z; // z axis + float temp; // Temperature + }; + + /** + * @brief BMM350 magnetometer cross axis compensation structure + */ + struct cross_axis + { + float cross_x_y; + float cross_y_x; + float cross_z_x; + float cross_z_y; + }; + + /** + * @brief BMM350 magnetometer compensate structure + */ + struct mag_compensate + { + struct vector4f offset_coef; // Offset coefficient + struct vector4f sensit_coef; // Sensitivity coefficient + Vector3f tco; // Temperature coefficient of the offset + Vector3f tcs; // Temperature coefficient of the sensitivity + float t0_reading; // Initialize T0_reading parameter + struct cross_axis cross_axis; // Cross axis compensation + }; + + enum power_mode + { + POWER_MODE_SUSPEND = 0, + POWER_MODE_NORMAL = 1, + POWER_MODE_FORCED = 3, + POWER_MODE_FORCED_FAST = 4 + }; + + /** + * Device periodic callback to read data from the sensor. + */ + bool init(); + void timer(); + bool read_otp_data(); + bool wait_pmu_cmd_ready(const uint8_t cmd, const uint32_t timeout); + bool mag_reset_and_wait(); + bool set_power_mode(const enum power_mode mode); + bool read_bytes(const uint8_t reg, uint8_t *out, const uint16_t read_len); + + uint8_t _compass_instance; + bool _force_external; + enum Rotation _rotation; + struct mag_compensate _mag_comp; // Structure for mag compensate +}; + +#endif // AP_COMPASS_BMM350_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 79bfe1f66fd7b8..68c0959cccec6d 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -74,6 +74,7 @@ class AP_Compass_Backend DEVTYPE_AK09918 = 0x14, DEVTYPE_AK09915 = 0x15, DEVTYPE_QMC5883P = 0x16, + DEVTYPE_BMM350 = 0x17, }; #if AP_COMPASS_MSP_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 809ca03c0e931d..db5e55d6717b61 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -63,7 +63,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) #endif if (_calibrator[prio] == nullptr) { - _calibrator[prio] = new CompassCalibrator(); + _calibrator[prio] = NEW_NOTHROW CompassCalibrator(); if (_calibrator[prio] == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal object not initialised"); return false; diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index 3f29ec5706b04b..50008d8424cb3e 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -37,24 +37,16 @@ AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devi { } -void AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mag_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mag2_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, driver_index) != nullptr) #if AP_COMPASS_DRONECAN_HIRES_ENABLED - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mag3_sub"); - } + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_hires, driver_index) != nullptr) #endif + ; } AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index) @@ -63,7 +55,7 @@ AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index) if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) { WITH_SEMAPHORE(_sem_registry); // Register new Compass mode to a backend - driver = new AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid); + driver = NEW_NOTHROW AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid); if (driver) { if (!driver->init()) { delete driver; @@ -222,8 +214,9 @@ void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, // @Field: My: y axis field // @Field: Mz: z axis field +#if HAL_LOGGING_ENABLED // just log it for now - AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F-----", "QBBBfff", + AP::logger().WriteStreaming("MAGH", "TimeUS,Node,Sensor,Bus,Mx,My,Mz", "s#-----", "F------", "QBBBfff", transfer.timestamp_usec, transfer.source_node_id, ap_dronecan->get_driver_index(), @@ -231,8 +224,9 @@ void AP_Compass_DroneCAN::handle_magnetic_field_hires(AP_DroneCAN *ap_dronecan, msg.magnetic_field_ga[0]*1000, msg.magnetic_field_ga[1]*1000, msg.magnetic_field_ga[2]*1000); +#endif // HAL_LOGGING_ENABLED } -#endif +#endif // AP_COMPASS_DRONECAN_HIRES_ENABLED void AP_Compass_DroneCAN::read(void) { diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h index 7a50f41406c14d..927821e5ef1fc5 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.h +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -14,7 +14,7 @@ class AP_Compass_DroneCAN : public AP_Compass_Backend { void read(void) override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_Compass_Backend* probe(uint8_t index); static uint32_t get_detected_devid(uint8_t index) { return _detected_modules[index].devid; } static void handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 6c8f91764598bc..1c2d969f34b06b 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -112,12 +112,12 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev)); + AP_HMC5843_BusDriver *bus = NEW_NOTHROW AP_HMC5843_BusDriver_HALDevice(std::move(dev)); if (!bus) { return nullptr; } - AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, force_external, rotation); + AP_Compass_HMC5843 *sensor = NEW_NOTHROW AP_Compass_HMC5843(bus, force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -132,13 +132,13 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation) AP_InertialSensor &ins = *AP_InertialSensor::get_singleton(); AP_HMC5843_BusDriver *bus = - new AP_HMC5843_BusDriver_Auxiliary(ins, HAL_INS_MPU60XX_SPI, + NEW_NOTHROW AP_HMC5843_BusDriver_Auxiliary(ins, HAL_INS_MPU60XX_SPI, HAL_COMPASS_HMC5843_I2C_ADDR); if (!bus) { return nullptr; } - AP_Compass_HMC5843 *sensor = new AP_Compass_HMC5843(bus, false, rotation); + AP_Compass_HMC5843 *sensor = NEW_NOTHROW AP_Compass_HMC5843(bus, false, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -334,9 +334,7 @@ bool AP_Compass_HMC5843::_check_whoami() // can't talk on bus return false; } - if (id[0] != 'H' || - id[1] != '4' || - id[2] != '3') { + if (memcmp(id, "H43", 3) != 0) { // not a HMC5x83 device return false; } diff --git a/libraries/AP_Compass/AP_Compass_IST8308.cpp b/libraries/AP_Compass/AP_Compass_IST8308.cpp index c4c3ea499feecb..722457dda3905b 100644 --- a/libraries/AP_Compass/AP_Compass_IST8308.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8308.cpp @@ -89,7 +89,7 @@ AP_Compass_Backend *AP_Compass_IST8308::probe(AP_HAL::OwnPtr return nullptr; } - AP_Compass_IST8308 *sensor = new AP_Compass_IST8308(std::move(dev), force_external, rotation); + AP_Compass_IST8308 *sensor = NEW_NOTHROW AP_Compass_IST8308(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -168,7 +168,7 @@ bool AP_Compass_IST8308::init() set_dev_id(_instance, _dev->get_bus_id()); printf("%s found on bus %u id %u address 0x%02x\n", name, - _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address()); + _dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address()); set_rotation(_instance, _rotation); @@ -200,10 +200,6 @@ void AP_Compass_IST8308::timer() return; } - if (stat & STAT1_VAL_DOR) { - printf("IST8308: data overrun\n"); - } - if (!_dev->read_registers(DATAX_L_REG, (uint8_t *) &buffer, sizeof(buffer))) { return; diff --git a/libraries/AP_Compass/AP_Compass_IST8310.cpp b/libraries/AP_Compass/AP_Compass_IST8310.cpp index be982a93c6d8c0..75c0ab8e17d91b 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8310.cpp @@ -86,7 +86,7 @@ AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr return nullptr; } - AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(std::move(dev), force_external, rotation); + AP_Compass_IST8310 *sensor = NEW_NOTHROW AP_Compass_IST8310(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -113,6 +113,22 @@ bool AP_Compass_IST8310::init() // high retries for init _dev->set_retries(10); + /* + unfortunately the IST8310 employs the novel concept of a + writeable WHOAMI register. The register can become corrupt due + to bus noise, and what is worse it persists the corruption even + across a power cycle. If you power it off for 30s or more then + it will reset to the default of 0x10, but for less than that the + value of WAI is unreliable. + + To avoid this issue we do a reset of the device before we probe + the WAI register. This is nasty as we don't yet know we've found + a real IST8310, but it is the best we can do given the bad + hardware design of the sensor + */ + _dev->write_register(CNTL2_REG, CNTL2_VAL_SRST); + hal.scheduler->delay(10); + uint8_t whoami; if (!_dev->read_registers(WAI_REG, &whoami, 1) || whoami != DEVICE_ID) { @@ -162,7 +178,7 @@ bool AP_Compass_IST8310::init() set_dev_id(_instance, _dev->get_bus_id()); printf("%s found on bus %u id %u address 0x%02x\n", name, - _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address()); + _dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address()); set_rotation(_instance, _rotation); diff --git a/libraries/AP_Compass/AP_Compass_LIS3MDL.cpp b/libraries/AP_Compass/AP_Compass_LIS3MDL.cpp index 713ff00befe2f0..b43f0706e1a1c9 100644 --- a/libraries/AP_Compass/AP_Compass_LIS3MDL.cpp +++ b/libraries/AP_Compass/AP_Compass_LIS3MDL.cpp @@ -57,7 +57,7 @@ AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_Compass_LIS3MDL *sensor = new AP_Compass_LIS3MDL(std::move(dev), force_external, rotation); + AP_Compass_LIS3MDL *sensor = NEW_NOTHROW AP_Compass_LIS3MDL(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -113,7 +113,7 @@ bool AP_Compass_LIS3MDL::init() } set_dev_id(compass_instance, dev->get_bus_id()); - printf("Found a LIS3MDL on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance); + printf("Found a LIS3MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance); set_rotation(compass_instance, rotation); diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.cpp b/libraries/AP_Compass/AP_Compass_LSM303D.cpp index c3a2e682179e56..7d0437d169d24c 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM303D.cpp @@ -164,7 +164,7 @@ AP_Compass_Backend *AP_Compass_LSM303D::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(std::move(dev)); + AP_Compass_LSM303D *sensor = NEW_NOTHROW AP_Compass_LSM303D(std::move(dev)); if (!sensor || !sensor->init(rotation)) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp index 60db0f54de6226..d423254347e301 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp @@ -62,7 +62,7 @@ AP_Compass_Backend *AP_Compass_LSM9DS1::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(std::move(dev), rotation); + AP_Compass_LSM9DS1 *sensor = NEW_NOTHROW AP_Compass_LSM9DS1(std::move(dev), rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_MAG3110.cpp b/libraries/AP_Compass/AP_Compass_MAG3110.cpp index 69ae611c82d6c9..c486a0fac10c6e 100644 --- a/libraries/AP_Compass/AP_Compass_MAG3110.cpp +++ b/libraries/AP_Compass/AP_Compass_MAG3110.cpp @@ -93,7 +93,7 @@ AP_Compass_Backend *AP_Compass_MAG3110::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_Compass_MAG3110 *sensor = new AP_Compass_MAG3110(std::move(dev)); + AP_Compass_MAG3110 *sensor = NEW_NOTHROW AP_Compass_MAG3110(std::move(dev)); if (!sensor || !sensor->init(rotation)) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_MMC3416.cpp b/libraries/AP_Compass/AP_Compass_MMC3416.cpp index b8003869c599d0..f58b779e31e12a 100644 --- a/libraries/AP_Compass/AP_Compass_MMC3416.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC3416.cpp @@ -50,7 +50,7 @@ AP_Compass_Backend *AP_Compass_MMC3416::probe(AP_HAL::OwnPtr if (!dev) { return nullptr; } - AP_Compass_MMC3416 *sensor = new AP_Compass_MMC3416(std::move(dev), force_external, rotation); + AP_Compass_MMC3416 *sensor = NEW_NOTHROW AP_Compass_MMC3416(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -99,7 +99,7 @@ bool AP_Compass_MMC3416::init() set_dev_id(compass_instance, dev->get_bus_id()); - printf("Found a MMC3416 on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance); + printf("Found a MMC3416 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance); set_rotation(compass_instance, rotation); diff --git a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp index d671f3deb5b796..f932865ab32461 100644 --- a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp @@ -49,7 +49,7 @@ AP_Compass_Backend *AP_Compass_MMC5XX3::probe(AP_HAL::OwnPtr dev if (!dev) { return nullptr; } - AP_Compass_MMC5XX3 *sensor = new AP_Compass_MMC5XX3(std::move(dev), force_external, rotation); + AP_Compass_MMC5XX3 *sensor = NEW_NOTHROW AP_Compass_MMC5XX3(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -63,8 +63,8 @@ AP_Compass_MMC5XX3::AP_Compass_MMC5XX3(AP_HAL::OwnPtr _dev, enum Rotation _rotation) : dev(std::move(_dev)) , force_external(_force_external) - , rotation(_rotation) , have_initial_offset(false) + , rotation(_rotation) { } @@ -115,7 +115,7 @@ bool AP_Compass_MMC5XX3::init() set_dev_id(compass_instance, dev->get_bus_id()); - printf("Found a MMC5983 on 0x%x as compass %u\n", dev->get_bus_id(), compass_instance); + printf("Found a MMC5983 on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance); set_rotation(compass_instance, rotation); diff --git a/libraries/AP_Compass/AP_Compass_QMC5883L.cpp b/libraries/AP_Compass/AP_Compass_QMC5883L.cpp index ad1bea49892a36..5414cedb287479 100644 --- a/libraries/AP_Compass/AP_Compass_QMC5883L.cpp +++ b/libraries/AP_Compass/AP_Compass_QMC5883L.cpp @@ -67,7 +67,7 @@ AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr return nullptr; } - AP_Compass_QMC5883L *sensor = new AP_Compass_QMC5883L(std::move(dev),force_external,rotation); + AP_Compass_QMC5883L *sensor = NEW_NOTHROW AP_Compass_QMC5883L(std::move(dev),force_external,rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -123,7 +123,7 @@ bool AP_Compass_QMC5883L::init() set_dev_id(_instance, _dev->get_bus_id()); printf("%s found on bus %u id %u address 0x%02x\n", name, - _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address()); + _dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address()); set_rotation(_instance, _rotation); diff --git a/libraries/AP_Compass/AP_Compass_QMC5883P.cpp b/libraries/AP_Compass/AP_Compass_QMC5883P.cpp index 80d6e46f1c6997..fb84afdd3eb8a1 100644 --- a/libraries/AP_Compass/AP_Compass_QMC5883P.cpp +++ b/libraries/AP_Compass/AP_Compass_QMC5883P.cpp @@ -82,7 +82,7 @@ AP_Compass_Backend *AP_Compass_QMC5883P::probe(AP_HAL::OwnPtr if (!dev) { return nullptr; } - AP_Compass_QMC5883P *sensor = new AP_Compass_QMC5883P(std::move(dev),force_external,rotation); + AP_Compass_QMC5883P *sensor = NEW_NOTHROW AP_Compass_QMC5883P(std::move(dev),force_external,rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; @@ -134,7 +134,7 @@ bool AP_Compass_QMC5883P::init() set_dev_id(_instance, _dev->get_bus_id()); printf("%s found on bus %u id %u address 0x%02x\n", name, - _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address()); + _dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address()); set_rotation(_instance, _rotation); diff --git a/libraries/AP_Compass/AP_Compass_RM3100.cpp b/libraries/AP_Compass/AP_Compass_RM3100.cpp index 7e4fd7970b5819..6a64bd0d0b1171 100644 --- a/libraries/AP_Compass/AP_Compass_RM3100.cpp +++ b/libraries/AP_Compass/AP_Compass_RM3100.cpp @@ -74,7 +74,7 @@ AP_Compass_Backend *AP_Compass_RM3100::probe(AP_HAL::OwnPtr dev, if (!dev) { return nullptr; } - AP_Compass_RM3100 *sensor = new AP_Compass_RM3100(std::move(dev), force_external, rotation); + AP_Compass_RM3100 *sensor = NEW_NOTHROW AP_Compass_RM3100(std::move(dev), force_external, rotation); if (!sensor || !sensor->init()) { delete sensor; return nullptr; diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index c6c236db17d734..9d135be9dda0cb 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -76,6 +76,10 @@ #define AP_COMPASS_BMM150_DETECT_BACKENDS_ENABLED AP_COMPASS_BMM150_ENABLED #endif +#ifndef AP_COMPASS_BMM350_ENABLED +#define AP_COMPASS_BMM350_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_COMPASS_HMC5843_ENABLED #define AP_COMPASS_HMC5843_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index 57a374987c5718..60dd68c2c035a9 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -138,9 +138,21 @@ void CompassCalibrator::new_sample(const Vector3f& sample) bool CompassCalibrator::failed() { WITH_SEMAPHORE(state_sem); - return (cal_state.status == Status::FAILED || - cal_state.status == Status::BAD_ORIENTATION || - cal_state.status == Status::BAD_RADIUS); + switch (cal_state.status) { + case Status::FAILED: + case Status::BAD_ORIENTATION: + case Status::BAD_RADIUS: + return true; + case Status::SUCCESS: + case Status::NOT_STARTED: + case Status::WAITING_TO_START: + case Status::RUNNING_STEP_ONE: + case Status::RUNNING_STEP_TWO: + return false; + } + + // compiler guarantees we don't get here + return true; } @@ -461,10 +473,10 @@ bool CompassCalibrator::set_status(CompassCalibrator::Status status) _status = status; return true; - - default: - return false; }; + + // compiler guarantees we don't get here + return false; } bool CompassCalibrator::fit_acceptable() const @@ -1065,14 +1077,15 @@ bool CompassCalibrator::calculate_orientation(void) */ bool CompassCalibrator::fix_radius(void) { - if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) { + Location loc; + if (!AP::ahrs().get_location(loc) && !AP::ahrs().get_origin(loc)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MagCal: No location, fix_radius skipped"); // we don't have a position, leave scale factor as 0. This // will disable use of WMM in the EKF. Users can manually set // scale factor after calibration if it is known _params.scale_factor = 0; return true; } - const Location &loc = AP::gps().location(); float intensity; float declination; float inclination; diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 3b58159f346ac8..896d8c9a76e08a 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -34,7 +34,8 @@ class CompassCalibrator { // update the state machine and calculate offsets, diagonals and offdiagonals void update(); - // compass calibration states + // compass calibration states - these correspond to the mavlink + // MAG_CAL_STATUS enumeration enum class Status { NOT_STARTED = 0, WAITING_TO_START = 1, diff --git a/libraries/AP_Compass/Compass_learn.h b/libraries/AP_Compass/Compass_learn.h index f24de57fef434e..c4b1f9a9e8bcce 100644 --- a/libraries/AP_Compass/Compass_learn.h +++ b/libraries/AP_Compass/Compass_learn.h @@ -1,14 +1,12 @@ #pragma once -#include - /* compass learning using magnetic field tables from AP_Declination and GSF */ class CompassLearn { public: - CompassLearn(Compass &compass); + CompassLearn(class Compass &compass); // called on each compass read void update(void); diff --git a/libraries/AP_CustomRotations/AP_CustomRotations.cpp b/libraries/AP_CustomRotations/AP_CustomRotations.cpp index ad938c1b109577..86345121a835cb 100644 --- a/libraries/AP_CustomRotations/AP_CustomRotations.cpp +++ b/libraries/AP_CustomRotations/AP_CustomRotations.cpp @@ -139,7 +139,7 @@ AP_CustomRotation* AP_CustomRotations::get_rotation(Rotation r) } const uint8_t index = r - ROTATION_CUSTOM_1; if (rotations[index] == nullptr) { - rotations[index] = new AP_CustomRotation(params[index]); + rotations[index] = NEW_NOTHROW AP_CustomRotation(params[index]); // make sure param is enabled if custom rotation is used enable.set_and_save_ifchanged(1); } diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 986fe66bcf0251..4d6a1f9bd6ad6b 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #if APM_BUILD_TYPE(APM_BUILD_Replay) #include @@ -65,7 +66,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) _RFRN.lat = _home.lat; _RFRN.lng = _home.lng; _RFRN.alt = _home.alt; - _RFRN.EAS2TAS = AP::baro().get_EAS2TAS(); + _RFRN.EAS2TAS = ahrs.get_EAS2TAS(); _RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class(); _RFRN.fly_forward = ahrs.get_fly_forward(); _RFRN.takeoff_expected = ahrs.get_takeoff_expected(); @@ -90,9 +91,11 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) if (_airspeed) { _airspeed->start_frame(); } +#if AP_RANGEFINDER_ENABLED if (_rangefinder) { _rangefinder->start_frame(); } +#endif #if AP_BEACON_ENABLED if (_beacon) { _beacon->start_frame(); @@ -134,29 +137,31 @@ void AP_DAL::init_sensors(void) at the time we startup the EKF */ +#if AP_RANGEFINDER_ENABLED auto *rng = AP::rangefinder(); if (rng && rng->num_sensors() > 0) { - alloc_failed |= (_rangefinder = new AP_DAL_RangeFinder) == nullptr; + alloc_failed |= (_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder) == nullptr; } +#endif #if AP_AIRSPEED_ENABLED auto *aspeed = AP::airspeed(); if (aspeed != nullptr && aspeed->get_num_sensors() > 0) { - alloc_failed |= (_airspeed = new AP_DAL_Airspeed) == nullptr; + alloc_failed |= (_airspeed = NEW_NOTHROW AP_DAL_Airspeed) == nullptr; } #endif #if AP_BEACON_ENABLED auto *bcn = AP::beacon(); if (bcn != nullptr && bcn->enabled()) { - alloc_failed |= (_beacon = new AP_DAL_Beacon) == nullptr; + alloc_failed |= (_beacon = NEW_NOTHROW AP_DAL_Beacon) == nullptr; } #endif #if HAL_VISUALODOM_ENABLED auto *vodom = AP::visualodom(); if (vodom != nullptr && vodom->enabled()) { - alloc_failed |= (_visualodom = new AP_DAL_VisualOdom) == nullptr; + alloc_failed |= (_visualodom = NEW_NOTHROW AP_DAL_VisualOdom) == nullptr; } #endif @@ -267,10 +272,14 @@ int AP_DAL::snprintf(char* str, size_t size, const char *format, ...) const return res; } -void *AP_DAL::malloc_type(size_t size, Memory_Type mem_type) const +void *AP_DAL::malloc_type(size_t size, MemoryType mem_type) const { return hal.util->malloc_type(size, AP_HAL::Util::Memory_Type(mem_type)); } +void AP_DAL::free_type(void *ptr, size_t size, MemoryType mem_type) const +{ + return hal.util->free_type(ptr, size, AP_HAL::Util::Memory_Type(mem_type)); +} // map core number for replay uint8_t AP_DAL::logging_core(uint8_t c) const @@ -463,7 +472,9 @@ void AP_DAL::handle_message(const log_ROFH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _ROFH = msg; ekf2.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride); +#if EK3_FEATURE_OPTFLOW_FUSION ekf3.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride); +#endif } /* diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index d8c92e01b53912..64a16fff456087 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -65,7 +65,7 @@ class AP_DAL { static AP_DAL *get_singleton() { if (!_singleton) { - _singleton = new AP_DAL(); + _singleton = NEW_NOTHROW AP_DAL(); } return _singleton; } @@ -121,19 +121,23 @@ class AP_DAL { int snprintf(char* str, size_t size, const char *format, ...) const; // copied in AP_HAL/Util.h - enum Memory_Type { - MEM_DMA_SAFE, - MEM_FAST + enum class MemoryType : uint8_t { + DMA_SAFE = 0, + FAST = 1, }; - void *malloc_type(size_t size, enum Memory_Type mem_type) const; + void *malloc_type(size_t size, MemoryType mem_type) const; + void free_type(void *ptr, size_t size, MemoryType memtype) const; AP_DAL_InertialSensor &ins() { return _ins; } AP_DAL_Baro &baro() { return _baro; } AP_DAL_GPS &gps() { return _gps; } +#if AP_RANGEFINDER_ENABLED AP_DAL_RangeFinder *rangefinder() { return _rangefinder; } +#endif + AP_DAL_Airspeed *airspeed() { return _airspeed; } @@ -242,13 +246,13 @@ class AP_DAL { void handle_message(const log_RASH &msg) { if (_airspeed == nullptr) { - _airspeed = new AP_DAL_Airspeed; + _airspeed = NEW_NOTHROW AP_DAL_Airspeed; } _airspeed->handle_message(msg); } void handle_message(const log_RASI &msg) { if (_airspeed == nullptr) { - _airspeed = new AP_DAL_Airspeed; + _airspeed = NEW_NOTHROW AP_DAL_Airspeed; } _airspeed->handle_message(msg); } @@ -261,16 +265,20 @@ class AP_DAL { } void handle_message(const log_RRNH &msg) { +#if AP_RANGEFINDER_ENABLED if (_rangefinder == nullptr) { - _rangefinder = new AP_DAL_RangeFinder; + _rangefinder = NEW_NOTHROW AP_DAL_RangeFinder; } _rangefinder->handle_message(msg); +#endif } void handle_message(const log_RRNI &msg) { +#if AP_RANGEFINDER_ENABLED if (_rangefinder == nullptr) { - _rangefinder = new AP_DAL_RangeFinder; + _rangefinder = NEW_NOTHROW AP_DAL_RangeFinder; } _rangefinder->handle_message(msg); +#endif } void handle_message(const log_RGPH &msg) { @@ -293,7 +301,7 @@ class AP_DAL { void handle_message(const log_RBCH &msg) { #if AP_BEACON_ENABLED if (_beacon == nullptr) { - _beacon = new AP_DAL_Beacon; + _beacon = NEW_NOTHROW AP_DAL_Beacon; } _beacon->handle_message(msg); #endif @@ -301,7 +309,7 @@ class AP_DAL { void handle_message(const log_RBCI &msg) { #if AP_BEACON_ENABLED if (_beacon == nullptr) { - _beacon = new AP_DAL_Beacon; + _beacon = NEW_NOTHROW AP_DAL_Beacon; } _beacon->handle_message(msg); #endif @@ -309,7 +317,7 @@ class AP_DAL { void handle_message(const log_RVOH &msg) { #if HAL_VISUALODOM_ENABLED if (_visualodom == nullptr) { - _visualodom = new AP_DAL_VisualOdom; + _visualodom = NEW_NOTHROW AP_DAL_VisualOdom; } _visualodom->handle_message(msg); #endif @@ -358,7 +366,9 @@ class AP_DAL { AP_DAL_InertialSensor _ins; AP_DAL_Baro _baro; AP_DAL_GPS _gps; +#if AP_RANGEFINDER_ENABLED AP_DAL_RangeFinder *_rangefinder; +#endif AP_DAL_Compass _compass; AP_DAL_Airspeed *_airspeed; #if AP_BEACON_ENABLED diff --git a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp index e8332cb7ad41db..6d0425a2aa678f 100644 --- a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp +++ b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp @@ -18,9 +18,9 @@ void AP_DAL_InertialSensor::start_frame() const log_RISH old_RISH = _RISH; _RISH.loop_rate_hz = ins.get_loop_rate_hz(); - _RISH.primary_gyro = ins.get_primary_gyro(); + _RISH.first_usable_gyro = ins.get_first_usable_gyro(); _RISH.loop_delta_t = ins.get_loop_delta_t(); - _RISH.primary_accel = ins.get_primary_accel(); + _RISH.first_usable_accel = ins.get_first_usable_accel(); _RISH.accel_count = ins.get_accel_count(); _RISH.gyro_count = ins.get_gyro_count(); WRITE_REPLAY_BLOCK_IFCHANGED(RISH, _RISH, old_RISH); @@ -54,9 +54,9 @@ void AP_DAL_InertialSensor::start_frame() void AP_DAL_InertialSensor::update_filtered(uint8_t i) { if (!is_positive(alpha)) { - // we use a constant 20Hz for EKF filtered accel/gyro, making the EKF + // we use a constant 10Hz for EKF filtered accel/gyro, making the EKF // independent of the INS filter settings - const float cutoff_hz = 20.0; + const float cutoff_hz = 10.0; alpha = calc_lowpass_alpha_dt(get_loop_delta_t(), cutoff_hz); } if (is_positive(_RISI[i].delta_angle_dt)) { diff --git a/libraries/AP_DAL/AP_DAL_InertialSensor.h b/libraries/AP_DAL/AP_DAL_InertialSensor.h index aa0943b2b70303..44361e99bd3e2d 100644 --- a/libraries/AP_DAL/AP_DAL_InertialSensor.h +++ b/libraries/AP_DAL/AP_DAL_InertialSensor.h @@ -18,7 +18,7 @@ class AP_DAL_InertialSensor { // accel stuff uint8_t get_accel_count(void) const { return _RISH.accel_count; } - uint8_t get_primary_accel(void) const { return _RISH.primary_accel; }; + uint8_t get_first_usable_accel(void) const { return _RISH.first_usable_accel; }; bool use_accel(uint8_t instance) const { return _RISI[instance].use_accel; } const Vector3f &get_accel(uint8_t i) const { return accel_filtered[i]; } @@ -30,7 +30,7 @@ class AP_DAL_InertialSensor { // gyro stuff uint8_t get_gyro_count(void) const { return _RISH.gyro_count; } - uint8_t get_primary_gyro(void) const { return _RISH.primary_gyro; }; + uint8_t get_first_usable_gyro(void) const { return _RISH.first_usable_gyro; }; bool use_gyro(uint8_t instance) const { return _RISI[instance].use_gyro; } const Vector3f &get_gyro(uint8_t i) const { return gyro_filtered[i]; } diff --git a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp index d7cee48bfa70dc..9603a2d39499cc 100644 --- a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp +++ b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp @@ -3,6 +3,9 @@ #include #include + +#if AP_RANGEFINDER_ENABLED + #include "AP_DAL.h" #include #include @@ -12,8 +15,8 @@ AP_DAL_RangeFinder::AP_DAL_RangeFinder() { #if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay) _RRNH.num_sensors = AP::rangefinder()->num_sensors(); - _RRNI = new log_RRNI[_RRNH.num_sensors]; - _backend = new AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors]; + _RRNI = NEW_NOTHROW log_RRNI[_RRNH.num_sensors]; + _backend = NEW_NOTHROW AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors]; if (!_RRNI || !_backend) { goto failed; } @@ -22,7 +25,7 @@ AP_DAL_RangeFinder::AP_DAL_RangeFinder() } for (uint8_t i=0; i<_RRNH.num_sensors; i++) { // this avoids having to discard a const.... - _backend[i] = new AP_DAL_RangeFinder_Backend(_RRNI[i]); + _backend[i] = NEW_NOTHROW AP_DAL_RangeFinder_Backend(_RRNI[i]); if (!_backend[i]) { goto failed; } @@ -132,8 +135,8 @@ void AP_DAL_RangeFinder::handle_message(const log_RRNH &msg) { _RRNH = msg; if (_RRNH.num_sensors > 0 && _RRNI == nullptr) { - _RRNI = new log_RRNI[_RRNH.num_sensors]; - _backend = new AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors]; + _RRNI = NEW_NOTHROW log_RRNI[_RRNH.num_sensors]; + _backend = NEW_NOTHROW AP_DAL_RangeFinder_Backend *[_RRNH.num_sensors]; } } @@ -142,7 +145,9 @@ void AP_DAL_RangeFinder::handle_message(const log_RRNI &msg) if (_RRNI != nullptr && msg.instance < _RRNH.num_sensors) { _RRNI[msg.instance] = msg; if (_backend != nullptr && _backend[msg.instance] == nullptr) { - _backend[msg.instance] = new AP_DAL_RangeFinder_Backend(_RRNI[msg.instance]); + _backend[msg.instance] = NEW_NOTHROW AP_DAL_RangeFinder_Backend(_RRNI[msg.instance]); } } } + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_DAL/AP_DAL_RangeFinder.h b/libraries/AP_DAL/AP_DAL_RangeFinder.h index 47a4d14ef98ae6..5bb60392cb02d3 100644 --- a/libraries/AP_DAL/AP_DAL_RangeFinder.h +++ b/libraries/AP_DAL/AP_DAL_RangeFinder.h @@ -2,6 +2,8 @@ #include +#if AP_RANGEFINDER_ENABLED + #include class AP_RangeFinder_Backend; @@ -68,3 +70,5 @@ class AP_DAL_RangeFinder_Backend { struct log_RRNI &_RRNI; }; + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_DAL/AP_DAL_VisualOdom.h b/libraries/AP_DAL/AP_DAL_VisualOdom.h index 7d50bddfd7f2e3..04ba7d5dd7273e 100644 --- a/libraries/AP_DAL/AP_DAL_VisualOdom.h +++ b/libraries/AP_DAL/AP_DAL_VisualOdom.h @@ -18,7 +18,7 @@ class AP_DAL_VisualOdom { return RVOH.enabled; } - bool get_delay_ms() const { + uint16_t get_delay_ms() const { return RVOH.delay_ms; } diff --git a/libraries/AP_DAL/LogStructure.h b/libraries/AP_DAL/LogStructure.h index 14942768f35c1f..c8ef3435844384 100644 --- a/libraries/AP_DAL/LogStructure.h +++ b/libraries/AP_DAL/LogStructure.h @@ -40,19 +40,24 @@ LOG_RWOH_MSG, \ LOG_RBOH_MSG -// Replay Data Structures +// @LoggerMessage: RFRH +// @Description: Replay FRame Header struct log_RFRH { uint64_t time_us; uint32_t time_flying_ms; uint8_t _end; }; +// @LoggerMessage: RFRF +// @Description: Replay FRame data - Finished frame struct log_RFRF { uint8_t frame_types; uint8_t core_slow; uint8_t _end; }; +// @LoggerMessage: RFRN +// @Description: Replay FRame - aNother frame header struct log_RFRN { int32_t lat; int32_t lng; @@ -73,18 +78,20 @@ struct log_RFRN { uint8_t _end; }; -// Replay Data Structure - Inertial Sensor header +// @LoggerMessage: RISH +// @Description: Replay Inertial Sensor header struct log_RISH { uint16_t loop_rate_hz; - uint8_t primary_gyro; - uint8_t primary_accel; + uint8_t first_usable_gyro; + uint8_t first_usable_accel; float loop_delta_t; uint8_t accel_count; uint8_t gyro_count; uint8_t _end; }; -// Replay Data Structure - Inertial Sensor instance data +// @LoggerMessage: RISI +// @Description: Replay Inertial Sensor instance data struct log_RISI { Vector3f delta_velocity; Vector3f delta_angle; @@ -99,14 +106,14 @@ struct log_RISI { }; // @LoggerMessage: REV2 -// @Description: Replay Event +// @Description: Replay Event (EKF2) struct log_REV2 { uint8_t event; uint8_t _end; }; // @LoggerMessage: RSO2 -// @Description: Replay Set Origin event +// @Description: Replay Set Origin event (EKF2) struct log_RSO2 { int32_t lat; int32_t lng; @@ -115,7 +122,7 @@ struct log_RSO2 { }; // @LoggerMessage: RWA2 -// @Description: Replay set-default-airspeed event +// @Description: Replay set-default-airspeed event (EKF2) struct log_RWA2 { float airspeed; float uncertainty; @@ -123,8 +130,14 @@ struct log_RWA2 { }; // same structures for EKF3 +// @LoggerMessage: REV3 +// @Description: Replay Event (EKF3) #define log_REV3 log_REV2 +// @LoggerMessage: RSO3 +// @Description: Replay Set Origin event (EKF3) #define log_RSO3 log_RSO2 +// @LoggerMessage: RWA3 +// @Description: Replay set-default-airspeed event (EKF3) #define log_RWA3 log_RWA2 // @LoggerMessage: REY3 @@ -220,14 +233,16 @@ struct log_RGPJ { uint8_t _end; }; -// Replay Data Structure - Airspeed Sensor header +// @LoggerMessage: RASH +// @Description: Replay Airspeed Sensor Header struct log_RASH { uint8_t num_sensors; uint8_t primary; uint8_t _end; }; -// Replay Data Structure - Airspeed Sensor instance +// @LoggerMessage: RASI +// @Description: Replay Airspeed Sensor Instance data struct log_RASI { float airspeed; uint32_t last_update_ms; diff --git a/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp b/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp index 6a9371ada0b733..16e02dfadd9e64 100644 --- a/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp +++ b/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp @@ -4,6 +4,7 @@ // #include +#include #include #include diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 373d93bc62ecac..0a7a81689b802a 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -1,26 +1,41 @@ #include +#include "AP_DDS_config.h" #if AP_DDS_ENABLED #include #include #include +#include #include #include #include #include #include #include +#if AP_DDS_ARM_SERVER_ENABLED #include +# endif // AP_DDS_ARM_SERVER_ENABLED #include +#include #include +#if AP_DDS_ARM_SERVER_ENABLED #include "ardupilot_msgs/srv/ArmMotors.h" +#endif // AP_DDS_ARM_SERVER_ENABLED +#if AP_DDS_MODE_SWITCH_SERVER_ENABLED #include "ardupilot_msgs/srv/ModeSwitch.h" +#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED +#if AP_DDS_ARM_CHECK_SERVER_ENABLED +#include "std_srvs/srv/Trigger.h" +#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED +#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED +#include "ardupilot_msgs/srv/Takeoff.h" +#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED #if AP_EXTERNAL_CONTROL_ENABLED #include "AP_DDS_ExternalControl.h" -#endif +#endif // AP_EXTERNAL_CONTROL_ENABLED #include "AP_DDS_Frames.h" #include "AP_DDS_Client.h" @@ -28,26 +43,69 @@ #include "AP_DDS_Service_Table.h" #include "AP_DDS_External_Odom.h" +#define STRCPY(D,S) strncpy(D, S, ARRAY_SIZE(D)) + // Enable DDS at runtime by default static constexpr uint8_t ENABLED_BY_DEFAULT = 1; -static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10; -static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = 1000; -static constexpr uint16_t DELAY_IMU_TOPIC_MS = 5; -static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33; -static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = 33; -static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = 33; -static constexpr uint16_t DELAY_CLOCK_TOPIC_MS = 10; -static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = 1000; +#if AP_DDS_TIME_PUB_ENABLED +static constexpr uint16_t DELAY_TIME_TOPIC_MS = AP_DDS_DELAY_TIME_TOPIC_MS; +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED +static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS; +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED +static constexpr uint16_t DELAY_IMU_TOPIC_MS = AP_DDS_DELAY_IMU_TOPIC_MS; +#endif // AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED +static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS; +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED +static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS; +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED +static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_MS; +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED +static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS; +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED +static constexpr uint16_t DELAY_GOAL_TOPIC_MS = AP_DDS_DELAY_GOAL_TOPIC_MS ; +#endif // AP_DDS_GOAL_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED +static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS; +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS; +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED static constexpr uint16_t DELAY_PING_MS = 500; +#ifdef AP_DDS_STATUS_PUB_ENABLED +static constexpr uint16_t DELAY_STATUS_TOPIC_MS = AP_DDS_DELAY_STATUS_TOPIC_MS; +#endif // AP_DDS_STATUS_PUB_ENABLED // Define the subscriber data members, which are static class scope. // If these are created on the stack in the subscriber, // the AP_DDS_Client::on_topic frame size is exceeded. +#if AP_DDS_JOY_SUB_ENABLED sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {}; +#endif // AP_DDS_JOY_SUB_ENABLED tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {}; +#if AP_DDS_VEL_CTRL_ENABLED geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {}; +#endif // AP_DDS_VEL_CTRL_ENABLED +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED ardupilot_msgs_msg_GlobalPosition AP_DDS_Client::rx_global_position_control_topic {}; - +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED + +// Define the parameter server data members, which are static class scope. +// If these are created on the stack, then the AP_DDS_Client::on_request +// frame size is exceeded. +#if AP_DDS_PARAMETER_SERVER_ENABLED +rcl_interfaces_srv_SetParameters_Request AP_DDS_Client::set_parameter_request {}; +rcl_interfaces_srv_SetParameters_Response AP_DDS_Client::set_parameter_response {}; +rcl_interfaces_srv_GetParameters_Request AP_DDS_Client::get_parameters_request {}; +rcl_interfaces_srv_GetParameters_Response AP_DDS_Client::get_parameters_response {}; +rcl_interfaces_msg_Parameter AP_DDS_Client::param {}; +#endif const AP_Param::GroupInfo AP_DDS_Client::var_info[] { @@ -74,9 +132,44 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { #endif + // @Param: _DOMAIN_ID + // @DisplayName: DDS DOMAIN ID + // @Description: Set the ROS_DOMAIN_ID + // @Range: 0 232 + // @RebootRequired: True + // @User: Standard + AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0), + + // @Param: _TIMEOUT_MS + // @DisplayName: DDS ping timeout + // @Description: The time in milliseconds the DDS client will wait for a response from the XRCE agent before reattempting. + // @Units: ms + // @Range: 1 10000 + // @RebootRequired: True + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_TIMEOUT_MS", 5, AP_DDS_Client, ping_timeout_ms, 1000), + + // @Param: _MAX_RETRY + // @DisplayName: DDS ping max attempts + // @Description: The maximum number of times the DDS client will attempt to ping the XRCE agent before exiting. + // @Range: 1 100 + // @RebootRequired: True + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_MAX_RETRY", 6, AP_DDS_Client, ping_max_retry, 10), + AP_GROUPEND }; +static void initialize(geometry_msgs_msg_Quaternion& q) +{ + q.x = 0.0; + q.y = 0.0; + q.z = 0.0; + q.w = 1.0; +} + AP_DDS_Client::~AP_DDS_Client() { // close transport @@ -89,6 +182,7 @@ AP_DDS_Client::~AP_DDS_Client() } } +#if AP_DDS_TIME_PUB_ENABLED void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) { uint64_t utc_usec; @@ -99,7 +193,9 @@ void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) msg.nanosec = (utc_usec % 1000000ULL) * 1000UL; } +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_NAVSATFIX_PUB_ENABLED bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) { // Add a lambda that takes in navsatfix msg and populates the cov @@ -107,11 +203,6 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i // https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/ // constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; }; - // assert(instance >= GPS_MAX_RECEIVERS); - if (instance >= GPS_MAX_RECEIVERS) { - return false; - } - auto &gps = AP::gps(); WITH_SEMAPHORE(gps.get_semaphore()); @@ -132,7 +223,8 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, WGS_84_FRAME_ID); + static_assert(GPS_MAX_RECEIVERS <= 9, "GPS_MAX_RECEIVERS is greater than 9"); + hal.util->snprintf(msg.header.frame_id, 2, "%u", instance); msg.status.service = 0; // SERVICE_GPS msg.status.status = -1; // STATUS_NO_FIX @@ -191,7 +283,9 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i return true; } +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_STATIC_TF_PUB_ENABLED void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg) { msg.transforms_size = 0; @@ -206,8 +300,8 @@ void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg) char gps_frame_id[16]; //! @todo should GPS frame ID's be 0 or 1 indexed in ROS? hal.util->snprintf(gps_frame_id, sizeof(gps_frame_id), "GPS_%u", i); - strcpy(msg.transforms[i].header.frame_id, BASE_LINK_FRAME_ID); - strcpy(msg.transforms[i].child_frame_id, gps_frame_id); + STRCPY(msg.transforms[i].header.frame_id, BASE_LINK_FRAME_ID); + STRCPY(msg.transforms[i].child_frame_id, gps_frame_id); // The body-frame offsets // X - Forward // Y - Right @@ -226,18 +320,26 @@ void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg) msg.transforms[i].transform.translation.y = -1 * offset[1]; msg.transforms[i].transform.translation.z = -1 * offset[2]; + // Ensure rotation is initialized. + initialize(msg.transforms[i].transform.rotation); + msg.transforms_size++; } } +#endif // AP_DDS_STATIC_TF_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance) { if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) { return; } + static_assert(AP_BATT_MONITOR_MAX_INSTANCES <= 99, "AP_BATT_MONITOR_MAX_INSTANCES is greater than 99"); update_topic(msg.header.stamp); + hal.util->snprintf(msg.header.frame_id, 2, "%u", instance); + auto &battery = AP::battery(); if (!battery.healthy(instance)) { @@ -272,9 +374,9 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_ if (battery.current_amps(current, instance)) { if (percentage == 100) { msg.power_supply_status = 4; //POWER_SUPPLY_STATUS_FULL - } else if (current < 0.0) { + } else if (is_negative(current)) { msg.power_supply_status = 1; //POWER_SUPPLY_STATUS_CHARGING - } else if (current > 0.0) { + } else if (is_positive(current)) { msg.power_supply_status = 2; //POWER_SUPPLY_STATUS_DISCHARGING } else { msg.power_supply_status = 3; //POWER_SUPPLY_STATUS_NOT_CHARGING @@ -288,15 +390,20 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_ msg.power_supply_technology = 0; //POWER_SUPPLY_TECHNOLOGY_UNKNOWN if (battery.has_cell_voltages(instance)) { - const uint16_t* cellVoltages = battery.get_cell_voltages(instance).cells; - std::copy(cellVoltages, cellVoltages + AP_BATT_MONITOR_CELLS_MAX, msg.cell_voltage); + const auto &cells = battery.get_cell_voltages(instance); + const uint8_t ncells_max = MIN(ARRAY_SIZE(msg.cell_voltage), ARRAY_SIZE(cells.cells)); + for (uint8_t i=0; i< ncells_max; i++) { + msg.cell_voltage[i] = cells.cells[i] * 0.001; + } } } +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg) { update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, BASE_LINK_FRAME_ID); + STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID); auto &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -337,13 +444,17 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg) msg.pose.orientation.x = orientation[1]; msg.pose.orientation.y = orientation[2]; msg.pose.orientation.z = orientation[3]; + } else { + initialize(msg.pose.orientation); } } +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED void AP_DDS_Client::update_topic(geometry_msgs_msg_TwistStamped& msg) { update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, BASE_LINK_FRAME_ID); + STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID); auto &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -381,11 +492,41 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_TwistStamped& msg) msg.twist.angular.y = -angular_velocity[1]; msg.twist.angular.z = -angular_velocity[2]; } +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED +bool AP_DDS_Client::update_topic(geometry_msgs_msg_Vector3Stamped& msg) +{ + update_topic(msg.header.stamp); + STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID); + auto &ahrs = AP::ahrs(); + WITH_SEMAPHORE(ahrs.get_semaphore()); + // In ROS REP 103, axis orientation uses the following convention: + // X - Forward + // Y - Left + // Z - Up + // https://www.ros.org/reps/rep-0103.html#axis-orientation + // The true airspeed data is received from AP_AHRS in body-frame + // X - Forward + // Y - Right + // Z - Down + // As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z + Vector3f true_airspeed_vec_bf; + bool is_airspeed_available {false}; + if (ahrs.airspeed_vector_true(true_airspeed_vec_bf)) { + msg.vector.x = true_airspeed_vec_bf[0]; + msg.vector.y = -true_airspeed_vec_bf[1]; + msg.vector.z = -true_airspeed_vec_bf[2]; + is_airspeed_available = true; + } + return is_airspeed_available; +} +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) { update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, BASE_LINK_FRAME_ID); + STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID); auto &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -416,13 +557,50 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) msg.pose.orientation.x = orientation[1]; msg.pose.orientation.y = orientation[2]; msg.pose.orientation.z = orientation[3]; + } else { + initialize(msg.pose.orientation); + } +} +#endif // AP_DDS_GEOPOSE_PUB_ENABLED + +#if AP_DDS_GOAL_PUB_ENABLED +bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg) +{ + const auto &vehicle = AP::vehicle(); + update_topic(msg.header.stamp); + Location target_loc; + // Exit if no target is available. + if (!vehicle->get_target_location(target_loc)) { + return false; + } + target_loc.change_alt_frame(Location::AltFrame::ABSOLUTE); + msg.position.latitude = target_loc.lat * 1e-7; + msg.position.longitude = target_loc.lng * 1e-7; + msg.position.altitude = target_loc.alt * 1e-2; + + // Check whether the goal has changed or if the topic has never been published. + const double tolerance_lat_lon = 1e-8; // One order of magnitude smaller than the target's resolution. + const double distance_alt = 1e-3; + if (abs(msg.position.latitude - prev_goal_msg.position.latitude) > tolerance_lat_lon || + abs(msg.position.longitude - prev_goal_msg.position.longitude) > tolerance_lat_lon || + abs(msg.position.altitude - prev_goal_msg.position.altitude) > distance_alt || + prev_goal_msg.header.stamp.sec == 0 ) { + update_topic(prev_goal_msg.header.stamp); + prev_goal_msg.position.latitude = msg.position.latitude; + prev_goal_msg.position.longitude = msg.position.longitude; + prev_goal_msg.position.altitude = msg.position.altitude; + return true; + } else { + return false; } } +#endif // AP_DDS_GOAL_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg) { update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, BASE_LINK_NED_FRAME_ID); + STRCPY(msg.header.frame_id, BASE_LINK_NED_FRAME_ID); auto &imu = AP::ins(); auto &ahrs = AP::ahrs(); @@ -435,6 +613,8 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg) msg.orientation.y = orientation[1]; msg.orientation.z = orientation[2]; msg.orientation.w = orientation[3]; + } else { + initialize(msg.orientation); } msg.orientation_covariance[0] = -1; @@ -454,16 +634,20 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg) msg.angular_velocity_covariance[0] = -1; msg.linear_acceleration_covariance[0] = -1; } +#endif // AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED void AP_DDS_Client::update_topic(rosgraph_msgs_msg_Clock& msg) { update_topic(msg.clock); } +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg) { update_topic(msg.header.stamp); - strcpy(msg.header.frame_id, BASE_LINK_FRAME_ID); + STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID); auto &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -477,7 +661,60 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg) msg.position.altitude = ekf_origin.alt * 0.01; } } +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_STATUS_PUB_ENABLED +bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg) +{ + // Fill the new message. + const auto &vehicle = AP::vehicle(); + const auto &battery = AP::battery(); + msg.vehicle_type = static_cast(AP::fwversion().vehicle_type); + msg.armed = hal.util->get_soft_armed(); + msg.mode = vehicle->get_mode(); + msg.flying = vehicle->get_likely_flying(); + msg.external_control = true; // Always true for now. To be filled after PR#28429. + uint8_t fs_iter = 0; + msg.failsafe_size = 0; + if (rc().in_rc_failsafe()) { + msg.failsafe[fs_iter++] = FS_RADIO; + } + if (battery.has_failsafed()) { + msg.failsafe[fs_iter++] = FS_BATTERY; + } + // TODO: replace flag with function. + if (AP_Notify::flags.failsafe_gcs) { + msg.failsafe[fs_iter++] = FS_GCS; + } + // TODO: replace flag with function. + if (AP_Notify::flags.failsafe_ekf) { + msg.failsafe[fs_iter++] = FS_EKF; + } + msg.failsafe_size = fs_iter; + + // Compare with the previous one. + bool is_message_changed {false}; + is_message_changed |= (last_status_msg_.flying != msg.flying); + is_message_changed |= (last_status_msg_.armed != msg.armed); + is_message_changed |= (last_status_msg_.mode != msg.mode); + is_message_changed |= (last_status_msg_.vehicle_type != msg.vehicle_type); + is_message_changed |= (last_status_msg_.failsafe_size != msg.failsafe_size); + is_message_changed |= (last_status_msg_.external_control != msg.external_control); + + if ( is_message_changed ) { + last_status_msg_.flying = msg.flying; + last_status_msg_.armed = msg.armed; + last_status_msg_.mode = msg.mode; + last_status_msg_.vehicle_type = msg.vehicle_type; + last_status_msg_.failsafe_size = msg.failsafe_size; + last_status_msg_.external_control = msg.external_control; + update_topic(msg.header.stamp); + return true; + } else { + return false; + } +} +#endif // AP_DDS_STATUS_PUB_ENABLED /* start the DDS thread */ @@ -519,6 +756,7 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin (void) stream_id; (void) length; switch (object_id.id) { +#if AP_DDS_JOY_SUB_ENABLED case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: { const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &rx_joy_topic); @@ -527,14 +765,28 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin } if (rx_joy_topic.axes_size >= 4) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received sensor_msgs/Joy: %f, %f, %f, %f", - msg_prefix, rx_joy_topic.axes[0], rx_joy_topic.axes[1], rx_joy_topic.axes[2], rx_joy_topic.axes[3]); - // TODO implement joystick RC control to AP - } else { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received sensor_msgs/Joy. Axes size must be >= 4", msg_prefix); + const uint32_t t_now = AP_HAL::millis(); + + for (uint8_t i = 0; i < MIN(8U, rx_joy_topic.axes_size); i++) { + // Ignore channel override if NaN. + if (std::isnan(rx_joy_topic.axes[i])) { + // Setting the RC override to 0U releases the channel back to the RC. + RC_Channels::set_override(i, 0U, t_now); + } else { + const uint16_t mapped_data = static_cast( + linear_interpolate(rc().channel(i)->get_radio_min(), + rc().channel(i)->get_radio_max(), + rx_joy_topic.axes[i], + -1.0, 1.0)); + RC_Channels::set_override(i, mapped_data, t_now); + } + } + } break; } +#endif // AP_DDS_JOY_SUB_ENABLED +#if AP_DDS_DYNAMIC_TF_SUB_ENABLED case topics[to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB)].dr_id.id: { const bool success = tf2_msgs_msg_TFMessage_deserialize_topic(ub, &rx_dynamic_transforms_topic); if (success == false) { @@ -551,12 +803,13 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin } break; } +#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED +#if AP_DDS_VEL_CTRL_ENABLED case topics[to_underlying(TopicIndex::VELOCITY_CONTROL_SUB)].dr_id.id: { const bool success = geometry_msgs_msg_TwistStamped_deserialize_topic(ub, &rx_velocity_control_topic); if (success == false) { break; } - #if AP_EXTERNAL_CONTROL_ENABLED if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) { // TODO #23430 handle velocity control failure through rosout, throttled. @@ -564,6 +817,8 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin #endif // AP_EXTERNAL_CONTROL_ENABLED break; } +#endif // AP_DDS_VEL_CTRL_ENABLED +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED case topics[to_underlying(TopicIndex::GLOBAL_POSITION_SUB)].dr_id.id: { const bool success = ardupilot_msgs_msg_GlobalPosition_deserialize_topic(ub, &rx_global_position_control_topic); if (success == false) { @@ -577,6 +832,7 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin #endif // AP_EXTERNAL_CONTROL_ENABLED break; } +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED } } @@ -595,6 +851,7 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u (void) request_id; (void) length; switch (object_id.id) { +#if AP_DDS_ARM_SERVER_ENABLED case services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id: { ardupilot_msgs_srv_ArmMotors_Request arm_motors_request; ardupilot_msgs_srv_ArmMotors_Response arm_motors_response; @@ -604,7 +861,13 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for %sing received", msg_prefix, arm_motors_request.arm ? "arm" : "disarm"); - arm_motors_response.result = arm_motors_request.arm ? AP::arming().arm(AP_Arming::Method::DDS) : AP::arming().disarm(AP_Arming::Method::DDS); +#if AP_EXTERNAL_CONTROL_ENABLED + const bool do_checks = true; + arm_motors_response.result = arm_motors_request.arm ? AP_DDS_External_Control::arm(AP_Arming::Method::DDS, do_checks) : AP_DDS_External_Control::disarm(AP_Arming::Method::DDS, do_checks); + if (!arm_motors_response.result) { + // TODO #23430 handle arm failure through rosout, throttled. + } +#endif // AP_EXTERNAL_CONTROL_ENABLED const uxrObjectId replier_id = { .id = services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id, @@ -624,6 +887,8 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Arming/Disarming : %s", msg_prefix, arm_motors_response.result ? "SUCCESS" : "FAIL"); break; } +#endif // AP_DDS_ARM_SERVER_ENABLED +#if AP_DDS_MODE_SWITCH_SERVER_ENABLED case services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id: { ardupilot_msgs_srv_ModeSwitch_Request mode_switch_request; ardupilot_msgs_srv_ModeSwitch_Response mode_switch_response; @@ -652,6 +917,257 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Mode Switch : %s", msg_prefix, mode_switch_response.status ? "SUCCESS" : "FAIL"); break; } +#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED +#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED + case services[to_underlying(ServiceIndex::TAKEOFF)].rep_id: { + ardupilot_msgs_srv_Takeoff_Request takeoff_request; + ardupilot_msgs_srv_Takeoff_Response takeoff_response; + const bool deserialize_success = ardupilot_msgs_srv_Takeoff_Request_deserialize_topic(ub, &takeoff_request); + if (deserialize_success == false) { + break; + } + takeoff_response.status = AP::vehicle()->start_takeoff(takeoff_request.alt); + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::TAKEOFF)].rep_id, + .type = UXR_REPLIER_ID + }; + + uint8_t reply_buffer[8] {}; + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer)); + const bool serialize_success = ardupilot_msgs_srv_Takeoff_Response_serialize_topic(&reply_ub, &takeoff_response); + if (serialize_success == false) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Takeoff : %s", msg_prefix, takeoff_response.status ? "SUCCESS" : "FAIL"); + break; + } +#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED +#if AP_DDS_ARM_CHECK_SERVER_ENABLED + case services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id: { + std_srvs_srv_Trigger_Request prearm_check_request; + std_srvs_srv_Trigger_Response prearm_check_response; + const bool deserialize_success = std_srvs_srv_Trigger_Request_deserialize_topic(ub, &prearm_check_request); + if (deserialize_success == false) { + break; + } + prearm_check_response.success = AP::arming().pre_arm_checks(false); + STRCPY(prearm_check_response.message, prearm_check_response.success ? "Vehicle is Armable" : "Vehicle is Not Armable"); + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::PREARM_CHECK)].rep_id, + .type = UXR_REPLIER_ID + }; + + uint8_t reply_buffer[sizeof(prearm_check_response.message) + 1] {}; + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer)); + const bool serialize_success = std_srvs_srv_Trigger_Response_serialize_topic(&reply_ub, &prearm_check_response); + if (serialize_success == false) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + break; + } +#endif //AP_DDS_ARM_CHECK_SERVER_ENABLED +#if AP_DDS_PARAMETER_SERVER_ENABLED + case services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id: { + const bool deserialize_success = rcl_interfaces_srv_SetParameters_Request_deserialize_topic(ub, &set_parameter_request); + if (deserialize_success == false) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Set Parameters Request : Failed to deserialize request.", msg_prefix); + break; + } + + if (set_parameter_request.parameters_size > 8U) { + break; + } + + // Set parameters and responses for each one requested + set_parameter_response.results_size = set_parameter_request.parameters_size; + for (size_t i = 0; i < set_parameter_request.parameters_size; i++) { + param = set_parameter_request.parameters[i]; + + enum ap_var_type var_type; + + // set parameter + AP_Param *vp; + char param_key[AP_MAX_NAME_SIZE + 1]; + strncpy(param_key, (char *)param.name, AP_MAX_NAME_SIZE); + param_key[AP_MAX_NAME_SIZE] = 0; + + // Currently only integer and double value types can be set. + // The following parameter value types are not handled: + // bool, string, byte_array, bool_array, integer_array, double_array and string_array + bool param_isnan = true; + bool param_isinf = true; + float param_value; + switch (param.value.type) { + case PARAMETER_INTEGER: { + param_isnan = isnan(param.value.integer_value); + param_isinf = isinf(param.value.integer_value); + param_value = float(param.value.integer_value); + break; + } + case PARAMETER_DOUBLE: { + param_isnan = isnan(param.value.double_value); + param_isinf = isinf(param.value.double_value); + param_value = float(param.value.double_value); + break; + } + default: { + break; + } + } + + // find existing param to get the old value + uint16_t parameter_flags = 0; + vp = AP_Param::find(param_key, &var_type, ¶meter_flags); + if (vp == nullptr || param_isnan || param_isinf) { + set_parameter_response.results[i].successful = false; + strncpy(set_parameter_response.results[i].reason, "Parameter not found", sizeof(set_parameter_response.results[i].reason)); + continue; + } + + // Add existing parameter checks used in GCS_Param.cpp + if (parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) { + // The user can set BRD_OPTIONS to enable set of internal + // parameters, for developer testing or unusual use cases + if (AP_BoardConfig::allow_set_internal_parameters()) { + parameter_flags &= ~AP_PARAM_FLAG_INTERNAL_USE_ONLY; + } + } + + if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) { + set_parameter_response.results[i].successful = false; + strncpy(set_parameter_response.results[i].reason, "Parameter is read only",sizeof(set_parameter_response.results[i].reason)); + continue; + } + + // Set and save the value if it changed + bool force_save = vp->set_and_save_by_name_ifchanged(param_key, param_value); + + if (force_save && (parameter_flags & AP_PARAM_FLAG_ENABLE)) { + AP_Param::invalidate_count(); + } + + set_parameter_response.results[i].successful = true; + strncpy(set_parameter_response.results[i].reason, "Parameter accepted", sizeof(set_parameter_response.results[i].reason)); + } + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::SET_PARAMETERS)].rep_id, + .type = UXR_REPLIER_ID + }; + + const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U); + uint8_t reply_buffer[reply_size]; + memset(reply_buffer, 0, reply_size * sizeof(uint8_t)); + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, reply_size); + const bool serialize_success = rcl_interfaces_srv_SetParameters_Response_serialize_topic(&reply_ub, &set_parameter_response); + if (serialize_success == false) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + bool successful_params = true; + for (size_t i = 0; i < set_parameter_response.results_size; i++) { + // Check that all the parameters were set successfully + successful_params &= set_parameter_response.results[i].successful; + } + GCS_SEND_TEXT(successful_params ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Set Parameters Request : %s", msg_prefix, successful_params ? "SUCCESSFUL" : "ONE OR MORE PARAMS FAILED" ); + break; + } + case services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id: { + const bool deserialize_success = rcl_interfaces_srv_GetParameters_Request_deserialize_topic(ub, &get_parameters_request); + if (deserialize_success == false) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Get Parameters Request : Failed to deserialize request.", msg_prefix); + break; + } + + if (get_parameters_request.names_size > 8U) { + break; + } + + bool successful_read = true; + get_parameters_response.values_size = get_parameters_request.names_size; + for (size_t i = 0; i < get_parameters_request.names_size; i++) { + enum ap_var_type var_type; + + AP_Param *vp; + char param_key[AP_MAX_NAME_SIZE + 1]; + strncpy(param_key, (char *)get_parameters_request.names[i], AP_MAX_NAME_SIZE); + param_key[AP_MAX_NAME_SIZE] = 0; + + vp = AP_Param::find(param_key, &var_type); + if (vp == nullptr) { + get_parameters_response.values[i].type = PARAMETER_NOT_SET; + successful_read &= false; + continue; + } + + switch (var_type) { + case AP_PARAM_INT8: { + get_parameters_response.values[i].type = PARAMETER_INTEGER; + get_parameters_response.values[i].integer_value = ((AP_Int8 *)vp)->get(); + successful_read &= true; + break; + } + case AP_PARAM_INT16: { + get_parameters_response.values[i].type = PARAMETER_INTEGER; + get_parameters_response.values[i].integer_value = ((AP_Int16 *)vp)->get(); + successful_read &= true; + break; + } + case AP_PARAM_INT32: { + get_parameters_response.values[i].type = PARAMETER_INTEGER; + get_parameters_response.values[i].integer_value = ((AP_Int32 *)vp)->get(); + successful_read &= true; + break; + } + case AP_PARAM_FLOAT: { + get_parameters_response.values[i].type = PARAMETER_DOUBLE; + get_parameters_response.values[i].double_value = vp->cast_to_float(var_type); + successful_read &= true; + break; + } + default: { + get_parameters_response.values[i].type = PARAMETER_NOT_SET; + successful_read &= false; + break; + } + } + } + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::GET_PARAMETERS)].rep_id, + .type = UXR_REPLIER_ID + }; + + const uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U); + uint8_t reply_buffer[reply_size]; + memset(reply_buffer, 0, reply_size * sizeof(uint8_t)); + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, reply_size); + const bool serialize_success = rcl_interfaces_srv_GetParameters_Response_serialize_topic(&reply_ub, &get_parameters_response); + if (serialize_success == false) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + + GCS_SEND_TEXT(successful_read ? MAV_SEVERITY_INFO : MAV_SEVERITY_WARNING, "%s Get Parameters Request : %s", msg_prefix, successful_read ? "SUCCESSFUL" : "ONE OR MORE PARAM NOT FOUND"); + break; + } +#endif // AP_DDS_PARAMETER_SERVER_ENABLED } } @@ -672,9 +1188,7 @@ void AP_DDS_Client::main_loop(void) } // check ping - const uint64_t ping_timeout_ms{1000}; - const uint8_t ping_max_attempts{10}; - if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { + if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_retry)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s No ping response, exiting", msg_prefix); return; } @@ -687,8 +1201,10 @@ void AP_DDS_Client::main_loop(void) connected = true; GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization passed", msg_prefix); +#if AP_DDS_STATIC_TF_PUB_ENABLED populate_static_transforms(tx_static_transforms_topic); write_static_transforms(); +#endif // AP_DDS_STATIC_TF_PUB_ENABLED uint64_t last_ping_ms{0}; uint8_t num_pings_missed{0}; @@ -774,8 +1290,8 @@ bool AP_DDS_Client::init_session() } // setup reliable stream buffers - input_reliable_stream = new uint8_t[DDS_BUFFER_SIZE]; - output_reliable_stream = new uint8_t[DDS_BUFFER_SIZE]; + input_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE]; + output_reliable_stream = NEW_NOTHROW uint8_t[DDS_BUFFER_SIZE]; if (input_reliable_stream == nullptr || output_reliable_stream == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Allocation failed", msg_prefix); return false; @@ -798,8 +1314,9 @@ bool AP_DDS_Client::create() .id = 0x01, .type = UXR_PARTICIPANT_ID }; - const char* participant_ref = "participant_profile"; - const auto participant_req_id = uxr_buffer_create_participant_ref(&session, reliable_out, participant_id,0,participant_ref,UXR_REPLACE); + const char* participant_name = AP_DDS_PARTICIPANT_NAME; + const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id, + static_cast(domain_id), participant_name, UXR_REPLACE); //Participant requests constexpr uint8_t nRequestsParticipant = 1; @@ -820,8 +1337,8 @@ bool AP_DDS_Client::create() .id = topics[i].topic_id, .type = UXR_TOPIC_ID }; - const char* topic_ref = topics[i].topic_profile_label; - const auto topic_req_id = uxr_buffer_create_topic_ref(&session,reliable_out,topic_id,participant_id,topic_ref,UXR_REPLACE); + const auto topic_req_id = uxr_buffer_create_topic_bin(&session, reliable_out, topic_id, + participant_id, topics[i].topic_name, topics[i].type_name, UXR_REPLACE); // Status requests constexpr uint8_t nRequests = 3; @@ -829,18 +1346,18 @@ bool AP_DDS_Client::create() constexpr uint16_t requestTimeoutMs = nRequests * maxTimeMsPerRequestMs; uint8_t status[nRequests]; - if (strlen(topics[i].dw_profile_label) > 0) { + if (topics[i].topic_rw == Topic_rw::DataWriter) { // Publisher const uxrObjectId pub_id = { .id = topics[i].pub_id, .type = UXR_PUBLISHER_ID }; - const char* pub_xml = ""; - const auto pub_req_id = uxr_buffer_create_publisher_xml(&session,reliable_out,pub_id,participant_id,pub_xml,UXR_REPLACE); + const auto pub_req_id = uxr_buffer_create_publisher_bin(&session, reliable_out, pub_id, + participant_id, UXR_REPLACE); // Data Writer - const char* data_writer_ref = topics[i].dw_profile_label; - const auto dwriter_req_id = uxr_buffer_create_datawriter_ref(&session,reliable_out,topics[i].dw_id,pub_id,data_writer_ref,UXR_REPLACE); + const auto dwriter_req_id = uxr_buffer_create_datawriter_bin(&session, reliable_out, topics[i].dw_id, + pub_id, topic_id, topics[i].qos, UXR_REPLACE); // save the request statuses requests[0] = topic_req_id; @@ -857,18 +1374,18 @@ bool AP_DDS_Client::create() } else { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Pub/Writer session pass for index '%u'", msg_prefix, i); } - } else if (strlen(topics[i].dr_profile_label) > 0) { + } else if (topics[i].topic_rw == Topic_rw::DataReader) { // Subscriber const uxrObjectId sub_id = { .id = topics[i].sub_id, .type = UXR_SUBSCRIBER_ID }; - const char* sub_xml = ""; - const auto sub_req_id = uxr_buffer_create_subscriber_xml(&session,reliable_out,sub_id,participant_id,sub_xml,UXR_REPLACE); + const auto sub_req_id = uxr_buffer_create_subscriber_bin(&session, reliable_out, sub_id, + participant_id, UXR_REPLACE); // Data Reader - const char* data_reader_ref = topics[i].dr_profile_label; - const auto dreader_req_id = uxr_buffer_create_datareader_ref(&session,reliable_out,topics[i].dr_id,sub_id,data_reader_ref,UXR_REPLACE); + const auto dreader_req_id = uxr_buffer_create_datareader_bin(&session, reliable_out, topics[i].dr_id, + sub_id, topic_id, topics[i].qos, UXR_REPLACE); // save the request statuses requests[0] = topic_req_id; @@ -895,13 +1412,14 @@ bool AP_DDS_Client::create() constexpr uint16_t requestTimeoutMs = maxTimeMsPerRequestMs; - if (strlen(services[i].rep_profile_label) > 0) { + if (services[i].service_rr == Service_rr::Replier) { const uxrObjectId rep_id = { .id = services[i].rep_id, .type = UXR_REPLIER_ID }; - const char* replier_ref = services[i].rep_profile_label; - const auto replier_req_id = uxr_buffer_create_replier_ref(&session, reliable_out, rep_id, participant_id, replier_ref, UXR_REPLACE); + const auto replier_req_id = uxr_buffer_create_replier_bin(&session, reliable_out, rep_id, + participant_id, services[i].service_name, services[i].request_type, services[i].reply_type, + services[i].request_topic_name, services[i].reply_topic_name, services[i].qos, UXR_REPLACE); uint16_t request = replier_req_id; uint8_t status; @@ -916,7 +1434,7 @@ bool AP_DDS_Client::create() uxr_buffer_request_data(&session, reliable_out, rep_id, reliable_in, &delivery_control); } - } else if (strlen(services[i].req_profile_label) > 0) { + } else if (services[i].service_rr == Service_rr::Requester) { // TODO : Add Similar Code for Requester Profile } } @@ -939,6 +1457,7 @@ void AP_DDS_Client::write_time_topic() } } +#if AP_DDS_NAVSATFIX_PUB_ENABLED void AP_DDS_Client::write_nav_sat_fix_topic() { WITH_SEMAPHORE(csem); @@ -953,7 +1472,9 @@ void AP_DDS_Client::write_nav_sat_fix_topic() } } } +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_STATIC_TF_PUB_ENABLED void AP_DDS_Client::write_static_transforms() { WITH_SEMAPHORE(csem); @@ -968,7 +1489,9 @@ void AP_DDS_Client::write_static_transforms() } } } +#endif // AP_DDS_STATIC_TF_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED void AP_DDS_Client::write_battery_state_topic() { WITH_SEMAPHORE(csem); @@ -983,7 +1506,9 @@ void AP_DDS_Client::write_battery_state_topic() } } } +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED void AP_DDS_Client::write_local_pose_topic() { WITH_SEMAPHORE(csem); @@ -998,7 +1523,9 @@ void AP_DDS_Client::write_local_pose_topic() } } } +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED void AP_DDS_Client::write_tx_local_velocity_topic() { WITH_SEMAPHORE(csem); @@ -1013,7 +1540,24 @@ void AP_DDS_Client::write_tx_local_velocity_topic() } } } - +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED +void AP_DDS_Client::write_tx_local_airspeed_topic() +{ + WITH_SEMAPHORE(csem); + if (connected) { + ucdrBuffer ub {}; + const uint32_t topic_size = geometry_msgs_msg_Vector3Stamped_size_of_topic(&tx_local_airspeed_topic, 0); + uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB)].dw_id, &ub, topic_size); + const bool success = geometry_msgs_msg_Vector3Stamped_serialize_topic(&ub, &tx_local_airspeed_topic); + if (!success) { + // TODO sometimes serialization fails on bootup. Determine why. + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + } + } +} +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED void AP_DDS_Client::write_imu_topic() { WITH_SEMAPHORE(csem); @@ -1028,7 +1572,9 @@ void AP_DDS_Client::write_imu_topic() } } } +#endif // AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED void AP_DDS_Client::write_geo_pose_topic() { WITH_SEMAPHORE(csem); @@ -1043,7 +1589,9 @@ void AP_DDS_Client::write_geo_pose_topic() } } } +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED void AP_DDS_Client::write_clock_topic() { WITH_SEMAPHORE(csem); @@ -1058,7 +1606,9 @@ void AP_DDS_Client::write_clock_topic() } } } +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED void AP_DDS_Client::write_gps_global_origin_topic() { WITH_SEMAPHORE(csem); @@ -1072,65 +1622,136 @@ void AP_DDS_Client::write_gps_global_origin_topic() } } } +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED + +#if AP_DDS_GOAL_PUB_ENABLED +void AP_DDS_Client::write_goal_topic() +{ + WITH_SEMAPHORE(csem); + if (connected) { + ucdrBuffer ub {}; + const uint32_t topic_size = geographic_msgs_msg_GeoPointStamped_size_of_topic(&goal_topic, 0); + uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::GOAL_PUB)].dw_id, &ub, topic_size); + const bool success = geographic_msgs_msg_GeoPointStamped_serialize_topic(&ub, &goal_topic); + if (!success) { + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + } + } +} +#endif // AP_DDS_GOAL_PUB_ENABLED + +#if AP_DDS_STATUS_PUB_ENABLED +void AP_DDS_Client::write_status_topic() +{ + WITH_SEMAPHORE(csem); + if (connected) { + ucdrBuffer ub {}; + const uint32_t topic_size = ardupilot_msgs_msg_Status_size_of_topic(&status_topic, 0); + uxr_prepare_output_stream(&session, reliable_out, topics[to_underlying(TopicIndex::STATUS_PUB)].dw_id, &ub, topic_size); + const bool success = ardupilot_msgs_msg_Status_serialize_topic(&ub, &status_topic); + if (!success) { + // TODO sometimes serialization fails on bootup. Determine why. + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + } + } +} +#endif // AP_DDS_STATUS_PUB_ENABLED void AP_DDS_Client::update() { WITH_SEMAPHORE(csem); const auto cur_time_ms = AP_HAL::millis64(); +#if AP_DDS_TIME_PUB_ENABLED if (cur_time_ms - last_time_time_ms > DELAY_TIME_TOPIC_MS) { update_topic(time_topic); last_time_time_ms = cur_time_ms; write_time_topic(); } - +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_NAVSATFIX_PUB_ENABLED constexpr uint8_t gps_instance = 0; if (update_topic(nav_sat_fix_topic, gps_instance)) { write_nav_sat_fix_topic(); } - +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED if (cur_time_ms - last_battery_state_time_ms > DELAY_BATTERY_STATE_TOPIC_MS) { - constexpr uint8_t battery_instance = 0; - update_topic(battery_state_topic, battery_instance); + for (uint8_t battery_instance = 0; battery_instance < AP_BATT_MONITOR_MAX_INSTANCES; battery_instance++) { + update_topic(battery_state_topic, battery_instance); + if (battery_state_topic.present) { + write_battery_state_topic(); + } + } last_battery_state_time_ms = cur_time_ms; - write_battery_state_topic(); } - +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED if (cur_time_ms - last_local_pose_time_ms > DELAY_LOCAL_POSE_TOPIC_MS) { update_topic(local_pose_topic); last_local_pose_time_ms = cur_time_ms; write_local_pose_topic(); } - +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED if (cur_time_ms - last_local_velocity_time_ms > DELAY_LOCAL_VELOCITY_TOPIC_MS) { update_topic(tx_local_velocity_topic); last_local_velocity_time_ms = cur_time_ms; write_tx_local_velocity_topic(); } - +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED + if (cur_time_ms - last_airspeed_time_ms > DELAY_AIRSPEED_TOPIC_MS) { + last_airspeed_time_ms = cur_time_ms; + if (update_topic(tx_local_airspeed_topic)) { + write_tx_local_airspeed_topic(); + } + } +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED if (cur_time_ms - last_imu_time_ms > DELAY_IMU_TOPIC_MS) { update_topic(imu_topic); last_imu_time_ms = cur_time_ms; write_imu_topic(); } - +#endif // AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED if (cur_time_ms - last_geo_pose_time_ms > DELAY_GEO_POSE_TOPIC_MS) { update_topic(geo_pose_topic); last_geo_pose_time_ms = cur_time_ms; write_geo_pose_topic(); } - +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED if (cur_time_ms - last_clock_time_ms > DELAY_CLOCK_TOPIC_MS) { update_topic(clock_topic); last_clock_time_ms = cur_time_ms; write_clock_topic(); } - +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED if (cur_time_ms - last_gps_global_origin_time_ms > DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS) { update_topic(gps_global_origin_topic); last_gps_global_origin_time_ms = cur_time_ms; write_gps_global_origin_topic(); } +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED + if (cur_time_ms - last_goal_time_ms > DELAY_GOAL_TOPIC_MS) { + if (update_topic_goal(goal_topic)) { + write_goal_topic(); + } + last_goal_time_ms = cur_time_ms; + } +#endif // AP_DDS_GOAL_PUB_ENABLED +#if AP_DDS_STATUS_PUB_ENABLED + if (cur_time_ms - last_status_check_time_ms > DELAY_STATUS_TOPIC_MS) { + if (update_topic(status_topic)) { + write_status_topic(); + } + last_status_check_time_ms = cur_time_ms; + } +#endif // AP_DDS_STATUS_PUB_ENABLED status_ok = uxr_run_session_time(&session, 1); } diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 260faec5c59b08..d5581c4ed57b2b 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -7,24 +7,60 @@ #include "uxr/client/client.h" #include "ucdr/microcdr.h" +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED #include "ardupilot_msgs/msg/GlobalPosition.h" +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED +#if AP_DDS_TIME_PUB_ENABLED #include "builtin_interfaces/msg/Time.h" - +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_NAVSATFIX_PUB_ENABLED #include "sensor_msgs/msg/NavSatFix.h" +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_NEEDS_TRANSFORMS #include "tf2_msgs/msg/TFMessage.h" +#endif // AP_DDS_NEEDS_TRANSFORMS +#if AP_DDS_BATTERY_STATE_PUB_ENABLED #include "sensor_msgs/msg/BatteryState.h" +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED #include "sensor_msgs/msg/Imu.h" +#endif // AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_STATUS_PUB_ENABLED +#include "ardupilot_msgs/msg/Status.h" +#endif // AP_DDS_STATUS_PUB_ENABLED +#if AP_DDS_JOY_SUB_ENABLED #include "sensor_msgs/msg/Joy.h" +#endif // AP_DDS_JOY_SUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED #include "geometry_msgs/msg/PoseStamped.h" +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_NEEDS_TWIST #include "geometry_msgs/msg/TwistStamped.h" +#endif // AP_DDS_NEEDS_TWIST +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED #include "geographic_msgs/msg/GeoPointStamped.h" +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED +#include "geometry_msgs/msg/Vector3Stamped.h" +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED #include "geographic_msgs/msg/GeoPoseStamped.h" +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED #include "rosgraph_msgs/msg/Clock.h" +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_PARAMETER_SERVER_ENABLED +#include "rcl_interfaces/srv/SetParameters.h" +#include "rcl_interfaces/msg/Parameter.h" +#include "rcl_interfaces/msg/SetParametersResult.h" +#include "rcl_interfaces/msg/ParameterValue.h" +#include "rcl_interfaces/msg/ParameterType.h" +#include "rcl_interfaces/srv/GetParameters.h" +#endif //AP_DDS_PARAMETER_SERVER_ENABLED #include #include #include -#include #include "fcntl.h" @@ -59,43 +95,156 @@ class AP_DDS_Client uxrStreamId reliable_out; // Outgoing Sensor and AHRS data + +#if AP_DDS_TIME_PUB_ENABLED builtin_interfaces_msg_Time time_topic; + // The last ms timestamp AP_DDS wrote a Time message + uint64_t last_time_time_ms; + //! @brief Serialize the current time state and publish to the IO stream(s) + void write_time_topic(); + static void update_topic(builtin_interfaces_msg_Time& msg); +#endif // AP_DDS_TIME_PUB_ENABLED + +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED geographic_msgs_msg_GeoPointStamped gps_global_origin_topic; + // The last ms timestamp AP_DDS wrote a gps global origin message + uint64_t last_gps_global_origin_time_ms; + //! @brief Serialize the current gps global origin and publish to the IO stream(s) + void write_gps_global_origin_topic(); + static void update_topic(geographic_msgs_msg_GeoPointStamped& msg); +# endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED + +#if AP_DDS_GOAL_PUB_ENABLED + geographic_msgs_msg_GeoPointStamped goal_topic; + // The last ms timestamp AP_DDS wrote a goal message + uint64_t last_goal_time_ms; + //! @brief Serialize the current goal and publish to the IO stream(s) + void write_goal_topic(); + bool update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg); + geographic_msgs_msg_GeoPointStamped prev_goal_msg; +# endif // AP_DDS_GOAL_PUB_ENABLED + +#if AP_DDS_GEOPOSE_PUB_ENABLED geographic_msgs_msg_GeoPoseStamped geo_pose_topic; + // The last ms timestamp AP_DDS wrote a GeoPose message + uint64_t last_geo_pose_time_ms; + //! @brief Serialize the current geo_pose and publish to the IO stream(s) + void write_geo_pose_topic(); + static void update_topic(geographic_msgs_msg_GeoPoseStamped& msg); +#endif // AP_DDS_GEOPOSE_PUB_ENABLED + +#if AP_DDS_LOCAL_POSE_PUB_ENABLED geometry_msgs_msg_PoseStamped local_pose_topic; + // The last ms timestamp AP_DDS wrote a Local Pose message + uint64_t last_local_pose_time_ms; + //! @brief Serialize the current local_pose and publish to the IO stream(s) + void write_local_pose_topic(); + static void update_topic(geometry_msgs_msg_PoseStamped& msg); +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED + +#if AP_DDS_LOCAL_VEL_PUB_ENABLED geometry_msgs_msg_TwistStamped tx_local_velocity_topic; + // The last ms timestamp AP_DDS wrote a Local Velocity message + uint64_t last_local_velocity_time_ms; + //! @brief Serialize the current local velocity and publish to the IO stream(s) + void write_tx_local_velocity_topic(); + static void update_topic(geometry_msgs_msg_TwistStamped& msg); +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED + +#if AP_DDS_AIRSPEED_PUB_ENABLED + geometry_msgs_msg_Vector3Stamped tx_local_airspeed_topic; + // The last ms timestamp AP_DDS wrote a airspeed message + uint64_t last_airspeed_time_ms; + //! @brief Serialize the current local airspeed and publish to the IO stream(s) + void write_tx_local_airspeed_topic(); + static bool update_topic(geometry_msgs_msg_Vector3Stamped& msg); +#endif //AP_DDS_AIRSPEED_PUB_ENABLED + +#if AP_DDS_BATTERY_STATE_PUB_ENABLED sensor_msgs_msg_BatteryState battery_state_topic; + // The last ms timestamp AP_DDS wrote a BatteryState message + uint64_t last_battery_state_time_ms; + //! @brief Serialize the current nav_sat_fix state and publish it to the IO stream(s) + void write_battery_state_topic(); + static void update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance); +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED + +#if AP_DDS_NAVSATFIX_PUB_ENABLED sensor_msgs_msg_NavSatFix nav_sat_fix_topic; + // The last ms timestamp AP_DDS wrote a NavSatFix message + uint64_t last_nav_sat_fix_time_ms; + //! @brief Serialize the current nav_sat_fix state and publish to the IO stream(s) + void write_nav_sat_fix_topic(); + bool update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) WARN_IF_UNUSED; +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED + +#if AP_DDS_IMU_PUB_ENABLED sensor_msgs_msg_Imu imu_topic; + // The last ms timestamp AP_DDS wrote an IMU message + uint64_t last_imu_time_ms; + static void update_topic(sensor_msgs_msg_Imu& msg); + //! @brief Serialize the current IMU data and publish to the IO stream(s) + void write_imu_topic(); +#endif // AP_DDS_IMU_PUB_ENABLED + +#if AP_DDS_CLOCK_PUB_ENABLED rosgraph_msgs_msg_Clock clock_topic; + // The last ms timestamp AP_DDS wrote a Clock message + uint64_t last_clock_time_ms; + //! @brief Serialize the current clock and publish to the IO stream(s) + void write_clock_topic(); + static void update_topic(rosgraph_msgs_msg_Clock& msg); +#endif // AP_DDS_CLOCK_PUB_ENABLED + +#if AP_DDS_STATUS_PUB_ENABLED + ardupilot_msgs_msg_Status status_topic; + bool update_topic(ardupilot_msgs_msg_Status& msg); + // The last ms timestamp AP_DDS wrote/checked a status message + uint64_t last_status_check_time_ms; + // last status values; + ardupilot_msgs_msg_Status last_status_msg_; + //! @brief Serialize the current status and publish to the IO stream(s) + void write_status_topic(); +#endif // AP_DDS_STATUS_PUB_ENABLED + +#if AP_DDS_STATIC_TF_PUB_ENABLED + // outgoing transforms + tf2_msgs_msg_TFMessage tx_static_transforms_topic; + //! @brief Serialize the static transforms and publish to the IO stream(s) + void write_static_transforms(); + static void populate_static_transforms(tf2_msgs_msg_TFMessage& msg); +#endif // AP_DDS_STATIC_TF_PUB_ENABLED + +#if AP_DDS_JOY_SUB_ENABLED // incoming joystick data static sensor_msgs_msg_Joy rx_joy_topic; +#endif // AP_DDS_JOY_SUB_ENABLED +#if AP_DDS_VEL_CTRL_ENABLED // incoming REP147 velocity control static geometry_msgs_msg_TwistStamped rx_velocity_control_topic; +#endif // AP_DDS_VEL_CTRL_ENABLED +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED // incoming REP147 goal interface global position static ardupilot_msgs_msg_GlobalPosition rx_global_position_control_topic; - // outgoing transforms - tf2_msgs_msg_TFMessage tx_static_transforms_topic; +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED +#if AP_DDS_DYNAMIC_TF_SUB_ENABLED // incoming transforms static tf2_msgs_msg_TFMessage rx_dynamic_transforms_topic; - +#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED HAL_Semaphore csem; +#if AP_DDS_PARAMETER_SERVER_ENABLED + static rcl_interfaces_srv_SetParameters_Request set_parameter_request; + static rcl_interfaces_srv_SetParameters_Response set_parameter_response; + static rcl_interfaces_srv_GetParameters_Request get_parameters_request; + static rcl_interfaces_srv_GetParameters_Response get_parameters_response; + static rcl_interfaces_msg_Parameter param; +#endif + // connection parametrics bool status_ok{false}; bool connected{false}; - static void update_topic(builtin_interfaces_msg_Time& msg); - bool update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) WARN_IF_UNUSED; - static void populate_static_transforms(tf2_msgs_msg_TFMessage& msg); - static void update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance); - static void update_topic(geometry_msgs_msg_PoseStamped& msg); - static void update_topic(geometry_msgs_msg_TwistStamped& msg); - static void update_topic(geographic_msgs_msg_GeoPoseStamped& msg); - static void update_topic(sensor_msgs_msg_Imu& msg); - static void update_topic(rosgraph_msgs_msg_Clock& msg); - static void update_topic(geographic_msgs_msg_GeoPointStamped& msg); - // subscription callback function static void on_topic_trampoline(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length, void* args); void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length); @@ -112,25 +261,6 @@ class AP_DDS_Client .min_pace_period = 0 }; - // The last ms timestamp AP_DDS wrote a Time message - uint64_t last_time_time_ms; - // The last ms timestamp AP_DDS wrote a NavSatFix message - uint64_t last_nav_sat_fix_time_ms; - // The last ms timestamp AP_DDS wrote a BatteryState message - uint64_t last_battery_state_time_ms; - // The last ms timestamp AP_DDS wrote an IMU message - uint64_t last_imu_time_ms; - // The last ms timestamp AP_DDS wrote a Local Pose message - uint64_t last_local_pose_time_ms; - // The last ms timestamp AP_DDS wrote a Local Velocity message - uint64_t last_local_velocity_time_ms; - // The last ms timestamp AP_DDS wrote a GeoPose message - uint64_t last_geo_pose_time_ms; - // The last ms timestamp AP_DDS wrote a Clock message - uint64_t last_clock_time_ms; - // The last ms timestamp AP_DDS wrote a gps global origin message - uint64_t last_gps_global_origin_time_ms; - // functions for serial transport bool ddsSerialInit(); static bool serial_transport_open(uxrCustomTransport* args); @@ -165,6 +295,7 @@ class AP_DDS_Client // client key we present static constexpr uint32_t key = 0xAAAABBBB; + public: ~AP_DDS_Client(); @@ -184,26 +315,6 @@ class AP_DDS_Client //! @return True on successful creation, false on failure bool create() WARN_IF_UNUSED; - //! @brief Serialize the current time state and publish to the IO stream(s) - void write_time_topic(); - //! @brief Serialize the current nav_sat_fix state and publish to the IO stream(s) - void write_nav_sat_fix_topic(); - //! @brief Serialize the static transforms and publish to the IO stream(s) - void write_static_transforms(); - //! @brief Serialize the current nav_sat_fix state and publish it to the IO stream(s) - void write_battery_state_topic(); - //! @brief Serialize the current local_pose and publish to the IO stream(s) - void write_local_pose_topic(); - //! @brief Serialize the current local velocity and publish to the IO stream(s) - void write_tx_local_velocity_topic(); - //! @brief Serialize the current geo_pose and publish to the IO stream(s) - void write_geo_pose_topic(); - //! @brief Serialize the current IMU data and publish to the IO stream(s) - void write_imu_topic(); - //! @brief Serialize the current clock and publish to the IO stream(s) - void write_clock_topic(); - //! @brief Serialize the current gps global origin and publish to the IO stream(s) - void write_gps_global_origin_topic(); //! @brief Update the internally stored DDS messages with latest data void update(); @@ -213,6 +324,21 @@ class AP_DDS_Client //! @brief Parameter storage static const struct AP_Param::GroupInfo var_info[]; + //! @brief ROS_DOMAIN_ID + AP_Int32 domain_id; + + //! @brief Timeout in milliseconds when pinging the XRCE agent + AP_Int32 ping_timeout_ms; + + //! @brief Maximum number of attempts to ping the XRCE agent before exiting + AP_Int8 ping_max_retry; + + //! @brief Enum used to mark a topic as a data reader or writer + enum class Topic_rw : uint8_t { + DataReader = 0, + DataWriter = 1, + }; + //! @brief Convenience grouping for a single "channel" of data struct Topic_table { const uint8_t topic_id; @@ -220,12 +346,19 @@ class AP_DDS_Client const uint8_t sub_id; // added sub_id fields to avoid confusion const uxrObjectId dw_id; const uxrObjectId dr_id; // added dr_id fields to avoid confusion - const char* topic_profile_label; - const char* dw_profile_label; - const char* dr_profile_label; + const Topic_rw topic_rw; + const char* topic_name; + const char* type_name; + const uxrQoS_t qos; }; static const struct Topic_table topics[]; + //! @brief Enum used to mark a service as a requester or replier + enum class Service_rr : uint8_t { + Requester = 0, + Replier = 1, + }; + //! @brief Convenience grouping for a single "channel" of services struct Service_table { //! @brief Request ID for the service @@ -234,11 +367,26 @@ class AP_DDS_Client //! @brief Reply ID for the service const uint8_t rep_id; - //! @brief Profile Label for the service requester - const char* req_profile_label; + //! @brief Service is requester or replier + const Service_rr service_rr; + + //! @brief Service name as it appears in ROS + const char* service_name; + + //! @brief Service requester message type + const char* request_type; + + //! @brief Service replier message type + const char* reply_type; + + //! @brief Service requester topic name + const char* request_topic_name; + + //! @brief Service replier topic name + const char* reply_topic_name; - //! @brief Profile Label for the service replier - const char* rep_profile_label; + //! @brief QoS for the service + const uxrQoS_t qos; }; static const struct Service_table services[]; }; diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.cpp b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp index 490ce519defe90..259dcb51601c9a 100644 --- a/libraries/AP_DDS/AP_DDS_ExternalControl.cpp +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp @@ -85,6 +85,26 @@ bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistSta return false; } +bool AP_DDS_External_Control::arm(AP_Arming::Method method, bool do_arming_checks) +{ + auto *external_control = AP::externalcontrol(); + if (external_control == nullptr) { + return false; + } + + return external_control->arm(method, do_arming_checks); +} + +bool AP_DDS_External_Control::disarm(AP_Arming::Method method, bool do_disarm_checks) +{ + auto *external_control = AP::externalcontrol(); + if (external_control == nullptr) { + return false; + } + + return external_control->disarm(method, do_disarm_checks); +} + bool AP_DDS_External_Control::convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out) { diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.h b/libraries/AP_DDS/AP_DDS_ExternalControl.h index 3986ef63774aa6..eeb86e5e9c1325 100644 --- a/libraries/AP_DDS/AP_DDS_ExternalControl.h +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.h @@ -3,7 +3,7 @@ #if AP_DDS_ENABLED #include "ardupilot_msgs/msg/GlobalPosition.h" #include "geometry_msgs/msg/TwistStamped.h" - +#include #include class AP_DDS_External_Control @@ -13,6 +13,9 @@ class AP_DDS_External_Control // https://ros.org/reps/rep-0147.html#goal-interface static bool handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos); static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel); + static bool arm(AP_Arming::Method method, bool do_arming_checks); + static bool disarm(AP_Arming::Method method, bool do_disarm_checks); + private: static bool convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out); }; diff --git a/libraries/AP_DDS/AP_DDS_Service_Table.h b/libraries/AP_DDS/AP_DDS_Service_Table.h index 50611276a5539e..7f04ab324845d3 100644 --- a/libraries/AP_DDS/AP_DDS_Service_Table.h +++ b/libraries/AP_DDS/AP_DDS_Service_Table.h @@ -1,8 +1,23 @@ #include "uxr/client/client.h" +#include enum class ServiceIndex: uint8_t { +#if AP_DDS_ARM_SERVER_ENABLED ARMING_MOTORS, - MODE_SWITCH +#endif // #if AP_DDS_ARM_SERVER_ENABLED +#if AP_DDS_MODE_SWITCH_SERVER_ENABLED + MODE_SWITCH, +#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED +#if AP_DDS_ARM_CHECK_SERVER_ENABLED + PREARM_CHECK, +#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED +#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED + TAKEOFF, +#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED +#if AP_DDS_PARAMETER_SERVER_ENABLED + SET_PARAMETERS, + GET_PARAMETERS +#endif // AP_DDS_PARAMETER_SERVER_ENABLED }; static inline constexpr uint8_t to_underlying(const ServiceIndex index) @@ -12,16 +27,80 @@ static inline constexpr uint8_t to_underlying(const ServiceIndex index) } constexpr struct AP_DDS_Client::Service_table AP_DDS_Client::services[] = { +#if AP_DDS_ARM_SERVER_ENABLED { .req_id = to_underlying(ServiceIndex::ARMING_MOTORS), .rep_id = to_underlying(ServiceIndex::ARMING_MOTORS), - .req_profile_label = "", - .rep_profile_label = "arm_motors__replier", + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/arm_motorsService", + .request_type = "ardupilot_msgs::srv::dds_::ArmMotors_Request_", + .reply_type = "ardupilot_msgs::srv::dds_::ArmMotors_Response_", + .request_topic_name = "rq/ap/arm_motorsRequest", + .reply_topic_name = "rr/ap/arm_motorsReply", + .qos = { + .durability = UXR_DURABILITY_TRANSIENT_LOCAL, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_ARM_SERVER_ENABLED +#if AP_DDS_MODE_SWITCH_SERVER_ENABLED { .req_id = to_underlying(ServiceIndex::MODE_SWITCH), .rep_id = to_underlying(ServiceIndex::MODE_SWITCH), - .req_profile_label = "", - .rep_profile_label = "mode_switch__replier", + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/mode_switchService", + .request_type = "ardupilot_msgs::srv::dds_::ModeSwitch_Request_", + .reply_type = "ardupilot_msgs::srv::dds_::ModeSwitch_Response_", + .request_topic_name = "rq/ap/mode_switchRequest", + .reply_topic_name = "rr/ap/mode_switchReply", }, +#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED +#if AP_DDS_ARM_CHECK_SERVER_ENABLED + { + .req_id = to_underlying(ServiceIndex::PREARM_CHECK), + .rep_id = to_underlying(ServiceIndex::PREARM_CHECK), + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/prearm_checkService", + .request_type = "std_srvs::srv::dds_::Trigger_Request_", + .reply_type = "std_srvs::srv::dds_::Trigger_Response_", + .request_topic_name = "rq/ap/prearm_checkRequest", + .reply_topic_name = "rr/ap/prearm_checkReply", + }, +#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED +#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED + { + .req_id = to_underlying(ServiceIndex::TAKEOFF), + .rep_id = to_underlying(ServiceIndex::TAKEOFF), + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/experimental/takeoffService", + .request_type = "ardupilot_msgs::srv::dds_::Takeoff_Request_", + .reply_type = "ardupilot_msgs::srv::dds_::Takeoff_Response_", + .request_topic_name = "rq/ap/experimental/takeoffRequest", + .reply_topic_name = "rr/ap/experimental/takeoffReply", + }, +#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED +#if AP_DDS_PARAMETER_SERVER_ENABLED + { + .req_id = to_underlying(ServiceIndex::SET_PARAMETERS), + .rep_id = to_underlying(ServiceIndex::SET_PARAMETERS), + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/set_parametersService", + .request_type = "rcl_interfaces::srv::dds_::SetParameters_Request_", + .reply_type = "rcl_interfaces::srv::dds_::SetParameters_Response_", + .request_topic_name = "rq/ap/set_parametersRequest", + .reply_topic_name = "rr/ap/set_parametersReply", + }, + { + .req_id = to_underlying(ServiceIndex::GET_PARAMETERS), + .rep_id = to_underlying(ServiceIndex::GET_PARAMETERS), + .service_rr = Service_rr::Replier, + .service_name = "rs/ap/get_parameterService", + .request_type = "rcl_interfaces::srv::dds_::GetParameters_Request_", + .reply_type = "rcl_interfaces::srv::dds_::GetParameters_Response_", + .request_topic_name = "rq/ap/get_parametersRequest", + .reply_topic_name = "rr/ap/get_parametersReply", + }, +#endif // AP_DDS_PARAMETER_SERVER_ENABLED }; diff --git a/libraries/AP_DDS/AP_DDS_Topic_Table.h b/libraries/AP_DDS/AP_DDS_Topic_Table.h index bee632d28c4efe..5212a42c902c5f 100644 --- a/libraries/AP_DDS/AP_DDS_Topic_Table.h +++ b/libraries/AP_DDS/AP_DDS_Topic_Table.h @@ -3,7 +3,10 @@ #include "tf2_msgs/msg/TFMessage.h" #include "sensor_msgs/msg/BatteryState.h" #include "geographic_msgs/msg/GeoPoseStamped.h" +#include "geometry_msgs/msg/Vector3Stamped.h" +#if AP_DDS_IMU_PUB_ENABLED #include "sensor_msgs/msg/Imu.h" +#endif //AP_DDS_IMU_PUB_ENABLED #include "uxr/client/client.h" @@ -12,20 +15,57 @@ // Can use jinja to template (like Flask) enum class TopicIndex: uint8_t { +#if AP_DDS_TIME_PUB_ENABLED TIME_PUB, +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_NAVSATFIX_PUB_ENABLED NAV_SAT_FIX_PUB, +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_STATIC_TF_PUB_ENABLED STATIC_TRANSFORMS_PUB, +#endif // AP_DDS_STATIC_TF_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED BATTERY_STATE_PUB, +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED IMU_PUB, +#endif //AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED LOCAL_POSE_PUB, +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED LOCAL_VELOCITY_PUB, +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED + LOCAL_AIRSPEED_PUB, +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED GEOPOSE_PUB, +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#ifdef AP_DDS_GOAL_PUB_ENABLED + GOAL_PUB, +#endif // AP_DDS_GOAL_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED CLOCK_PUB, +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED GPS_GLOBAL_ORIGIN_PUB, +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_STATUS_PUB_ENABLED + STATUS_PUB, +#endif // AP_DDS_STATUS_PUB_ENABLED +#if AP_DDS_JOY_SUB_ENABLED JOY_SUB, +#endif // AP_DDS_JOY_SUB_ENABLED +#if AP_DDS_DYNAMIC_TF_SUB_ENABLED DYNAMIC_TRANSFORMS_SUB, +#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED +#if AP_DDS_VEL_CTRL_ENABLED VELOCITY_CONTROL_SUB, +#endif // AP_DDS_VEL_CTRL_ENABLED +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED GLOBAL_POSITION_SUB, +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED }; static inline constexpr uint8_t to_underlying(const TopicIndex index) @@ -36,144 +76,310 @@ static inline constexpr uint8_t to_underlying(const TopicIndex index) constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = { +#if AP_DDS_TIME_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::TIME_PUB), .pub_id = to_underlying(TopicIndex::TIME_PUB), .sub_id = to_underlying(TopicIndex::TIME_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "time__t", - .dw_profile_label = "time__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/time", + .type_name = "builtin_interfaces::msg::dds_::Time_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 20, + }, }, +#endif // AP_DDS_TIME_PUB_ENABLED +#if AP_DDS_NAVSATFIX_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .pub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .sub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "navsatfix0__t", - .dw_profile_label = "navsatfix0__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/navsat", + .type_name = "sensor_msgs::msg::dds_::NavSatFix_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_NAVSATFIX_PUB_ENABLED +#if AP_DDS_STATIC_TF_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .pub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .sub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "statictransforms__t", - .dw_profile_label = "statictransforms__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/tf_static", + .type_name = "tf2_msgs::msg::dds_::TFMessage_", + .qos = { + .durability = UXR_DURABILITY_TRANSIENT_LOCAL, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 1, + }, }, +#endif // AP_DDS_STATIC_TF_PUB_ENABLED +#if AP_DDS_BATTERY_STATE_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::BATTERY_STATE_PUB), .pub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB), .sub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "batterystate0__t", - .dw_profile_label = "batterystate0__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/battery", + .type_name = "sensor_msgs::msg::dds_::BatteryState_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED +#if AP_DDS_IMU_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::IMU_PUB), .pub_id = to_underlying(TopicIndex::IMU_PUB), .sub_id = to_underlying(TopicIndex::IMU_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "imu__t", - .dw_profile_label = "imu__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/imu/experimental/data", + .type_name = "sensor_msgs::msg::dds_::Imu_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif //AP_DDS_IMU_PUB_ENABLED +#if AP_DDS_LOCAL_POSE_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::LOCAL_POSE_PUB), .pub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB), .sub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "localpose__t", - .dw_profile_label = "localpose__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/pose/filtered", + .type_name = "geometry_msgs::msg::dds_::PoseStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED +#if AP_DDS_LOCAL_VEL_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .pub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .sub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "localvelocity__t", - .dw_profile_label = "localvelocity__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/twist/filtered", + .type_name = "geometry_msgs::msg::dds_::TwistStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED +#if AP_DDS_AIRSPEED_PUB_ENABLED + { + .topic_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), + .pub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), + .sub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), + .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAWRITER_ID}, + .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAREADER_ID}, + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/airspeed", + .type_name = "geometry_msgs::msg::dds_::Vector3Stamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, + }, +#endif // AP_DDS_AIRSPEED_PUB_ENABLED +#if AP_DDS_GEOPOSE_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::GEOPOSE_PUB), .pub_id = to_underlying(TopicIndex::GEOPOSE_PUB), .sub_id = to_underlying(TopicIndex::GEOPOSE_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "geopose__t", - .dw_profile_label = "geopose__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/geopose/filtered", + .type_name = "geographic_msgs::msg::dds_::GeoPoseStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, + }, +#endif // AP_DDS_GEOPOSE_PUB_ENABLED +#if AP_DDS_GOAL_PUB_ENABLED + { + .topic_id = to_underlying(TopicIndex::GOAL_PUB), + .pub_id = to_underlying(TopicIndex::GOAL_PUB), + .sub_id = to_underlying(TopicIndex::GOAL_PUB), + .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAWRITER_ID}, + .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAREADER_ID}, + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/goal_lla", + .type_name = "geographic_msgs::msg::dds_::GeoPointStamped_", + .qos = { + .durability = UXR_DURABILITY_TRANSIENT_LOCAL, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 1, + }, }, +#endif // AP_DDS_GOAL_PUB_ENABLED +#if AP_DDS_CLOCK_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::CLOCK_PUB), .pub_id = to_underlying(TopicIndex::CLOCK_PUB), .sub_id = to_underlying(TopicIndex::CLOCK_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "clock__t", - .dw_profile_label = "clock__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/clock", + .type_name = "rosgraph_msgs::msg::dds_::Clock_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 20, + }, }, +#endif // AP_DDS_CLOCK_PUB_ENABLED +#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED { .topic_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .pub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .sub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "gps_global_origin__t", - .dw_profile_label = "gps_global_origin__dw", - .dr_profile_label = "", + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/gps_global_origin/filtered", + .type_name = "geographic_msgs::msg::dds_::GeoPointStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, + }, +#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#if AP_DDS_STATUS_PUB_ENABLED + { + .topic_id = to_underlying(TopicIndex::STATUS_PUB), + .pub_id = to_underlying(TopicIndex::STATUS_PUB), + .sub_id = to_underlying(TopicIndex::STATUS_PUB), + .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAWRITER_ID}, + .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAREADER_ID}, + .topic_rw = Topic_rw::DataWriter, + .topic_name = "rt/ap/status", + .type_name = "ardupilot_msgs::msg::dds_::Status_", + .qos = { + .durability = UXR_DURABILITY_TRANSIENT_LOCAL, + .reliability = UXR_RELIABILITY_RELIABLE, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 1, + }, }, +#endif // AP_DDS_STATUS_PUB_ENABLED +#if AP_DDS_JOY_SUB_ENABLED { .topic_id = to_underlying(TopicIndex::JOY_SUB), .pub_id = to_underlying(TopicIndex::JOY_SUB), .sub_id = to_underlying(TopicIndex::JOY_SUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "joy__t", - .dw_profile_label = "", - .dr_profile_label = "joy__dr", + .topic_rw = Topic_rw::DataReader, + .topic_name = "rt/ap/joy", + .type_name = "sensor_msgs::msg::dds_::Joy_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_JOY_SUB_ENABLED +#if AP_DDS_DYNAMIC_TF_SUB_ENABLED { .topic_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .pub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .sub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "dynamictf__t", - .dw_profile_label = "", - .dr_profile_label = "dynamictf__dr", + .topic_rw = Topic_rw::DataReader, + .topic_name = "rt/ap/tf", + .type_name = "tf2_msgs::msg::dds_::TFMessage_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED +#if AP_DDS_VEL_CTRL_ENABLED { .topic_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .pub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .sub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "velocitycontrol__t", - .dw_profile_label = "", - .dr_profile_label = "velocitycontrol__dr", + .topic_rw = Topic_rw::DataReader, + .topic_name = "rt/ap/cmd_vel", + .type_name = "geometry_msgs::msg::dds_::TwistStamped_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_VEL_CTRL_ENABLED +#if AP_DDS_GLOBAL_POS_CTRL_ENABLED { .topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .pub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID}, .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID}, - .topic_profile_label = "globalposcontrol__t", - .dw_profile_label = "", - .dr_profile_label = "globalposcontrol__dr", + .topic_rw = Topic_rw::DataReader, + .topic_name = "rt/ap/cmd_gps_pose", + .type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_", + .qos = { + .durability = UXR_DURABILITY_VOLATILE, + .reliability = UXR_RELIABILITY_BEST_EFFORT, + .history = UXR_HISTORY_KEEP_LAST, + .depth = 5, + }, }, +#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED }; diff --git a/libraries/AP_DDS/AP_DDS_UDP.cpp b/libraries/AP_DDS/AP_DDS_UDP.cpp index 6593100618bb50..6496e7ebb076c2 100644 --- a/libraries/AP_DDS/AP_DDS_UDP.cpp +++ b/libraries/AP_DDS/AP_DDS_UDP.cpp @@ -10,7 +10,7 @@ bool AP_DDS_Client::udp_transport_open(uxrCustomTransport *t) { AP_DDS_Client *dds = (AP_DDS_Client *)t->args; - auto *sock = new SocketAPM(true); + auto *sock = NEW_NOTHROW SocketAPM(true); if (sock == nullptr) { return false; } diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index f1c71bbc871484..022bce3d39dc69 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -17,6 +17,148 @@ #define AP_DDS_VISUALODOM_ENABLED HAL_VISUALODOM_ENABLED && AP_DDS_ENABLED #endif +// Whether experimental interfaces are enabled. +#ifndef AP_DDS_EXPERIMENTAL_ENABLED +#define AP_DDS_EXPERIMENTAL_ENABLED 1 +#endif + +#ifndef AP_DDS_IMU_PUB_ENABLED +#define AP_DDS_IMU_PUB_ENABLED AP_DDS_EXPERIMENTAL_ENABLED +#endif + +#ifndef AP_DDS_DELAY_IMU_TOPIC_MS +#define AP_DDS_DELAY_IMU_TOPIC_MS 5 +#endif + +#ifndef AP_DDS_TIME_PUB_ENABLED +#define AP_DDS_TIME_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_TIME_TOPIC_MS +#define AP_DDS_DELAY_TIME_TOPIC_MS 10 +#endif + +#ifndef AP_DDS_NAVSATFIX_PUB_ENABLED +#define AP_DDS_NAVSATFIX_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_STATIC_TF_PUB_ENABLED +#define AP_DDS_STATIC_TF_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED +#define AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS +#define AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS 1000 +#endif + +#ifndef AP_DDS_GEOPOSE_PUB_ENABLED +#define AP_DDS_GEOPOSE_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_GEO_POSE_TOPIC_MS +#define AP_DDS_DELAY_GEO_POSE_TOPIC_MS 33 +#endif + +#ifndef AP_DDS_LOCAL_POSE_PUB_ENABLED +#define AP_DDS_LOCAL_POSE_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS +#define AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS 33 +#endif + +#ifndef AP_DDS_LOCAL_VEL_PUB_ENABLED +#define AP_DDS_LOCAL_VEL_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS +#define AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS 33 +#endif + +#ifndef AP_DDS_AIRSPEED_PUB_ENABLED +#define AP_DDS_AIRSPEED_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_AIRSPEED_TOPIC_MS +#define AP_DDS_DELAY_AIRSPEED_TOPIC_MS 33 +#endif + +#ifndef AP_DDS_BATTERY_STATE_PUB_ENABLED +#define AP_DDS_BATTERY_STATE_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS +#define AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS 1000 +#endif + +#ifndef AP_DDS_DELAY_STATUS_TOPIC_MS +#define AP_DDS_DELAY_STATUS_TOPIC_MS 100 +#endif + +#ifndef AP_DDS_CLOCK_PUB_ENABLED +#define AP_DDS_CLOCK_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_CLOCK_TOPIC_MS +#define AP_DDS_DELAY_CLOCK_TOPIC_MS 10 +#endif + +#ifndef AP_DDS_GOAL_PUB_ENABLED +#define AP_DDS_GOAL_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_DELAY_GOAL_TOPIC_MS +#define AP_DDS_DELAY_GOAL_TOPIC_MS 200 +#endif +#ifndef AP_DDS_STATUS_PUB_ENABLED +#define AP_DDS_STATUS_PUB_ENABLED 1 +#endif + +#ifndef AP_DDS_JOY_SUB_ENABLED +#define AP_DDS_JOY_SUB_ENABLED 1 +#endif + +#ifndef AP_DDS_VEL_CTRL_ENABLED +#define AP_DDS_VEL_CTRL_ENABLED 1 +#endif + +#ifndef AP_DDS_GLOBAL_POS_CTRL_ENABLED +#define AP_DDS_GLOBAL_POS_CTRL_ENABLED 1 +#endif + +#ifndef AP_DDS_DYNAMIC_TF_SUB_ENABLED +#define AP_DDS_DYNAMIC_TF_SUB_ENABLED 1 +#endif + +#ifndef AP_DDS_ARM_SERVER_ENABLED +#define AP_DDS_ARM_SERVER_ENABLED 1 +#endif + +#ifndef AP_DDS_MODE_SWITCH_SERVER_ENABLED +#define AP_DDS_MODE_SWITCH_SERVER_ENABLED 1 +#endif + +#ifndef AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED +#define AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED 1 +#endif + +#ifndef AP_DDS_PARAMETER_SERVER_ENABLED +#define AP_DDS_PARAMETER_SERVER_ENABLED 1 +#endif + +#ifndef AP_DDS_ARM_CHECK_SERVER_ENABLED +#define AP_DDS_ARM_CHECK_SERVER_ENABLED 1 +#endif + +// Whether to include Twist support +#define AP_DDS_NEEDS_TWIST AP_DDS_VEL_CTRL_ENABLED || AP_DDS_LOCAL_VEL_PUB_ENABLED + +// Whether to include Transform support +#define AP_DDS_NEEDS_TRANSFORMS AP_DDS_DYNAMIC_TF_SUB_ENABLED || AP_DDS_STATIC_TF_PUB_ENABLED + #ifndef AP_DDS_DEFAULT_UDP_IP_ADDR #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #define AP_DDS_DEFAULT_UDP_IP_ADDR "192.168.13.2" @@ -24,3 +166,7 @@ #define AP_DDS_DEFAULT_UDP_IP_ADDR "127.0.0.1" #endif #endif + +#ifndef AP_DDS_PARTICIPANT_NAME +#define AP_DDS_PARTICIPANT_NAME "ap" +#endif diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/msg/Status.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/Status.idl new file mode 100644 index 00000000000000..a06a0da8cb2e65 --- /dev/null +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/Status.idl @@ -0,0 +1,56 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from ardupilot_msgs/msg/Status.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module ardupilot_msgs { + module msg { + module Status_Constants { + const uint8 APM_ROVER = 1; + const uint8 APM_ARDUCOPTER = 2; + const uint8 APM_ARDUPLANE = 3; + const uint8 APM_ANTENNATRACKER = 4; + const uint8 APM_UNKNOWN = 5; + const uint8 APM_REPLAY = 6; + const uint8 APM_ARDUSUB = 7; + const uint8 APM_IOFIRMWARE = 8; + const uint8 APM_AP_PERIPH = 9; + const uint8 APM_AP_DAL_STANDALONE = 10; + const uint8 APM_AP_BOOTLOADER = 11; + const uint8 APM_BLIMP = 12; + const uint8 APM_HELI = 13; + const uint8 FS_RADIO = 21; + const uint8 FS_BATTERY = 22; + const uint8 FS_GCS = 23; + const uint8 FS_EKF = 24; + }; + struct Status { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + "From AP_Vehicle_Type.h") + uint8 vehicle_type; + + @verbatim (language="comment", text= + "true if vehicle is armed.") + boolean armed; + + @verbatim (language="comment", text= + "Vehicle mode, enum depending on vehicle type.") + uint8 mode; + + @verbatim (language="comment", text= + "True if flying/driving/diving/tracking.") + boolean flying; + + @verbatim (language="comment", text= + "True is external control is enabled.") + boolean external_control; + + @verbatim (language="comment", text= + "Array containing all active failsafe.") + sequence failsafe; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/srv/Takeoff.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/Takeoff.idl new file mode 100644 index 00000000000000..2e16f5cd627145 --- /dev/null +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/Takeoff.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from ardupilot_msgs/srv/Takeoff.srv +// generated code does not contain a copyright notice + + +module ardupilot_msgs { + module srv { + struct Takeoff_Request { + @verbatim (language="comment", text= + "This service requests the vehicle to takeoff" "\n" + "float : Set the takeoff altitude [m] above home, or above terrain if rangefinder is healthy") + float alt; + }; + @verbatim (language="comment", text= + "status : True if the request for takeoff was successful, False otherwise") + struct Takeoff_Response { + boolean status; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/geometry_msgs/msg/Vector3Stamped.idl b/libraries/AP_DDS/Idl/geometry_msgs/msg/Vector3Stamped.idl new file mode 100644 index 00000000000000..edb586e2138d3e --- /dev/null +++ b/libraries/AP_DDS/Idl/geometry_msgs/msg/Vector3Stamped.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Vector3Stamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + "This represents a Vector3 with reference coordinate frame and timestamp") + struct Vector3Stamped { + @verbatim (language="comment", text= + "Note that this follows vector semantics with it always anchored at the origin," "\n" + "so the rotational elements of a transform are the only parts applied when transforming.") + std_msgs::msg::Header header; + + geometry_msgs::msg::Vector3 vector; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/msg/Parameter.idl b/libraries/AP_DDS/Idl/rcl_interfaces/msg/Parameter.idl new file mode 100644 index 00000000000000..992213a287458a --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/msg/Parameter.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/Parameter.msg +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterValue.idl" + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + "This is the message to communicate a parameter. It is an open struct with an enum in" "\n" + "the descriptor to select which value is active.") + struct Parameter { + @verbatim (language="comment", text= + "The full name of the parameter.") + string name; + + @verbatim (language="comment", text= + "The parameter's value which can be one of several types, see" "\n" + "`ParameterValue.msg` and `ParameterType.msg`.") + rcl_interfaces::msg::ParameterValue value; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterType.idl b/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterType.idl new file mode 100644 index 00000000000000..e6a6bfcca7da79 --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterType.idl @@ -0,0 +1,28 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterType.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + module ParameterType_Constants { + @verbatim (language="comment", text= + "Default value, which implies this is not a valid parameter.") + const uint8 PARAMETER_NOT_SET = 0; + const uint8 PARAMETER_BOOL = 1; + const uint8 PARAMETER_INTEGER = 2; + const uint8 PARAMETER_DOUBLE = 3; + const uint8 PARAMETER_STRING = 4; + const uint8 PARAMETER_BYTE_ARRAY = 5; + const uint8 PARAMETER_BOOL_ARRAY = 6; + const uint8 PARAMETER_INTEGER_ARRAY = 7; + const uint8 PARAMETER_DOUBLE_ARRAY = 8; + const uint8 PARAMETER_STRING_ARRAY = 9; + }; + @verbatim (language="comment", text= + "These types correspond to the value that is set in the ParameterValue message.") + struct ParameterType { + uint8 structure_needs_at_least_one_member; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterValue.idl b/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterValue.idl new file mode 100644 index 00000000000000..3adbc5233cac2b --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/msg/ParameterValue.idl @@ -0,0 +1,58 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterValue.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + "Used to determine which of the next *_value fields are set." "\n" + "ParameterType.PARAMETER_NOT_SET indicates that the parameter was not set" "\n" + "(if gotten) or is uninitialized." "\n" + "Values are enumerated in `ParameterType.msg`.") + struct ParameterValue { + @verbatim (language="comment", text= + "The type of this parameter, which corresponds to the appropriate field below.") + uint8 type; + + @verbatim (language="comment", text= + "\"Variant\" style storage of the parameter value. Only the value corresponding" "\n" + "the type field will have valid information." "\n" + "Boolean value, can be either true or false.") + boolean bool_value; + + @verbatim (language="comment", text= + "Integer value ranging from -9,223,372,036,854,775,808 to" "\n" + "9,223,372,036,854,775,807.") + int64 integer_value; + + @verbatim (language="comment", text= + "A double precision floating point value following IEEE 754.") + double double_value; + + @verbatim (language="comment", text= + "A textual value with no practical length limit.") + string string_value; + + @verbatim (language="comment", text= + "An array of bytes, used for non-textual information.") + sequence byte_array_value; + + @verbatim (language="comment", text= + "An array of boolean values.") + sequence bool_array_value; + + @verbatim (language="comment", text= + "An array of 64-bit integer values.") + sequence integer_array_value; + + @verbatim (language="comment", text= + "An array of 64-bit floating point values.") + sequence double_array_value; + + @verbatim (language="comment", text= + "An array of string values.") + sequence string_array_value; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/msg/SetParametersResult.idl b/libraries/AP_DDS/Idl/rcl_interfaces/msg/SetParametersResult.idl new file mode 100644 index 00000000000000..d1c68fe1200f1d --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/msg/SetParametersResult.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/SetParametersResult.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + "A true value of the same index indicates that the parameter was set" "\n" + "successfully. A false value indicates the change was rejected.") + struct SetParametersResult { + boolean successful; + + @verbatim (language="comment", text= + "Reason why the setting was either successful or a failure. This should only be" "\n" + "used for logging and user interfaces.") + string reason; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/srv/GetParameters.idl b/libraries/AP_DDS/Idl/rcl_interfaces/srv/GetParameters.idl new file mode 100644 index 00000000000000..d6579f51b2c12c --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/srv/GetParameters.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/GetParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterValue.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + "TODO(wjwwood): Decide on the rules for grouping, nodes, and parameter \"names\"" "\n" + "in general, then link to that." "\n" + "" "\n" + "For more information about parameters and naming rules, see:" "\n" + "https://design.ros2.org/articles/ros_parameters.html" "\n" + "https://github.com/ros2/design/pull/241") + struct GetParameters_Request { + @verbatim (language="comment", text= + "A list of parameter names to get.") + sequence names; + }; + @verbatim (language="comment", text= + "List of values which is the same length and order as the provided names. If a" "\n" + "parameter was not yet set, the value will have PARAMETER_NOT_SET as the" "\n" + "type.") + struct GetParameters_Response { + sequence values; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/rcl_interfaces/srv/SetParameters.idl b/libraries/AP_DDS/Idl/rcl_interfaces/srv/SetParameters.idl new file mode 100644 index 00000000000000..ade6df7994030d --- /dev/null +++ b/libraries/AP_DDS/Idl/rcl_interfaces/srv/SetParameters.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/SetParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/Parameter.idl" +#include "rcl_interfaces/msg/SetParametersResult.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + "A list of parameters to set.") + struct SetParameters_Request { + sequence parameters; + }; + @verbatim (language="comment", text= + "Indicates whether setting each parameter succeeded or not and why.") + struct SetParameters_Response { + sequence results; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/std_srvs/srv/Trigger.idl b/libraries/AP_DDS/Idl/std_srvs/srv/Trigger.idl new file mode 100644 index 00000000000000..6c763b5e7aab0a --- /dev/null +++ b/libraries/AP_DDS/Idl/std_srvs/srv/Trigger.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from std_srvs/srv/Trigger.srv +// generated code does not contain a copyright notice + + +module std_srvs { + module srv { + struct Trigger_Request { + uint8 structure_needs_at_least_one_member; + }; + struct Trigger_Response { + @verbatim (language="comment", text= + "indicate successful run of triggered service") + boolean success; + + @verbatim (language="comment", text= + "informational, e.g. for error messages") + string message; + }; + }; +}; diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index f08aaf12490d82..ad323ba17392fd 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -55,40 +55,7 @@ graph LR While DDS support in Ardupilot is mostly through git submodules, another tool needs to be available on your system: Micro XRCE DDS Gen. -- Go to a directory on your system to clone the repo (perhaps next to `ardupilot`) -- Install java - ```console - sudo apt install default-jre - ```` -- Follow instructions [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/installation.html#installing-the-micro-xrce-dds-gen-tool) to install the latest version of the generator using Ardupilot's mirror - ```console - git clone --recurse-submodules https://github.com/ardupilot/Micro-XRCE-DDS-Gen.git - cd Micro-XRCE-DDS-Gen - ./gradlew assemble - ``` - -- Add the generator directory to $PATH. - ```console - # Add this to ~/.bashrc - - export PATH=$PATH:/your/path/to/Micro-XRCE-DDS-Gen/scripts - ``` -- Test it - ```console - cd /path/to/ardupilot - microxrceddsgen -version - # openjdk version "11.0.18" 2023-01-17 - # OpenJDK Runtime Environment (build 11.0.18+10-post-Ubuntu-0ubuntu122.04) - # OpenJDK 64-Bit Server VM (build 11.0.18+10-post-Ubuntu-0ubuntu122.04, mixed mode, sharing) - # microxrceddsgen version: 1.0.0beta2 - ``` - -> :warning: **If you have installed FastDDS or FastDDSGen globally on your system**: -eProsima's libraries and the packaging system in Ardupilot are not deterministic in this scenario. -You may experience the wrong version of a library brought in, or runtime segfaults. -For now, avoid having simultaneous local and global installs. -If you followed the [global install](https://fast-dds.docs.eprosima.com/en/latest/installation/sources/sources_linux.html#global-installation) -section, you should remove it and switch to local install. +Follow the wiki [here](https://ardupilot.org/dev/docs/ros2.html#installation-ubuntu) to set up your environment. ### Serial Only: Set up serial for SITL with DDS @@ -109,6 +76,7 @@ Run the simulator with the following command. If using UDP, the only parameter y | DDS_ENABLE | Set to 1 to enable DDS, or 0 to disable | 1 | | SERIAL1_BAUD | The serial baud rate for DDS | 57 | | SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | 0 | + ```console # Wipe params till you see "AP: ArduPilot Ready" # Select your favorite vehicle type @@ -164,7 +132,7 @@ Next, follow the associated section for your chosen transport, and finally you c - Run the microROS agent ```console cd ardupilot/libraries/AP_DDS - ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019 -r dds_xrce_profile.xml + ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019 ``` - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) ```console @@ -184,7 +152,7 @@ Next, follow the associated section for your chosen transport, and finally you c ```console cd ardupilot/libraries/AP_DDS # assuming we are using tty/pts/2 for DDS Application - ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/pts/2 + ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 ``` - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) ```console @@ -204,12 +172,13 @@ $ ros2 node list ```bash $ ros2 topic list -v Published topics: - * /ap/battery/battery0 [sensor_msgs/msg/BatteryState] 1 publisher + * /ap/airspeed [geometry_msgs/msg/Vector3] 1 publisher + * /ap/battery [sensor_msgs/msg/BatteryState] 1 publisher * /ap/clock [rosgraph_msgs/msg/Clock] 1 publisher * /ap/geopose/filtered [geographic_msgs/msg/GeoPoseStamped] 1 publisher * /ap/gps_global_origin/filtered [geographic_msgs/msg/GeoPointStamped] 1 publisher * /ap/imu/experimental/data [sensor_msgs/msg/Imu] 1 publisher - * /ap/navsat/navsat0 [sensor_msgs/msg/NavSatFix] 1 publisher + * /ap/navsat [sensor_msgs/msg/NavSatFix] 1 publisher * /ap/pose/filtered [geometry_msgs/msg/PoseStamped] 1 publisher * /ap/tf_static [tf2_msgs/msg/TFMessage] 1 publisher * /ap/time [builtin_interfaces/msg/Time] 1 publisher @@ -240,6 +209,8 @@ nanosec: 729410000 $ ros2 service list /ap/arm_motors /ap/mode_switch +/ap/prearm_check +/ap/experimental/takeoff --- ``` @@ -253,7 +224,7 @@ In order to consume the transforms, it's highly recommended to [create and run a ## Using ROS 2 services -The `AP_DDS` library exposes services which are automatically mapped to ROS 2 +The `AP_DDS` library exposes services which are automatically mapped to ROS 2 services using appropriate naming conventions for topics and message and service types. An earlier version of `AP_DDS` required the use of the eProsima [Integration Service](https://github.com/eProsima/Integration-Service) to map @@ -265,6 +236,8 @@ List the available services: $ ros2 service list -t /ap/arm_motors [ardupilot_msgs/srv/ArmMotors] /ap/mode_switch [ardupilot_msgs/srv/ModeSwitch] +/ap/prearm_check [std_srvs/srv/Trigger] +/ap/experimental/takeoff [ardupilot_msgs/srv/Takeoff] ``` Call the arm motors service: @@ -286,6 +259,55 @@ requester: making request: ardupilot_msgs.srv.ModeSwitch_Request(mode=4) response: ardupilot_msgs.srv.ModeSwitch_Response(status=True, curr_mode=4) ``` + +Call the prearm check service: + +```bash +$ ros2 service call /ap/prearm_check std_srvs/srv/Trigger +requester: making request: std_srvs.srv.Trigger_Request() + +response: +std_srvs.srv.Trigger_Response(success=False, message='Vehicle is Not Armable') + +or + +std_srvs.srv.Trigger_Response(success=True, message='Vehicle is Armable') +``` + +Call the takeoff service: + +```bash +$ ros2 service call /ap/experimental/takeoff ardupilot_msgs/srv/Takeoff "{alt: 10.5}" +requester: making request: ardupilot_msgs.srv.Takeoff_Request(alt=10.5) + +response: +ardupilot_msgs.srv.Takeoff_Response(status=True) +``` + +## Commanding using ROS 2 Topics + +The following topic can be used to control the vehicle. + +- `/ap/joy` (type `sensor_msgs/msg/Joy`): overrides a maximum of 8 RC channels, +at least 4 axes must be sent. Values are clamped between -1.0 and 1.0. +Use `NaN` to disable the override of a single channel. +A channel defaults back to RC after 1 second of not receiving commands. + +```bash +ros2 topic pub /ap/joy sensor_msgs/msg/Joy "{axes: [0.0, 0.0, 0.0, 0.0]}" + +publisher: beginning loop +publishing #1: sensor_msgs.msg.Joy(header=std_msgs.msg.Header(stamp=builtin_interfaces.msg.Time(sec=0, nanosec=0), frame_id=''), axes=[0.0, 0.0, 0.0, 0.0], buttons=[]) +``` +- `/ap/cmd_gps_pose` (type `ardupilot_msgs/msg/GlobalPosition`): sends +a waypoint to head to when the selected mode is GUIDED. + +```bash +ros2 topic pub /ap/cmd_gps_pose ardupilot_msgs/msg/GlobalPosition "{latitude: 34, longitude: 118, altitude: 1000}" + +publisher: beginning loop +publishing #1: ardupilot_msgs.msg.GlobalPosition(header=std_msgs.msg.Header(stamp=builtin_interfaces.msg.Time(sec=0, nanosec=0), frame_id=''), coordinate_frame=0, type_mask=0, latitude=34.0, longitude=118.0, altitude=1000.0, velocity=geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0)), acceleration_or_force=geometry_msgs.msg.Twist(linear=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0), angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0)), yaw=0.0) +``` ## Contributing to `AP_DDS` library @@ -318,18 +340,18 @@ If the message is custom for ardupilot, first create the ROS message in `Tools/r Then, build ardupilot_msgs with colcon. Finally, copy the IDL folder from the install directory into the source tree. -### Rules for adding topics and services to `dds_xrce_profile.xml` +### Rules for adding topics and services Topics and services available from `AP_DDS` are automatically mapped into ROS 2 -provided a few rules are followed when defining the entries in -`dds_xrce_profile.xml`. +provided a few rules are followed when defining the entries in the +topic and service tables. #### ROS 2 message and service interface types ROS 2 message and interface definitions are mangled by the `rosidl_adapter` when mapping from ROS 2 to DDS to avoid naming conflicts in the C/C++ libraries. The ROS 2 object `namespace::Struct` is mangled to `namespace::dds_::Struct_` -for DDS. The table below provides some example mappings: +for DDS. The table below provides some example mappings: | ROS 2 | DDS | | --- | --- | @@ -355,23 +377,25 @@ The request / response pair for services require an additional suffix. | parameter | rp/ | | | action | ra/ | | -The table below provides example mappings for topics and services +The table below provides example mappings for topics and services | ROS 2 | DDS | | --- | --- | | ap/clock | rt/ap/clock | -| ap/navsat/navsat0 | rt/ap/navsat/navsat0 | +| ap/navsat | rt/ap/navsat | | ap/arm_motors | rq/ap/arm_motorsRequest, rr/ap/arm_motorsReply | -Refer to existing mappings in [`dds_xrce_profile.xml`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/dds_xrce_profile.xml) for additional details. +Refer to existing mappings in [`AP_DDS_Topic_Table`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h) +and [`AP_DDS_Service_Table`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_Service_Table.h) +for additional details. ### Development Requirements Astyle is used to format the C++ code in AP_DDS. This is required for CI to pass the build. -See [Tools/CodeStyle/ardupilot-astyle.sh](../../Tools/CodeStyle/ardupilot-astyle.sh). +To run the automated formatter, run: ```bash -./Tools/CodeStyle/ardupilot-astyle.sh libraries/AP_DDS/*.h libraries/AP_DDS/*.cpp +./Tools/scripts/run_astyle.py ``` Pre-commit is used for other things like formatting python and XML code. @@ -412,7 +436,7 @@ Then run the Micro ROS agent cd /path/to/ros2_ws source install/setup.bash cd src/ardupilot/libraries/AP_DDS -ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02 +ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02 ``` If connection fails, instead of running the Micro ROS agent, debug the stream diff --git a/libraries/AP_DDS/dds_xrce_profile.xml b/libraries/AP_DDS/dds_xrce_profile.xml deleted file mode 100644 index 3dcece3f9d30cd..00000000000000 --- a/libraries/AP_DDS/dds_xrce_profile.xml +++ /dev/null @@ -1,345 +0,0 @@ - - - - - ardupilot_dds - - - - rt/ap/time - builtin_interfaces::msg::dds_::Time_ - - KEEP_LAST - 20 - - - - PREALLOCATED_WITH_REALLOC - - - RELIABLE - - - - NO_KEY - rt/ap/time - builtin_interfaces::msg::dds_::Time_ - - KEEP_LAST - 20 - - - - - rt/ap/navsat/navsat0 - sensor_msgs::msg::dds_::NavSatFix_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/navsat/navsat0 - sensor_msgs::msg::dds_::NavSatFix_ - - KEEP_LAST - 5 - - - - - rt/ap/tf_static - tf2_msgs::msg::dds_::TFMessage_ - - KEEP_LAST - 1 - - - - PREALLOCATED_WITH_REALLOC - - - RELIABLE - - - TRANSIENT_LOCAL - - - - NO_KEY - rt/ap/tf_static - tf2_msgs::msg::dds_::TFMessage_ - - KEEP_LAST - 1 - - - - - rt/ap/battery/battery0 - sensor_msgs::msg::dds_::BatteryState_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/battery/battery0 - sensor_msgs::msg::dds_::BatteryState_ - - KEEP_LAST - 5 - - - - - rt/ap/imu/experimental/data - sensor_msgs::msg::dds_::Imu_ - - KEEP_LAST - 20 - - - - - NO_KEY - rt/ap/imu/experimental/data - sensor_msgs::msg::dds_::Imu_ - - - - RELIABLE - - - TRANSIENT_LOCAL - - - - - rt/ap/pose/filtered - geometry_msgs::msg::dds_::PoseStamped_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/pose/filtered - geometry_msgs::msg::dds_::PoseStamped_ - - KEEP_LAST - 5 - - - - - rt/ap/twist/filtered - geometry_msgs::msg::dds_::TwistStamped_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/twist/filtered - geometry_msgs::msg::dds_::TwistStamped_ - - KEEP_LAST - 5 - - - - - rt/ap/geopose/filtered - geographic_msgs::msg::dds_::GeoPoseStamped_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/geopose/filtered - geographic_msgs::msg::dds_::GeoPoseStamped_ - - KEEP_LAST - 5 - - - - - rt/ap/clock - rosgraph_msgs::msg::dds_::Clock_ - - KEEP_LAST - 20 - - - - PREALLOCATED_WITH_REALLOC - - - RELIABLE - - - - NO_KEY - rt/ap/clock - rosgraph_msgs::msg::dds_::Clock_ - - KEEP_LAST - 20 - - - - - rt/ap/gps_global_origin/filtered - geographic_msgs::msg::dds_::GeoPointStamped_ - - KEEP_LAST - 5 - - - - PREALLOCATED_WITH_REALLOC - - - BEST_EFFORT - - - VOLATILE - - - - NO_KEY - rt/ap/gps_global_origin/filtered - geographic_msgs::msg::dds_::GeoPointStamped_ - - KEEP_LAST - 5 - - - - - rt/ap/joy - sensor_msgs::msg::dds_::Joy_ - - KEEP_LAST - 5 - - - - - NO_KEY - rt/ap/joy - sensor_msgs::msg::dds_::Joy_ - - - - rt/ap/tf - tf2_msgs::msg::dds_::TFMessage_ - - KEEP_LAST - 5 - - - - - NO_KEY - rt/ap/tf - tf2_msgs::msg::dds_::TFMessage_ - - - - rt/ap/cmd_vel - geometry_msgs::msg::dds_::TwistStamped_ - - KEEP_LAST - 5 - - - - - NO_KEY - rt/ap/cmd_vel - geometry_msgs::msg::dds_::TwistStamped_ - - - - rq/ap/arm_motorsRequest - rr/ap/arm_motorsReply - - - rq/ap/mode_switchRequest - rr/ap/mode_switchReply - - - rt/ap/cmd_gps_pose - ardupilot_msgs::msg::dds_::GlobalPosition_ - - KEEP_LAST - 5 - - - - - NO_KEY - rt/ap/cmd_gps_pose - ardupilot_msgs::msg::dds_::GlobalPosition_ - - - diff --git a/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp b/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp index 804d891e161806..35d37bd97d603c 100644 --- a/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp +++ b/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp @@ -1,9 +1,13 @@ #include +#include + #include #include "geometry_msgs/msg/TransformStamped.h" #include +#if AP_DDS_VISUALODOM_ENABLED + const AP_HAL::HAL &hal = AP_HAL::get_HAL(); TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success) @@ -35,4 +39,6 @@ TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success) ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); } +#endif // AP_DDS_VISUALODOM_ENABLED + AP_GTEST_MAIN() diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index ebece8962676ac..fd38e303c42535 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -30,7 +30,7 @@ HAL_Semaphore test_iface_sem; void canard_allocate_sem_take(CanardPoolAllocator *allocator) { if (allocator->semaphore == nullptr) { - allocator->semaphore = new HAL_Semaphore; + allocator->semaphore = NEW_NOTHROW HAL_Semaphore; if (allocator->semaphore == nullptr) { // out of memory CANARD_ASSERT(0); @@ -456,14 +456,15 @@ bool CanardInterface::add_11bit_driver(CANSensor *sensor) } // handler for outgoing frames for auxillary drivers -bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { + const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us; bool ret = false; for (uint8_t iface = 0; iface < num_ifaces; iface++) { if (ifaces[iface] == NULL) { continue; } - ret |= ifaces[iface]->send(out_frame, timeout_us, 0) > 0; + ret |= ifaces[iface]->send(out_frame, tx_deadline_us, 0) > 0; } return ret; } diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index 43d786639fdf05..671722028dffc7 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -54,7 +54,7 @@ class CanardInterface : public Canard::Interface { bool add_11bit_driver(CANSensor *sensor); // handler for outgoing frames for auxillary drivers - bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us); + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us); #if AP_TEST_DRONECAN_DRIVERS static CanardInterface& get_test_iface() { return test_iface; } diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index b72899bf72cae9..a8c9a531c33e43 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -61,6 +61,8 @@ #include +#include + extern const AP_HAL::HAL& hal; // setup default pool size @@ -78,8 +80,8 @@ extern const AP_HAL::HAL& hal; #define DRONECAN_STACK_SIZE 4096 #endif -#ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED -#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0 +#ifndef AP_DRONECAN_DEFAULT_NODE +#define AP_DRONECAN_DEFAULT_NODE 10 #endif #define AP_DRONECAN_GETSET_TIMEOUT_MS 100 // timeout waiting for response from node after 0.1 sec @@ -94,11 +96,11 @@ extern const AP_HAL::HAL& hal; // table of user settable CAN bus parameters const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: NODE - // @DisplayName: DroneCAN node that is used for this network - // @Description: DroneCAN node should be set implicitly - // @Range: 1 250 + // @DisplayName: Own node ID + // @Description: DroneCAN node ID used by the driver itself on this network + // @Range: 1 125 // @User: Advanced - AP_GROUPINFO("NODE", 1, AP_DroneCAN, _dronecan_node, 10), + AP_GROUPINFO("NODE", 1, AP_DroneCAN, _dronecan_node, AP_DRONECAN_DEFAULT_NODE), // @Param: SRV_BM // @DisplayName: Output channels to be transmitted as servo over DroneCAN @@ -126,7 +128,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: OPTION // @DisplayName: DroneCAN options // @Description: Option flags - // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS,6:UseHimarkServo,7:HobbyWingESC,8:EnableStats + // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS,6:UseHimarkServo,7:HobbyWingESC,8:EnableStats,9:EnableFlexDebug // @User: Advanced AP_GROUPINFO("OPTION", 5, AP_DroneCAN, _options, 0), @@ -324,6 +326,11 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: init called more than once\n\r"); return; } + uint8_t node = _dronecan_node; + if (node < 1 || node > 125) { // reset to default if invalid + _dronecan_node.set(AP_DRONECAN_DEFAULT_NODE); + node = AP_DRONECAN_DEFAULT_NODE; + } node_info_rsp.name.len = hal.util->snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index); @@ -341,62 +348,70 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) uint8_t uid_len = sizeof(uavcan_protocol_HardwareVersion::unique_id); uint8_t unique_id[sizeof(uavcan_protocol_HardwareVersion::unique_id)]; - mem_pool = new uint32_t[_pool_size/sizeof(uint32_t)]; + mem_pool = NEW_NOTHROW uint32_t[_pool_size/sizeof(uint32_t)]; if (mem_pool == nullptr) { debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to allocate memory pool\n\r"); return; } - canard_iface.init(mem_pool, (_pool_size/sizeof(uint32_t))*sizeof(uint32_t), _dronecan_node); + canard_iface.init(mem_pool, (_pool_size/sizeof(uint32_t))*sizeof(uint32_t), node); if (!hal.util->get_system_id_unformatted(unique_id, uid_len)) { return; } - unique_id[uid_len - 1] += _dronecan_node; + unique_id[uid_len - 1] += node; memcpy(node_info_rsp.hardware_version.unique_id, unique_id, uid_len); //Start Servers - if (!_dna_server.init(unique_id, uid_len, _dronecan_node)) { + if (!_dna_server.init(unique_id, uid_len, node)) { debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to start DNA Server\n\r"); return; } // Roundup all subscribers from supported drivers + bool subscribed = true; #if AP_GPS_DRONECAN_ENABLED - AP_GPS_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_GPS_DroneCAN::subscribe_msgs(this); #endif #if AP_COMPASS_DRONECAN_ENABLED - AP_Compass_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_Compass_DroneCAN::subscribe_msgs(this); #endif #if AP_BARO_DRONECAN_ENABLED - AP_Baro_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_Baro_DroneCAN::subscribe_msgs(this); #endif - AP_BattMonitor_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_BattMonitor_DroneCAN::subscribe_msgs(this); #if AP_AIRSPEED_DRONECAN_ENABLED - AP_Airspeed_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_Airspeed_DroneCAN::subscribe_msgs(this); #endif #if AP_OPTICALFLOW_HEREFLOW_ENABLED - AP_OpticalFlow_HereFlow::subscribe_msgs(this); + subscribed = subscribed && AP_OpticalFlow_HereFlow::subscribe_msgs(this); #endif #if AP_RANGEFINDER_DRONECAN_ENABLED - AP_RangeFinder_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_RangeFinder_DroneCAN::subscribe_msgs(this); #endif #if AP_RCPROTOCOL_DRONECAN_ENABLED - AP_RCProtocol_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_RCProtocol_DroneCAN::subscribe_msgs(this); #endif #if AP_EFI_DRONECAN_ENABLED - AP_EFI_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_EFI_DroneCAN::subscribe_msgs(this); #endif #if AP_PROXIMITY_DRONECAN_ENABLED - AP_Proximity_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_Proximity_DroneCAN::subscribe_msgs(this); #endif #if HAL_MOUNT_XACTI_ENABLED - AP_Mount_Xacti::subscribe_msgs(this); + subscribed = subscribed && AP_Mount_Xacti::subscribe_msgs(this); #endif #if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED - AP_TemperatureSensor_DroneCAN::subscribe_msgs(this); + subscribed = subscribed && AP_TemperatureSensor_DroneCAN::subscribe_msgs(this); +#endif +#if AP_RPM_DRONECAN_ENABLED + subscribed = subscribed && AP_RPM_DroneCAN::subscribe_msgs(this); #endif + if (!subscribed) { + AP_BoardConfig::allocation_error("DroneCAN callback"); + } + act_out_array.set_timeout_ms(5); act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); @@ -511,6 +526,10 @@ void AP_DroneCAN::loop(void) continue; } + // ensure that the DroneCAN thread cannot completely saturate + // the CPU, preventing low priority threads from running + hal.scheduler->delay_microseconds(100); + canard_iface.process(1); safety_state_send(); @@ -699,14 +718,17 @@ void AP_DroneCAN::handle_node_info_request(const CanardRxTransfer& transfer, con int16_t AP_DroneCAN::scale_esc_output(uint8_t idx){ static const int16_t cmd_max = ((1<<13)-1); - float scaled = 0; - + float scaled = hal.rcout->scale_esc_to_unity(_SRV_conf[idx].pulse); + // Prevent invalid values (from misconfigured scaling parameters) from sending non-zero commands + if (!isfinite(scaled)) { + return 0; + } + scaled = constrain_float(scaled, -1, 1); //Check if this channel has a reversible ESC. If it does, we can send negative commands. if ((((uint32_t) 1) << idx) & _esc_rv) { - scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[idx].pulse)); + scaled *= cmd_max; } else { - scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[idx].pulse) + 1.0) / 2.0; - scaled = constrain_float(scaled, 0, cmd_max); + scaled = cmd_max * (scaled + 1.0) / 2.0; } return static_cast(scaled); @@ -827,9 +849,9 @@ void AP_DroneCAN::SRV_send_esc(void) // if at least one is active (update) we need to send to all if (active_esc_num > 0) { k = 0; - + const bool armed = hal.util->get_soft_armed(); for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) { - if ((((uint32_t) 1) << i) & _ESC_armed_mask) { + if (armed && ((((uint32_t) 1U) << i) & _ESC_armed_mask)) { esc_msg.cmd.data[k] = scale_esc_output(i); } else { esc_msg.cmd.data[k] = static_cast(0); @@ -880,9 +902,9 @@ void AP_DroneCAN::SRV_send_esc_hobbywing(void) // if at least one is active (update) we need to send to all if (active_esc_num > 0) { k = 0; - + const bool armed = hal.util->get_soft_armed(); for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) { - if ((((uint32_t) 1) << i) & _ESC_armed_mask) { + if (armed && ((((uint32_t) 1U) << i) & _ESC_armed_mask)) { esc_msg.command.data[k] = scale_esc_output(i); } else { esc_msg.command.data[k] = static_cast(0); @@ -1410,7 +1432,7 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, ToDeg(msg.actual_position), msg.current * 0.025f, msg.voltage * 0.2f, - msg.motor_pwm * (100.0/255.0), + uint8_t(msg.motor_pwm * (100.0/255.0)), int16_t(msg.motor_temperature) - 50); #endif } @@ -1433,15 +1455,50 @@ void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavc .temperature_cdeg = int16_t((KELVIN_TO_C(msg.temperature)) * 100), .voltage = msg.voltage, .current = msg.current, +#if AP_EXTENDED_ESC_TELEM_ENABLED + .power_percentage = msg.power_rating_pct, +#endif }; update_rpm(esc_index, msg.rpm, msg.error_count); update_telem_data(esc_index, t, (isnan(msg.current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT) | (isnan(msg.voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) - | (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)); + | (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) +#if AP_EXTENDED_ESC_TELEM_ENABLED + | AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE #endif + ); +#endif // HAL_WITH_ESC_TELEM +} + +#if AP_EXTENDED_ESC_TELEM_ENABLED +/* + handle Extended ESC status message + */ +void AP_DroneCAN::handle_esc_ext_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_StatusExtended& msg) +{ + const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER); + const uint8_t esc_index = msg.esc_index + esc_offset; + + if (!is_esc_data_index_valid(esc_index)) { + return; + } + + TelemetryData telemetryData { + .motor_temp_cdeg = (int16_t)(msg.motor_temperature_degC * 100), + .input_duty = msg.input_pct, + .output_duty = msg.output_pct, + .flags = msg.status_flags, + }; + + update_telem_data(esc_index, telemetryData, + AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE + | AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY + | AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY + | AP_ESC_Telem_Backend::TelemetryType::FLAGS); } +#endif // AP_EXTENDED_ESC_TELEM_ENABLED bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) { if (index > DRONECAN_SRV_NUMBER) { @@ -1451,6 +1508,62 @@ bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) { return true; } +#if AP_SCRIPTING_ENABLED +/* + handle FlexDebug message, holding a copy locally for a lua script to access + */ +void AP_DroneCAN::handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug &msg) +{ + if (!option_is_set(Options::ENABLE_FLEX_DEBUG)) { + return; + } + + // find an existing element in the list + const uint8_t source_node = transfer.source_node_id; + for (auto *p = flexDebug_list; p != nullptr; p = p->next) { + if (p->node_id == source_node && p->msg.id == msg.id) { + p->msg = msg; + p->timestamp_us = uint32_t(transfer.timestamp_usec); + return; + } + } + + // new message ID, add to the list. Note that this gets called + // only from one thread, so no lock needed + auto *p = NEW_NOTHROW FlexDebug; + if (p == nullptr) { + return; + } + p->node_id = source_node; + p->msg = msg; + p->timestamp_us = uint32_t(transfer.timestamp_usec); + p->next = flexDebug_list; + + // link into the list + flexDebug_list = p; +} + +/* + get the last FlexDebug message from a node + */ +bool AP_DroneCAN::get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t ×tamp_us, dronecan_protocol_FlexDebug &msg) const +{ + for (const auto *p = flexDebug_list; p != nullptr; p = p->next) { + if (p->node_id == node_id && p->msg.id == msg_id) { + if (timestamp_us == p->timestamp_us) { + // stale message + return false; + } + timestamp_us = p->timestamp_us; + msg = p->msg; + return true; + } + } + return false; +} + +#endif // AP_SCRIPTING_ENABLED + /* handle LogMessage debug */ @@ -1848,7 +1961,7 @@ bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor) } // handler for outgoing frames for auxillary drivers -bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { if (out_frame.isExtended()) { // don't allow extended frames to be sent by auxillary driver diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 8b37c2528b89b9..9a7ae54c6639c3 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -64,6 +64,10 @@ #define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024) #endif +#ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED +#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0 +#endif + #if AP_DRONECAN_SERIAL_ENABLED #include "AP_DroneCAN_serial.h" #endif @@ -91,7 +95,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { bool add_11bit_driver(CANSensor *sensor) override; // handler for outgoing frames for auxillary drivers - bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) override; + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) override; uint8_t get_driver_index() const { return _driver_index; } @@ -144,6 +148,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { USE_HIMARK_SERVO = (1U<<6), USE_HOBBYWING_ESC = (1U<<7), ENABLE_STATS = (1U<<8), + ENABLE_FLEX_DEBUG = (1U<<9), }; // check if a option is set @@ -172,6 +177,10 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::Publisher relay_hardpoint{canard_iface}; #endif +#if AP_SCRIPTING_ENABLED + bool get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t ×tamp_us, dronecan_protocol_FlexDebug &msg) const; +#endif + private: void loop(void); @@ -231,10 +240,12 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint32_t *mem_pool; - AP_DroneCAN_DNA_Server _dna_server; - uint8_t _driver_index; + CanardInterface canard_iface; + + AP_DroneCAN_DNA_Server _dna_server; + char _thread_name[13]; bool _initialized; ///// SRV output ///// @@ -288,8 +299,6 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { } _relay; #endif - CanardInterface canard_iface; - #if AP_DRONECAN_SERIAL_ENABLED AP_DroneCAN_Serial serial; #endif @@ -326,9 +335,19 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::ObjCallback esc_status_cb{this, &AP_DroneCAN::handle_ESC_status}; Canard::Subscriber esc_status_listener{esc_status_cb, _driver_index}; +#if AP_EXTENDED_ESC_TELEM_ENABLED + Canard::ObjCallback esc_status_extended_cb{this, &AP_DroneCAN::handle_esc_ext_status}; + Canard::Subscriber esc_status_extended_listener{esc_status_extended_cb, _driver_index}; +#endif + Canard::ObjCallback debug_cb{this, &AP_DroneCAN::handle_debug}; Canard::Subscriber debug_listener{debug_cb, _driver_index}; +#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED + Canard::ObjCallback volz_servo_ActuatorStatus_cb{this, &AP_DroneCAN::handle_actuator_status_Volz}; + Canard::Subscriber volz_servo_ActuatorStatus_listener{volz_servo_ActuatorStatus_cb, _driver_index}; +#endif + // param client Canard::ObjCallback param_get_set_res_cb{this, &AP_DroneCAN::handle_param_get_set_response}; Canard::Client param_get_set_client{canard_iface, param_get_set_res_cb}; @@ -349,6 +368,11 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::Server node_info_server{canard_iface, node_info_req_cb}; uavcan_protocol_GetNodeInfoResponse node_info_rsp; +#if AP_SCRIPTING_ENABLED + Canard::ObjCallback FlexDebug_cb{this, &AP_DroneCAN::handle_FlexDebug}; + Canard::Subscriber FlexDebug_listener{FlexDebug_cb, _driver_index}; +#endif + #if AP_DRONECAN_HOBBYWING_ESC_SUPPORT /* Hobbywing ESC support. Note that we need additional meta-data as @@ -387,11 +411,24 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { void handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg); void handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg); void handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg); +#if AP_EXTENDED_ESC_TELEM_ENABLED + void handle_esc_ext_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_StatusExtended& msg); +#endif static bool is_esc_data_index_valid(const uint8_t index); void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg); void handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp); void handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp); void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req); + +#if AP_SCRIPTING_ENABLED + void handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug& msg); + struct FlexDebug { + struct FlexDebug *next; + uint32_t timestamp_us; + uint8_t node_id; + dronecan_protocol_FlexDebug msg; + } *flexDebug_list; +#endif }; #endif // #if HAL_ENABLE_DRONECAN_DRIVERS diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 12262859c53a0b..74ac9452cc0c68 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -1,4 +1,3 @@ - /* * 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 @@ -30,185 +29,231 @@ #include extern const AP_HAL::HAL& hal; -#define NODEDATA_MAGIC 0xAC01 -#define NODEDATA_MAGIC_LEN 2 +// FORMAT REVISION DREAMS (things to address if the NodeRecord needs to be changed substantially) +// * have DNA server accept only a 16 byte local UID to avoid overhead from variable sized hash +// * have a real empty flag for entries and/or use a CRC which is not zero for an input of all zeros +// * fix FNV-1a hash folding to be to 48 bits (6 bytes) instead of 56 + +#define NODERECORD_MAGIC 0xAC01 +#define NODERECORD_MAGIC_LEN 2 // uint16_t #define MAX_NODE_ID 125 +#define NODERECORD_LOC(node_id) ((node_id * sizeof(NodeRecord)) + NODERECORD_MAGIC_LEN) #define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0) -AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index) : - _ap_dronecan(ap_dronecan), - _canard_iface(canard_iface), - storage(StorageManager::StorageCANDNA), - allocation_sub(allocation_cb, driver_index), - node_status_sub(node_status_cb, driver_index), - node_info_client(_canard_iface, node_info_cb) -{} +// database is currently shared by all DNA servers +AP_DroneCAN_DNA_Server::Database AP_DroneCAN_DNA_Server::db; -/* Method to generate 6byte hash from the Unique ID. -We return it packed inside the referenced NodeData structure */ -void AP_DroneCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const +// initialize database (storage accessor is always replaced with the one supplied) +void AP_DroneCAN_DNA_Server::Database::init(StorageAccess *storage_) { - uint64_t hash = FNV_1_OFFSET_BASIS_64; - hash_fnv_1a(size, unique_id, &hash); + // storage size must be synced with StorageCANDNA entry in StorageManager.cpp + static_assert(NODERECORD_LOC(MAX_NODE_ID+1) <= 1024, "DNA storage too small"); - // xor-folding per http://www.isthe.com/chongo/tech/comp/fnv/ - hash = (hash>>56) ^ (hash&(((uint64_t)1<<56)-1)); + // might be called from multiple threads if multiple servers use the same database + WITH_SEMAPHORE(sem); - // write it to ret - for (uint8_t i=0; i<6; i++) { - node_data.hwid_hash[i] = (hash >> (8*i)) & 0xff; + storage = storage_; // use supplied accessor + + // validate magic number + uint16_t magic = storage->read_uint16(0); + if (magic != NODERECORD_MAGIC) { + reset(); // resetting the database will put the magic back + } + + // check and note each possible node ID's registration's presence + for (uint8_t i = 1; i <= MAX_NODE_ID; i++) { + if (check_registration(i)) { + node_registered.set(i); + } } } -//Read Node Data from Storage Region -bool AP_DroneCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id) +// remove all registrations from the database +void AP_DroneCAN_DNA_Server::Database::reset() { - 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; - return false; + WITH_SEMAPHORE(sem); + + NodeRecord record; + memset(&record, 0, sizeof(record)); + node_registered.clearall(); + + // all-zero record means no registration + // ensure node ID 0 is cleared even if we can't use it so we know the state + for (uint8_t i = 0; i <= MAX_NODE_ID; i++) { + write_record(record, i); } - return true; + + // mark the magic at the start to indicate a valid (and reset) database + storage->write_uint16(0, NODERECORD_MAGIC); } -//Write Node Data to Storage Region -bool AP_DroneCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id) +// handle initializing the server with its own node ID and unique ID +void AP_DroneCAN_DNA_Server::Database::init_server(uint8_t own_node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len) { - 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; - return false; + WITH_SEMAPHORE(sem); + + // register server node ID and unique ID if not correctly registered. note + // that ardupilot mixes the node ID into the unique ID so changing the node + // ID will "leak" the old node ID + if (own_node_id != find_node_id(own_unique_id, own_unique_id_len)) { + register_uid(own_node_id, own_unique_id, own_unique_id_len); } - return true; } -/* Set Occupation Mask, handy for keeping track of all node ids that -are allocated and all that are available. */ -bool AP_DroneCAN_DNA_Server::setOccupationMask(uint8_t node_id) +// handle processing the node info message. returns true if from a duplicate node +bool AP_DroneCAN_DNA_Server::Database::handle_node_info(uint8_t source_node_id, const uint8_t unique_id[]) { - if (node_id > MAX_NODE_ID) { - return false; + WITH_SEMAPHORE(sem); + + if (is_registered(source_node_id)) { + // this device's node ID is associated with a different unique ID + if (source_node_id != find_node_id(unique_id, 16)) { + return true; // so raise as duplicate + } + } else { + register_uid(source_node_id, unique_id, 16); // we don't know about this node ID, let's register it } - occupation_mask.set(node_id); - return true; + return false; // not a duplicate } -/* Remove Node Data from Server Record in Storage, -and also clear Occupation Mask */ -bool AP_DroneCAN_DNA_Server::freeNodeID(uint8_t node_id) +// handle the allocation message. returns the allocated node ID, or 0 if allocation failed +uint8_t AP_DroneCAN_DNA_Server::Database::handle_allocation(const uint8_t unique_id[]) { - if (node_id > MAX_NODE_ID) { - return false; + WITH_SEMAPHORE(sem); + + uint8_t resp_node_id = find_node_id(unique_id, 16); + if (resp_node_id == 0) { + // find free node ID, starting at the max as prescribed by the standard + resp_node_id = MAX_NODE_ID; + while (resp_node_id > 0) { + if (!node_registered.get(resp_node_id)) { + break; + } + resp_node_id--; + } + + if (resp_node_id != 0) { + create_registration(resp_node_id, unique_id, 16); + } } + return resp_node_id; // will be 0 if not found and not created +} - struct NodeData node_data; +// retrieve node ID that matches the given unique ID. returns 0 if not found +uint8_t AP_DroneCAN_DNA_Server::Database::find_node_id(const uint8_t unique_id[], uint8_t size) +{ + NodeRecord record, cmp_record; + compute_uid_hash(cmp_record, unique_id, size); + + for (int i = MAX_NODE_ID; i > 0; i--) { + if (node_registered.get(i)) { + read_record(record, i); + if (memcmp(record.uid_hash, cmp_record.uid_hash, sizeof(NodeRecord::uid_hash)) == 0) { + return i; // node ID found + } + } + } + return 0; // not found +} - //Eliminate from Server Record - memset(&node_data, 0, sizeof(node_data)); - writeNodeData(node_data, node_id); +// fill the given record with the hash of the given unique ID +void AP_DroneCAN_DNA_Server::Database::compute_uid_hash(NodeRecord &record, const uint8_t unique_id[], uint8_t size) const +{ + uint64_t hash = FNV_1_OFFSET_BASIS_64; + hash_fnv_1a(size, unique_id, &hash); - //Clear Occupation Mask - occupation_mask.clear(node_id); + // xor-folding per http://www.isthe.com/chongo/tech/comp/fnv/ + hash = (hash>>56) ^ (hash&(((uint64_t)1<<56)-1)); // 56 should be 48 since we use 6 bytes - return true; + // write it to ret + for (uint8_t i=0; i<6; i++) { + record.uid_hash[i] = (hash >> (8*i)) & 0xff; + } } -/* Sets the verification mask. This is to be called, once -The Seen Node has been both registered and verified against the -Server Records. */ -void AP_DroneCAN_DNA_Server::setVerificationMask(uint8_t node_id) +// register a given unique ID to a given node ID, deleting any existing registration for the unique ID +void AP_DroneCAN_DNA_Server::Database::register_uid(uint8_t node_id, const uint8_t unique_id[], uint8_t size) { - if (node_id > MAX_NODE_ID) { - return; + uint8_t prev_node_id = find_node_id(unique_id, size); // have we registered this unique ID under a different node ID? + if (prev_node_id != 0) { + delete_registration(prev_node_id); // yes, delete old node ID's registration } - verified_mask.set(node_id); + // overwrite an existing registration with this node ID, if any + create_registration(node_id, unique_id, size); } -/* Checks if the NodeID is occupied, i.e. its recorded -in the Server Records against a unique ID */ -bool AP_DroneCAN_DNA_Server::isNodeIDOccupied(uint8_t node_id) const +// create the registration for the given node ID and set its record's unique ID +void AP_DroneCAN_DNA_Server::Database::create_registration(uint8_t node_id, const uint8_t unique_id[], uint8_t size) { - if (node_id > MAX_NODE_ID) { - return false; - } - return occupation_mask.get(node_id); + NodeRecord record; + compute_uid_hash(record, unique_id, size); + // compute and store CRC of the record's data to validate it + record.crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash)); + + write_record(record, node_id); + + node_registered.set(node_id); } -/* Checks if NodeID is verified, i.e. the unique id in -Storage Records matches the one provided by Device with this node id. */ -bool AP_DroneCAN_DNA_Server::isNodeIDVerified(uint8_t node_id) const +// delete the given node ID's registration +void AP_DroneCAN_DNA_Server::Database::delete_registration(uint8_t node_id) { if (node_id > MAX_NODE_ID) { - return false; + return; } - return verified_mask.get(node_id); + + NodeRecord record; + + // all-zero record means no registration + memset(&record, 0, sizeof(record)); + write_record(record, node_id); + node_registered.clear(node_id); } -/* Go through Server Records, and fetch node id that matches the provided -Unique IDs hash. -Returns 255 if no Node ID was detected */ -uint8_t AP_DroneCAN_DNA_Server::getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size) +// return true if the given node ID has a registration +bool AP_DroneCAN_DNA_Server::Database::check_registration(uint8_t node_id) { - uint8_t node_id = 255; - NodeData node_data, cmp_node_data; - getHash(cmp_node_data, unique_id, size); + NodeRecord record; + read_record(record, node_id); - for (int i = MAX_NODE_ID; i >= 0; i--) { - if (!isNodeIDOccupied(i)) { // No point in checking NodeID that's not taken - continue; - } - if (!readNodeData(node_data, i)) { - break; //Storage module has failed, report that as no NodeID detected - } - if (memcmp(node_data.hwid_hash, cmp_node_data.hwid_hash, sizeof(NodeData::hwid_hash)) == 0) { - node_id = i; - break; - } + uint8_t empty_uid[sizeof(NodeRecord::uid_hash)] {}; + uint8_t crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash)); + if (crc == record.crc && memcmp(&record.uid_hash[0], &empty_uid[0], sizeof(empty_uid)) != 0) { + return true; // CRC matches and UID hash is not all zero } - return node_id; + return false; } -/* Hash the Unique ID and add it to the Server Record -for specified Node ID. */ -bool AP_DroneCAN_DNA_Server::addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size) +// read the given node ID's registration's record +void AP_DroneCAN_DNA_Server::Database::read_record(NodeRecord &record, uint8_t node_id) { - NodeData node_data; - getHash(node_data, unique_id, size); - //Generate CRC for validating the data when read back - node_data.crc = crc_crc8(node_data.hwid_hash, sizeof(node_data.hwid_hash)); - - //Write Data to the records - if (!writeNodeData(node_data, node_id)) { - server_state = FAILED_TO_ADD_NODE; - fault_node_id = node_id; - return false; + if (node_id > MAX_NODE_ID) { + return; } - setOccupationMask(node_id); - return true; + storage->read_block(&record, NODERECORD_LOC(node_id), sizeof(NodeRecord)); } -//Checks if a valid Server Record is present for specified Node ID -bool AP_DroneCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) +// write the given node ID's registration's record +void AP_DroneCAN_DNA_Server::Database::write_record(const NodeRecord &record, uint8_t node_id) { - NodeData node_data; - readNodeData(node_data, node_id); - uint8_t crc = crc_crc8(node_data.hwid_hash, sizeof(node_data.hwid_hash)); - if (crc == node_data.crc && node_data.crc != 0) { - return true; + if (node_id > MAX_NODE_ID) { + return; } - return false; + + storage->write_block(NODERECORD_LOC(node_id), &record, sizeof(NodeRecord)); } + +AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index) : + storage(StorageManager::StorageCANDNA), + _ap_dronecan(ap_dronecan), + _canard_iface(canard_iface), + allocation_sub(allocation_cb, driver_index), + node_status_sub(node_status_cb, driver_index), + node_info_client(_canard_iface, node_info_cb) {} + /* Initialises Publishers for respective UAVCAN Instance Also resets the Server Record in case there is a mismatch between specified node id and unique id against the existing @@ -217,130 +262,25 @@ bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id { //Read the details from AP_DroneCAN server_state = HEALTHY; - /* Go through our records and look for valid NodeData, to initialise - occupation mask */ - for (uint8_t i = 0; i <= MAX_NODE_ID; i++) { - if (isValidNodeDataAvailable(i)) { - occupation_mask.set(i); - } - } - // Check if the magic is present - uint16_t magic; - { - 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(); - } + db.init(&storage); // initialize the database with our accessor + if (_ap_dronecan.check_and_reset_option(AP_DroneCAN::Options::DNA_CLEAR_DATABASE)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset"); - reset(); - } - // Making sure that the server is started with the same node ID - const uint8_t stored_own_node_id = getNodeIDForUniqueID(own_unique_id, own_unique_id_len); - static bool reset_done; - if (stored_own_node_id != 255) { - if (stored_own_node_id != node_id) { - /* We have a different node id recorded against our own unique id - This calls for a reset */ - if (!reset_done) { - /* ensure we only reset once per power cycle - else we will wipe own record on next init(s) */ - reset(); - reset_done = true; - } - //Add ourselves to the Server Record - if (!addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len)) { - return false; - } - } - } else { - //We have no record of our own Unique ID do a reset - if (!reset_done) { - /* ensure we only reset once per power cycle - else we will wipe own record on next init(s) */ - reset(); - reset_done = true; - } - //Add ourselves to the Server Record - if (!addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len)) { - return false; - } + db.reset(); } + + db.init_server(node_id, own_unique_id, own_unique_id_len); + /* Also add to seen node id this is to verify if any duplicates are on the bus carrying our Node ID */ - addToSeenNodeMask(node_id); - setVerificationMask(node_id); - node_healthy_mask.set(node_id); + node_seen.set(node_id); + node_verified.set(node_id); + node_healthy.set(node_id); self_node_id = node_id; return true; } - -//Reset the Server Records -void AP_DroneCAN_DNA_Server::reset() -{ - NodeData node_data; - memset(&node_data, 0, sizeof(node_data)); - occupation_mask.clearall(); - - //Just write empty Node Data to the Records - 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); -} - -/* Go through the Occupation mask for available Node ID -based on pseudo code provided in -uavcan/protocol/dynamic_node_id/1.Allocation.uavcan */ -uint8_t AP_DroneCAN_DNA_Server::findFreeNodeID(uint8_t preferred) -{ - // Search up - uint8_t candidate = (preferred > 0) ? preferred : 125; - while (candidate <= 125) { - if (!isNodeIDOccupied(candidate)) { - return candidate; - } - candidate++; - } - //Search down - candidate = (preferred > 0) ? preferred : 125; - while (candidate > 0) { - if (!isNodeIDOccupied(candidate)) { - return candidate; - } - candidate--; - } - // Not found - return 255; -} - -//Check if we have received Node Status from this node_id -bool AP_DroneCAN_DNA_Server::isNodeSeen(uint8_t node_id) -{ - if (node_id > MAX_NODE_ID) { - return false; - } - return node_seen_mask.get(node_id); -} - -/* Set the Seen Node Mask, to be called when received -Node Status from the node id */ -void AP_DroneCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id) -{ - if (node_id > MAX_NODE_ID) { - return; - } - node_seen_mask.set(node_id); -} - /* Run through the list of seen node ids for verification no more than once per 5 second. We continually verify the nodes in our seen list, So that we can raise issue if there are duplicates @@ -356,7 +296,7 @@ void AP_DroneCAN_DNA_Server::verify_nodes() uint8_t log_count = AP::logger().get_log_start_count(); if (log_count != last_logging_count) { last_logging_count = log_count; - logged.clearall(); + node_logged.clearall(); } #endif @@ -371,12 +311,7 @@ void AP_DroneCAN_DNA_Server::verify_nodes() Reason for this could be either the node was disconnected Or a node with conflicting ID appeared and is sending response at the same time. */ - /* Only report if the node was verified, otherwise ignore - as this could be just Bootloader to Application transition. */ - if (isNodeIDVerified(curr_verifying_node)) { - // remove verification flag for this node - verified_mask.clear(curr_verifying_node); - } + node_verified.clear(curr_verifying_node); } last_verification_request = now; @@ -386,11 +321,11 @@ void AP_DroneCAN_DNA_Server::verify_nodes() if ((curr_verifying_node == self_node_id) || (curr_verifying_node == 0)) { continue; } - if (isNodeSeen(curr_verifying_node)) { + if (node_seen.get(curr_verifying_node)) { break; } } - if (isNodeIDOccupied(curr_verifying_node)) { + if (db.is_registered(curr_verifying_node)) { uavcan_protocol_GetNodeInfoRequest request; node_info_client.request(curr_verifying_node, request); nodeInfo_resp_rcvd = false; @@ -411,20 +346,20 @@ void AP_DroneCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, //if node is not healthy or operational, clear resp health mask, and set fault_node_id fault_node_id = transfer.source_node_id; server_state = NODE_STATUS_UNHEALTHY; - node_healthy_mask.clear(transfer.source_node_id); + node_healthy.clear(transfer.source_node_id); } else { - node_healthy_mask.set(transfer.source_node_id); - if (node_healthy_mask == verified_mask) { + node_healthy.set(transfer.source_node_id); + if (node_healthy == node_verified) { server_state = HEALTHY; } } - if (!isNodeIDVerified(transfer.source_node_id)) { + if (!node_verified.get(transfer.source_node_id)) { //immediately begin verification of the node_id uavcan_protocol_GetNodeInfoRequest request; node_info_client.request(transfer.source_node_id, request); } //Add node to seen list if not seen before - addToSeenNodeMask(transfer.source_node_id); + node_seen.set(transfer.source_node_id); } /* Node Info message handler @@ -434,15 +369,15 @@ Or register if the node id is available and not recorded for the received Unique ID */ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp) { - if (transfer.source_node_id > MAX_NODE_ID) { + if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) { return; } /* if we haven't logged this node then log it now */ #if HAL_LOGGING_ENABLED - if (!logged.get(transfer.source_node_id) && AP::logger().logging_started()) { - logged.set(transfer.source_node_id); + if (!node_logged.get(transfer.source_node_id) && AP::logger().logging_started()) { + node_logged.set(transfer.source_node_id); uint64_t uid[2]; memcpy(uid, rsp.hardware_version.unique_id, sizeof(rsp.hardware_version.unique_id)); // @LoggerMessage: CAND @@ -469,14 +404,9 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co } #endif - if (isNodeIDOccupied(transfer.source_node_id)) { - //if node_id already registered, just verify if Unique ID matches as well - if (transfer.source_node_id == getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16)) { - if (transfer.source_node_id == curr_verifying_node) { - nodeInfo_resp_rcvd = true; - } - setVerificationMask(transfer.source_node_id); - } else if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { + bool duplicate = db.handle_node_info(transfer.source_node_id, rsp.hardware_version.unique_id); + if (duplicate) { + if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { /* This is a device with node_id already registered for another device */ server_state = DUPLICATE_NODES; @@ -484,97 +414,76 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co memcpy(fault_node_name, rsp.name.data, sizeof(fault_node_name)); } } else { - /* Node Id was not allocated by us, or during this boot, let's register this in our records - Check if we allocated this Node before */ - uint8_t prev_node_id = getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16); - if (prev_node_id != 255) { - //yes we did, remove this registration - freeNodeID(prev_node_id); - } - //add a new server record - addNodeIDForUniqueID(transfer.source_node_id, rsp.hardware_version.unique_id, 16); //Verify as well - setVerificationMask(transfer.source_node_id); + node_verified.set(transfer.source_node_id); if (transfer.source_node_id == curr_verifying_node) { nodeInfo_resp_rcvd = true; } } } -/* Handle the allocation message from the devices supporting -dynamic node allocation. */ -void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg) +// process node ID allocation messages for DNA +void AP_DroneCAN_DNA_Server::handle_allocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg) { if (transfer.source_node_id != 0) { - //Ignore Allocation messages that are not DNA requests - return; + return; // ignore allocation messages that are not DNA requests } uint32_t now = AP_HAL::millis(); - if (rcvd_unique_id_offset == 0 || - (now - last_alloc_msg_ms) > 500) { - if (msg.first_part_of_unique_id) { - rcvd_unique_id_offset = 0; - memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); - } else { - //we are only accepting first part - return; - } - } else if (msg.first_part_of_unique_id) { - // we are only accepting follow up messages - return; + if ((now - last_alloc_msg_ms) > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_FOLLOWUP_TIMEOUT_MS) { + rcvd_unique_id_offset = 0; // reset state, timed out + } + + if (msg.first_part_of_unique_id) { + // nodes waiting to send a follow up will instead send a first part + // again if they see another allocation message. therefore we should + // always reset and process a received first part, since any node we + // were allocating will never send its follow up and we'd just time out + rcvd_unique_id_offset = 0; + } else if (rcvd_unique_id_offset == 0) { + return; // not first part but we are expecting one, ignore } if (rcvd_unique_id_offset) { - debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", - (long int)AP_HAL::millis(), + debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting Followup part! %u\n", + (unsigned long)now, unsigned((now - last_alloc_msg_ms))); } else { - debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", - (long int)AP_HAL::millis(), + debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting First part! %u\n", + (unsigned long)now, unsigned((now - last_alloc_msg_ms))); } last_alloc_msg_ms = now; - if ((rcvd_unique_id_offset + msg.unique_id.len) > 16) { - //This request is malformed, Reset! - rcvd_unique_id_offset = 0; - memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); + if ((rcvd_unique_id_offset + msg.unique_id.len) > sizeof(rcvd_unique_id)) { + rcvd_unique_id_offset = 0; // reset state, request contains an over-long ID return; } - //copy over the unique_id - for (uint8_t i=rcvd_unique_id_offset; i<(rcvd_unique_id_offset + msg.unique_id.len); i++) { - rcvd_unique_id[i] = msg.unique_id.data[i - rcvd_unique_id_offset]; - } + // save the new portion of the unique ID + memcpy(&rcvd_unique_id[rcvd_unique_id_offset], msg.unique_id.data, msg.unique_id.len); rcvd_unique_id_offset += msg.unique_id.len; - //send follow up message + // respond with the message containing the received unique ID so far, or + // with the node ID if we successfully allocated one uavcan_protocol_dynamic_node_id_Allocation rsp {}; - - /* Respond with the message containing the received unique ID so far - or with node id if we successfully allocated one. */ memcpy(rsp.unique_id.data, rcvd_unique_id, rcvd_unique_id_offset); rsp.unique_id.len = rcvd_unique_id_offset; - if (rcvd_unique_id_offset == 16) { - //We have received the full Unique ID, time to do allocation - uint8_t resp_node_id = getNodeIDForUniqueID((const uint8_t*)rcvd_unique_id, 16); - if (resp_node_id == 255) { - resp_node_id = findFreeNodeID(msg.node_id); - if (resp_node_id != 255) { - if (addNodeIDForUniqueID(resp_node_id, (const uint8_t*)rcvd_unique_id, 16)) { - rsp.node_id = resp_node_id; - } - } else { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UC Node Alloc Failed!"); - } - } else { - rsp.node_id = resp_node_id; + if (rcvd_unique_id_offset == sizeof(rcvd_unique_id)) { // full unique ID received, allocate it! + // we ignore the preferred node ID as it seems nobody uses the feature + // and we couldn't guarantee it anyway. we will always remember and + // re-assign node IDs consistently, so the node could send a status + // with a particular ID once then switch back to no preference for DNA + rsp.node_id = db.handle_allocation(rcvd_unique_id); + rcvd_unique_id_offset = 0; // reset state for next allocation + if (rsp.node_id == 0) { // allocation failed + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN DNA allocation failed; database full"); + // don't send reply with a failed ID in case the allocatee does + // silly things, though it is technically legal. the allocatee will + // then time out and try again (though we still won't have an ID!) + return; } - //reset states as well - rcvd_unique_id_offset = 0; - memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); } allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD @@ -586,10 +495,6 @@ bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) switch (server_state) { case HEALTHY: return true; - case STORAGE_FAILURE: { - snprintf(fail_msg, fail_msg_len, "Failed to access storage!"); - return false; - } case DUPLICATE_NODES: { if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { // ignore error @@ -598,10 +503,6 @@ bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) snprintf(fail_msg, fail_msg_len, "Duplicate Node %s../%d!", fault_node_name, fault_node_id); return false; } - case FAILED_TO_ADD_NODE: { - snprintf(fail_msg, fail_msg_len, "Failed to add Node %d!", fault_node_id); - return false; - } case NODE_STATUS_UNHEALTHY: { if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { // ignore error diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h index ee58191e803c3d..d68f6a4c67dc62 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h @@ -18,16 +18,87 @@ class AP_DroneCAN_DNA_Server { StorageAccess storage; - struct NodeData { - uint8_t hwid_hash[6]; + struct NodeRecord { + uint8_t uid_hash[6]; uint8_t crc; }; + /* + * For each node ID (1 through MAX_NODE_ID), the database can have one + * registration for it. Each registration consists of a NodeRecord which + * contains the (hash of the) unique ID reported by that node ID. Other + * info could be added to the registration in the future. + * + * Physically, the database is stored as a header and format version, + * followed by an array of NodeRecords indexed by node ID. If a particular + * NodeRecord has an all-zero unique ID hash or an invalid CRC, then that + * node ID isn't considerd to have a registration. + * + * The database has public methods which handle the server behavior for the + * relevant message. The methods can be used by multiple servers in + * different threads, so each holds a lock for its duration. + */ + class Database { + public: + Database() {}; + + // initialize database (storage accessor is always replaced with the one supplied) + void init(StorageAccess *storage_); + + // remove all registrations from the database + void reset(); + + // return true if the given node ID is registered + bool is_registered(uint8_t node_id) { + return node_registered.get(node_id); + } + + // handle initializing the server with its own node ID and unique ID + void init_server(uint8_t own_node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len); + + // handle processing the node info message. returns true if from a duplicate node + bool handle_node_info(uint8_t source_node_id, const uint8_t unique_id[]); + + // handle the allocation message. returns the allocated node ID, or 0 if allocation failed + uint8_t handle_allocation(const uint8_t unique_id[]); + + private: + // retrieve node ID that matches the given unique ID. returns 0 if not found + uint8_t find_node_id(const uint8_t unique_id[], uint8_t size); + + // fill the given record with the hash of the given unique ID + void compute_uid_hash(NodeRecord &record, const uint8_t unique_id[], uint8_t size) const; + + // register a given unique ID to a given node ID, deleting any existing registration for the unique ID + void register_uid(uint8_t node_id, const uint8_t unique_id[], uint8_t size); + + // create the registration for the given node ID and set its record's unique ID + void create_registration(uint8_t node_id, const uint8_t unique_id[], uint8_t size); + + // delete the given node ID's registration + void delete_registration(uint8_t node_id); + + // return true if the given node ID has a registration + bool check_registration(uint8_t node_id); + + // read the given node ID's registration's record + void read_record(NodeRecord &record, uint8_t node_id); + + // write the given node ID's registration's record + void write_record(const NodeRecord &record, uint8_t node_id); + + // bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID) + Bitmask<128> node_registered; // have a registration for this node ID + + StorageAccess *storage; + HAL_Semaphore sem; + }; + + static Database db; + enum ServerState { NODE_STATUS_UNHEALTHY = -5, - STORAGE_FAILURE = -3, DUPLICATE_NODES = -2, - FAILED_TO_ADD_NODE = -1, HEALTHY = 0 }; @@ -36,11 +107,11 @@ class AP_DroneCAN_DNA_Server uint8_t self_node_id; bool nodeInfo_resp_rcvd; - Bitmask<128> occupation_mask; - Bitmask<128> verified_mask; - Bitmask<128> node_seen_mask; - Bitmask<128> logged; - Bitmask<128> node_healthy_mask; + // bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID) + Bitmask<128> node_verified; // node seen and unique ID matches stored + Bitmask<128> node_seen; // received NodeStatus + Bitmask<128> node_logged; // written to log fle + Bitmask<128> node_healthy; // reports healthy uint8_t last_logging_count; @@ -50,51 +121,17 @@ class AP_DroneCAN_DNA_Server char fault_node_name[15]; - //Allocation params + // dynamic node ID allocation state variables uint8_t rcvd_unique_id[16]; uint8_t rcvd_unique_id_offset; uint32_t last_alloc_msg_ms; - //Methods to handle and report Node IDs seen on the bus - void addToSeenNodeMask(uint8_t node_id); - bool isNodeSeen(uint8_t node_id); - - //Generates 6Byte long hash from the specified unique_id - void getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const; - - //Reads the Server Record from storage for specified node id - bool readNodeData(NodeData &data, uint8_t node_id); - - //Writes the Server Record from storage for specified node id - bool writeNodeData(const NodeData &data, uint8_t node_id); - - //Methods to set, clear and report NodeIDs allocated/registered so far - bool setOccupationMask(uint8_t node_id); - bool isNodeIDOccupied(uint8_t node_id) const; - bool freeNodeID(uint8_t node_id); - - //Set the mask to report that the unique id matches the record - void setVerificationMask(uint8_t node_id); - - //Go through List to find node id for specified unique id - uint8_t getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size); - - //Add Node ID info to the record and setup necessary mask fields - bool addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size); - - //Finds next available free Node, starting from preferred NodeID - uint8_t findFreeNodeID(uint8_t preferred); - - //Look in the storage and check if there's a valid Server Record there - bool isValidNodeDataAvailable(uint8_t node_id); - - HAL_Semaphore storage_sem; AP_DroneCAN &_ap_dronecan; CanardInterface &_canard_iface; Canard::Publisher allocation_pub{_canard_iface}; - Canard::ObjCallback allocation_cb{this, &AP_DroneCAN_DNA_Server::handleAllocation}; + Canard::ObjCallback allocation_cb{this, &AP_DroneCAN_DNA_Server::handle_allocation}; Canard::Subscriber allocation_sub; Canard::ObjCallback node_status_cb{this, &AP_DroneCAN_DNA_Server::handleNodeStatus}; @@ -113,24 +150,11 @@ class AP_DroneCAN_DNA_Server //Initialises publisher and Server Record for specified uavcan driver bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id); - //Reset the Server Record - void reset(); - - /* Checks if the node id has been verified against the record - Specific CAN drivers are expected to check use this method to - verify if the node is healthy and has static node_id against - hwid in the records */ - bool isNodeIDVerified(uint8_t node_id) const; - - /* Subscribe to the messages to be handled for maintaining and allocating - Node ID list */ - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - //report the server state, along with failure message if any bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; - //Callbacks - void handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg); + // canard message handler callbacks + void handle_allocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg); void handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg); void handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp index f0bbd72884d1ad..bf5b94edaa22ac 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp @@ -52,7 +52,7 @@ void AP_DroneCAN_Serial::init(AP_DroneCAN *_dronecan) if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("serial_tunnel_sub"); } - targetted = new Canard::Publisher(dronecan->get_canard_iface()); + targetted = NEW_NOTHROW Canard::Publisher(dronecan->get_canard_iface()); if (targetted == nullptr) { AP_BoardConfig::allocation_error("serial_tunnel_pub"); } @@ -86,7 +86,20 @@ void AP_DroneCAN_Serial::update(void) } n = MIN(avail, sizeof(pkt.buffer.data)); pkt.target_node = p.node; - pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED; + switch (p.state.protocol) { + case AP_SerialManager::SerialProtocol_MAVLink: + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK; + break; + case AP_SerialManager::SerialProtocol_MAVLink2: + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK2; + break; + case AP_SerialManager::SerialProtocol_GPS: + case AP_SerialManager::SerialProtocol_GPS2: // is not in SERIAL1_PROTOCOL option list, but could be entered by user + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_GPS_GENERIC; + break; + default: + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED; + } pkt.buffer.len = n; pkt.baudrate = p.baudrate; pkt.serial_id = p.idx; @@ -132,7 +145,7 @@ void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan, */ void AP_DroneCAN_Serial::Port::init(void) { - baudrate = state.baud; + baudrate = AP_SerialManager::map_baudrate(state.baud); begin(baudrate, 0, 0); } @@ -194,12 +207,12 @@ bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32 } WITH_SEMAPHORE(sem); if (readbuffer == nullptr) { - readbuffer = new ByteBuffer(size_rx); + readbuffer = NEW_NOTHROW ByteBuffer(size_rx); } else { readbuffer->set_size_best(size_rx); } if (writebuffer == nullptr) { - writebuffer = new ByteBuffer(size_tx); + writebuffer = NEW_NOTHROW ByteBuffer(size_tx); } else { writebuffer->set_size_best(size_tx); } diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp index 949d52bfcf46dc..a76877d0d2eb84 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp @@ -120,7 +120,7 @@ void DroneCAN_sniffer::init(void) // we need to mutate the HAL to install new CAN interfaces AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable(); - hal_mutable.can[driver_index] = new HAL_CANIface(driver_index); + hal_mutable.can[driver_index] = NEW_NOTHROW HAL_CANIface(driver_index); if (hal_mutable.can[driver_index] == nullptr) { AP_HAL::panic("Couldn't allocate CANManager, something is very wrong"); @@ -132,7 +132,7 @@ void DroneCAN_sniffer::init(void) debug_dronecan("Can not initialised\n"); return; } - _uavcan_iface_mgr = new CanardInterface{driver_index}; + _uavcan_iface_mgr = NEW_NOTHROW CanardInterface{driver_index}; if (_uavcan_iface_mgr == nullptr) { return; @@ -145,12 +145,12 @@ void DroneCAN_sniffer::init(void) _uavcan_iface_mgr->init(node_memory_pool, sizeof(node_memory_pool), 9); - node_status_pub = new Canard::Publisher{*_uavcan_iface_mgr}; + node_status_pub = NEW_NOTHROW Canard::Publisher{*_uavcan_iface_mgr}; if (node_status_pub == nullptr) { return; } - node_info_srv = new Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; + node_info_srv = NEW_NOTHROW Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; if (node_info_srv == nullptr) { return; } diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript index 3e81beeee182a4..6de16dbf02cdd8 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript @@ -11,8 +11,6 @@ def build(bld): dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AP_OSD', - 'AP_RCMapper', - 'AP_Arming' ], ) bld.ap_program( diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index 79bffff77a9577..e6ba53d2b02f37 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -41,7 +41,7 @@ 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,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAV + // @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAVLink // @User: Advanced // @RebootRequired: True AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE), @@ -98,42 +98,42 @@ void AP_EFI::init(void) break; #if AP_EFI_SERIAL_MS_ENABLED case Type::MegaSquirt: - backend = new AP_EFI_Serial_MS(*this); + backend = NEW_NOTHROW AP_EFI_Serial_MS(*this); break; #endif #if AP_EFI_SERIAL_LUTAN_ENABLED case Type::Lutan: - backend = new AP_EFI_Serial_Lutan(*this); + backend = NEW_NOTHROW AP_EFI_Serial_Lutan(*this); break; #endif #if AP_EFI_NWPWU_ENABLED case Type::NWPMU: - backend = new AP_EFI_NWPMU(*this); + backend = NEW_NOTHROW AP_EFI_NWPMU(*this); break; #endif #if AP_EFI_DRONECAN_ENABLED case Type::DroneCAN: - backend = new AP_EFI_DroneCAN(*this); + backend = NEW_NOTHROW AP_EFI_DroneCAN(*this); break; #endif #if AP_EFI_CURRAWONG_ECU_ENABLED case Type::CurrawongECU: - backend = new AP_EFI_Currawong_ECU(*this); + backend = NEW_NOTHROW AP_EFI_Currawong_ECU(*this); break; #endif #if AP_EFI_SCRIPTING_ENABLED case Type::SCRIPTING: - backend = new AP_EFI_Scripting(*this); + backend = NEW_NOTHROW AP_EFI_Scripting(*this); break; #endif #if AP_EFI_SERIAL_HIRTH_ENABLED case Type::Hirth: - backend = new AP_EFI_Serial_Hirth(*this); + backend = NEW_NOTHROW AP_EFI_Serial_Hirth(*this); break; #endif #if AP_EFI_MAV_ENABLED case Type::MAV: - backend = new AP_EFI_MAV(*this); + backend = NEW_NOTHROW AP_EFI_MAV(*this); break; #endif default: @@ -252,16 +252,16 @@ void AP_EFI::log_status(void) "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX", "s#dsOO-OO-", "F-0C000000", - "QBfffffBff", + "QBffffffff", 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, + KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature), + KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature), state.cylinder_status.lambda_coefficient, - state.cylinder_status.cylinder_head_temperature2, - state.cylinder_status.exhaust_gas_temperature2, + KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature2), + KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature2), state.ecu_index); } #endif // LOGGING_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index d917cb6599bc94..736196f63be86e 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -21,15 +21,11 @@ AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) : } // links the DroneCAN message to this backend -void AP_EFI_DroneCAN::subscribe_msgs(AP_DroneCAN *ap_dronecan) +bool AP_EFI_DroneCAN::subscribe_msgs(AP_DroneCAN *ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, driver_index) != nullptr); } // Called from frontend to update with the readings received by handler @@ -151,6 +147,9 @@ void AP_EFI_DroneCAN::handle_status(const uavcan_equipment_ice_reciprocating_Sta c.lambda_coefficient = cs.lambda_coefficient; } + // Required for healthy message + istate.last_updated_ms = AP_HAL::millis(); + copy_to_frontend(); } diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h index 0512d8ea1f7ca3..2d067554acbf59 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.h +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -13,7 +13,7 @@ class AP_EFI_DroneCAN : public AP_EFI_Backend { void update() override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static void trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg); private: diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp index a7d3978a3e00fe..37ca36f3333c2a 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp @@ -33,7 +33,6 @@ #define ENGINE_RUNNING 4 #define THROTTLE_POSITION_FACTOR 10 -#define CRANK_SHAFT_SENSOR_OK 0x0F #define INJECTION_TIME_RESOLUTION 0.8 #define THROTTLE_POSITION_RESOLUTION 0.1 #define VOLTAGE_RESOLUTION 0.0049 /* 5/1024 */ @@ -205,6 +204,7 @@ void AP_EFI_Serial_Hirth::send_request() bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr) { uint8_t computed_checksum = 0; + throttle_to_hirth = 0; // clear buffer memset(raw_data, 0, ARRAY_SIZE(raw_data)); @@ -214,15 +214,15 @@ bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr) thr = linearise_throttle(thr); #endif - const uint16_t throttle = thr * THROTTLE_POSITION_FACTOR; + throttle_to_hirth = thr * THROTTLE_POSITION_FACTOR; uint8_t idx = 0; // set Quantity + Code + "20 bytes of records to set" + Checksum computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE; computed_checksum += raw_data[idx++] = requested_code = CODE_SET_VALUE; - computed_checksum += raw_data[idx++] = throttle & 0xFF; - computed_checksum += raw_data[idx++] = (throttle >> 8) & 0xFF; + computed_checksum += raw_data[idx++] = throttle_to_hirth & 0xFF; + computed_checksum += raw_data[idx++] = (throttle_to_hirth >> 8) & 0xFF; // checksum calculation raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum); @@ -300,7 +300,6 @@ void AP_EFI_Serial_Hirth::decode_data() // EFI2 log internal_state.engine_state = (Engine_State)record1->engine_status; - internal_state.crankshaft_sensor_status = (record1->sensor_ok & CRANK_SHAFT_SENSOR_OK) ? Crankshaft_Sensor_Status::OK : Crankshaft_Sensor_Status::ERROR; // ECYL log internal_state.cylinder_status.injection_time_ms = record1->injection_time * INJECTION_TIME_RESOLUTION; @@ -309,10 +308,7 @@ void AP_EFI_Serial_Hirth::decode_data() // EFI3 log internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION; - engine_temperature_sensor_status = (record1->sensor_ok & 0x01) != 0; - air_temperature_sensor_status = (record1->sensor_ok & 0x02) != 0; - air_pressure_sensor_status = (record1->sensor_ok & 0x04) != 0; - throttle_sensor_status = (record1->sensor_ok & 0x08) != 0; + sensor_status = record1->sensor_ok; // resusing mavlink variables as required for Hirth // add in ADC voltage of MAP sensor > convert to MAP in kPa @@ -344,10 +340,7 @@ void AP_EFI_Serial_Hirth::decode_data() struct Record3 *record3 = (Record3*)raw_data; // EFI3 Log - CHT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0007) != 0; - CHT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0038) != 0; - EGT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x01C0) != 0; - EGT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0E00) != 0; + error_excess_temperature = record3->error_excess_temperature_bitfield; // ECYL log internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1); @@ -369,36 +362,28 @@ void AP_EFI_Serial_Hirth::log_status(void) // @LoggerMessage: EFIS // @Description: Electronic Fuel Injection data - Hirth specific Status information // @Field: TimeUS: Time since system startup - // @Field: ETS1: Status of EGT1 excess temperature error - // @Field: ETS2: Status of EGT2 excess temperature error - // @Field: CTS1: Status of CHT1 excess temperature error - // @Field: CTS2: Status of CHT2 excess temperature error - // @Field: ETSS: Status of Engine temperature sensor - // @Field: ATSS: Status of Air temperature sensor - // @Field: APSS: Status of Air pressure sensor - // @Field: TSS: Status of Temperature sensor - // @Field: CRCF: CRC failure count - // @Field: AckF: ACK failure count + // @Field: EET: Error Excess Temperature Bitfield + // @FieldBitmaskEnum: EET: AP_EFI_Serial_Hirth:::Error_Excess_Temp_Bitfield + // @Field: FLAG: Sensor Status Bitfield + // @FieldBitmaskEnum: FLAG: AP_EFI_Serial_Hirth:::Sensor_Status_Bitfield + // @Field: CRF: CRC failure count + // @Field: AKF: ACK failure count // @Field: Up: Uptime between 2 messages - // @Field: ThrO: Throttle output as received by the engine + // @Field: ThO: Throttle output as received by the engine + // @Field: ThM: Modified throttle_to_hirth output sent to the engine AP::logger().WriteStreaming("EFIS", - "TimeUS,ETS1,ETS2,CTS1,CTS2,ETSS,ATSS,APSS,TSS,CRCF,AckF,Up,ThrO", - "s------------", - "F------------", - "QBBBBBBBBIIIf", + "TimeUS,EET,FLAG,CRF,AKF,Up,ThO,ThM", + "s-------", + "F-------", + "QHBIIIfH", AP_HAL::micros64(), - uint8_t(EGT_1_error_excess_temperature_status), - uint8_t(EGT_2_error_excess_temperature_status), - uint8_t(CHT_1_error_excess_temperature_status), - uint8_t(CHT_2_error_excess_temperature_status), - uint8_t(engine_temperature_sensor_status), - uint8_t(air_temperature_sensor_status), - uint8_t(air_pressure_sensor_status), - uint8_t(throttle_sensor_status), + uint16_t(error_excess_temperature), + uint8_t(sensor_status), uint32_t(crc_fail_cnt), uint32_t(ack_fail_cnt), uint32_t(uptime), - float(internal_state.throttle_out)); + float(internal_state.throttle_out), + uint16_t(throttle_to_hirth)); } #endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.h b/libraries/AP_EFI/AP_EFI_Serial_Hirth.h index 350a3477c41a1c..3ca06ff5178d30 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Hirth.h +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.h @@ -31,6 +31,28 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend { void update() override; + enum class Error_Excess_Temp_Bitfield : uint16_t { + CHT_1_LOW = 1U<<0, // true if CHT1 is too low + CHT_1_HIGH = 1U<<1, // true if CHT1 is too high + CHT_1_ENRC_ACTIVE = 1U<<2, // true if CHT1 Enrichment is active + CHT_2_LOW = 1U<<3, // true if CHT2 is too low + CHT_2_HIGH = 1U<<4, // true if CHT2 is too high + CHT_2_ENRC_ACTIVE = 1U<<5, // true if CHT2 Enrichment is active + EGT_1_LOW = 1U<<6, // true if EGT1 is too low + EGT_1_HIGH = 1U<<7, // true if EGT1 is too high + EGT_1_ENRC_ACTIVE = 1U<<8, // true if EGT1 Enrichment is active + EGT_2_LOW = 1U<<9, // true if EGT2 is too low + EGT_2_HIGH = 1U<<10, // true if EGT2 is too high + EGT_2_ENRC_ACTIVE = 1U<<11, // true if EGT2 Enrichment is active + }; + + enum class Sensor_Status_Bitfield : uint8_t { + ENGINE_TEMP_SENSOR_OK = 1U<<1, // true if engine temperature sensor is OK + AIR_TEMP_SENSOR_OK = 1U<<2, // true if air temperature sensor is OK + AIR_PRESSURE_SENSOR_OK = 1U<<3, // true if intake air pressure sensor is OK + THROTTLE_SENSOR_OK = 1U<<4, // true if throttle sensor is OK + }; + private: // serial port instance AP_HAL::UARTDriver *port; @@ -61,20 +83,15 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend { uint8_t expected_bytes; // Throttle values - uint16_t last_throttle; + uint16_t last_throttle; + uint16_t throttle_to_hirth; uint32_t last_fuel_integration_ms; // custom status for Hirth - bool engine_temperature_sensor_status; - bool air_temperature_sensor_status; - bool air_pressure_sensor_status; - bool throttle_sensor_status; - - bool CHT_1_error_excess_temperature_status; - bool CHT_2_error_excess_temperature_status; - bool EGT_1_error_excess_temperature_status; - bool EGT_2_error_excess_temperature_status; + uint16_t sensor_status; + + uint16_t error_excess_temperature; uint32_t crc_fail_cnt; uint32_t uptime; uint32_t ack_fail_cnt; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index a82a014dedd644..17f62791526b91 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -120,6 +120,30 @@ uint32_t AP_ESC_Telem::get_active_esc_mask() const { return ret; } +// return an active ESC for the purposes of reporting (e.g. in the OSD) +uint8_t AP_ESC_Telem::get_max_rpm_esc() const +{ + uint32_t ret = 0; + float max_rpm = 0; + const uint32_t now = AP_HAL::millis(); + const uint32_t now_us = AP_HAL::micros(); + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { + // have never seen telem from this ESC + continue; + } + if (_telem_data[i].stale(now) + && !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) { + continue; + } + if (_rpm_data[i].rpm > max_rpm) { + max_rpm = _rpm_data[i].rpm; + ret = i; + } + } + return ret; +} + // return number of active ESCs present uint8_t AP_ESC_Telem::get_num_active_escs() const { uint32_t active = get_active_esc_mask(); @@ -214,10 +238,12 @@ bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const // get an individual ESC's temperature in centi-degrees if available, returns true on success bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & (AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL))) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL)) { return false; } temp = telemdata.temperature_cdeg; @@ -227,10 +253,12 @@ bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const // get an individual motor's temperature in centi-degrees if available, returns true on success bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & (AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL))) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL)) { return false; } temp = telemdata.motor_temp_cdeg; @@ -238,13 +266,13 @@ bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const } // get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC -bool AP_ESC_Telem::get_highest_motor_temperature(int16_t& temp) const +bool AP_ESC_Telem::get_highest_temperature(int16_t& temp) const { uint8_t valid_escs = 0; for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { int16_t temp_temp; - if (get_motor_temperature(i, temp_temp)) { + if (get_temperature(i, temp_temp)) { temp = MAX(temp, temp_temp); valid_escs++; } @@ -256,10 +284,12 @@ bool AP_ESC_Telem::get_highest_motor_temperature(int16_t& temp) const // get an individual ESC's current in Ampere if available, returns true on success bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::CURRENT)) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CURRENT)) { return false; } amps = telemdata.current; @@ -269,10 +299,12 @@ bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const // get an individual ESC's voltage in Volt if available, returns true on success bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)) { return false; } volts = telemdata.voltage; @@ -282,10 +314,12 @@ bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const // get an individual ESC's energy consumption in milli-Ampere.hour if available, returns true on success bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION)) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION)) { return false; } consumption_mah = telemdata.consumption_mah; @@ -295,16 +329,80 @@ bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah // get an individual ESC's usage time in seconds if available, returns true on success bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_index, uint32_t& usage_s) const { + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; - if (esc_index >= ESC_TELEM_MAX_ESCS - || telemdata.stale() - || !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::USAGE)) { + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::USAGE)) { return false; } usage_s = telemdata.usage_s; return true; } +#if AP_EXTENDED_ESC_TELEM_ENABLED +// get an individual ESC's input duty cycle if available, returns true on success +bool AP_ESC_Telem::get_input_duty(uint8_t esc_index, uint8_t& input_duty) const +{ + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY)) { + return false; + } + input_duty = telemdata.input_duty; + return true; +} + +// get an individual ESC's output duty cycle if available, returns true on success +bool AP_ESC_Telem::get_output_duty(uint8_t esc_index, uint8_t& output_duty) const +{ + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY)) { + return false; + } + output_duty = telemdata.output_duty; + return true; +} + +// get an individual ESC's status flags if available, returns true on success +bool AP_ESC_Telem::get_flags(uint8_t esc_index, uint32_t& flags) const +{ + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::FLAGS)) { + return false; + } + flags = telemdata.flags; + return true; +} + +// get an individual ESC's percentage of output power if available, returns true on success +bool AP_ESC_Telem::get_power_percentage(uint8_t esc_index, uint8_t& power_percentage) const +{ + if (esc_index >= ESC_TELEM_MAX_ESCS) { + return false; + } + + const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index]; + if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE)) { + return false; + } + power_percentage = telemdata.power_percentage; + return true; +} +#endif // AP_EXTENDED_ESC_TELEM_ENABLED + // send ESC telemetry messages over MAVLink void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) { @@ -318,8 +416,11 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) const uint32_t now_us = AP_HAL::micros(); // loop through groups of 4 ESCs - const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS - 1); - const uint8_t num_idx = ESC_TELEM_MAX_ESCS / 4; + const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1); + + // ensure we send out partially-full groups: + const uint8_t num_idx = (ESC_TELEM_MAX_ESCS + 3) / 4; + for (uint8_t idx = 0; idx < num_idx; idx++) { const uint8_t i = (next_idx + idx) % num_idx; @@ -465,6 +566,30 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem telemdata.usage_s = new_data.usage_s; } +#if AP_EXTENDED_ESC_TELEM_ENABLED + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY) { + telemdata.input_duty = new_data.input_duty; + } + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY) { + telemdata.output_duty = new_data.output_duty; + } + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) { + telemdata.flags = new_data.flags; + } + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE) { + telemdata.power_percentage = new_data.power_percentage; + } +#endif //AP_EXTENDED_ESC_TELEM_ENABLED + +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS) { + telemdata.edt2_status = merge_edt2_status(telemdata.edt2_status, new_data.edt2_status); + } + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS) { + telemdata.edt2_stress = merge_edt2_stress(telemdata.edt2_stress, new_data.edt2_stress); + } +#endif + telemdata.count++; telemdata.types |= data_mask; telemdata.last_update_ms = AP_HAL::millis(); @@ -496,6 +621,63 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, cons #endif } +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + +// The following is based on https://github.com/bird-sanctuary/extended-dshot-telemetry. +// For the following part we explain the bits of Extended DShot Telemetry v2 status telemetry: +// - bits 0-3: the "stress level" +// - bit 5: the "error" bit (e.g. the stall event in Bluejay) +// - bit 6: the "warning" bit (e.g. the desync event in Bluejay) +// - bit 7: the "alert" bit (e.g. the demag event in Bluejay) + +// Since logger can read out telemetry values less frequently than they are updated, +// it makes sense to aggregate these status bits, and to collect the maximum observed stress level. +// To reduce the logging rate of the EDT2 messages, we will try to log them only once a new frame comes. +// To track this, we are going to (ab)use bit 15 of the field: 1 means there is something to write. + +// EDTv2 also features separate "stress" messages. +// These come more frequently, and are scaled differently (the allowed range is from 0 to 255), +// so we have to log them separately. + +constexpr uint16_t EDT2_TELEM_UPDATED = 0x8000U; +constexpr uint16_t EDT2_STRESS_0F_MASK = 0xfU; +constexpr uint16_t EDT2_STRESS_FF_MASK = 0xffU; +constexpr uint16_t EDT2_ERROR_MASK = 0x20U; +constexpr uint16_t EDT2_WARNING_MASK = 0x40U; +constexpr uint16_t EDT2_ALERT_MASK = 0x80U; +constexpr uint16_t EDT2_ALL_BITS = EDT2_ERROR_MASK | EDT2_WARNING_MASK | EDT2_ALERT_MASK; + +#define EDT2_HAS_NEW_DATA(status) bool((status) & EDT2_TELEM_UPDATED) +#define EDT2_STRESS_FROM_STATUS(status) uint8_t((status) & EDT2_STRESS_0F_MASK) +#define EDT2_ERROR_BIT_FROM_STATUS(status) bool((status) & EDT2_ERROR_MASK) +#define EDT2_WARNING_BIT_FROM_STATUS(status) bool((status) & EDT2_WARNING_MASK) +#define EDT2_ALERT_BIT_FROM_STATUS(status) bool((status) & EDT2_ALERT_MASK) +#define EDT2_STRESS_FROM_STRESS(stress) uint8_t((stress) & EDT2_STRESS_FF_MASK) + +uint16_t AP_ESC_Telem::merge_edt2_status(uint16_t old_status, uint16_t new_status) +{ + if (EDT2_HAS_NEW_DATA(old_status)) { + new_status = uint16_t( + (old_status & ~EDT2_STRESS_0F_MASK) | // old status except for the stress is preserved + (new_status & EDT2_ALL_BITS) | // all new status bits are included + MAX(old_status & EDT2_STRESS_0F_MASK, new_status & EDT2_STRESS_0F_MASK) // the stress is maxed out + ); + } + return EDT2_TELEM_UPDATED | new_status; +} + +uint16_t AP_ESC_Telem::merge_edt2_stress(uint16_t old_stress, uint16_t new_stress) +{ + if (EDT2_HAS_NEW_DATA(old_stress)) { + new_stress = uint16_t( + MAX(old_stress & EDT2_STRESS_FF_MASK, new_stress & EDT2_STRESS_FF_MASK) // the stress is maxed out + ); + } + return EDT2_TELEM_UPDATED | new_stress; +} + +#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + void AP_ESC_Telem::update() { #if HAL_LOGGING_ENABLED @@ -504,12 +686,16 @@ void AP_ESC_Telem::update() for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { const volatile AP_ESC_Telem_Backend::RpmData &rpmdata = _rpm_data[i]; - const volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i]; + volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i]; // Push received telemetry data into the logging system if (logger && logger->logging_enabled()) { if (telemdata.last_update_ms != _last_telem_log_ms[i] || rpmdata.last_update_us != _last_rpm_log_us[i]) { + // Update last log timestamps + _last_telem_log_ms[i] = telemdata.last_update_ms; + _last_rpm_log_us[i] = rpmdata.last_update_us; + float rpm = AP::logger().quiet_nanf(); get_rpm(i, rpm); float raw_rpm = AP::logger().quiet_nanf(); @@ -538,9 +724,86 @@ void AP_ESC_Telem::update() error_rate : rpmdata.error_rate }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); - _last_telem_log_ms[i] = telemdata.last_update_ms; - _last_rpm_log_us[i] = rpmdata.last_update_us; + +#if AP_EXTENDED_ESC_TELEM_ENABLED + // Write ESC extended status messages + // id: starts from 0 + // input duty: duty cycle input to the ESC in percent + // output duty: duty cycle output to the motor in percent + // status flags: manufacurer-specific status flags + const bool has_ext_data = telemdata.types & + (AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY | + AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY | + AP_ESC_Telem_Backend::TelemetryType::FLAGS | + AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE); + if (has_ext_data) { + // @LoggerMessage: ESCX + // @Description: ESC extended telemetry data + // @Field: TimeUS: Time since system startup + // @Field: Instance: starts from 0 + // @Field: inpct: input duty cycle in percent + // @Field: outpct: output duty cycle in percent + // @Field: flags: manufacturer-specific status flags + // @Field: Pwr: Power percentage + AP::logger().WriteStreaming("ESCX", + "TimeUS,Instance,inpct,outpct,flags,Pwr", + "s" "#" "%" "%" "-" "%", + "F" "-" "-" "-" "-" "-", + "Q" "B" "B" "B" "I" "B", + AP_HAL::micros64(), + i, + telemdata.input_duty, + telemdata.output_duty, + telemdata.flags, + telemdata.power_percentage); + } +#endif //AP_EXTENDED_ESC_TELEM_ENABLED } + +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + // Write an EDTv2 message, if there is any update + uint16_t edt2_status = telemdata.edt2_status; + uint16_t edt2_stress = telemdata.edt2_stress; + if (EDT2_HAS_NEW_DATA(edt2_status | edt2_stress)) { + // Could probably be faster/smaller with bitmasking, but not sure + uint8_t status = 0; + if (EDT2_HAS_NEW_DATA(edt2_stress)) { + status |= uint8_t(log_Edt2_Status::HAS_STRESS_DATA); + } + if (EDT2_HAS_NEW_DATA(edt2_status)) { + status |= uint8_t(log_Edt2_Status::HAS_STATUS_DATA); + } + if (EDT2_ALERT_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::ALERT_BIT); + } + if (EDT2_WARNING_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::WARNING_BIT); + } + if (EDT2_ERROR_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::ERROR_BIT); + } + // An EDT2 status message is: + // id: starts from 0 + // stress: the current stress which comes from edt2_stress + // max_stress: the maximum stress which comes from edt2_status + // status: the status bits which come from both + const struct log_Edt2 pkt_edt2{ + LOG_PACKET_HEADER_INIT(uint8_t(LOG_EDT2_MSG)), + time_us : now_us64, + instance : i, + stress : EDT2_STRESS_FROM_STRESS(edt2_stress), + max_stress : EDT2_STRESS_FROM_STATUS(edt2_status), + status : status, + }; + if (AP::logger().WriteBlock_first_succeed(&pkt_edt2, sizeof(pkt_edt2))) { + // Only clean the telem_updated bits if the write succeeded. + // This is important because, if rate limiting is enabled, + // the log-on-change behavior may lose a lot of entries + telemdata.edt2_status &= ~EDT2_TELEM_UPDATED; + telemdata.edt2_stress &= ~EDT2_TELEM_UPDATED; + } + } +#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED } } #endif // HAL_LOGGING_ENABLED @@ -605,4 +868,4 @@ AP_ESC_Telem &esc_telem() }; -#endif +#endif // HAL_WITH_ESC_TELEM diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index ae40ede5970792..cf4a5a9cc2d573 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -7,7 +7,9 @@ #if HAL_WITH_ESC_TELEM -#define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS +#ifndef ESC_TELEM_MAX_ESCS + #define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS +#endif static_assert(ESC_TELEM_MAX_ESCS > 0, "Cannot have 0 ESC telemetry instances"); #define ESC_TELEM_DATA_TIMEOUT_MS 5000UL @@ -53,7 +55,7 @@ class AP_ESC_Telem { bool get_motor_temperature(uint8_t esc_index, int16_t& temp) const; // get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC - bool get_highest_motor_temperature(int16_t& temp) const; + bool get_highest_temperature(int16_t& temp) const; // get an individual ESC's current in Ampere if available, returns true on success bool get_current(uint8_t esc_index, float& amps) const; @@ -67,6 +69,20 @@ class AP_ESC_Telem { // get an individual ESC's consumption in milli-Ampere.hour if available, returns true on success bool get_consumption_mah(uint8_t esc_index, float& consumption_mah) const; +#if AP_EXTENDED_ESC_TELEM_ENABLED + // get an individual ESC's input duty cycle if available, returns true on success + bool get_input_duty(uint8_t esc_index, uint8_t& input_duty) const; + + // get an individual ESC's output duty cycle if available, returns true on success + bool get_output_duty(uint8_t esc_index, uint8_t& output_duty) const; + + // get an individual ESC's status flags if available, returns true on success + bool get_flags(uint8_t esc_index, uint32_t& flags) const; + + // get an individual ESC's percentage of output power if available, returns true on success + bool get_power_percentage(uint8_t esc_index, uint8_t& power_percentage) const; +#endif + // return the average motor frequency in Hz for dynamic filtering float get_average_motor_frequency_hz(uint32_t servo_channel_mask) const { return get_average_motor_rpm(servo_channel_mask) * (1.0f / 60.0f); }; @@ -83,6 +99,9 @@ class AP_ESC_Telem { // ESC_TELEM_DATA_TIMEOUT_MS uint32_t get_active_esc_mask() const; + // return an active ESC with the highest RPM for the purposes of reporting (e.g. in the OSD) + uint8_t get_max_rpm_esc() 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 { if (esc_index >= ESC_TELEM_MAX_ESCS) {return 0;} @@ -118,6 +137,12 @@ class AP_ESC_Telem { static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us); static bool was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance); +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + // helpers that aggregate data in EDTv2 messages + static uint16_t merge_edt2_status(uint16_t old_status, uint16_t new_status); + static uint16_t merge_edt2_stress(uint16_t old_stress, uint16_t new_stress); +#endif + // rpm data volatile AP_ESC_Telem_Backend::RpmData _rpm_data[ESC_TELEM_MAX_ESCS]; // telemetry data diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index 46f5aa61459964..a63c0191c5c853 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -50,10 +50,19 @@ void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const Tele */ bool AP_ESC_Telem_Backend::TelemetryData::stale(uint32_t now_ms) const volatile { - if (now_ms == 0) { - now_ms = AP_HAL::millis(); - } return last_update_ms == 0 || now_ms - last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS; } +/* + return true if the requested types of data are available and not stale + */ +bool AP_ESC_Telem_Backend::TelemetryData::valid(const uint16_t type_mask) const volatile +{ + if ((types & type_mask) == 0) { + // Requested type not available + return false; + } + return !stale(AP_HAL::millis()); +} + #endif diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index b6d6725a55fa15..f127c0d71ab92c 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -19,9 +19,22 @@ class AP_ESC_Telem_Backend { uint32_t last_update_ms; // last update time in milliseconds, determines whether active uint16_t types; // telemetry types present uint16_t count; // number of times updated +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + uint16_t edt2_status; // status reported by Extended DShot Telemetry v2 + uint16_t edt2_stress; // stress reported in dedicated messages by Extended DShot Telemetry v2 +#endif +#if AP_EXTENDED_ESC_TELEM_ENABLED + uint8_t input_duty; // input duty cycle + uint8_t output_duty; // output duty cycle + uint32_t flags; // Status flags + uint8_t power_percentage; // Percentage of output power +#endif // AP_EXTENDED_ESC_TELEM_ENABLED // return true if the data is stale - bool stale(uint32_t now_ms=0) const volatile; + bool stale(uint32_t now_ms) const volatile; + + // return true if the requested type of data is available and not stale + bool valid(const uint16_t type_mask) const volatile; }; struct RpmData { @@ -42,6 +55,16 @@ class AP_ESC_Telem_Backend { USAGE = 1 << 5, TEMPERATURE_EXTERNAL = 1 << 6, MOTOR_TEMPERATURE_EXTERNAL = 1 << 7, +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + EDT2_STATUS = 1 << 8, + EDT2_STRESS = 1 << 9, +#endif +#if AP_EXTENDED_ESC_TELEM_ENABLED + INPUT_DUTY = 1 << 10, + OUTPUT_DUTY = 1 << 11, + FLAGS = 1 << 12, + POWER_PERCENTAGE = 1 << 13, +#endif // AP_EXTENDED_ESC_TELEM_ENABLED }; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp index 25f84fb285c69a..cf435a2051c79a 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp @@ -71,13 +71,28 @@ void AP_ESC_Telem_SITL::update() .voltage = 16.8f, .current = 0.8f, .consumption_mah = 1.0f, + .motor_temp_cdeg = 3500, +#if AP_EXTENDED_ESC_TELEM_ENABLED + .input_duty = 1, + .output_duty = 2, + .flags = 3, + .power_percentage = 4, +#endif }; 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); + | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE + | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE +#if AP_EXTENDED_ESC_TELEM_ENABLED + | AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE + | AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY + | AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY + | AP_ESC_Telem_Backend::TelemetryType::FLAGS +#endif + ); } #endif } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_config.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_config.h index fdd9cea2feba10..f3fb6fac7bb89f 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_config.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_config.h @@ -6,3 +6,11 @@ #ifndef HAL_WITH_ESC_TELEM #define HAL_WITH_ESC_TELEM ((NUM_SERVO_CHANNELS > 0) && ((HAL_SUPPORT_RCOUT_SERIAL || HAL_MAX_CAN_PROTOCOL_DRIVERS))) #endif + +#ifndef AP_EXTENDED_ESC_TELEM_ENABLED +#define AP_EXTENDED_ESC_TELEM_ENABLED HAL_ENABLE_DRONECAN_DRIVERS +#endif + +#if AP_EXTENDED_ESC_TELEM_ENABLED && !HAL_WITH_ESC_TELEM + #error "AP_EXTENDED_ESC_TELEM_ENABLED requires HAL_WITH_ESC_TELEM" +#endif diff --git a/libraries/AP_ESC_Telem/LogStructure.h b/libraries/AP_ESC_Telem/LogStructure.h index a3c0dc791cd3df..c50ac47b95e97f 100644 --- a/libraries/AP_ESC_Telem/LogStructure.h +++ b/libraries/AP_ESC_Telem/LogStructure.h @@ -3,7 +3,8 @@ #include #define LOG_IDS_FROM_ESC_TELEM \ - LOG_ESC_MSG + LOG_ESC_MSG, \ + LOG_EDT2_MSG // @LoggerMessage: ESC // @Description: Feedback received from ESCs @@ -31,6 +32,35 @@ struct PACKED log_Esc { float error_rate; }; -#define LOG_STRUCTURE_FROM_ESC_TELEM \ +enum class log_Edt2_Status : uint8_t { + HAS_STRESS_DATA = 1U<<0, // true if the message contains up-to-date stress data + HAS_STATUS_DATA = 1U<<1, // true if the message contains up-to-date status data + ALERT_BIT = 1U<<2, // true if the last status had the "alert" bit (e.g. demag) + WARNING_BIT = 1U<<3, // true if the last status had the "warning" bit (e.g. desync) + ERROR_BIT = 1U<<4, // true if the last status had the "error" bit (e.g. stall) +}; + + +// @LoggerMessage: EDT2 +// @Description: Status received from ESCs via Extended DShot telemetry v2 +// @Field: TimeUS: microseconds since system startup +// @Field: Instance: ESC instance number +// @Field: Stress: current stress level (commutation effort), scaled to [0..255] +// @Field: MaxStress: maximum stress level (commutation effort) since arming, scaled to [0..15] +// @Field: Status: status bits +// @FieldBitmaskEnum: Status: log_Edt2_Status +struct PACKED log_Edt2 { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + uint8_t stress; + uint8_t max_stress; + uint8_t status; +}; + +#define LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_ESC_MSG, sizeof(log_Esc), \ - "ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, + "ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, \ + { LOG_EDT2_MSG, sizeof(log_Edt2), \ + "EDT2", "QBBBB", "TimeUS,Instance,Stress,MaxStress,Status", "s#---", "F----" , true }, + diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index 315cc17b22765c..07d875e57de959 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -29,6 +29,7 @@ #include #include +#include #include extern const AP_HAL::HAL &hal; @@ -107,25 +108,25 @@ void AP_ExternalAHRS::init(void) #if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED case DevType::VecNav: - backend = new AP_ExternalAHRS_VectorNav(this, state); + backend = NEW_NOTHROW AP_ExternalAHRS_VectorNav(this, state); return; #endif #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED case DevType::MicroStrain5: - backend = new AP_ExternalAHRS_MicroStrain5(this, state); + backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain5(this, state); return; #endif #if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED case DevType::MicroStrain7: - backend = new AP_ExternalAHRS_MicroStrain7(this, state); + backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain7(this, state); return; #endif -#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED case DevType::InertialLabs: - backend = new AP_ExternalAHRS_InertialLabs(this, state); + backend = NEW_NOTHROW AP_ExternalAHRS_InertialLabs(this, state); return; #endif @@ -179,6 +180,17 @@ bool AP_ExternalAHRS::get_origin(Location &loc) return false; } +bool AP_ExternalAHRS::set_origin(const Location &loc) +{ + WITH_SEMAPHORE(state.sem); + if (state.have_origin) { + return false; + } + state.origin = loc; + state.have_origin = true; + return true; +} + bool AP_ExternalAHRS::get_location(Location &loc) { if (!state.have_location) { @@ -238,6 +250,27 @@ bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) if (!backend->pre_arm_check(failure_msg, failure_msg_len)) { return false; } + // Verify the user has configured the GPS to accept EAHRS data. + if (has_sensor(AvailableSensor::GPS)) { + const auto eahrs_gps_sensors = backend->num_gps_sensors(); + + const auto &gps = AP::gps(); + uint8_t n_configured_eahrs_gps = 0; + for (uint8_t i = 0; i < GPS_MAX_INSTANCES; ++i) { + const auto gps_type = gps.get_type(i); + if (gps_type == AP_GPS::GPS_TYPE_EXTERNAL_AHRS) { + n_configured_eahrs_gps++; + } + } + + // Once AP supports at least 3 GPS's, change to == and remove the second condition. + // At that point, enforce that all GPS's in EAHRS can report to AP_GPS. + if (n_configured_eahrs_gps < 1 && eahrs_gps_sensors >= 1) { + hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Incorrect number of GPS sensors configured for EAHRS"); + return false; + } + } + if (!state.have_origin) { hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin"); return false; @@ -256,6 +289,17 @@ void AP_ExternalAHRS::get_filter_status(nav_filter_status &status) const } } +/* + get estimated variances, return false if not implemented + */ +bool AP_ExternalAHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const +{ + if (backend != nullptr) { + return backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar); + } + return false; +} + bool AP_ExternalAHRS::get_gyro(Vector3f &gyro) { WITH_SEMAPHORE(state.sem); @@ -279,9 +323,56 @@ bool AP_ExternalAHRS::get_accel(Vector3f &accel) // send an EKF_STATUS message to GCS void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const { - if (backend) { - backend->send_status_report(link); + float velVar, posVar, hgtVar, tasVar; + Vector3f magVar; + if (backend == nullptr || !backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) { + return; + } + + uint16_t flags = 0; + nav_filter_status filterStatus {}; + get_filter_status(filterStatus); + + if (filterStatus.flags.attitude) { + flags |= EKF_ATTITUDE; + } + if (filterStatus.flags.horiz_vel) { + flags |= EKF_VELOCITY_HORIZ; + } + if (filterStatus.flags.vert_vel) { + flags |= EKF_VELOCITY_VERT; + } + if (filterStatus.flags.horiz_pos_rel) { + flags |= EKF_POS_HORIZ_REL; + } + if (filterStatus.flags.horiz_pos_abs) { + flags |= EKF_POS_HORIZ_ABS; + } + if (filterStatus.flags.vert_pos) { + flags |= EKF_POS_VERT_ABS; + } + if (filterStatus.flags.terrain_alt) { + flags |= EKF_POS_VERT_AGL; + } + if (filterStatus.flags.const_pos_mode) { + flags |= EKF_CONST_POS_MODE; } + if (filterStatus.flags.pred_horiz_pos_rel) { + flags |= EKF_PRED_POS_HORIZ_REL; + } + if (filterStatus.flags.pred_horiz_pos_abs) { + flags |= EKF_PRED_POS_HORIZ_ABS; + } + if (!filterStatus.flags.initalized) { + flags |= EKF_UNINITIALIZED; + } + + const float mag_var = MAX(magVar.x, MAX(magVar.y, magVar.z)); + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, + velVar, + posVar, + hgtVar, + mag_var, 0, 0); } void AP_ExternalAHRS::update(void) @@ -290,19 +381,7 @@ void AP_ExternalAHRS::update(void) backend->update(); } - /* - if backend has not supplied an origin and AHRS has an origin - then use that origin so we get a common origin for minimum - disturbance when switching backends - */ WITH_SEMAPHORE(state.sem); - if (!state.have_origin) { - Location origin; - if (AP::ahrs().get_origin(origin)) { - state.origin = origin; - state.have_origin = true; - } - } #if HAL_LOGGING_ENABLED const uint32_t now_ms = AP_HAL::millis(); if (log_rate.get() > 0 && now_ms - last_log_ms >= uint32_t(1000U/log_rate.get())) { @@ -336,6 +415,28 @@ void AP_ExternalAHRS::update(void) state.velocity.x, state.velocity.y, state.velocity.z, state.location.lat, state.location.lng, state.location.alt*0.01, filterStatus.value); + + // @LoggerMessage: EAHV + // @Description: External AHRS variances + // @Field: TimeUS: Time since system startup + // @Field: Vel: velocity variance + // @Field: Pos: position variance + // @Field: Hgt: height variance + // @Field: MagX: magnetic variance, X + // @Field: MagY: magnetic variance, Y + // @Field: MagZ: magnetic variance, Z + // @Field: TAS: true airspeed variance + + float velVar, posVar, hgtVar, tasVar; + Vector3f magVar; + if (backend != nullptr && backend->get_variances(velVar, posVar, hgtVar, magVar, tasVar)) { + AP::logger().WriteStreaming("EAHV", "TimeUS,Vel,Pos,Hgt,MagX,MagY,MagZ,TAS", + "Qfffffff", + AP_HAL::micros64(), + velVar, posVar, hgtVar, + magVar.x, magVar.y, magVar.z, + tasVar); + } } #endif // HAL_LOGGING_ENABLED } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index 2d01f28c289d89..c5913baa8c6dbb 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -26,6 +26,7 @@ #include #include #include +#include class AP_ExternalAHRS_backend; @@ -49,7 +50,7 @@ class AP_ExternalAHRS { #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED MicroStrain5 = 2, #endif -#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED InertialLabs = 5, #endif // 3 reserved for AdNav @@ -109,6 +110,7 @@ class AP_ExternalAHRS { bool initialised(void) const; bool get_quaternion(Quaternion &quat); bool get_origin(Location &loc); + bool set_origin(const Location &loc); bool get_location(Location &loc); Vector2f get_groundspeed_vector(); bool get_velocity_NED(Vector3f &vel); @@ -118,6 +120,7 @@ class AP_ExternalAHRS { bool get_gyro(Vector3f &gyro); bool get_accel(Vector3f &accel); void send_status_report(class GCS_MAVLINK &link) const; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const; // update backend void update(); @@ -136,9 +139,9 @@ class AP_ExternalAHRS { } mag_data_message_t; typedef struct { - uint16_t gps_week; // GPS week, 0xFFFF if not available + uint16_t gps_week; uint32_t ms_tow; - uint8_t fix_type; + AP_GPS_FixType fix_type; uint8_t satellites_in_view; float horizontal_pos_accuracy; float vertical_pos_accuracy; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index 43e858a74007ce..fb057d000fde15 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -18,7 +18,7 @@ #include "AP_ExternalAHRS_config.h" -#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED #include "AP_ExternalAHRS_InertialLabs.h" #include @@ -62,11 +62,11 @@ extern const AP_HAL::HAL &hal; #define ILABS_UNIT_STATUS2_BARO_FAIL 0x0008 #define ILABS_UNIT_STATUS2_DIFF_PRESS_FAIL 0x0010 #define ILABS_UNIT_STATUS2_MAGCAL_2D_ACT 0x0020 -#define ILABS_UNIT_STATUS2_MAGCAL_3D_ACT 0x0020 -#define ILABS_UNIT_STATUS2_GNSS_FUSION_OFF 0x0040 -#define ILABS_UNIT_STATUS2_DIFF_PRESS_FUSION_OFF 0x0080 -#define ILABS_UNIT_STATUS2_MAG_FUSION_OFF 0x0100 -#define ILABS_UNIT_STATUS2_GNSS_POS_VALID 0x0200 +#define ILABS_UNIT_STATUS2_MAGCAL_3D_ACT 0x0040 +#define ILABS_UNIT_STATUS2_GNSS_FUSION_OFF 0x0080 +#define ILABS_UNIT_STATUS2_DIFF_PRESS_FUSION_OFF 0x0100 +#define ILABS_UNIT_STATUS2_MAG_FUSION_OFF 0x0200 +#define ILABS_UNIT_STATUS2_GNSS_POS_VALID 0x0400 // air data status bits #define ILABS_AIRDATA_INIT_FAIL 0x0001 @@ -75,9 +75,9 @@ extern const AP_HAL::HAL &hal; #define ILABS_AIRDATA_DIFF_PRESS_FAIL 0x0008 #define ILABS_AIRDATA_STATIC_PRESS_RANGE_ERR 0x0010 #define ILABS_AIRDATA_DIFF_PRESS_RANGE_ERR 0x0020 -#define ILABS_AIRDATA_PRESS_ALT_FAIL 0x0040 -#define ILABS_AIRDATA_AIRSPEED_FAIL 0x0080 -#define ILABS_AIRDATA_BELOW_THRESHOLD 0x0100 +#define ILABS_AIRDATA_PRESS_ALT_FAIL 0x0100 +#define ILABS_AIRDATA_AIRSPEED_FAIL 0x0200 +#define ILABS_AIRDATA_BELOW_THRESHOLD 0x0400 // constructor @@ -256,40 +256,42 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() switch (mtype) { case MessageType::GPS_INS_TIME_MS: { // this is the GPS tow timestamp in ms for when the IMU data was sampled - CHECK_SIZE(u.gps_time_ms); - state2.gnss_ins_time_ms = u.gps_time_ms; + CHECK_SIZE(u.gnss_time_ms); + gps_data.ms_tow = u.gnss_time_ms; break; } case MessageType::GPS_WEEK: { - CHECK_SIZE(u.gps_week); - gps_data.gps_week = u.gps_week; + CHECK_SIZE(u.gnss_week); + gps_data.gps_week = u.gnss_week; break; } case MessageType::ACCEL_DATA_HR: { CHECK_SIZE(u.accel_data_hr); - ins_data.accel = u.accel_data_hr.tofloat().rfu_to_frd()*GRAVITY_MSS*1.0e-6; + // should use 9.8106 instead of GRAVITY_MSS-constant in accordance with the device-documentation + ins_data.accel = u.accel_data_hr.tofloat().rfu_to_frd()*9.8106f*1.0e-6; // m/s^2 break; } case MessageType::GYRO_DATA_HR: { CHECK_SIZE(u.gyro_data_hr); - ins_data.gyro = u.gyro_data_hr.tofloat().rfu_to_frd()*DEG_TO_RAD*1.0e-5; + ins_data.gyro = u.gyro_data_hr.tofloat().rfu_to_frd()*DEG_TO_RAD*1.0e-5; // rad/s break; } case MessageType::BARO_DATA: { CHECK_SIZE(u.baro_data); - baro_data.pressure_pa = u.baro_data.pressure_pa2*2; + baro_data.pressure_pa = u.baro_data.pressure_pa2*2; // Pa + state2.baro_alt = u.baro_data.baro_alt*0.01; // m break; } case MessageType::MAG_DATA: { CHECK_SIZE(u.mag_data); - mag_data.field = u.mag_data.tofloat().rfu_to_frd()*(10*NTESLA_TO_MGAUSS); + mag_data.field = u.mag_data.tofloat().rfu_to_frd()*(10*NTESLA_TO_MGAUSS); // milligauss break; } case MessageType::ORIENTATION_ANGLES: { CHECK_SIZE(u.orientation_angles); state.quat.from_euler(radians(u.orientation_angles.roll*0.01), - radians(u.orientation_angles.pitch*0.01), - radians(u.orientation_angles.yaw*0.01)); + radians(u.orientation_angles.pitch*0.01), + radians(u.orientation_angles.yaw*0.01)); state.have_quaternion = true; if (last_att_ms == 0) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "InertialLabs: got link"); @@ -300,15 +302,23 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() case MessageType::VELOCITIES: { CHECK_SIZE(u.velocity); state.velocity = u.velocity.tofloat().rfu_to_frd()*0.01; + gps_data.ned_vel_north = state.velocity.x; // m/s + gps_data.ned_vel_east = state.velocity.y; // m/s + gps_data.ned_vel_down = state.velocity.z; // m/s state.have_velocity = true; last_vel_ms = now_ms; break; } case MessageType::POSITION: { CHECK_SIZE(u.position); - state.location.lat = u.position.lat; - state.location.lng = u.position.lon; - state.location.alt = u.position.alt; + state.location.lat = u.position.lat; // deg*1.0e7 + state.location.lng = u.position.lon; // deg*1.0e7 + state.location.alt = u.position.alt; // m*100 + + gps_data.latitude = u.position.lat; // deg*1.0e7 + gps_data.longitude = u.position.lon; // deg*1.0e7 + gps_data.msl_altitude = u.position.alt; // m*100 + state.have_location = true; state.last_location_update_us = AP_HAL::micros(); last_pos_ms = now_ms; @@ -316,12 +326,12 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() } case MessageType::KF_VEL_COVARIANCE: { CHECK_SIZE(u.kf_vel_covariance); - state2.kf_vel_covariance = u.kf_vel_covariance.tofloat() * 0.001; + state2.kf_vel_covariance = u.kf_vel_covariance.tofloat().rfu_to_frd(); // mm/s break; } case MessageType::KF_POS_COVARIANCE: { CHECK_SIZE(u.kf_pos_covariance); - state2.kf_pos_covariance = u.kf_pos_covariance.tofloat() * 0.001; + state2.kf_pos_covariance = u.kf_pos_covariance.tofloat(); // mm break; } case MessageType::UNIT_STATUS: { @@ -331,8 +341,8 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() } case MessageType::GNSS_EXTENDED_INFO: { CHECK_SIZE(u.gnss_extended_info); - gps_data.fix_type = u.gnss_extended_info.fix_type+1; - state2.gnss_extended_info = u.gnss_extended_info; + gps_data.fix_type = AP_GPS_FixType(u.gnss_extended_info.fix_type+1); + gnss_data.spoof_status = u.gnss_extended_info.spoofing_status; break; } case MessageType::NUM_SATS: { @@ -341,54 +351,52 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() break; } case MessageType::GNSS_POSITION: { - CHECK_SIZE(u.position); - gps_data.latitude = u.position.lat; - gps_data.longitude = u.position.lon; - gps_data.msl_altitude = u.position.alt; + CHECK_SIZE(u.gnss_position); + gnss_data.lat = u.gnss_position.lat; // deg*1.0e7 + gnss_data.lng = u.gnss_position.lon; // deg*1.0e7 + gnss_data.alt = u.gnss_position.alt; // mm break; } case MessageType::GNSS_VEL_TRACK: { CHECK_SIZE(u.gnss_vel_track); - Vector2f velxy; - velxy.offset_bearing(u.gnss_vel_track.track_over_ground*0.01, u.gnss_vel_track.hor_speed*0.01); - gps_data.ned_vel_north = velxy.x; - gps_data.ned_vel_east = velxy.y; - gps_data.ned_vel_down = -u.gnss_vel_track.ver_speed*0.01; + gnss_data.hor_speed = u.gnss_vel_track.hor_speed*0.01; // m/s + gnss_data.ver_speed = u.gnss_vel_track.ver_speed*0.01; // m/s + gnss_data.track_over_ground = u.gnss_vel_track.track_over_ground*0.01; // deg break; } case MessageType::GNSS_POS_TIMESTAMP: { CHECK_SIZE(u.gnss_pos_timestamp); - gps_data.ms_tow = u.gnss_pos_timestamp; + gnss_data.pos_timestamp = u.gnss_pos_timestamp; break; } case MessageType::GNSS_INFO_SHORT: { CHECK_SIZE(u.gnss_info_short); - state2.gnss_info_short = u.gnss_info_short; + gnss_data.info_short = u.gnss_info_short; break; } case MessageType::GNSS_NEW_DATA: { CHECK_SIZE(u.gnss_new_data); - state2.gnss_new_data = u.gnss_new_data; + gnss_data.new_data = u.gnss_new_data; break; } case MessageType::GNSS_JAM_STATUS: { CHECK_SIZE(u.gnss_jam_status); - state2.gnss_jam_status = u.gnss_jam_status; + gnss_data.jam_status = u.gnss_jam_status; break; } case MessageType::DIFFERENTIAL_PRESSURE: { CHECK_SIZE(u.differential_pressure); - airspeed_data.differential_pressure = u.differential_pressure*1.0e-4; + airspeed_data.differential_pressure = u.differential_pressure*1.0e-4*100; // 100: mbar to Pa break; } case MessageType::TRUE_AIRSPEED: { CHECK_SIZE(u.true_airspeed); - state2.true_airspeed = u.true_airspeed*0.01; + state2.true_airspeed = u.true_airspeed*0.01; // m/s break; } case MessageType::WIND_SPEED: { CHECK_SIZE(u.wind_speed); - state2.wind_speed = u.wind_speed.tofloat().rfu_to_frd()*0.01; + state2.wind_speed = u.wind_speed.tofloat().rfu_to_frd()*0.01; // m/s break; } case MessageType::AIR_DATA_STATUS: { @@ -398,14 +406,15 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() } case MessageType::SUPPLY_VOLTAGE: { CHECK_SIZE(u.supply_voltage); - state2.supply_voltage = u.supply_voltage*0.01; + state2.supply_voltage = u.supply_voltage*0.01; // V break; } case MessageType::TEMPERATURE: { CHECK_SIZE(u.temperature); // assume same temperature for baro and airspeed - baro_data.temperature = u.temperature*0.1; - airspeed_data.temperature = u.temperature*0.1; + baro_data.temperature = u.temperature*0.1; // degC + airspeed_data.temperature = u.temperature*0.1; // degC + ins_data.temperature = u.temperature*0.1; break; } case MessageType::UNIT_STATUS2: { @@ -413,6 +422,37 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() state2.unit_status2 = u.unit_status2; break; } + case MessageType::GNSS_ANGLES: { + CHECK_SIZE(u.gnss_angles); + gnss_data.heading = u.gnss_angles.heading*0.01; // deg + gnss_data.pitch = u.gnss_angles.pitch*0.01; // deg + break; + } + case MessageType::GNSS_ANGLE_POS_TYPE: { + CHECK_SIZE(u.gnss_angle_pos_type); + gnss_data.angle_pos_type = u.gnss_angle_pos_type; + break; + } + case MessageType::GNSS_HEADING_TIMESTAMP: { + CHECK_SIZE(u.gnss_heading_timestamp); + gnss_data.heading_timestamp = u.gnss_heading_timestamp; + break; + } + case MessageType::GNSS_DOP: { + CHECK_SIZE(u.gnss_dop); + gnss_data.gdop = u.gnss_dop.gdop*0.1; + gnss_data.pdop = u.gnss_dop.pdop*0.1; + gnss_data.tdop = u.gnss_dop.tdop*0.1; + + gps_data.hdop = u.gnss_dop.hdop*0.1; + gps_data.vdop = u.gnss_dop.vdop*0.1; + break; + } + case MessageType::INS_SOLUTION_STATUS: { + CHECK_SIZE(u.ins_sol_status); + state2.ins_sol_status = u.ins_sol_status; + break; + } } if (msg_len == 0) { @@ -440,13 +480,37 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() AP::ins().handle_external(ins_data); state.accel = ins_data.accel; state.gyro = ins_data.gyro; + +#if HAL_LOGGING_ENABLED + uint64_t now_us = AP_HAL::micros64(); + + // @LoggerMessage: ILB1 + // @Description: InertialLabs AHRS data1 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GPS INS time (round) + // @Field: GyrX: Gyro X + // @Field: GyrY: Gyro Y + // @Field: GyrZ: Gyro z + // @Field: AccX: Accelerometer X + // @Field: AccY: Accelerometer Y + // @Field: AccZ: Accelerometer Z + + AP::logger().WriteStreaming("ILB1", "TimeUS,GMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ", + "s-kkkooo", + "F-------", + "QIffffff", + now_us, gps_data.ms_tow, + ins_data.gyro.x, ins_data.gyro.y, ins_data.gyro.z, + ins_data.accel.x, ins_data.accel.y, ins_data.accel.z); +#endif // HAL_LOGGING_ENABLED } + if (GOT_MSG(GPS_INS_TIME_MS) && GOT_MSG(NUM_SATS) && GOT_MSG(GNSS_POSITION) && GOT_MSG(GNSS_NEW_DATA) && GOT_MSG(GNSS_EXTENDED_INFO) && - state2.gnss_new_data != 0) { + gnss_data.new_data != 0) { uint8_t instance; if (AP::gps().get_first_external_instance(instance)) { AP::gps().handle_external(gps_data, instance); @@ -465,18 +529,137 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() } last_gps_ms = now_ms; } + +#if HAL_LOGGING_ENABLED + uint64_t now_us = AP_HAL::micros64(); + + // @LoggerMessage: ILB4 + // @Description: InertialLabs AHRS data4 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GNSS Position timestamp + // @Field: GWk: GPS Week + // @Field: NSat: Number of satellites + // @Field: NewGPS: Indicator of new update of GPS data + // @Field: Lat: GNSS Latitude + // @Field: Lng: GNSS Longitude + // @Field: Alt: GNSS Altitude + // @Field: GCrs: GNSS Track over ground + // @Field: Spd: GNSS Horizontal speed + // @Field: VZ: GNSS Vertical speed + + AP::logger().WriteStreaming("ILB4", "TimeUS,GMS,GWk,NSat,NewGPS,Lat,Lng,Alt,GCrs,Spd,VZ", + "s----DUmhnn", + "F----------", + "QIHBBffffff", + now_us, gnss_data.pos_timestamp, gps_data.gps_week, + gps_data.satellites_in_view, gnss_data.new_data, + gnss_data.lat*1.0e-7, gnss_data.lng*1.0e-7, gnss_data.alt*0.01, + gnss_data.track_over_ground, gnss_data.hor_speed, gnss_data.ver_speed + ); + + // @LoggerMessage: ILB5 + // @Description: InertialLabs AHRS data5 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GNSS Position timestamp + // @Field: FType: fix type + // @Field: GSS: GNSS spoofing status + // @Field: GJS: GNSS jamming status + // @Field: GI1: GNSS Info1 + // @Field: GI2: GNSS Info2 + // @Field: GAPS: GNSS Angles position type + + AP::logger().WriteStreaming("ILB5", "TimeUS,GMS,FType,GSS,GJS,GI1,GI2,GAPS", + "s-------", + "F-------", + "QIBBBBBB", + now_us, gnss_data.pos_timestamp, gps_data.fix_type, + gnss_data.spoof_status, gnss_data.jam_status, + gnss_data.info_short.info1, gnss_data.info_short.info2, + gnss_data.angle_pos_type); + + // @LoggerMessage: ILB6 + // @Description: InertialLabs AHRS data6 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GNSS Position timestamp + // @Field: GpsHTS: GNSS Heading timestamp + // @Field: GpsYaw: GNSS Heading + // @Field: GpsPitch: GNSS Pitch + // @Field: GDOP: GNSS GDOP + // @Field: PDOP: GNSS PDOP + // @Field: HDOP: GNSS HDOP + // @Field: VDOP: GNSS VDOP + // @Field: TDOP: GNSS TDOP + + AP::logger().WriteStreaming("ILB6", "TimeUS,GMS,GpsHTS,GpsYaw,GpsPitch,GDOP,PDOP,HDOP,VDOP,TDOP", + "s--hd-----", + "F---------", + "QIIfffffff", + now_us, gnss_data.pos_timestamp, gnss_data.heading_timestamp, + gnss_data.heading, gnss_data.pitch, gnss_data.gdop, gnss_data.pdop, + gps_data.hdop, gps_data.vdop, gnss_data.tdop); +#endif // HAL_LOGGING_ENABLED } + #if AP_BARO_EXTERNALAHRS_ENABLED if (GOT_MSG(BARO_DATA) && GOT_MSG(TEMPERATURE)) { AP::baro().handle_external(baro_data); + +#if HAL_LOGGING_ENABLED + uint64_t now_us = AP_HAL::micros64(); + + // @LoggerMessage: ILB3 + // @Description: InertialLabs AHRS data3 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GPS INS time (round) + // @Field: Press: Static pressure + // @Field: Diff: Differential pressure + // @Field: Temp: Temperature + // @Field: Alt: Baro altitude + // @Field: TAS: true airspeed + // @Field: VWN: Wind velocity north + // @Field: VWE: Wind velocity east + // @Field: VWD: Wind velocity down + // @Field: ADU: Air Data Unit status + + AP::logger().WriteStreaming("ILB3", "TimeUS,GMS,Press,Diff,Temp,Alt,TAS,VWN,VWE,VWD,ADU", + "s-PPOmnnnn-", + "F----------", + "QIffffffffH", + now_us, gps_data.ms_tow, + baro_data.pressure_pa, airspeed_data.differential_pressure, baro_data.temperature, + state2.baro_alt, state2.true_airspeed, + state2.wind_speed.x, state2.wind_speed.y, state2.wind_speed.z, + state2.air_data_status); +#endif // HAL_LOGGING_ENABLED } -#endif - #if AP_COMPASS_EXTERNALAHRS_ENABLED +#endif // AP_BARO_EXTERNALAHRS_ENABLED + +#if AP_COMPASS_EXTERNALAHRS_ENABLED if (GOT_MSG(MAG_DATA)) { AP::compass().handle_external(mag_data); + +#if HAL_LOGGING_ENABLED + uint64_t now_us = AP_HAL::micros64(); + + // @LoggerMessage: ILB2 + // @Description: InertialLabs AHRS data2 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GPS INS time (round) + // @Field: MagX: Magnetometer X + // @Field: MagY: Magnetometer Y + // @Field: MagZ: Magnetometer Z + + AP::logger().WriteStreaming("ILB2", "TimeUS,GMS,MagX,MagY,MagZ", + "s----", + "F----", + "QIfff", + now_us, gps_data.ms_tow, + mag_data.field.x, mag_data.field.y, mag_data.field.z); +#endif // HAL_LOGGING_ENABLED } -#endif +#endif // AP_COMPASS_EXTERNALAHRS_ENABLED + #if AP_AIRSPEED_EXTERNAL_ENABLED && (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)) // only on plane and copter as others do not link AP_Airspeed if (GOT_MSG(DIFFERENTIAL_PRESSURE) && @@ -486,64 +669,352 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() arsp->handle_external(airspeed_data); } } + #endif // AP_AIRSPEED_EXTERNAL_ENABLED + buffer_ofs = 0; -#if HAL_LOGGING_ENABLED if (GOT_MSG(POSITION) && GOT_MSG(ORIENTATION_ANGLES) && GOT_MSG(VELOCITIES)) { - float roll, pitch, yaw; - state.quat.to_euler(roll, pitch, yaw); + float roll, pitch, yaw_deg; + state.quat.to_euler(roll, pitch, yaw_deg); + + yaw_deg = fmodf(degrees(yaw_deg), 360.0f); + if (yaw_deg < 0.0f) { + yaw_deg += 360.0f; + } + +#if HAL_LOGGING_ENABLED uint64_t now_us = AP_HAL::micros64(); - // @LoggerMessage: ILB1 - // @Description: InertialLabs AHRS data1 + // @LoggerMessage: ILB7 + // @Description: InertialLabs AHRS data7 // @Field: TimeUS: Time since system startup - // @Field: PosVarN: position variance north - // @Field: PosVarE: position variance east - // @Field: PosVarD: position variance down - // @Field: VelVarN: velocity variance north - // @Field: VelVarE: velocity variance east - // @Field: VelVarD: velocity variance down - - AP::logger().WriteStreaming("ILB1", "TimeUS,PosVarN,PosVarE,PosVarD,VelVarN,VelVarE,VelVarD", - "smmmnnn", - "F000000", - "Qffffff", - now_us, - state2.kf_pos_covariance.x, state2.kf_pos_covariance.x, state2.kf_pos_covariance.z, - state2.kf_vel_covariance.x, state2.kf_vel_covariance.x, state2.kf_vel_covariance.z); + // @Field: GMS: GPS INS time (round) + // @Field: Roll: euler roll + // @Field: Pitch: euler pitch + // @Field: Yaw: euler yaw + // @Field: VN: velocity north + // @Field: VE: velocity east + // @Field: VD: velocity down + // @Field: Lat: latitude + // @Field: Lng: longitude + // @Field: Alt: altitude MSL + // @Field: USW: USW1 + // @Field: USW2: USW2 + // @Field: Vdc: Supply voltage - // @LoggerMessage: ILB2 - // @Description: InertialLabs AHRS data3 - // @Field: TimeUS: Time since system startup - // @Field: Stat1: unit status1 - // @Field: Stat2: unit status2 - // @Field: FType: fix type - // @Field: SpStat: spoofing status - // @Field: GI1: GNSS Info1 - // @Field: GI2: GNSS Info2 - // @Field: GJS: GNSS jamming status - // @Field: TAS: true airspeed - // @Field: WVN: Wind velocity north - // @Field: WVE: Wind velocity east - // @Field: WVD: Wind velocity down - - AP::logger().WriteStreaming("ILB2", "TimeUS,Stat1,Stat2,FType,SpStat,GI1,GI2,GJS,TAS,WVN,WVE,WVD", - "s-----------", - "F-----------", - "QHHBBBBBffff", - now_us, + AP::logger().WriteStreaming("ILB7", "TimeUS,GMS,Roll,Pitch,Yaw,VN,VE,VD,Lat,Lng,Alt,USW,USW2,Vdc", + "s-dddnnnDUm--v", + "F-------------", + "QIfffffffffHHf", + now_us, gps_data.ms_tow, + degrees(roll), degrees(pitch), yaw_deg, + state.velocity.x, state.velocity.y, state.velocity.z, + state.location.lat*1.0e-7, state.location.lng*1.0e-7, state.location.alt*0.01, state2.unit_status, state2.unit_status2, - state2.gnss_extended_info.fix_type, state2.gnss_extended_info.spoofing_status, - state2.gnss_info_short.info1, state2.gnss_info_short.info2, - state2.gnss_jam_status, - state2.true_airspeed, - state2.wind_speed.x, state2.wind_speed.y, state2.wind_speed.z); - } + state2.supply_voltage); + + // @LoggerMessage: ILB8 + // @Description: InertialLabs AHRS data8 + // @Field: TimeUS: Time since system startup + // @Field: GMS: GPS INS time (round) + // @Field: PVN: position variance north + // @Field: PVE: position variance east + // @Field: PVD: position variance down + // @Field: VVN: velocity variance north + // @Field: VVE: velocity variance east + // @Field: VVD: velocity variance down + + AP::logger().WriteStreaming("ILB8", "TimeUS,GMS,PVN,PVE,PVD,VVN,VVE,VVD", + "s-mmmnnn", + "F-------", + "QIffffff", + now_us, gps_data.ms_tow, + state2.kf_pos_covariance.x, state2.kf_pos_covariance.y, state2.kf_pos_covariance.z, + state2.kf_vel_covariance.x, state2.kf_vel_covariance.y, state2.kf_vel_covariance.z); #endif // HAL_LOGGING_ENABLED + } + + const uint32_t dt_critical_usw = 10000; + uint32_t now_usw = AP_HAL::millis(); + + // InertialLabs critical messages to GCS (sending messages once every 10 seconds) + if ((last_unit_status != state2.unit_status) || + (last_unit_status2 != state2.unit_status2) || + (last_air_data_status != state2.air_data_status) || + (now_usw - last_critical_msg_ms > dt_critical_usw)) { + + // Critical USW message + if (state2.unit_status & ILABS_UNIT_STATUS_ALIGNMENT_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Unsuccessful initial alignment"); + } + if (state2.unit_status & ILABS_UNIT_STATUS_OPERATION_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: IMU data are incorrect"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_GYRO_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Gyros failure"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_ACCEL_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Accelerometers failure"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_MAG_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Magnetometers failure"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_ELECTRONICS_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Electronics failure"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_GNSS_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: GNSS receiver failure"); + } + + // Critical USW2 message + if (state2.unit_status2 & ILABS_UNIT_STATUS2_BARO_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Baro altimeter failure"); + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_DIFF_PRESS_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Diff. pressure sensor failure"); + } + + // Critical ADU message + if (state2.air_data_status & ILABS_AIRDATA_INIT_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Static pressure sensor unsuccessful initialization"); + } + + if (state2.air_data_status & ILABS_AIRDATA_DIFF_PRESS_INIT_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ILAB: Diff. pressure sensor unsuccessful initialization"); + } + + if (state2.air_data_status & ILABS_AIRDATA_STATIC_PRESS_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ILAB: Static pressure sensor failure is detect"); + } + + if (state2.air_data_status & ILABS_AIRDATA_DIFF_PRESS_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ILAB: Diff. pressure sensor failure is detect"); + } + + last_critical_msg_ms = AP_HAL::millis(); + } + + if (last_unit_status != state2.unit_status) { + if (state2.unit_status & ILABS_UNIT_STATUS_RUNTIME_CAL) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: On-the-fly calibration is in progress"); + } + + if (state2.unit_status & ILABS_UNIT_STATUS_VOLTAGE_LOW) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Low input voltage"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_VOLTAGE_LOW) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Input voltage is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_VOLTAGE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: High input voltage"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_VOLTAGE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Input voltage is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_X_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Y-axis angular rate is exceeded"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_X_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Y-axis angular rate is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_Y_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: X-axis angular rate is exceeded"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_Y_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: X-axis angular rate is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_Z_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Z-axis angular rate is exceeded"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_Z_RATE_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Z-axis angular rate is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_MAG_FIELD_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Large total magnetic field"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_MAG_FIELD_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Total magnetic field is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_TEMP_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Temperature is out of range"); + } else { + if (last_unit_status & ILABS_UNIT_STATUS_TEMP_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Temperature is in range"); + } + } + + if (state2.unit_status & ILABS_UNIT_STATUS_RUNTIME_CAL2) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: On-the-fly calibration successful"); + } + + last_unit_status = state2.unit_status; + } + + // InertialLabs INS Unit Status Word 2 (USW2) messages to GCS + if (last_unit_status2 != state2.unit_status2) { + if (state2.unit_status2 & ILABS_UNIT_STATUS2_ACCEL_X_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Y-acceleration is out of range"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_ACCEL_X_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Y-acceleration is in range"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_ACCEL_Y_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: X-acceleration is out of range"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_ACCEL_Y_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: X-acceleration is in range"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_ACCEL_Z_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Z-acceleration is out of range"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_ACCEL_Z_HIGH) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Z-acceleration is in range"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_MAGCAL_2D_ACT) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Automatic 2D calibration is in progress"); + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_MAGCAL_3D_ACT) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Automatic 3D calibration is in progress"); + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_GNSS_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: GNSS input switched off"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_GNSS_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: GNSS input switched on"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_DIFF_PRESS_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Diff. pressure input switched off"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_DIFF_PRESS_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Diff. pressure input switched on"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_MAG_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Magnetometer input switched off"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_MAG_FUSION_OFF) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Magnetometer input switched on"); + } + } + + if (state2.unit_status2 & ILABS_UNIT_STATUS2_GNSS_POS_VALID) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Incorrect GNSS position"); + } else { + if (last_unit_status2 & ILABS_UNIT_STATUS2_GNSS_POS_VALID) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: GNSS position is correct"); + } + } + + last_unit_status2 = state2.unit_status2; + } + + // InertialLabs INS Air Data Unit (ADU) status messages to GCS + if (last_air_data_status != state2.air_data_status) { + if (state2.air_data_status & ILABS_AIRDATA_STATIC_PRESS_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Static pressure is out of range"); + } else { + if (last_air_data_status & ILABS_AIRDATA_STATIC_PRESS_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Static pressure is in range"); + } + } + + if (state2.air_data_status & ILABS_AIRDATA_DIFF_PRESS_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Diff. pressure is out of range"); + } else { + if (last_air_data_status & ILABS_AIRDATA_DIFF_PRESS_RANGE_ERR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Diff. pressure is in range"); + } + } + + if (state2.air_data_status & ILABS_AIRDATA_PRESS_ALT_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Pressure altitude is incorrect"); + } else { + if (last_air_data_status & ILABS_AIRDATA_PRESS_ALT_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Pressure altitude is correct"); + } + } + + if (state2.air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Air speed is incorrect"); + } else { + if (last_air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Air speed is correct"); + } + } + + if (state2.air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: Air speed is below the threshold"); + } else { + if (last_air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: Air speed is above the threshold"); + } + } + + last_air_data_status = state2.air_data_status; + } + + // InertialLabs INS spoofing detection messages to GCS + if (last_spoof_status != gnss_data.spoof_status) { + if ((last_spoof_status == 2 || last_spoof_status == 3) && (gnss_data.spoof_status == 1)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: GNSS no spoofing"); + } + + if (last_spoof_status == 2) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: GNSS spoofing indicated"); + } + + if (last_spoof_status == 3) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: GNSS multiple spoofing indicated"); + } + + last_spoof_status = gnss_data.spoof_status; + } + + // InertialLabs INS jamming detection messages to GCS + if (last_jam_status != gnss_data.jam_status) { + if ((last_jam_status == 2 || last_jam_status == 3) && (gnss_data.jam_status == 1)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ILAB: GNSS no jamming"); + } + + if (gnss_data.jam_status == 3) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ILAB: GNSS jamming indicated and no fix"); + } + + last_jam_status = gnss_data.jam_status; + } return true; } @@ -632,65 +1103,22 @@ void AP_ExternalAHRS_InertialLabs::get_filter_status(nav_filter_status &status) status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_abs; status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs; status.flags.using_gps = (now - last_gps_ms < dt_limit_gps) && - (state2.unit_status & (ILABS_UNIT_STATUS_GNSS_FAIL|ILABS_UNIT_STATUS2_GNSS_FUSION_OFF)) == 0; + ((state2.unit_status & ILABS_UNIT_STATUS_GNSS_FAIL) | (state2.unit_status2 & ILABS_UNIT_STATUS2_GNSS_FUSION_OFF)) == 0; status.flags.gps_quality_good = (now - last_gps_ms < dt_limit_gps) && (state2.unit_status2 & ILABS_UNIT_STATUS2_GNSS_POS_VALID) != 0 && (state2.unit_status & ILABS_UNIT_STATUS_GNSS_FAIL) == 0; status.flags.rejecting_airspeed = (state2.air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL); } -// send an EKF_STATUS message to GCS -void AP_ExternalAHRS_InertialLabs::send_status_report(GCS_MAVLINK &link) const +// get variances +bool AP_ExternalAHRS_InertialLabs::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { - // prepare flags - uint16_t flags = 0; - nav_filter_status filterStatus; - get_filter_status(filterStatus); - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - if (!filterStatus.flags.initalized) { - flags |= EKF_UNINITIALIZED; - } - - // send message - const float vel_gate = 5; - const float pos_gate = 5; - const float hgt_gate = 5; - const float mag_var = 0; - mavlink_msg_ekf_status_report_send(link.get_chan(), flags, - state2.kf_vel_covariance.length()/vel_gate, - state2.kf_pos_covariance.xy().length()/pos_gate, - state2.kf_pos_covariance.z/hgt_gate, - mag_var, 0, 0); + velVar = state2.kf_vel_covariance.length() * vel_gate_scale; + posVar = state2.kf_pos_covariance.xy().length() * pos_gate_scale; + hgtVar = state2.kf_pos_covariance.z * hgt_gate_scale; + tasVar = 0; + return true; } -#endif // AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#endif // AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h index bee7d5c28e0cce..0db51358e79b34 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h @@ -20,7 +20,7 @@ #include "AP_ExternalAHRS_config.h" -#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED #include "AP_ExternalAHRS_backend.h" @@ -37,7 +37,7 @@ class AP_ExternalAHRS_InertialLabs : 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(class GCS_MAVLINK &link) const override; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override; // check for new data void update() override { @@ -77,6 +77,11 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { SUPPLY_VOLTAGE = 0x50, TEMPERATURE = 0x52, UNIT_STATUS2 = 0x5A, + GNSS_ANGLES = 0x33, + GNSS_ANGLE_POS_TYPE = 0x3A, + GNSS_HEADING_TIMESTAMP = 0x40, + GNSS_DOP = 0x42, + INS_SOLUTION_STATUS = 0x54, }; /* @@ -129,8 +134,8 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { }; union PACKED ILabsData { - uint32_t gps_time_ms; // ms since start of GPS week - uint16_t gps_week; + uint32_t gnss_time_ms; // ms since start of GNSS week + uint16_t gnss_week; vec3_32_t accel_data_hr; // g * 1e6 vec3_32_t gyro_data_hr; // deg/s * 1e5 struct PACKED { @@ -139,7 +144,7 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { } baro_data; vec3_16_t mag_data; // nT/10 struct PACKED { - int16_t yaw; // deg*100 + uint16_t yaw; // deg*100 int16_t pitch; // deg*100 int16_t roll; // deg*100 } orientation_angles; // 321 euler order? @@ -150,10 +155,15 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { int32_t alt; // m*100, AMSL } position; vec3_u8_t kf_vel_covariance; // mm/s - vec3_u16_t kf_pos_covariance; + vec3_u16_t kf_pos_covariance; // mm uint16_t unit_status; // set ILABS_UNIT_STATUS_* gnss_extended_info_t gnss_extended_info; uint8_t num_sats; + struct PACKED { + int32_t lat; // deg*1e7 + int32_t lon; // deg*1e7 + int32_t alt; // m*100 + } gnss_position; struct PACKED { int32_t hor_speed; // m/s*100 uint16_t track_over_ground; // deg*100 @@ -170,6 +180,20 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { uint16_t supply_voltage; // V*100 int16_t temperature; // degC*10 uint16_t unit_status2; + struct PACKED { + uint16_t heading; // deg*100 + int16_t pitch; // deg*100 + } gnss_angles; + uint8_t gnss_angle_pos_type; + uint32_t gnss_heading_timestamp; // ms + struct PACKED { + uint16_t gdop; + uint16_t pdop; + uint16_t hdop; + uint16_t vdop; + uint16_t tdop; + } gnss_dop; // 10e3 + uint8_t ins_sol_status; }; AP_ExternalAHRS::gps_data_message_t gps_data; @@ -181,6 +205,12 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { uint16_t buffer_ofs; uint8_t buffer[256]; // max for normal message set is 167+8 +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } + private: AP_HAL::UARTDriver *uart; int8_t port_num; @@ -200,27 +230,53 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { } message_lengths[]; struct { + float baro_alt; Vector3f kf_vel_covariance; Vector3f kf_pos_covariance; - uint32_t gnss_ins_time_ms; uint16_t unit_status; uint16_t unit_status2; - gnss_extended_info_t gnss_extended_info; - gnss_info_short_t gnss_info_short; - uint8_t gnss_new_data; - uint8_t gnss_jam_status; float differential_pressure; float true_airspeed; Vector3f wind_speed; uint16_t air_data_status; float supply_voltage; + uint8_t ins_sol_status; } state2; + struct { + float lat; + float lng; + float alt; + float hor_speed; + float ver_speed; + float track_over_ground; + uint8_t new_data; + uint32_t pos_timestamp; + uint32_t heading_timestamp; + uint8_t spoof_status; + uint8_t jam_status; + uint8_t angle_pos_type; + gnss_info_short_t info_short; + float heading; + float pitch; + float gdop; + float pdop; + float tdop; + } gnss_data; + + uint16_t last_unit_status; + uint16_t last_unit_status2; + uint16_t last_air_data_status; + uint8_t last_spoof_status; + uint8_t last_jam_status; + + uint32_t last_critical_msg_ms; + uint32_t last_att_ms; uint32_t last_vel_ms; uint32_t last_pos_ms; uint32_t last_gps_ms; }; -#endif // AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#endif // AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp index ed6304429c28d8..0e500bc403a896 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp @@ -169,7 +169,7 @@ void AP_ExternalAHRS_MicroStrain5::post_filter() const AP_ExternalAHRS::gps_data_message_t gps { gps_week: filter_data.week, ms_tow: filter_data.tow_ms, - fix_type: (uint8_t) gnss_data[gnss_instance].fix_type, + fix_type: AP_GPS_FixType(gnss_data[gnss_instance].fix_type), satellites_in_view: gnss_data[gnss_instance].satellites, horizontal_pos_accuracy: gnss_data[gnss_instance].horizontal_position_accuracy, @@ -188,7 +188,7 @@ void AP_ExternalAHRS_MicroStrain5::post_filter() const ned_vel_down: filter_data.ned_velocity_down, }; - if (gps.fix_type >= 3 && !state.have_origin) { + if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) { WITH_SEMAPHORE(state.sem); state.origin = Location{int32_t(filter_data.lat), int32_t(filter_data.lon), @@ -268,55 +268,14 @@ void AP_ExternalAHRS_MicroStrain5::get_filter_status(nav_filter_status &status) } } -void AP_ExternalAHRS_MicroStrain5::send_status_report(GCS_MAVLINK &link) const +// get variances +bool AP_ExternalAHRS_MicroStrain5::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { - // prepare flags - uint16_t flags = 0; - nav_filter_status filterStatus; - get_filter_status(filterStatus); - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - if (!filterStatus.flags.initalized) { - flags |= EKF_UNINITIALIZED; - } - - // send message - const float vel_gate = 4; // represents hz value data is posted at - 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(link.get_chan(), flags, - gnss_data[gnss_instance].speed_accuracy/vel_gate, gnss_data[gnss_instance].horizontal_position_accuracy/pos_gate, gnss_data[gnss_instance].vertical_position_accuracy/hgt_gate, - mag_var, 0, 0); - + velVar = gnss_data[gnss_instance].speed_accuracy * vel_gate_scale; + posVar = gnss_data[gnss_instance].horizontal_position_accuracy * pos_gate_scale; + hgtVar = gnss_data[gnss_instance].vertical_position_accuracy * hgt_gate_scale; + tasVar = 0; + return true; } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h index e6b2b9e6bdcb17..a311af5089f241 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h @@ -42,13 +42,19 @@ class AP_ExternalAHRS_MicroStrain5: public AP_ExternalAHRS_backend, public AP_Mi 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(class GCS_MAVLINK &link) const override; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override; // check for new data void update() override { build_packet(); }; +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } + private: uint32_t baudrate; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp index 901fff1c84cf53..31082aea9b2e51 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp @@ -18,6 +18,7 @@ param set AHRS_EKF_TYPE 11 param set EAHRS_TYPE 7 param set GPS1_TYPE 21 + param set GPS2_TYPE 21 param set SERIAL3_BAUD 115 param set SERIAL3_PROTOCOL 36 UDEV rules for repeatable USB connection: @@ -209,7 +210,7 @@ void AP_ExternalAHRS_MicroStrain7::post_filter() const AP_ExternalAHRS::gps_data_message_t gps { gps_week: filter_data.week, ms_tow: filter_data.tow_ms, - fix_type: (uint8_t) gnss_data[instance].fix_type, + fix_type: AP_GPS_FixType(gnss_data[instance].fix_type), satellites_in_view: gnss_data[instance].satellites, horizontal_pos_accuracy: gnss_data[instance].horizontal_position_accuracy, @@ -229,7 +230,7 @@ void AP_ExternalAHRS_MicroStrain7::post_filter() const }; // *INDENT-ON* - if (gps.fix_type >= 3 && !state.have_origin) { + if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) { WITH_SEMAPHORE(state.sem); state.origin = Location{int32_t(gnss_data[instance].lat), int32_t(gnss_data[instance].lon), @@ -269,28 +270,24 @@ bool AP_ExternalAHRS_MicroStrain7::initialised(void) const bool AP_ExternalAHRS_MicroStrain7::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const { if (!initialised()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "not initialised"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "not initialised"); return false; } if (!times_healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "data is stale"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "data is stale"); return false; } if (!filter_healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "filter is unhealthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "filter is unhealthy"); return false; } if (!healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "unhealthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "unhealthy"); return false; } static_assert(NUM_GNSS_INSTANCES == 2, "This check only works if there are two GPS types."); if (gnss_data[0].fix_type < GPS_FIX_TYPE_3D_FIX && gnss_data[1].fix_type < GPS_FIX_TYPE_3D_FIX) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "missing 3D GPS fix on either GPS"); - return false; - } - if (!filter_state_healthy(FilterState(filter_status.state))) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "filter not healthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "missing 3D GPS fix on either GPS"); return false; } @@ -320,63 +317,14 @@ void AP_ExternalAHRS_MicroStrain7::get_filter_status(nav_filter_status &status) } } -void AP_ExternalAHRS_MicroStrain7::send_status_report(GCS_MAVLINK &link) const +// get variances +bool AP_ExternalAHRS_MicroStrain7::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { - // prepare flags - uint16_t flags = 0; - nav_filter_status filterStatus; - get_filter_status(filterStatus); - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - if (!filterStatus.flags.initalized) { - flags |= EKF_UNINITIALIZED; - } - - // send message - const float vel_gate = 4; // represents hz value data is posted at - 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 - - const float velocity_variance {filter_data.ned_velocity_uncertainty.length() / vel_gate}; - const float pos_horiz_variance {filter_data.ned_position_uncertainty.xy().length() / pos_gate}; - const float pos_vert_variance {filter_data.ned_position_uncertainty.z / hgt_gate}; - // No terrain alt sensor on MicroStrain7. - const float terrain_alt_variance {0}; - // No airspeed sensor on MicroStrain7. - const float airspeed_variance {0}; - mavlink_msg_ekf_status_report_send(link.get_chan(), flags, - velocity_variance, pos_horiz_variance, pos_vert_variance, - mag_var, terrain_alt_variance, airspeed_variance); - + velVar = filter_data.ned_velocity_uncertainty.length() * vel_gate_scale; + posVar = filter_data.ned_position_uncertainty.xy().length() * pos_gate_scale; + hgtVar = filter_data.ned_position_uncertainty.z * hgt_gate_scale; + tasVar = 0; + return true; } bool AP_ExternalAHRS_MicroStrain7::times_healthy() const diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h index 5cff5af56a6dcd..27fcd19d00eb1d 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h @@ -42,7 +42,7 @@ class AP_ExternalAHRS_MicroStrain7: public AP_ExternalAHRS_backend, public AP_Mi 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(class GCS_MAVLINK &link) const override; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override; // check for new data void update() override @@ -50,6 +50,13 @@ class AP_ExternalAHRS_MicroStrain7: public AP_ExternalAHRS_backend, public AP_Mi build_packet(); }; +protected: + + uint8_t num_gps_sensors(void) const override + { + return AP_MicroStrain::NUM_GNSS_INSTANCES; + } + private: // GQ7 Filter States diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 179f05fd9f1e2c..4a502624021a1b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -38,135 +38,138 @@ extern const AP_HAL::HAL &hal; -/* - header for pre-configured 50Hz data - assumes the following config for VN-300: - $VNWRG,75,3,8,34,072E,0106,0612*0C - - 0x34: Groups 3,5,6 - Group 3 (IMU): - 0x072E: - UncompMag - UncompAccel - UncompGyro - Pres - Mag - Accel - AngularRate - Group 5 (Attitude): - 0x0106: - YawPitchRoll - Quaternion - YprU - Group 6 (INS): - 0x0612: - PosLLa - VelNed - PosU - VelU +/* +TYPE::VN_AHRS configures 2 packets: high-rate IMU and mid-rate EKF +Header for IMU packet + $VNWRG,75,3,16,01,0721*D415 + Common group (Group 1) + TimeStartup + AngularRate + Accel + Imu + MagPres +Header for EKF packet + $VNWRG,76,3,16,11,0001,0106*B36B + Common group (Group 1) + TimeStartup + Attitude group (Group 4) + Ypr + Quaternion + YprU */ -static const uint8_t vn_pkt1_header[] { 0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06 }; -#define VN_PKT1_LENGTH 170 // includes header and CRC -struct PACKED VN_packet1 { - float uncompMag[3]; +struct PACKED VN_IMU_packet { + static constexpr uint8_t header[]{0x01, 0x21, 0x07}; + uint64_t timeStartup; + float gyro[3]; + float accel[3]; float uncompAccel[3]; float uncompAngRate[3]; - float pressure; float mag[3]; - float accel[3]; - float gyro[3]; + float temp; + float pressure; +}; +constexpr uint8_t VN_IMU_packet::header[]; +constexpr uint8_t VN_IMU_LENGTH = sizeof(VN_IMU_packet) + sizeof(VN_IMU_packet::header) + 1 + 2; // Includes sync byte and CRC + +struct PACKED VN_AHRS_ekf_packet { + static constexpr uint8_t header[]{0x11, 0x01, 0x00, 0x06, 0x01}; + uint64_t timeStartup; float ypr[3]; float quaternion[4]; float yprU[3]; - double positionLLA[3]; - float velNED[3]; - float posU; - float velU; }; - -// check packet size for 4 groups -static_assert(sizeof(VN_packet1)+2+3*2+2 == VN_PKT1_LENGTH, "incorrect VN_packet1 length"); +constexpr uint8_t VN_AHRS_ekf_packet::header[]; +constexpr uint8_t VN_AHRS_EKF_LENGTH = sizeof(VN_AHRS_ekf_packet) + sizeof(VN_AHRS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC /* - header for pre-configured 5Hz data - assumes the following VN-300 config: - $VNWRG,76,3,80,4E,0002,0010,20B8,0018*63 - - 0x4E: Groups 2,3,4,7 - Group 2 (Time): - 0x0002: - TimeGps - Group 3 (IMU): - 0x0010: - Temp - Group 4 (GPS1): - 0x20B8: - NumSats - Fix - PosLLa - VelNed - DOP - Group 7 (GPS2): - 0x0018: - NumSats - Fix +TYPE::VN_INS configures 3 packets: high-rate IMU, mid-rate EKF, and 5Hz GNSS +Header for IMU packet + $VNWRG,75,3,16,01,0721*D415 + Common group (Group 1) + TimeStartup + AngularRate + Accel + Imu + MagPres +Header for EKF packet + $VNWRG,76,3,16,31,0001,0106,0613*097A + Common group (Group 1) + TimeStartup + Attitude group (Group 4) + Ypr + Quaternion + YprU + Ins group (Group 5) + InsStatus + PosLla + VelNed + PosU + VelU +Header for GNSS packet + $VNWRG,77,1,160,49,0003,26B8,0018*4FD9 + Common group (Group 1) + TimeStartup + TimeGps + Gnss1 group (Group 3) + NumSats + GnssFix + GnssPosLla + GnssVelNed + PosU1 + VelU1 + GnssDop + Gnss2 group (Group 6) + NumSats + GnssFix */ -static const uint8_t vn_pkt2_header[] { 0x4e, 0x02, 0x00, 0x10, 0x00, 0xb8, 0x20, 0x18, 0x00 }; -#define VN_PKT2_LENGTH 92 // includes header and CRC -struct PACKED VN_packet2 { - uint64_t timeGPS; - float temp; - uint8_t numGPS1Sats; - uint8_t GPS1Fix; - double GPS1posLLA[3]; - float GPS1velNED[3]; - float GPS1DOP[7]; - uint8_t numGPS2Sats; - uint8_t GPS2Fix; +union Ins_Status { + uint16_t _value; + struct { + uint16_t mode : 2; + uint16_t gnssFix : 1; + uint16_t resv1 : 2; + uint16_t imuErr : 1; + uint16_t magPresErr : 1; + uint16_t gnssErr : 1; + uint16_t resv2 : 1; + uint16_t gnssHeadingIns : 2; + }; }; -// check packet size for 4 groups -static_assert(sizeof(VN_packet2)+2+4*2+2 == VN_PKT2_LENGTH, "incorrect VN_packet2 length"); - -/* - assumes the following VN-300 config: - $VNWRG,75,3,80,14,073E,0004*66 - - Alternate first packet for VN-100 - 0x14: Groups 3, 5 - Group 3 (IMU): - 0x073E: - UncompMag - UncompAccel - UncompGyro - Temp - Pres - Mag - Accel - Gyro - Group 5 (Attitude): - 0x0004: - Quaternion -*/ -static const uint8_t vn_100_pkt1_header[] { 0x14, 0x3E, 0x07, 0x04, 0x00 }; -#define VN_100_PKT1_LENGTH 104 // includes header and CRC - -struct PACKED VN_100_packet1 { - float uncompMag[3]; - float uncompAccel[3]; - float uncompAngRate[3]; - float temp; - float pressure; - float mag[3]; - float accel[3]; - float gyro[3]; +struct PACKED VN_INS_ekf_packet { + static constexpr uint8_t header[]{0x31, 0x01, 0x00, 0x06, 0x01, 0x13, 0x06}; + uint64_t timeStartup; + float ypr[3]; float quaternion[4]; + float yprU[3]; + uint16_t insStatus; + double posLla[3]; + float velNed[3]; + float posU; + float velU; }; - -static_assert(sizeof(VN_100_packet1)+2+2*2+2 == VN_100_PKT1_LENGTH, "incorrect VN_100_packet1 length"); +constexpr uint8_t VN_INS_ekf_packet::header[]; +constexpr uint8_t VN_INS_EKF_LENGTH = sizeof(VN_INS_ekf_packet) + sizeof(VN_INS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC + +struct PACKED VN_INS_gnss_packet { + static constexpr uint8_t header[]{0x49, 0x03, 0x00, 0xB8, 0x26, 0x18, 0x00}; + uint64_t timeStartup; + uint64_t timeGps; + uint8_t numSats1; + uint8_t fix1; + double posLla1[3]; + float velNed1[3]; + float posU1[3]; + float velU1; + float dop1[7]; + uint8_t numSats2; + uint8_t fix2; +}; +constexpr uint8_t VN_INS_gnss_packet::header[]; +constexpr uint8_t VN_INS_GNSS_LENGTH = sizeof(VN_INS_gnss_packet) + sizeof(VN_INS_gnss_packet::header) + 1 + 2; // Includes sync byte and CRC // constructor AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, @@ -182,12 +185,13 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); - bufsize = MAX(MAX(VN_PKT1_LENGTH, VN_PKT2_LENGTH), VN_100_PKT1_LENGTH); - pktbuf = new uint8_t[bufsize]; - last_pkt1 = new VN_packet1; - last_pkt2 = new VN_packet2; + bufsize = MAX(MAX(MAX(VN_IMU_LENGTH, VN_INS_EKF_LENGTH), VN_INS_GNSS_LENGTH), VN_AHRS_EKF_LENGTH); + + pktbuf = NEW_NOTHROW uint8_t[bufsize]; + latest_ins_ekf_packet = NEW_NOTHROW VN_INS_ekf_packet; + latest_ins_gnss_packet = NEW_NOTHROW VN_INS_gnss_packet; - if (!pktbuf || !last_pkt1 || !last_pkt2) { + if (!pktbuf || !latest_ins_ekf_packet) { AP_BoardConfig::allocation_error("VectorNav ExternalAHRS"); } @@ -225,48 +229,57 @@ bool AP_ExternalAHRS_VectorNav::check_uart() bool match_header1 = false; bool match_header2 = false; bool match_header3 = false; + bool match_header4 = false; if (pktbuf[0] != SYNC_BYTE) { goto reset; } - if (type == TYPE::VN_300) { - match_header1 = (0 == memcmp(&pktbuf[1], vn_pkt1_header, MIN(sizeof(vn_pkt1_header), unsigned(pktoffset-1)))); - match_header2 = (0 == memcmp(&pktbuf[1], vn_pkt2_header, MIN(sizeof(vn_pkt2_header), unsigned(pktoffset-1)))); + + match_header1 = (0 == memcmp(&pktbuf[1], VN_IMU_packet::header, MIN(sizeof(VN_IMU_packet::header), unsigned(pktoffset - 1)))); + if (type == TYPE::VN_AHRS) { + match_header2 = (0 == memcmp(&pktbuf[1], VN_AHRS_ekf_packet::header, MIN(sizeof(VN_AHRS_ekf_packet::header), unsigned(pktoffset - 1)))); } else { - match_header3 = (0 == memcmp(&pktbuf[1], vn_100_pkt1_header, MIN(sizeof(vn_100_pkt1_header), unsigned(pktoffset-1)))); + match_header3 = (0 == memcmp(&pktbuf[1], VN_INS_ekf_packet::header, MIN(sizeof(VN_INS_ekf_packet::header), unsigned(pktoffset - 1)))); + match_header4 = (0 == memcmp(&pktbuf[1], VN_INS_gnss_packet::header, MIN(sizeof(VN_INS_gnss_packet::header), unsigned(pktoffset - 1)))); } - if (!match_header1 && !match_header2 && !match_header3) { + if (!match_header1 && !match_header2 && !match_header3 && !match_header4) { goto reset; } - if (match_header1 && pktoffset >= VN_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_PKT1_LENGTH-1, 0); + if (match_header1 && pktoffset >= VN_IMU_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_IMU_LENGTH - 1, 0); + if (crc == 0) { + process_imu_packet(&pktbuf[sizeof(VN_IMU_packet::header) + 1]); + memmove(&pktbuf[0], &pktbuf[VN_IMU_LENGTH], pktoffset - VN_IMU_LENGTH); + pktoffset -= VN_IMU_LENGTH; + } else { + goto reset; + } + } else if (match_header2 && pktoffset >= VN_AHRS_EKF_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_EKF_LENGTH - 1, 0); if (crc == 0) { - // got pkt1 - process_packet1(&pktbuf[sizeof(vn_pkt1_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_PKT1_LENGTH], pktoffset-VN_PKT1_LENGTH); - pktoffset -= VN_PKT1_LENGTH; + process_ahrs_ekf_packet(&pktbuf[sizeof(VN_AHRS_ekf_packet::header) + 1]); + memmove(&pktbuf[0], &pktbuf[VN_AHRS_EKF_LENGTH], pktoffset - VN_AHRS_EKF_LENGTH); + pktoffset -= VN_AHRS_EKF_LENGTH; } else { goto reset; } - } else if (match_header2 && pktoffset >= VN_PKT2_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_PKT2_LENGTH-1, 0); + } else if (match_header3 && pktoffset >= VN_INS_EKF_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_EKF_LENGTH - 1, 0); if (crc == 0) { - // got pkt2 - process_packet2(&pktbuf[sizeof(vn_pkt2_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_PKT2_LENGTH], pktoffset-VN_PKT2_LENGTH); - pktoffset -= VN_PKT2_LENGTH; + process_ins_ekf_packet(&pktbuf[sizeof(VN_INS_ekf_packet::header) + 1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_EKF_LENGTH], pktoffset - VN_INS_EKF_LENGTH); + pktoffset -= VN_INS_EKF_LENGTH; } else { goto reset; } - } else if (match_header3 && pktoffset >= VN_100_PKT1_LENGTH) { - uint16_t crc = crc16_ccitt(&pktbuf[1], VN_100_PKT1_LENGTH-1, 0); + } else if (match_header4 && pktoffset >= VN_INS_GNSS_LENGTH) { + uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_GNSS_LENGTH - 1, 0); if (crc == 0) { - // got VN-100 pkt1 - process_packet_VN_100(&pktbuf[sizeof(vn_100_pkt1_header)+1]); - memmove(&pktbuf[0], &pktbuf[VN_100_PKT1_LENGTH], pktoffset-VN_100_PKT1_LENGTH); - pktoffset -= VN_100_PKT1_LENGTH; + process_ins_gnss_packet(&pktbuf[sizeof(VN_INS_gnss_packet::header) + 1]); + memmove(&pktbuf[0], &pktbuf[VN_INS_GNSS_LENGTH], pktoffset - VN_INS_GNSS_LENGTH); + pktoffset -= VN_INS_GNSS_LENGTH; } else { goto reset; } @@ -285,12 +298,16 @@ bool AP_ExternalAHRS_VectorNav::check_uart() return true; } -// Send command to read given register number and wait for response -// Only run from thread! This blocks until a response is received +// Send command and wait for response +// Only run from thread! This blocks and retries until a non-error response is received #define READ_REQUEST_RETRY_MS 500 -void AP_ExternalAHRS_VectorNav::wait_register_responce(const uint8_t register_num) +void AP_ExternalAHRS_VectorNav::run_command(const char * fmt, ...) { - nmea.register_number = register_num; + va_list ap; + + va_start(ap, fmt); + hal.util->vsnprintf(message_to_send, sizeof(message_to_send), fmt, ap); + va_end(ap); uint32_t request_sent = 0; while (true) { @@ -298,8 +315,7 @@ void AP_ExternalAHRS_VectorNav::wait_register_responce(const uint8_t register_nu const uint32_t now = AP_HAL::millis(); if (now - request_sent > READ_REQUEST_RETRY_MS) { - // Send request to read - nmea_printf(uart, "$%s%u", "VNRRG,", nmea.register_number); + nmea_printf(uart, "$%s", message_to_send); request_sent = now; } @@ -307,6 +323,10 @@ void AP_ExternalAHRS_VectorNav::wait_register_responce(const uint8_t register_nu while (nbytes-- > 0) { char c = uart->read(); if (decode(c)) { + if (nmea.error_response && nmea.sentence_done) { + // Received a valid VNERR. Try to resend after the timeout length + break; + } return; } } @@ -355,6 +375,7 @@ bool AP_ExternalAHRS_VectorNav::decode(char c) nmea.checksum = 0; nmea.term_is_checksum = false; nmea.sentence_done = false; + nmea.error_response = false; return false; } @@ -370,65 +391,83 @@ bool AP_ExternalAHRS_VectorNav::decode(char c) } // decode the most recently consumed term -// returns true if new sentence has just passed checksum test and is validated +// returns true if new term is valid bool AP_ExternalAHRS_VectorNav::decode_latest_term() { + // Check the first two terms (In most cases header + reg number) that they match the sent + // message. If not, the response is invalid. switch (nmea.term_number) { case 0: - if (strcmp(nmea.term, "VNRRG") != 0) { + if (strncmp(nmea.term, "VNERR", nmea.term_offset) == 0) { + nmea.error_response = true; // Message will be printed on next term + } else if (strncmp(nmea.term, message_to_send, nmea.term_offset) != 0) { return false; } - break; - - case 1: - if (nmea.register_number != strtoul(nmea.term, nullptr, 10)) { + return true; + case 1: + if (nmea.error_response) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "VectorNav received VNERR code: %s", nmea.term); + } else if (strlen(message_to_send) > 6 && + strncmp(nmea.term, &message_to_send[6], nmea.term_offset) != 0) { // Start after "VNXXX," return false; } - break; - - case 2: - strncpy(model_name, nmea.term, sizeof(model_name)); - break; - + return true; + case 2: + if (strncmp(nmea.term, "VN-", 3) == 0) { + // This term is the model number + strncpy(model_name, nmea.term, sizeof(model_name)); + } + return true; default: - return false; + return true; } - return true; } -void AP_ExternalAHRS_VectorNav::update_thread() -{ +void AP_ExternalAHRS_VectorNav::initialize() { // Open port in the thread uart->begin(baudrate, 1024, 512); - // Reset and wait for module to reboot - // VN_100 takes 1.25 seconds - //nmea_printf(uart, "$VNRST"); - //hal.scheduler->delay(3000); + // Pause asynchronous communications to simplify packet finding + run_command("VNASY,0"); - // Stop NMEA Async Outputs (this UART only) - nmea_printf(uart, "$VNWRG,6,0"); + // Stop ASCII async outputs for both UARTs. If only active UART is disabled, we get a baudrate + // overflow on the other UART when configuring binary outputs (reg 75 and 76) to both UARTs + run_command("VNWRG,06,0,1"); + run_command("VNWRG,06,0,2"); - // Detect version // Read Model Number Register, ID 1 - wait_register_responce(1); + run_command("VNRRG,01"); // Setup for messages respective model types (on both UARTs) - if (strncmp(model_name, "VN-100", 6) == 0) { - // VN-100 - type = TYPE::VN_100; - - // This assumes unit is still configured at its default rate of 800hz - nmea_printf(uart, "$VNWRG,75,3,%u,14,073E,0004", unsigned(800/get_rate())); + if (strncmp(model_name, "VN-1", 4) == 0) { + // VN-1X0 + type = TYPE::VN_AHRS; + // These assumes unit is still configured at its default rate of 800hz + run_command("VNWRG,75,3,%u,01,0721", unsigned(800 / get_rate())); + run_command("VNWRG,76,3,16,11,0001,0106"); } else { - // Default to Setup for VN-300 series - // This assumes unit is still configured at its default rate of 400hz - nmea_printf(uart, "$VNWRG,75,3,%u,34,072E,0106,0612", unsigned(400/get_rate())); - nmea_printf(uart, "$VNWRG,76,3,80,4E,0002,0010,20B8,0018"); + // Default to setup for sensors other than VN-100 or VN-110 + // This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz for others + uint16_t imu_rate = 800; // Default for everything but VN-300 + if (strncmp(model_name, "VN-300", 6) == 0) { + imu_rate = 400; + } + if (strncmp(model_name, "VN-3", 4) == 0) { + has_dual_gnss = true; + } + run_command("VNWRG,75,3,%u,01,0721", unsigned(imu_rate / get_rate())); + run_command("VNWRG,76,3,%u,31,0001,0106,0613", unsigned(imu_rate / 50)); + run_command("VNWRG,77,3,%u,49,0003,26B8,0018", unsigned(imu_rate / 5)); } + // Resume asynchronous communications + run_command("VNASY,1"); setup_complete = true; +} + +void AP_ExternalAHRS_VectorNav::update_thread() { + initialize(); while (true) { if (!check_uart()) { hal.scheduler->delay(1); @@ -444,129 +483,48 @@ const char* AP_ExternalAHRS_VectorNav::get_name() const return nullptr; } -/* - process packet type 1 - */ -void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) -{ - const struct VN_packet1 &pkt1 = *(struct VN_packet1 *)b; - const struct VN_packet2 &pkt2 = *last_pkt2; - - last_pkt1_ms = AP_HAL::millis(); - *last_pkt1 = pkt1; - - const bool use_uncomp = option_is_set(AP_ExternalAHRS::OPTIONS::VN_UNCOMP_IMU); - - { - WITH_SEMAPHORE(state.sem); - if (use_uncomp) { - state.accel = Vector3f{pkt1.uncompAccel[0], pkt1.uncompAccel[1], pkt1.uncompAccel[2]}; - state.gyro = Vector3f{pkt1.uncompAngRate[0], pkt1.uncompAngRate[1], pkt1.uncompAngRate[2]}; - } else { - state.accel = Vector3f{pkt1.accel[0], pkt1.accel[1], pkt1.accel[2]}; - state.gyro = Vector3f{pkt1.gyro[0], pkt1.gyro[1], pkt1.gyro[2]}; - } - - state.quat = Quaternion{pkt1.quaternion[3], pkt1.quaternion[0], pkt1.quaternion[1], pkt1.quaternion[2]}; - state.have_quaternion = true; - - state.velocity = Vector3f{pkt1.velNED[0], pkt1.velNED[1], pkt1.velNED[2]}; - state.have_velocity = true; - - state.location = Location{int32_t(pkt1.positionLLA[0] * 1.0e7), - int32_t(pkt1.positionLLA[1] * 1.0e7), - int32_t(pkt1.positionLLA[2] * 1.0e2), - Location::AltFrame::ABSOLUTE}; - state.last_location_update_us = AP_HAL::micros(); - state.have_location = true; - } - -#if AP_BARO_EXTERNALAHRS_ENABLED - { - AP_ExternalAHRS::baro_data_message_t baro; - baro.instance = 0; - baro.pressure_pa = pkt1.pressure*1e3; - baro.temperature = pkt2.temp; +// Input data struct for EAHA logging message, used by both AHRS mode and INS mode +struct AP_ExternalAHRS_VectorNav::VNAT { + uint64_t timeUs; + float quat[4]; + float ypr[3]; + float yprU[3]; +}; - AP::baro().handle_external(baro); - } -#endif -#if AP_COMPASS_EXTERNALAHRS_ENABLED - { - AP_ExternalAHRS::mag_data_message_t mag; - mag.field = Vector3f{pkt1.mag[0], pkt1.mag[1], pkt1.mag[2]}; - mag.field *= 1000; // to mGauss +void AP_ExternalAHRS_VectorNav::write_vnat(const VNAT& data_to_log) const { - AP::compass().handle_external(mag); - } +#if HAL_LOGGING_ENABLED + // @LoggerMessage: VNAT + // @Description: VectorNav Attitude data + // @Field: TimeUS: Time since system startup + // @Field: Q1: Attitude quaternion 1 + // @Field: Q2: Attitude quaternion 2 + // @Field: Q3: Attitude quaternion 3 + // @Field: Q4: Attitude quaternion 4 + // @Field: Yaw: Yaw + // @Field: Pitch: Pitch + // @Field: Roll: Roll + // @Field: YU: Yaw unceratainty + // @Field: PU: Pitch uncertainty + // @Field: RU: Roll uncertainty + + AP::logger().WriteStreaming("VNAT", "TimeUS,Q1,Q2,Q3,Q4,Yaw,Pitch,Roll,YU,PU,RU", + "s----dddddd", "F0000000000", + "Qffffffffff", + data_to_log.timeUs, + data_to_log.quat[0], data_to_log.quat[1], data_to_log.quat[2], data_to_log.quat[3], + data_to_log.ypr[0], data_to_log.ypr[1], data_to_log.ypr[2], + data_to_log.yprU[0], data_to_log.yprU[1], data_to_log.yprU[2]); #endif - - { - AP_ExternalAHRS::ins_data_message_t ins; - - ins.accel = state.accel; - ins.gyro = state.gyro; - ins.temperature = pkt2.temp; - - AP::ins().handle_external(ins); - } } -/* - process packet type 2 - */ -void AP_ExternalAHRS_VectorNav::process_packet2(const uint8_t *b) -{ - const struct VN_packet2 &pkt2 = *(struct VN_packet2 *)b; - const struct VN_packet1 &pkt1 = *last_pkt1; - - last_pkt2_ms = AP_HAL::millis(); - *last_pkt2 = pkt2; - - AP_ExternalAHRS::gps_data_message_t gps; - - // get ToW in milliseconds - gps.gps_week = pkt2.timeGPS / (AP_MSEC_PER_WEEK * 1000000ULL); - gps.ms_tow = (pkt2.timeGPS / 1000000ULL) % (60*60*24*7*1000ULL); - gps.fix_type = pkt2.GPS1Fix; - gps.satellites_in_view = pkt2.numGPS1Sats; - - gps.horizontal_pos_accuracy = pkt1.posU; - gps.vertical_pos_accuracy = pkt1.posU; - gps.horizontal_vel_accuracy = pkt1.velU; - - gps.hdop = pkt2.GPS1DOP[4]; - gps.vdop = pkt2.GPS1DOP[3]; - gps.latitude = pkt2.GPS1posLLA[0] * 1.0e7; - gps.longitude = pkt2.GPS1posLLA[1] * 1.0e7; - gps.msl_altitude = pkt2.GPS1posLLA[2] * 1.0e2; - - gps.ned_vel_north = pkt2.GPS1velNED[0]; - gps.ned_vel_east = pkt2.GPS1velNED[1]; - gps.ned_vel_down = pkt2.GPS1velNED[2]; - - if (gps.fix_type >= 3 && !state.have_origin) { - WITH_SEMAPHORE(state.sem); - state.origin = Location{int32_t(pkt2.GPS1posLLA[0] * 1.0e7), - int32_t(pkt2.GPS1posLLA[1] * 1.0e7), - int32_t(pkt2.GPS1posLLA[2] * 1.0e2), - Location::AltFrame::ABSOLUTE}; - state.have_origin = true; - } - uint8_t instance; - if (AP::gps().get_first_external_instance(instance)) { - AP::gps().handle_external(gps, instance); - } -} -/* - process VN-100 packet type 1 - */ -void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) +// process INS mode INS packet +void AP_ExternalAHRS_VectorNav::process_imu_packet(const uint8_t *b) { - const struct VN_100_packet1 &pkt = *(struct VN_100_packet1 *)b; + const struct VN_IMU_packet &pkt = *(struct VN_IMU_packet *)b; last_pkt1_ms = AP_HAL::millis(); @@ -581,16 +539,13 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) state.accel = Vector3f{pkt.accel[0], pkt.accel[1], pkt.accel[2]}; state.gyro = Vector3f{pkt.gyro[0], pkt.gyro[1], pkt.gyro[2]}; } - - state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]}; - state.have_quaternion = true; } #if AP_BARO_EXTERNALAHRS_ENABLED { AP_ExternalAHRS::baro_data_message_t baro; baro.instance = 0; - baro.pressure_pa = pkt.pressure*1e3; + baro.pressure_pa = pkt.pressure * 1e3; baro.temperature = pkt.temp; AP::baro().handle_external(baro); @@ -600,11 +555,7 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) #if AP_COMPASS_EXTERNALAHRS_ENABLED { AP_ExternalAHRS::mag_data_message_t mag; - if (use_uncomp) { - mag.field = Vector3f{pkt.uncompMag[0], pkt.uncompMag[1], pkt.uncompMag[2]}; - } else { - mag.field = Vector3f{pkt.mag[0], pkt.mag[1], pkt.mag[2]}; - } + mag.field = Vector3f{pkt.mag[0], pkt.mag[1], pkt.mag[2]}; mag.field *= 1000; // to mGauss AP::compass().handle_external(mag); @@ -622,8 +573,8 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) } #if HAL_LOGGING_ENABLED - // @LoggerMessage: EAH3 - // @Description: External AHRS data + // @LoggerMessage: VNIM + // @Description: VectorNav IMU data // @Field: TimeUS: Time since system startup // @Field: Temp: Temprature // @Field: Pres: Pressure @@ -636,25 +587,131 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) // @Field: GX: Rotation rate X-axis // @Field: GY: Rotation rate Y-axis // @Field: GZ: Rotation rate Z-axis - // @Field: Q1: Attitude quaternion 1 - // @Field: Q2: Attitude quaternion 2 - // @Field: Q3: Attitude quaternion 3 - // @Field: Q4: Attitude quaternion 4 - AP::logger().WriteStreaming("EAH3", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ,Q1,Q2,Q3,Q4", - "sdPGGGoooEEE----", "F000000000000000", - "Qfffffffffffffff", + AP::logger().WriteStreaming("VNIM", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ", + "sdPGGGoooEEE", "F00000000000", + "Qfffffffffff", AP_HAL::micros64(), pkt.temp, pkt.pressure*1e3, - use_uncomp ? pkt.uncompMag[0] : pkt.mag[0], - use_uncomp ? pkt.uncompMag[1] : pkt.mag[1], - use_uncomp ? pkt.uncompMag[2] : pkt.mag[2], + pkt.mag[0], pkt.mag[1], pkt.mag[2], state.accel[0], state.accel[1], state.accel[2], state.gyro[0], state.gyro[1], state.gyro[2], state.quat[0], state.quat[1], state.quat[2], state.quat[3]); #endif // HAL_LOGGING_ENABLED } +// process AHRS mode AHRS packet +void AP_ExternalAHRS_VectorNav::process_ahrs_ekf_packet(const uint8_t *b) { + const struct VN_AHRS_ekf_packet &pkt = *(struct VN_AHRS_ekf_packet *)b; + + last_pkt2_ms = AP_HAL::millis(); + + state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]}; + state.have_quaternion = true; + +#if HAL_LOGGING_ENABLED + VNAT data_to_log; + data_to_log.timeUs = AP_HAL::micros64(); + memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion)); + memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr)); + memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU)); + + write_vnat(data_to_log); +#endif // HAL_LOGGING_ENABLED +} + +// process INS mode EKF packet +void AP_ExternalAHRS_VectorNav::process_ins_ekf_packet(const uint8_t *b) { + const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)b; + + last_pkt2_ms = AP_HAL::millis(); + *latest_ins_ekf_packet = pkt; + + state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]}; + state.have_quaternion = true; + + state.velocity = Vector3f{pkt.velNed[0], pkt.velNed[1], pkt.velNed[2]}; + state.have_velocity = true; + + state.location = Location{int32_t(pkt.posLla[0] * 1.0e7), int32_t(pkt.posLla[1] * 1.0e7), int32_t(pkt.posLla[2] * 1.0e2), Location::AltFrame::ABSOLUTE}; + state.last_location_update_us = AP_HAL::micros(); + state.have_location = true; + +#if HAL_LOGGING_ENABLED + VNAT data_to_log; + auto now = AP_HAL::micros64(); + data_to_log.timeUs = now; + memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion)); + memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr)); + memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU)); + write_vnat(data_to_log); + + // @LoggerMessage: VNKF + // @Description: VectorNav INS Kalman Filter data + // @Field: TimeUS: Time since system startup + // @Field: InsStatus: VectorNav INS health status + // @Field: Lat: Latitude + // @Field: Lon: Longitude + // @Field: Alt: Altitude + // @Field: VelN: Velocity Northing + // @Field: VelE: Velocity Easting + // @Field: VelD: Velocity Downing + // @Field: PosU: Filter estimated position uncertainty + // @Field: VelU: Filter estimated Velocity uncertainty + + AP::logger().WriteStreaming("VNKF", "TimeUS,InsStatus,Lat,Lon,Alt,VelN,VelE,VelD,PosU,VelU", + "s-ddmnnndn", "F000000000", + "QHdddfffff", + now, + pkt.insStatus, + pkt.posLla[0], pkt.posLla[1], pkt.posLla[2], + pkt.velNed[0], pkt.velNed[1], pkt.velNed[2], + pkt.posU, pkt.velU); +#endif // HAL_LOGGING_ENABLED + +} + +// process INS mode GNSS packet +void AP_ExternalAHRS_VectorNav::process_ins_gnss_packet(const uint8_t *b) { + const struct VN_INS_gnss_packet &pkt = *(struct VN_INS_gnss_packet *)b; + AP_ExternalAHRS::gps_data_message_t gps; + + + last_pkt3_ms = AP_HAL::millis(); + *latest_ins_gnss_packet = pkt; + + // get ToW in milliseconds + gps.gps_week = pkt.timeGps / (AP_MSEC_PER_WEEK * 1000000ULL); + gps.ms_tow = (pkt.timeGps / 1000000ULL) % (60 * 60 * 24 * 7 * 1000ULL); + gps.fix_type = AP_GPS_FixType(pkt.fix1); + gps.satellites_in_view = pkt.numSats1; + + gps.horizontal_pos_accuracy = pkt.posU1[0]; + gps.vertical_pos_accuracy = pkt.posU1[2]; + gps.horizontal_vel_accuracy = pkt.velU1; + + gps.hdop = pkt.dop1[4]; + gps.vdop = pkt.dop1[3]; + + gps.latitude = pkt.posLla1[0] * 1.0e7; + gps.longitude = pkt.posLla1[1] * 1.0e7; + gps.msl_altitude = pkt.posLla1[2] * 1.0e2; + + gps.ned_vel_north = pkt.velNed1[0]; + gps.ned_vel_east = pkt.velNed1[1]; + gps.ned_vel_down = pkt.velNed1[2]; + + if (!state.have_origin && gps.fix_type >= AP_GPS_FixType::FIX_3D) { + WITH_SEMAPHORE(state.sem); + state.origin = Location{int32_t(pkt.posLla1[0] * 1.0e7), int32_t(pkt.posLla1[1] * 1.0e7), + int32_t(pkt.posLla1[2] * 1.0e2), Location::AltFrame::ABSOLUTE}; + state.have_origin = true; + } + uint8_t instance; + if (AP::gps().get_first_external_instance(instance)) { + AP::gps().handle_external(gps, instance); + } +} // get serial port number for the uart int8_t AP_ExternalAHRS_VectorNav::get_port(void) const @@ -669,10 +726,7 @@ int8_t AP_ExternalAHRS_VectorNav::get_port(void) const bool AP_ExternalAHRS_VectorNav::healthy(void) const { const uint32_t now = AP_HAL::millis(); - if (type == TYPE::VN_100) { - return (now - last_pkt1_ms < 40); - } - return (now - last_pkt1_ms < 40 && now - last_pkt2_ms < 500); + return (now - last_pkt1_ms < 40) && (now - last_pkt2_ms < 500) && (type == TYPE::VN_AHRS ? true: now - last_pkt3_ms < 1000); } bool AP_ExternalAHRS_VectorNav::initialised(void) const @@ -680,10 +734,7 @@ bool AP_ExternalAHRS_VectorNav::initialised(void) const if (!setup_complete) { return false; } - if (type == TYPE::VN_100) { - return last_pkt1_ms != 0; - } - return last_pkt1_ms != 0 && last_pkt2_ms != 0; + return last_pkt1_ms != UINT32_MAX && last_pkt2_ms != UINT32_MAX && (type == TYPE::VN_AHRS ? true : last_pkt3_ms != UINT32_MAX); } bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const @@ -696,12 +747,12 @@ bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav unhealthy"); return false; } - if (type == TYPE::VN_300) { - if (last_pkt2->GPS1Fix < 3) { + if (type == TYPE::VN_INS) { + if (latest_ins_gnss_packet->fix1 < 3) { hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS1 lock"); return false; } - if (last_pkt2->GPS2Fix < 3) { + if (has_dual_gnss && (latest_ins_gnss_packet->fix2 < 3)) { hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS2 lock"); return false; } @@ -716,86 +767,36 @@ bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const { memset(&status, 0, sizeof(status)); - if (type == TYPE::VN_300) { - if (last_pkt1 && last_pkt2) { - status.flags.initalized = true; - } - if (healthy() && last_pkt2) { + status.flags.initalized = initialised(); + if (healthy()) { + if (type == TYPE::VN_AHRS) { status.flags.attitude = true; - status.flags.vert_vel = true; - status.flags.vert_pos = true; - - const struct VN_packet2 &pkt2 = *last_pkt2; - if (pkt2.GPS1Fix >= 3) { - status.flags.horiz_vel = true; - status.flags.horiz_pos_rel = true; - status.flags.horiz_pos_abs = true; + } else { + status.flags.attitude = true; + if (latest_ins_ekf_packet) { + status.flags.vert_vel = true; + status.flags.vert_pos = true; + + status.flags.horiz_vel = true; + status.flags.horiz_pos_rel = true; + status.flags.horiz_pos_abs = true; status.flags.pred_horiz_pos_rel = true; status.flags.pred_horiz_pos_abs = true; - status.flags.using_gps = true; + status.flags.using_gps = true; } } - } else { - status.flags.initalized = initialised(); - if (healthy()) { - status.flags.attitude = true; - } } } -// send an EKF_STATUS message to GCS -void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const +// get variances +bool AP_ExternalAHRS_VectorNav::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { - if (!last_pkt1) { - return; - } - // prepare flags - uint16_t flags = 0; - nav_filter_status filterStatus; - get_filter_status(filterStatus); - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - if (!filterStatus.flags.initalized) { - flags |= EKF_UNINITIALIZED; - } - - // send message - const struct VN_packet1 &pkt1 = *(struct VN_packet1 *)last_pkt1; - const float vel_gate = 5; - const float pos_gate = 5; - const float hgt_gate = 5; - const float mag_var = 0; - 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); + const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)latest_ins_ekf_packet; + velVar = pkt.velU * vel_gate_scale; + posVar = pkt.posU * pos_gate_scale; + hgtVar = pkt.posU * hgt_gate_scale; + tasVar = 0; + return true; } #endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 3ce1fe7f5e2d5d..c6665bb59bc48c 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -37,7 +37,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(class GCS_MAVLINK &link) const override; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override; // check for new data void update() override { @@ -47,6 +47,11 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { // Get model/type name const char* get_name() const override; +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } private: AP_HAL::UARTDriver *uart; int8_t port_num; @@ -56,42 +61,53 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { void update_thread(); bool check_uart(); - void process_packet1(const uint8_t *b); - void process_packet2(const uint8_t *b); - void process_packet_VN_100(const uint8_t *b); - void wait_register_responce(const uint8_t register_num); + void initialize(); + + void run_command(const char *fmt, ...); + + struct VNAT; + void write_vnat(const VNAT& data_to_log) const; + void process_imu_packet(const uint8_t *b); + void process_ahrs_ekf_packet(const uint8_t *b); + void process_ins_ekf_packet(const uint8_t *b); + void process_ins_gnss_packet(const uint8_t *b); + uint8_t *pktbuf; uint16_t pktoffset; uint16_t bufsize; - struct VN_packet1 *last_pkt1; - struct VN_packet2 *last_pkt2; + struct VN_imu_packet *latest_imu_packet; + struct VN_INS_ekf_packet *latest_ins_ekf_packet; + struct VN_INS_gnss_packet *latest_ins_gnss_packet; uint32_t last_pkt1_ms; uint32_t last_pkt2_ms; + uint32_t last_pkt3_ms; enum class TYPE { - VN_300, - VN_100, + VN_INS, // Full INS mode, requiring GNSS. Used by VN-2X0 and VN-3X0 + VN_AHRS, // IMU-only mode, used by VN-1X0 } type; - char model_name[25]; + bool has_dual_gnss = false; + + char model_name[20]; + char message_to_send[50]; // NMEA parsing for setup bool decode(char c); bool decode_latest_term(); struct NMEA_parser { - char term[25]; // buffer for the current term within the current sentence + char term[20]; // buffer for the current term within the current sentence uint8_t term_offset; // offset within the _term buffer where the next character should be placed uint8_t term_number; // term index within the current sentence uint8_t checksum; // checksum accumulator 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 - uint8_t register_number; // VectorNAV register number were reading + bool error_response; // true if received a VNERR response } nmea; - }; #endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.cpp index 94cf8c41b7d2b8..4357738da7cf6b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.cpp @@ -23,8 +23,8 @@ AP_ExternalAHRS_backend::AP_ExternalAHRS_backend(AP_ExternalAHRS *_frontend, AP_ExternalAHRS::state_t &_state) : - frontend(*_frontend), - state(_state) + state(_state), + frontend(*_frontend) {} diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h index ed987a01ced3aa..8ee9af82ce5944 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h @@ -41,13 +41,16 @@ 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(class GCS_MAVLINK &link) const {} + virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { return false; } // Check for new data. // This is used when there's not a separate thread for EAHRS. // This can also copy interim state protected by locking. virtual void update() = 0; + // Return the number of GPS sensors sharing data to AP_GPS. + virtual uint8_t num_gps_sensors(void) const = 0; + protected: AP_ExternalAHRS::state_t &state; uint16_t get_rate(void) const; @@ -70,6 +73,13 @@ class AP_ExternalAHRS_backend { */ bool in_fly_forward(void) const; + /* + scale factors for get_variances() to return normalised values from SI units + */ + const float vel_gate_scale = 0.2; + const float pos_gate_scale = 0.2; + const float hgt_gate_scale = 0.2; + private: AP_ExternalAHRS &frontend; }; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h index 75e8e5228021bb..650f605b0a9f22 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h @@ -26,6 +26,6 @@ #define AP_EXTERNAL_AHRS_VECTORNAV_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED #endif -#ifndef AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED -#define AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED +#ifndef AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED +#define AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.cpp b/libraries/AP_ExternalControl/AP_ExternalControl.cpp index e0e92f0a299113..92a97f18b75727 100644 --- a/libraries/AP_ExternalControl/AP_ExternalControl.cpp +++ b/libraries/AP_ExternalControl/AP_ExternalControl.cpp @@ -5,6 +5,16 @@ // singleton instance AP_ExternalControl *AP_ExternalControl::singleton; +bool AP_ExternalControl::arm(AP_Arming::Method method, bool do_arming_checks) +{ + return AP::arming().arm(method, do_arming_checks); +} + +bool AP_ExternalControl::disarm(AP_Arming::Method method, bool do_disarm_checks) +{ + return AP::arming().disarm(method, do_disarm_checks); +} + AP_ExternalControl::AP_ExternalControl() { singleton = this; diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.h b/libraries/AP_ExternalControl/AP_ExternalControl.h index 34228e2b7ab4ff..57670008f48968 100644 --- a/libraries/AP_ExternalControl/AP_ExternalControl.h +++ b/libraries/AP_ExternalControl/AP_ExternalControl.h @@ -8,6 +8,7 @@ #if AP_EXTERNAL_CONTROL_ENABLED +#include #include #include @@ -32,6 +33,16 @@ class AP_ExternalControl return false; } + /* + Arm the vehicle + */ + virtual bool arm(AP_Arming::Method method, bool do_arming_checks) WARN_IF_UNUSED; + + /* + Disarm the vehicle + */ + virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks) WARN_IF_UNUSED; + static AP_ExternalControl *get_singleton(void) WARN_IF_UNUSED { return singleton; } diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp index af59ca8110a180..9bbc3e2e7d5f38 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp @@ -134,7 +134,7 @@ void AP_FETtecOneWire::init() } // we have a uart and the desired ESC combination id valid, allocate some memory: - _escs = new ESC[_esc_count]; + _escs = NEW_NOTHROW ESC[_esc_count]; if (_escs == nullptr) { return; } diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index b7642da19cfcf4..240e95e41de9c6 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -16,6 +16,9 @@ #include "AP_Filesystem.h" #include "AP_Filesystem_config.h" + +#if AP_FILESYSTEM_FILE_READING_ENABLED + #include #include #include @@ -202,13 +205,15 @@ AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname) (strlen(pathname) == 1 && pathname[0] == '/')) { virtual_dirent.backend_ofs = 0; virtual_dirent.d_off = 0; +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE virtual_dirent.de.d_type = DT_DIR; +#endif } else { virtual_dirent.backend_ofs = 255; } const Backend &backend = backend_by_path(pathname); - DirHandle *h = new DirHandle; + DirHandle *h = NEW_NOTHROW DirHandle; if (!h) { return nullptr; } @@ -306,7 +311,9 @@ void AP_Filesystem::unmount(void) } /* - load a file to memory as a single chunk. Use only for small files + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. */ FileData *AP_Filesystem::load_file(const char *filename) { @@ -319,19 +326,31 @@ bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd) { const Backend &backend = backend_by_fd(fd); + // we will need to seek back to the right location at the end + auto offset_start = backend.fs.lseek(fd, 0, SEEK_CUR); + if (offset_start < 0) { + return false; + } + + auto n = backend.fs.read(fd, buf, buflen); + if (n <= 0) { + return false; + } + uint8_t i = 0; - for (; i= 0 && fileno <= 2) { return true; @@ -706,7 +706,7 @@ void *AP_Filesystem_FATFS::opendir(const char *pathdir) CHECK_REMOUNT_NULL(); debug("Opendir %s", pathdir); - struct DIR_Wrapper *ret = new DIR_Wrapper; + struct DIR_Wrapper *ret = NEW_NOTHROW DIR_Wrapper; if (!ret) { return nullptr; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp b/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp index cba03addcdf75b..6754170703a763 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp @@ -30,7 +30,11 @@ #include extern const AP_HAL::HAL& hal; + +// QURT HAL already has a declaration of errno in errno.h +#if CONFIG_HAL_BOARD != HAL_BOARD_QURT extern int errno; +#endif #define IDLE_TIMEOUT_MS 30000 @@ -70,7 +74,7 @@ int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolut r.num_items = get_num_items(r.mtype); if (!readonly) { // setup for upload - r.writebuf = new ExpandingString(); + r.writebuf = NEW_NOTHROW ExpandingString(); } else { r.writebuf = nullptr; } @@ -464,7 +468,7 @@ bool AP_Filesystem_Mission::finish_upload_fence(const struct header &hdr, const // passing nullptr and 0 items through to Polyfence loader is // absolutely OK: if (hdr.num_items != 0) { - new_items = new AC_PolyFenceItem[hdr.num_items]; + new_items = NEW_NOTHROW AC_PolyFenceItem[hdr.num_items]; if (new_items == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Out of memory for upload"); goto OUT; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp index d29efe8f9df055..d79f2cd7b3a09a 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp @@ -29,7 +29,11 @@ #define PACKED_NAME "param.pck" extern const AP_HAL::HAL& hal; + +// QURT HAL already has a declaration of errno in errno.h +#if CONFIG_HAL_BOARD != HAL_BOARD_QURT extern int errno; +#endif int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_path) { @@ -50,7 +54,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_ } struct rfile &r = file[idx]; if (read_only) { - r.cursors = new cursor[num_cursors]; + r.cursors = NEW_NOTHROW cursor[num_cursors]; if (r.cursors == nullptr) { errno = ENOMEM; return -1; @@ -66,7 +70,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_ r.writebuf = nullptr; if (!read_only) { // setup for upload - r.writebuf = new ExpandingString(); + r.writebuf = NEW_NOTHROW ExpandingString(); if (r.writebuf == nullptr) { close(idx); errno = ENOMEM; diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index 930b4f62682c78..f481d872558e5c 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -192,11 +192,14 @@ struct dirent *AP_Filesystem_ROMFS::readdir(void *dirp) const char* slash = strchr(name, '/'); if (slash == nullptr) { // File +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE dir[idx].de.d_type = DT_REG; - +#endif } else { // Directory +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE dir[idx].de.d_type = DT_DIR; +#endif // Add null termination after directory name const size_t index = slash - name; @@ -239,15 +242,17 @@ bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_s } /* - load a full file. Use delete to free the data - we override this in ROMFS to avoid taking twice the memory + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. Overridden in ROMFS to avoid taking twice the memory. */ FileData *AP_Filesystem_ROMFS::load_file(const char *filename) { - FileData *fd = new FileData(this); + FileData *fd = NEW_NOTHROW FileData(this); if (!fd) { return nullptr; } + // AP_ROMFS adds the guaranteed termination so we don't have to. fd->data = AP_ROMFS::find_decompress(filename, fd->length); if (fd->data == nullptr) { delete fd; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp index 9eadd7f607b407..5063267c04a658 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp @@ -83,7 +83,7 @@ int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_pa return -1; } struct rfile &r = file[idx]; - r.str = new ExpandingString; + r.str = NEW_NOTHROW ExpandingString; if (r.str == nullptr) { errno = ENOMEM; return -1; @@ -229,7 +229,7 @@ void *AP_Filesystem_Sys::opendir(const char *pathname) errno = ENOENT; return nullptr; } - DirReadTracker *dtracker = new DirReadTracker; + DirReadTracker *dtracker = NEW_NOTHROW DirReadTracker; if (dtracker == nullptr) { errno = ENOMEM; return nullptr; @@ -244,7 +244,9 @@ struct dirent *AP_Filesystem_Sys::readdir(void *dirp) // we have reached end of list return nullptr; } +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE dtracker->curr_file.d_type = DT_REG; +#endif size_t max_length = ARRAY_SIZE(dtracker->curr_file.d_name); strncpy_noterm(dtracker->curr_file.d_name, sysfs_file_list[dtracker->file_offset].name, max_length); dtracker->file_offset++; diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp index 87fe694d9ec619..db1eb970756e0e 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp @@ -19,7 +19,9 @@ extern const AP_HAL::HAL& hal; /* - load a full file. Use delete to free the data + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. */ FileData *AP_Filesystem_Backend::load_file(const char *filename) { @@ -27,11 +29,12 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename) if (stat(filename, &st) != 0) { return nullptr; } - FileData *fd = new FileData(this); + FileData *fd = NEW_NOTHROW FileData(this); if (fd == nullptr) { return nullptr; } - void *data = malloc(st.st_size); + // add one byte for null termination; ArduPilot's malloc will zero it. + void *data = malloc(st.st_size+1); if (data == nullptr) { delete fd; return nullptr; @@ -49,7 +52,7 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename) return nullptr; } close(d); - fd->length = st.st_size; + fd->length = st.st_size; // length does not include our added termination fd->data = (const uint8_t *)data; return fd; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.h b/libraries/AP_Filesystem/AP_Filesystem_backend.h index 187f9c48c3041d..8cf0fa655a1cf7 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.h +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.h @@ -87,7 +87,9 @@ class AP_Filesystem_Backend { virtual AP_Filesystem_Backend::FormatStatus get_format_status() const { return FormatStatus::NOT_STARTED; } /* - load a full file. Use delete to free the data + Load a file's contents into memory. Returned object must be `delete`d to + free the data. The data is guaranteed to be null-terminated such that it + can be treated as a string. */ virtual FileData *load_file(const char *filename); diff --git a/libraries/AP_Filesystem/AP_Filesystem_config.h b/libraries/AP_Filesystem/AP_Filesystem_config.h index a184051610cc4a..a23b1f2c1b543e 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_config.h +++ b/libraries/AP_Filesystem/AP_Filesystem_config.h @@ -2,8 +2,6 @@ #include -#include - // backends: #ifndef AP_FILESYSTEM_ESP32_ENABLED @@ -14,16 +12,12 @@ #define AP_FILESYSTEM_FATFS_ENABLED HAL_OS_FATFS_IO #endif -#ifndef AP_FILESYSTEM_MISSION_ENABLED -#define AP_FILESYSTEM_MISSION_ENABLED AP_MISSION_ENABLED -#endif - #ifndef AP_FILESYSTEM_PARAM_ENABLED #define AP_FILESYSTEM_PARAM_ENABLED 1 #endif #ifndef AP_FILESYSTEM_POSIX_ENABLED -#define AP_FILESYSTEM_POSIX_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) +#define AP_FILESYSTEM_POSIX_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_QURT) #endif #ifndef AP_FILESYSTEM_ROMFS_ENABLED @@ -34,6 +28,11 @@ #define AP_FILESYSTEM_SYS_ENABLED 1 #endif +#ifndef AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC +// this requires AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR +#define AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC 0 +#endif + // AP_FILESYSTEM_FILE_WRITING_ENABLED is true if you could expect to // be able to open and write a non-virtual file. Notably this // excludes virtual files like SYSFS, and the magic param/mission @@ -47,9 +46,18 @@ // be able to open and read a non-virtual file. Notably this excludes // virtual files like SYSFS, and the magic param/mission upload targets. #ifndef AP_FILESYSTEM_FILE_READING_ENABLED -#define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED) +#define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED || AP_FILESYSTEM_SYS_ENABLED || AP_FILESYSTEM_PARAM_ENABLED) #endif #ifndef AP_FILESYSTEM_SYS_FLASH_ENABLED #define AP_FILESYSTEM_SYS_FLASH_ENABLED CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #endif + +#ifndef AP_FILESYSTEM_HAVE_DIRENT_DTYPE +#define AP_FILESYSTEM_HAVE_DIRENT_DTYPE 1 +#endif + +#ifndef AP_FILESYSTEM_MISSION_ENABLED +#include +#define AP_FILESYSTEM_MISSION_ENABLED AP_MISSION_ENABLED +#endif diff --git a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp index 5a6169053472da..2283933a552fa4 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp @@ -24,20 +24,31 @@ #include #include -#if defined(__APPLE__) +#if defined(__APPLE__) || defined(__OpenBSD__) #include -#else +#elif CONFIG_HAL_BOARD != HAL_BOARD_QURT #include #endif + +#if AP_FILESYSTEM_POSIX_HAVE_UTIME #include +#endif extern const AP_HAL::HAL& hal; /* - map a filename for SITL so operations are relative to the current directory + map a filename so operations are relative to the current directory if needed */ static const char *map_filename(const char *fname) { +#if AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC + // this system needs to add a prefix to the filename, which means + // memory allocation. This is needed for QURT which lacks chdir() + char *fname2 = nullptr; + asprintf(&fname2, "%s/%s", AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR, fname); + return fname2; +#else + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !APM_BUILD_TYPE(APM_BUILD_Replay) // on SITL only allow paths under subdirectory. Users can still // escape with .. if they want to @@ -50,6 +61,14 @@ static const char *map_filename(const char *fname) #endif // on Linux allow original name return fname; +#endif // AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC +} + +static void map_filename_free(const char *fname) +{ +#if AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC + ::free(const_cast(fname)); +#endif } int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_paths) @@ -62,10 +81,18 @@ int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_ if (::stat(fname, &st) == 0 && ((st.st_mode & S_IFMT) != S_IFREG && (st.st_mode & S_IFMT) != S_IFLNK)) { // only allow links and files + if (!allow_absolute_paths) { + map_filename_free(fname); + } return -1; } + // we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage - return ::open(fname, flags | O_CLOEXEC, 0644); + auto ret = ::open(fname, flags | O_CLOEXEC, 0644); + if (!allow_absolute_paths) { + map_filename_free(fname); + } + return ret; } int AP_Filesystem_Posix::close(int fd) @@ -88,8 +115,14 @@ int32_t AP_Filesystem_Posix::write(int fd, const void *buf, uint32_t count) int AP_Filesystem_Posix::fsync(int fd) { +#if AP_FILESYSTEM_POSIX_HAVE_FSYNC FS_CHECK_ALLOWED(-1); return ::fsync(fd); +#else + // we have to pass success here as otherwise it is assumed to be + // failed IO and the caller may close the fd and give up + return 0; +#endif } int32_t AP_Filesystem_Posix::lseek(int fd, int32_t offset, int seek_from) @@ -102,7 +135,9 @@ int AP_Filesystem_Posix::stat(const char *pathname, struct stat *stbuf) { FS_CHECK_ALLOWED(-1); pathname = map_filename(pathname); - return ::stat(pathname, stbuf); + auto ret = ::stat(pathname, stbuf); + map_filename_free(pathname); + return ret; } int AP_Filesystem_Posix::unlink(const char *pathname) @@ -111,10 +146,11 @@ int AP_Filesystem_Posix::unlink(const char *pathname) pathname = map_filename(pathname); // we match the FATFS interface and use unlink // for both files and directories - int ret = ::rmdir(pathname); + int ret = ::rmdir(const_cast(pathname)); if (ret == -1) { ret = ::unlink(pathname); } + map_filename_free(pathname); return ret; } @@ -122,14 +158,18 @@ int AP_Filesystem_Posix::mkdir(const char *pathname) { FS_CHECK_ALLOWED(-1); pathname = map_filename(pathname); - return ::mkdir(pathname, 0775); + auto ret = ::mkdir(const_cast(pathname), 0775); + map_filename_free(pathname); + return ret; } void *AP_Filesystem_Posix::opendir(const char *pathname) { FS_CHECK_ALLOWED(nullptr); pathname = map_filename(pathname); - return (void*)::opendir(pathname); + auto *ret = (void*)::opendir(pathname); + map_filename_free(pathname); + return ret; } struct dirent *AP_Filesystem_Posix::readdir(void *dirp) @@ -149,31 +189,46 @@ int AP_Filesystem_Posix::rename(const char *oldpath, const char *newpath) FS_CHECK_ALLOWED(-1); oldpath = map_filename(oldpath); newpath = map_filename(newpath); - return ::rename(oldpath, newpath); + auto ret = ::rename(oldpath, newpath); + map_filename_free(oldpath); + map_filename_free(newpath); + return ret; } // return free disk space in bytes int64_t AP_Filesystem_Posix::disk_free(const char *path) { +#if AP_FILESYSTEM_POSIX_HAVE_STATFS FS_CHECK_ALLOWED(-1); path = map_filename(path); struct statfs stats; if (::statfs(path, &stats) < 0) { + map_filename_free(path); return -1; } + map_filename_free(path); return (((int64_t)stats.f_bavail) * stats.f_bsize); +#else + return -1; +#endif } // return total disk space in bytes int64_t AP_Filesystem_Posix::disk_space(const char *path) { +#if AP_FILESYSTEM_POSIX_HAVE_STATFS FS_CHECK_ALLOWED(-1); path = map_filename(path); struct statfs stats; if (::statfs(path, &stats) < 0) { + map_filename_free(path); return -1; } + map_filename_free(path); return (((int64_t)stats.f_blocks) * stats.f_bsize); +#else + return -1; +#endif } @@ -182,13 +237,19 @@ int64_t AP_Filesystem_Posix::disk_space(const char *path) */ bool AP_Filesystem_Posix::set_mtime(const char *filename, const uint32_t mtime_sec) { +#if AP_FILESYSTEM_POSIX_HAVE_UTIME FS_CHECK_ALLOWED(false); filename = map_filename(filename); struct utimbuf times {}; times.actime = mtime_sec; times.modtime = mtime_sec; - return utime(filename, ×) == 0; + auto ret = utime(filename, ×) == 0; + map_filename_free(filename); + return ret; +#else + return false; +#endif } #endif // AP_FILESYSTEM_POSIX_ENABLED diff --git a/libraries/AP_Filesystem/AP_Filesystem_posix.h b/libraries/AP_Filesystem/AP_Filesystem_posix.h index e44764213aee45..2e291db70f77db 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_posix.h +++ b/libraries/AP_Filesystem/AP_Filesystem_posix.h @@ -29,6 +29,22 @@ #include #include "AP_Filesystem_backend.h" +#ifndef AP_FILESYSTEM_POSIX_HAVE_UTIME +#define AP_FILESYSTEM_POSIX_HAVE_UTIME 1 +#endif + +#ifndef AP_FILESYSTEM_POSIX_HAVE_FSYNC +#define AP_FILESYSTEM_POSIX_HAVE_FSYNC 1 +#endif + +#ifndef AP_FILESYSTEM_POSIX_HAVE_STATFS +#define AP_FILESYSTEM_POSIX_HAVE_STATFS 1 +#endif + +#ifndef O_CLOEXEC +#define O_CLOEXEC 0 +#endif + class AP_Filesystem_Posix : public AP_Filesystem_Backend { public: diff --git a/libraries/AP_Filesystem/posix_compat.cpp b/libraries/AP_Filesystem/posix_compat.cpp index 6dee4f1653431f..f29e70fe803b66 100644 --- a/libraries/AP_Filesystem/posix_compat.cpp +++ b/libraries/AP_Filesystem/posix_compat.cpp @@ -70,7 +70,7 @@ static int posix_fopen_modes_to_open(const char *mode) APFS_FILE *apfs_fopen(const char *pathname, const char *mode) { - APFS_FILE *f = new APFS_FILE; + APFS_FILE *f = NEW_NOTHROW APFS_FILE; if (!f) { return nullptr; } diff --git a/libraries/AP_Filesystem/posix_compat.h b/libraries/AP_Filesystem/posix_compat.h index 4ccf56b5c5f43e..a7dba7c58e792a 100644 --- a/libraries/AP_Filesystem/posix_compat.h +++ b/libraries/AP_Filesystem/posix_compat.h @@ -58,7 +58,6 @@ 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[L_tmpnam]); #undef stdin #undef stdout @@ -78,6 +77,12 @@ char *tmpnam(char s[L_tmpnam]); #endif #define FILE APFS_FILE + +#ifndef __cplusplus +/* + only redefine posix functions for C code (eg. lua). + for C++ use the AP_Filsystem APIs +*/ #define fopen(p,m) apfs_fopen(p,m) #define fprintf(stream, format, args...) apfs_fprintf(stream, format, ##args) #define fflush(s) apfs_fflush(s) @@ -101,6 +106,7 @@ char *tmpnam(char s[L_tmpnam]); #define remove(pathname) apfs_remove(pathname) int sprintf(char *str, const char *format, ...); #endif +#endif // __cplusplus #ifdef __cplusplus } diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index a93f79d667ce21..8792efd2488988 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -272,27 +272,40 @@ bool AP_Follow::get_target_heading_deg(float &heading) const return true; } -// handle mavlink DISTANCE_SENSOR messages -void AP_Follow::handle_msg(const mavlink_message_t &msg) +// returns true if we should extract information from msg +bool AP_Follow::should_handle_message(const mavlink_message_t &msg) const { // exit immediately if not enabled if (!_enabled) { - return; + return false; } // skip our own messages if (msg.sysid == mavlink_system.sysid) { - return; + return false; } // skip message if not from our target if (_sysid != 0 && msg.sysid != _sysid) { - if (_automatic_sysid) { - // maybe timeout who we were following... - if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) { - _sysid.set(0); - } + return false; + } + + return true; +} + +// handle mavlink DISTANCE_SENSOR messages +void AP_Follow::handle_msg(const mavlink_message_t &msg) +{ + // this method should be called from an "update()" method: + if (_automatic_sysid) { + // maybe timeout who we were following... + if ((_last_location_update_ms == 0) || + (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) { + _sysid.set(0); } + } + + if (!should_handle_message(msg)) { return; } @@ -301,13 +314,31 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) switch (msg.msgid) { case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: { + updated = handle_global_position_int_message(msg); + break; + } + case MAVLINK_MSG_ID_FOLLOW_TARGET: { + updated = handle_follow_target_message(msg); + break; + } + } + + if (updated) { +#if HAL_LOGGING_ENABLED + Log_Write_FOLL(); +#endif + } +} + +bool AP_Follow::handle_global_position_int_message(const mavlink_message_t &msg) +{ // decode message mavlink_global_position_int_t packet; mavlink_msg_global_position_int_decode(&msg, &packet); // ignore message if lat and lon are (exactly) zero if ((packet.lat == 0 && packet.lon == 0)) { - return; + return false; } _target_location.lat = packet.lat; @@ -337,33 +368,34 @@ 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: { + return true; +} + +bool AP_Follow::handle_follow_target_message(const mavlink_message_t &msg) +{ // 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; + return false; } // require at least position if ((packet.est_capabilities & (1<<0)) == 0) { - return; + return false; } 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); + new_loc.set_alt_m(packet.alt, 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; + return false; } _target_location = new_loc; @@ -391,13 +423,14 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) _sysid.set(msg.sysid); _automatic_sysid = true; } - updated = true; - break; - } - } - if (updated) { + return true; +} + +// write out an onboard-log message to help diagnose follow problems: #if HAL_LOGGING_ENABLED +void AP_Follow::Log_Write_FOLL() +{ // get estimated location and velocity Location loc_estimate{}; Vector3f vel_estimate; @@ -432,9 +465,8 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) loc_estimate.lng, loc_estimate.alt ); -#endif - } } +#endif // HAL_LOGGING_ENABLED // get velocity estimate in m/s in NED frame using dt since last update bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const @@ -456,13 +488,13 @@ void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned) 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.set(rotate_vector(-dist_vec_ned, -target_heading_deg)); - gcs().send_text(MAV_SEVERITY_INFO, "Relative follow offset loaded"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Relative follow offset loaded"); } else { // initialise offset in NED frame _offset.set(-dist_vec_ned); // ensure offset_type used matches frame of offsets saved _offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED); - gcs().send_text(MAV_SEVERITY_INFO, "N-E-D follow offset loaded"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "N-E-D follow offset loaded"); } } @@ -492,9 +524,10 @@ bool AP_Follow::get_offsets_ned(Vector3f &offset) const Vector3f AP_Follow::rotate_vector(const Vector3f &vec, float angle_deg) const { // rotate roll, pitch input from north facing to vehicle's perspective - const float cos_yaw = cosf(radians(angle_deg)); - const float sin_yaw = sinf(radians(angle_deg)); - return Vector3f((vec.x * cos_yaw) - (vec.y * sin_yaw), (vec.y * cos_yaw) + (vec.x * sin_yaw), vec.z); + Vector3f ret = vec; + ret.xy().rotate(radians(angle_deg)); + + return ret; } // set recorded distance and bearing to target to zero diff --git a/libraries/AP_Follow/AP_Follow.h b/libraries/AP_Follow/AP_Follow.h index 5918215352a7ca..48c43fc9ff4706 100644 --- a/libraries/AP_Follow/AP_Follow.h +++ b/libraries/AP_Follow/AP_Follow.h @@ -118,6 +118,9 @@ class AP_Follow private: static AP_Follow *_singleton; + // returns true if we should extract information from msg + bool should_handle_message(const mavlink_message_t &msg) const; + // get velocity estimate in m/s in NED frame using dt since last update bool get_velocity_ned(Vector3f &vel_ned, float dt) const; @@ -133,6 +136,13 @@ class AP_Follow // set recorded distance and bearing to target to zero void clear_dist_and_bearing_to_target(); + // handle various mavlink messages supplying position: + bool handle_global_position_int_message(const mavlink_message_t &msg); + bool handle_follow_target_message(const mavlink_message_t &msg); + + // write out an onboard-log message to help diagnose follow problems: + void Log_Write_FOLL(); + // parameters AP_Int8 _enabled; // 1 if this subsystem is enabled AP_Int16 _sysid; // target's mavlink system id (0 to use first sysid seen) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp index 113e717ca108eb..e78b576c27c45f 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp @@ -5,6 +5,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -44,49 +45,15 @@ void AP_Frsky_Backend::loop(void) } } -/* - * get vertical speed from ahrs, if not available fall back to baro climbrate, units is m/s - * for FrSky D and SPort protocols - */ -float AP_Frsky_Backend::get_vspeed_ms(void) -{ - - { - // release semaphore as soon as possible - AP_AHRS &_ahrs = AP::ahrs(); - Vector3f v; - WITH_SEMAPHORE(_ahrs.get_semaphore()); - if (_ahrs.get_velocity_NED(v)) { - return -v.z; - } - } - - auto &_baro = AP::baro(); - WITH_SEMAPHORE(_baro.get_semaphore()); - return _baro.get_climb_rate(); -} - /* * prepare altitude between vehicle and home location data * for FrSky D and SPort protocols */ void AP_Frsky_Backend::calc_nav_alt(void) { - _SPort_data.vario_vspd = (int32_t)(get_vspeed_ms()*100); //convert to cm/s - - Location loc; - float current_height = 0; // in centimeters above home - - AP_AHRS &_ahrs = AP::ahrs(); - WITH_SEMAPHORE(_ahrs.get_semaphore()); - if (_ahrs.get_location(loc)) { - current_height = loc.alt*0.01f; - if (!loc.relative_alt) { - // loc.alt has home altitude added, remove it - current_height -= _ahrs.get_home().alt*0.01f; - } - } + _SPort_data.vario_vspd = (int32_t)(AP_RCTelemetry::get_vspeed_ms()*100); //convert to cm/s + float current_height = AP_RCTelemetry::get_nav_alt_m(); _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); } diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp index 623ad0184f748e..afc1f8b7f1a638 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp @@ -153,10 +153,10 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavl switch ((uint16_t)mav_command_long.param1) { case 0: - fence->enable(false); + fence->enable_configured(false); return MAV_RESULT_ACCEPTED; case 1: - fence->enable(true); + fence->enable_configured(true); return MAV_RESULT_ACCEPTED; default: return MAV_RESULT_FAILED; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.cpp index f9bf7872e892d6..6d474337ef227e 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.cpp @@ -14,9 +14,9 @@ */ #include "AP_Frsky_Parameters.h" -#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL const AP_Param::GroupInfo AP_Frsky_Parameters::var_info[] = { +#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL // @Param: UPLINK_ID // @DisplayName: Uplink sensor id // @Description: Change the uplink sensor id (SPort only) @@ -37,6 +37,7 @@ const AP_Param::GroupInfo AP_Frsky_Parameters::var_info[] = { // @Values: -1:Disable,7:7,8:8,9:9,10:10,11:11,12:12,13:13,14:14,15:15,16:16,17:17,18:18,19:19,20:20,21:21,22:22,23:23,24:24,25:25,26:26 // @User: Advanced AP_GROUPINFO("DNLINK2_ID", 3, AP_Frsky_Parameters, _dnlink2_id, 7), +#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL // @Param: DNLINK_ID // @DisplayName: Default downlink sensor id @@ -58,5 +59,3 @@ AP_Frsky_Parameters::AP_Frsky_Parameters() { AP_Param::setup_object_defaults(this, var_info); } - -#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.h b/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.h index 3826f340e6191f..f6a06ac962570b 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Parameters.h @@ -16,7 +16,6 @@ #include "AP_Frsky_Telem.h" -#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL #include #include @@ -33,11 +32,11 @@ class AP_Frsky_Parameters private: // settable parameters - AP_Int8 _uplink_id; AP_Int8 _dnlink_id; +#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL + AP_Int8 _uplink_id; AP_Int8 _dnlink1_id; AP_Int8 _dnlink2_id; +#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL AP_Int8 _options; }; - -#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp index c4dd68e481dcc5..ee22bc40de43bb 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp @@ -43,7 +43,10 @@ void AP_Frsky_SPort::send(void) } for (int16_t i = 0; i < numc; i++) { - int16_t readbyte = _port->read(); + uint8_t readbyte; + if (!_port->read(readbyte)) { + break; + } if (_SPort.sport_status == false) { if (readbyte == FRAME_HEAD) { _SPort.sport_status = true; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index 2f3acb0fb36277..c6e69d626c3e29 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -20,8 +20,8 @@ #if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL #include "AP_Frsky_MAVlite.h" -#include "AP_Frsky_Parameters.h" #endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL +#include "AP_Frsky_Parameters.h" /* for FrSky SPort Passthrough @@ -77,7 +77,7 @@ for FrSky SPort Passthrough #define WIND_ANGLE_LIMIT 0x7F #define WIND_SPEED_OFFSET 7 #define WIND_APPARENT_ANGLE_OFFSET 15 -#define WIND_APPARENT_SPEED_OFFSET 23 +#define WIND_APPARENT_SPEED_OFFSET 22 // for waypoint data #define WP_NUMBER_LIMIT 2047 #define WP_DISTANCE_LIMIT 1023000 @@ -646,7 +646,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_home(void) */ uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void) { - float vspd = get_vspeed_ms(); + float vspd = AP_RCTelemetry::get_vspeed_ms(); // vertical velocity in dm/s uint32_t velandyaw = prep_number(roundf(vspd * 10), 2, 1); float airspeed_m; // m/s @@ -683,7 +683,9 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void) */ uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void) { +#if AP_RANGEFINDER_ENABLED const RangeFinder *_rng = RangeFinder::get_singleton(); +#endif float roll; float pitch; @@ -693,7 +695,11 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_attiandrng(void) // pitch from [-9000;9000] centidegrees to unsigned .2 degree increments [0;900] (just in case, limit to 1023 (0x3FF) since the value is stored on 10 bits) attiandrng |= ((uint16_t)roundf((pitch * RAD_TO_DEG * 100 + 9000) * 0.05f) & ATTIANDRNG_PITCH_LIMIT)<distance_cm_orient(ROTATION_PITCH_270) : 0, 3, 1)<get_true_wind_speed() * 10), 2, 1) << WIND_SPEED_OFFSET; // apparent wind angle in 3 degree increments -180,180 (signed) - value |= prep_number(roundf(degrees(windvane->get_apparent_wind_direction_rad()) * (1.0f/3.0f)), 2, 0); + value |= prep_number(roundf(degrees(windvane->get_apparent_wind_direction_rad()) * (1.0f/3.0f)), 2, 0) << WIND_APPARENT_ANGLE_OFFSET; // apparent wind speed in dm/s value |= prep_number(roundf(windvane->get_apparent_wind_speed() * 10), 2, 1) << WIND_APPARENT_SPEED_OFFSET; } @@ -934,6 +940,16 @@ void AP_Frsky_SPort_Passthrough::process_tx_queue() send_sport_frame(SPORT_DOWNLINK_FRAME, packet.appid, packet.data); } +/* + * Send a mavlite message + * Message is chunked in sport packets pushed in the tx queue + * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers) + */ +bool AP_Frsky_SPort_Passthrough::send_message(const AP_Frsky_MAVlite_Message &txmsg) +{ + return mavlite_to_sport.process(_SPort_bidir.tx_packet_queue, txmsg); +} +#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL /* * Utility method to apply constraints in changing sensor id values * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers) @@ -950,17 +966,6 @@ void AP_Frsky_SPort_Passthrough::set_sensor_id(AP_Int8 param_idx, uint8_t &senso sensor = calc_sensor_id(idx); } -/* - * Send a mavlite message - * Message is chunked in sport packets pushed in the tx queue - * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers) - */ -bool AP_Frsky_SPort_Passthrough::send_message(const AP_Frsky_MAVlite_Message &txmsg) -{ - return mavlite_to_sport.process(_SPort_bidir.tx_packet_queue, txmsg); -} -#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL - namespace AP { AP_Frsky_SPort_Passthrough *frsky_passthrough_telem() diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h index e48541d8cdd8d3..5f78deff54273c 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h @@ -26,8 +26,8 @@ class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry AP_Frsky_SPort_Passthrough(AP_HAL::UARTDriver *port, bool use_external_data, AP_Frsky_Parameters *&frsky_parameters) : AP_Frsky_SPort(port), AP_RCTelemetry(WFQ_LAST_ITEM), - _use_external_data(use_external_data), - _frsky_parameters(frsky_parameters) + _frsky_parameters(frsky_parameters), + _use_external_data(use_external_data) { singleton = this; } @@ -149,7 +149,6 @@ class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry AP_Frsky_MAVlite_SPortToMAVlite sport_to_mavlite; AP_Frsky_MAVlite_MAVliteToSPort mavlite_to_sport; - void set_sensor_id(AP_Int8 idx, uint8_t &sensor); // tx/rx sport packet processing void queue_rx_packet(const AP_Frsky_SPort::sport_packet_t sp); void process_rx_queue(void); @@ -160,7 +159,7 @@ class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry bool send_message(const AP_Frsky_MAVlite_Message &txmsg); AP_Frsky_MAVliteMsgHandler mavlite{FUNCTOR_BIND_MEMBER(&AP_Frsky_SPort_Passthrough::send_message, bool, const AP_Frsky_MAVlite_Message &)}; #endif - + void set_sensor_id(AP_Int8 idx, uint8_t &sensor); void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data); // true if we need to respond to the last polling byte diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index aba8772465226e..450591a381bd37 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -66,15 +66,15 @@ bool AP_Frsky_Telem::init(bool use_external_data) AP_HAL::UARTDriver *port; if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) { #if AP_FRSKY_D_TELEM_ENABLED - _backend = new AP_Frsky_D(port); + _backend = NEW_NOTHROW AP_Frsky_D(port); #endif } else if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) { #if AP_FRSKY_SPORT_TELEM_ENABLED - _backend = new AP_Frsky_SPort(port); + _backend = NEW_NOTHROW AP_Frsky_SPort(port); #endif } else if (use_external_data || (port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) { #if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED - _backend = new AP_Frsky_SPort_Passthrough(port, use_external_data, _frsky_parameters); + _backend = NEW_NOTHROW AP_Frsky_SPort_Passthrough(port, use_external_data, _frsky_parameters); #endif } @@ -116,7 +116,7 @@ void AP_Frsky_Telem::try_create_singleton_for_external_data() { // try to allocate an AP_Frsky_Telem object only if we are disarmed if (!singleton && !hal.util->get_soft_armed()) { - new AP_Frsky_Telem(); + NEW_NOTHROW AP_Frsky_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(true); diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 91b7c0dcd1c651..79a69b88b29621 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -29,6 +29,7 @@ #include #include "AP_GPS_NOVA.h" +#include "AP_GPS_Blended.h" #include "AP_GPS_ERB.h" #include "AP_GPS_GSOF.h" #include "AP_GPS_NMEA.h" @@ -59,6 +60,12 @@ #include "RTCM3_Parser.h" #endif +#if !AP_GPS_BLENDED_ENABLED +#if defined(GPS_BLENDED_INSTANCE) +#error GPS_BLENDED_INSTANCE should not be defined when AP_GPS_BLENDED_ENABLED is false +#endif +#endif + #define GPS_RTK_INJECT_TO_ALL 127 #ifndef GPS_MAX_RATE_MS #define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms @@ -66,8 +73,6 @@ #define GPS_BAUD_TIME_MS 1200 #define GPS_TIMEOUT_MS 4000u -#define BLEND_COUNTER_FAILURE_INCREMENT 10 - extern const AP_HAL::HAL &hal; // baudrates to try to detect GPSes with @@ -347,6 +352,11 @@ void AP_GPS::init() rate_ms.set(GPS_MAX_RATE_MS); } } + + // create the blended instance if appropriate: +#if AP_GPS_BLENDED_ENABLED + drivers[GPS_BLENDED_INSTANCE] = NEW_NOTHROW AP_GPS_Blended(*this, params[GPS_BLENDED_INSTANCE], state[GPS_BLENDED_INSTANCE], timing[GPS_BLENDED_INSTANCE]); +#endif } void AP_GPS::convert_parameters() @@ -633,7 +643,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) case GPS_TYPE_MAV: #if AP_GPS_MAV_ENABLED dstate->auto_detected_baud = false; // specified, not detected - return new AP_GPS_MAV(*this, params[instance], state[instance], nullptr); + return NEW_NOTHROW AP_GPS_MAV(*this, params[instance], state[instance], nullptr); #endif //AP_GPS_MAV_ENABLED // user has to explicitly set the UAVCAN type, do not use AUTO @@ -648,17 +658,20 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) #if HAL_MSP_GPS_ENABLED case GPS_TYPE_MSP: dstate->auto_detected_baud = false; // specified, not detected - return new AP_GPS_MSP(*this, params[instance], state[instance], nullptr); + return NEW_NOTHROW AP_GPS_MSP(*this, params[instance], state[instance], nullptr); #endif #if HAL_EXTERNAL_AHRS_ENABLED case GPS_TYPE_EXTERNAL_AHRS: - dstate->auto_detected_baud = false; // specified, not detected - return new AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr); + if (AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::GPS) >= 0) { + dstate->auto_detected_baud = false; // specified, not detected + return NEW_NOTHROW AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr); + } + break; #endif #if AP_GPS_GSOF_ENABLED case GPS_TYPE_GSOF: dstate->auto_detected_baud = false; // specified, not detected - return new AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]); #endif //AP_GPS_GSOF_ENABLED default: break; @@ -712,16 +725,16 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) // by default the sbf/trimble gps outputs no data on its port, until configured. case GPS_TYPE_SBF: case GPS_TYPE_SBF_DUAL_ANTENNA: - return new AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]); #endif //AP_GPS_SBF_ENABLED #if AP_GPS_NOVA_ENABLED case GPS_TYPE_NOVA: - return new AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]); #endif //AP_GPS_NOVA_ENABLED #if HAL_SIM_GPS_ENABLED case GPS_TYPE_SITL: - return new AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]); #endif // HAL_SIM_GPS_ENABLED default: @@ -746,7 +759,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) (_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) || _baudrates[dstate->current_baud] == 230400) && AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) { - return new AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL); + return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL); } const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800; @@ -760,31 +773,31 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) } else { role = GPS_ROLE_MB_ROVER; } - return new AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role); + return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role); } #endif // AP_GPS_UBLOX_ENABLED #if AP_GPS_SBP2_ENABLED if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) && AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) { - return new AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]); } #endif //AP_GPS_SBP2_ENABLED #if AP_GPS_SBP_ENABLED if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) && AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) { - return new AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]); } #endif //AP_GPS_SBP_ENABLED #if AP_GPS_SIRF_ENABLED if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SIRF) && AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) { - return new AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]); } #endif #if AP_GPS_ERB_ENABLED if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_ERB) && AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) { - return new AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]); } #endif // AP_GPS_ERB_ENABLED #if AP_GPS_NMEA_ENABLED @@ -796,7 +809,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) #endif type == GPS_TYPE_ALLYSTAR) && AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) { - return new AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]); + return NEW_NOTHROW AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]); } #endif //AP_GPS_NMEA_ENABLED } @@ -980,7 +993,7 @@ void AP_GPS::update_instance(uint8_t instance) #if GPS_MOVING_BASELINE -void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) +bool AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) { for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) { if (drivers[i] && @@ -991,8 +1004,10 @@ void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float relPosD = state[i].relPosD; accHeading = state[i].accHeading; timestamp = state[i].relposheading_ts; + return true; } } + return false; } bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) @@ -1082,25 +1097,15 @@ void AP_GPS::update_primary(void) */ const bool using_moving_base = is_rtk_base(0) || is_rtk_base(1); if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) { - _output_is_blended = calc_blend_weights(); - // adjust blend health counter - if (!_output_is_blended) { - _blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100); - } else if (_blend_health_counter > 0) { - _blend_health_counter--; - } - // stop blending if unhealthy - if (_blend_health_counter >= 50) { - _output_is_blended = false; - } + _output_is_blended = ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_weights(); } else { _output_is_blended = false; - _blend_health_counter = 0; + ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->zero_health_counter(); } if (_output_is_blended) { // Use the weighting to calculate blended GPS states - calc_blended_state(); + ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_state(); // set primary to the virtual instance primary_instance = GPS_BLENDED_INSTANCE; return; @@ -1362,6 +1367,7 @@ uint16_t AP_GPS::gps_yaw_cdeg(uint8_t instance) const return yaw_cd; } +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) { const Location &loc = location(0); @@ -1395,8 +1401,9 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) 0, // TODO one-sigma heading accuracy standard deviation gps_yaw_cdeg(0)); } +#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED -#if GPS_MAX_RECEIVERS > 1 +#if AP_GPS_GPS2_RAW_SENDING_ENABLED void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) { // always send the message if 2nd GPS is configured @@ -1437,9 +1444,9 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) sacc * 1000, // one-sigma standard deviation in mm/s 0); // TODO one-sigma heading accuracy standard deviation } -#endif // GPS_MAX_RECEIVERS +#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED -#if HAL_GCS_ENABLED +#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) { if (inst >= GPS_MAX_RECEIVERS) { @@ -1616,7 +1623,7 @@ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm return false; } if (rtcm.parsers[chan] == nullptr) { - rtcm.parsers[chan] = new RTCM3_Parser(); + rtcm.parsers[chan] = NEW_NOTHROW RTCM3_Parser(); if (rtcm.parsers[chan] == nullptr) { return false; } @@ -1693,10 +1700,7 @@ bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const #if AP_GPS_BLENDED_ENABLED // return lag of blended GPS if (instance == GPS_BLENDED_INSTANCE) { - lag_sec = _blended_lag_sec; - // auto switching uses all GPS receivers, so all must be configured - uint8_t inst; // we don't actually care what the number is, but must pass it - return first_unconfigured_gps(inst); + return drivers[instance]->get_lag(lag_sec); } #endif @@ -1730,7 +1734,7 @@ const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const #if AP_GPS_BLENDED_ENABLED if (instance == GPS_BLENDED_INSTANCE) { // return an offset for the blended GPS solution - return _blended_antenna_offset; + return ((AP_GPS_Blended*)drivers[instance])->get_antenna_offset(); } #endif @@ -1786,12 +1790,6 @@ bool AP_GPS::is_healthy(uint8_t instance) const } #endif // HAL_BUILD_AP_PERIPH -#if AP_GPS_BLENDED_ENABLED - if (instance == GPS_BLENDED_INSTANCE) { - return blend_health_check(); - } -#endif - return drivers[instance] != nullptr && drivers[instance]->is_healthy(); } @@ -1806,18 +1804,17 @@ bool AP_GPS::prepare_for_arming(void) { return all_passed; } -bool AP_GPS::backends_healthy(char failure_msg[], uint16_t failure_msg_len) { - for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { +bool AP_GPS::pre_arm_checks(char failure_msg[], uint16_t failure_msg_len) +{ + // the DroneCAN class has additional checks for DroneCAN-specific + // parameters: #if AP_GPS_DRONECAN_ENABLED - const auto type = params[i].type; - if (type == GPS_TYPE_UAVCAN || - type == GPS_TYPE_UAVCAN_RTK_BASE || - type == GPS_TYPE_UAVCAN_RTK_ROVER) { - if (!AP_GPS_DroneCAN::backends_healthy(failure_msg, failure_msg_len)) { - return false; - } - } + if (!AP_GPS_DroneCAN::inter_instance_pre_arm_checks(failure_msg, failure_msg_len)) { + return false; + } #endif + + for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { if (is_rtk_rover(i)) { if (AP_HAL::millis() - state[i].gps_yaw_time_ms > 15000) { hal.util->snprintf(failure_msg, failure_msg_len, "GPS[%u] yaw not available", unsigned(i+1)); @@ -1825,6 +1822,14 @@ bool AP_GPS::backends_healthy(char failure_msg[], uint16_t failure_msg_len) { } } } + +#if AP_GPS_BLENDED_ENABLED + if (!drivers[GPS_BLENDED_INSTANCE]->is_healthy()) { + hal.util->snprintf(failure_msg, failure_msg_len, "GPS blending unhealthy"); + return false; + } +#endif + return true; } @@ -1995,31 +2000,36 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _TYPE // @DisplayName: 1st GPS type - // @Description: GPS type of 1st GPS + // @Description: GPS type of 1st GPS.Renamed in 4.6 and later to GPS1_TYPE // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna // @RebootRequired: True // @User: Advanced + // @Legacy: only included here so GCSs running stable can get the description. Omitted in the Wiki. // @Param: _TYPE2 // @CopyFieldsFrom: GPS_TYPE - // @DisplayName: 2nd GPS type + // @DisplayName: 2nd GPS type.Renamed in 4.6 to GPS2_TYPE // @Description: GPS type of 2nd GPS + // @Legacy: 4.5 param // @Param: _GNSS_MODE // @DisplayName: GNSS system configuration - // @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured) + // @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured).Renamed in 4.6 and later to GPS1_GNSS_MODE. + // @Legacy: 4.5 param // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS // @User: Advanced // @Param: _GNSS_MODE2 - // @DisplayName: GNSS system configuration - // @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured) + // @DisplayName: GNSS system configuration. + // @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured). Renamed in 4.6 and later to GPS2_GNSS_MODE + // @Legacy: 4.5 param // @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS // @User: Advanced // @Param: _RATE_MS // @DisplayName: GPS update rate in milliseconds - // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance. + // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS1_RATE_MS + // @Legacy: 4.5 param // @Units: ms // @Values: 100:10Hz,125:8Hz,200:5Hz // @Range: 50 200 @@ -2027,7 +2037,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _RATE_MS2 // @DisplayName: GPS 2 update rate in milliseconds - // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance. + // @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS2_RATE_MS + // @Legacy: 4.5 param // @Units: ms // @Values: 100:10Hz,125:8Hz,200:5Hz // @Range: 50 200 @@ -2035,7 +2046,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS1_X // @DisplayName: Antenna X position offset - // @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_X. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2043,7 +2055,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS1_Y // @DisplayName: Antenna Y position offset - // @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_Y. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2051,7 +2064,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS1_Z // @DisplayName: Antenna Z position offset - // @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_Z. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2059,7 +2073,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS2_X // @DisplayName: Antenna X position offset - // @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_X. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2067,7 +2082,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS2_Y // @DisplayName: Antenna Y position offset - // @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_Y. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2075,7 +2091,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _POS2_Z // @DisplayName: Antenna Z position offset - // @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_Z. + // @Legacy: 4.5 param // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -2083,7 +2100,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _DELAY_MS // @DisplayName: GPS delay in milliseconds - // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type. + // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS1_DELAY_MS. + // @Legacy: 4.5 param // @Units: ms // @Range: 0 250 // @User: Advanced @@ -2091,7 +2109,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _DELAY_MS2 // @DisplayName: GPS 2 delay in milliseconds - // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type. + // @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS2_DELAY_MS. + // @Legacy: 4.5 param // @Units: ms // @Range: 0 250 // @User: Advanced @@ -2099,7 +2118,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _COM_PORT // @DisplayName: GPS physical COM port - // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS + // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS,Renamed in 4.6 and later to GPS1_COM_PORT. + // @Legacy: 4.5 param // @Range: 0 10 // @Increment: 1 // @User: Advanced @@ -2108,7 +2128,8 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Param: _COM_PORT2 // @DisplayName: GPS physical COM port - // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS + // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS.Renamed in 4.6 and later to GPS1_COM_PORT. + // @Legacy: 4.5 param // @Range: 0 10 // @Increment: 1 // @User: Advanced @@ -2116,19 +2137,23 @@ bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, // @Group: _MB1_ // @Path: MovingBase.cpp + // @Legacy: 4.5 param // @Group: _MB2_ // @Path: MovingBase.cpp + // @Legacy: 4.5 param // @Param: _CAN_NODEID1 // @DisplayName: GPS Node ID 1 - // @Description: GPS Node id for first-discovered GPS. + // @Description: GPS Node id for first-discovered GPS.Renamed in 4.6 and later to GPS1_CAN_NODEID. + // @Legacy: 4.5 param // @ReadOnly: True // @User: Advanced // @Param: _CAN_NODEID2 // @DisplayName: GPS Node ID 2 - // @Description: GPS Node id for second-discovered GPS. + // @Description: GPS Node id for second-discovered GPS.Renamed in 4.6 and later to GPS2_CAN_NODEID. + // @Legacy: 4.5 param // @ReadOnly: True // @User: Advanced diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 70879831078eb0..a3c814ffc241f8 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -52,6 +52,7 @@ class RTCM3_Parser; /// GPS driver main class class AP_GPS { + friend class AP_GPS_Blended; friend class AP_GPS_ERB; friend class AP_GPS_GSOF; friend class AP_GPS_MAV; @@ -197,12 +198,12 @@ class AP_GPS uint16_t time_week; ///< GPS week number Location location; ///< last fix location float ground_speed; ///< ground speed in m/s - float ground_course; ///< ground course in degrees + float ground_course; ///< ground course in degrees, wrapped 0-360 float gps_yaw; ///< GPS derived yaw information, if available (degrees) uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading bool gps_yaw_configured; ///< GPS is configured to provide yaw - uint16_t hdop; ///< horizontal dilution of precision in cm - uint16_t vdop; ///< vertical dilution of precision in cm + uint16_t hdop; ///< horizontal dilution of precision, scaled by a factor of 100 (155 means the HDOP value is 1.55) + uint16_t vdop; ///< vertical dilution of precision, scaled by a factor of 100 (155 means the VDOP value is 1.55) uint8_t num_sats; ///< Number of visible satellites Vector3f velocity; ///< 3D velocity in m/s, in NED format float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s @@ -512,9 +513,6 @@ class AP_GPS // pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned bool all_consistent(float &distance) const; - // pre-arm check of GPS blending. False if blending is unhealthy, True if healthy or blending is not being used - bool blend_health_check() const; - // handle sending of initialisation strings to the GPS - only used by backends void send_blob_start(uint8_t instance); void send_blob_start(uint8_t instance, const char *_blob, uint16_t size); @@ -551,9 +549,10 @@ class AP_GPS // returns true if all GPS instances have passed all final arming checks/state changes bool prepare_for_arming(void); - // returns true if all GPS backend drivers haven't seen any failure - // this is for backends to be able to spout pre arm error messages - bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); + // returns true if all GPS backend drivers are OK with the concept + // of the vehicle arming. this is for backends to be able to + // spout pre arm error messages + bool pre_arm_checks(char failure_msg[], uint16_t failure_msg_len); // returns false if any GPS drivers are not performing their logging appropriately bool logging_failed(void) const; @@ -594,7 +593,7 @@ class AP_GPS #if GPS_MOVING_BASELINE // methods used by UAVCAN GPS driver and AP_Periph for moving baseline void inject_MBL_data(uint8_t* data, uint16_t length); - void get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading); + bool get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED; bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len); void clear_RTCMV3(); #endif // GPS_MOVING_BASELINE @@ -606,7 +605,7 @@ class AP_GPS protected: // configuration parameters - Params params[GPS_MAX_RECEIVERS]; + Params params[GPS_MAX_INSTANCES]; AP_Int8 _navfilter; AP_Int8 _auto_switch; AP_Int16 _sbp_logmask; @@ -668,7 +667,7 @@ class AP_GPS // Note allowance for an additional instance to contain blended data GPS_timing timing[GPS_MAX_INSTANCES]; GPS_State state[GPS_MAX_INSTANCES]; - AP_GPS_Backend *drivers[GPS_MAX_RECEIVERS]; + AP_GPS_Backend *drivers[GPS_MAX_INSTANCES]; AP_HAL::UARTDriver *_port[GPS_MAX_RECEIVERS]; /// primary GPS instance @@ -756,18 +755,7 @@ class AP_GPS void inject_data(uint8_t instance, const uint8_t *data, uint16_t len); #if AP_GPS_BLENDED_ENABLED - // GPS blending and switching - Vector3f _blended_antenna_offset; // blended antenna offset - float _blended_lag_sec; // blended receiver lag in seconds - float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances. bool _output_is_blended; // true when a blended GPS solution being output - uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy - - // calculate the blend weight. Returns true if blend could be calculated, false if not - bool calc_blend_weights(void); - - // calculate the blended state - void calc_blended_state(void); #endif bool should_log() const; diff --git a/libraries/AP_GPS/AP_GPS_Blended.cpp b/libraries/AP_GPS/AP_GPS_Blended.cpp index 071b377817cc52..47deea9f4b3292 100644 --- a/libraries/AP_GPS/AP_GPS_Blended.cpp +++ b/libraries/AP_GPS/AP_GPS_Blended.cpp @@ -1,22 +1,20 @@ -#include "AP_GPS.h" +#include "AP_GPS_config.h" #if AP_GPS_BLENDED_ENABLED +#include "AP_GPS_Blended.h" + // defines used to specify the mask position for use of different accuracy metrics in the blending algorithm #define BLEND_MASK_USE_HPOS_ACC 1 #define BLEND_MASK_USE_VPOS_ACC 2 #define BLEND_MASK_USE_SPD_ACC 4 -// pre-arm check of GPS blending. True means healthy or that blending is not being used -bool AP_GPS::blend_health_check() const -{ - return (_blend_health_counter < 50); -} +#define BLEND_COUNTER_FAILURE_INCREMENT 10 /* calculate the weightings used to blend GPSs location and velocity data */ -bool AP_GPS::calc_blend_weights(void) +bool AP_GPS_Blended::_calc_weights(void) { // zero the blend weights memset(&_blend_weights, 0, sizeof(_blend_weights)); @@ -27,7 +25,7 @@ bool AP_GPS::calc_blend_weights(void) // The time delta calculations below also rely upon every instance being currently detected and being parsed // exit immediately if not enough receivers to do blending - if (state[0].status <= NO_FIX || state[1].status <= NO_FIX) { + if (gps.state[0].status <= AP_GPS::NO_FIX || gps.state[1].status <= AP_GPS::NO_FIX) { return false; } @@ -37,22 +35,22 @@ bool AP_GPS::calc_blend_weights(void) uint32_t max_rate_ms = 0; // largest update interval of a GPS receiver for (uint8_t i=0; i max_ms) { - max_ms = state[i].last_gps_time_ms; + if (gps.state[i].last_gps_time_ms > max_ms) { + max_ms = gps.state[i].last_gps_time_ms; } - if ((state[i].last_gps_time_ms < min_ms) && (state[i].last_gps_time_ms > 0)) { - min_ms = state[i].last_gps_time_ms; + if ((gps.state[i].last_gps_time_ms < min_ms) && (gps.state[i].last_gps_time_ms > 0)) { + min_ms = gps.state[i].last_gps_time_ms; } - max_rate_ms = MAX(get_rate_ms(i), max_rate_ms); - if (isinf(state[i].speed_accuracy) || - isinf(state[i].horizontal_accuracy) || - isinf(state[i].vertical_accuracy)) { + max_rate_ms = MAX(gps.get_rate_ms(i), max_rate_ms); + if (isinf(gps.state[i].speed_accuracy) || + isinf(gps.state[i].horizontal_accuracy) || + isinf(gps.state[i].vertical_accuracy)) { return false; } } if ((max_ms - min_ms) < (2 * max_rate_ms)) { // data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated - state[GPS_BLENDED_INSTANCE].last_gps_time_ms = min_ms; + state.last_gps_time_ms = min_ms; } else { // receiver data has timed out so fail out of blending return false; @@ -60,11 +58,11 @@ bool AP_GPS::calc_blend_weights(void) // calculate the sum squared speed accuracy across all GPS sensors float speed_accuracy_sum_sq = 0.0f; - if (_blend_mask & BLEND_MASK_USE_SPD_ACC) { + if (gps._blend_mask & BLEND_MASK_USE_SPD_ACC) { 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 += sq(state[i].speed_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) { + if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f) { + speed_accuracy_sum_sq += sq(gps.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; @@ -76,11 +74,11 @@ bool AP_GPS::calc_blend_weights(void) // calculate the sum squared horizontal position accuracy across all GPS sensors float horizontal_accuracy_sum_sq = 0.0f; - if (_blend_mask & BLEND_MASK_USE_HPOS_ACC) { + if (gps._blend_mask & BLEND_MASK_USE_HPOS_ACC) { 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 += sq(state[i].horizontal_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D) { + if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f) { + horizontal_accuracy_sum_sq += sq(gps.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; @@ -92,11 +90,11 @@ bool AP_GPS::calc_blend_weights(void) // calculate the sum squared vertical position accuracy across all GPS sensors float vertical_accuracy_sum_sq = 0.0f; - if (_blend_mask & BLEND_MASK_USE_VPOS_ACC) { + if (gps._blend_mask & BLEND_MASK_USE_VPOS_ACC) { 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 += sq(state[i].vertical_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) { + if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f) { + vertical_accuracy_sum_sq += sq(gps.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; @@ -121,8 +119,8 @@ bool AP_GPS::calc_blend_weights(void) // 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 / sq(state[i].horizontal_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D && gps.state[i].horizontal_accuracy >= 0.001f) { + hpos_blend_weights[i] = horizontal_accuracy_sum_sq / sq(gps.state[i].horizontal_accuracy); sum_of_hpos_weights += hpos_blend_weights[i]; } } @@ -141,8 +139,8 @@ bool AP_GPS::calc_blend_weights(void) // 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 / sq(state[i].vertical_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].vertical_accuracy >= 0.001f) { + vpos_blend_weights[i] = vertical_accuracy_sum_sq / sq(gps.state[i].vertical_accuracy); sum_of_vpos_weights += vpos_blend_weights[i]; } } @@ -161,8 +159,8 @@ bool AP_GPS::calc_blend_weights(void) // 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 / sq(state[i].speed_accuracy); + if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].speed_accuracy >= 0.001f) { + spd_blend_weights[i] = speed_accuracy_sum_sq / sq(gps.state[i].speed_accuracy); sum_of_spd_weights += spd_blend_weights[i]; } } @@ -187,104 +185,116 @@ bool AP_GPS::calc_blend_weights(void) return true; } +bool AP_GPS_Blended::calc_weights() +{ + // adjust blend health counter + if (!_calc_weights()) { + _blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100); + } else if (_blend_health_counter > 0) { + _blend_health_counter--; + } + // stop blending if unhealthy + return _blend_health_counter < 50; +} + /* calculate a blended GPS state */ -void AP_GPS::calc_blended_state(void) +void AP_GPS_Blended::calc_state(void) { // initialise the blended states so we can accumulate the results using the weightings for each GPS receiver - state[GPS_BLENDED_INSTANCE].instance = GPS_BLENDED_INSTANCE; - state[GPS_BLENDED_INSTANCE].status = NO_FIX; - state[GPS_BLENDED_INSTANCE].time_week_ms = 0; - state[GPS_BLENDED_INSTANCE].time_week = 0; - state[GPS_BLENDED_INSTANCE].ground_speed = 0.0f; - state[GPS_BLENDED_INSTANCE].ground_course = 0.0f; - state[GPS_BLENDED_INSTANCE].hdop = GPS_UNKNOWN_DOP; - state[GPS_BLENDED_INSTANCE].vdop = GPS_UNKNOWN_DOP; - state[GPS_BLENDED_INSTANCE].num_sats = 0; - state[GPS_BLENDED_INSTANCE].velocity.zero(); - state[GPS_BLENDED_INSTANCE].speed_accuracy = 1e6f; - state[GPS_BLENDED_INSTANCE].horizontal_accuracy = 1e6f; - state[GPS_BLENDED_INSTANCE].vertical_accuracy = 1e6f; - state[GPS_BLENDED_INSTANCE].have_vertical_velocity = false; - state[GPS_BLENDED_INSTANCE].have_speed_accuracy = false; - state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = false; - state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = false; - state[GPS_BLENDED_INSTANCE].location = {}; + state.instance = GPS_BLENDED_INSTANCE; + state.status = AP_GPS::NO_FIX; + state.time_week_ms = 0; + state.time_week = 0; + state.ground_speed = 0.0f; + state.ground_course = 0.0f; + state.hdop = GPS_UNKNOWN_DOP; + state.vdop = GPS_UNKNOWN_DOP; + state.num_sats = 0; + state.velocity.zero(); + state.speed_accuracy = 1e6f; + state.horizontal_accuracy = 1e6f; + state.vertical_accuracy = 1e6f; + state.have_vertical_velocity = false; + state.have_speed_accuracy = false; + state.have_horizontal_accuracy = false; + state.have_vertical_accuracy = false; + state.location = {}; _blended_antenna_offset.zero(); _blended_lag_sec = 0; #if HAL_LOGGING_ENABLED - const uint32_t last_blended_message_time_ms = timing[GPS_BLENDED_INSTANCE].last_message_time_ms; + const uint32_t last_blended_message_time_ms = timing.last_message_time_ms; #endif - 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; + timing.last_fix_time_ms = 0; + timing.last_message_time_ms = 0; + + if (gps.state[0].have_undulation) { + state.have_undulation = true; + state.undulation = gps.state[0].undulation; + } else if (gps.state[1].have_undulation) { + state.have_undulation = true; + state.undulation = gps.state[1].undulation; } else { - state[GPS_BLENDED_INSTANCE].have_undulation = false; + state.have_undulation = false; } // combine the states into a blended solution for (uint8_t i=0; i state[GPS_BLENDED_INSTANCE].status) { - state[GPS_BLENDED_INSTANCE].status = state[i].status; + if (gps.state[i].status > state.status) { + state.status = gps.state[i].status; } // calculate a blended average velocity - state[GPS_BLENDED_INSTANCE].velocity += state[i].velocity * _blend_weights[i]; + state.velocity += gps.state[i].velocity * _blend_weights[i]; // report the best valid accuracies and DOP metrics - if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f && state[i].horizontal_accuracy < state[GPS_BLENDED_INSTANCE].horizontal_accuracy) { - state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = true; - state[GPS_BLENDED_INSTANCE].horizontal_accuracy = state[i].horizontal_accuracy; + if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f && gps.state[i].horizontal_accuracy < state.horizontal_accuracy) { + state.have_horizontal_accuracy = true; + state.horizontal_accuracy = gps.state[i].horizontal_accuracy; } - if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f && state[i].vertical_accuracy < state[GPS_BLENDED_INSTANCE].vertical_accuracy) { - state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = true; - state[GPS_BLENDED_INSTANCE].vertical_accuracy = state[i].vertical_accuracy; + if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f && gps.state[i].vertical_accuracy < state.vertical_accuracy) { + state.have_vertical_accuracy = true; + state.vertical_accuracy = gps.state[i].vertical_accuracy; } - if (state[i].have_vertical_velocity) { - state[GPS_BLENDED_INSTANCE].have_vertical_velocity = true; + if (gps.state[i].have_vertical_velocity) { + state.have_vertical_velocity = true; } - if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f && state[i].speed_accuracy < state[GPS_BLENDED_INSTANCE].speed_accuracy) { - state[GPS_BLENDED_INSTANCE].have_speed_accuracy = true; - state[GPS_BLENDED_INSTANCE].speed_accuracy = state[i].speed_accuracy; + if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f && gps.state[i].speed_accuracy < state.speed_accuracy) { + state.have_speed_accuracy = true; + state.speed_accuracy = gps.state[i].speed_accuracy; } - if (state[i].hdop > 0 && state[i].hdop < state[GPS_BLENDED_INSTANCE].hdop) { - state[GPS_BLENDED_INSTANCE].hdop = state[i].hdop; + if (gps.state[i].hdop > 0 && gps.state[i].hdop < state.hdop) { + state.hdop = gps.state[i].hdop; } - if (state[i].vdop > 0 && state[i].vdop < state[GPS_BLENDED_INSTANCE].vdop) { - state[GPS_BLENDED_INSTANCE].vdop = state[i].vdop; + if (gps.state[i].vdop > 0 && gps.state[i].vdop < state.vdop) { + state.vdop = gps.state[i].vdop; } - if (state[i].num_sats > 0 && state[i].num_sats > state[GPS_BLENDED_INSTANCE].num_sats) { - state[GPS_BLENDED_INSTANCE].num_sats = state[i].num_sats; + if (gps.state[i].num_sats > 0 && gps.state[i].num_sats > state.num_sats) { + state.num_sats = gps.state[i].num_sats; } // report a blended average GPS antenna position - Vector3f temp_antenna_offset = params[i].antenna_offset; + Vector3f temp_antenna_offset = gps.params[i].antenna_offset; temp_antenna_offset *= _blend_weights[i]; _blended_antenna_offset += temp_antenna_offset; // blend the timing data - if (timing[i].last_fix_time_ms > timing[GPS_BLENDED_INSTANCE].last_fix_time_ms) { - timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = timing[i].last_fix_time_ms; + if (gps.timing[i].last_fix_time_ms > timing.last_fix_time_ms) { + timing.last_fix_time_ms = gps.timing[i].last_fix_time_ms; } - if (timing[i].last_message_time_ms > timing[GPS_BLENDED_INSTANCE].last_message_time_ms) { - timing[GPS_BLENDED_INSTANCE].last_message_time_ms = timing[i].last_message_time_ms; + if (gps.timing[i].last_message_time_ms > timing.last_message_time_ms) { + timing.last_message_time_ms = gps.timing[i].last_message_time_ms; } } @@ -300,7 +310,7 @@ void AP_GPS::calc_blended_state(void) if (_blend_weights[i] > best_weight) { best_weight = _blend_weights[i]; best_index = i; - state[GPS_BLENDED_INSTANCE].location = state[i].location; + state.location = gps.state[i].location; } } @@ -310,18 +320,18 @@ void AP_GPS::calc_blended_state(void) blended_NE_offset_m.zero(); for (uint8_t i=0; i 0.0f && i != best_index) { - blended_NE_offset_m += state[GPS_BLENDED_INSTANCE].location.get_distance_NE(state[i].location) * _blend_weights[i]; - blended_alt_offset_cm += (float)(state[i].location.alt - state[GPS_BLENDED_INSTANCE].location.alt) * _blend_weights[i]; + blended_NE_offset_m += state.location.get_distance_NE(gps.state[i].location) * _blend_weights[i]; + blended_alt_offset_cm += (float)(gps.state[i].location.alt - state.location.alt) * _blend_weights[i]; } } // Add the sum of weighted offsets to the reference location to obtain the blended location - state[GPS_BLENDED_INSTANCE].location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y); - state[GPS_BLENDED_INSTANCE].location.alt += (int)blended_alt_offset_cm; + state.location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y); + state.location.alt += (int)blended_alt_offset_cm; // Calculate ground speed and course from blended velocity vector - state[GPS_BLENDED_INSTANCE].ground_speed = state[GPS_BLENDED_INSTANCE].velocity.xy().length(); - state[GPS_BLENDED_INSTANCE].ground_course = wrap_360(degrees(atan2f(state[GPS_BLENDED_INSTANCE].velocity.y, state[GPS_BLENDED_INSTANCE].velocity.x))); + state.ground_speed = state.velocity.xy().length(); + state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x))); // If the GPS week is the same then use a blended time_week_ms // If week is different, then use time stamp from GPS with largest weighting @@ -331,8 +341,8 @@ void AP_GPS::calc_blended_state(void) for (uint8_t i=0; i 0) { // this is our first valid sensor week data - last_week_instance = state[i].time_week; - } else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != state[i].time_week) { + last_week_instance = gps.state[i].time_week; + } else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != gps.state[i].time_week) { // there is valid sensor week data that is inconsistent weeks_consistent = false; } @@ -340,19 +350,19 @@ void AP_GPS::calc_blended_state(void) // calculate output if (!weeks_consistent) { // use data from highest weighted sensor - state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week; - state[GPS_BLENDED_INSTANCE].time_week_ms = state[best_index].time_week_ms; + state.time_week = gps.state[best_index].time_week; + state.time_week_ms = gps.state[best_index].time_week_ms; } else { // use week number from highest weighting GPS (they should all have the same week number) - state[GPS_BLENDED_INSTANCE].time_week = state[best_index].time_week; + state.time_week = gps.state[best_index].time_week; // calculate a blended value for the number of ms lapsed in the week double temp_time_0 = 0.0; for (uint8_t i=0; i 0.0f) { - temp_time_0 += (double)state[i].time_week_ms * (double)_blend_weights[i]; + temp_time_0 += (double)gps.state[i].time_week_ms * (double)_blend_weights[i]; } } - state[GPS_BLENDED_INSTANCE].time_week_ms = (uint32_t)temp_time_0; + state.time_week_ms = (uint32_t)temp_time_0; } // calculate a blended value for the timing data and lag @@ -360,21 +370,30 @@ void AP_GPS::calc_blended_state(void) double temp_time_2 = 0.0; for (uint8_t i=0; i 0.0f) { - temp_time_1 += (double)timing[i].last_fix_time_ms * (double) _blend_weights[i]; - temp_time_2 += (double)timing[i].last_message_time_ms * (double)_blend_weights[i]; + temp_time_1 += (double)gps.timing[i].last_fix_time_ms * (double) _blend_weights[i]; + temp_time_2 += (double)gps.timing[i].last_message_time_ms * (double)_blend_weights[i]; float gps_lag_sec = 0; - get_lag(i, gps_lag_sec); + gps.get_lag(i, gps_lag_sec); _blended_lag_sec += gps_lag_sec * _blend_weights[i]; } } - timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = (uint32_t)temp_time_1; - timing[GPS_BLENDED_INSTANCE].last_message_time_ms = (uint32_t)temp_time_2; + timing.last_fix_time_ms = (uint32_t)temp_time_1; + timing.last_message_time_ms = (uint32_t)temp_time_2; #if HAL_LOGGING_ENABLED - if (timing[GPS_BLENDED_INSTANCE].last_message_time_ms > last_blended_message_time_ms && + if (timing.last_message_time_ms > last_blended_message_time_ms && should_log()) { - Write_GPS(GPS_BLENDED_INSTANCE); + gps.Write_GPS(GPS_BLENDED_INSTANCE); } #endif } + +bool AP_GPS_Blended::get_lag(float &lag_sec) const +{ + lag_sec = _blended_lag_sec; + // auto switching uses all GPS receivers, so all must be configured + uint8_t inst; // we don't actually care what the number is, but must pass it + return gps.first_unconfigured_gps(inst); +} + #endif // AP_GPS_BLENDED_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_Blended.h b/libraries/AP_GPS/AP_GPS_Blended.h new file mode 100644 index 00000000000000..77fe25ffb88844 --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_Blended.h @@ -0,0 +1,73 @@ +#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 . + */ + +#pragma once + +#include "AP_GPS_config.h" + +#if AP_GPS_BLENDED_ENABLED + +#include "AP_GPS.h" +#include "GPS_Backend.h" + +class AP_GPS_Blended : public AP_GPS_Backend +{ +public: + + AP_GPS_Blended(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, class AP_GPS::GPS_timing &_timing) : + AP_GPS_Backend(_gps, _params, _state, nullptr), + timing{_timing} + { } + + // pre-arm check of GPS blending. False if blending is unhealthy, + // True if healthy or blending is not being used + bool is_healthy() const override { + return (_blend_health_counter < 50); + } + + bool read() override { return true; } + + const char *name() const override { return "Blended"; } + + bool get_lag(float &lag_sec) const override; + const Vector3f &get_antenna_offset() const { + return _blended_antenna_offset; + } + + // calculate the blend weight. Returns true if blend could be + // calculated, false if not + bool calc_weights(void); + // calculate the blended state + void calc_state(void); + + void zero_health_counter() { + _blend_health_counter = 0; + } + +private: + + // GPS blending and switching + Vector3f _blended_antenna_offset; // blended antenna offset + float _blended_lag_sec; // blended receiver lag in seconds + float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances. + uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy + + AP_GPS::GPS_timing &timing; + bool _calc_weights(void); +}; + +#endif // AP_GPS_BLENDED_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index 927090a36fb946..aeec0442289af3 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -89,36 +89,19 @@ AP_GPS_DroneCAN::~AP_GPS_DroneCAN() #endif } -void AP_GPS_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_GPS_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, driver_index) != nullptr) #if GPS_MOVING_BASELINE - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("moving_baseline_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("relposheading_sub"); - } + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, driver_index) != nullptr) #endif + ; } AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) @@ -170,14 +153,14 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) // initialise the backend based on the UAVCAN Moving baseline selection switch (_gps.get_type(_state.instance)) { case AP_GPS::GPS_TYPE_UAVCAN: - backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL); + backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL); break; #if GPS_MOVING_BASELINE case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE: - backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE); + backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE); break; case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER: - backend = new AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER); + backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER); break; #endif default: @@ -214,7 +197,7 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) } #if GPS_MOVING_BASELINE if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) { - backend->rtcm3_parser = new RTCM3_Parser; + backend->rtcm3_parser = NEW_NOTHROW RTCM3_Parser; if (backend->rtcm3_parser == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); } @@ -225,10 +208,15 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) return backend; } -bool AP_GPS_DroneCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_len) +bool AP_GPS_DroneCAN::inter_instance_pre_arm_checks(char failure_msg[], uint16_t failure_msg_len) { + // lint parameters and detected node IDs: for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { const auto ¶ms_i = AP::gps().params[i]; + // we are only interested in parameters for DroneCAN GPSs: + if (!is_dronecan_gps_type(params_i.type)) { + continue; + } bool overriden_node_found = false; bool bad_override_config = false; if (params_i.override_node_id == 0) { @@ -237,6 +225,10 @@ bool AP_GPS_DroneCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_ } for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { const auto ¶ms_j = AP::gps().params[j]; + // we are only interested in parameters for DroneCAN GPSs: + if (!is_dronecan_gps_type(params_j.type)) { + continue; + } if (params_i.override_node_id == params_j.override_node_id && (i != j)) { bad_override_config = true; break; @@ -822,7 +814,7 @@ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len) if (_rtcm_stream.buf == nullptr) { // give enough space for a full round from a NTRIP server with all // constellations - _rtcm_stream.buf = new ByteBuffer(2400); + _rtcm_stream.buf = NEW_NOTHROW ByteBuffer(2400); if (_rtcm_stream.buf == nullptr) { return; } diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.h b/libraries/AP_GPS/AP_GPS_DroneCAN.h index 200d8ae11c3ff7..a0b62c8e5b3d71 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.h +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.h @@ -44,7 +44,7 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { const char *name() const override { return _name; } - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state); static void handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); @@ -56,7 +56,7 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { static void handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); static void handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); #endif - static bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); + static bool inter_instance_pre_arm_checks(char failure_msg[], uint16_t failure_msg_len); void inject_data(const uint8_t *data, uint16_t len) override; bool get_error_codes(uint32_t &error_codes) const override { error_codes = error_code; return seen_status; }; @@ -149,6 +149,15 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { uint32_t last_send_ms; ByteBuffer *buf; } _rtcm_stream; + + // returns true if the supplied GPS_Type is a DroneCAN GPS type + static bool is_dronecan_gps_type(AP_GPS::GPS_Type type) { + return ( + type == AP_GPS::GPS_TYPE_UAVCAN || + type == AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE || + type == AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER + ); + } }; #endif // AP_GPS_DRONECAN_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp b/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp index e19e433055ceb5..592a87ef1ad252 100644 --- a/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp +++ b/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp @@ -41,7 +41,7 @@ void AP_GPS_ExternalAHRS::handle_external(const AP_ExternalAHRS::gps_data_messag state.time_week = pkt.gps_week; state.time_week_ms = pkt.ms_tow; - if (pkt.fix_type == 0) { + if (pkt.fix_type == AP_GPS_FixType::NO_GPS) { state.status = AP_GPS::NO_FIX; } else { state.status = (AP_GPS::GPS_Status)pkt.fix_type; diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 4fbfef5833a2d5..588265b5334f69 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -19,7 +19,7 @@ // // Usage in SITL with hardware for debugging: // sim_vehicle.py -v Plane -A "--serial3=uart:/dev/ttyUSB0" --console --map -DG -// param set GPS_TYPE 11 // GSOF +// param set GPS1_TYPE 11 // GSOF // param set SERIAL3_PROTOCOL 5 // GPS // // Pure SITL usage @@ -58,8 +58,6 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, { // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Overview.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257COverview%257C_____0 static_assert(ARRAY_SIZE(gsofmsgreq) <= 10, "The maximum number of outputs allowed with GSOF is 10."); - - msg.state = Msg_Parser::State::STARTTX; constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); params.com_port.set_default(default_com_port); @@ -101,66 +99,19 @@ AP_GPS_GSOF::read(void) #if AP_GPS_DEBUG_LOGGING_ENABLED log_data(&temp, 1); #endif - ret |= parse(temp); - } - - return ret; -} - -bool -AP_GPS_GSOF::parse(const uint8_t temp) -{ - // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html - switch (msg.state) - { - default: - case Msg_Parser::State::STARTTX: - if (temp == STX) - { - msg.state = Msg_Parser::State::STATUS; - msg.read = 0; - msg.checksumcalc = 0; - } - break; - case Msg_Parser::State::STATUS: - msg.status = temp; - msg.state = Msg_Parser::State::PACKETTYPE; - msg.checksumcalc += temp; - break; - case Msg_Parser::State::PACKETTYPE: - msg.packettype = temp; - msg.state = Msg_Parser::State::LENGTH; - msg.checksumcalc += temp; - break; - case Msg_Parser::State::LENGTH: - msg.length = temp; - msg.state = Msg_Parser::State::DATA; - msg.checksumcalc += temp; - break; - case Msg_Parser::State::DATA: - msg.data[msg.read] = temp; - msg.read++; - msg.checksumcalc += temp; - if (msg.read >= msg.length) - { - msg.state = Msg_Parser::State::CHECKSUM; - } - break; - case Msg_Parser::State::CHECKSUM: - msg.checksum = temp; - msg.state = Msg_Parser::State::ENDTX; - if (msg.checksum == msg.checksumcalc) - { - return process_message(); + const int n_gsof_received = parse(temp, ARRAY_SIZE(gsofmsgreq)); + if(n_gsof_received == UNEXPECTED_NUM_GSOF_PACKETS) { + state.status = AP_GPS::NO_FIX; + continue; } - break; - case Msg_Parser::State::ENDTX: - msg.endtx = temp; - msg.state = Msg_Parser::State::STARTTX; - break; + const bool got_expected_packets = n_gsof_received == ARRAY_SIZE(gsofmsgreq); + ret |= got_expected_packets; + } + if (ret) { + pack_state_data(); } - return false; + return ret; } void @@ -205,172 +156,61 @@ AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, con port->write((const uint8_t*)buffer, sizeof(buffer)); } -double -AP_GPS_GSOF::SwapDouble(const uint8_t* src, const uint32_t pos) const -{ - union { - double d; - char bytes[sizeof(double)]; - } doubleu; - doubleu.bytes[0] = src[pos + 7]; - doubleu.bytes[1] = src[pos + 6]; - doubleu.bytes[2] = src[pos + 5]; - doubleu.bytes[3] = src[pos + 4]; - doubleu.bytes[4] = src[pos + 3]; - doubleu.bytes[5] = src[pos + 2]; - doubleu.bytes[6] = src[pos + 1]; - doubleu.bytes[7] = src[pos + 0]; - - return doubleu.d; -} - -float -AP_GPS_GSOF::SwapFloat(const uint8_t* src, const uint32_t pos) const -{ - union { - float f; - char bytes[sizeof(float)]; - } floatu; - floatu.bytes[0] = src[pos + 3]; - floatu.bytes[1] = src[pos + 2]; - floatu.bytes[2] = src[pos + 1]; - floatu.bytes[3] = src[pos + 0]; - - return floatu.f; -} - -uint32_t -AP_GPS_GSOF::SwapUint32(const uint8_t* src, const uint32_t pos) const -{ - uint32_t u; - memcpy(&u, &src[pos], sizeof(u)); - return be32toh(u); -} - -uint16_t -AP_GPS_GSOF::SwapUint16(const uint8_t* src, const uint32_t pos) const +bool +AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const { - uint16_t u; - memcpy(&u, &src[pos], sizeof(u)); - return be16toh(u); + switch(com_port) { + case static_cast(HW_Port::COM1): + case static_cast(HW_Port::COM2): + return true; + default: + return false; + } } -bool -AP_GPS_GSOF::process_message(void) +void +AP_GPS_GSOF::pack_state_data() { - if (msg.packettype == 0x40) { // GSOF - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 -#if gsof_DEBUGGING - const uint8_t trans_number = msg.data[0]; - const uint8_t pageidx = msg.data[1]; - const uint8_t maxpageidx = msg.data[2]; - - Debug("GSOF page: %u of %u (trans_number=%u)", - pageidx, maxpageidx, trans_number); -#endif - - int valid = 0; - - // want 1 2 8 9 12 - for (uint32_t a = 3; a < msg.length; a++) - { - const uint8_t output_type = msg.data[a]; - a++; - const uint8_t output_length = msg.data[a]; - a++; - //Debug("GSOF type: " + output_type + " len: " + output_length); - - if (output_type == 1) // pos time - { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 - state.time_week_ms = SwapUint32(msg.data, a); - state.time_week = SwapUint16(msg.data, a + 4); - state.num_sats = msg.data[a + 6]; - const uint8_t posf1 = msg.data[a + 7]; - const uint8_t posf2 = msg.data[a + 8]; - - //Debug("POSTIME: " + posf1 + " " + posf2); - - if ((posf1 & 1)) { // New position - state.status = AP_GPS::GPS_OK_FIX_3D; - if ((posf2 & 1)) { // Differential position - state.status = AP_GPS::GPS_OK_FIX_3D_DGPS; - if (posf2 & 2) { // Differential position method - if (posf2 & 4) {// Differential position method - state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; - } else { - state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT; - } - } - } + // TODO should we pack time data if there is no fix? + state.time_week_ms = pos_time.time_week_ms; + state.time_week = pos_time.time_week; + state.num_sats = pos_time.num_sats; + + if ((pos_time.pos_flags1 & 1)) { // New position + state.status = AP_GPS::GPS_OK_FIX_3D; + if ((pos_time.pos_flags2 & 1)) { // Differential position + state.status = AP_GPS::GPS_OK_FIX_3D_DGPS; + if (pos_time.pos_flags2 & 2) { // Differential position method + if (pos_time.pos_flags2 & 4) {// Differential position method + state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } else { - state.status = AP_GPS::NO_FIX; - } - valid++; - } - else if (output_type == 2) // position - { - // This packet is not documented in Trimble's receiver help as of May 18, 2023 - state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(msg.data, a)) * (double)1e7); - state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(msg.data, a + 8)) * (double)1e7); - state.location.alt = (int32_t)(SwapDouble(msg.data, a + 16) * 100); - - state.last_gps_time_ms = AP_HAL::millis(); - - valid++; - } - else if (output_type == 8) // velocity - { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Velocity.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____32 - const uint8_t vflag = msg.data[a]; - if ((vflag & 1) == 1) - { - state.ground_speed = SwapFloat(msg.data, a + 1); - state.ground_course = degrees(SwapFloat(msg.data, a + 5)); - fill_3d_velocity(); - state.velocity.z = -SwapFloat(msg.data, a + 9); - state.have_vertical_velocity = true; + state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT; } - valid++; } - else if (output_type == 9) //dop - { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 - state.hdop = (uint16_t)(SwapFloat(msg.data, a + 4) * 100); - valid++; - } - else if (output_type == 12) // position sigma - { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_SIGMA.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____24 - state.horizontal_accuracy = (SwapFloat(msg.data, a + 4) + SwapFloat(msg.data, a + 8)) / 2; - state.vertical_accuracy = SwapFloat(msg.data, a + 16); - state.have_horizontal_accuracy = true; - state.have_vertical_accuracy = true; - valid++; - } - - a += output_length-1u; } + } else { + state.status = AP_GPS::NO_FIX; + } - if (valid == 5) { - return true; - } else { - state.status = AP_GPS::NO_FIX; - } + state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * position.latitude_rad * (double)1e7); + state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * position.longitude_rad * (double)1e7); + state.location.alt = (int32_t)(position.altitude * 100); + state.last_gps_time_ms = AP_HAL::millis(); + + if ((vel.velocity_flags & 1) == 1) { + state.ground_speed = vel.horizontal_velocity; + state.ground_course = wrap_360(degrees(vel.heading)); + fill_3d_velocity(); + state.velocity.z = -vel.vertical_velocity; + state.have_vertical_velocity = true; } - return false; -} + state.hdop = (uint16_t)(dop.hdop * 100); + state.vdop = (uint16_t)(dop.vdop * 100); -bool -AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const { - switch(com_port) { - case static_cast(HW_Port::COM1): - case static_cast(HW_Port::COM2): - return true; - default: - return false; - } + state.horizontal_accuracy = (pos_sigma.sigma_east + pos_sigma.sigma_north) / 2; + state.vertical_accuracy = pos_sigma.sigma_up; + state.have_horizontal_accuracy = true; + state.have_vertical_accuracy = true; } - #endif diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index c1bf4a3fbd6d7b..7a10bc6dd5e28d 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -22,9 +22,10 @@ #include "AP_GPS.h" #include "GPS_Backend.h" +#include #if AP_GPS_GSOF_ENABLED -class AP_GPS_GSOF : public AP_GPS_Backend +class AP_GPS_GSOF : public AP_GPS_Backend, public AP_GSOF { public: AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); @@ -56,9 +57,6 @@ class AP_GPS_GSOF : public AP_GPS_Backend FREQ_100_HZ = 16, }; - bool parse(const uint8_t temp) WARN_IF_UNUSED; - bool process_message() WARN_IF_UNUSED; - // Send a request to the GPS to set the baud rate on the specified port. // Note - these request functions currently ignore the ACK from the device. // If the device is already sending serial traffic, there is no mechanism to prevent conflict. @@ -67,43 +65,10 @@ class AP_GPS_GSOF : public AP_GPS_Backend // Send a request to the GPS to enable a message type on the port at the specified rate. void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz); - double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; - float SwapFloat(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; - uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; - uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; - bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED; bool validate_com_port(const uint8_t com_port) const WARN_IF_UNUSED; - struct Msg_Parser - { - - enum class State - { - STARTTX = 0, - STATUS, - PACKETTYPE, - LENGTH, - DATA, - CHECKSUM, - ENDTX - }; - - State state; - - uint8_t status; - uint8_t packettype; - uint8_t length; - uint8_t data[256]; - uint8_t checksum; - uint8_t endtx; - - uint16_t read; - uint8_t checksumcalc; - } msg; - - static const uint8_t STX = 0x02; - static const uint8_t ETX = 0x03; + void pack_state_data(); uint8_t packetcount; uint32_t gsofmsg_time; diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index d5c3f4925ea888..2a059af35b0181 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -47,6 +47,11 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg) mavlink_gps_input_t packet; mavlink_msg_gps_input_decode(&msg, &packet); + // check if target instance belongs to incoming gps data. + if (state.instance != packet.gps_id) { + return; + } + bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0); bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0); bool have_vdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VDOP) == 0); @@ -138,44 +143,8 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg) state.last_gps_time_ms = now_ms; _new_data = true; break; - } + } - case MAVLINK_MSG_ID_HIL_GPS: { - mavlink_hil_gps_t packet; - mavlink_msg_hil_gps_decode(&msg, &packet); - - state.time_week = 0; - state.time_week_ms = packet.time_usec/1000; - state.status = (AP_GPS::GPS_Status)packet.fix_type; - - Location loc = {}; - loc.lat = packet.lat; - loc.lng = packet.lon; - loc.alt = packet.alt * 0.1f; - state.location = loc; - state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP); - state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP); - if (packet.vel < 65535) { - state.ground_speed = packet.vel * 0.01f; - } - Vector3f vel(packet.vn*0.01f, packet.ve*0.01f, packet.vd*0.01f); - state.velocity = vel; - if (packet.vd != 0) { - state.have_vertical_velocity = true; - } - if (packet.cog < 36000) { - state.ground_course = packet.cog * 0.01f; - } - state.have_speed_accuracy = false; - state.have_horizontal_accuracy = false; - state.have_vertical_accuracy = false; - if (packet.satellites_visible < 255) { - state.num_sats = packet.satellites_visible; - } - state.last_gps_time_ms = AP_HAL::millis(); - _new_data = true; - break; - } default: // ignore all other messages break; diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index e03640188a7791..db43f108ab294d 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -176,8 +176,8 @@ AP_GPS_NOVA::parse(uint8_t temp) nova_msg.crc += (uint32_t) (temp << 24); nova_msg.nova_state = nova_msg_parser::PREAMBLE1; - uint32_t crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.headerlength, (uint8_t *)&nova_msg.header.data, (uint32_t)0); - crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.messagelength, (uint8_t *)&nova_msg.data, crc); + uint32_t crc = crc_crc32((uint32_t)0, (uint8_t *)&nova_msg.header.data, (uint32_t)nova_msg.header.nova_headeru.headerlength); + crc = crc_crc32(crc, (uint8_t *)&nova_msg.data, (uint32_t)nova_msg.header.nova_headeru.messagelength); if (nova_msg.crc == crc) { return process_message(); @@ -293,25 +293,4 @@ AP_GPS_NOVA::process_message(void) return false; } -#define CRC32_POLYNOMIAL 0xEDB88320L -uint32_t AP_GPS_NOVA::CRC32Value(uint32_t icrc) -{ - int i; - uint32_t crc = icrc; - for ( i = 8 ; i > 0; i-- ) { - if ( crc & 1 ) - crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL; - else - crc >>= 1; - } - return crc; -} - -uint32_t AP_GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) -{ - while ( length-- != 0 ) { - crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff)); - } - return( crc ); -} #endif diff --git a/libraries/AP_GPS/AP_GPS_NOVA.h b/libraries/AP_GPS/AP_GPS_NOVA.h index 6f10806af5572a..4f60dff2fd5fe5 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.h +++ b/libraries/AP_GPS/AP_GPS_NOVA.h @@ -39,8 +39,6 @@ class AP_GPS_NOVA : public AP_GPS_Backend bool parse(uint8_t temp); bool process_message(); - uint32_t CRC32Value(uint32_t icrc); - uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc); static const uint8_t NOVA_PREAMBLE1 = 0xaa; static const uint8_t NOVA_PREAMBLE2 = 0x44; diff --git a/libraries/AP_GPS/AP_GPS_Params.cpp b/libraries/AP_GPS/AP_GPS_Params.cpp index 7f227dbace6191..1ee7bb46a86d70 100644 --- a/libraries/AP_GPS/AP_GPS_Params.cpp +++ b/libraries/AP_GPS/AP_GPS_Params.cpp @@ -25,7 +25,7 @@ const AP_Param::GroupInfo AP_GPS::Params::var_info[] = { // @Param: TYPE // @DisplayName: GPS type // @Description: GPS type - // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna + // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:Septentrio(SBF),11:Trimble(GSOF),13:ERB,14:MAVLink,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:Septentrio-DualAntenna(SBF) // @RebootRequired: True // @User: Advanced AP_GROUPINFO_FLAGS("TYPE", 1, AP_GPS::Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index e5a102998bf96f..d771e439b338a9 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -138,6 +138,19 @@ AP_GPS_SBF::read(void) config_string = nullptr; } break; + case Config_State::Constellation: + if ((params.gnss_mode&0x6F)!=0) { + //IMES not taken into account by Septentrio receivers + if (asprintf(&config_string, "sst, %s%s%s%s%s%s\n", (params.gnss_mode&(1U<<0))!=0 ? "GPS" : "", + (params.gnss_mode&(1U<<1))!=0 ? ((params.gnss_mode&0x01)==0 ? "SBAS" : "+SBAS") : "", + (params.gnss_mode&(1U<<2))!=0 ? ((params.gnss_mode&0x03)==0 ? "GALILEO" : "+GALILEO") : "", + (params.gnss_mode&(1U<<3))!=0 ? ((params.gnss_mode&0x07)==0 ? "BEIDOU" : "+BEIDOU") : "", + (params.gnss_mode&(1U<<5))!=0 ? ((params.gnss_mode&0x0F)==0 ? "QZSS" : "+QZSS") : "", + (params.gnss_mode&(1U<<6))!=0 ? ((params.gnss_mode&0x2F)==0 ? "GLONASS" : "+GLONASS") : "") == -1) { + config_string=nullptr; + } + } + break; case Config_State::Blob: if (asprintf(&config_string, "%s\n", _initialisation_blob[_init_blob_index]) == -1) { config_string = nullptr; @@ -364,6 +377,9 @@ AP_GPS_SBF::parse(uint8_t temp) config_step = Config_State::SSO; break; case Config_State::SSO: + config_step = Config_State::Constellation; + break; + case Config_State::Constellation: config_step = Config_State::Blob; break; case Config_State::Blob: @@ -407,6 +423,15 @@ AP_GPS_SBF::parse(uint8_t temp) return false; } +static bool is_DNU(double value) +{ + constexpr double DNU = -2e-10f; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values + return value != DNU; +#pragma GCC diagnostic pop +} + bool AP_GPS_SBF::process_message(void) { @@ -450,9 +475,13 @@ AP_GPS_SBF::process_message(void) if (temp.Latitude > -200000) { 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.have_undulation = true; - state.undulation = -temp.Undulation; - set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f); + state.have_undulation = !is_DNU(temp.Undulation); + double height = temp.Height; // in metres + if (state.have_undulation) { + height -= temp.Undulation; + state.undulation = -temp.Undulation; + } + set_alt_amsl_cm(state, (float)height * 1e2f); // m -> cm } state.num_sats = temp.NrSV; @@ -654,7 +683,7 @@ void AP_GPS_SBF::broadcast_configuration_failure_reason(void) const bool AP_GPS_SBF::is_configured (void) const { return ((gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) || - (config_step == Config_State::Complete)); + (config_step == Config_State::Complete) ||AP_SIM_GPS_SBF_ENABLED); } bool AP_GPS_SBF::is_healthy (void) const { @@ -699,4 +728,5 @@ bool AP_GPS_SBF::prepare_for_arming(void) { return is_logging; } + #endif diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index 8817653f42ed74..b4e1bb28c62b1e 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -76,6 +76,7 @@ class AP_GPS_SBF : public AP_GPS_Backend Blob, SBAS, SGA, + Constellation, Complete }; Config_State config_step; diff --git a/libraries/AP_GPS/AP_GPS_SITL.cpp b/libraries/AP_GPS/AP_GPS_SITL.cpp index e671ce05f5e9be..c423983adf3d9f 100644 --- a/libraries/AP_GPS/AP_GPS_SITL.cpp +++ b/libraries/AP_GPS/AP_GPS_SITL.cpp @@ -21,6 +21,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 179c5d34d482e7..f4b665b7cdbb95 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -100,12 +100,6 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_HAL::UARTDriver *_port, AP_GPS::GPS_Role _role) : AP_GPS_Backend(_gps, _params, _state, _port), - _next_message(STEP_PVT), - _ublox_port(255), - _unconfigured_messages(CONFIG_ALL), - _hardware_generation(UBLOX_UNKNOWN_HARDWARE_GENERATION), - next_fix(AP_GPS::NO_FIX), - noReceivedHdop(true), role(_role) { // stop any config strings that are pending @@ -120,7 +114,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, #if GPS_MOVING_BASELINE if (role == AP_GPS::GPS_ROLE_MB_BASE && !mb_use_uart2()) { - rtcm3_parser = new RTCM3_Parser; + rtcm3_parser = NEW_NOTHROW RTCM3_Parser; if (rtcm3_parser == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "u-blox %d: failed RTCMv3 parser allocation", state.instance + 1); } @@ -334,6 +328,12 @@ AP_GPS_UBLOX::_request_next_config(void) } break; case STEP_POLL_GNSS: + if (supports_F9_config()) { + if (last_configured_gnss != params.gnss_mode) { + _unconfigured_messages |= CONFIG_F9; + } + break; + } if (!_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0)) { _next_message--; } @@ -455,7 +455,43 @@ AP_GPS_UBLOX::_request_next_config(void) #endif break; + case STEP_F9: { + if (_hardware_generation == UBLOX_F9) { + uint8_t cfg_count = populate_F9_gnss(); + // special handling of F9 config + if (cfg_count > 0) { + CFG_Debug("Sending F9 settings, GNSS=%u", params.gnss_mode); + + if (!_configure_list_valset(config_GNSS, cfg_count, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) { + _next_message--; + break; + } + _f9_config_time = AP_HAL::millis(); + } + } + break; + } + case STEP_F9_VALIDATE: { + if (_hardware_generation == UBLOX_F9) { + // GNSS takes 0.5s to reset + if (AP_HAL::millis() - _f9_config_time < 500) { + _next_message--; + break; + } + _f9_config_time = 0; + uint8_t cfg_count = populate_F9_gnss(); + // special handling of F9 config + if (cfg_count > 0) { + CFG_Debug("Validating F9 settings, GNSS=%u", params.gnss_mode); + // now validate all of the settings, this is a no-op if the first call succeeded + if (!_configure_config_set(config_GNSS, cfg_count, CONFIG_F9, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) { + _next_message--; + } + } + } + break; + } case STEP_M10: { if (_hardware_generation == UBLOX_M10) { // special handling of M10 config @@ -1029,6 +1065,7 @@ AP_GPS_UBLOX::_parse_gps(void) _unconfigured_messages &= ~CONFIG_TP5; break; } + break; case CLASS_MON: switch(_buffer.ack.msgID) { @@ -1046,6 +1083,7 @@ AP_GPS_UBLOX::_parse_gps(void) case CLASS_CFG: switch(_buffer.nack.msgID) { case MSG_CFG_VALGET: + CFG_Debug("NACK VALGET 0x%x", (unsigned)_buffer.nack.msgID); if (active_config.list != nullptr) { /* likely this device does not support fetching multiple keys at once, go one at a time @@ -1072,6 +1110,15 @@ AP_GPS_UBLOX::_parse_gps(void) } } break; + case MSG_CFG_VALSET: + CFG_Debug("NACK VALSET 0x%x 0x%x", (unsigned)_buffer.nack.msgID, + unsigned(active_config.list[active_config.set_index].key)); + if (is_gnss_key(active_config.list[active_config.set_index].key)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "GPS %u: unable to configure band 0x%02x", + unsigned(state.instance + 1), unsigned(active_config.list[active_config.set_index].key)); + + } + break; } } } @@ -1114,7 +1161,7 @@ AP_GPS_UBLOX::_parse_gps(void) #if UBLOX_GNSS_SETTINGS case MSG_CFG_GNSS: - if (params.gnss_mode != 0) { + if (params.gnss_mode != 0 && !supports_F9_config()) { struct ubx_cfg_gnss start_gnss = _buffer.gnss; uint8_t gnssCount = 0; Debug("Got GNSS Settings %u %u %u %u:\n", @@ -1290,12 +1337,16 @@ AP_GPS_UBLOX::_parse_gps(void) // see if it is in active config list int8_t cfg_idx = find_active_config_index(id); if (cfg_idx >= 0) { + CFG_Debug("valset(0x%lx): %u", uint32_t(id), (*cfg_data) & 0x1); 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) { + if (cfg_len < key_size + // for keys of length 1 only the LSB is significant + || (key_size == 1 && (active_config.list[cfg_idx].value & 0x1) != (*cfg_data & 0x1)) + || memcmp(&active_config.list[cfg_idx].value, cfg_data, key_size) != 0) { _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); + active_config.set_index = cfg_idx; _cfg_needs_save = true; } else { active_config.done_mask |= (1U << cfg_idx); @@ -1318,6 +1369,8 @@ AP_GPS_UBLOX::_parse_gps(void) unsigned(active_config.list[active_config.fetch_index].key)); } } + } else { + CFG_Debug("valget no active config for 0x%lx", (uint32_t)id); } // step over the value @@ -1349,8 +1402,14 @@ AP_GPS_UBLOX::_parse_gps(void) _have_version = true; strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion)); strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion)); + void* mod = memmem(_buffer.mon_ver.extension, sizeof(_buffer.mon_ver.extension), "MOD=", 4); + if (mod != nullptr) { + strncpy(_module, (char*)mod+4, UBLOX_MODULE_LEN-1); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, - "u-blox %d HW: %s SW: %s", + "u-blox %s%s%d HW: %s SW: %s", + _module, mod != nullptr ? " " : "", state.instance + 1, _version.hwVersion, _version.swVersion); @@ -1364,6 +1423,13 @@ AP_GPS_UBLOX::_parse_gps(void) _unconfigured_messages |= CONFIG_TMODE_MODE; } _hardware_generation = UBLOX_F9; + _unconfigured_messages |= CONFIG_F9; + _unconfigured_messages &= ~CONFIG_GNSS; + if (strncmp(_module, "ZED-F9P", UBLOX_MODULE_LEN) == 0) { + _hardware_variant = UBLOX_F9_ZED; + } else if (strncmp(_module, "NEO-F9P", UBLOX_MODULE_LEN) == 0) { + _hardware_variant = UBLOX_F9_NEO; + } } if (strncmp(_version.swVersion, "EXT CORE 4", 10) == 0) { // a M9 @@ -1647,8 +1713,10 @@ AP_GPS_UBLOX::_parse_gps(void) state.hdop = _buffer.pvt.p_dop; state.vdop = _buffer.pvt.p_dop; } - - state.last_gps_time_ms = AP_HAL::millis(); + + if (_buffer.pvt.fix_type >= 2) { + state.last_gps_time_ms = AP_HAL::millis(); + } // time state.time_week_ms = _buffer.pvt.itow; @@ -1763,7 +1831,7 @@ AP_GPS_UBLOX::_parse_gps(void) void AP_GPS_UBLOX::pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us) { - _last_pps_time_us = timestamp_us; + _last_pps_time_us = AP_HAL::micros64(); } void @@ -1866,6 +1934,7 @@ AP_GPS_UBLOX::_configure_valset(ConfigKey key, const void *value, uint8_t layers if (!supports_F9_config()) { return false; } + const uint8_t len = config_key_size(key); struct ubx_cfg_valset msg {}; uint8_t buf[sizeof(msg)+len]; @@ -1939,6 +2008,48 @@ AP_GPS_UBLOX::_configure_config_set(const config_list *list, uint8_t count, uint return _send_message(CLASS_CFG, MSG_CFG_VALGET, buf, sizeof(buf)); } +/* + * configure F9 based key/value pair for a complete configuration set + * + * this method sends all the key/value pairs in a block, but makes no attempt to check + * the results. Sending in a block is necessary for updates such as GNSS where certain + * combinations are invalid and setting one at a time will not produce the correct result + * if the result needs to be validated then a subsequent _configure_config_set() can be + * issued which will get all the values and reset those that are not properly updated. + */ +bool +AP_GPS_UBLOX::_configure_list_valset(const config_list *list, uint8_t count, uint8_t layers) +{ + if (!supports_F9_config()) { + return false; + } + + struct ubx_cfg_valset msg {}; + uint8_t buf[sizeof(msg)+sizeof(config_list)*count]; + if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(buf)+2)) { + return false; + } + msg.version = 1; + msg.layers = layers; + msg.transaction = 0; + uint32_t msg_len = sizeof(msg) - sizeof(msg.key); + memcpy(buf, &msg, msg_len); + + uint8_t* payload = &buf[msg_len]; + for (uint8_t i=0; i1024) @@ -68,6 +69,7 @@ #define UBX_TIMEGPS_VALID_WEEK_MASK 0x2 #define UBLOX_MAX_PORTS 6 +#define UBLOX_MODULE_LEN 9 #define RATE_POSLLH 1 #define RATE_STATUS 1 @@ -99,9 +101,10 @@ #define CONFIG_TMODE_MODE (1<<16) #define CONFIG_RTK_MOVBASE (1<<17) #define CONFIG_TIM_TM2 (1<<18) -#define CONFIG_M10 (1<<19) -#define CONFIG_L5 (1<<20) -#define CONFIG_LAST (1<<21) // this must always be the last bit +#define CONFIG_F9 (1<<19) +#define CONFIG_M10 (1<<20) +#define CONFIG_L5 (1<<21) +#define CONFIG_LAST (1<<22) // this must always be the last bit #define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED) @@ -518,7 +521,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend struct PACKED ubx_mon_ver { char swVersion[30]; char hwVersion[10]; - char extension[50]; // extensions are not enabled + char extension[30*UBLOX_MAX_EXTENSIONS]; // extensions are not enabled }; struct PACKED ubx_nav_svinfo_header { uint32_t itow; @@ -719,6 +722,12 @@ class AP_GPS_UBLOX : public AP_GPS_Backend // flagging state in the driver }; + enum ubx_hardware_variant { + UBLOX_F9_ZED, // comes from MON_VER extension strings + UBLOX_F9_NEO, // comes from MON_VER extension strings + UBLOX_UNKNOWN_HARDWARE_VARIANT = 0xff + }; + enum config_step { STEP_PVT = 0, STEP_NAV_RATE, // poll NAV rate @@ -742,6 +751,8 @@ class AP_GPS_UBLOX : public AP_GPS_Backend STEP_VERSION, STEP_RTK_MOVBASE, // setup moving baseline STEP_TIM_TM2, + STEP_F9, + STEP_F9_VALIDATE, STEP_M10, STEP_L5, STEP_LAST @@ -765,13 +776,16 @@ class AP_GPS_UBLOX : public AP_GPS_Backend uint32_t _last_cfg_sent_time; uint8_t _num_cfg_save_tries; uint32_t _last_config_time; + uint32_t _f9_config_time; uint16_t _delay_time; - uint8_t _next_message; - uint8_t _ublox_port; + uint8_t _next_message { STEP_PVT }; + uint8_t _ublox_port { 255 }; bool _have_version; struct ubx_mon_ver _version; - uint32_t _unconfigured_messages; - uint8_t _hardware_generation; + char _module[UBLOX_MODULE_LEN]; + uint32_t _unconfigured_messages {CONFIG_ALL}; + uint8_t _hardware_generation { UBLOX_UNKNOWN_HARDWARE_GENERATION }; + uint8_t _hardware_variant; uint32_t _last_pvt_itow; uint32_t _last_relposned_itow; uint32_t _last_relposned_ms; @@ -790,16 +804,25 @@ class AP_GPS_UBLOX : public AP_GPS_Backend bool _parse_gps(); // used to update fix between status and position packets - AP_GPS::GPS_Status next_fix; + AP_GPS::GPS_Status next_fix { AP_GPS::NO_FIX }; bool _cfg_needs_save; - bool noReceivedHdop; + bool noReceivedHdop { true }; bool havePvtMsg; + // structure for list of config key/value pairs for + // specific configurations + struct PACKED config_list { + ConfigKey key; + // support up to 4 byte values, assumes little-endian + uint32_t value; + }; + bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate); bool _configure_valset(ConfigKey key, const void *value, uint8_t layers=UBX_VALSET_LAYER_ALL); + bool _configure_list_valset(const config_list *list, uint8_t count, uint8_t layers=UBX_VALSET_LAYER_ALL); bool _configure_valget(ConfigKey key); void _configure_rate(void); void _configure_sbas(bool enable); @@ -828,14 +851,6 @@ class AP_GPS_UBLOX : public AP_GPS_Backend } #endif - // structure for list of config key/value pairs for - // specific configurations - struct PACKED config_list { - ConfigKey key; - // support up to 4 byte values, assumes little-endian - uint32_t value; - }; - // return size of a config key payload uint8_t config_key_size(ConfigKey key) const; @@ -849,6 +864,13 @@ class AP_GPS_UBLOX : public AP_GPS_Backend // return true if GPS is capable of F9 config bool supports_F9_config(void) const; + // is the config key a GNSS key + bool is_gnss_key(ConfigKey key) const; + + // populate config_GNSS for F9P + uint8_t populate_F9_gnss(void); + uint8_t last_configured_gnss; + uint8_t _pps_freq = 1; #ifdef HAL_GPIO_PPS void pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us); @@ -863,6 +885,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend uint32_t unconfig_bit; uint8_t layers; int8_t fetch_index; + int8_t set_index; } active_config; #if GPS_MOVING_BASELINE @@ -882,6 +905,8 @@ class AP_GPS_UBLOX : public AP_GPS_Backend static const config_list config_M10[]; static const config_list config_L5_ovrd_ena[]; static const config_list config_L5_ovrd_dis[]; + // scratch space for GNSS config + config_list* config_GNSS; }; #endif diff --git a/libraries/AP_GPS/AP_GPS_config.h b/libraries/AP_GPS/AP_GPS_config.h index 9aab43a02b88b2..550add0e1fa62d 100644 --- a/libraries/AP_GPS/AP_GPS_config.h +++ b/libraries/AP_GPS/AP_GPS_config.h @@ -15,6 +15,7 @@ #ifndef GPS_MAX_RECEIVERS #define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data #endif + #if !defined(GPS_MAX_INSTANCES) #if GPS_MAX_RECEIVERS > 1 #define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data @@ -26,18 +27,22 @@ #if GPS_MAX_RECEIVERS <= 1 && GPS_MAX_INSTANCES > 1 #error "GPS_MAX_INSTANCES should be 1 for GPS_MAX_RECEIVERS <= 1" #endif - -#if GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS -#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2) -#endif #endif #ifndef AP_GPS_BACKEND_DEFAULT_ENABLED #define AP_GPS_BACKEND_DEFAULT_ENABLED AP_GPS_ENABLED #endif +#if !defined(AP_GPS_BLENDED_ENABLED) && defined(GPS_MAX_INSTANCES) +#define AP_GPS_BLENDED_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS +#endif + #ifndef AP_GPS_BLENDED_ENABLED -#define AP_GPS_BLENDED_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && defined(GPS_BLENDED_INSTANCE) +#define AP_GPS_BLENDED_ENABLED 0 +#endif + +#if AP_GPS_BLENDED_ENABLED +#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2) #endif #ifndef AP_GPS_DRONECAN_ENABLED @@ -99,3 +104,20 @@ #ifndef HAL_GPS_COM_PORT_DEFAULT #define HAL_GPS_COM_PORT_DEFAULT 1 #endif + + +#ifndef AP_GPS_GPS_RAW_INT_SENDING_ENABLED +#define AP_GPS_GPS_RAW_INT_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED +#endif + +#ifndef AP_GPS_GPS2_RAW_SENDING_ENABLED +#define AP_GPS_GPS2_RAW_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1 +#endif + +#ifndef AP_GPS_GPS_RTK_SENDING_ENABLED +#define AP_GPS_GPS_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED) +#endif + +#ifndef AP_GPS_GPS2_RTK_SENDING_ENABLED +#define AP_GPS_GPS2_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1 && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED) +#endif diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index eb55bd76e433d0..380730a9af6794 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -172,7 +172,7 @@ bool AP_GPS_Backend::should_log() const #endif -#if HAL_GCS_ENABLED +#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) { const uint8_t instance = state.instance; @@ -212,7 +212,8 @@ void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) break; } } -#endif +#endif // AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED + /* diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 70f4cb36fc2150..2a70a1c57153ea 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -71,7 +71,9 @@ class AP_GPS_Backend #if HAL_GCS_ENABLED //MAVLink methods virtual bool supports_mavlink_gps_rtk_message() const { return false; } +#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED virtual void send_mavlink_gps_rtk(mavlink_channel_t chan); +#endif virtual void handle_msg(const mavlink_message_t &msg) { return ; } #endif diff --git a/libraries/AP_GPS/LogStructure.h b/libraries/AP_GPS/LogStructure.h index 5ed1d2794693d3..bb155451ac2040 100644 --- a/libraries/AP_GPS/LogStructure.h +++ b/libraries/AP_GPS/LogStructure.h @@ -23,7 +23,7 @@ // @Field: GMS: milliseconds since start of GPS Week // @Field: GWk: weeks since 5 Jan 1980 // @Field: NSats: number of satellites visible -// @Field: HDop: horizontal precision +// @Field: HDop: horizontal dilution of precision // @Field: Lat: latitude // @Field: Lng: longitude // @Field: Alt: altitude @@ -55,7 +55,7 @@ struct PACKED log_GPS { // @Description: GPS accuracy information // @Field: I: GPS instance number // @Field: TimeUS: Time since system startup -// @Field: VDop: vertical degree of procession +// @Field: VDop: vertical dilution of precision // @Field: HAcc: horizontal position accuracy // @Field: VAcc: vertical position accuracy // @Field: SAcc: speed accuracy diff --git a/libraries/AP_GPS/MovingBase.cpp b/libraries/AP_GPS/MovingBase.cpp index 3ce55c6d82ad7d..9a2143bfff952c 100644 --- a/libraries/AP_GPS/MovingBase.cpp +++ b/libraries/AP_GPS/MovingBase.cpp @@ -3,7 +3,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = { // @Param: TYPE // @DisplayName: Moving base type - // @Description: Controls the type of moving base used if using moving base. + // @Description: Controls the type of moving base used if using moving base.This is renamed in 4.6 and later to GPSx_MB_TYPE. // @Values: 0:Relative to alternate GPS instance,1:RelativeToCustomBase // @User: Advanced // @RebootRequired: True @@ -11,7 +11,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = { // @Param: OFS_X // @DisplayName: Base antenna X position offset - // @Description: X position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive X is forward of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer. + // @Description: X position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive X is forward of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.This is renamed in 4.6 and later to GPSx_MB_OFS_X. // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -19,7 +19,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = { // @Param: OFS_Y // @DisplayName: Base antenna Y position offset - // @Description: Y position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Y is to the right of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Y position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Y is to the right of the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.This is renamed in 4.6 and later to GPSx_MB_OFS_Y. // @Units: m // @Range: -5 5 // @Increment: 0.01 @@ -27,7 +27,7 @@ const AP_Param::GroupInfo MovingBase::var_info[] = { // @Param: OFS_Z // @DisplayName: Base antenna Z position offset - // @Description: Z position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Z is down from the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer. + // @Description: Z position of the base (primary) GPS antenna in body frame from the position of the 2nd antenna. Positive Z is down from the 2nd antenna. Use antenna phase centroid location if provided by the manufacturer.This is renamed in 4.6 and later to GPSx_MB_OFS_Z. // @Units: m // @Range: -5 5 // @Increment: 0.01 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 278b0ee3e569cb..5eb2b45ae6d2bb 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 @@ -33,8 +33,10 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); //Declare "hal" static AP_BoardConfig board_config; +#if AP_NOTIFY_GPIO_LED_3_ENABLED // create board led object AP_BoardLED board_led; +#endif // create fake gcs object GCS_Dummy _gcs; //gcs stands for Ground Control Station @@ -61,8 +63,10 @@ void setup() board_config.init(); +#if AP_NOTIFY_GPIO_LED_3_ENABLED // Initialise the leds board_led.init(); +#endif // Initialize the UART for GPS system serial_manager.init(); diff --git a/libraries/AP_GSOF/AP_GSOF.cpp b/libraries/AP_GSOF/AP_GSOF.cpp new file mode 100644 index 00000000000000..f60fb37207e7d3 --- /dev/null +++ b/libraries/AP_GSOF/AP_GSOF.cpp @@ -0,0 +1,197 @@ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + +#include "AP_GSOF_config.h" +#include "AP_GSOF.h" + +#if AP_GSOF_ENABLED + + + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define gsof_DEBUGGING 0 + +#if gsof_DEBUGGING +# define Debug(fmt, args ...) \ +do { \ + hal.console->printf("%s:%d: " fmt "\n", \ + __FUNCTION__, __LINE__, \ + ## args); \ + hal.scheduler->delay(1); \ +} while(0) +#else +# define Debug(fmt, args ...) +#endif + +int +AP_GSOF::parse(const uint8_t temp, const uint8_t n_expected) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html + switch (msg.state) { + default: + case Msg_Parser::State::STARTTX: + if (temp == STX) { + msg.state = Msg_Parser::State::STATUS; + msg.read = 0; + msg.checksumcalc = 0; + } + break; + case Msg_Parser::State::STATUS: + msg.status = temp; + msg.state = Msg_Parser::State::PACKETTYPE; + msg.checksumcalc += temp; + break; + case Msg_Parser::State::PACKETTYPE: + msg.packettype = temp; + msg.state = Msg_Parser::State::LENGTH; + msg.checksumcalc += temp; + break; + case Msg_Parser::State::LENGTH: + msg.length = temp; + msg.state = Msg_Parser::State::DATA; + msg.checksumcalc += temp; + break; + case Msg_Parser::State::DATA: + msg.data[msg.read] = temp; + msg.read++; + msg.checksumcalc += temp; + if (msg.read >= msg.length) { + msg.state = Msg_Parser::State::CHECKSUM; + } + break; + case Msg_Parser::State::CHECKSUM: + msg.checksum = temp; + msg.state = Msg_Parser::State::ENDTX; + if (msg.checksum == msg.checksumcalc) { + const auto n_processed = process_message(); + if (n_processed != n_expected ) { + return UNEXPECTED_NUM_GSOF_PACKETS; + } + return n_processed; + } + break; + case Msg_Parser::State::ENDTX: + msg.endtx = temp; + msg.state = Msg_Parser::State::STARTTX; + break; + } + + return NO_GSOF_DATA; +} + +int +AP_GSOF::process_message(void) +{ + if (msg.packettype == 0x40) { // GSOF + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 +#if gsof_DEBUGGING + const uint8_t trans_number = msg.data[0]; + const uint8_t pageidx = msg.data[1]; + const uint8_t maxpageidx = msg.data[2]; + + Debug("GSOF page: %u of %u (trans_number=%u)", + pageidx, maxpageidx, trans_number); +#endif + + // This counts up the number of received packets. + int valid = 0; + + // want 1 2 8 9 12 + for (uint32_t a = 3; a < msg.length; a++) { + const uint8_t output_type = msg.data[a]; + a++; + const uint8_t output_length = msg.data[a]; + a++; + // TODO handle corruption on output_length causing buffer overrun? + + switch (output_type) { + case POS_TIME: + parse_pos_time(a); + valid++; + break; + case POS: + parse_pos(a); + valid++; + break; + case VEL: + parse_vel(a); + valid++; + break; + case DOP: + parse_dop(a); + valid++; + break; + case POS_SIGMA: + parse_pos_sigma(a); + valid++; + break; + default: + break; + } + + a += output_length - 1u; + } + + return valid; + } + + // No GSOF packets. + return NO_GSOF_DATA; +} + +void AP_GSOF::parse_pos_time(uint32_t a) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 + pos_time.time_week_ms = be32toh_ptr(msg.data + a); + pos_time.time_week = be32toh_ptr(msg.data + a + 4); + pos_time.num_sats = msg.data[a + 6]; + pos_time.pos_flags1 = msg.data[a + 7]; + pos_time.pos_flags2 = msg.data[a + 8]; +} + +void AP_GSOF::parse_pos(uint32_t a) +{ + // This packet is not documented in Trimble's receiver help as of May 18, 2023 + position.latitude_rad = be64todouble_ptr(msg.data, a); + position.longitude_rad = be64todouble_ptr(msg.data, a + 8); + position.altitude = be64todouble_ptr(msg.data, a + 16); +} + +void AP_GSOF::parse_vel(uint32_t a) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Velocity.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____32 + vel.velocity_flags = msg.data[a]; + + constexpr uint8_t BIT_VELOCITY_VALID = 0; + if (BIT_IS_SET(vel.velocity_flags, BIT_VELOCITY_VALID)) { + vel.horizontal_velocity = be32tofloat_ptr(msg.data, a + 1); + vel.vertical_velocity = be32tofloat_ptr(msg.data, a + 9); + } + + constexpr uint8_t BIT_HEADING_VALID = 2; + if (BIT_IS_SET(vel.velocity_flags, BIT_HEADING_VALID)) { + vel.heading = be32tofloat_ptr(msg.data, a + 5); + } +} + +void AP_GSOF::parse_dop(uint32_t a) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 + // Skip pdop. + dop.hdop = be32tofloat_ptr(msg.data, a + 4); +} + +void AP_GSOF::parse_pos_sigma(uint32_t a) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_SIGMA.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____24 + // Skip pos_rms + pos_sigma.sigma_east = be32tofloat_ptr(msg.data, a + 4); + pos_sigma.sigma_north = be32tofloat_ptr(msg.data, a + 8); + pos_sigma.sigma_up = be32tofloat_ptr(msg.data, a + 16); +} +#endif // AP_GSOF_ENABLED + diff --git a/libraries/AP_GSOF/AP_GSOF.h b/libraries/AP_GSOF/AP_GSOF.h new file mode 100644 index 00000000000000..1aeda025643879 --- /dev/null +++ b/libraries/AP_GSOF/AP_GSOF.h @@ -0,0 +1,131 @@ +// Trimble GSOF protocol parser library. + +#pragma once + +#include "AP_GSOF_config.h" + +#if AP_GSOF_ENABLED + +class AP_GSOF +{ +public: + + static constexpr int NO_GSOF_DATA = 0; + static constexpr int UNEXPECTED_NUM_GSOF_PACKETS = -1; + + // Parse a single byte into the buffer. + // When enough data has arrived, it returns the number of GSOF packets parsed in the GENOUT packet. + // If an unexpected number of GSOF packets were parsed, returns UNEXPECTED_NUM_GSOF_PACKETS. + // This means there is no fix. + // If it returns NO_GSOF_DATA, the parser just needs more data. + int parse(const uint8_t temp, const uint8_t n_expected) WARN_IF_UNUSED; + + // GSOF packet numbers. + enum msg_idx_t { + POS_TIME = 1, + POS = 2, + VEL = 8, + DOP = 9, + POS_SIGMA = 12 + }; + + // GSOF1 + struct PACKED pos_time_t { + uint32_t time_week_ms; + uint16_t time_week; + uint16_t num_sats; + uint8_t pos_flags1; + uint8_t pos_flags2; + uint8_t initialized_number; + }; + + pos_time_t pos_time; + + // GSOF2 + struct PACKED pos_t { + // [rad] + double latitude_rad; + // [rad] + double longitude_rad; + // [m] + double altitude; + }; + pos_t position; + + // GSOF8 + struct PACKED vel_t { + uint8_t velocity_flags; + float horizontal_velocity; + // True north, WGS-84 [rad]. Actually ground course, just mislabeled in the docs. + float heading; + // Stored in the direction from GSOF (up = positive). + float vertical_velocity; + // These bytes are included only if a local coordinate system is loaded. + float local_heading; + }; + vel_t vel; + + // GSOF9 + struct PACKED dop_t { + float pdop; + float hdop; + float vdop; + float tdop; + }; + dop_t dop; + + // GSOF12 + struct PACKED pos_sigma_t { + float pos_rms; + float sigma_east; + float sigma_north; + float cov_east_north; + float sigma_up; + float semi_major_axis; + float semi_minor_axis; + float orientation; + float unit_variance; + uint16_t num_epochs; + }; + pos_sigma_t pos_sigma; + +private: + + // Parses current data and returns the number of parsed GSOF messages. + int process_message() WARN_IF_UNUSED; + + void parse_pos_time(uint32_t a); + void parse_pos(uint32_t a); + void parse_vel(uint32_t a); + void parse_dop(uint32_t a); + void parse_pos_sigma(uint32_t a); + + struct Msg_Parser { + + enum class State { + STARTTX = 0, + STATUS, + PACKETTYPE, + LENGTH, + DATA, + CHECKSUM, + ENDTX + }; + + State state {State::STARTTX}; + + uint8_t status; + uint8_t packettype; + uint8_t length; + uint8_t data[256]; + uint8_t checksum; + uint8_t endtx; + uint8_t read; + + uint8_t checksumcalc; + } msg; + + static const uint8_t STX = 0x02; + static const uint8_t ETX = 0x03; +}; +#endif // AP_GSOF_ENABLED diff --git a/libraries/AP_GSOF/AP_GSOF_config.h b/libraries/AP_GSOF/AP_GSOF_config.h new file mode 100644 index 00000000000000..a44e7ff407f5f2 --- /dev/null +++ b/libraries/AP_GSOF/AP_GSOF_config.h @@ -0,0 +1,9 @@ +#pragma once + +#include +#include + +#ifndef AP_GSOF_ENABLED +#define AP_GSOF_ENABLED 1 +#endif + diff --git a/libraries/AP_GSOF/tests/README.md b/libraries/AP_GSOF/tests/README.md new file mode 100644 index 00000000000000..684c3174743aa5 --- /dev/null +++ b/libraries/AP_GSOF/tests/README.md @@ -0,0 +1,3 @@ +# GSOF Tests + +A UDP packet of binary GSOF data is attached in the `gsof_data` file. diff --git a/libraries/AP_GSOF/tests/gsof_gps.dat b/libraries/AP_GSOF/tests/gsof_gps.dat new file mode 100644 index 00000000000000..8b856f475e4895 Binary files /dev/null and b/libraries/AP_GSOF/tests/gsof_gps.dat differ diff --git a/libraries/AP_GSOF/tests/test_gsof.cpp b/libraries/AP_GSOF/tests/test_gsof.cpp new file mode 100644 index 00000000000000..549b9169c3eec4 --- /dev/null +++ b/libraries/AP_GSOF/tests/test_gsof.cpp @@ -0,0 +1,41 @@ +// Tests for the GSOF parser. +// * ./waf tests +// * ./build/sitl/tests/test_gsof + + +#include + +#include + +#include +#include + +const AP_HAL::HAL &hal = AP_HAL::get_HAL(); + + +TEST(AP_GSOF, incomplete_packet) +{ + AP_GSOF gsof; + EXPECT_FALSE(gsof.parse(0, 5)); +} + +TEST(AP_GSOF, packet1) +{ + GTEST_SKIP() << "There is not yet a convention for loading in a data file in a cross-platform way in AP for unit tests"; + FILE* fp = std::fopen("libraries/AP_GSOF/tests/gsof_gps.dat", "rb"); + EXPECT_NE(fp, nullptr); + AP_GSOF gsof; + char c = 0; + bool parsed = false; + while (c != EOF) { + c = fgetc (fp); + parsed |= gsof.parse((uint8_t)c, 5); + } + + EXPECT_TRUE(parsed); + + fclose(fp); + +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_GSOF/tests/wscript b/libraries/AP_GSOF/tests/wscript new file mode 100644 index 00000000000000..a11f1fe06096b1 --- /dev/null +++ b/libraries/AP_GSOF/tests/wscript @@ -0,0 +1,7 @@ +#!/usr/bin/env python3 + +def build(bld): + bld.ap_find_tests( + use='ap', + ) + diff --git a/libraries/AP_Generator/AP_Generator.cpp b/libraries/AP_Generator/AP_Generator.cpp index d5cfca045d2d79..f1906bdc8fb503 100644 --- a/libraries/AP_Generator/AP_Generator.cpp +++ b/libraries/AP_Generator/AP_Generator.cpp @@ -67,19 +67,19 @@ void AP_Generator::init() #if AP_GENERATOR_IE_650_800_ENABLED case Type::IE_650_800: - _driver_ptr = new AP_Generator_IE_650_800(*this); + _driver_ptr = NEW_NOTHROW AP_Generator_IE_650_800(*this); break; #endif #if AP_GENERATOR_IE_2400_ENABLED case Type::IE_2400: - _driver_ptr = new AP_Generator_IE_2400(*this); + _driver_ptr = NEW_NOTHROW AP_Generator_IE_2400(*this); break; #endif #if AP_GENERATOR_RICHENPOWER_ENABLED case Type::RICHENPOWER: - _driver_ptr = new AP_Generator_RichenPower(*this); + _driver_ptr = NEW_NOTHROW AP_Generator_RichenPower(*this); break; #endif } diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index 21725b932c251d..7a13bed22e5742 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -43,11 +43,9 @@ void AP_Generator_IE_FuelCell::update() const uint32_t now = AP_HAL::millis(); // Read any available data - uint32_t nbytes = MIN(_uart->available(),30u); - while (nbytes-- > 0) { - const int16_t c = _uart->read(); - if (c < 0) { - // Nothing to decode + for (uint8_t i=0; i<30; i++) { // process at most n bytes + uint8_t c; + if (!_uart->read(c)) { break; } diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.cpp b/libraries/AP_Generator/AP_Generator_RichenPower.cpp index 6ce1e2fa8525e0..21750784e51a63 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.cpp +++ b/libraries/AP_Generator/AP_Generator_RichenPower.cpp @@ -125,7 +125,7 @@ bool AP_Generator_RichenPower::get_reading() const uint8_t minor = (version % 100) / 10; const uint8_t point = version % 10; if (!protocol_information_anounced) { - gcs().send_text(MAV_SEVERITY_INFO, "RichenPower: protocol %u.%u.%u", major, minor, point); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RichenPower: protocol %u.%u.%u", major, minor, point); protocol_information_anounced = true; } @@ -212,7 +212,7 @@ void AP_Generator_RichenPower::check_maintenance_required() if (last_reading.errors & (1U< 60000) { - gcs().send_text(MAV_SEVERITY_NOTICE, "Generator: requires maintenance"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Generator: requires maintenance"); last_maintenance_warning_ms = now; } } @@ -267,7 +267,7 @@ void AP_Generator_RichenPower::update_runstate() // because the vehicle is crashed. if (AP::vehicle()->is_crashed()) { if (!vehicle_was_crashed) { - gcs().send_text(MAV_SEVERITY_INFO, "Crash; stopping generator"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Crash; stopping generator"); pilot_desired_runstate = RunState::STOP; vehicle_was_crashed = true; } diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.h b/libraries/AP_Generator/AP_Generator_RichenPower.h index 2fce45e60cc32b..b21c030053ab5d 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.h +++ b/libraries/AP_Generator/AP_Generator_RichenPower.h @@ -68,7 +68,7 @@ class AP_Generator_RichenPower : public AP_Generator_Backend RunState pilot_desired_runstate = RunState::STOP; RunState commanded_runstate = RunState::STOP; // output is based on this void set_pilot_desired_runstate(RunState newstate) { - // gcs().send_text(MAV_SEVERITY_INFO, "RichenPower: Moving to state (%u) from (%u)\n", (unsigned)newstate, (unsigned)runstate); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RichenPower: Moving to state (%u) from (%u)\n", (unsigned)newstate, (unsigned)runstate); pilot_desired_runstate = newstate; } void update_runstate(); diff --git a/libraries/AP_Gripper/AP_Gripper.cpp b/libraries/AP_Gripper/AP_Gripper.cpp index 1fbd9e197ae83a..6c069e603ec0a5 100644 --- a/libraries/AP_Gripper/AP_Gripper.cpp +++ b/libraries/AP_Gripper/AP_Gripper.cpp @@ -113,12 +113,12 @@ void AP_Gripper::init() break; #if AP_GRIPPER_SERVO_ENABLED case 1: - backend = new AP_Gripper_Servo(config); + backend = NEW_NOTHROW AP_Gripper_Servo(config); break; #endif #if AP_GRIPPER_EPM_ENABLED case 2: - backend = new AP_Gripper_EPM(config); + backend = NEW_NOTHROW AP_Gripper_EPM(config); break; #endif default: diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index a2d13897727ba0..9e2ad8956ad2ff 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -104,8 +104,10 @@ 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; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbed"); } else if (config.state == AP_Gripper::STATE_RELEASING && has_state_pwm(config.release_pwm)) { config.state = AP_Gripper::STATE_RELEASED; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load released"); } } diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 308c9e598ab188..54c47dc6caa1f3 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -259,7 +259,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) } _current_sample_mode = _sample_mode; - _ref_energy = new Vector3f[_window_size]; + _ref_energy = NEW_NOTHROW Vector3f[_window_size]; if (_ref_energy == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to allocate window for AP_GyroFFT"); return; diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.h b/libraries/AP_GyroFFT/AP_GyroFFT.h index 19b501b7193580..115448227b3087 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.h +++ b/libraries/AP_GyroFFT/AP_GyroFFT.h @@ -157,7 +157,7 @@ class AP_GyroFFT } private: - LowPassFilterFloat _lowpass_filter[XYZ_AXIS_COUNT]; + LowPassFilterConstDtFloat _lowpass_filter[XYZ_AXIS_COUNT]; FilterWithBuffer _median_filter[XYZ_AXIS_COUNT]; }; @@ -311,7 +311,7 @@ class AP_GyroFFT // smoothing filter on the bandwidth MedianLowPassFilter3dFloat _center_bandwidth_filter[FrequencyPeak::MAX_TRACKED_PEAKS]; // smoothing filter on the frequency fit - LowPassFilterFloat _harmonic_fit_filter[XYZ_AXIS_COUNT]; + LowPassFilterConstDtFloat _harmonic_fit_filter[XYZ_AXIS_COUNT]; // configured sampling rate uint16_t _fft_sampling_rate_hz; diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 5ba862d7ef177f..26a47e2c8cd995 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -6,16 +6,20 @@ */ #pragma once +// @LoggerEnum: HAL_BOARD #define HAL_BOARD_SITL 3 -#define HAL_BOARD_SMACCM 4 // unused -#define HAL_BOARD_PX4 5 // unused +// #define HAL_BOARD_SMACCM 4 // unused +// #define HAL_BOARD_PX4 5 // unused #define HAL_BOARD_LINUX 7 -#define HAL_BOARD_VRBRAIN 8 +// #define HAL_BOARD_VRBRAIN 8 #define HAL_BOARD_CHIBIOS 10 -#define HAL_BOARD_F4LIGHT 11 // reserved +// #define HAL_BOARD_F4LIGHT 11 // reserved #define HAL_BOARD_ESP32 12 +#define HAL_BOARD_QURT 13 #define HAL_BOARD_EMPTY 99 +// @LoggerEnumEnd +// @LoggerEnum: HAL_BOARD_SUBTYPE /* Default board subtype is -1 */ #define HAL_BOARD_SUBTYPE_NONE -1 @@ -69,6 +73,7 @@ #define HAL_BOARD_SUBTYPE_ESP32_NICK 6006 #define HAL_BOARD_SUBTYPE_ESP32_S3DEVKIT 6007 #define HAL_BOARD_SUBTYPE_ESP32_S3EMPTY 6008 +// @LoggerEnumEnd /* InertialSensor driver types */ #define HAL_INS_NONE 0 @@ -133,12 +138,12 @@ #include #elif CONFIG_HAL_BOARD == HAL_BOARD_EMPTY #include -#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN - #include #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include #elif CONFIG_HAL_BOARD == HAL_BOARD_ESP32 #include +#elif CONFIG_HAL_BOARD == HAL_BOARD_QURT + #include #else #error "Unknown CONFIG_HAL_BOARD type" #endif @@ -163,10 +168,6 @@ #define HAL_NUM_CAN_IFACES 0 #endif -#ifndef HAL_RCINPUT_WITH_AP_RADIO -#define HAL_RCINPUT_WITH_AP_RADIO 0 -#endif - #ifndef HAL_WITH_IO_MCU #define HAL_WITH_IO_MCU 0 #endif @@ -179,11 +180,17 @@ #define HAL_WITH_IO_MCU_DSHOT HAL_WITH_IO_MCU_BIDIR_DSHOT #endif -// this is used as a general mechanism to make a 'small' build by -// dropping little used features. We use this to allow us to keep -// FMUv2 going for as long as possible -#ifndef HAL_MINIMIZE_FEATURES -#define HAL_MINIMIZE_FEATURES 0 +#ifndef HAL_REQUIRES_BDSHOT_SUPPORT +#define HAL_REQUIRES_BDSHOT_SUPPORT (defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT) +#endif + +// support for Extended DShot Telemetry v2 is enabled only if any kind of such telemetry +// can in principle arrive, either from servo outputs or from IOMCU + +// if not desired, set to 0 - and if IOMCU has bidirectional DShot enabled, recompile it too, +// otherwise the communication to IOMCU breaks! +#ifndef AP_EXTENDED_DSHOT_TELEM_V2_ENABLED +#define AP_EXTENDED_DSHOT_TELEM_V2_ENABLED HAL_REQUIRES_BDSHOT_SUPPORT #endif #ifndef BOARD_FLASH_SIZE @@ -366,10 +373,16 @@ #ifndef HAL_GPIO_LED_ON #define HAL_GPIO_LED_ON 0 +#elif HAL_GPIO_LED_ON == 0 +#error "Do not specify HAL_GPIO_LED_ON if you are setting it to the default, 0" #endif #ifdef HAL_GPIO_LED_OFF #error "HAL_GPIO_LED_OFF must not be defined, it is implicitly !HAL_GPIO_LED_ON" #endif +#ifndef HAL_WITH_POSTYPE_DOUBLE +#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024 +#endif + #define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON) diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index 7bd1a8ebbda471..74fa742f9cb77f 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -58,9 +58,16 @@ bool AP_HAL::CANFrame::priorityHigherThan(const CANFrame& rhs) const */ int16_t AP_HAL::CANIface::receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags) { - auto cb = frame_callback; - if (cb && (out_flags & IsMAVCAN)==0) { - cb(get_iface_num(), out_frame); + if ((out_flags & IsMAVCAN) != 0) { + return 1; + } +#ifndef HAL_BOOTLOADER_BUILD + WITH_SEMAPHORE(callbacks.sem); +#endif + for (auto &cb : callbacks.cb) { + if (cb != nullptr) { + cb(get_iface_num(), out_frame); + } } return 1; } @@ -70,28 +77,59 @@ int16_t AP_HAL::CANIface::receive(CANFrame& out_frame, uint64_t& out_ts_monotoni */ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags) { - auto cb = frame_callback; - if (cb) { +#ifndef HAL_BOOTLOADER_BUILD + WITH_SEMAPHORE(callbacks.sem); +#endif + bool added_to_rx_queue = false; + for (auto &cb : callbacks.cb) { + if (cb == nullptr) { + continue; + } if ((flags & IsMAVCAN) == 0) { cb(get_iface_num(), frame); - } else { + } else if (!added_to_rx_queue) { CanRxItem rx_item; rx_item.frame = frame; rx_item.timestamp_us = AP_HAL::micros64(); rx_item.flags = AP_HAL::CANIface::IsMAVCAN; add_to_rx_queue(rx_item); + added_to_rx_queue = true; } } return 1; } /* - register a callback for for sending CAN_FRAME messages + register a callback for for sending CAN_FRAME messages. + On success the returned callback_id can be used to unregister the callback + */ +bool AP_HAL::CANIface::register_frame_callback(FrameCb cb, uint8_t &callback_id) +{ +#ifndef HAL_BOOTLOADER_BUILD + WITH_SEMAPHORE(callbacks.sem); +#endif + for (uint8_t i=0; i +#include /* using checked registers allows a device check that a set of critical @@ -44,7 +45,7 @@ bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency) _checked.n_set = 0; _checked.next = 0; } - _checked.regs = new struct checkreg[nregs]; + _checked.regs = NEW_NOTHROW struct checkreg[nregs]; if (_checked.regs == nullptr) { return false; } diff --git a/libraries/AP_HAL/Device.h b/libraries/AP_HAL/Device.h index 95f997138d2cd2..74d2c910a04227 100644 --- a/libraries/AP_HAL/Device.h +++ b/libraries/AP_HAL/Device.h @@ -20,6 +20,12 @@ #include "AP_HAL_Namespace.h" #include "utility/functor.h" +#include "AP_HAL_Boards.h" + +#if CONFIG_HAL_BOARD != HAL_BOARD_QURT +// we need utility for std::move, but not on QURT due to a include error in hexagon SDK +#include +#endif /* * This is an interface abstracting I2C and SPI devices diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index cb71ca5ec833f3..a2bef78e470def 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -55,17 +55,6 @@ class AP_HAL::HAL { AP_HAL::CANIface** _can_ifaces) #endif : - serial_array{ - _serial0, - _serial1, - _serial2, - _serial3, - _serial4, - _serial5, - _serial6, - _serial7, - _serial8, - _serial9}, i2c_mgr(_i2c_mgr), spi(_spi), wspi(_wspi), @@ -78,13 +67,24 @@ class AP_HAL::HAL { scheduler(_scheduler), util(_util), opticalflow(_opticalflow), + flash(_flash), #if HAL_WITH_DSP dsp(_dsp), #endif + serial_array{ + _serial0, + _serial1, + _serial2, + _serial3, + _serial4, + _serial5, + _serial6, + _serial7, + _serial8, + _serial9} #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL - simstate(_simstate), + ,simstate(_simstate) #endif - flash(_flash) { #if HAL_NUM_CAN_IFACES > 0 if (_can_ifaces == nullptr) { diff --git a/libraries/AP_HAL/I2CDevice.h b/libraries/AP_HAL/I2CDevice.h index 841e5575c1d001..1f6e6cf5b4352b 100644 --- a/libraries/AP_HAL/I2CDevice.h +++ b/libraries/AP_HAL/I2CDevice.h @@ -17,7 +17,6 @@ #pragma once #include -#include #include "AP_HAL_Namespace.h" #include "Device.h" @@ -76,20 +75,6 @@ class I2CDeviceManager { uint32_t bus_clock=400000, bool use_smbus = false, uint32_t timeout_ms=4) = 0; - /* - * Get device by looking up the I2C bus on the buses from @devpaths. - * - * Each string in @devpaths are possible locations for the bus. How the - * strings are implemented are HAL-specific. On Linux this is the info - * returned by 'udevadm info -q path /dev/i2c-X'. The first I2C bus - * matching a prefix in @devpaths is used to create a I2CDevice object. - */ - virtual OwnPtr get_device(std::vector devpaths, - uint8_t address) { - // Not implemented - return nullptr; - } - /* get mask of bus numbers for all configured I2C buses */ diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index c4de0473a96f66..68a84b1a10fcd6 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -406,7 +406,7 @@ class AP_HAL::RCOutput { // See WS2812B spec for expected pulse widths static constexpr uint32_t NEOP_BIT_WIDTH_TICKS = 8; - static constexpr uint32_t NEOP_BIT_0_TICKS = 3; + static constexpr uint32_t NEOP_BIT_0_TICKS = 2; static constexpr uint32_t NEOP_BIT_1_TICKS = 6; // neopixel does not use pulse widths at all static constexpr uint32_t PROFI_BIT_0_TICKS = 7; @@ -422,6 +422,6 @@ class AP_HAL::RCOutput { void append_to_banner(char banner_msg[], uint8_t banner_msg_len, output_mode out_mode, uint8_t low_ch, uint8_t high_ch) const; const char* get_output_mode_string(enum output_mode out_mode) const; - uint16_t _esc_pwm_min; - uint16_t _esc_pwm_max; + uint16_t _esc_pwm_min = 1000; + uint16_t _esc_pwm_max = 2000; }; diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index e03cde7a663da6..f5c47834220047 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -12,6 +12,7 @@ #include #include #include +#include #include #include #include @@ -130,7 +131,7 @@ void SIMState::fdm_input_local(void) // output JSON state to ride along flight controllers // ride_along.send(_sitl->state,sitl_model->get_position_relhome()); -#if HAL_SIM_GIMBAL_ENABLED +#if AP_SIM_SOLOGIMBAL_ENABLED if (gimbal != nullptr) { gimbal->update(); } diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index 0c84791f91ea39..f4343475715d2f 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include #include @@ -109,10 +109,10 @@ class AP_HAL::SIMState { // internal SITL model SITL::Aircraft *sitl_model; -#if HAL_SIM_GIMBAL_ENABLED +#if AP_SIM_SOLOGIMBAL_ENABLED // simulated gimbal bool enable_gimbal; - SITL::Gimbal *gimbal; + SITL::SoloGimbal *gimbal; #endif #if HAL_SIM_ADSB_ENABLED diff --git a/libraries/AP_HAL/Scheduler.cpp b/libraries/AP_HAL/Scheduler.cpp index b22d586b76bc7c..92f9e45ffe9629 100644 --- a/libraries/AP_HAL/Scheduler.cpp +++ b/libraries/AP_HAL/Scheduler.cpp @@ -42,8 +42,8 @@ ExpectDelay::~ExpectDelay() */ TimeCheck::TimeCheck(uint32_t _limit_ms, const char *_file, uint32_t _line) : limit_ms(_limit_ms), - file(_file), - line(_line) + line(_line), + file(_file) { start_ms = AP_HAL::millis(); } diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 20e5741ed81ca1..55412be3185c7f 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -165,6 +165,25 @@ uint64_t AP_HAL::UARTDriver::receive_time_constraint_us(uint16_t nbytes) return AP_HAL::micros64(); } +// Helper to check if flow control is enabled given the passed setting +bool AP_HAL::UARTDriver::flow_control_enabled(enum flow_control flow_control_setting) const +{ + switch(flow_control_setting) { + case FLOW_CONTROL_ENABLE: + case FLOW_CONTROL_AUTO: + return true; + case FLOW_CONTROL_DISABLE: + case FLOW_CONTROL_RTS_DE: + break; + } + return false; +} + +uint8_t AP_HAL::UARTDriver::get_parity(void) +{ + return AP_HAL::UARTDriver::parity; +} + #if HAL_UART_STATS_ENABLED // Take cumulative bytes and return the change since last call uint32_t AP_HAL::UARTDriver::StatsTracker::ByteTracker::update(uint32_t bytes) diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index 829d7907b315f4..317ddd1fba5437 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -78,6 +78,9 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { // read buffer from a locked port. If port is locked and key is not correct then -1 is returned ssize_t read_locked(uint8_t *buf, size_t count, uint32_t key) WARN_IF_UNUSED; + + // get current parity for passthrough use + uint8_t get_parity(void); // control optional features virtual bool set_options(uint16_t options) { _last_options = options; return options==0; } @@ -103,10 +106,14 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { FLOW_CONTROL_DISABLE=0, FLOW_CONTROL_ENABLE=1, FLOW_CONTROL_AUTO=2, + FLOW_CONTROL_RTS_DE=3, // RTS pin is used as a driver enable (used in RS-485) }; virtual void set_flow_control(enum flow_control flow_control_setting) {}; virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; } + // Return true if flow control is currently enabled + bool flow_control_enabled() { return flow_control_enabled(get_flow_control()); } + virtual void configure_parity(uint8_t v){}; virtual void set_stop_bits(int n){}; @@ -185,6 +192,9 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { // return true requested baud on USB port virtual uint32_t get_usb_baud(void) const { return 0; } + // return requested parity on USB port + virtual uint8_t get_usb_parity(void) const { return parity; } + // disable TX/RX pins for unusued uart virtual void disable_rxtx(void) const {} @@ -209,6 +219,8 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { uint32_t lock_write_key; uint32_t lock_read_key; + uint8_t parity; + /* backend begin method */ @@ -240,6 +252,9 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { // discard incoming data on the port virtual bool _discard_input(void) = 0; + // Helper to check if flow control is enabled given the passed setting + bool flow_control_enabled(enum flow_control flow_control_setting) const; + #if HAL_UART_STATS_ENABLED // Getters for cumulative tx and rx counts virtual uint32_t get_total_tx_bytes() const { return 0; } diff --git a/libraries/AP_HAL/Util.cpp b/libraries/AP_HAL/Util.cpp index 374fc77c48c675..7b69c58d008a7e 100644 --- a/libraries/AP_HAL/Util.cpp +++ b/libraries/AP_HAL/Util.cpp @@ -9,6 +9,8 @@ #else #include #endif +#include +#include /* Helper class implements AP_HAL::Print so we can use utility/vprintf */ class BufferPrinter : public AP_HAL::BetterStream { diff --git a/libraries/AP_HAL/Util.h b/libraries/AP_HAL/Util.h index da22f1a8be1d99..a4eca9ce2633a3 100644 --- a/libraries/AP_HAL/Util.h +++ b/libraries/AP_HAL/Util.h @@ -5,6 +5,10 @@ #include "AP_HAL_Namespace.h" #include +#ifndef ENABLE_HEAP +#define ENABLE_HEAP 0 +#endif + class ExpandingString; class AP_HAL::Util { @@ -44,11 +48,6 @@ class AP_HAL::Util { // set command line parameters to the eeprom on start virtual void set_cmdline_parameters() {}; - // run a debug shall on the given stream if possible. This is used - // to support dropping into a debug shell to run firmware upgrade - // commands - virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0; - enum safety_state : uint8_t { SAFETY_NONE, SAFETY_DISARMED, @@ -134,11 +133,6 @@ class AP_HAL::Util { virtual bool toneAlarm_init(uint8_t types) { return false;} virtual void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) {} - /* - return a stream for access to a system shell, if available - */ - virtual AP_HAL::BetterStream *get_shell_stream() { return nullptr; } - /* Support for an imu heating system */ virtual void set_imu_temp(float current) {} @@ -154,17 +148,16 @@ class AP_HAL::Util { virtual void *malloc_type(size_t size, Memory_Type mem_type) { return calloc(1, size); } virtual void free_type(void *ptr, size_t size, Memory_Type mem_type) { return free(ptr); } -#ifdef ENABLE_HEAP - // heap functions, note that a heap once alloc'd cannot be dealloc'd - virtual void *allocate_heap_memory(size_t size) = 0; - virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) = 0; +#if ENABLE_HEAP + /* + heap functions used by non-scripting + */ #if USE_LIBC_REALLOC - virtual void *std_realloc(void *ptr, size_t new_size) { return realloc(ptr, new_size); } + virtual void *std_realloc(void *ptr, uint32_t new_size) { return realloc(ptr, new_size); } #else - virtual void *std_realloc(void *ptr, size_t new_size) = 0; + virtual void *std_realloc(void *ptr, uint32_t new_size) = 0; #endif // USE_LIBC_REALLOC -#endif // ENABLE_HEAP - +#endif /** how much free memory do we have in bytes. If unknown return 4096 diff --git a/libraries/AP_HAL/WSPIDevice.h b/libraries/AP_HAL/WSPIDevice.h index 1b4c3a294c5f7e..4ad8e67d84f0d6 100644 --- a/libraries/AP_HAL/WSPIDevice.h +++ b/libraries/AP_HAL/WSPIDevice.h @@ -17,7 +17,6 @@ #pragma once #include -#include #include "AP_HAL_Namespace.h" #include "Device.h" diff --git a/libraries/AP_HAL/board/chibios.h b/libraries/AP_HAL/board/chibios.h index cd0d890810e446..9e5cd5911f5a1b 100644 --- a/libraries/AP_HAL/board/chibios.h +++ b/libraries/AP_HAL/board/chibios.h @@ -4,6 +4,10 @@ #define HAL_BOARD_NAME "ChibiOS" +#ifdef HAL_HAVE_PIXRACER_LED +#error "use AP_NOTIFY_GPIO_LED_RGB_ENABLED in place of HAL_HAVE_PIXRACER_LED (and rename your pins!)" +#endif + #if HAL_MEMORY_TOTAL_KB >= 1000 #define HAL_MEM_CLASS HAL_MEM_CLASS_1000 #elif HAL_MEMORY_TOTAL_KB >= 500 diff --git a/libraries/AP_HAL/board/esp32.h b/libraries/AP_HAL/board/esp32.h index b5990fd237fe33..e927165b8cd25b 100644 --- a/libraries/AP_HAL/board/esp32.h +++ b/libraries/AP_HAL/board/esp32.h @@ -52,6 +52,10 @@ #define __LITTLE_ENDIAN 1234 #define __BYTE_ORDER __LITTLE_ENDIAN +// ArduPilot uses __RAMFUNC__ to place functions in fast instruction RAM +#define __RAMFUNC__ IRAM_ATTR + + // whenver u get ... error: "xxxxxxx" is not defined, evaluates to 0 [-Werror=undef] just define it below as 0 #define CONFIG_SPIRAM_ALLOW_BSS_SEG_EXTERNAL_MEMORY 0 #define XCHAL_ERRATUM_453 0 @@ -116,3 +120,6 @@ // other big things.. #define HAL_QUADPLANE_ENABLED 0 #define HAL_GYROFFT_ENABLED 0 + +// remove once ESP32 isn't so chronically slow +#define AP_SCHEDULER_OVERTIME_MARGIN_US 50000UL diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index 80238c3a56eb93..a7e6c3fc1740ff 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -36,6 +36,7 @@ #define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(MS56XX, "ms5611") #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_PROBE_EXTERNAL_I2C_COMPASSES + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 61 #define HAL_GPIO_B_LED_PIN 48 #define HAL_GPIO_C_LED_PIN 117 @@ -56,6 +57,7 @@ #define HAL_LINUX_HEAT_TARGET_TEMP 50 #define BEBOP_CAMV_PWM 9 #define BEBOP_CAMV_PWM_FREQ 43333333 + #define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP #define HAL_OPTFLOW_ONBOARD_VDEV_PATH "/dev/video0" #define HAL_OPTFLOW_ONBOARD_SUBDEV_PATH "/dev/v4l-subdev0" #define HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH 320 @@ -121,7 +123,9 @@ #define AP_COMPASS_OFFSETS_MAX_DEFAULT 2200 #define HAL_BATT_MONITOR_DEFAULT AP_BattMonitor::Type::BEBOP #define HAL_GPIO_SCRIPT "/data/ftp/internal_000/ardupilot/gpio.sh" + #define AP_NOTIFY_DISCO_LED_ENABLED 1 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 0 #define HAL_GPIO_B_LED_PIN 1 #define HAL_GPIO_C_LED_PIN 2 @@ -138,11 +142,13 @@ #define HAL_MAG_PROBE2 PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_MAG_PROBE_LIST HAL_MAG_PROBE1; HAL_MAG_PROBE2 #define HAL_PROBE_EXTERNAL_I2C_COMPASSES + #define AP_NOTIFY_SYSFS_LED_ENABLED 1 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 #define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensense, "mpu9250", ROTATION_YAW_270) #define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(MS56XX, "ms5611") #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_PROBE_EXTERNAL_I2C_COMPASSES + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 24 #define HAL_GPIO_B_LED_PIN 25 #define HAL_GPIO_C_LED_PIN 16 @@ -158,6 +164,7 @@ #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_PROBE_EXTERNAL_I2C_COMPASSES #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 69 #define HAL_GPIO_B_LED_PIN 68 #define HAL_GPIO_C_LED_PIN 45 @@ -178,14 +185,16 @@ #define HAL_MAG_PROBE1 PROBE_MAG_SPI(MMC5XX3, "mmc5983", false, ROTATION_YAW_180) #define HAL_MAG_PROBE2 PROBE_MAG_I2C(AK09916, 1, 0X0c, false, ROTATION_YAW_270) #define HAL_MAG_PROBE_LIST HAL_MAG_PROBE1; HAL_MAG_PROBE2 - #define HAL_BARO_PROBE_LIST PROBE_BARO_I2C(BMP280, 1, 0x76) + #define HAL_BARO_PROBE_LIST PROBE_BARO_I2C(BMP280, 1, 0x76); PROBE_BARO_I2C(BMP388, 1, 0x76) #define HAL_BARO_EXTERNAL_BUS_DEFAULT 6 #define HAL_PROBE_EXTERNAL_I2C_COMPASSES // I2C6 is the only i2c one exposed on a header #define HAL_LINUX_I2C_EXTERNAL_BUS_MASK 1 << 6 // We don't want any probing on the internal buses #define HAL_LINUX_I2C_INTERNAL_BUS_MASK 0 + #define AP_NOTIFY_NAVIGATOR_LED_ENABLED 1 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE + #define AP_NOTIFY_GPIO_LED_2_ENABLED 1 #define HAL_GPIO_A_LED_PIN 66 #define HAL_GPIO_B_LED_PIN 67 #define HAL_GPIO_LED_ON 1 @@ -197,6 +206,7 @@ #define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 1 #define HAL_NUM_CAN_IFACES 1 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 59 #define HAL_GPIO_B_LED_PIN 58 #define HAL_GPIO_C_LED_PIN 57 @@ -216,9 +226,11 @@ #define HAL_INS_PROBE_LIST HAL_INS_PROBE1; HAL_INS_PROBE2 #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_PROBE_EXTERNAL_I2C_COMPASSES + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 17 #define HAL_GPIO_B_LED_PIN 18 #define HAL_GPIO_C_LED_PIN 22 + #define AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED 1 #define HAL_RCOUT_RGBLED_RED 13 #define HAL_RCOUT_RGBLED_GREEN 14 #define HAL_RCOUT_RGBLED_BLUE 15 @@ -227,6 +239,7 @@ #define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(MS56XX, "ms5611") #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_PROBE_EXTERNAL_I2C_COMPASSES + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 24 #define HAL_GPIO_B_LED_PIN 25 #define HAL_GPIO_C_LED_PIN 16 @@ -243,6 +256,7 @@ #define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensense, "mpu9250", ROTATION_NONE) #define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) #define HAL_BARO_PROBE_LIST PROBE_BARO_I2C(MS56XX, 1, 0x77) + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 24 #define HAL_GPIO_B_LED_PIN 25 #define HAL_GPIO_C_LED_PIN 16 @@ -266,6 +280,7 @@ #define HAL_LINUX_HEAT_PERIOD_NS 2040816 #define HAL_GPS1_TYPE_DEFAULT 9 #define HAL_CAN_DRIVER_DEFAULT 1 + #define AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED 1 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ #define HAL_INS_PROBE_LIST PROBE_IMU_SPI2(Invensense, "rst_g", "rst_a", ROTATION_ROLL_180_YAW_90, ROTATION_ROLL_180_YAW_90) #define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(MS56XX, "ms5611") @@ -278,6 +293,7 @@ #define HAL_PROBE_EXTERNAL_I2C_COMPASSES #define HAL_NUM_CAN_IFACES 1 #define HAL_CAN_DRIVER_DEFAULT 1 + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 22 #define HAL_GPIO_B_LED_PIN 27 #define HAL_GPIO_C_LED_PIN 6 @@ -313,6 +329,7 @@ #ifdef OBAL_NOTIFY_LED + #define AP_NOTIFY_GPIO_LED_3_ENABLED 1 #define HAL_GPIO_A_LED_PIN 27 // You can choose between 27,22,4,12 #define HAL_GPIO_C_LED_PIN 22 // You can choose between 27,22,4,12 #define HAL_GPIO_B_LED_PIN 4 // You can choose between 27,22,4,12 @@ -325,6 +342,10 @@ #error "no Linux board subtype set" #endif +#ifndef BOARD_FLASH_SIZE +#define BOARD_FLASH_SIZE 4096 +#endif + #ifndef HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS #define HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS 0x42 #endif diff --git a/libraries/AP_HAL/board/qurt.h b/libraries/AP_HAL/board/qurt.h new file mode 100644 index 00000000000000..6f48b5fcbd5720 --- /dev/null +++ b/libraries/AP_HAL/board/qurt.h @@ -0,0 +1,110 @@ +#pragma once + +#include + +#define HAL_BOARD_NAME "QURT" +#define HAL_CPU_CLASS HAL_CPU_CLASS_1000 +#define HAL_MEM_CLASS HAL_MEM_CLASS_1000 +#define HAL_STORAGE_SIZE 32768 +#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE + +// only include if compiling C++ code +#ifdef __cplusplus +#include +#define HAL_Semaphore QURT::Semaphore +#define HAL_BinarySemaphore QURT::BinarySemaphore +#endif + +#ifndef HAL_HAVE_HARDWARE_DOUBLE +#define HAL_HAVE_HARDWARE_DOUBLE 0 +#endif + +#ifndef HAL_WITH_EKF_DOUBLE +#define HAL_WITH_EKF_DOUBLE HAL_HAVE_HARDWARE_DOUBLE +#endif + +#ifndef HAL_GYROFFT_ENABLED +#define HAL_GYROFFT_ENABLED 0 +#endif + +/* + disable features for initial port + */ +#define HAL_HAVE_BOARD_VOLTAGE 0 +#define HAL_HAVE_SERVO_VOLTAGE 0 +#define HAL_HAVE_SAFETY_SWITCH 0 +#define HAL_WITH_MCU_MONITORING 0 +#define HAL_USE_QUADSPI 0 +#define HAL_WITH_DSP 0 + +#define HAL_CANFD_SUPPORTED 0 +#define HAL_NUM_CAN_IFACES 0 + +#define AP_CRASHDUMP_ENABLED 0 +#define HAL_ENABLE_DFU_BOOT 0 + + +#define HAL_LOGGING_MAVLINK_ENABLED 0 + +#define HAL_LOGGING_FILESYSTEM_ENABLED 1 + +#define AP_FILESYSTEM_POSIX_HAVE_UTIME 0 +#define AP_FILESYSTEM_POSIX_HAVE_FSYNC 0 +#define AP_FILESYSTEM_POSIX_HAVE_STATFS 0 +#define AP_FILESYSTEM_HAVE_DIRENT_DTYPE 0 + +#define AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC 1 +#define AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR "/data" +#define HAL_BOARD_STORAGE_DIRECTORY "APM" +#define HAL_BOARD_LOG_DIRECTORY "APM/logs" +#define HAL_BOARD_TERRAIN_DIRECTORY "APM/terrain" + +#define SCRIPTING_DIRECTORY "APM/scripts" + +/* + a defaults file for this vehicle + */ +#ifndef HAL_PARAM_DEFAULTS_PATH +// this is an absolute path, as required by AP_Param +#define HAL_PARAM_DEFAULTS_PATH AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR "/APM/defaults.parm" +#endif + +#define USE_LIBC_REALLOC 1 + +#define HAL_WITH_ESC_TELEM 1 + +/* + battery monitoring setup, comes in via ESCs + */ +#define HAL_BATT_VOLT_PIN 1 +#define HAL_BATT_CURR_PIN 2 +#define HAL_BATT_MONITOR_DEFAULT 4 +#define HAL_BATT_VOLT_SCALE 1 +#define HAL_BATT_CURR_SCALE 1 + +#define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +/* + compass list + */ +#define PROBE_MAG_I2C(driver, bus, addr, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe(GET_I2C_DEVICE(bus, addr),##args)) +#define HAL_MAG_PROBE_LIST PROBE_MAG_I2C(QMC5883L, 0, 0x0d, true, ROTATION_NONE) + +/* + barometer list + */ +#define PROBE_BARO_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_Baro_ ## driver::probe(*this,std::move(GET_I2C_DEVICE(bus, addr)),##args)) +#define HAL_BARO_PROBE_LIST PROBE_BARO_I2C(ICP101XX, 2, 0x63) + +/* + IMU list + */ +#define PROBE_IMU_SPI(driver, devname, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,hal.spi->get_device(devname),##args)) +#define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensensev3, "INV3", ROTATION_NONE) + +/* + bring in missing standard library functions + */ +#include + +#define DEFAULT_SERIAL4_PROTOCOL 23 // RC input diff --git a/libraries/AP_HAL/board/sitl.h b/libraries/AP_HAL/board/sitl.h index ea0e165ad9ba86..773881489857c6 100644 --- a/libraries/AP_HAL/board/sitl.h +++ b/libraries/AP_HAL/board/sitl.h @@ -29,6 +29,10 @@ #define HAL_FLASH_ALLOW_UPDATE 0 #endif +#ifndef BOARD_FLASH_SIZE +#define BOARD_FLASH_SIZE 4096 +#endif + #ifndef HAL_STORAGE_SIZE #define HAL_STORAGE_SIZE 32768 #endif @@ -39,9 +43,17 @@ #define HAL_PARAM_DEFAULTS_PATH nullptr #define HAL_INS_DEFAULT HAL_INS_NONE #define HAL_BARO_DEFAULT HAL_BARO_NONE -#define HAL_GPIO_A_LED_PIN 61 -#define HAL_GPIO_B_LED_PIN 48 -#define HAL_GPIO_C_LED_PIN 117 + +// simulated LEDs are disabled by default as they lead to a large +// amount of SIM_GPIO_MASK mavlink traffic + +// #define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 +#define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 8 // these are set in SIM_PIN_MASK +#define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 9 +#define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 10 + +// #define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +#define AP_NOTIFY_GPIO_LED_A_PIN 8 // these are set in SIM_PIN_MASK #define HAL_HAVE_BOARD_VOLTAGE 1 #define HAL_HAVE_SERVO_VOLTAGE 1 @@ -82,3 +94,5 @@ #ifndef AP_FILTER_ENABLED #define AP_FILTER_ENABLED 1 #endif + +#define HAL_SOLO_GIMBAL_ENABLED 1 diff --git a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp index 23e079f23ead8c..78737f12a846f5 100644 --- a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp +++ b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp @@ -4,6 +4,7 @@ #include #include #include +#include #include "GyroFrame.h" #if HAL_WITH_DSP diff --git a/libraries/AP_HAL/utility/DataRateLimit.cpp b/libraries/AP_HAL/utility/DataRateLimit.cpp new file mode 100644 index 00000000000000..a61259428b919e --- /dev/null +++ b/libraries/AP_HAL/utility/DataRateLimit.cpp @@ -0,0 +1,25 @@ +#include "DataRateLimit.h" + +#include + +// Return the max number of bytes that can be sent since the last call given byte/s rate limit +uint32_t DataRateLimit::max_bytes(const float bytes_per_sec) +{ + // Time since last call + const uint32_t now_us = AP_HAL::micros(); + const float dt = (now_us - last_us) * 1.0e-6; + last_us = now_us; + + // Maximum number of bytes that could be transferred in that time + float max_bytes = bytes_per_sec * dt; + + // Add on the remainder from the last call, this prevents cumulative rounding errors + max_bytes += remainder; + + // Get integer number of bytes and store the remainder + float max_bytes_int; + remainder = modf(max_bytes, &max_bytes_int); + + // Add 0.5 to make sure the float rounds to the correct int + return uint32_t(max_bytes_int + 0.5); +} diff --git a/libraries/AP_HAL/utility/DataRateLimit.h b/libraries/AP_HAL/utility/DataRateLimit.h new file mode 100644 index 00000000000000..ec8f55e37a3051 --- /dev/null +++ b/libraries/AP_HAL/utility/DataRateLimit.h @@ -0,0 +1,26 @@ +/* + 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 + +// Returns the max number of bytes that can be sent since the last call given byte/s rate limit +class DataRateLimit { +public: + uint32_t max_bytes(const float bytes_per_sec); +private: + uint32_t last_us; + float remainder; +}; diff --git a/libraries/AP_HAL/utility/RingBuffer.h b/libraries/AP_HAL/utility/RingBuffer.h index bddfc54283fb9a..e28f7084b124cc 100644 --- a/libraries/AP_HAL/utility/RingBuffer.h +++ b/libraries/AP_HAL/utility/RingBuffer.h @@ -116,7 +116,7 @@ class ObjectBuffer { // gives one less byte than requested. We round up to a full // multiple of the object size so that we always get aligned // elements, which makes the readptr() method possible - buffer = new ByteBuffer(((_size+1) * sizeof(T))); + buffer = NEW_NOTHROW ByteBuffer(((_size+1) * sizeof(T))); external_buf = false; } @@ -288,7 +288,7 @@ class ObjectBuffer_TS { // gives one less byte than requested. We round up to a full // multiple of the object size so that we always get aligned // elements, which makes the readptr() method possible - buffer = new ByteBuffer(((_size+1) * sizeof(T))); + buffer = NEW_NOTHROW ByteBuffer(((_size+1) * sizeof(T))); } ~ObjectBuffer_TS(void) { delete buffer; @@ -472,7 +472,7 @@ class ObjectArray { ObjectArray(uint16_t size_) { _size = size_; _head = _count = 0; - _buffer = new T[_size]; + _buffer = NEW_NOTHROW T[_size]; } ~ObjectArray(void) { delete[] _buffer; diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 841c0c3c928c21..6f8509a4d02023 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #endif #include @@ -99,7 +100,7 @@ void SOCKET_CLASS_NAME::make_sockaddr(const char *address, uint16_t port, struct sockaddr.sin_addr.s_addr = htonl(inet_str_to_addr(address)); } -#if !defined(HAL_BOOTLOADER_BUILD) +#if !defined(HAL_BOOTLOADER_BUILD) || AP_NETWORKING_CAN_MCAST_ENABLED /* connect the socket */ @@ -186,7 +187,7 @@ bool SOCKET_CLASS_NAME::connect(const char *address, uint16_t port) fd_in = -1; return false; } -#endif // HAL_BOOTLOADER_BUILD +#endif // !defined(HAL_BOOTLOADER_BUILD) || AP_NETWORKING_CAN_MCAST_ENABLED /* connect the socket with a timeout @@ -303,7 +304,27 @@ ssize_t SOCKET_CLASS_NAME::send(const void *buf, size_t size) const } /* - send some data + send some data with address as a uint32_t + */ +ssize_t SOCKET_CLASS_NAME::sendto(const void *buf, size_t size, uint32_t address, uint16_t port) +{ + if (fd == -1) { + return -1; + } + struct sockaddr_in sockaddr = {}; + +#ifdef HAVE_SOCK_SIN_LEN + sockaddr.sin_len = sizeof(sockaddr); +#endif + sockaddr.sin_port = htons(port); + sockaddr.sin_family = AF_INET; + sockaddr.sin_addr.s_addr = htonl(address); + + return CALL_PREFIX(sendto)(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); +} + +/* + send some data with address as a string */ ssize_t SOCKET_CLASS_NAME::sendto(const void *buf, size_t size, const char *address, uint16_t port) { @@ -327,8 +348,12 @@ ssize_t SOCKET_CLASS_NAME::recv(void *buf, size_t size, uint32_t timeout_ms) socklen_t len = sizeof(struct sockaddr_in); int fin = get_read_fd(); ssize_t ret; - ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr[0], &len); - if (ret <= 0) { + uint32_t in_addr[4] = {}; + ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr[0], &len); + if (ret > 0) { + // only update last_in_addr if we received data + memcpy(last_in_addr, in_addr, sizeof(last_in_addr)); + } else { if (!datagram && connected && ret == 0) { // remote host has closed connection connected = false; @@ -380,6 +405,24 @@ const char *SOCKET_CLASS_NAME::last_recv_address(char *ip_addr_buf, uint8_t bufl return ret; } +/* + return the IP address and port of the last received packet + */ +bool SOCKET_CLASS_NAME::last_recv_address(uint32_t &ip_addr, uint16_t &port) const +{ + const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; + if (sin.sin_family != AF_INET) { + return false; + } + ip_addr = ntohl(sin.sin_addr.s_addr); + port = ntohs(sin.sin_port); + if (ip_addr == 0 || + port == 0) { + return false; + } + return true; +} + void SOCKET_CLASS_NAME::set_broadcast(void) const { if (fd == -1) { @@ -467,7 +510,7 @@ SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::accept(uint32_t timeout_ms) if (newfd == -1) { return nullptr; } - auto *ret = new SOCKET_CLASS_NAME(false, newfd); + auto *ret = NEW_NOTHROW SOCKET_CLASS_NAME(false, newfd); if (ret != nullptr) { ret->connected = true; ret->reuseaddress(); @@ -504,7 +547,7 @@ void SOCKET_CLASS_NAME::close(void) */ SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::duplicate(void) { - auto *ret = new SOCKET_CLASS_NAME(datagram, fd); + auto *ret = NEW_NOTHROW SOCKET_CLASS_NAME(datagram, fd); if (ret == nullptr) { return nullptr; } diff --git a/libraries/AP_HAL/utility/Socket.hpp b/libraries/AP_HAL/utility/Socket.hpp index 8847ce958f55b8..480ef365cb4c30 100644 --- a/libraries/AP_HAL/utility/Socket.hpp +++ b/libraries/AP_HAL/utility/Socket.hpp @@ -43,6 +43,7 @@ class SOCKET_CLASS_NAME { ssize_t send(const void *pkt, size_t size) const; ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); + ssize_t sendto(const void *buf, size_t size, uint32_t address, uint16_t port); ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); // return the IP address and port of the last received packet @@ -51,6 +52,9 @@ class SOCKET_CLASS_NAME { // return the IP address and port of the last received packet, using caller supplied buffer const char *last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const; + // return the IP address and port of the last received packet + bool last_recv_address(uint32_t &ip_addr, uint16_t &port) const; + // return true if there is pending data for input bool pollin(uint32_t timeout_ms); diff --git a/libraries/AP_HAL/utility/packetise.cpp b/libraries/AP_HAL/utility/packetise.cpp index 4ab8d7dc448736..b64ed69845fd5d 100644 --- a/libraries/AP_HAL/utility/packetise.cpp +++ b/libraries/AP_HAL/utility/packetise.cpp @@ -2,12 +2,11 @@ support for sending UDP packets on MAVLink packet boundaries. */ -#include - -#if HAL_GCS_ENABLED - #include "packetise.h" +#if AP_MAVLINK_PACKETISE_ENABLED +#include + /* return the number of bytes to send for a packetised connection */ @@ -68,4 +67,4 @@ uint16_t mavlink_packetise(ByteBuffer &writebuf, uint16_t n) return n; } -#endif // HAL_GCS_ENABLED +#endif // AP_MAVLINK_PACKETISE_ENABLED diff --git a/libraries/AP_HAL/utility/packetise.h b/libraries/AP_HAL/utility/packetise.h index b312942ca47d53..14c8721b4b148e 100644 --- a/libraries/AP_HAL/utility/packetise.h +++ b/libraries/AP_HAL/utility/packetise.h @@ -1,4 +1,10 @@ #pragma once +#include "RingBuffer.h" +#include + +#ifndef AP_MAVLINK_PACKETISE_ENABLED +#define AP_MAVLINK_PACKETISE_ENABLED HAL_GCS_ENABLED +#endif /* return the number of bytes to send for a packetised connection diff --git a/libraries/AP_HAL/utility/sparse-endian.h b/libraries/AP_HAL/utility/sparse-endian.h index f562e1166dca06..2162f034e418a3 100644 --- a/libraries/AP_HAL/utility/sparse-endian.h +++ b/libraries/AP_HAL/utility/sparse-endian.h @@ -57,6 +57,12 @@ typedef uint64_t __ap_bitwise be64_t; #undef be64toh #undef le64toh +#if !defined (__BYTE_ORDER) && defined (__OpenBSD__) +#define __BYTE_ORDER __BYTE_ORDER__ +#define __LITTLE_ENDIAN __ORDER_LITTLE_ENDIAN__ +#define __BIG_ENDIAN __ORDER_BIG_ENDIAN__ +#endif + #if __BYTE_ORDER == __LITTLE_ENDIAN #define bswap_16_on_le(x) __bswap_16(x) #define bswap_32_on_le(x) __bswap_32(x) diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 0621162132eef5..b388e5cf77eff8 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -770,7 +770,7 @@ AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) WITH_SEMAPHORE(_semaphore); for (uint8_t j=0; jget_soft_armed()) { // the power status has changed while armed flags |= MAV_POWER_STATUS_CHANGED; diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index cc4001940a4ecd..4d258e1c46f3e5 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -167,9 +167,9 @@ static inline void handleCANInterrupt(uint8_t phys_index, uint8_t line_index) uint32_t CANIface::FDCANMessageRAMOffset_ = 0; CANIface::CANIface(uint8_t index) : - self_index_(index), rx_bytebuffer_((uint8_t*)rx_buffer, sizeof(rx_buffer)), - rx_queue_(&rx_bytebuffer_) + rx_queue_(&rx_bytebuffer_), + self_index_(index) { if (index >= HAL_NUM_CAN_IFACES) { AP_HAL::panic("Bad CANIface index."); @@ -379,6 +379,17 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, if ((can_->TXFQS & FDCAN_TXFQS_TFQF) != 0) { stats.tx_overflow++; + if (stats.tx_success == 0) { + /* + if we have never successfully transmitted a frame + then we may be operating with just MAVCAN or UDP + MCAST. Consider the frame sent if the send + succeeds. This allows for UDP MCAST and MAVCAN to + operate fully when the CAN bus has no cable plugged + in + */ + return AP_HAL::CANIface::send(frame, tx_deadline, flags); + } return 0; //we don't have free space } index = ((can_->TXFQS & FDCAN_TXFQS_TFQPI) >> FDCAN_TXFQS_TFQPI_Pos); diff --git a/libraries/AP_HAL_ChibiOS/CanIface.cpp b/libraries/AP_HAL_ChibiOS/CanIface.cpp index f6704b6438d09d..90badc41581baa 100644 --- a/libraries/AP_HAL_ChibiOS/CanIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CanIface.cpp @@ -140,9 +140,9 @@ const uint32_t CANIface::TSR_ABRQx[CANIface::NumTxMailboxes] = { CANIface::CANIface(uint8_t index) : - self_index_(index), rx_bytebuffer_((uint8_t*)rx_buffer, sizeof(rx_buffer)), - rx_queue_(&rx_bytebuffer_) + rx_queue_(&rx_bytebuffer_), + self_index_(index) { if (index >= HAL_NUM_CAN_IFACES) { AP_HAL::panic("Bad CANIface index."); @@ -325,6 +325,19 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, txmailbox = 2; } else { PERF_STATS(stats.tx_overflow); +#if !defined(HAL_BOOTLOADER_BUILD) + if (stats.tx_success == 0) { + /* + if we have never successfully transmitted a frame + then we may be operating with just MAVCAN or UDP + MCAST. Consider the frame sent if the send + succeeds. This allows for UDP MCAST and MAVCAN to + operate fully when the CAN bus has no cable plugged + in + */ + return AP_HAL::CANIface::send(frame, tx_deadline, flags); + } +#endif return 0; // No transmission for you. } @@ -847,7 +860,7 @@ bool CANIface::init(const uint32_t bitrate, const CANIface::OperatingMode mode) mode_ = mode; if (can_ifaces[0] == nullptr) { - can_ifaces[0] = new CANIface(0); + can_ifaces[0] = NEW_NOTHROW CANIface(0); Debug("Failed to allocate CAN iface 0"); if (can_ifaces[0] == nullptr) { return false; diff --git a/libraries/AP_HAL_ChibiOS/DSP.cpp b/libraries/AP_HAL_ChibiOS/DSP.cpp index 0fb0692e264d50..fd8bd2bbfdce1a 100644 --- a/libraries/AP_HAL_ChibiOS/DSP.cpp +++ b/libraries/AP_HAL_ChibiOS/DSP.cpp @@ -52,7 +52,7 @@ extern const AP_HAL::HAL& hal; // initialize the FFT state machine 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, sliding_window_size); + DSP::FFTWindowStateARM* fft = NEW_NOTHROW 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; diff --git a/libraries/AP_HAL_ChibiOS/Device.cpp b/libraries/AP_HAL_ChibiOS/Device.cpp index 619804a4b98e5a..ac78bfca0e0e7d 100644 --- a/libraries/AP_HAL_ChibiOS/Device.cpp +++ b/libraries/AP_HAL_ChibiOS/Device.cpp @@ -111,6 +111,9 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe // setup a name for the thread const uint8_t name_len = 7; char *name = (char *)malloc(name_len); + if (name == nullptr){ + return nullptr; + } switch (hal_device->bus_type()) { case AP_HAL::Device::BUS_TYPE_I2C: snprintf(name, name_len, "I2C%u", @@ -134,7 +137,7 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe AP_HAL::panic("Failed to create bus thread %s", name); } } - DeviceBus::callback_info *callback = new DeviceBus::callback_info; + DeviceBus::callback_info *callback = NEW_NOTHROW DeviceBus::callback_info; if (callback == nullptr) { return nullptr; } diff --git a/libraries/AP_HAL_ChibiOS/GPIO.cpp b/libraries/AP_HAL_ChibiOS/GPIO.cpp index f62bd73c27bfd2..d2218a21ab2a81 100644 --- a/libraries/AP_HAL_ChibiOS/GPIO.cpp +++ b/libraries/AP_HAL_ChibiOS/GPIO.cpp @@ -241,17 +241,16 @@ uint8_t GPIO::read(uint8_t pin) if (g) { return palReadLine(g->pal_line); } +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { + return iomcu.read_virtual_GPIO(pin); + } +#endif return 0; } void GPIO::write(uint8_t pin, uint8_t value) { -#if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { - iomcu.write_GPIO(pin, value); - return; - } -#endif struct gpio_entry *g = gpio_by_pin_num(pin); if (g) { if (g->is_input) { @@ -263,36 +262,42 @@ void GPIO::write(uint8_t pin, uint8_t value) } else { palSetLine(g->pal_line); } + return; + } +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { + iomcu.write_GPIO(pin, value); } +#endif } void GPIO::toggle(uint8_t pin) { + struct gpio_entry *g = gpio_by_pin_num(pin); + if (g) { + palToggleLine(g->pal_line); + return; + } #if HAL_WITH_IO_MCU if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { iomcu.toggle_GPIO(pin); - return; } #endif - struct gpio_entry *g = gpio_by_pin_num(pin); - if (g) { - palToggleLine(g->pal_line); - } } /* Alternative interface: */ AP_HAL::DigitalSource* GPIO::channel(uint16_t pin) { + struct gpio_entry *g = gpio_by_pin_num(pin); + if (g != nullptr) { + return NEW_NOTHROW DigitalSource(g->pal_line); + } #if HAL_WITH_IO_MCU if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { - return new IOMCU_DigitalSource(pin); + return NEW_NOTHROW IOMCU_DigitalSource(pin); } #endif - struct gpio_entry *g = gpio_by_pin_num(pin); - if (!g) { - return nullptr; - } - return new DigitalSource(g->pal_line); + return nullptr; } extern const AP_HAL::HAL& hal; @@ -526,12 +531,15 @@ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_u // check if a pin number is valid bool GPIO::valid_pin(uint8_t pin) const { + if (gpio_by_pin_num(pin) != nullptr) { + return true; + } #if HAL_WITH_IO_MCU if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) { return true; } #endif - return gpio_by_pin_num(pin) != nullptr; + return false; } // return servo channel associated with GPIO pin. Returns true on success and fills in servo_ch argument diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index f046fdd4979f7b..12bead827bdcbb 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -102,7 +102,7 @@ I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)]; void I2CBus::dma_init(void) { chMtxObjectInit(&dma_lock); - dma_handle = new Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx, + dma_handle = NEW_NOTHROW Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx, FUNCTOR_BIND_MEMBER(&I2CBus::dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&I2CBus::dma_deallocate, void, Shared_DMA *)); } @@ -261,11 +261,11 @@ I2CDeviceManager::I2CDeviceManager(void) } I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) : + bus(I2CDeviceManager::businfo[busnum]), _retries(2), _address(address), _use_smbus(use_smbus), - _timeout_ms(timeout_ms), - bus(I2CDeviceManager::businfo[busnum]) + _timeout_ms(timeout_ms) { set_device_bus(busnum+HAL_I2C_BUS_BASE); set_device_address(address); @@ -459,7 +459,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address, if (bus >= ARRAY_SIZE(I2CD)) { return AP_HAL::OwnPtr(nullptr); } - auto dev = AP_HAL::OwnPtr(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); + auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); return dev; } diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index cd44c7b3644d67..2f4e460b377e6d 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -84,15 +84,6 @@ bool RCInput::new_input() _last_read = _rcin_timestamp_last_signal; } -#if HAL_RCINPUT_WITH_AP_RADIO - if (!_radio_init) { - _radio_init = true; - radio = AP_Radio::get_singleton(); - if (radio) { - radio->init(); - } - } -#endif return valid; } @@ -114,12 +105,6 @@ uint16_t RCInput::read(uint8_t channel) WITH_SEMAPHORE(rcin_mutex); v = _rc_values[channel]; } -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio && channel == 0) { - // hook to allow for update of radio on main thread, for mavlink sends - radio->update(); - } -#endif return v; } @@ -136,12 +121,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) WITH_SEMAPHORE(rcin_mutex); memcpy(periods, _rc_values, len*sizeof(periods[0])); } -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio) { - // hook to allow for update of radio on main thread, for mavlink sends - radio->update(); - } -#endif return len; } @@ -186,7 +165,7 @@ void RCInput::_timer_tick(void) if (!have_iocmu_rc) { _rcin_last_iomcu_ms = 0; } -#elif AP_RCPROTOCOL_ENABLED || HAL_RCINPUT_WITH_AP_RADIO +#elif AP_RCPROTOCOL_ENABLED const bool have_iocmu_rc = false; #endif @@ -206,22 +185,6 @@ void RCInput::_timer_tick(void) } #endif // AP_RCPROTOCOL_ENABLED -#if HAL_RCINPUT_WITH_AP_RADIO - 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; - _num_channels = radio->num_channels(); - _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS); - for (uint8_t i=0; i<_num_channels; i++) { - _rc_values[i] = radio->read(i); - } -#ifndef HAL_NO_UARTDRIVER - source = RCSource::APRADIO; -#endif - } -#endif - #if HAL_WITH_IO_MCU { WITH_SEMAPHORE(rcin_mutex); @@ -269,11 +232,6 @@ bool RCInput::rc_bind(int dsmMode) AP::RC().start_bind(); #endif -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio) { - radio->start_recv_bind(); - } -#endif return true; } #endif //#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS diff --git a/libraries/AP_HAL_ChibiOS/RCInput.h b/libraries/AP_HAL_ChibiOS/RCInput.h index 0b3ec8ea5a5754..5d03d563003e79 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.h +++ b/libraries/AP_HAL_ChibiOS/RCInput.h @@ -19,10 +19,6 @@ #include "AP_HAL_ChibiOS.h" #include "Semaphores.h" -#if HAL_RCINPUT_WITH_AP_RADIO -#include -#endif - #include #if HAL_USE_ICU == TRUE @@ -80,17 +76,10 @@ class ChibiOS::RCInput : public AP_HAL::RCInput { IOMCU = 1, RCPROT_PULSES = 2, RCPROT_BYTES = 3, - APRADIO = 4, } last_source; bool pulse_input_enabled; -#if HAL_RCINPUT_WITH_AP_RADIO - bool _radio_init; - AP_Radio *radio; - uint32_t last_radio_us; -#endif - #if HAL_USE_ICU == TRUE ChibiOS::SoftSigReader sig_reader; #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index d6157f0d96c69e..3d3245444fecd7 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -650,6 +650,11 @@ uint32_t RCOutput::get_disabled_channels(uint32_t digital_mask) } disabled_chan_mask <<= chan_offset; +#if HAL_WITH_IO_MCU + if (iomcu_dshot) { + disabled_chan_mask |= iomcu.get_disabled_channels(digital_mask); + } +#endif return disabled_chan_mask; } @@ -808,11 +813,9 @@ void RCOutput::push_local(void) #endif // HAL_DSHOT_ENABLED if (group.current_mode == MODE_PWM_ONESHOT || group.current_mode == MODE_PWM_ONESHOT125 || - group.current_mode == MODE_NEOPIXEL || - group.current_mode == MODE_NEOPIXELRGB || - group.current_mode == MODE_PROFILED || is_dshot_protocol(group.current_mode)) { // only control widest pulse for oneshot and dshot + // do not control for neopixel since updates to these are not pushed if (period_us > widest_pulse) { widest_pulse = period_us; } @@ -945,7 +948,7 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_ } #else if (!group.dma_handle) { - group.dma_handle = new Shared_DMA(group.dma_up_stream_id, SHARED_DMA_NONE, + group.dma_handle = NEW_NOTHROW Shared_DMA(group.dma_up_stream_id, SHARED_DMA_NONE, FUNCTOR_BIND_MEMBER(&RCOutput::dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&RCOutput::dma_deallocate, void, Shared_DMA *)); if (!group.dma_handle) { @@ -1133,6 +1136,7 @@ void RCOutput::set_group_mode(pwm_group &group) if (is_bidir_dshot_enabled(group)) { group.dshot_pulse_send_time_us = pulse_send_time_us; // to all intents and purposes the pulse time of send and receive are the same + // for dshot600 this is roughly 26us + 30us + 26us = 82us group.dshot_pulse_time_us = pulse_send_time_us + pulse_send_time_us + 30; } #endif @@ -1263,9 +1267,13 @@ bool RCOutput::get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) if (iomcu_enabled) { uint8_t iomcu_mask; const output_mode iomcu_mode = iomcu.get_output_mode(iomcu_mask); + const uint8_t gpio_mask = iomcu.get_GPIO_mask(); for (uint8_t i = 0; i < chan_offset; i++ ) { - if (iomcu_mask & 1U<is_shared()) { - group.pwm_drv->tim->CR1 = 0; - group.pwm_drv->tim->DIER = 0; + bdshot_disable_pwm_f1(group); } #endif - dmaStreamFreeI(group.dma); group.dma = nullptr; chSysUnlock(); } @@ -1635,9 +1642,8 @@ void RCOutput::dshot_send(pwm_group &group, rcout_timer_t cycle_start_us, rcout_ bdshot_prepare_for_next_pulse(group); #endif bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED; -#if !defined(IOMCU_FW) bool armed = hal.util->get_soft_armed(); -#endif + memset((uint8_t *)group.dma_buffer, 0, DSHOT_BUFFER_LENGTH); for (uint8_t i=0; i<4; i++) { @@ -1648,7 +1654,9 @@ void RCOutput::dshot_send(pwm_group &group, rcout_timer_t cycle_start_us, rcout_ bdshot_decode_telemetry_from_erpm(group.bdshot.erpm[i], chan); } #endif - if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) { + const uint32_t servo_chan_mask = 1U<<(chan+chan_offset); + + if (safety_on && !(safety_mask & servo_chan_mask)) { // safety is on, don't output anything continue; } @@ -1660,12 +1668,10 @@ void RCOutput::dshot_send(pwm_group &group, rcout_timer_t cycle_start_us, rcout_ continue; } - const uint32_t chan_mask = (1U<safety_button_handle_pressed(safety_press_count)) { @@ -2566,7 +2573,7 @@ bool RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t for (uint8_t j = 0; j < 4; j++) { delete[] grp->serial_led_data[j]; grp->serial_led_data[j] = nullptr; - grp->serial_led_data[j] = new SerialLed[grp->serial_nleds]; + grp->serial_led_data[j] = NEW_NOTHROW SerialLed[grp->serial_nleds]; if (grp->serial_led_data[j] == nullptr) { // if allocation failed clear all memory for (uint8_t k = 0; k < 4; k++) { diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 3dc76d6f043266..87aa9948dbd9ca 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -733,6 +733,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput static void bdshot_receive_pulses_DMAR_f1(pwm_group* group); static void bdshot_reset_pwm(pwm_group& group, uint8_t telem_channel); static void bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel); + static void bdshot_disable_pwm_f1(pwm_group& group); static void bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch); static void bdshot_config_icu_dshot_f1(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch); static uint32_t bdshot_get_output_rate_hz(const enum output_mode mode); diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index cb1c04e29d5745..801512a687d7d9 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -101,7 +101,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) if (group.dma_ch[i].stream_id == group.dma_up_stream_id) { group.bdshot.ic_dma_handle[i] = group.dma_handle; } else { - group.bdshot.ic_dma_handle[i] = new Shared_DMA(group.dma_ch[i].stream_id, SHARED_DMA_NONE, + group.bdshot.ic_dma_handle[i] = NEW_NOTHROW Shared_DMA(group.dma_ch[i].stream_id, SHARED_DMA_NONE, FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_deallocate, void, Shared_DMA *)); } @@ -165,7 +165,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) group.bdshot.ic_dma_handle[i] = group.dma_handle; } else { // we can use the next channel - group.bdshot.ic_dma_handle[i] = new Shared_DMA(group.dma_ch[curr_chan].stream_id, SHARED_DMA_NONE, + group.bdshot.ic_dma_handle[i] = NEW_NOTHROW Shared_DMA(group.dma_ch[curr_chan].stream_id, SHARED_DMA_NONE, FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_deallocate, void, Shared_DMA *)); } @@ -230,6 +230,11 @@ void RCOutput::bdshot_ic_dma_deallocate(Shared_DMA *ctx) chSysLock(); if (group.bdshot.ic_dma_handle[icuch] == ctx && group.bdshot.ic_dma[icuch] != nullptr) { dmaStreamFreeI(group.bdshot.ic_dma[icuch]); +#if defined(STM32F1) + if (group.bdshot.ic_dma_handle[icuch]->is_shared()) { + bdshot_disable_pwm_f1(group); + } +#endif group.bdshot.ic_dma[icuch] = nullptr; } chSysUnlock(); @@ -755,12 +760,12 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c uint16_t value = (encodederpm & 0x000001ffU); // 9bits #if HAL_WITH_ESC_TELEM uint8_t normalized_chan = chan; -#endif #if HAL_WITH_IO_MCU if (iomcu_enabled) { normalized_chan = chan + chan_offset; } #endif +#endif // HAL_WITH_ESC_TELEM: one can possibly imagine a FC with IOMCU but with ESC_TELEM compiled out... if (!(value & 0x100U) && (_dshot_esc_type == DSHOT_ESC_BLHELI_EDT || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S)) { switch (expo) { @@ -796,10 +801,28 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c break; case 0b100: // Debug 1 case 0b101: // Debug 2 - case 0b110: // Stress level - case 0b111: // Status return false; break; + case 0b110: { // Stress level + #if HAL_WITH_ESC_TELEM && AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + TelemetryData t { + .edt2_stress = value + }; + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS); + #endif + return false; + } + break; + case 0b111: { // Status + #if HAL_WITH_ESC_TELEM && AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + TelemetryData t { + .edt2_status = value + }; + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS); + #endif + return false; + } + break; default: // eRPM break; } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp index 70959c03e433b3..ddde8797412b70 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp @@ -135,23 +135,32 @@ void RCOutput::rcout_thread() { } } -#if defined(HAL_WITH_BIDIR_DSHOT) && defined(STM32F1) -// reset pwm driver to output mode without resetting the clock or the peripheral -// the code here is the equivalent of pwmStart()/pwmStop() -void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel) +#if defined(STM32F1) +void RCOutput::bdshot_disable_pwm_f1(pwm_group& group) { - osalSysLock(); - stm32_tim_t* TIMx = group.pwm_drv->tim; // pwmStop sets these TIMx->CR1 = 0; /* Timer disabled. */ TIMx->DIER = 0; /* All IRQs disabled. */ TIMx->SR = 0; /* Clear eventual pending IRQs. */ - TIMx->CNT = 0; + TIMx->CNT = 0; TIMx->CCR[0] = 0; /* Comparator 1 disabled. */ TIMx->CCR[1] = 0; /* Comparator 2 disabled. */ TIMx->CCR[2] = 0; /* Comparator 3 disabled. */ TIMx->CCR[3] = 0; /* Comparator 4 disabled. */ +} +#endif + +#if defined(HAL_WITH_BIDIR_DSHOT) && defined(STM32F1) +// reset pwm driver to output mode without resetting the clock or the peripheral +// the code here is the equivalent of pwmStart()/pwmStop() +void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel) +{ + osalSysLock(); + + stm32_tim_t* TIMx = group.pwm_drv->tim; + bdshot_disable_pwm_f1(group); + // at the point this is called we will have done input capture on two CC channels // we need to switch those channels back to output and the default settings // all other channels will not have been modified @@ -195,7 +204,7 @@ void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel) // we need to switch every output on the same input channel to avoid // spurious line changes for (uint8_t i = 0; i<4; i++) { - if (group.chan[i] == CHAN_DISABLED) { + if (!group.is_chan_enabled(i)) { continue; } if (group.bdshot.telem_tim_ch[telem_channel] == group.bdshot.telem_tim_ch[i]) { @@ -241,7 +250,7 @@ void RCOutput::bdshot_receive_pulses_DMAR_f1(pwm_group* group) // we need to switch every input on the same input channel to allow // the ESCs to drive the lines for (uint8_t i = 0; i<4; i++) { - if (group->chan[i] == CHAN_DISABLED) { + if (!group->is_chan_enabled(i)) { continue; } if (group->bdshot.telem_tim_ch[curr_ch] == group->bdshot.telem_tim_ch[i]) { diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index dc6824256a1322..0a86e12dd0539c 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -33,6 +33,8 @@ using namespace ChibiOS; extern const AP_HAL::HAL& hal; +// send a dshot command to group +// chan is the FMU channel to send the command to bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t chan) { if (!group.can_send_dshot_pulse()) { @@ -112,10 +114,11 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman DshotCommandPacket pkt; pkt.command = command; if (chan != ALL_CHANNELS) { - pkt.chan = chan - chan_offset; + pkt.chan = chan - chan_offset; // normalize to FMU channel } else { pkt.chan = ALL_CHANNELS; } + if (command_timeout_ms == 0) { pkt.cycle = MAX(10, repeat_count); } else { @@ -140,6 +143,12 @@ void RCOutput::set_reversed_mask(uint32_t chanmask) { // The mask uses servo channel numbering void RCOutput::set_reversible_mask(uint32_t chanmask) { _reversible_mask |= chanmask; +#if HAL_WITH_IO_MCU + const uint32_t iomcu_mask = ((1U< 0 - for (uint8_t i=chan_offset; i 0 + for (uint8_t i=0; i(new SPIDevice(*busp, desc)); + return AP_HAL::OwnPtr(NEW_NOTHROW SPIDevice(*busp, desc)); } void SPIDeviceManager::set_register_rw_callback(const char* name, AP_HAL::Device::RegisterRWCb cb) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 128ab1cc1eb314..36b1d7a5518f37 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -64,6 +64,10 @@ using namespace ChibiOS; #define HAL_RCIN_THREAD_ENABLED 1 #endif +#ifndef HAL_MONITOR_THREAD_ENABLED +#define HAL_MONITOR_THREAD_ENABLED 1 +#endif + extern const AP_HAL::HAL& hal; #ifndef HAL_NO_TIMER_THREAD THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE); @@ -80,7 +84,7 @@ THD_WORKING_AREA(_io_thread_wa, IO_THD_WA_SIZE); #ifndef HAL_USE_EMPTY_STORAGE THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE); #endif -#ifndef HAL_NO_MONITOR_THREAD +#if HAL_MONITOR_THREAD_ENABLED THD_WORKING_AREA(_monitor_thread_wa, MONITOR_THD_WA_SIZE); #endif @@ -100,7 +104,7 @@ void Scheduler::init() chBSemObjectInit(&_timer_semaphore, false); chBSemObjectInit(&_io_semaphore, false); -#ifndef HAL_NO_MONITOR_THREAD +#if HAL_MONITOR_THREAD_ENABLED // setup the monitor thread - this is used to detect software lockups _monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa, sizeof(_monitor_thread_wa), @@ -407,7 +411,7 @@ bool Scheduler::in_expected_delay(void) const return false; } -#ifndef HAL_NO_MONITOR_THREAD +#if HAL_MONITOR_THREAD_ENABLED void Scheduler::_monitor_thread(void *arg) { Scheduler *sched = (Scheduler *)arg; @@ -513,7 +517,7 @@ void Scheduler::_monitor_thread(void *arg) #endif } } -#endif // HAL_NO_MONITOR_THREAD +#endif // HAL_MONITOR_THREAD_ENABLED void Scheduler::_rcin_thread(void *arg) { diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 069f64085f98d4..b8c995a4b2b9c9 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -70,6 +70,9 @@ static const eventmask_t EVT_PARITY = EVENT_MASK(11); // event for transmit end for half-duplex static const eventmask_t EVT_TRANSMIT_END = EVENT_MASK(12); +// event for framing error +static const eventmask_t EVT_ERROR = EVENT_MASK(13); + // events for dma tx, thread per UART so can be from 0 static const eventmask_t EVT_TRANSMIT_DMA_START = EVENT_MASK(0); static const eventmask_t EVT_TRANSMIT_DMA_COMPLETE = EVENT_MASK(1); @@ -100,8 +103,8 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3); #endif UARTDriver::UARTDriver(uint8_t _serial_num) : -serial_num(_serial_num), sdef(_serial_tab[_serial_num]), +serial_num(_serial_num), _baudrate(57600) { osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many SERIALn drivers"); @@ -292,13 +295,12 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) thrashing of the heap once we are up. The ttyACM0 driver may not connect for some time after boot */ - while (_in_rx_timer) { - hal.scheduler->delay(1); - } + WITH_SEMAPHORE(rx_sem); if (rxS != _readbuf.get_size()) { _rx_initialised = false; _readbuf.set_size_best(rxS); } + _rts_threshold = _readbuf.get_size() / 16U; bool clear_buffers = false; if (b != 0) { @@ -355,9 +357,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) /* allocate the write buffer */ - while (_in_tx_timer) { - hal.scheduler->delay(1); - } + WITH_SEMAPHORE(tx_sem); if (txS != _writebuf.get_size()) { _tx_initialised = false; _writebuf.set_size_best(txS); @@ -414,7 +414,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) // we only allow for sharing of the TX DMA channel, not the RX // DMA channel, as the RX side is active all the time, so // cannot be shared - dma_handle = new Shared_DMA(sdef.dma_tx_stream_id, + dma_handle = NEW_NOTHROW Shared_DMA(sdef.dma_tx_stream_id, SHARED_DMA_NONE, FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_deallocate, void, Shared_DMA *)); @@ -451,6 +451,13 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) sercfg.cr3 |= USART_CR3_DMAT; } sercfg.irq_cb = rx_irq_cb; +#if HAL_HAVE_LOW_NOISE_UART + if (sdef.low_noise_line) { + // we can mark UART to sample on one bit instead of default 3 bits + // this allows us to be slightly less sensitive to clock differences + sercfg.cr3 |= USART_CR3_ONEBIT; + } +#endif #endif // HAL_UART_NODMA if (!(sercfg.cr2 & USART_CR2_STOP2_BITS)) { sercfg.cr2 |= USART_CR2_STOP1_BITS; @@ -494,6 +501,16 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) vprintf_console_hook = hal_console_vprintf; #endif } + +#if HAL_UART_STATS_ENABLED && CH_CFG_USE_EVENTS == TRUE + if (!err_listener_initialised) { + chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial), + &err_listener, + EVT_ERROR, + SD_FRAMING_ERROR | SD_OVERRUN_ERROR | SD_NOISE_ERROR); + err_listener_initialised = true; + } +#endif } #ifndef HAL_UART_NODMA @@ -619,9 +636,9 @@ __RAMFUNC__ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) void UARTDriver::_end() { - while (_in_rx_timer) hal.scheduler->delay(1); + WITH_SEMAPHORE(rx_sem); + WITH_SEMAPHORE(tx_sem); _rx_initialised = false; - while (_in_tx_timer) hal.scheduler->delay(1); _tx_initialised = false; if (sdef.is_usb) { @@ -672,6 +689,19 @@ uint32_t UARTDriver::get_usb_baud() const return 0; } +/* + get the requested usb parity. Valid if get_usb_baud() returned non-zero. +*/ +uint8_t UARTDriver::get_usb_parity() const +{ +#if HAL_USE_SERIAL_USB + if (sdef.is_usb) { + return ::get_usb_parity(sdef.endpoint_id); + } +#endif + return 0; +} + uint32_t UARTDriver::_available() { if (!_rx_initialised || _uart_owner_thd != chThdGetSelfX()) { @@ -805,7 +835,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) } while (n > 0) { - if (_flow_control != FLOW_CONTROL_DISABLE && + if (flow_control_enabled(_flow_control) && acts_line != 0 && palReadLine(acts_line)) { // we are using hw flow control and the CTS line is high. We @@ -877,6 +907,9 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); dmaStreamEnable(txdma); uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500; + // prevent very long timeouts at low baudrates which could cause another thread + // using begin() to block + timeout_us = MIN(timeout_us, 100000UL); chSysUnlock(); // wait for the completion or timeout handlers to signal that we are done eventmask_t mask = chEvtWaitAnyTimeout(EVT_TRANSMIT_DMA_COMPLETE, chTimeUS2I(timeout_us)); @@ -1075,7 +1108,23 @@ void UARTDriver::_rx_timer_tick(void) return; } - _in_rx_timer = true; + WITH_SEMAPHORE(rx_sem); + +#if HAL_UART_STATS_ENABLED && CH_CFG_USE_EVENTS == TRUE + if (!sdef.is_usb) { + const auto err_flags = chEvtGetAndClearFlags(&err_listener); + // count the number of errors + if (err_flags & SD_FRAMING_ERROR) { + _rx_stats_framing_errors++; + } + if (err_flags & SD_OVERRUN_ERROR) { + _rx_stats_overrun_errors++; + } + if (err_flags & SD_NOISE_ERROR) { + _rx_stats_noise_errors++; + } + } +#endif #ifndef HAL_UART_NODMA if (rx_dma_enabled && rxdma) { @@ -1112,7 +1161,6 @@ void UARTDriver::_rx_timer_tick(void) if (sdef.is_usb) { #ifdef HAVE_USB_SERIAL if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) { - _in_rx_timer = false; return; } #endif @@ -1136,7 +1184,6 @@ void UARTDriver::_rx_timer_tick(void) fwd_otg2_serial(); } #endif - _in_rx_timer = false; } // forward data from a serial port to the USB @@ -1255,14 +1302,13 @@ void UARTDriver::_tx_timer_tick(void) return; } - _in_tx_timer = true; - if (hd_tx_active) { + WITH_SEMAPHORE(tx_sem); hd_tx_active &= ~chEvtGetAndClearFlags(&hd_listener); if (!hd_tx_active) { /* - half-duplex transmit has finished. We now re-enable the - HDSEL bit for receive + half-duplex transmit has finished. We now re-enable the + HDSEL bit for receive */ SerialDriver *sd = (SerialDriver*)(sdef.serial); sdStop(sd); @@ -1275,7 +1321,6 @@ void UARTDriver::_tx_timer_tick(void) if (sdef.is_usb) { #ifdef HAVE_USB_SERIAL if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) { - _in_tx_timer = false; return; } #endif @@ -1288,18 +1333,16 @@ void UARTDriver::_tx_timer_tick(void) // half duplex we do reads in the write thread if (half_duplex) { - _in_rx_timer = true; + WITH_SEMAPHORE(rx_sem); read_bytes_NODMA(); if (_wait.thread_ctx && _readbuf.available() >= _wait.n) { chEvtSignal(_wait.thread_ctx, EVT_DATA); } - _in_rx_timer = false; } // now do the write + WITH_SEMAPHORE(tx_sem); write_pending_bytes(); - - _in_tx_timer = false; } /* @@ -1360,6 +1403,33 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol) } chSysUnlock(); break; + + case FLOW_CONTROL_RTS_DE: + // Driver Enable, RTS pin high during transmit + // If posible enable in hardware +#if defined(USART_CR3_DEM) + if (sdef.rts_alternative_function != UINT8_MAX) { + // Hand over control of RTS pin to the UART driver + palSetLineMode(arts_line, PAL_MODE_ALTERNATE(sdef.rts_alternative_function)); + + // Enable in driver, if not already set + chSysLock(); + if ((sd->usart->CR3 & USART_CR3_DEM) != USART_CR3_DEM) { + // Disable UART, set bit and then re-enable + sd->usart->CR1 &= ~USART_CR1_UE; + sd->usart->CR3 |= USART_CR3_DEM; + sd->usart->CR1 |= USART_CR1_UE; + } + chSysUnlock(); + } else +#endif + { + // No hardware support for DEM mode or + // No alternative function, RTS GPIO pin is not a conected to the UART peripheral + // This is typicaly fine becaues we do software flow control. + set_flow_control(FLOW_CONTROL_DISABLE); + } + break; } #endif // HAL_USE_SERIAL } @@ -1370,14 +1440,14 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol) */ __RAMFUNC__ void UARTDriver::update_rts_line(void) { - if (arts_line == 0 || _flow_control == FLOW_CONTROL_DISABLE) { + if (arts_line == 0 || !flow_control_enabled(_flow_control)) { return; } uint16_t space = _readbuf.space(); - if (_rts_is_active && space < 16) { + if (_rts_is_active && space < _rts_threshold) { _rts_is_active = false; palSetLine(arts_line); - } else if (!_rts_is_active && space > 32) { + } else if (!_rts_is_active && space > _rts_threshold+16) { _rts_is_active = true; palClearLine(arts_line); } @@ -1402,6 +1472,7 @@ void UARTDriver::configure_parity(uint8_t v) // not possible return; } + UARTDriver::parity = v; #if HAL_USE_SERIAL == TRUE // stop and start to take effect sdStop((SerialDriver*)sdef.serial); @@ -1620,22 +1691,38 @@ bool UARTDriver::set_options(uint16_t options) cr2 &= ~USART_CR2_SWAP; _cr2_options &= ~USART_CR2_SWAP; } -#else // STM32F4 +#elif defined(STM32F4) // STM32F4 // F4 can do inversion by GPIO if enabled in hwdef.dat, using // TXINV and RXINV options if (options & OPTION_RXINV) { if (sdef.rxinv_gpio >= 0) { hal.gpio->write(sdef.rxinv_gpio, sdef.rxinv_polarity); + if (arx_line != 0) { + palLineSetPushPull(arx_line, PAL_PUSHPULL_PULLDOWN); + } } else { ret = false; } + } else if (sdef.rxinv_gpio >= 0) { + hal.gpio->write(sdef.rxinv_gpio, !sdef.rxinv_polarity); + if (arx_line != 0) { + palLineSetPushPull(arx_line, PAL_PUSHPULL_PULLUP); + } } if (options & OPTION_TXINV) { if (sdef.txinv_gpio >= 0) { hal.gpio->write(sdef.txinv_gpio, sdef.txinv_polarity); + if (atx_line != 0) { + palLineSetPushPull(atx_line, PAL_PUSHPULL_PULLDOWN); + } } else { ret = false; } + } else if (sdef.txinv_gpio >= 0) { + hal.gpio->write(sdef.txinv_gpio, !sdef.txinv_polarity); + if (atx_line != 0) { + palLineSetPushPull(atx_line, PAL_PUSHPULL_PULLUP); + } } if (options & OPTION_SWAP) { ret = false; @@ -1706,13 +1793,23 @@ void UARTDriver::uart_info(ExpandingString &str, StatsTracker &stats, const uint } else { str.printf("UART%u ", unsigned(sdef.instance)); } - str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u\n", + str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u" +#if CH_CFG_USE_EVENTS == TRUE + " FE=%lu OE=%lu NE=%lu" +#endif + " FlowCtrl=%u\n", tx_dma_enabled ? '*' : ' ', unsigned(tx_bytes), rx_dma_enabled ? '*' : ' ', unsigned(rx_bytes), unsigned((tx_bytes * 10000) / dt_ms), - unsigned((rx_bytes * 10000) / dt_ms)); + unsigned((rx_bytes * 10000) / dt_ms), +#if CH_CFG_USE_EVENTS == TRUE + _rx_stats_framing_errors, + _rx_stats_overrun_errors, + _rx_stats_noise_errors, +#endif + _flow_control); } #endif diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index b28091e053e90a..b0e4d3b26be6a8 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -28,6 +28,10 @@ // enough for serial0 to serial9, plus IOMCU #define UART_MAX_DRIVERS 11 +#ifndef HAL_HAVE_LOW_NOISE_UART +#define HAL_HAVE_LOW_NOISE_UART 0 +#endif + class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { public: UARTDriver(uint8_t serial_num); @@ -38,6 +42,7 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { bool is_initialized() override; bool tx_pending() override; uint32_t get_usb_baud() const override; + uint8_t get_usb_parity() const override; // disable TX/RX pins for unusued uart void disable_rxtx(void) const override; @@ -74,9 +79,14 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { int8_t txinv_gpio; uint8_t txinv_polarity; uint8_t endpoint_id; + uint8_t rts_alternative_function; uint8_t get_index(void) const { return uint8_t(this - &_serial_tab[0]); } + +#if HAL_HAVE_LOW_NOISE_UART + bool low_noise_line; +#endif }; bool wait_timeout(uint16_t n, uint32_t timeout_ms) override; @@ -180,13 +190,14 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { #endif ByteBuffer _readbuf{0}; ByteBuffer _writebuf{0}; + uint32_t _rts_threshold; HAL_Semaphore _write_mutex; #ifndef HAL_UART_NODMA const stm32_dma_stream_t* rxdma; const stm32_dma_stream_t* txdma; #endif - volatile bool _in_rx_timer; - volatile bool _in_tx_timer; + HAL_Semaphore tx_sem; + HAL_Semaphore rx_sem; volatile bool _rx_initialised; volatile bool _tx_initialised; volatile bool _device_initialised; @@ -279,6 +290,13 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { // Getters for cumulative tx and rx counts uint32_t get_total_tx_bytes() const override { return _tx_stats_bytes; } uint32_t get_total_rx_bytes() const override { return _rx_stats_bytes; } +#if CH_CFG_USE_EVENTS == TRUE + uint32_t _rx_stats_framing_errors; + uint32_t _rx_stats_overrun_errors; + uint32_t _rx_stats_noise_errors; + event_listener_t err_listener; + bool err_listener_initialised; +#endif #endif }; diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index 03a8b3e745027c..1012216b023c86 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -96,22 +96,12 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) } -#ifdef ENABLE_HEAP - -void *Util::allocate_heap_memory(size_t size) -{ - memory_heap_t *heap = (memory_heap_t *)malloc(size + sizeof(memory_heap_t)); - if (heap == nullptr) { - return nullptr; - } - chHeapObjectInit(heap, heap + 1U, size); - return heap; -} - +#if ENABLE_HEAP /* - realloc implementation thanks to wolfssl, used by AP_Scripting + realloc implementation thanks to wolfssl, used by ExpandingString + and ExpandingArray */ -void *Util::std_realloc(void *addr, size_t size) +void *Util::std_realloc(void *addr, uint32_t size) { if (size == 0) { free(addr); @@ -128,33 +118,6 @@ void *Util::std_realloc(void *addr, size_t size) return new_mem; } -void *Util::heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) -{ - if (heap == nullptr) { - return nullptr; - } - if (new_size == 0) { - if (ptr != nullptr) { - chHeapFree(ptr); - } - return nullptr; - } - if (ptr == nullptr) { - return chHeapAlloc((memory_heap_t *)heap, new_size); - } - void *new_mem = chHeapAlloc((memory_heap_t *)heap, new_size); - if (new_mem != nullptr) { - const size_t old_size2 = chHeapGetSize(ptr); -#if defined(HAL_DEBUG_BUILD) && !defined(IOMCU_FW) - if (new_size != 0 && old_size2 != old_size) { - INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); - } -#endif - memcpy(new_mem, ptr, old_size2 > new_size ? new_size : old_size2); - chHeapFree(ptr); - } - return new_mem; -} #endif // ENABLE_HEAP #endif // CH_CFG_USE_HEAP @@ -227,7 +190,7 @@ void Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t dur #endif // HAL_USE_PWM #if HAL_DSHOT_ALARM_ENABLED // don't play the motors while flying - if (!(_toneAlarm_types & AP_Notify::Notify_Buzz_DShot) || get_soft_armed() || hal.rcout->get_dshot_esc_type() == RCOutput::DSHOT_ESC_NONE) { + if (!(_toneAlarm_types & uint8_t(AP_Notify::BuzzerType::DSHOT)) || get_soft_armed() || hal.rcout->get_dshot_esc_type() == RCOutput::DSHOT_ESC_NONE) { return; } @@ -269,7 +232,7 @@ uint64_t Util::get_hw_rtc() const #if HAL_GCS_ENABLED #include -#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0) +#define Debug(fmt, args ...) do { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } while (0) #endif // HAL_GCS_ENABLED #ifndef Debug @@ -641,8 +604,11 @@ void Util::apply_persistent_params(void) const been done by whether the IDs are configured in storage */ - if (strncmp(pname, "INS_ACC", 7) == 0 && - strcmp(pname+strlen(pname)-3, "_ID") == 0) { + bool legacy_acc_id = strncmp(pname, "INS_ACC", 7) == 0 && + strcmp(pname+strlen(pname)-3, "_ID") == 0; + bool new_acc_id = strncmp(pname, "INS", 3) == 0 && + strcmp(pname+strlen(pname)-6, "ACC_ID") == 0; + if (legacy_acc_id || new_acc_id) { enum ap_var_type ptype; AP_Int32 *ap = (AP_Int32 *)AP_Param::find(pname, &ptype); if (ap && ptype == AP_PARAM_INT32) { diff --git a/libraries/AP_HAL_ChibiOS/Util.h b/libraries/AP_HAL_ChibiOS/Util.h index 8e431484a096d5..5ff46016e77e9b 100644 --- a/libraries/AP_HAL_ChibiOS/Util.h +++ b/libraries/AP_HAL_ChibiOS/Util.h @@ -37,7 +37,6 @@ class ChibiOS::Util : public AP_HAL::Util { return static_cast(util); } - bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; } uint32_t available_memory() override; // get path to custom defaults file for AP_Param @@ -49,11 +48,8 @@ class ChibiOS::Util : public AP_HAL::Util { void *malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override; void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override; -#ifdef ENABLE_HEAP - // heap functions, note that a heap once alloc'd cannot be dealloc'd - virtual void *allocate_heap_memory(size_t size) override; - virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override; - virtual void *std_realloc(void *ptr, size_t new_size) override; +#if ENABLE_HEAP + void *std_realloc(void *ptr, uint32_t new_size) override; #endif // ENABLE_HEAP /* @@ -143,10 +139,6 @@ class ChibiOS::Util : public AP_HAL::Util { FlashBootloader flash_bootloader() override; #endif -#ifdef ENABLE_HEAP - static memory_heap_t scripting_heap; -#endif // ENABLE_HEAP - // stm32F4 and F7 have 20 total RTC backup registers. We use the first one for boot type // flags, so 19 available for persistent data static_assert(sizeof(persistent_data) <= 19*4, "watchdog persistent data too large"); diff --git a/libraries/AP_HAL_ChibiOS/WSPIDevice.cpp b/libraries/AP_HAL_ChibiOS/WSPIDevice.cpp index ac654919810a4e..49857a09a7e6e4 100644 --- a/libraries/AP_HAL_ChibiOS/WSPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/WSPIDevice.cpp @@ -212,7 +212,7 @@ WSPIDeviceManager::get_device(const char *name) } if (busp == nullptr) { // create a new one - busp = new WSPIBus(desc.bus); + busp = NEW_NOTHROW WSPIBus(desc.bus); if (busp == nullptr) { return nullptr; } @@ -222,7 +222,7 @@ WSPIDeviceManager::get_device(const char *name) buses = busp; } - return AP_HAL::OwnPtr(new WSPIDevice(*busp, desc)); + return AP_HAL::OwnPtr(NEW_NOTHROW WSPIDevice(*busp, desc)); } #endif // #if HAL_USE_WSPI == TRUE && defined(HAL_QPI_DEVICE_LIST) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/README.md b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/README.md new file mode 100644 index 00000000000000..19b808289ccce6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/README.md @@ -0,0 +1,130 @@ +# 3DR (mRo) Control Zero H7 OEM Flight Controller revision G + +The Control Zero H7 OEM revision G is a flight controller produced by [3DR (mRo)](https://store.3dr.com/control-zero-h7-oem-g/). + +![3DR Control Zero H7 OEM rev G - Top](https://vddwxegfxugwzpfnrrlp.supabase.co/storage/v1/object/public/Website-CDN/autopilot-img/CZOEM_revG_front.JPG) +![3DR Control Zero H7 OEM rev G - Bottom](https://vddwxegfxugwzpfnrrlp.supabase.co/storage/v1/object/public/Website-CDN/autopilot-img/CZOEM_revG_back.JPG?t=2024-03-08T20%3A18%3A49.140Z) +![3DR Control Zero H7 OEM rev G - Top w/ case](https://vddwxegfxugwzpfnrrlp.supabase.co/storage/v1/object/public/Website-CDN/autopilot-img/CZOEM_revG_case_front.JPG?t=2024-03-08T20%3A18%3A57.128Z) +![3DR Control Zero H7 OEM rev G - Bottomi w/ case](https://vddwxegfxugwzpfnrrlp.supabase.co/storage/v1/object/public/Website-CDN/autopilot-img/CZOEM_revG_case.jpg?t=2024-03-08T20%3A18%3A52.750Z) + +## Features + + Processor + STM32H743IIK6 32-bit Processor + Sensors + BMI088 6DOF + ICM20602 6DOF + ICM20948 9DOF + DPS368 Baro + Power + External Power Supply + Logic level at 3.3V + Interfaces + Bottom Connectors: 36pin front and 40pin back Samtec FTM-118-02-x and FTM-120-02-x + 8x PWM / IO - DMA capable + 1x RC Input + 5x UARTs (2x with hardware flow control) + 2x CAN + 1x SPI + 3x I2C + SWD via TC2030 header + SDCARD Socket + Memory + FRAM (256KB) + Miscellaneous + Onboard 3 color LED + Buzzer + Safety Button + + +### Uncased Weight and Dimensions + + Weight: 3.66g (13.oz) + Width: 20mm (.79in) + Length: 34mm (1.34in) + + *Case sold separately* + +## Changelog + +- M10059C - Initial Release +- M10059G adds external power supply and TCXO. + +## Pinout + +![Control Zero H7 OEM revision G pinout](https://vddwxegfxugwzpfnrrlp.supabase.co/storage/v1/object/public/Website-CDN/pinouts/czoem_pinout_revG_topview.png) + +## UART Mapping + +- SERIAL0 -> USB1, for GCS connection + +- SERIAL1 -> USART2 (TELEM 1) DMA Enabled + +- SERIAL2 -> USART3 (TELEM 2) DMA Enabled + +- SERIAL3 -> UART4 (GPS) DMA Enabled + +- SERIAL4 -> UART8 (GPS 2) DMA Enabled + +- SERIAL5 -> UART7 (DEBUG) DMA Enabled + +- SERIAL6 -> USART6 (Additional USART) DMA Enabled + +- SERIAL7 -> USB2, MAVLink interface + +## RC Input + +RC input is configured on the RC_IN pin. These are the supported RC input protocols: + +Spektrum DSM / DSM2 / DSM-X® Satellite compatible input and binding. +Futaba S.BUS® & S.BUS2® compatible input. +Graupner SUMD. Yuneec ST24. + +## Analog Inputs + +The Control Zero H7 OEM revision G has 4 ADC inputs: + +- ADC1 Pin11 -> RSSI IN +- ADC1 Pin14 -> Battery Voltage +- ADC1 Pin15 -> Battery Current +- ADC1 Pin18 -> 5V Sensor + +## PWM Output + +The Control Zero H7 OEM revision G supports up to 8 PWM outputs. All DShot and BiDirDShot capable. + +The PWM outputs are distributed in 3 groups: + +- PWM 1-4 in group 1 +- PWM 5-6 in group 4 +- PWM 7-8 in group 8 + +Channels within the same group must use only one output rate. If any channel is using DShot or BiDirDShot the rest of the group will use the said output type. + +## Power Supply + +This board requires a 5V, 1 Amps power supply. + +## Battery Monitoring + +This board has a built-in voltage and current sensors. The following settings need to be present already on the board to work with a Power Zero Module (M10077): + +- BATT_MONITOR 4 +- BATT_VOLT_PIN 14 +- BATT_CURR_PIN 15 +- BATT_VOLT_SCALE 15.3 +- BATT_CURR_SCALE 50.0 + +*Other Power Module needs to be adjusted accordingly* + +## Build + +`./waf configure --board=3DRControlZeroG` + +`./waf copter` (check ArduPilot's docs for more info about the available targets) + +The compiled binary will be located in `build/3DRControlZeroG/bin/arducopter.apj`. + +## Uploading Firmware + +Any Control Zero H7 OEM revision G has a preloaded Ardupilot bootloader, which allows the user to use a compatible Ground Station software to upload the `.apj` file. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/defaults.parm new file mode 100644 index 00000000000000..689afeaab08552 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/defaults.parm @@ -0,0 +1,4 @@ +#Default Parameters for the mRo Control Zero OEM H7 + +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef-bl.dat new file mode 100644 index 00000000000000..f9032408a4712d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef-bl.dat @@ -0,0 +1,58 @@ +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# USB setup +USB_VENDOR 0x26ac +USB_PRODUCT 0x1124 +USB_STRING_MANUFACTURER "3DR" +USB_STRING_PRODUCT "CZOEMrevG" + +# crystal frequency +OSCILLATOR_HZ 24000000 +define STM32_HSE_BYPASS +define SMPS_EXT + +# board ID for firmware load +APJ_BOARD_ID 1124 + +FLASH_SIZE_KB 2048 + +# 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 + +PB11 LED_BOOTLOADER OUTPUT + +PH5 VDD_1V2_CORE_EN OUTPUT HIGH + +# define all 3 to make LED output White. +PB1 LED_ACTIVITY OUTPUT +PB3 LED_ACTIVITY2 OUTPUT +# PB11 LED_ACTIVITY3 OUTPUT + +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 + +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +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 ICM_20602_CS CS +PD7 BARO_CS CS +PD10 FRAM_CS CS SPEED_VERYLOW NODMA +PE15 ICM_20948_CS CS +PF6 BMI088_ACCEL_CS CS +PF10 BMI088_GYRO_CS CS +#PG9 EXTERNAL CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef.dat new file mode 100644 index 00000000000000..3223ef5ef2400d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/3DRControlZeroG/hwdef.dat @@ -0,0 +1,266 @@ +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1124 + +# crystal frequency +OSCILLATOR_HZ 24000000 +define STM32_HSE_BYPASS +define SMPS_EXT + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# start on 2th sector (1st sector for bootloader) +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 + +# USB setup +USB_VENDOR 0x26ac +USB_PRODUCT 0x1124 +USB_STRING_MANUFACTURER "3DR" +USB_STRING_PRODUCT "CZOEMrevG" + +PA8 RCC_MCO_1 OUTPUT LOW + +PH5 VDD_1V2_CORE_EN OUTPUT HIGH + +# RC Input set for Interrupt not DMA +PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW + +# GPIO(70) # also USART6_RX for serial RC + +# Control of Spektrum power pin +PE4 SPEKTRUM_PWR OUTPUT LOW GPIO(70) +define HAL_GPIO_SPEKTRUM_PWR 70 + +# Spektrum Power is Active High +define HAL_SPEKTRUM_PWR_ENABLED 0 + +# Spektrum RC Input pin, used as GPIO for bind for Satellite Receivers +PB0 SPEKTRUM_RC INPUT PULLUP GPIO(71) +define HAL_GPIO_SPEKTRUM_RC 71 + +# Order of I2C buses +I2C_ORDER I2C1 I2C3 I2C4 + +# this board has no internal I2C buses so mark them all external +define HAL_I2C_INTERNAL_MASK 0 + +# order of UARTs and suggested uses +# USART2 TELEM1 +# USART3 TELEM2 +# UART4 GPS +# UART8 GPS2 +# UART7 DEBUG + +# USART6 RC input (Only RX pin is connected) + +# OTG1 and OTG2 are USB devices (1x physical USB connection enumerated as 2x logical ports) + +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 USART6 OTG2 + +# Another USART, this one for telem1. This one has RTS and CTS lines. +# USART2 telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# The telem2 USART, with RTS and CTS lines. +# USART3 telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +PD11 USART3_CTS USART3 +PD12 USART3_RTS USART3 + +# UART4 GPS +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +# UART7 +PE8 UART7_TX UART7 NODMA +PE7 UART7_RX UART7 NODMA + +# USART6 +PG14 USART6_TX USART6 +PG9 USART6_RX USART6 +PG13 USART6_CTS USART6 +PG12 USART6_RTS USART6 + +# UART8 GPS2 +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 + +# RSSI Analog Input +PC1 RSSI_IN ADC1 + +# Safety Switch Input +PC4 SAFETY_IN INPUT PULLDOWN +define HAL_HAVE_SAFETY_SWITCH 1 + +# Battery Analog Sense Pins +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) + +# Now setup the default battery pins driver analog pins and default +# scaling for the power brick (Adjusted for Power Zero - M10077). +define HAL_BATT_VOLT_PIN 14 +define HAL_BATT_CURR_PIN 15 +define HAL_BATT_VOLT_SCALE 15.3 +define HAL_BATT_CURR_SCALE 50.0 + +#SPI1 ICM_20602 / ICM_20948 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +#SPI2 FRAM / DPS310 +PB10 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +#SPI5 BMI088 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +#SPI6 External +#PG13 SPI6_SCK SPI6 +#PG12 SPI6_MISO SPI6 +#PG14 SPI6_MOSI SPI6 + +# This is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN. +PA9 VBUS INPUT OPENDRAIN + +# This input pin is used to detect that power is valid on USB. +PC0 VBUS_VALID INPUT PULLDOWN + +# 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 + +# First I2C bus. +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Second I2C bus. +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# Third I2C bus. +PB6 I2C4_SCL I2C4 +PB7 I2C4_SDA I2C4 + +# microSD card +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# CS pins for SPI sensors. The labels for all CS pins need to +# match the SPI device table later in this file. +PC2 ICM_20602_CS CS +PD7 BARO_CS CS +PD10 FRAM_CS CS SPEED_VERYLOW NODMA +PE15 ICM_20948_CS CS +PF6 BMI088_ACCEL_CS CS +PF10 BMI088_GYRO_CS CS +#PG9 EXTERNAL CS + +# CAN Busses +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB13 CAN2_TX CAN2 +PB12 CAN2_RX CAN2 + +# CAN Silent Pins LOW Enable +PF5 GPIO_CAN_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(72) + +# 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) BIDIR +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR +PI5 TIM8_CH1 TIM8 PWM(7) GPIO(56) BIDIR +PI6 TIM8_CH2 TIM8 PWM(8) GPIO(57) + +# This is the invensense 20602 data-ready pin. +PD15 MPU_DRDY INPUT + +# Power Supply Enable +PE3 VDD_1V8_3V3_SENSORS_EN OUTPUT HIGH + +# Power Supply Enable 3.3v Periph/Spektrum +PC5 VDD_3V3_PERIPH_EN OUTPUT HIGH + +# 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_VALID INPUT PULLDOWN + +SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ +SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ +SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 7*MHZ +SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 7*MHZ + +# Enable RAMTROM parameter storage. +define HAL_WITH_RAMTRON 1 + +# Enable FAT filesystem support (needs a microSD defined via SDMMC). +define HAL_OS_FATFS_IO 1 + +# Control Zero has a TriColor LED, Red, Green, Blue +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# LED setup for PixracerLED driver +PB11 LED_R OUTPUT HIGH GPIO(0) +PB1 LED_G OUTPUT HIGH GPIO(1) +PB3 LED_B OUTPUT HIGH GPIO(2) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 + +# DMA_PRIORITY SDMMC* +DMA_NOSHARE SPI1* SPI5* + +# 3 IMUs +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE +IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90 +IMU Invensensev2 SPI:icm20948 ROTATION_ROLL_180_YAW_90 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# 1 baro +BARO DPS280 SPI:dps310 + +# 1 compass +COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat index b7ccd9ff579f7f..3d92193527e5e4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat @@ -111,6 +111,7 @@ PC14 LED_BLUE OUTPUT LOW GPIO(0) PA13 LED_GREEN OUTPUT LOW GPIO(1) #PC15 LED_RED OUTPUT LOW GPIO(2) +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 0 define HAL_GPIO_B_LED_PIN 1 #define HAL_GPIO_C_LED_PIN 2 @@ -163,9 +164,6 @@ COMPASS LIS3MDL SPI:lis3mdl false ROTATION_ROLL_180_YAW_270 define HAL_OS_FATFS_IO 1 -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" - # define default battery setup define HAL_BATT_MONITOR_DEFAULT 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat index 299624fd64a654..b46ceda16840a0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat @@ -112,6 +112,7 @@ PC14 LED_BLUE OUTPUT LOW GPIO(0) PA13 LED_GREEN OUTPUT LOW GPIO(1) PC15 LED_RED OUTPUT LOW GPIO(2) +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 define HAL_GPIO_A_LED_PIN 0 define HAL_GPIO_B_LED_PIN 1 define HAL_GPIO_C_LED_PIN 2 @@ -168,9 +169,6 @@ COMPASS LIS3MDL SPI:lis3mdl false ROTATION_ROLL_180_YAW_90 define HAL_OS_FATFS_IO 1 -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" - # define default battery setup define HAL_BATT_MONITOR_DEFAULT 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_core_board.png b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_core_board.png new file mode 100644 index 00000000000000..af10c4ea12a12e Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_core_board.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_overview.jpg b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_overview.jpg new file mode 100644 index 00000000000000..abec38a65d5940 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_overview.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_power_board.png b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_power_board.png new file mode 100644 index 00000000000000..dd1906a5bece94 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/AET-H743-Basic_power_board.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/README.md b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/README.md new file mode 100644 index 00000000000000..8108d09740d3ab --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/README.md @@ -0,0 +1,142 @@ +# AET-H743-Basic Flight Controller + +The AET-H743-Basic is a flight controller designed and produced by AeroEggTech + +## Features + + - STM32H743 microcontroller + - Dual ICM42688P IMUs + - 13 PWM / Dshot outputs + - 8 UARTs, one with CTS/RTS flow control pins + - 1 CAN + - Dedicated USB board + - DPS310 or SPL06 barometer + - 5V/6V/7V 10A Servo rail BEC + - 9V 2A BEC for VTX, GPIO controlled + - 5V 4A BEC + - MicroSD Card Slot + - 2-way camera input + - AT7456E OSD + - 2 I2Cs + +## Physical + +![AET-H743-Basic overview](AET-H743-Basic_overview.jpg) + +![AET-H743-Basic core board](AET-H743-Basic_core_board.png) + +![AET-H743-Basic power board](AET-H743-Basic_power_board.png) + + +## Mechanical + + - Dimensions: 36 x 47 x 17 mm + - Weight: 45g + + +## Power supply + +The AET-H743-Basic supports 2-6s Li battery input. It has 3 ways of BEC, which result in 6 ways of power supplys. Please see the table below. + +| Power symbol | Power source | Max power (current) | +|--------------|--------------|---------------------| +| 5V | from 5V BEC | 20W (4A) | +| 9V | from 9V BEC | 18W (2A) | +| 9Vsw | from 9V BEC, controlled by MCU with an NPN MOS | 10W (1A) | +| 4V5 | from USB or 5V BEC, with a diode | 5W (1A) | +| VX | from Servo rail VX BEC, default 5V, can be changed to 6V or 7V | 50W (10A) | +| BAT | directly from battery | (5A) | + + +## 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 favorite DFU loading tool, such as Mission Planner. + +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. + +## UART Mapping + +All UARTs are DMA capable. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2) + - SERIAL2 -> UART2 (GPS) + - SERIAL3 -> UART3 (MAVLink2) + - SERIAL4 -> UART4 (GPS2, RX4 is also available as ESC telem if protocol is changed for this UART) + - SERIAL5 -> USB (SLCAN) + - SERIAL6 -> UART6 (RCIN) + - SERIAL7 -> UART7 (MAVLink2, Integrated Bluetooth module) + - SERIAL8 -> UART8 (User) + + +## RC Input + +The default RC input is configured on the UART6 and supports all RC protocols except PPM. The SBUS pin is inverted and connected to RX6. RC can be attached to any UART port as long as the serial port protocol is set to `SERIALn_PROTOCOL=23` and SERIAL6_Protocol is changed to something other than '23'. + + +## OSD Support + +The AET-H743-Basic supports onboard analog SD OSD using a AT7456 chip. The analog VTX should connect to the VTX pin. + + +## PWM Output + +The AET-H743-Basic supports up to 13 PWM outputs. + +All the channels support DShot. + +Outputs are grouped and every output within a group must use the same output protocol: + +1, 2 are Group 1; + +3, 4, 5, 6 are Group 2; + +7, 8, 9, 10 are Group 3; + +11, 12 are Group 4; + +13(LED) is Group 5; + +Output 13 can be used as LED neopixel output; + +## Battery Monitoring + +The board has two internal voltage sensors and one integrated current sensor, and a second external current sensor input. + +The voltage sensors can handle up to 6S LiPo batteries. + +The first voltage/current sensor is enabled by default and the pin inputs for the second, unenabled sensor are also set by default: +* BATT_MONITOR 4 +* BATT_VOLT_PIN 10 +* BATT_CURR_PIN 11 +* BATT_VOLT_MULT 11 +* BATT_CURR_SCALE 40 +* BATT2_VOLT_PIN 18 +* BATT2_CURR_PIN 7 +* BATT2_VOLT_MULT 11 + +## Compass + +The AET-H743-Basic has no built-in compass, so if needed, you should use an external compass. + +## Analog cameras + +The AET-H743-Basic supports up to 2 cameras, connected to pin CAM1 and CAM2. You can select the video signal to VTX from camera by an RC channel. Set the parameters below: + +- RELAY2_FUNCTION = 1 +- RELAY_PIN2 = 82 +- RC8_OPTION = 34 + +## 9V switch + +The 9Vsw power supply can be controlled by an RC channel. Set the parameters below: + +- RELAY1_FUNCTION = 1 +- RELAY_PIN = 81 +- RC7_OPTION = 28 + +## Bluetooth + +The AET-H743-Basic support both legacy bluetooth SPP and BLE serial. The bluetooth uses UART7 as serial port. Search for `AET-H743-SPP` or `AET-H743-BLE` to connect. + +Note: you should connect a battery to the board so the bluetooth module can work. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/defaults.parm new file mode 100644 index 00000000000000..731906830a3a2b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/defaults.parm @@ -0,0 +1,3 @@ +# setup for LEDs on chan13 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef-bl.dat new file mode 100644 index 00000000000000..5eee362f08c5b9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef-bl.dat @@ -0,0 +1,49 @@ +# hw definition file for processing by chibios_pins.py +# for AET H743-Basic bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_AET-H743-Basic + +# 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 +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + + +# order of UARTs (and USB). Allow bootloading on USB and telem1 +SERIAL_ORDER OTG1 UART7 + +# UART7 (telem1) +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +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 + +# Add CS pins to ensure they are high in bootloader +PC15 IMU1_CS CS +PB12 MAX7456_CS CS +PE11 IMU2_CS CS +PD4 EXT_CS1 CS +PE2 EXT_CS2 CS +PC13 IMU3_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef.dat new file mode 100644 index 00000000000000..e16c0b29f5e932 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AET-H743-Basic/hwdef.dat @@ -0,0 +1,205 @@ +# hw definition file for processing by chibios_pins.py +# for AET H743-Basic + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_AET-H743-Basic + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 +env OPTIMIZE -Os + +USB_STRING_MANUFACTURER "AET" + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# SPI1 for IMU1 (ICM-42688) +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PC15 IMU1_CS CS + +# SPI2 for MAX7456 OSD +PB12 MAX7456_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI4 for IMU3 (ICM-42688) +PC13 IMU3_CS CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# two I2C bus +I2C_ORDER I2C2 I2C1 + +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# ADC +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1) +PA7 BATT2_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT2_VOLT_PIN 18 +define HAL_BATT2_CURR_PIN 7 +define HAL_BATT_VOLT_SCALE 11.0 +define HAL_BATT_CURR_SCALE 40.0 +define HAL_BATT2_VOLT_SCALE 11.0 + +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 + +# LED +# green LED1 marked as B/E +# blue LED0 marked as ACT +PE3 LED0 OUTPUT LOW GPIO(90) # blue +PE4 LED1 OUTPUT LOW GPIO(91) # green +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 + +define HAL_GPIO_LED_ON 1 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 OTG2 USART6 UART7 UART8 + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 +PD9 USART3_RX USART3 +PD8 USART3_TX USART3 + +# UART4 +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# USART6 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +# UART7 +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + +# UART8 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# Serial functions +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS +define DEFAULT_SERIAL3_BAUD 115 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MAVLink2 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN +define DEFAULT_SERIAL7_BAUD 115 +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2 + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# Motors +PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50) +PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51) +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED + +# Beeper +PA15 TIM2_CH1 TIM2 GPIO(32) ALARM + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# GPIOs +PD10 PINIO1 OUTPUT GPIO(81) LOW +PD11 PINIO2 OUTPUT GPIO(82) LOW + +DMA_PRIORITY S* + +define HAL_STORAGE_SIZE 32768 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 + +# spi devices +SPIDEV icm42688_0 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8 +SPIDEV icm42688_1 SPI4 DEVID1 IMU3_CS MODE3 2*MHZ 16*MHZ +SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ + + +DMA_NOSHARE SPI1* SPI4* + +# 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 + +# two IMUs +# ICM42688P, ICM42688P +IMU Invensensev3 SPI:icm42688_0 ROTATION_YAW_180 +IMU Invensensev3 SPI:icm42688_1 ROTATION_YAW_270 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# BAROs +BARO SPL06 I2C:0:0x76 +BARO DPS310 I2C:0:0x76 + +define HAL_OS_FATFS_IO 1 + +# 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/AIRLink/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat index 500cce011091cc..88db88f3b7e5e0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat @@ -229,9 +229,9 @@ PE4 LED_GREEN OUTPUT GPIO(91) LOW PE3 LED_BLUE OUTPUT GPIO(92) HIGH # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat index 8d728a45672cfc..6e780be0b3ad35 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat @@ -30,8 +30,6 @@ PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH CAN_ORDER 1 -define HAL_NO_MONITOR_THREAD - # debugger support PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat index 4dc19548f3c62c..2fb7970bf13742 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat @@ -24,8 +24,7 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat index f107450d24c8c9..9a36471c7f0329 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat @@ -33,6 +33,10 @@ SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 USART6 OTG2 # order of UARTs (and USB) with IO MCU # SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 +# debug console +STDOUT_SERIAL SD3 +STDOUT_BAUDRATE 57600 + # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN @@ -79,7 +83,7 @@ PH14 UART4_RX UART4 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# USART6 is for IOMCU +# used for RC SBUS PC6 USART6_TX USART6 PC7 USART6_RX USART6 @@ -264,12 +268,11 @@ 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # ID pins PG0 HW_VER_REV_DRIVE OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat index 82e803a3c79460..204b261acbc500 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat @@ -39,12 +39,12 @@ PA8 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PA9 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PA10 LED_B1 OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # CAN bus PA11 CAN1_RX CAN1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index 68e50acd54a32c..e82ea526d0a0a5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -65,12 +65,12 @@ PA8 LED_R1 OUTPUT HIGH GPIO(0) PA9 LED_G1 OUTPUT HIGH GPIO(1) PA10 LED_B1 OUTPUT HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # CAN bus PA11 CAN1_RX CAN1 @@ -131,3 +131,4 @@ define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat index 56b7a3f6108f90..a75dcba4751d32 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat @@ -58,12 +58,12 @@ PA8 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PA9 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PA10 LED_B1 OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # CAN bus PA11 CAN1_RX CAN1 @@ -124,3 +124,4 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 1 define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat index df4a0950eb87ec..172deb9b6c2e24 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat @@ -62,12 +62,12 @@ PA8 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PA9 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PA10 LED_B1 OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # CAN bus PA11 CAN1_RX CAN1 @@ -135,3 +135,4 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 1 define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat index 5e48e7763513d6..a817aea2f9b7a3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat @@ -32,7 +32,6 @@ MAIN_STACK 0x300 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0xA00 -define HAL_NO_MONITOR_THREAD # we setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 @@ -92,7 +91,6 @@ COMPASS QMC5883L I2C:0:0xd false ROTATION_YAW_180 define HAL_USE_ADC FALSE # disable unnecessary threads -define HAL_NO_MONITOR_THREAD define HAL_NO_TIMER_THREAD # enable LED @@ -100,10 +98,10 @@ define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY #GPIO LED -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.dat index a7d5e558dfd221..56a3ef2dc0b8a3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.dat @@ -49,13 +49,13 @@ define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 #GPIO LED -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0) PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1) PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc index 726c65dd548746..8de03084121513 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc @@ -36,8 +36,6 @@ MAIN_STACK 0x300 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0xA00 -define HAL_NO_MONITOR_THREAD - # setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AnyleafH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AnyleafH7/hwdef.dat index ae5f1d61295bec..1e2dbea3581940 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AnyleafH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AnyleafH7/hwdef.dat @@ -50,6 +50,7 @@ define HAL_BATT_CURR_SCALE 40.0 # This depends on the ESC's V/mA output ratio. # LED PC13 LED0 OUTPUT LOW GPIO(90) # Amber; System status. PC0 LED1 OUTPUT LOW GPIO(91) # Not connected; GPS Status. (Required, or the system status LED won't work.) +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 91 @@ -111,6 +112,14 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 1 # DPS310 integrated on I2C2 bus, multiple possible choices for external barometer BARO DPS310 I2C:0:0x77 +# 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 + # setup for OSD define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 5 # MSP Displayport +define HAL_LOGGING_DATAFLASH_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat index 6a1236d5b1db62..f31999bc433953 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat @@ -100,6 +100,7 @@ define BOARD_RSSI_ANA_PIN 8 # green LED1 marked as B/E PE3 LED0 OUTPUT LOW GPIO(90) # blue PE4 LED1 OUTPUT LOW GPIO(91) # orange +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 91 define HAL_GPIO_B_LED_PIN 90 @@ -154,10 +155,10 @@ PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR //S1 PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) //S2 PA0 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR //S3 PA1 TIM2_CH2 TIM2 PWM(4) GPIO(53) //S4 -PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR //S5 -PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) //S6 -PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR //S7 -PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) //S8 +PA2 TIM5_CH3 TIM5 PWM(8) GPIO(54) BIDIR //S8 +PA3 TIM5_CH4 TIM5 PWM(7) GPIO(55) //S7 +PD12 TIM4_CH1 TIM4 PWM(6) GPIO(56) BIDIR //S6 +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(57) //S5 PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR //S9 PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) //S10 @@ -218,6 +219,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin # enable logging to dataflash define HAL_LOGGING_DATAFLASH_ENABLED 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat index ec4c000c005b04..aa029c0acda723 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat @@ -23,6 +23,7 @@ SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 PA14 LED_BLUE OUTPUT LOW GPIO(0) PA13 LED_GREEN OUTPUT LOW GPIO(1) +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 0 define HAL_GPIO_B_LED_PIN 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat index c3a950437836c4..ea7aec21b57e57 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + PA10 USART1_RX USART1 HIGH PULLUP PB11 USART3_RX USART3 HIGH PULLUP diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat index 69919b27275beb..8e451e2bed4fcf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat @@ -99,8 +99,9 @@ PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) BIDIR # M3 PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4 # LEDs +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PB5 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # LED strip PB6 TIM4_CH1 TIM4 PWM(5) GPIO(56) # M7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat index 9f7f7d829fbd01..e27f72b6000575 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat @@ -89,9 +89,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_NO_MONITOR_THREAD - - define HAL_DEVICE_THREAD_STACK 768 define AP_PARAM_MAX_EMBEDDED_PARAM 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md new file mode 100644 index 00000000000000..94cffb226d0e58 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md @@ -0,0 +1,92 @@ +# iFlight BLITZ F745 Flight Controller + +https://shop.iflight.com/electronics-cat27/BLITZ-F745-Flight-Controller-Pro2141 + +The BLITZ F745 is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU: BGA-STM32F745, 216MHz + - Gyro: ICM42688 + - 32Mbytes Onboard Flash + - BEC output: 5V 2.5A + - Barometer: DPS310 + - OSD: AT7456E + - 6 UARTS: (UART1, UART2, UART3, UART4, UART5, UART6) + - I2C for external compass. + - 9 PWM outputs (8 motor outputs and 1 LED output) + +## Pinout + +![BLITZ F745 Board](blitz_f7_pinout.jpg "BLITZ F745") + +## 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 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (GPS, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|RX6|UART6 (ESC telemetry)| + +Note:UART3 is used for GPS not UART4 as shown in typical wiring diagram + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX). It supports all serial RC protocols. + +## OSD Support + +The BLITZ F745 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ F745 has 9 PWM outputs. The pads for motor output are M1 to M8 on the board and M1-M4 are also in the ESC connector housing. All 9 outputs support DShot and the first four outputs support bi-directional DShot as well as all PWM types. Output 9 is the "LED" pin and is configured for serial LED by default. + +The PWM are in three 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. + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current 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 11 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ F745 does not have a builtin compass, but you can attach an external compass to I2C 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/BlitzF745/blitz_f7_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/blitz_f7_pinout.jpg new file mode 100644 index 00000000000000..1867bf29e456bb Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/blitz_f7_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm new file mode 100644 index 00000000000000..558c392df49267 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat new file mode 100644 index 00000000000000..3300a02844ece6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat @@ -0,0 +1,42 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_F7_AIO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzF7 + +# 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) +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 + + + + +# Chip select pins +PA15 FLASH1_CS CS +PE4 OSD1_CS CS +PA4 GYRO1_CS CS + +PC9 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat new file mode 100644 index 00000000000000..f4f12ed84fd984 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat @@ -0,0 +1,164 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_F7_AIO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzF7 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 96 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 5 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PD6 SPI3_MOSI SPI3 + +# SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# Chip select pins +PA15 FLASH1_CS CS +PE4 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PD3 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - VTX +PA10 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort + +# USART2 - RX +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 - GPS +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS + +# UART4 +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None + +# USART6 - ESC Telem +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry + +# I2C ports +I2C_ORDER I2C1 I2C4 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C4 +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# Servos + +# ADC ports + +# ADC1 +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_CURR_SCALE 50.0 +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_VOLT_SCALE 11.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB4 TIM3_CH1 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB0 TIM3_CH3 TIM3 PWM(2) GPIO(51) # M2 +PB5 TIM3_CH2 TIM3 PWM(3) GPIO(52) # M3 +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5 +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) # M6 +PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) # M7 +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) # M8 + +# LEDs +PC9 TIM8_CH4 TIM8 PWM(9) GPIO(58) # M9 + +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +PD15 LED0 OUTPUT LOW GPIO(90) +define AP_NOTIFY_GPIO_LED_1_PIN 90 + +# Dataflash setup +SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI4 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# IMU setup + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +DMA_NOSHARE TIM3_UP TIM1_UP SPI1* +DMA_PRIORITY TIM3_UP TIM1_UP SPI1* + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +# Barometer setup +BARO DPS310 I2C:1: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 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# save some flash +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745AIO/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745AIO/hwdef-bl.dat index eb9a170bc88d27..7a226ae2b9b99b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745AIO/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745AIO/hwdef-bl.dat @@ -3,8 +3,7 @@ # for IFLIGHT_BLITZ_F7_AIO hardware. # thanks to betaflight for pin information -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # MCU class and specific type MCU STM32F7xx STM32F745xx diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md new file mode 100644 index 00000000000000..64c4321d822f90 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md @@ -0,0 +1,113 @@ +# iFlight BLITZ H7 Pro Flight Controller + +The Blitz H7 Pro is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - Gyro: ICM42688 + - 32Gb SDCard for logging + - BEC output: 5V 2.5A, switch controlled 12v 2A + - Barometer: DPS310 + - OSD: AT7456E + - 7x UARTs + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - 2x I2C for external compass, airspeed, etc. + - CAN port + +## Pinout + +![BLITZ H7 Pro Board](blitz_h7_pro.png "BLITZ H7 Pro") + +back side pinout image pending from iFlight + +The expansion connector provides access to the following pins: + - CAN+/CAN- + - M9 through M12 + - TX7/RX7 + - SCL2/SDA2 + - RSSI + - 5V/12V/GND + +## 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, DMA-enabled)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (GPS, DMA-enabled)| +|SERIAL5|RX5|UART5 (ESC Telemetry)| +|SERIAL6|TX6/RX6|UART6| +|SERIAL7|TX7/RX7|UART7| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX) pins which forms part of the DJI connector. It supports all serial RC protocols. + +## OSD Support + +The BLITZ H7 Pro supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ H7 Pro has 13 PWM outputs. The pads for motor output M1-M4 are in one ESC connector and M5-M8 in the second ESC connector. The remaining outputs are on the pads on the daughterboard. The first 8 outputs support bi-directional DShot and DShot, as well as all PWM types. Outputs 9-10 support DShot, as well as all PWM types and outputs 11-12 only support PWM. + +The PWM are in in five groups: + + - PWM 1-2 in group1 + - PWM 3-6 in group2 + - PWM 7-10 in group3 + - PWM 11-12 in group4 + - PWM 13 in group5 +.. note:: for users migrating from BetaflightX quads, the first four outputs M1-M4 have been configured for use with existing motor wiring using these default parameters: + +- :ref:`FRAME_CLASS` = 1 (Quad) +- :ref:`FRAME_TYPE` = 12 (BetaFlightX) + + +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. + +Video Power Control +================ + +The 12V video power can be turned off/on using GPIO 81 which is already assigned by default to RELAY2. This relay can be controlled either from the GCS or using a transmitter channel (See :ref:`common-auxiliary-functions`) +RSSI +==== + +Analog RSSI pin is "4" + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 11 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ H7 Pro does not have a builtin compass, but you can attach an external compass to I2C pins. + +## 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/BlitzH743Pro/blitz_h7_pro.png b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/blitz_h7_pro.png new file mode 100644 index 00000000000000..b1a6e0e177efca Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/blitz_h7_pro.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm new file mode 100644 index 00000000000000..2059843c09e121 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm @@ -0,0 +1,6 @@ +# setup for LEDs on chan9 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 + +#enable CAN port +CAN_P1_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat new file mode 100644 index 00000000000000..0f0993178803cc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat @@ -0,0 +1,44 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_H7_PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzH7Pro + +# 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 + + + + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +PD10 VTX_PWR OUTPUT GPIO(81) HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat new file mode 100644 index 00000000000000..794d4d558e3c28 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat @@ -0,0 +1,186 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_H7_PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzH7Pro + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +FLASH_RESERVE_START_KB 384 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +# Beeper +PA15 TIM2_CH1 TIM2 GPIO(32) ALARM + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 UART8 OTG2 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - VTX +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort + +# USART2 - RX +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 - GPS +PB8 UART4_RX UART4 +PB9 UART4_TX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry + +# UART7 +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +# Not pinned out +PE9 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# UART8 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA + +# I2C ports +I2C_ORDER I2C1 I2C2 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define HAL_OS_FATFS_IO 1 + +# CAN +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# VTX power +PD10 VTX_PWR OUTPUT GPIO(81) HIGH +define RELAY2_PIN_DEFAULT 81 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 50.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 +define HAL_BATT_MONITOR_DEFAULT 4 +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2 +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) BIDIR # M3 +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) # M4 +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR # M5 +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) # M6 +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR # M7 +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # M8 +# Motor outputs on daughterboard +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) # M9 +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10 +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA # M11 +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA # M12 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # M9 + +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 + +PE3 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PE4 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +BARO DPS310 I2C:1:0x76 + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +DMA_NOSHARE TIM3_UP TIM5_UP TIM4_UP SPI1* +DMA_PRIORITY TIM3_UP TIM5_UP TIM4_UP SPI1* + +# 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 1 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md new file mode 100644 index 00000000000000..e44dd4a6d29156 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md @@ -0,0 +1,89 @@ +# iFlight BLITZ Mini F745 Flight Controller + +https://shop.iflight.com/BLITZ-Mini-F745-Flight-Controller-Pro2142 + +The BLITZ Mini F745 is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU: BGA-STM32F745, 216MHz + - Gyro: ICM42688 + - 16Mbytes Onboard Flash + - BEC output: 5V 2.5A + - Barometer: DPS310 + - OSD: AT7456E + - 6 UARTS: (UART1, UART2, UART3, UART4, UART5, UART6) + - I2C for external compass. + - 5 PWM outputs (4 motor outputs and 1 LED output) + +## Pinout + +![BLITZ Mini F745 Board](blitz_f7_pinout.jpg "BLITZ Mini F745") + +## 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 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (GPS, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|RX6|UART6 (ESC telemetry)| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX). It supports all serial RC protocols. + +## OSD Support + +The BLITZ Mini F745 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ Mini F745 has 5 PWM outputs. The motor outputs M1-M4 are in the ESC connector housing. All 5 outputs support DShot and the first four outputs support bi-directional DShot as well as all PWM types. Output 5 is the "LED" pin and is configured for serial LED by default. + +The PWM are in two 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. + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current 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 11 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ Mini F745 does not have a builtin compass, but you can attach an external compass to I2C 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/BlitzMiniF745/blitz_f7_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/blitz_f7_pinout.jpg new file mode 100644 index 00000000000000..5bfb22ea692758 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/blitz_f7_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm new file mode 100644 index 00000000000000..5adf224c99384d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat new file mode 100644 index 00000000000000..5b31b8c20b51d4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat @@ -0,0 +1,4 @@ + +include ../BlitzF745/hwdef-bl.dat + +APJ_BOARD_ID AP_HW_BlitzF7Mini diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat new file mode 100644 index 00000000000000..300a026dde9820 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat @@ -0,0 +1,11 @@ +include ../BlitzF745/hwdef.dat + +APJ_BOARD_ID AP_HW_BlitzF7Mini + +undef IMU +undef PE9 PE11 PE13 PE14 PC9 + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_135 + +# LEDs +PC9 TIM8_CH4 TIM8 PWM(5) GPIO(54) # M5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md new file mode 100644 index 00000000000000..37dfb7934484ed --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md @@ -0,0 +1,106 @@ +# iFlight BLITZ Wing H743 Flight Controller + +The BLITZ Wing H743 is a flight controller produced by [iFlight](https://shop.iflight.com/electronics-cat27/BLITZ-Wing-H743-Flight-Controller-Pro2174). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - Gyro: ICM42688 + - SDCard for logging + - 5V 3A BEC for Flight Controller + - 9V 3A BEC for VTX + - 5-8.4V 6A BEC for Servo + - Barometer: DPS310 + - OSD: AT7456E + - 7x UARTs + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - 2x I2C for external compass, airspeed, etc. + - CAN port + +## Physical + - Mount pattern: 30.5*30.5mm/?4 + - Dimensions: 36.9*52mm + - Weight: 35g + +## Pinout + +![BLITZ Wing H743 Board](blitz_h7_wing_top.PNG "BLITZ Wing H743 Top") +![BLITZ Wing H743 Board](blitz_h7_wing_middle.PNG "BLITZ Wing H743 Middle") +![BLITZ Wing H743 Board](blitz_h7_wing_bottom.PNG "BLITZ Wing H743 Bottom") + +## 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, DMA-enabled)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (GPS, DMA-enabled)| +|SERIAL6|TX6/RX6|UART6| +|SERIAL7|TX7/RX7|UART7| +|SERIAL8|TX8/RX8|UART8 (ESC Telemetry)| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX) pins which forms part of the DJI connector. It supports all serial RC protocols. + +## OSD Support + +The BLITZ Wing H743 supports OSD using OSD_TYPE 1 (MAX7456 driver). Simultaneously, DisplayPort HD OSD is enabled by default and available on the HD VTX connector. + +## PWM Output + +The BLITZ Wing H743 has 13 PWM outputs. The first 8 outputs support bi-directional DShot and DShot, as well as all PWM types. Outputs 9-10 support DShot, as well as all PWM types and outputs 11-12 only support PWM. + +The PWM are in in five groups: + + - PWM 1-2 in group1 + - PWM 3-6 in group2 + - PWM 7-10 in group3 + - PWM 11-12 in group4 + - PWM 13 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. + +## Video Power Control + +The 9V video power can be turned off/on using GPIO 81 which is already assigned by default to RELAY2. This relay can be controlled either from the GCS or using a transmitter channel (See :ref:`common-auxiliary-functions`) + +## Analog Airspeed Input + +The analog airspeed pin is "4" + +## Battery Monitoring + +The board has a built-in voltage sensor and current sensor. The voltage sensor can handle up to 8S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 11 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ Wing H743 does not have a builtin compass, but you can attach an external compass to I2C pins. + +## 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/BlitzWingH743/blitz_h7_wing_bottom.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_bottom.PNG new file mode 100644 index 00000000000000..9de0830011dd31 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_bottom.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG new file mode 100644 index 00000000000000..1aad2f38886b8d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG new file mode 100644 index 00000000000000..6ec7202d6ae388 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm new file mode 100644 index 00000000000000..5d4fab1adaed4b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat new file mode 100644 index 00000000000000..2406ec403c5e77 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../BlitzH743Pro/hwdef-bl.dat + +APJ_BOARD_ID AP_HW_BlitzH7Wing \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat new file mode 100644 index 00000000000000..2332cd2e028032 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat @@ -0,0 +1,13 @@ +include ../BlitzH743Pro/hwdef.dat + +APJ_BOARD_ID AP_HW_BlitzH7Wing + +undef SERIAL_ORDER +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 OTG2 + +undef DEFAULT_SERIAL5_PROTOCOL +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry +undef HAL_FRAME_TYPE_DEFAULT + +undef PC5 +undef BOARD_RSSI_ANA_PIN diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm new file mode 100644 index 00000000000000..0327366dcabc51 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/defaults.parm @@ -0,0 +1,12 @@ +NET_ENABLE 1 +NET_OPTIONS 3 + +# enable hw flow control +UART1_RTSCTS 1 + +SCR_ENABLE 1 +SCR_VM_I_COUNT 1000000 +SCR_HEAP_SIZE 100000 + +WEB_ENABLE 1 +WEB_PORT 80 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef-bl.dat similarity index 76% rename from libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef-bl.dat rename to libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef-bl.dat index f330a1c45585c0..27643dde6848b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef-bl.dat @@ -1,14 +1,13 @@ # hw definition file for processing by chibios_hwdef.py # for the BotBloxSwitch hardware -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # MCU class and specific type MCU STM32H7xx STM32H723xx # crystal frequency -OSCILLATOR_HZ 0 +OSCILLATOR_HZ 16000000 # setup build for a peripheral bootloader env AP_PERIPH 1 @@ -40,13 +39,18 @@ PA14 JTCK-SWCLK SWD PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 +#PD4 USART2_DE USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + PD8 USART3_TX USART3 PD9 USART3_RX USART3 PD12 USART3_RTS USART3 PD11 USART3_CTS USART3 # LEDs -PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue +PC0 LED_STT1 OUTPUT OPENDRAIN HIGH +PA4 LED_STT2 OUTPUT OPENDRAIN HIGH define HAL_LED_ON 0 define HAL_USE_EMPTY_STORAGE 1 @@ -56,17 +60,18 @@ PC1 ETH_MDC ETH1 PA2 ETH_MDIO ETH1 PC4 ETH_RMII_RXD0 ETH1 PC5 ETH_RMII_RXD1 ETH1 -#PB12 ETH_RMII_TXD0 ETH1 -PG13 ETH_RMII_TXD0 ETH1 +PB12 ETH_RMII_TXD0 ETH1 PB13 ETH_RMII_TXD1 ETH1 -#PB11 ETH_RMII_TX_EN ETH1 -PG11 ETH_RMII_TX_EN ETH1 +PB11 ETH_RMII_TX_EN ETH1 PA7 ETH_RMII_CRS_DV ETH1 PA1 ETH_RMII_REF_CLK ETH1 -define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_ADDRESS 5 define BOARD_PHY_RMII +# auto-negotiation doesn't work, force 100MBit full duplex +define STM32_MAC_PHY_LINK_TYPE MAC_LINK_100_FULLDUPLEX + include ../include/network_bootloader.inc SERIAL_ORDER OTG1 USART3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef.dat similarity index 55% rename from libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef.dat rename to libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef.dat index 24f6c6e702b2b1..434a87992d6bd3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BotBloxSwitch/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BotBloxDroneNet/hwdef.dat @@ -8,7 +8,7 @@ DEFAULTGPIO OUTPUT LOW PULLDOWN MCU STM32H7xx STM32H723xx # crystal frequency -OSCILLATOR_HZ 0 +OSCILLATOR_HZ 16000000 # setup build for a peripheral bootloader env AP_PERIPH 1 @@ -42,46 +42,68 @@ PA9 VBUS INPUT OPENDRAIN PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 +#PD4 USART2_DE USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + PD8 USART3_TX USART3 PD9 USART3_RX USART3 PD12 USART3_RTS USART3 PD11 USART3_CTS USART3 # LEDs -PE3 LED_RED OUTPUT OPENDRAIN HIGH -PE4 LED_GREEN OUTPUT OPENDRAIN HIGH -PE5 LED_BLUE OUTPUT OPENDRAIN HIGH +PC0 LED_STT1 OUTPUT OPENDRAIN HIGH +PA4 LED_STT2 OUTPUT OPENDRAIN HIGH define HAL_LED_ON 0 -# use blue LED -define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE +# use first LED +define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_STT1 + +# Ethernet switch chip reset pin +PD13 GPIO_ETH_RST OUTPUT HIGH PULLUP +# CAN1 standby GPIO +PA0 GPIO_CAN_S OUTPUT LOW PULLUP + +# GPIO/PWMs +#PC6 TIM3_CH1 TIM3 PWM(1) GPIO(100) +#PB14 TIM12_CH1 TIM12 PWM(2) GPIO(101) +#PB15 TIM12_CH2 TIM12 PWM(3) GPIO(102) PC1 ETH_MDC ETH1 PA2 ETH_MDIO ETH1 PC4 ETH_RMII_RXD0 ETH1 PC5 ETH_RMII_RXD1 ETH1 -#PB12 ETH_RMII_TXD0 ETH1 -PG13 ETH_RMII_TXD0 ETH1 +PB12 ETH_RMII_TXD0 ETH1 PB13 ETH_RMII_TXD1 ETH1 -#PB11 ETH_RMII_TX_EN ETH1 -PG11 ETH_RMII_TX_EN ETH1 +PB11 ETH_RMII_TX_EN ETH1 PA7 ETH_RMII_CRS_DV ETH1 PA1 ETH_RMII_REF_CLK ETH1 -define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_ADDRESS 5 define BOARD_PHY_RMII -include ../include/network_PPPGW.inc +# auto-negotiation doesn't work, force 100MBit full duplex +define STM32_MAC_PHY_LINK_TYPE MAC_LINK_100_FULLDUPLEX + +define HAL_PERIPH_ENABLE_NETWORKING +define AP_NETWORKING_MAX_INSTANCES 4 # allow load from USB SERIAL_ORDER OTG1 USART3 -# no ADC pins +define HAL_RCIN_THREAD_ENABLED 1 +define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 + define HAL_USE_ADC FALSE -define STM32_ADC_USE_ADC1 FALSE -define STM32_ADC_USE_ADC2 FALSE -define STM32_ADC_USE_ADC3 FALSE +define AP_SERIALMANAGER_REGISTER_ENABLED 1 +define AP_SCRIPTING_ENABLED 1 +define AP_FILESYSTEM_ROMFS_ENABLED 1 -define HAL_RCIN_THREAD_ENABLED 1 -define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the network enabled bootloader at runtime +env ROMFS_UNCOMPRESSED True + +include ../include/network_PPPGW.inc + +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat index 756c80e9f0c8f5..205562fc6d3d0b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat @@ -62,7 +62,7 @@ I2C_ORDER I2C3 COMPASS RM3100 I2C:0:0x20 false ROTATION_YAW_270 # safety LED, active low -PB1 SAFE_LED OUTPUT HIGH +PB5 SAFE_LED OUTPUT HIGH define SAFE_LED_ON 0 define HAL_USE_ADC FALSE @@ -79,6 +79,7 @@ define DMA_RESERVE_SIZE 0 # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 +PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) # sensor power enable PA12 VDD_SENSOR_EN OUTPUT HIGH @@ -89,8 +90,6 @@ PA4 RTK_RESET_N OUTPUT HIGH # PPS PA7 PPS INPUT PULLUP -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743Pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743Pinout.png deleted file mode 100644 index f65bf4302c65c8..00000000000000 Binary files a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743Pinout.png and /dev/null differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743StampFront&Back.png b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743StampFront&Back.png deleted file mode 100644 index 207616eb109ce3..00000000000000 Binary files a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743StampFront&Back.png and /dev/null differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743_SD.png b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743_SD.png new file mode 100644 index 00000000000000..da099460006640 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/H743_SD.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/README.md index 50160b10e8709f..eb48dcbc40629e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/README.md @@ -2,19 +2,19 @@ # CBUnmanned H743 Stamp -The [CBUnmanned H743 Stamp](https://cbunmanned.com/store) is a flight controller loosely based on the FMUv6 standards & is designed for low volume OEMs as a drop in way to add ArduPilot to their custom hardware builds. It is a part of CBUnmanned's wider ["Stamp" Eco-System](https://wiki.cbunmanned.com/wiki/cbunmanned-stamp-eco-system), which brings together all the typical avionics hardware into a neat custom carrier PCB. Mounting footprints and symbols are available along with examples of basic usage on the [Wiki](https://wiki.cbunmanned.com/wiki/cbunmanned-stamp-eco-system/h743-flight-controller). +The [CBUnmanned H743 Stamp](https://cbunmanned.com/store) is a flight controller loosely based on the FMUv6 standards & is designed for low volume OEMs as a drop in way to add ArduPilot to their custom hardware builds. It is a part of CBUnmanned's wider ["Stamp" Eco-System](https://cbunmanned.com), which brings together all the typical avionics hardware into a neat custom carrier PCB. Mounting footprints and symbols are available along with examples of basic usage on the [Wiki](https://wiki.cbunmanned.com/). -![H743StampFront&Back](H743StampFront&Back.png "H743FB") +![H743StampFront&Back](H743_SD.png "H743FB") ## Features - Class leading H7 SOC. - Triple IMU sensors for extra redundancy. - Based on the FMU-V6 standards. - Micro SD Card for Logging/LUA Scripting. -- Direct solder mounting or optional 1.27mm header. +- 1.27mm header - x1 Ethernet and x2 CAN for easy integration with the next generation of UAV accessories. - All complicated/supporting circuitry is on-board, just power with 5v. -- Just 22mm x 24.25mm & 1.9g. +- Just 22mm x 24.25mm & 3g. ## Specifications - Processor @@ -26,7 +26,7 @@ The [CBUnmanned H743 Stamp](https://cbunmanned.com/store) is a flight controller - Sensors - x2 Ivensense ICM-42688 IMU - x1 Ivensense ICM-42670 IMU - - x1 Infineon DPS310 Barometer + - x1 BMP280 Barometer - x1 Bosch BMM150 Magnetometer - Power @@ -50,7 +50,7 @@ The [CBUnmanned H743 Stamp](https://cbunmanned.com/store) is a flight controller ![H743 Stamp Pinout](H743Pinout.png "H743") -### UART Mapping (Yellow Fade) +### UART Mapping Ardupilot -> STM32 - SERIAL0 -> USB @@ -75,10 +75,10 @@ USART 6 Tx is available for use with bi directional protocols. An optional IOMCU can be connected to this serial port, a compatible custom build of the firmware required. -### CAN Ports (Light Green Fade) +### CAN Ports 2 CAN buses are available, each with a built in 120 ohm termination resistor. -### I2C (Maroon Fade) +### I2C I2C 1 - Internal for BMM150 Compass. I2C 2 - Internal for DPS310 Barometer. @@ -87,10 +87,10 @@ I2C 3 - External With internal 2.2k Pull Up. I2C 4 - External With internal 2.2k Pull Up. -### SPI (Cyan Fade) +### SPI SPI 4 is available for use with external sensors alongside a Chip Select and Data Ready pin, compatible custom build of the firmware required. -### PWM Output (Blue Fade) +### PWM Output The Stamp supports up to 10 PWM outputs with D-Shot. The PWM outputs are in 3 groups: @@ -105,11 +105,11 @@ BiDirectional DShot available on the first 8 outputs. A buzzer alarm signal is available on Timer 14. -### Analog Inputs (Purple Fade) +### Analog Inputs The board has two ADC input channels for Voltage (0-3.3v) and Current (0-3.3v) measurement. Settings are dependent on the external hardware used. -### Ethernet (Green Fade) +### Ethernet Ethernet is available on 4 output pads and has internal magnetics supporting direct connection to external equipment, no need for a large RJ45 connector. ### Compass diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef-bl.dat index 77c422ffe09174..5fe147cd65a614 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef-bl.dat @@ -1,9 +1,6 @@ # hw definition file for processing by chibios_hwdef.py # for the CBUnmanned H743 Stamp hardware -# default to all pins low to avoid ESD issues -#DEFAULTGPIO OUTPUT LOW PULLDOWN - # MCU class and specific type MCU STM32H7xx STM32H743xx diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef.dat index 87f8956c00ea69..639e0c6256b4d7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CBU-H7-Stamp/hwdef.dat @@ -149,7 +149,7 @@ PB13 CAN2_TX CAN2 PB9 I2C1_SDA I2C1 PB8 I2C1_SCL I2C1 -# I2C2 - DPS310 +# I2C2 - BMP280 PF1 I2C2_SCL I2C2 PF0 I2C2_SDA I2C2 @@ -188,11 +188,12 @@ PF5 SAFETY_IN INPUT PULLDOWN # LED PE3 LED_RED OUTPUT HIGH GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 90 define HAL_GPIO_LED_ON 1 # barometers -BARO DPS310 I2C:1:0x77 +BARO BMP280 I2C:1:0x76 # compass COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat index 636724294de326..74bf4d5e3cdae4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CSKY405/hwdef.dat @@ -26,6 +26,7 @@ OSCILLATOR_HZ 8000000 # --------------------- LED ----------------------- PA14 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT PA13 LED1 OUTPUT LOW GPIO(91) # green marked as B/E +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 91 define HAL_GPIO_B_LED_PIN 90 @@ -139,8 +140,6 @@ SPIDEV sdcard SPI2 DEVID3 SDCARD_CS MODE3 104*MHZ 104*MHZ #define HAL_LOGGING_DATAFLASH_ENABLED 1 define HAL_OS_FATFS_IO 1 -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # ----------------- I2C compass & Baro ----------------- # no built-in compass, but probe the i2c bus for all possible diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/CUAV-7-Nano-pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/CUAV-7-Nano-pinout.png new file mode 100644 index 00000000000000..fe2ea5b4827bc6 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/CUAV-7-Nano-pinout.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/README.md new file mode 100644 index 00000000000000..ffdce53289aef6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/README.md @@ -0,0 +1,80 @@ +# CUAV-7-Nano Flight Controller + +The CUAV-7-Nano flight controller produced by [CUAV](https://www.cuav.net). + +## Features + +- STM32H753 microcontroller +- 2 IMUs: IIM42652 and BMI088 +- builtin IST8310 magnetometer +- 2 barometers: BMP581 and ICP20100 +- microSD card slot +- USB-TypeC port +- 1 ETH network interface +- 5 UARTs plus USB +- 14 PWM outputs +- 3 I2C ports +- 3 CAN ports (two of which share a CAN bus and one is an independent CAN bus) +- Analog RSSI input +- 3.3V/5V configurable PWM ouput voltage + +## Pinout + +![CUAV-7-Nano_interface_definition.png](CUAV-7-Nano-pinout.png) + +## UART Mapping + +- SERIAL0 -> USB +- SERIAL1 -> UART7 (TELEM1) +- SERIAL2 -> UART5 (TELEM2) +- SERIAL3 -> USART1 (GPS&SAFETY) +- SERIAL4 -> UART8 (GPS2) +- SERIAL5 -> USART3 (FMU DEBUG) + +The TELEM1 and TELEM2 ports have RTS/CTS pins, the other UARTs do not have RTS/CTS. All have full DMA capability. + +## RC Input + +RC input is configured on the RCIN pin, at one end of the servo rail, marked RCIN in the above diagram. All ArduPilot supported unidirectional RC protocols can be input here including PPM. For bi-directional or half-duplex protocols, such as CRSF/ELRS a full UART will have to be used. + +## PWM Output + +The CUAV-7-Nano flight controller supports up to 14 PWM outputs. + +The 14 PWM outputs are in 6 groups: + +- PWM 1-4 in group1 (TIM5) +- PWM 5 and 6 in group2 (TIM4) +- PWM 7 and 8 in group3 (TIM1) +- PWM 9, 10 and 11 in group4 (TIM8) +- PWM 12 in group5 (TIM15) +- PWM 13 and 14 in group6 (TIM12) + +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-4 support BDShot. + +First first 8 PWM outputs of CUAV-7-Nano flight controller support switching between 3.3V voltage and 5V voltage output. It can be switched to 5V by setting GPIO 80 high by setting up a Voltage-Level Translator to control it. + +## Battery Monitoring + +The board has a dedicated power monitor ports on 6 pin connectors(POWER A). The correct battery setting parameters are dependent on the type of power brick which is connected. + +## Compass + +The CUAV-7-Nano has an IST8310 builtin compass, but due to interference the board is usually used with an external I2C compass as part of a GPS/Compass combination. + +## Analog inputs + +The CUAV-7-Nano has 6 analog inputs. + +- ADC Pin9 -> Battery Voltage +- ADC Pin8 -> Battery Current Sensor +- ADC Pin5 -> Vdd 5V supply sense +- ADC Pin13 -> ADC 3.3V Sense +- ADC Pin12 -> ADC 6.6V Sense +- ADC Pin10 -> RSSI voltage monitoring + +## Loading Firmware + +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled "CUAV-7-Nano". + +The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/defaults.parm new file mode 100644 index 00000000000000..f46b1f17c1a3e4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/defaults.parm @@ -0,0 +1,2 @@ +INS_ACCEL_FILTER 10 +CAN_P1_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef-bl.dat new file mode 100644 index 00000000000000..62d0bae7107ef4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef-bl.dat @@ -0,0 +1,101 @@ +# hw definition file for processing by chibios_hwdef.py +# for CUAV-7-Nano board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 7000 + +# 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 + +# 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 ICM42652_CS CS +PH5 BMI088_A_CS CS +PG2 BMI088_G_CS CS +PD15 BMP581_CS CS +PG7 FRAM_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 +PE7 nARMED OUTPUT HIGH + +# start peripheral power off +PG4 VDD_5V_PERIPH_EN OUTPUT HIGH +PG10 VDD_5V_HIPOWER_EN OUTPUT HIGH + +# LEDs +PE3 LED_RED OUTPUT LOW # red +PE4 LED_ACTIVITY OUTPUT LOW # green +PE5 LED_BOOTLOADER OUTPUT LOW # 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 + +# support flashing from SD card: +# power enable pins +PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 + +# 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 + +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 AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef.dat new file mode 100644 index 00000000000000..277ebd65f78fa1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef.dat @@ -0,0 +1,295 @@ +# hw definition file for processing by chibios_hwdef.py +# for CUAV-7-Nano board + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# 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 7000 + +# bootloader takes first sector +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 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART3 OTG2 + +# 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 + +# GPS1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# GPS2 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# uart6, RX only, RC input, if no IOMCU +PC7 USART6_RX USART6 + +# ethernet +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PG13 ETH_RMII_TXD0 ETH1 +PG12 ETH_RMII_TXD1 ETH1 +PB11 ETH_RMII_TX_EN ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 +#PG15 ETH_POWER_EN ETH1 + +PG15 Ethernet_PWR_EN OUTPUT HIGH # disable power on ethernet + +define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_RMII + +# ADC +PA0 SCALED1_V3V3 ADC1 SCALE(2) +PA4 SCALED2_V3V3 ADC1 SCALE(2) +PB1 VDD_5V_SENS ADC1 SCALE(2) +PC0 RSSI_IN ADC1 SCALE(1) +PF12 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# analog in +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(9) +PB0 BATT_CURRENT_SENS ADC1 SCALE(1) ANALOG(8) + +# pin7 on AD&IO, analog 12 +PF3 ADC3_6V6 ADC3 SCALE(2) ANALOG(12) + +# pin6 on AD&IO, analog 13 +PC3 ADC1_3V3 ADC1 SCALE(1) ANALOG(13) + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 9 +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_VOLT_SCALE 31.0 +define HAL_BATT_CURR_SCALE 24.0 + +# SPI1 - IIM42652 +PA5 SPI1_SCK SPI1 +PB5 SPI1_MOSI SPI1 +PG9 SPI1_MISO SPI1 +PI9 IIM42652_CS CS +PF2 IIM42652_DRDY INPUT + +# SPI2 - BMI088 +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 +PH5 BMI088_A_CS CS +PG2 BMI088_G_CS CS +PG3 BMI088_DRDY_GYR INPUT +PA10 BMI088_DRDY_ACC INPUT + +# SPI4 - BMP581 +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 +PD15 BMP581_CS CS +PG1 BMP581_DRDY INPUT + +# SPI5 - FRAM +PF7 SPI5_SCK SPI5 +PH7 SPI5_MISO SPI5 +PF11 SPI5_MOSI SPI5 +PG7 FRAM_CS CS + +# SPI devices +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 +SPIDEV iim42652 SPI1 DEVID1 IIM42652_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV bmp581 SPI4 DEVID1 BMP581_CS MODE3 7.5*MHZ 12*MHZ + +# PWM output pins +PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) BIDIR +PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) +PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) BIDIR +PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) +PE11 TIM1_CH2 TIM1 PWM(7) GPIO(56) +PE9 TIM1_CH1 TIM1 PWM(8) GPIO(57) +PI6 TIM8_CH2 TIM8 PWM(9) GPIO(58) +PI7 TIM8_CH3 TIM8 PWM(10) GPIO(59) +PI5 TIM8_CH1 TIM8 PWM(11) GPIO(60) +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) + +# 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(13) GPIO(62) NODMA +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# control for silent (no output) for CAN +PE2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PI8 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# I2C buses + +# I2C1, GPS+MAG +PB9 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 + +# I2C2, GPS2+MAG +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3, IST8310 +PA8 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4, ICM20100 +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 +PG5 DRDY1_ICP20100 INPUT + +# order of I2C buses +I2C_ORDER I2C3 I2C4 I2C1 I2C2 +define HAL_I2C_INTERNAL_MASK 3 + +# armed indication +PE7 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 +PH2 VDD_3V3_SENSORS3_EN OUTPUT HIGH + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PG10 VDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 VDD_5V_PERIPH_EN OUTPUT HIGH + +# power sensing +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP +PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP + +# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v, 3.3v default +PG8 PWM_VOLT_SEL OUTPUT LOW GPIO(80) +define HAL_GPIO_PWM_VOLT_PIN 80 +define HAL_GPIO_PWM_VOLT_3v3 0 + +# 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 GPIO(90) LOW +PE4 LED_GREEN OUTPUT GPIO(91) LOW +PE5 LED_BLUE OUTPUT GPIO(92) LOW + +# setup for "pixracer" RGB LEDs +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 + +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# 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 +PC6 TIM3_CH1 TIM3 RCININT PULLDOWN LOW + +# other I2C devices +# 24LC64T eeprom 64Kbit, address 0x50 on I2C4 + +BARO BMP581 SPI:bmp581 +BARO ICP201XX I2C:1:0x63 + +# compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_90_YAW_90 +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 + +# IMUs +IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_90_YAW_90 +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_90 + +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 TIM5* SDMMC* USART6* ADC* UART* USART* SPI* TIM* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +# 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/CUAV-Nora/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat index b16621fed42c31..5e73da62cc94df 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat @@ -105,9 +105,7 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold +# start peripheral power on PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH PG4 VDD_5V_PERIPH_EN OUTPUT HIGH @@ -275,12 +273,12 @@ PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Pixhack-v3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Pixhack-v3/hwdef.dat new file mode 100644 index 00000000000000..99497e032ddd98 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Pixhack-v3/hwdef.dat @@ -0,0 +1,3 @@ +include ../fmuv3/hwdef.dat + +USE_BOOTLOADER_FROM_BOARD fmuv3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat index 7437418d97a728..1d28897e350a75 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat @@ -105,9 +105,7 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold +# start peripheral power on PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH PG4 VDD_5V_PERIPH_EN OUTPUT HIGH @@ -285,12 +283,12 @@ PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index a5514acaff99d3..58c9756d6dbbc7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -119,10 +119,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -define HAL_NO_MONITOR_THREAD - - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat index 4b4825dc48f6bd..a339f854e2af47 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat @@ -8,14 +8,14 @@ PH10 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PH11 LED_G1 OUTPUT OPENDRAIN HIGH GPIO(1) PH12 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -undef HAL_GPIO_A_LED_PIN -undef HAL_GPIO_B_LED_PIN +undef AP_NOTIFY_GPIO_LED_RGB_RED_PIN +undef AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 undef IMU undef PF11 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat index f00e9746dfe33a..c8d1a3607c9fac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat @@ -57,11 +57,11 @@ PH10 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PH11 LED_G1 OUTPUT OPENDRAIN HIGH GPIO(1) PH12 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -undef HAL_GPIO_A_LED_PIN -undef HAL_GPIO_B_LED_PIN +undef AP_NOTIFY_GPIO_LED_RGB_RED_PIN +undef AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat index 2bb60402c2c780..9bc6e1920a5590 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -109,7 +109,6 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index c84f2d0adc3df7..baa3a17da95680 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -112,7 +112,6 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack+/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack+/hwdef.dat index 39c7cfa10d1dcd..851814d8087979 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack+/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack+/hwdef.dat @@ -19,4 +19,6 @@ IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180 IMU Invensense SPI:mpu9250 ROTATION_YAW_270 undef ROMFS -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.bin +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_cube_highpolh.bin + +define AP_IOMCU_PROFILED_SUPPORT_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat index f1ae6809ea431b..b7b5592eb285b5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat @@ -35,8 +35,6 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE define HAL_BARO_ALLOW_INIT_NO_BARO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat index cccd5a28e00f3a..04aa6bf20f8fcf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat @@ -102,8 +102,9 @@ define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 # default the 2nd interface to SLCAN define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN -ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.bin +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_cube_highpolh.bin +define AP_IOMCU_PROFILED_SUPPORT_ENABLED 1 # enable support for dshot on iomcu define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/defaults.parm similarity index 91% rename from libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm rename to libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/defaults.parm index 5f23d5515f0ea8..65718aac21df7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLE 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef-bl.dat similarity index 81% rename from libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat rename to libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef-bl.dat index 83e9d53d2fcf35..6e6f3b172a874a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef-bl.dat @@ -1,4 +1,4 @@ -include ../CubePilot-CANMod/hwdef-bl.dat +include ../CubeNode/hwdef-bl.dat # Ethernet PC1 ETH_MDC ETH1 @@ -15,6 +15,3 @@ define BOARD_PHY_ID MII_LAN8720_ID define BOARD_PHY_RMII include ../include/network_bootloader.inc - -# allow USB bootloader too -SERIAL_ORDER OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef.dat new file mode 100644 index 00000000000000..4aef18a5c3e421 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode-ETH/hwdef.dat @@ -0,0 +1,38 @@ +include ../CubeNode/hwdef.dat + +# we need RTS/CTS for the PPP link +undef PE0 +undef PE1 +undef PC12 +undef HAL_PERIPH_ENABLE_IMU +undef HAL_GCS_ENABLED + +# need to use UART8 to get RTS/CTS +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 +PA10 UART8_RTS UART8 +PC12 UART8_CTS_GPIO UART8 + +SERIAL_ORDER OTG1 UART8 + +PA4 VDD_5V_SENS ADC1 SCALE(2) + +# LEDs +undef PC11 +PC11 LED0 OUTPUT LOW GPIO(0) +PB14 LED1 OUTPUT LOW GPIO(1) + +undef HAL_USE_ADC +define HAL_USE_ADC TRUE +define HAL_WITH_MCU_MONITORING 1 + +# can optionally run at half clock +# MCU_CLOCKRATE_MHZ 200 + +include ../include/network_PPPGW.inc + +define HAL_MONITOR_THREAD_ENABLED 1 + +define AP_NETWORKING_TESTS_ENABLED 1 + +define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode/CubeNode_PinOut.pdf similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf rename to libraries/AP_HAL_ChibiOS/hwdef/CubeNode/CubeNode_PinOut.pdf diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef-bl.dat similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat rename to libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef.dat similarity index 86% rename from libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat rename to libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef.dat index 4637d12cc777c4..58464c44be7781 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef.dat @@ -70,12 +70,26 @@ define BOARD_PHY_ID MII_LAN8720_ID define BOARD_PHY_RMII define HAL_PERIPH_ENABLE_NETWORKING +# IMU +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 +PG15 IMU_CS CS + +SPIDEV icm45686 SPI3 DEVID4 IMU_CS MODE0 24*MHZ 24*MHZ + +IMU Invensensev3 SPI:icm45686 ROTATION_NONE + +define HAL_PERIPH_ENABLE_IMU + +# Periph GCS +define HAL_GCS_ENABLED 1 + ################################# # AP_Periph - configurations specific to this App ################################# define HAL_BARO_ALLOW_INIT_NO_BARO -define AP_INERTIALSENSOR_ENABLED 0 define AP_NETWORKING_MAX_INSTANCES 4 @@ -86,3 +100,5 @@ define AP_FILESYSTEM_ROMFS_ENABLED 1 # undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0 define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 ################################# + +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm index 911b2f03eca06e..5a2ee38df3c7ba 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm @@ -24,5 +24,4 @@ AHRS_EKF_TYPE 3 @READONLY GPS1_TYPE 1 GPS2_TYPE 0 -EK2_PRIMARY 1 EK3_PRIMARY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm index b6a7989b19ac08..5a25829337b26f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm @@ -57,5 +57,4 @@ 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-joey/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm index c7f16a36c2b2fb..8f59a0bbb5886f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm @@ -47,5 +47,4 @@ 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-periph-heavy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat index 003ee1508e9e02..2aeea2620be870 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat @@ -22,18 +22,15 @@ define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY +define HAL_PERIPH_ENABLE_IMU define HAL_LOGGING_ENABLED TRUE -define AP_INERTIALSENSOR_ENABLED 1 - # single GPS and compass for peripherals define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE define HAL_GCS_ENABLED 1 @@ -60,3 +57,4 @@ define HAL_PICCOLO_CAN_ENABLE 0 define AP_RELAY_ENABLED 1 define AP_SERVORELAYEVENTS_ENABLED 1 +define AP_SCHEDULER_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat index b8ba9df8ea3d74..8afdcc21f1f2a4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat @@ -22,8 +22,8 @@ define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY +define HAL_PERIPH_ENABLE_IMU -define AP_INERTIALSENSOR_ENABLED 1 define AP_KDECAN_ENABLED 1 # single GPS and compass for peripherals @@ -31,8 +31,6 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE define HAL_BARO_ALLOW_INIT_NO_BARO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md index 4d8df17a80146d..13453e451b4039 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md @@ -212,12 +212,12 @@ to the cube. The TX pin is closest to the servo rail. 2 - RX (IN) + RX (IN) / NC (ADSB CB) +3.3V 3 - TX (OUT) + TX (OUT) / NC (ADSB CB) +3.3V diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm index fdb083659efe2d..52d3df5ea5dadc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm @@ -9,5 +9,4 @@ 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.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc index cb5769d8d514b3..b34eb0a9faf4b0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc @@ -212,17 +212,8 @@ 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 @@ -231,18 +222,7 @@ 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 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 @@ -270,12 +250,7 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 7 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 +# one internal compass COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 # offset the internal compass for EM impact of the IMU heater @@ -321,12 +296,14 @@ define HAL_GPIO_PWM_VOLT_3v3 1 # 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 +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_cube_highpolh.bin # enable support for dshot on iomcu -ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin define HAL_WITH_IO_MCU_DSHOT 1 +define AP_IOMCU_PROFILED_SUPPORT_ENABLED 1 + DMA_NOSHARE SPI1* SPI4* USART6* # for users who have replaced their CubeSolo with a CubeOrange: diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat index 236b2b6dcbd575..d2163dbf14520b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat @@ -99,3 +99,5 @@ BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHEC # build ABIN for flash-from-bootloader support: env BUILD_ABIN True define HAL_INS_HIGHRES_SAMPLE 6 + +define AP_NETWORKING_BACKEND_PPP 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat deleted file mode 100644 index 70c50244fd8ef4..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat +++ /dev/null @@ -1,17 +0,0 @@ -include ../CubePilot-CANMod/hwdef.dat - -# we need RTS/CTS for the PPP link -undef PD14 -undef PD13 -undef PE0 -undef PE1 - -# need to use UART8 to get RTS/CTS -PE1 UART8_TX UART8 -PE0 UART8_RX UART8 -PD13 UART8_RTS UART8 -PD14 UART8_CTS UART8 - -SERIAL_ORDER OTG1 UART8 - -include ../include/network_PPPGW.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm index 5f23d5515f0ea8..65718aac21df7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLE 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/hwdef.dat index 0e0f1898c8a856..0dcf4bba308721 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary-PPPGW/hwdef.dat @@ -23,8 +23,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS define AP_NETWORKING_BACKEND_PPP 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE # use amber LED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm index 1e5d44378dc3a3..22f785c1a3b188 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/defaults.parm @@ -5,5 +5,23 @@ SERIAL7_OPTIONS 8 ADSB_TYPE 1 SERIAL5_BAUD 57 SERIAL5_PROTOCOL 1 -EK2_PRIMARY 1 EK3_PRIMARY 1 + +NET_ENABLE 1 +NET_OPTIONS 1 +NET_DHCP 0 +NET_P1_TYPE 1 +NET_P1_PROTOCOL 2 +NET_P1_IP0 192 +NET_P1_IP1 168 +NET_P1_IP2 144 +NET_P1_IP3 10 +NET_P1_PORT 14553 + +NET_P2_TYPE 4 +NET_P2_PROTOCOL 2 +NET_P2_IP0 192 +NET_P2_IP1 168 +NET_P2_IP2 144 +NET_P2_IP3 100 +NET_P2_PORT 14554 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef-bl.dat index 58726d22aac330..bb4cfa826fdf4f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef-bl.dat @@ -41,14 +41,23 @@ PA14 JTCK-SWCLK SWD PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 +# primary <-> secondary +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 # USART2 USART6 USART3 UART8 UART7 UART4 define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_UART7 TRUE define HAL_USE_SERIAL TRUE define BOOTLOADER_DEBUG SD2 +define BOOTLOADER_FORWARD_OTG2_SERIAL SD7 +define BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE 2000000 +define BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP TRUE +define HAL_HAVE_DUAL_USB_CDC 1 # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat index cbc174d9a55ac6..f0ea70db249208 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat @@ -98,32 +98,40 @@ PB14 SPI2_MISO SPI2 PB15 SPI2_MOSI SPI2 # SPI4 -PF5 ICM20649_CS CS +PF5 ICM_2_CS CS PC2 BARO_1_CS CS PE12 SPI4_SCK SPI4 PE5 SPI4_MISO SPI4 PE6 SPI4_MOSI SPI4 # Sensors -SPIDEV icm42688_0 SPI1 DEVID1 ICM42688_0_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42688_0 SPI1 DEVID1 ICM42688_0_CS MODE3 2*MHZ 24*MHZ SPIDEV ms5611_0 SPI1 DEVID2 BARO_0_CS MODE3 20*MHZ 20*MHZ -SPIDEV icm42688_1 SPI2 DEVID1 ICM42688_1_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42688_1 SPI2 DEVID1 ICM42688_1_CS MODE3 2*MHZ 24*MHZ SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ -SPIDEV icm20649 SPI4 DEVID1 ICM20649_CS MODE3 4*MHZ 8*MHZ +SPIDEV icm20649 SPI4 DEVID1 ICM_2_CS MODE3 4*MHZ 8*MHZ +# alternative to icm20649 +SPIDEV icm45686 SPI4 DEVID1 ICM_2_CS MODE3 2*MHZ 24*MHZ SPIDEV ms5611_1 SPI4 DEVID2 BARO_1_CS MODE3 20*MHZ 20*MHZ IMU Invensensev3 SPI:icm42688_1 ROTATION_YAW_90 IMU Invensensev3 SPI:icm42688_0 ROTATION_PITCH_180_YAW_270 IMU Invensensev2 SPI:icm20649 ROTATION_PITCH_180 +IMU Invensensev3 SPI:icm45686 ROTATION_YAW_180 + +define HAL_INS_HIGHRES_SAMPLE 5 +define ICM45686_CLKIN 1 BARO MS56XX SPI:ms5611_0 BARO MS56XX SPI:ms5611_1 COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_270 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES CHECK_ICM20649 spi_check_register_inv2("icm20649", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) +CHECK_ICM45686_2 spi_check_register("icm45686", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686) CHECK_ICM42688_0 spi_check_register("icm42688_0", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) CHECK_ICM45686_0 spi_check_register("icm42688_0", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686) @@ -135,7 +143,7 @@ CHECK_MS5611_0 check_ms5611("ms5611_0") CHECK_MS5611_1 check_ms5611("ms5611_1") -CHECK_IMU0_PRESENT $CHECK_ICM20649 +CHECK_IMU0_PRESENT $CHECK_ICM20649 || $CHECK_ICM45686_2 CHECK_IMU1_PRESENT $CHECK_ICM42688_0 || $CHECK_ICM45686_0 CHECK_IMU2_PRESENT $CHECK_ICM42688_1 || $CHECK_ICM45686_1 CHECK_BARO0_PRESENT $CHECK_MS5611_0 @@ -148,7 +156,7 @@ define HAL_CHIBIOS_ARCH_FMUV3 1 define BOARD_TYPE_DEFAULT 3 # MCO output -PA8 RCC_MCO_1 OUTPUT LOW +PA8 RCC_MCO_1 INPUT # I2C PF0 I2C2_SDA I2C2 @@ -270,17 +278,20 @@ PG15 USART6_CTS USART6 PG8 USART6_RTS USART6 # primary <-> secondary -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 +PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE +PE8 UART7_TX UART7 SPEED_VERYLOW # order of UARTs (and USB) -SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 EMPTY UART7 +SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 OTG2 UART7 EXT_FLASH_SIZE_MB 32 INT_FLASH_PRIMARY 1 -# forward Serial traffic from USB OTG2 to Serial7(UART7) -define HAL_FORWARD_OTG2_SERIAL 7 -define HAL_HAVE_DUAL_USB_CDC 1 -define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2 -define DEFAULT_SERIAL7_BAUD 2000000 +# set protocol for UART7 to SerialProtocol_PPP +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_PPP +define DEFAULT_SERIAL7_BAUD 8000000 + +define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR "192.168.144.100" +define AP_NETWORKING_DEFAULT_STATIC_NETMASK "255.255.255.0" +define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR "192.168.144.11" +define AP_NETWORKING_BACKEND_PPP 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm index 3be7684ba40cad..342b61b6d584b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/defaults.parm @@ -1,2 +1,12 @@ SERIAL3_OPTIONS 8 SERIAL4_OPTIONS 8 +NET_ENABLE 1 +NET_P1_TYPE 3 +NET_P1_PROTOCOL 2 +NET_P1_IP0 192 +NET_P1_IP1 168 +NET_P1_IP2 144 +NET_P1_IP3 100 +NET_P1_PORT 14554 + +SYSID_THISMAV 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat index bd77ac79c934f3..e24d8c5299effb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat @@ -7,6 +7,8 @@ MCU STM32H7xx STM32H757xx define CORE_CM7 define SMPS_PWR +env OPTIMIZE -Os + # crystal frequency OSCILLATOR_HZ 24000000 @@ -39,7 +41,8 @@ PA6 RSSI_IN ADC1 SCALE(2) # CAN config PB14 GPIOCAN2_TERM OUTPUT HIGH - +PC12 GPIOCAN1_SHUTDOWN OUTPUT LOW +PF1 GPIOCAN2_SHUTDOWN OUTPUT LOW PA12 CAN1_TX CAN1 PB8 CAN1_RX CAN1 @@ -118,8 +121,8 @@ PA7 HP_UNIDIR_ENABLED OUTPUT HIGH GPIO(5) # UART connected to FMU, uses DMA -PE7 UART7_RX UART7 SPEED_HIGH -PE8 UART7_TX UART7 SPEED_HIGH +PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE +PE8 UART7_TX UART7 SPEED_VERYLOW # UART for SBUS out PC7 USART6_RX USART6 SPEED_HIGH LOW @@ -144,13 +147,16 @@ PD4 USART2_RTS USART2 SPEED_HIGH PD3 USART2_CTS USART2 SPEED_HIGH # order of UARTs -SERIAL_ORDER UART7 UART8 USART3 USART6 UART4 USART2 +SERIAL_ORDER UART8 UART7 USART3 USART6 UART4 USART2 # use 2 MBaud when talking to primary controller -define DEFAULT_SERIAL0_BAUD 2000000 +define DEFAULT_SERIAL1_BAUD 8000000 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_PPP define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1 define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN +define AP_NETWORKING_BACKEND_PPP 1 + # only use pulse input for PPM, other protocols # are on serial define HAL_RCIN_PULSE_PPM_ONLY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm index 014be025e832d8..367407fcca1e5b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm @@ -146,6 +146,8 @@ RTL_ALT,4500 RTL_CLIMB_MIN,1000 RTL_SPEED,800 SERIAL1_BAUD,921 +SERIAL1_PROTOCOL,1 +SERIAL2_PROTOCOL,1 SERIAL4_BAUD,230 SERIAL4_PROTOCOL,1 SERVO1_FUNCTION,33 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index afc44a107c6050..2c32d6813560e8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -351,17 +351,8 @@ 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 @@ -382,18 +373,7 @@ SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ #SPIDEV clock8 SPI4 DEVID5 MPU_EXT_CS MODE0 8*MHZ 8*MHZ # gives 5.5MHz #SPIDEV clock16 SPI4 DEVID5 MPU_EXT_CS MODE0 16*MHZ 16*MHZ # gives 10.6MHz -# 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 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 @@ -404,12 +384,7 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 5 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 +# one compass COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 # also probe for external compasses @@ -470,9 +445,10 @@ STORAGE_FLASH_PAGE 1 # 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 +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_cube_highpolh.bin # enable support for dshot on iomcu -ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin define HAL_WITH_IO_MCU_DSHOT 1 +define AP_IOMCU_PROFILED_SUPPORT_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index 5f7421a78f114e..222aa5f835510d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -107,11 +107,9 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# 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 -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW PG5 VDD_5V_RC_EN OUTPUT HIGH PG6 VDD_5V_WIFI_EN OUTPUT HIGH @@ -298,9 +296,9 @@ PC6 LED_GREEN OUTPUT GPIO(91) LOW PC7 LED_BLUE OUTPUT GPIO(92) HIGH # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat index 88260318626d0e..3b2655f8123ff7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat @@ -70,8 +70,9 @@ define BOARD_RSSI_ANA_PIN 13 #PA4 VDD_5V_SENS ADC1 SCALE(2) # LED +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC10 LED OUTPUT HIGH GPIO(57) -define HAL_GPIO_A_LED_PIN 57 +define AP_NOTIFY_GPIO_LED_1_PIN 57 # SPI PA5 SPI1_SCK SPI1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat index 7eb716d1436147..ffc86110c7bf1b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat @@ -131,15 +131,15 @@ PD14 TIM4_CH3 TIM4 PWM(12) GPIO(61) PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0 # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 PC0 PRESSURE_SENS ADC1 SCALE(1) PC1 RSSI_IN ADC1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/README.md b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/README.md new file mode 100644 index 00000000000000..f096ef850c56a5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/README.md @@ -0,0 +1,22 @@ +# F4BY Flight Controller MCU upgrade + +The F4BY flight controller shop: https://f4by.com/en/?order/our_product + +The instructions are available here: https://f4by.com/en/?doc/fc_f4by_v2.1.5 + +## Howto +for self upgrage old fc: +replace old MCU STM32F407VGT (1MB Flash) with STM32F427VET rev3 or above (2MB Flash) + + +## Features + + - Full Ardupilot features support (exclude LUA Script) + + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +boot solder pads connected. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef-bl.dat new file mode 100644 index 00000000000000..60889f42de5ab6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef-bl.dat @@ -0,0 +1,42 @@ +# hw definition file for processing by chibios_hwdef.py +# for f4by bootloader + +MCU STM32F4xx STM32F427xx + +APJ_BOARD_ID AP_HW_F4BY_F427 + +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 2048 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 + +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 + +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +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 MPU_CS CS +PB12 FRAM_CS CS SPEED_VERYLOW +PE15 FLASH_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef.dat new file mode 100644 index 00000000000000..c7a5ee84733990 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY_F427/hwdef.dat @@ -0,0 +1,177 @@ +# hw definition file for processing by chibios_hwdef.py +# for F4BY v2.1.5 board description http://swift-flyer.com/?page_id=83 + +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_F4BY_F427 + +# USB setup +USB_VENDOR 0x27AC # Swift-Flyer +USB_PRODUCT 0x0201 # fmu usb driver +USB_STRING_MANUFACTURER "Swift-Flyer" +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + + +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 16 +define HAL_STORAGE_SIZE 16384 +env OPTIMIZE -O2 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + + + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# the normal usage of this ordering is: +# 1) SERIAL0: console (primary mavlink, usually USB) +# 2) SERIAL3: primary GPS +# 3) SERIAL1: telem1 +# 4) SERIAL2: telem2 +# 5) SERIAL4: GPS2 +# 6) SERIAL5: extra UART (usually RTOS debug console) + +# use UART for stdout, so no STDOUT_SERIAL +#STDOUT_SERIAL SD5 +#STDOUT_BAUDRATE 57600 + + + +SERIAL_ORDER OTG1 USART2 USART1 USART3 UART4 UART5 + +# UART1 as board 2.1.5 for serial 3 gps +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# USART2 serial2 telem2 +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 + +# USART3 serial3 telem1 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 + +PC10 UART4_TX UART4 NODMA +PC11 UART4_RX UART4 + +# SHARE dma with I2C2_TX +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + + +#SPI1 for MPU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 MPU_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 + +SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*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 +IMU Invensense SPI:mpu6000 ROTATION_NONE + +# one baro, check both addresses +BARO MS56XX I2C:0:0x76 +BARO MS56XX I2C:0:0x77 + +# enable RAMTROM parameter storage +define HAL_WITH_RAMTRON 1 +# enable FAT filesystem support +define HAL_OS_FATFS_IO 1 + +# 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 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# look for I2C compass +COMPASS HMC5843 I2C:0:0x1E false ROTATION_YAW_270 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# 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) + +PD13 TIM4_CH2 TIM4 PWM(9) GPIO(58) +PD12 TIM4_CH1 TIM4 PWM(10) GPIO(59) +PD15 TIM4_CH4 TIM4 PWM(11) GPIO(60) +PD14 TIM4_CH3 TIM4 PWM(12) GPIO(61) + +# also USART6_RX for unidirectional RC,including PPM +PC7 TIM8_CH2 TIM8 RCININT PULLDOWN LOW DMA_CH0 +# PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW DMA_CH0 + + +# New style Pixracer LED configuration for master repo +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 + + + +PC0 PRESSURE_SENS ADC1 SCALE(1) +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) + + +PE5 TIM9_CH1 TIM9 ALARM +PC14 EXTERN_GPIO1 OUTPUT GPIO(1) +PC13 EXTERN_GPIO2 OUTPUT GPIO(2) +PE4 EXTERN_GPIO3 OUTPUT GPIO(3) +PE6 EXTERN_GPIO4 OUTPUT GPIO(4) +PC9 EXTERN_GPIO5 OUTPUT GPIO(5) + +# IRQ for MPU6000 +PB0 EXTI_MPU6000 INPUT PULLUP +PB1 DRDY_HMC5883 INPUT PULLUP + +# this constants with HAL_ +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 16.04981 +define HAL_BATT_CURR_SCALE 100 + +# this constant with AP_ +define AP_BATT_CURR_AMP_OFFSET_DEFAULT 2.316 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat index ec839060c9f5ed..d91e00dbff9a86 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat @@ -142,15 +142,15 @@ define RELAY5_PIN_DEFAULT 5 PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW DMA_CH0 # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 # analog in PC0 PRESSURE_SENS ADC1 SCALE(2) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat index 8599389217198b..5df193ee03de25 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat @@ -66,7 +66,7 @@ PD2 UART5_RX UART5 NODMA PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 -# SPI1 for IMU OSD +# SPI1 for IMU PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 @@ -74,7 +74,6 @@ 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 @@ -93,7 +92,6 @@ SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20649 SPI1 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42605 SPI1 DEVID3 ICM42605_CS MODE3 2*MHZ 8*MHZ SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 1*MHZ 1*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 @@ -158,15 +156,15 @@ define RELAY5_PIN_DEFAULT 5 PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW DMA_CH0 # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 # analog in PC0 PRESSURE_SENS ADC1 SCALE(2) @@ -187,7 +185,3 @@ 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/FlyingMoonH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat index 1832c01d0d5f91..9e1c637b83bcc2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat @@ -73,7 +73,7 @@ PD1 CAN1_TX CAN1 PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 -# SPI1 for IMU OSD +# SPI1 for IMU PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 @@ -81,7 +81,6 @@ PB0 ICM20689_CS CS PB1 ICM42605_CS CS PB2 ICM20649_CS CS PA4 RM3100_CS CS -PA8 MAX7456_CS CS # SPI bus for dataflash AND SD PD3 SPI2_SCK SPI2 @@ -100,7 +99,6 @@ SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20649 SPI1 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42605 SPI1 DEVID3 ICM42605_CS MODE3 2*MHZ 8*MHZ SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 1*MHZ 1*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 @@ -165,15 +163,15 @@ define RELAY5_PIN_DEFAULT 5 PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW DMA_CH0 # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 # analog in PC0 PRESSURE_SENS ADC1 SCALE(2) @@ -195,8 +193,3 @@ PE8 SAFETY_IN INPUT PULLDOWN # PWM output for buzzer PE5 TIM15_CH1 TIM15 GPIO(77) 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/FlywooF405HD-AIOv2/GokuF405HD_AIOv2_Pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/GokuF405HD_AIOv2_Pinout.png new file mode 100644 index 00000000000000..bdf722336588b3 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/GokuF405HD_AIOv2_Pinout.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/README.md new file mode 100644 index 00000000000000..1848c17d47baa0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/README.md @@ -0,0 +1,111 @@ +# GOKU F405 HD 1-2S AIO v2 w/ built-in ELRS 2.4g RX + +https://flywoo.net/products/goku-f405-hd-1-2s-elrs-aio-v2 + +The Flywoo GOKU F405 HD AIO v2 is a flight controller produced by [Flywoo](https://flywoo.net/). + +## Features + +- MCU: STM32F405 32-bit processor. 1024Kbytes Flash +- IMU: MPU6000 (SPI) or ICM42688 (SPI) +- Barometer: DPS310/SPL06 +- Onboard LED:WS2812*2 +- USB VCP Driver (all UARTs usable simultaneously; USB does not take up a UART) +- 6 hardware UARTS (UART1,2,3,4,5,6) +- Built-in ELRS 2.4 GHz serial receiver (on some models) +- Also supports external serial receivers (SBUS, iBus, Spektrum, Crossfire) +- Onbord 8 Mbytes for Blackbox logging +- 5V Power Out: 2.0A max +- 9V Power Out: 2.0A max (on/off software controllable via PINIO) +- Dimensions: 30x30mm +- Mounting Holes: Standard 25.5/25.5mm square to center of holes +- Weight: 4.9g + +- Built-in 12A BLHeli_S 4in1 ESC +- Supports BLheli_S / BlueJay / J-ESC +- Supports Oneshot125, Oneshot42, Multishot, Dshot150, Dshot300, Dshot600 +- Input Voltage: 1-2S Lipo +- Continuous Current: 12A +- Firmware: Z_H_30_REV16.7 + +## Pinout + +![GOKU F405 HD 12A AIO v2](GokuF405HD_AIOv2_Pinout.png "GOKU F405 HD 12A AIO 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. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|USART1 (ELRS, DMA-enabled)| +|SERIAL2|TX2/RX2|USART2 (Telem, DMA on RX)| +|SERIAL3|TX3/RX3|USART3 (USER, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (GPS)| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|TX6/RX6|UART6 (DisplayPort)| + +USART1 and USART3 supports RX and TX DMA. UART4 supports TX DMA. USART2 supports RX DMA. UART5 and UART6 do not support DMA. + +## RC Input + +RC input is configured as ELRS by default using UART1. Alternatively, UART3 could be used for RC inputs other than ELRS but its protocol would need to be changed to 23 and UART1 disabled by setting its protocol as -1. This board does not support PPM. + +## OSD Support + +The GOKU F405 HD AIO v2 supports OSD using OSD_TYPE 5 (MSP DisplayPort). + +## PWM Output + +The GOKU F405 AIO supports up to 5 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are the first 4 outputs. All 5 outputs support DShot. + +The PWM are in 3 groups: + +PWM 1-2: Group 1 +PWM 3-4: Group 2 +LED: Group 3 + +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. PWM 1-4 support bidirectional dshot. +.. note:: for users migrating from BetaflightX quads, the first four outputs M1-M4 have been configured for use with existing motor wiring using these default parameters: + +- :ref:`FRAME_CLASS` = 1 (Quad) +- :ref:`FRAME_TYPE` = 12 (BetaFlightX) +## Battery Monitoring + +The board has a builtin voltage sensor. The voltage sensor can handle 2S to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 13 + - BATT_VOLT_MULT around 11 + - BATT_CURR_PIN 12 + - BATT_AMP_PERVLT around 60.2 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The GOKU F405 HD AIO v2 does not have a builtin compass but it does have an external I2C connector. + +## NeoPixel LED + +The board includes a NeoPixel LED pad. + +## 9V/VTX Electronic Switch + +9V/VTX state can be controlled using ArduPilot Relay, GPIO pin 81. + +## Loading Firmware (you will need to compile your own 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/FlywooF405HD-AIOv2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/defaults.parm new file mode 100644 index 00000000000000..0315767096a5a0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/defaults.parm @@ -0,0 +1,13 @@ +# setup for LEDs on chan9 +SERVO5_FUNCTION 120 +NTF_LED_LEN 2 +# ESC setup +MOT_PWM_TYPE 5 +SERVO_BLH_AUTO 1 +SERVO_BLH_TRATE 0 +# RC setup +RC_OPTIONS 8704 +OSD_TYPE 5 +SERIAL3_PROTOCOL -1 +SERIAL2_PROTOCOL 2 +SERIAL6_PROTOCOL 42 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef-bl.dat new file mode 100644 index 00000000000000..1add17be4730ba --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef-bl.dat @@ -0,0 +1,15 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOF405HD_AIOv2 hardware. +# thanks to betaflight for pin information + +include ../FlywooF405S-AIO/hwdef-bl.dat + +#undefine items to be changed +undef APJ_BOARD_ID + +# board ID for firmware load +APJ_BOARD_ID 1180 + +#required to prevent ELRS from changing modes at boot +PA10 USART1_RX USART1 OUTPUT HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef.dat new file mode 100644 index 00000000000000..cfd417420c5313 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405HD-AIOv2/hwdef.dat @@ -0,0 +1,15 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOF405HD_AIOv2 hardware. +# thanks to betaflight for pin information + +include ../FlywooF405S-AIO/hwdef.dat + +#undefine items to be changed +undef APJ_BOARD_ID + +# board ID for firmware load +APJ_BOARD_ID 1180 + +# GPIOs +PB5 PINIO1 OUTPUT GPIO(81) LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat index b02a0ace60109b..aec6b5772bedcb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat index 1014e4d783e742..d3cd91aeb33f12 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat @@ -118,8 +118,9 @@ PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) # M8 # LEDs PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58) # M9 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC14 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # Dataflash setup SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef-bl.dat index 56dcdc07d8177d..5d0ef165e54e05 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat index 0264c4a44eae9f..6c06ea552a8ea5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat @@ -106,8 +106,9 @@ PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4 # LEDs PA9 TIM1_CH2 TIM1 PWM(5) GPIO(54) # M5 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC14 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # Dataflash setup SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat index 1543f2b3379a81..5f03e5bad7c1d0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat @@ -149,9 +149,11 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 1 # one BARO BARO BMP280 I2C:0:0x76 BARO SPL06 I2C:0:0x76 +BARO DPS310 I2C:0:0x76 define AP_BARO_BACKEND_DEFAULT_ENABLED 0 define AP_BARO_SPL06_ENABLED 1 define AP_BARO_BMP280_ENABLED 1 +define AP_BARO_DPS280_ENABLED 1 # setup for OSD define OSD_ENABLED 1 @@ -162,10 +164,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin # define HAL_GYROFFT_ENABLED 1 # define AP_OAPATHPLANNER_ENABLED 0 -# EK2 options (disabled by default) -# define HAL_NAVEKF2_AVAILABLE 1 -# define HAL_NAVEKF3_AVAILABLE 0 - # save some flash include ../include/minimize_fpv_osd.inc include ../include/no_bootloader_DFU.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/Bottom.png b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/Bottom.png new file mode 100644 index 00000000000000..3c34aacdce3a08 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/Bottom.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/README.md new file mode 100644 index 00000000000000..2d1d8a3c89a8a1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/README.md @@ -0,0 +1,112 @@ +# Flywoo H743 Pro Flight Controller + +The Flywoo H743 Pro is a flight controller produced by [Flywoo](https://www.flywoo.net/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - Dual ICM42688 + - Barometer - SPL06 + - OSD - AT7456E + - Onboard Flash: 500MByte + - 7x UARTs + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 3.3V 0.5A + - BEC 5V 3A + - BEC 10V 3A for video, gpio controlled + - Dual switchable camera inputs + +## Pinout + +![Flywoo H743 Pro Board Top](Top.png "Flywoo H743 Pro Top") +![Flywoo H743 Pro Board Bottom](Bottom.png "Flywoo H743 Pro Bottom") + +## 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 (User, DMA-enabled) + - SERIAL2 -> UART2 (RX, DMA-enabled) + - SERIAL3 -> UART3 (User) + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL6 -> UART6 (ESC Telemetry) + - SERIAL7 -> UART7 (User) + - SERIAL8 -> UART8 (DisplayPort, DMA-enabled) + +## RC Input + +RC input is configured by default via the USART2 RX input. It supports all serial RC protocols except PPM. + +Note: If the receiver is FPort the receiver must be tied to the USART2 TX pin , RSSI_TYPE set to 3, +and SERIAL2_OPTIONS must be set to 7 (invert TX/RX, half duplex). For full duplex like CRSF/ELRS use both +RX1 and TX1 and set RSSI_TYPE also to 3. + +## FrSky Telemetry + +FrSky Telemetry is supported using an unused UART, such as the T3 pin (UART3 transmit). +You need to set the following parameters to enable support for FrSky S.PORT: + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The Flywoo H743 Pro supports OSD using OSD_TYPE 1 (MAX7456 driver) and simultaneously DisplayPort using TX8/RX8 on the HD VTX connector. + +## PWM Output + +The Flywoo H743 Pro supports up to 13 PWM or DShot outputs. The pads for motor output +M1 to M8 are provided on both the motor connectors and on separate pads, plus +M9-13 on a separate pads for LED strip and other PWM outputs. + +The PWM is in 4 groups: + + - PWM 1-2 in group1 + - PWM 3-6 in group2 + - PWM 7-10 in group3 + - PWM 11-12 in group4 + - PWM 13 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-10 support bi-directional dshot. + +## Battery Monitoring + +The board has a built-in voltage sensor and external current sensor input. 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 40 + +## Compass + +The Flywoo H743 Pro does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## VTX power control + +GPIO 81 controls the VTX BEC output to pins marked "10V". Setting this GPIO low removes voltage supply to pins. +By default RELAY2 is configured to control this pin and sets the GPIO high. + +## Camera control + +GPIO 82 controls the camera output to the connectors marked "CAM1" and "CAM2". Setting this GPIO low switches the video output from CAM1 to CAM2. By default RELAY3 is configured to control this pin and sets the GPIO high. + +## 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/FlywooH743Pro/Top.png b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/Top.png new file mode 100644 index 00000000000000..c6a86b6769fa68 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/Top.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/defaults.parm new file mode 100644 index 00000000000000..8b7587d088829d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/defaults.parm @@ -0,0 +1,2 @@ +SERVO13_FUNCTION 120 +OSD_TYPE2 5 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef-bl.dat new file mode 100644 index 00000000000000..d43b36e618507f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef-bl.dat @@ -0,0 +1,42 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOH743 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_FlywooH743Pro + +# 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 + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +PD10 VTX_PWR OUTPUT HIGH +PD11 CAM_CTRL OUTPUT HIGH + +PE3 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef.dat new file mode 100644 index 00000000000000..aebd3d3511c67d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooH743Pro/hwdef.dat @@ -0,0 +1,195 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOH743 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_FlywooH743Pro + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 384 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# SPI devices + +# SPI1 (IMU1) +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 (OSD) +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 (External) +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# SPI4 (IMU2) +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +# Beeper +PA15 TIM2_CH1 TIM2 GPIO(32) ALARM + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 (RX) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN + +# USART3 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (GPS1) +PB8 UART4_RX UART4 +PB9 UART4_TX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry + +# UART7 +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# UART8 (DJI/MSP) +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_MSP_DisplayPort + +# I2C ports +I2C_ORDER I2C1 I2C2 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +BARO SPL06 I2C:1:0x76 +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_SPL06_ENABLED 1 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 40.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 +define HAL_BATT_MONITOR_DEFAULT 4 +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2 +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) BIDIR # M3 +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) # M4 +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR # M5 +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) # M6 +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR # M7 +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # M8 +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR # S9 +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # S10 +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA # S11 +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA # S12 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # S13 + +# VTX Power control - should be high at startup to ensure power +PD10 VTX_PWR OUTPUT HIGH GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +# Camera switch control - should be high at startup to ensure Camera 1 selected +PD11 CAM_CTRL OUTPUT HIGH GPIO(82) +define RELAY3_PIN_DEFAULT 82 + +PE3 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PE4 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 + +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# IMU setup + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ +SPIDEV imu2 SPI4 DEVID1 GYRO2_CS MODE3 1*MHZ 16*MHZ + +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define HAL_OS_FATFS_IO 1 + +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90 +IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_90 + +DMA_NOSHARE TIM3_UP TIM5_UP TIM4_UP SPI1* SPI4* +DMA_PRIORITY TIM3_UP TIM5_UP TIM4_UP SPI1* SPI4* + +# 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 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat index fc17a788636d51..e9ef89d24e1626 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat @@ -27,8 +27,7 @@ SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat index 31b8c0a884528f..8a7d80b127a8a4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat @@ -92,8 +92,6 @@ PB8 I2C1_SCL I2C1 PB9 I2C1_SDA I2C1 # Servos -PB1 SERVO1 OUTPUT GPIO(70) LOW -define RELAY2_PIN_DEFAULT 70 PB14 CAMERA1 OUTPUT GPIO(71) LOW define RELAY3_PIN_DEFAULT 71 @@ -122,14 +120,18 @@ PB10 TIM2_CH3 TIM2 PWM(8) GPIO(57) # M8 PB7 TIM4_CH2 TIM4 PWM(9) GPIO(58) # LED +# Servos +PB1 TIM3_CH4 TIM3 PWM(10) GPIO(70) NODMA # S1 / M10 +PB0 TIM3_CH3 TIM3 PWM(11) GPIO(72) NODMA # S2 / M11 + # LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA13 LED0 OUTPUT LOW GPIO(90) define HAL_GPIO_A_LED_PIN 90 PA14 LED1 OUTPUT LOW GPIO(91) define HAL_GPIO_B_LED_PIN 91 -define HAL_GPIO_LED_ON 0 # Dataflash setup SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ @@ -145,6 +147,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin # Barometer setup BARO DPS310 I2C:0:0x76 +BARO BMP280 I2C:0:0x76 # IMU setup diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef-bl.dat index e12dd8df1edeba..3106a80968d85a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef.dat index 11b5ec3caae2ee..8f0f642cdebb7f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerH743v1/hwdef.dat @@ -136,8 +136,9 @@ PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) # M8 # LEDs PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC13 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # Dataflash setup SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ @@ -158,7 +159,9 @@ BARO DPS310 I2C:0:0x76 # IMU setup SPIDEV imu1 SPI2 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +SPIDEV imu2 SPI2 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ IMU Invensense SPI:imu1 ROTATION_YAW_270 +IMU Invensensev3 SPI:imu2 ROTATION_YAW_180 DMA_NOSHARE TIM3_UP TIM4_UP TIM8_UP SPI2* DMA_PRIORITY TIM3_UP TIM4_UP TIM8_UP SPI2* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat index 27f44956794e02..feb334dbb05549 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat @@ -110,9 +110,6 @@ define DMA_RESERVE_SIZE 0 PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 - -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat index f272f5fd135459..088062cadf56c5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat @@ -130,10 +130,6 @@ define HAL_UART_MIN_RX_SIZE 128 define HAL_UART_STACK_SIZE 0x200 - -define HAL_NO_MONITOR_THREAD - - define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 define IO_THD_WA_SIZE 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/README.md b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/README.md new file mode 100644 index 00000000000000..8d88bb0c111e00 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/README.md @@ -0,0 +1,99 @@ +# GEPRC TAKER F745 BT Flight Controller + +The TAKER F745 BT is a flight controller produced by [GEPRC](https://geprc.com/). + +## Features + + - STM32F745 microcontroller + - MPU6000+ICM42688 dual IMU + - BMP280 barometer + - microSD based 512MB flash logging + - AT7456E OSD + - 7 UARTs + - 8 PWM outputs + +## Pinout + +![TAKER F745 BT Board](TAKER_F745_BT_Board_Top.jpg "GEPRCF745BTHD") +![TAKER F745 BT Board](TAKER_F745_BT_Board_Bottom.jpg "GEPRCF745BTHD") + +## 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 (DisplayPort, DMA-enabled) + - SERIAL2 -> UART2 (RCIN, DMA-enabled) + - SERIAL3 -> UART3 (connected to internal BT module, not currently usable by ArduPilot) + - SERIAL4 -> UART4 (GPS) + - SERIAL6 -> UART6 (User) + - SERIAL7 -> UART7 (User) + - SERIAL8 -> UART8 (ESC Telemetry) + +## RC Input + +RC input is configured by default via the USAR2 RX input. It supports all unidirectional RC protocols except PPM. FPort and full duplex protocols, like CRSF/ELRS, will need to use TX2 also. + +Note: +If the receiver is FPort or a full duplex protocol, then the receiver must be tied to the USART2 TX pin and [SERIAL2_OPTIONS](https://ardupilot.org/copter/docs/parameters.html#serial2-options) = 7 (invert TX/RX, half duplex), and [RSSI_TYPE](https://ardupilot.org/copter/docs/parameters.html#rssi-type) =3. + +## 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 TAKER F745 BT supports analog OSD using its internal OSD chip and simultaneously HD goggle DisplayPort OSDs via the HD VTX connector. + +## VTX Support + +The SH1.0-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 12v (or VBAT by solder pad selection) so be careful not to connect to devices expecting 5v. + +## PWM Output + +The TAKER F745 BT supports up to 9 PWM outputs. The pads for motor output +M1 to M4 are on the esc connector, M5-M8 are solder pads, plus M9 is defaulted for serial LED strip or can be used as 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-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 13 + - BATT_VOLT_SCALE 11.0 + - BATT_CURR_PIN 12 + - BATT_CURR_SCALE 28.5 + +## Compass + +The TAKER F745 BT 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/GEPRCF745BTHD/TAKER_F745_BT_Board_Bottom.jpg b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/TAKER_F745_BT_Board_Bottom.jpg new file mode 100644 index 00000000000000..dfc0462b64bf2e Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/TAKER_F745_BT_Board_Bottom.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/TAKER_F745_BT_Board_Top.jpg b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/TAKER_F745_BT_Board_Top.jpg new file mode 100644 index 00000000000000..e4b6bdac6b392c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/TAKER_F745_BT_Board_Top.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/defaults.parm new file mode 100644 index 00000000000000..6455bd215b277c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 + +OSD_TYPE2 5 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef-bl.dat new file mode 100644 index 00000000000000..8906e3f859dfa0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef-bl.dat @@ -0,0 +1,54 @@ +# hw definition file for processing by chibios_pins.py +# for GEPRFF745-BT-HD bootloader + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_GEPRCF745BTHD + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +define STM32_LSECLK 32768U +define STM32_LSEDRV (3U << 3U) + +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) +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 + +PD2 BUZZER OUTPUT LOW PULLDOWN + +PC13 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# Motors for esc init +PB0 PWMOUT1 OUTPUT LOW +PB1 PWMOUT2 OUTPUT LOW +PB5 PWMOUT3 OUTPUT LOW +PB4 PWMOUT4 OUTPUT LOW +PD12 PWMOUT5 OUTPUT LOW +PD13 PWMOUT6 OUTPUT LOW +PC8 PWMOUT7 OUTPUT LOW +PC9 PWMOUT8 OUTPUT LOW + +# Add CS pins to ensure they are high in bootloader +PA15 SDCARD_CS CS +PE4 MAX7456_CS CS +PA4 MPU6000_CS CS +PB12 ICM42605_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef.dat new file mode 100644 index 00000000000000..1406cfeff35426 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/GEPRCF745BTHD/hwdef.dat @@ -0,0 +1,184 @@ +# hw definition file for processing by chibios_pins.py +# for TAKER F745 BT hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_GEPRCF745BTHD + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# leave 2 sectors free +FLASH_RESERVE_START_KB 96 + + +# only one I2C bus +I2C_ORDER I2C1 + +# I2C1 for baro +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# order of UARTs (and USB), +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 + +# buzzer +#define HAL_BUZZER_PIN 80 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for MPU6000 +PA4 MPU6000_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 for ICM42688 +PB12 ICM42605_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 for SDCard +PA15 SDCARD_CS CS +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# SPI4 for MAX7456 OSD +PE4 MAX7456_CS CS +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 11.13 +define HAL_BATT_CURR_SCALE 28.5 + +PC13 LED0 OUTPUT LOW GPIO(90) # LED +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 90 + +# In order to accommodate bi-directional dshot certain devices cannot be DMA enabled +# NODMA indicates these devices, if you remove it they will still not be resolved for DMA + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort + +# USART2 +# RC input defaults to UART to allow for bi-dir dshot +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN +define DEFAULT_SERIAL2_BAUD 115 + +# USART3 (BT) +PB11 USART3_RX USART3 NODMA +PB10 USART3_TX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (GPS) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# UART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None + +# UART7 +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None + +# UART8 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry + +# Motors, bi-directional dshot capable +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR # M2 +PB5 TIM3_CH2 TIM3 PWM(3) GPIO(52) # M3 +PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) # M5 +PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55) # M6 +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) NODMA # M7 +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) NODMA # M8 + +# extra PWM outs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # led pin +PD2 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +DMA_PRIORITY USART2* + +define HAL_STORAGE_SIZE 16384 +STORAGE_FLASH_PAGE 1 + +# spi devices +SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ +SPIDEV icm42688 SPI2 DEVID1 ICM42605_CS MODE3 2*MHZ 16*MHZ +SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ +SPIDEV osd SPI4 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ + +# IMU setup +IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 +IMU Invensense SPI:mpu6000 ROTATION_YAW_90 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# 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 + +# one BARO +BARO BMP280 I2C:0:0x76 + +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 + +# save some flash +include ../include/minimize_fpv_osd.inc +# disable parachute to save flash +define HAL_PARACHUTE_ENABLED 0 +include ../include/no_bootloader_DFU.inc + +#only enable BMP280 Baro +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +undef define AP_BARO_BMP280_ENABLED +define AP_BARO_BMP280_ENABLED 1 +define AP_BARO_MS56XX_ENABLED 1 + +# need to probe external baros even 'though we're minimised to allow custom build options: +undef AP_BARO_PROBE_EXTERNAL_I2C_BUSES +define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat index 350f832c1f62c1..40d0002e377359 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat @@ -21,9 +21,6 @@ APJ_BOARD_ID 146 FLASH_SIZE_KB 2048 -# setup build for a peripheral firmware -env AP_PERIPH 1 - EXT_FLASH_SIZE_MB 32 # bootloader is installed at zero offset diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat index 469cf96f1e0356..d040bb75c25808 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat @@ -23,9 +23,6 @@ APJ_BOARD_ID 146 FLASH_SIZE_KB 2048 -# setup build for a peripheral firmware -# env AP_PERIPH 1 - # bootloader is installed at zero offset FLASH_RESERVE_START_KB 128 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat index 68926f04e5401e..002175646b5109 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat @@ -22,6 +22,7 @@ OSCILLATOR_HZ 8000000 # --------------------- LED ----------------------- +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PC13 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT PC15 LED1 OUTPUT LOW GPIO(91) # green marked as B/E define HAL_GPIO_A_LED_PIN 91 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat index e3e6dca8be5ea1..2468fe41676a9e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat @@ -45,8 +45,6 @@ STM32_VDD 330U PB8 LED_SCK OUTPUT LOW PB9 LED_DI OUTPUT HIGH -define HAL_NO_MONITOR_THREAD - PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat index bfc89616e307dd..c0e8b3a72c65be 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat @@ -110,7 +110,6 @@ BARO MS56XX SPI:ms5611 PB8 TIM4_CH3 TIM4 PWM(1) PB9 TIM4_CH4 TIM4 PWM(2) - define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 @@ -132,7 +131,9 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 3 # for ProfiLed we need RC out and notify define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY +define AP_SERIALLED_ENABLED 1 define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat index b83fa886e228f1..ce612d3480cc23 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat @@ -45,8 +45,6 @@ STM32_VDD 330U PB8 LED_SCK OUTPUT LOW PB9 LED_DI OUTPUT HIGH -define HAL_NO_MONITOR_THREAD - PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat index daffe920786e07..02e4dc43f3032c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat @@ -92,9 +92,6 @@ define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE -define HAL_NO_MONITOR_THREAD - - define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 define IO_THD_WA_SIZE 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat index 5e63804ec10728..5ad3e22addf722 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat @@ -101,10 +101,6 @@ define HAL_UART_MIN_RX_SIZE 128 define HAL_UART_STACK_SIZE 0x200 - -define HAL_NO_MONITOR_THREAD - - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/HolybroF4_PMU_Board.jpg b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/HolybroF4_PMU_Board.jpg new file mode 100644 index 00000000000000..b37b6475b7231f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/HolybroF4_PMU_Board.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/README.md b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/README.md new file mode 100644 index 00000000000000..56d14eb425c768 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/README.md @@ -0,0 +1,42 @@ +# Holybro DroneCAN PMU + +https://holybro.com/products/dronecan-pm08-power-module-14s-200a + +## Features + +- Processor£ºSTM32F405RG 168MHz 1024KB Flash 196KB RAM +- Voltage input: 7~60.9V (2S~14S) +- Continuous current:200A +- Burst current 400A @ 25¡æ 1 sec£¬1000A @ 25¡æ < 1 sec +- Max current sensing: 376A +- Voltage accuracy: ¡À0.1V +- Current accuracy: ¡À5% +- Temperature accuracy:¡À1¡æ +- Power port output: 5.3V/3A each port +- Protocol: DroneCAN +- Operating temperature :-25¡æ~105¡æ +- Firmware upgrade: Support +- Calibration: Support + +## Interface Type + +- Power & CAN Port: Molex CLIK-Mate 2mm 6Pin +- Battery IN/OUT Options: + --XT90 Connectors + --Tinned Wires + --XT90 & Ring Terminals + +## Status LED + +- Flashing quickly continuously: MCU is in the bootloader stage, waiting for firmware to be flashed +- Flashing quickly for 3 seconds, and then on for 1 second: Waiting for CAN connection +- Flashing slowly (one-second intervals): CAN is successfully connected + +## Mechanical Spec + +- Size: 45mm¡Á41mm¡Á26mm (not include cable) +- Weight: 185g (include cable) + +## Loading Firmware + +You can upgrade the *.bin firmware files using the DroneCan GUI tool. *.apj files can also be upgraded using mossionplanner ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/defaults.parm new file mode 100644 index 00000000000000..20e564e87810e1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/defaults.parm @@ -0,0 +1,6 @@ +# Enable TSYS03 +TEMP1_TYPE 4 +TEMP1_SRC 3 +TEMP1_SRC_ID 1 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef-bl.dat new file mode 100644 index 00000000000000..abdec0497edaaa --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef-bl.dat @@ -0,0 +1,43 @@ +# hw definition file f405 Holybro CAN PMU + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 5401 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_SIZE_KB 1024 +FLASH_BOOTLOADER_LOAD_KB 64 + +PB0 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue +define HAL_LED_ON 0 + +# debug +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# order of UARTs +SERIAL_ORDER USART3 + +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA15 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.f405_HolybroPMU" + + +# Add CS pins to ensure they are high in bootloader diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef.dat new file mode 100644 index 00000000000000..5373728eb07f11 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroF4_PMU/hwdef.dat @@ -0,0 +1,114 @@ +# hw definition file for f405 Holybro CAN PMU + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 +FLASH_SIZE_KB 1024 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 15360 + +# board ID for firmware load +APJ_BOARD_ID 5401 + +env AP_PERIPH 1 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# enable watchdog + +# crystal frequency +OSCILLATOR_HZ 16000000 + +STDOUT_SERIAL SD3 +STDOUT_BAUDRATE 57600 + +# blue LED0 marked as ACT +PB0 LED OUTPUT HIGH GPIO(90) +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 90 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +# debug +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# avoid timer and RCIN threads 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_DEVICE_THREAD_STACK 768 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +# ---------------------- CAN bus ------------------------- +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# use DNA for node allocation + +define CAN_APP_NODE_NAME "org.ardupilot.f405_HolybroPMU" + + +# ---------------------- UARTs --------------------------- +# +SERIAL_ORDER USART3 + +# USART3, for debug +PC10 USART3_TX USART3 SPEED_HIGH NODMA +PC11 USART3_RX USART3 SPEED_HIGH NODMA + +# ---------------------- I2Cs --------------------------- +# +I2C_ORDER I2C1 + +# I2C2, for TEMP SENSOR +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# ------------------ BATTERY Monitor ----------------------- +define HAL_PERIPH_ENABLE_BATTERY +define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) + +# Set the Default Battery Monitor Type to be Analog I/V +define HAL_BATT_MONITOR_DEFAULT 4 + +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 18.0 + +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 125 + +# ACS772-400U Zero-Current Offset +define AP_BATT_CURR_AMP_OFFSET_DEFAULT 0.409 + +# ------------------ Temperature Sensor ----------------------- +define AP_TEMPERATURE_SENSOR_ENABLED 1 +define AP_TEMPERATURE_SENSOR_TSYS03_ENABLED 1 +define AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT 64 +define AP_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT 0 + + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef-bl.dat new file mode 100644 index 00000000000000..a091d179c22e20 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef-bl.dat @@ -0,0 +1,84 @@ +# 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 + +# 512k flash part +FLASH_SIZE_KB 512 + +# board ID for firmware load +APJ_BOARD_ID 5405 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# debug on USART1 +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# order of UARTs +SERIAL_ORDER USART1 + +# I2C buses +I2C_ORDER I2C1 + +# blue LED +PB15 LED_BOOTLOADER OUTPUT HIGH +define HAL_LED_ON 0 + +#green LED, Power ON indicator, Low ON +PA4 LED_GREEN OUTPUT LOW + +# I2C1 bus +PB7 I2C1_SDA I2C1 +PA15 I2C1_SCL I2C1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# 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 FALSE +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 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB2 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a smaller bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 2500 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef.dat new file mode 100644 index 00000000000000..753463b21b5512 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Airspeed/hwdef.dat @@ -0,0 +1,95 @@ +# 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 5405 + +# 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 USART1 +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER USART1 + +# I2C buses +I2C_ORDER I2C1 + +# LEDs +# blue LED0 marked as ACT +PB15 LED OUTPUT HIGH +define HAL_LED_ON 0 + +#green LED, Power ON indicator, Low ON +PA4 LED_GREEN OUTPUT LOW + +# USART1, debug +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# I2C1 bus +PB7 I2C1_SDA I2C1 +PA15 I2C1_SCL I2C1 + +define HAL_I2C_INTERNAL_MASK 1 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +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 +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB2 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_NO_MONITOR_THREAD + +define HAL_DEVICE_THREAD_STACK 768 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# Airspeed +define HAL_PERIPH_ENABLE_AIRSPEED + +# 10" DLVR sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 10 +define AIRSPEED_MAX_SENSORS 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/HolybroG4_Compass/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat index 9638c51aa21d8f..2b849b6f64ea81 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat @@ -38,11 +38,11 @@ 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # USART2, debug PA2 USART2_TX USART2 @@ -81,8 +81,6 @@ PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat index e4748206c69b46..895e3703bc86b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat @@ -42,11 +42,11 @@ 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # USART3, GPS PB10 USART3_TX USART3 @@ -86,9 +86,15 @@ PC14 ICM_CS CS # GPS PPS PA15 GPS_PPS_IN INPUT -# compass +# compass bmm150 on can-M8N and can-F9P-v1 COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90 +# compass ist8310 on can-M9N +COMPASS IST8310 I2C:0:0x0E false ROTATION_NONE + +# compass RM3100 on can-F9P-v2 +COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE + define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE @@ -109,8 +115,6 @@ PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat index eb7125097e9ee4..a5257aff3ea538 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat @@ -44,11 +44,11 @@ PB15 LED OUTPUT HIGH GPIO(2) # blue PA7 LED_R OUTPUT HIGH GPIO(0) PB14 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # USART1, GPS PA9 USART1_TX USART1 NODMA @@ -126,10 +126,6 @@ PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -define HAL_NO_MONITOR_THREAD - - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/README.md new file mode 100644 index 00000000000000..9cb60c81804dcc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/README.md @@ -0,0 +1,105 @@ +# iFlight 2RAW H743 Flight Controller + +The iFlight 2RAW H743 is a flight controller produced by [iFlight](https://shop.iflight.com/Thunder-H7-Flight-Controller-Pro2200). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - ICM42688P + - Barometer - SPL06-001 + - Onboard Flash: 1GBit exposed as microSD card + - 6x UARTs + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 5V 1.5A + - BEC 10V 1.5A + +## Pinout + +![iFlight 2RAW H743 Board Top](Thunder-H7-1.png "iFlight 2RAW H743 Top") +![iFlight 2RAW H743 Board Bottom](Thunder-H7-2.png "iFlight 2RAW H743 Bottom") + +## 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 (VTX HD, DMA-enabled) + - SERIAL2 -> UART2 (RX, DMA-enabled) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL6 -> UART6 (ESC Telemetry) + +## 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 SERIAL3 as an RC input serial port, +with half-duplex, pin-swap and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the T3 pin (UART3 transmit). You need to set the following parameters to enable support for FrSky S.PORT + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The iFlight 2RAW H743 supports MSP DisplayPort OSD using OSD_TYPE 5 + +## PWM Output + +The iFlight 2RAW H743 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 are provided in the motor connector, plus M9 on a separate pad for LED strip +or another PWM output. + +The PWM is in 5 groups: + + - PWM 1-2 in group1 + - PWM 3-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 iFlight 2RAW H743 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## VTX power control +GPIO 81 controls the VTX BEC output to pins marked "10V". Setting this GPIO low removes voltage supply to pins. +By default RELAY2 is configured to control this pin and sets the GPIO high. + +## Logging + +Logging is via a 1GBit flash chip exposed via a microSD interface. In order to be used you must format the card using mission planner +after the first time you have loaded the firmware + +## 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/IFLIGHT_2RAW_H7/Thunder-H7-1.png b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/Thunder-H7-1.png new file mode 100644 index 00000000000000..75ff0f8d108704 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/Thunder-H7-1.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/Thunder-H7-2.png b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/Thunder-H7-2.png new file mode 100644 index 00000000000000..29d2020f2cad90 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/Thunder-H7-2.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/defaults.parm new file mode 100644 index 00000000000000..a328b10088d6a2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +# Default VTX power to on +RELAY2_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef-bl.dat new file mode 100644 index 00000000000000..0c899d32513c0d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef-bl.dat @@ -0,0 +1,42 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_2RAW_H743 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_2RAWH743 + +# 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 + +PD11 CAM_SW OUTPUT LOW +PD10 VTX_PWR OUTPUT HIGH + +# Chip select pins +PA15 SDCARD1_CS CS +PB12 OSD1_CS CS +PC15 GYRO1_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef.dat new file mode 100644 index 00000000000000..d90fe2e67904ec --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/IFLIGHT_2RAW_H7/hwdef.dat @@ -0,0 +1,150 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_2RAW_H743 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_2RAWH743 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 384 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 2 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 +PC12 SPI3_MOSI SPI3 +PC11 SPI3_MISO SPI3 +PC10 SPI3_SCK SPI3 + +# Chip select pins +PA15 SDCARD1_CS CS +PB12 OSD1_CS CS +PC15 GYRO1_CS CS + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 OTG2 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 (VTX HD) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 5 + +# USART2 (RX) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 (GPS) +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS + +# UART4 (GPS) +PB8 UART4_RX UART4 +PB9 UART4_TX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry + +# I2C ports +I2C_ORDER I2C1 I2C2 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 40.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2 +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) BIDIR # M3 +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) # M4 +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR # M5 +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) # M6 +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR # M7 +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # M8 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 + +# VTX power switch +PD10 VTX_PWR OUTPUT LOW GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 +PE3 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PE4 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 + +BARO SPL06 I2C:1:0x76 + +# SPI setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ +SPIDEV sdcard SPI3 DEVID1 SDCARD1_CS MODE0 400*KHZ 25*MHZ + +# IMU setup +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +DMA_NOSHARE TIM3_UP TIM5_UP TIM4_UP SPI1* +DMA_PRIORITY TIM3_UP TIM5_UP TIM4_UP SPI1* + +# 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 1 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 +define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat index 21d2a04a331f34..efa1c9bd79b98e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat @@ -288,9 +288,9 @@ PC7 LED_BLUE OUTPUT GPIO(90) HIGH PB1 LED_RED OUTPUT OPENDRAIN GPIO(92) # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat index 6a7b2f739bd483..6e564b78f160bf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat @@ -42,8 +42,7 @@ SERIAL_ORDER OTG1 UART7 UART5 USART3 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 921600 -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # USB OTG1 SERIAL0 PA11 OTG_FS_DM OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat index 714b561d303cde..531d1327d2f3b6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat @@ -316,10 +316,10 @@ PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(71) LOW SPEED_VERYLOW PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(72) HIGH SPEED_VERYLOW # setup for "AP_BoardLED" RGB LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 72 define HAL_GPIO_B_LED_PIN 70 #define HAL_GPIO_C_LED_PIN 71 -define HAL_GPIO_LED_ON 0 # PWM output for buzzer PF9 TIM14_CH1 TIM14 GPIO(73) ALARM SPEED_VERYLOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat index 58fe5d18983b75..e1d5cee3f1d7fc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat @@ -71,6 +71,7 @@ PA3 TIM5_CH4 TIM5 PWM(3) GPIO(52) BIDIR PA2 TIM5_CH3 TIM5 PWM(4) GPIO(53) # Board LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PC14 LED1 OUTPUT LOW GPIO(1) PC15 LED2 OUTPUT LOW GPIO(2) define HAL_GPIO_A_LED_PIN 1 @@ -152,20 +153,8 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define HAL_GYROFFT_ENABLED 0 # --------------------- save flash ---------------------- -define AP_BATTERY_SMBUS_ENABLED 0 -define AP_BATT_MONITOR_MAX_INSTANCES 1 define HAL_PARACHUTE_ENABLED 0 -define HAL_SPRAYER_ENABLED 0 -define HAL_GENERATOR_ENABLED 0 -define AP_OAPATHPLANNER_ENABLED 0 -define AC_PRECLAND_ENABLED 0 -define HAL_BARO_WIND_COMP_ENABLED 0 -define AP_GRIPPER_ENABLED 0 -define HAL_HOTT_TELEM_ENABLED 0 -define HAL_NMEA_OUTPUT_ENABLED 0 -define HAL_BUTTON_ENABLED 0 -define AP_NOTIFY_OREOLED_ENABLED 0 -define HAL_PICCOLO_CAN_ENABLE 0 -define BARO_MAX_INSTANCES 1 +include ../include/minimize_fpv_osd.inc + AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/JHEMCU-H743HD_Board.jpg b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/JHEMCU-H743HD_Board.jpg new file mode 100644 index 00000000000000..9ab9c11367c605 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/JHEMCU-H743HD_Board.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/README.md b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/README.md new file mode 100644 index 00000000000000..8f49647cf831e2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/README.md @@ -0,0 +1,79 @@ +# JHEMCU H743 HD Flight Controller + +The JHEMCU H743 HD is a flight controller produced by [JHEMCU](https://jhemcu.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - dual ICM42688P + - Barometer - DPS310 + - Voltage & current sensor + - OSD - AT7456E + - Onboard Flash: 1 Gbits (W25N01G) + - 7x UARTs (1,2,3,4,5,6,7) + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 3S-6S + - BEC 5V/2.5A, 10V/2.0A + +## Pinout + +![JHEMCU H743 Board](JHEMCU-H743HD_Board.jpg "JHEMCU H743HD") + +## UART Mapping + +The UARTs are marked RXn and TXn in the above pinouts. The RXn pin is the +receive pin for UARTn. The TXn pin is the transmit pin for UARTn. + +In addition to pinouts, the board also has SH6P 1mm connector for DJI FPV and SH8P 1mm connector for 4 in 1 ESC. + + - SERIAL0 -> USB + - SERIAL1 -> USART1 (DMA-enabled) + - SERIAL2 -> USART2 (RX/SBUS, DMA-enabled) + - SERIAL3 -> USART3 (DMA-enabled) + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL5 -> UART5 (Pins labeled R5 T5) + - SERIAL6 -> USART6 (DisplayPort, DMA-enabled) + - SERIAL7 -> UART7 (ESC Telemetry) + - SERIAL8 -> UART8 (Unused, not tested, no pinout, need to solder direct on precessor pins to utilize if you need just one more UART) + +## RC Input + +RC input is configured on the RX2/TX2 (USART2_RX/USART2_TX) pins. It supports ELRS(CSRF), TBS(CSRF), SBUS, IBUS, DSM2, and DSMX. + +## OSD Support + +JHEMCU H743 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +JHEMCU H743 supports up to 9 PWM outputs. 8 motors and 1 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 built-in voltage and current sensor. The current +sensor's max Amps is not specified. The voltage sensor can handle up to 6S +LiPo batteries. + +## Compass + +JHEMCU H743 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/JHEMCU-H743HD/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/defaults.parm new file mode 100644 index 00000000000000..bf8d477d44bec3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/defaults.parm @@ -0,0 +1,2 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef-bl.dat new file mode 100644 index 00000000000000..66e51185c64bd8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef-bl.dat @@ -0,0 +1,45 @@ + +# hw definition file for processing by chibios_hwdef.py +# for JHEH743_HD hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1411 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +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 + + + + +# Chip select pins +PA15 FLASH1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS +PE11 GYRO2_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef.dat new file mode 100644 index 00000000000000..5d7c65b52855e5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/hwdef.dat @@ -0,0 +1,181 @@ + +# hw definition file for processing by chibios_hwdef.py +# for JHEH743_HD hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1411 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 384 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 2 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 +PB2 SPI3_MOSI SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 + +# SPI4 +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# Chip select pins +PA15 FLASH1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS +PE11 GYRO2_CS CS + +# Beeper +PE3 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8 OTG2 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 +PD0 UART4_RX UART4 +PD1 UART4_TX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +# USART6 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_MSP_DisplayPort + +# UART7 +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry + +# UART8 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA + +# I2C ports +I2C_ORDER I2C1 I2C2 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# Servos + +# ADC ports + +# ADC1 +PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 11 +define HAL_BATT_VOLT_SCALE 11.0 +PC3 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 13 +define HAL_BATT_CURR_SCALE 58.8 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR # M1 +PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51) # M2 +PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR # M3 +PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4 +PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) BIDIR # M5 +PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55) # M6 +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR # M7 +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) # M8 + + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 + +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 +PE5 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PE4 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 + +# Dataflash setup +SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +BARO DPS310 I2C:0:0x76 + +# IMU setup + +# IMU setup +SPIDEV icm42688p SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +IMU Invensensev3 SPI:icm42688p ROTATION_PITCH_180 + +SPIDEV icm42688p2 SPI4 DEVID2 GYRO2_CS MODE3 1*MHZ 8*MHZ +IMU Invensensev3 SPI:icm42688p2 ROTATION_ROLL_180 + +DMA_NOSHARE TIM5_UP TIM3_UP TIM8_UP SPI1* SPI4* +DMA_PRIORITY TIM5_UP TIM3_UP TIM8_UP SPI1* SPI4* + +# 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 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/processor pins.png b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/processor pins.png new file mode 100644 index 00000000000000..7967658f1074a1 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-H743HD/processor pins.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat index 19fa51f746848c..b579c42686de12 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat @@ -21,7 +21,11 @@ FLASH_RESERVE_START_KB 0 FLASH_BOOTLOADER_LOAD_KB 48 # order of UARTs (and USB) -SERIAL_ORDER OTG1 +SERIAL_ORDER OTG1 USART6 + +# adding USART6 to be active in bl +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 # PA10 IO-debug-console PA11 OTG_FS_DM OTG1 @@ -30,8 +34,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat index 24fcd7064fd486..e55d72117bb2e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat @@ -108,8 +108,9 @@ PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) # M8 # LEDs PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58) # LED +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC14 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # Dataflash setup SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/README.md b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/README.md new file mode 100644 index 00000000000000..7fce398d54d911 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/README.md @@ -0,0 +1,93 @@ +# KakuteF4-Wing Flight Controller + +The KakuteF4-Wing is a flight controller produced by [Holybro](http://www.holybro.com/). + +## Features + Processor + STM32F405 32-bit processor + AT7456E OSD + Sensors + ICM42688 Acc/Gyro + SLP06 barometer + Power + 2S - 8S Lipo input voltage with voltage monitoring + 9V/12V, 1.5A BEC for powering Video Transmitter + 6V/7.2V, ?A BEC for servos + 3.3V, 1A BEC + Interfaces + 7x PWM outputs DShot capable, 4 outputs BiDirDShot capable + 1x RC input + 5x UARTs/serial for GPS and other peripherals + 1x I2C ports for external compass, airspeed, etc. + USB-C port + +## Pinout + +![KakuteF4-Wing Bottom](kakutef4-esc.png) +![KakuteF4-Wing Top Underside](kakutef4-uart.png) +![KakuteF4-Wing Top](kakutef4-uart2.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. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (GPS) DMA-Enabled + - SERIAL2 -> UART2 (Telem1) DMA Enabled + - SERIAL3 -> UART3 (RX) DMA Enabled + - SERIAL5 -> UART5 (User) + - SERIAL6 -> USART6 (User) + +## RC Input + +RC input is configured on the R3 (UART3_RX) pin. It supports all serial RC +protocols. + +## OSD Support + +The KakuteF4-Wing supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The KakuteF4 supports up to 7 PWM outputs. All outputs support DShot. Outputs 1-4 support BiDirDshot. + +The PWM is in 5 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 and current sensor. The current +sensor can read up to ?? 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 + - BATT_AMP_PERVLT 40 + +## Compass + +The KakuteF4-Wing does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “KakuteF4-Wingâ€. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "KakuteF4-Wing_bl.hex" +firmware, using your favourite DFU loading tool. + +Subsequently, you can update firmware with Mission Planner. + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/defaults.parm new file mode 100644 index 00000000000000..18c9c24de3f115 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan5 +SERVO7_FUNCTION 120 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef-bl.dat new file mode 100644 index 00000000000000..0e2f5951533a5f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for KAKUTEF4WING hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_Holybro-KakuteF4-Wing + +# 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 48 + +# 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 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PC14 FLASH1_CS CS +PC15 OSD1_CS CS +PA4 GYRO1_CS CS + +PA1 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef.dat new file mode 100644 index 00000000000000..9981b3dfe799af --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/hwdef.dat @@ -0,0 +1,156 @@ + +# hw definition file for processing by chibios_hwdef.py +# for KAKUTEF4WING hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_Holybro-KakuteF4-Wing + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 48 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +define STM32_ST_USE_TIMER 9 +define CH_CFG_ST_RESOLUTION 16 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# SPI3 +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# Chip select pins +PC14 FLASH1_CS CS +PC15 OSD1_CS CS +PA4 GYRO1_CS CS + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 EMPTY UART5 USART6 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# This is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN. +PA10 VBUS INPUT OPENDRAIN + +# USART1 +PB7 USART1_RX USART1 +PB6 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_GPS + +# USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 NODMA +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2 + +# USART3 - RX +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN +# SBUS inversion control pin, active high +PC13 USART3_RXINV OUTPUT HIGH GPIO(78) POL(1) + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA + +# I2C ports +I2C_ORDER I2C2 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# Servos + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 40 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) # M1 +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) BIDIR # M2 +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) # M3 +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) # M5 +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6 + +# LEDs +PA1 TIM5_CH2 TIM5 PWM(7) GPIO(56) # M7 + +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +PC5 LED_BLUE OUTPUT LOW GPIO(90) +define AP_NOTIFY_GPIO_LED_1_PIN 90 + +# GPIOs +PB14 PINIO1 OUTPUT GPIO(81) LOW +PB15 PINIO2 OUTPUT GPIO(82) LOW + +# Dataflash setup +SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +# one IMU +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90 + +DMA_PRIORITY I2C2* SPI3* + +# Baro setup +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 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 +define HAL_FRAME_TYPE_DEFAULT 12 + +# minimal drivers to reduce flash usage +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-esc.png b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-esc.png new file mode 100644 index 00000000000000..b165f1ce0d54b2 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-esc.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart.png b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart.png new file mode 100644 index 00000000000000..4f0c4ae2172e2a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart2.png b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart2.png new file mode 100644 index 00000000000000..30a823e6422e90 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4-Wing/kakutef4-uart2.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat index eea0b4785433c6..37fcf36778e079 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat @@ -139,8 +139,10 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180 # one baro BARO BMP280 I2C:0:0x76 +BARO SPL06 I2C:0:0x76 define AP_BARO_BACKEND_DEFAULT_ENABLED 0 define AP_BARO_BMP280_ENABLED 1 +define AP_BARO_SPL06_ENABLED 1 # enable logging to dataflash define HAL_LOGGING_DATAFLASH_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index b0d9ea996a64b0..fff9f062272e98 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -144,10 +144,10 @@ define HAL_PARACHUTE_ENABLED 0 # save FLASH, but leave above when flash issue is fixed include ../include/minimize_fpv_osd.inc include ../include/no_bootloader_DFU.inc - -# disable SMBUS battery monitors to save flash -undef AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_ENABLED 0 +#only enable BMP280 Baro +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +undef define AP_BARO_BMP280_ENABLED +define AP_BARO_BMP280_ENABLED 1 # setup for OSD define HAL_OSD_TYPE_DEFAULT 1 @@ -159,6 +159,6 @@ define HAL_WITH_MSP_DISPLAYPORT 1 undef HAL_MSP_ENABLED define HAL_MSP_ENABLED 1 -# need to probe external baros even 'though we're minimised: +# need to probe external baros even 'though we're minimised to allow custom build options: undef AP_BARO_PROBE_EXTERNAL_I2C_BUSES define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat index 9123963e568eea..53ae134e5bc5df 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat @@ -85,6 +85,7 @@ define BOARD_RSSI_ANA_PIN 10 # LED # green LED1 marked as B/E # blue LED0 marked as ACT +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PC15 LED0 OUTPUT LOW GPIO(90) # blue PC14 LED1 OUTPUT LOW GPIO(91) # red define HAL_GPIO_A_LED_PIN 91 @@ -203,6 +204,7 @@ IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270 # BMP280 integrated on I2C4 bus BARO BMP280 I2C:0:0x76 +BARO SPL06 I2C:0:0x76 define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat index a39b0076291bd4..b70f466f513ed6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat @@ -35,8 +35,7 @@ PC13 BUZZER OUTPUT LOW PULLDOWN PC2 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Add CS pins to ensure they are high in bootloader PE4 IMU_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat index 11dfb4ae418f85..5ce9b33c622d03 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat @@ -150,6 +150,7 @@ IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_270 # one BARO BARO BMP280 I2C:0:0x76 +BARO SPL06 I2C:0:0x76 define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat index 98d7f7c038865e..5e3a7b1bdbd709 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat @@ -9,4 +9,4 @@ 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 +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/defaults.parm index 3687d251b52296..74526c42af1bc4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/defaults.parm @@ -1,7 +1,7 @@ # setup for LEDs on chan9 SERVO9_FUNCTION 120 # Default VTX power to on -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 # UART1 for DJI Goggles SERIAL1_PROTOCOL 33 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat index c66e93ba9df9bf..d618ce194c4232 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat @@ -35,8 +35,7 @@ PC13 BUZZER OUTPUT LOW PULLDOWN PC2 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Add CS pins to ensure they are high in bootloader PE4 IMU_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef.dat index 0c2d49296f1464..258a9ea05428f2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef.dat @@ -136,6 +136,7 @@ DMA_NOSHARE SPI1* SPI4* # spi devices SPIDEV mpu6000 SPI4 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ +SPIDEV icm42688 SPI4 DEVID1 MPU6000_CS MODE3 2*MHZ 16*MHZ SPIDEV dataflash SPI1 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ @@ -146,11 +147,13 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 -# one IMU +# one IMU v1.1 mpu6000, v1.5 icm42688 IMU Invensense SPI:mpu6000 ROTATION_YAW_180 +IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 # one BARO BARO BMP280 I2C:0:0x76 +BARO SPL06 I2C:0:0x76 # setup for OSD define OSD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md index 45610569cee87e..9589e7e46ab8a5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md @@ -52,7 +52,7 @@ 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. +this to a peripheral requiring 5v. The 9v supply is controlled by RELAY2_PIN and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2. ## PWM Output diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm index 8775f3bf2290ff..7258a35328ee2c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm @@ -1,7 +1,7 @@ # setup for LEDs on chan9 SERVO9_FUNCTION 120 # Default VTX power to on -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 # UART1 for DJI Goggles SERIAL1_PROTOCOL 33 # UART3 for VTX diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat index d871100d15b3d9..2a40cc91f5912b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat @@ -65,6 +65,6 @@ DMA_NOSHARE *UP SPI1* # 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 +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING.jpg b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING.jpg new file mode 100644 index 00000000000000..5b56f187bd6e9a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING_pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING_pinout.png new file mode 100644 index 00000000000000..9fe0ac0ff69682 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/LongBowF405WING_pinout.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/PMU.png b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/PMU.png new file mode 100644 index 00000000000000..3846e951a35349 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/PMU.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/Readme.md new file mode 100644 index 00000000000000..9e2273518f3eb9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/Readme.md @@ -0,0 +1,117 @@ +# LongBowF405WING Flight Controller + +The LongBowF405WING is a flight controller produced by [lefei rc](http://www.lefeirc.com/). + +## Features + Processor + STM32F405 168Mhz, 1MB 32-bit processor + AT7456E OSD + Sensors + ICM42688P Acc/Gyro + SPL006 barometer + Power + 2S - 6S Lipo input voltage with voltage monitoring + 120A Cont., 215A peak current monitor + 9V/12/5V, 1.8A BEC for powering Video Transmitter controlled by GPIO + 4.9V/6V/7.2V, 6A BEC for servos + 5V, 2.4A BEC for internal and peripherals + Interfaces + 12x PWM outputs DShot capable (Serail LED output is PWM12) + 1x RC input + 5x UARTs/serial for GPS and other peripherals, 6th UART internally tied to Wireless board) + I2C port for external compass, airspeed, etc. + microSDCard for logging, etc. + USB-C port + +## Pinout +![LongBowF405WING](LongBowF405WING_pinout.png) + +## Wiring Diagram +![LongBowF405WING](LongBowF405WING.jpg) + +## PDB +![LongBowF405WING](PMU.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. + + - SERIAL0 -> USB + - SERIAL1 -> USART1 (User) (DMA capable) + - SERIAL2 -> USART2 (RX tied to inverted SBUS RC input, but can be used as normal UART if :ref:`BRD_ALT_CONFIG<>` =1) + - SERIAL3 -> UART3 (GPS) (TX DMA capable) + - SERIAL4 -> UART4 (User) (TX DMA capable) + - SERIAL5 -> UART5 (DisplayPort, available on DJI air unit connector) (TX DMA capable) + - SERIAL6 -> UART6 (tied to internal wireless module, MAVLink2 telem) + + +## RC Input + +RC input is configured on the SBUS pin (inverted and sent to UART2_RX). It supports all RC +protocols except serial protocols such as CRSF, ELRS, etc. Those devices can be connected to USART1 TX and RX, instead. +Fport can be connected to USART1 TX also, but will require an external bi-directional inverter and the ref:`SERIAL1_OPTION' = 4 (HalfDuplex) set. + +## OSD Support + +The LongBowF405WING supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such DisplayPor is setup by default using UART5. Simultaneous use of the internal OSD and Displayport is allowed. See :ref:`common-msp-osd-overview-4.2` for more info. + + +## PWM Output + +The LongBowF405WING supports up to 12 PWM outputs . +All outputs support DShot. + +The PWM is in 5 groups: + + - PWM 1,2 in group1 + - PWM 3,4 in group2 + - PWM 5-6 in group3 + - PWM 7-9 in group4 + - PWM 10-12 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 that group would need +to use DShot. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 120A continuosly, 160 Amps peak. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are set by default and are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.0 + - BATT_AMP_PERVLT 50 + +## Compass + +The LongBowF405WING does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## VTX power control + +GPIO 81 controls the VTX BEC output to pins marked "9V" and "Vs1". Setting a RELAY function to this pin and turning it "ON" will remove the supply from these pins. + +## Camera Switch + +GPIO 82 controls which camera input (CC1 or C2 is applied to the internal OSD. A RELAY function can be enabled to control the switching. + +## Buzzer + +An active buzzer output is provided and is controlled as GPIO 80 + +## Loading Firmware + +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled LongBowF405WING. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "LongBowF405WING_bl.hex" +firmware, using your favourite DFU loading tool. + +Subsequently, you can update firmware with Mission Planner. + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/defaults.parm new file mode 100644 index 00000000000000..3fb16d3236780b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/defaults.parm @@ -0,0 +1,10 @@ +#Serial Port defaults +SERIAL4_PROTOCOL -1 +SERIAL1_PROTOCOL 23 +SERIAL2_PROTOCOL -1 +SERIAL5_PROTOCOL 42 +SERIAL6_PROTOCOL 2 + +#Enable second OSD Type as DisplayPort +OSD_TYPE2 5 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef-bl.dat new file mode 100644 index 00000000000000..efc1004b2861ae --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef-bl.dat @@ -0,0 +1,38 @@ +# hw definition file for processing by chibios_pins.py +# for LongBowF4 bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_LongbowF405 + + +# crystal frequency +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + +# LEDs +PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) +PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) +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 MPU_CS CS +PB12 OSD_CS CS +PC14 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef.dat new file mode 100644 index 00000000000000..01db0f16784dac --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/LongBowF405WING/hwdef.dat @@ -0,0 +1,192 @@ +# hw definition file for LongBow F4 WING hardware +# tested on the LongBow F405 WING board +# + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_LongbowF405 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# reserve 16k for bootloader, 16k for OSD and 32k for flash storage +FLASH_RESERVE_START_KB 64 +FLASH_SIZE_KB 1024 + +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# only one I2C bus +I2C_ORDER I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 + +# LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 + +PA13 LED_GREEN OUTPUT LOW GPIO(0) +PA14 LED_BLUE OUTPUT LOW GPIO(1) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 + +# buzzer +PC15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + + + +# spi1 bus for IMU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 MPU_CS CS + +# spi2 for OSD +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PB12 OSD_CS CS + +# spi3 for sdcard +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 +PC14 SDCARD_CS CS + +# only one I2C bus in normal config +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# analog pins +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC4 RSSI_ADC_PIN ADC1 SCALE(1) + +PC5 PRESSURE_SENS ADC1 SCALE(1) +define HAL_DEFAULT_AIRSPEED_PIN 15 + +# 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.0 # matched to PDB board +define HAL_BATT_CURR_SCALE 50 # matched to PDB board + +# analog rssi pin +define BOARD_RSSI_ANA_PIN 14 + +# USART1 (ELRS) +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + + +# USART2 (RCIN with inverter) + +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW + +# alternative with PA3 as USART2_RX +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) + +# USART3 (GPS) +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_BAUD 115 + +# UART4 serial4 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA + +# USART5 (DJI / VTX) +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 NODMA + +# UART6 (onboard Telemetry) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_BAUD 115 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# PWM out pins. Note that channel order follows the ArduPilot motor +# order conventions +PC9 TIM8_CH4 TIM8 PWM(1) GPIO(50) +PC8 TIM8_CH3 TIM8 PWM(2) GPIO(51) +PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) +PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) +PB6 TIM4_CH1 TIM4 PWM(5) GPIO(54) +PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55) +PA8 TIM1_CH1 TIM1 PWM(7) GPIO(56) +PB15 TIM1_CH3N TIM1 PWM(8) GPIO(57) +PB14 TIM1_CH2N TIM1 PWM(9) GPIO(58) +PA15 TIM2_CH1 TIM2 PWM(10) GPIO(59) +PB11 TIM2_CH4 TIM2 PWM(11) GPIO(60) +PB10 TIM2_CH3 TIM2 PWM(12) GPIO(61) + + +# one IMU +IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_270 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# one baro +BARO SPL06 I2C:0:0x77 +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 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +# ICM42688P on SPI1 +SPIDEV icm42688 SPI1 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ + +# OSD on SPI2 +SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ + +# SD Card on SPI3 +SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + +#VTX power control +PC13 PINIO1 OUTPUT GPIO(81) LOW + +#CAM SW +PB2 PINIO2 OUTPUT GPIO(82) LOW + +define STM32_PWM_USE_ADVANCED TRUE + +define HAL_WITH_DSP FALSE + +include ../include/minimize_fpv_osd.inc + +#undef AP_CAMERA_MOUNT_ENABLED +#undef AP_LANDINGGEAR_ENABLED +#undef HAL_MOUNT_ENABLED +#undef HAL_MOUNT_SERVO_ENABLED + +#define AP_CAMERA_MOUNT_ENABLED 1 +#define AP_LANDINGGEAR_ENABLED 1 +#define HAL_MOUNT_ENABLED 1 +#define HAL_MOUNT_SERVO_ENABLED 1 + +#define DEFAULT_NTF_LED_TYPES 257 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/MFE_POS3_CAN-1.png b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/MFE_POS3_CAN-1.png new file mode 100644 index 00000000000000..d12d1fc728e07c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/MFE_POS3_CAN-1.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/README.md new file mode 100644 index 00000000000000..c3635c32e47d30 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/README.md @@ -0,0 +1,66 @@ + +## MFE_POS3_CAN + +The MFE_POS3_CAN is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com) + +## Features + +• STM32F427VIT6 microcontroller + +• RM3100 compass + +• NEO-M9N + +• one CAN port + +• Blue led + + +## Picture + +![MFE_POS3_CAN](MFE_POS3_CAN-1.png "MFE_POS3_CAN-1") + +## Pinout + + Connector pin assignments +========================= + +CAN1 ports +--------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2CAN_H+12V
3CAN_L+12V
4GNDGND
+ + +Where to Buy +============ + +`makeflyeasy ` + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef-bl.dat new file mode 100644 index 00000000000000..6d5cb6d930cd6f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef-bl.dat @@ -0,0 +1,76 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 32 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# 128k flash part +FLASH_SIZE_KB 2048 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MFE_POS3_CAN + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# debug on USART1 +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# order of UARTs +SERIAL_ORDER + +# blue LED +PC6 LED_BOOTLOADER OUTPUT HIGH +define HAL_LED_ON 1 + +#PA0 LED_RED OUTPUT LOW +#PA2 LED_GREEN OUTPUT LOW +#PA3 LED_SAFETY OUTPUT LOW +#PA4 VDD_3V3_SENSORS_EN OUTPUT LOW + +# USART1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# 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 + +# avoid timer and RCIN threads to save memory +define HAL_NO_TIMER_THREAD + +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# 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 +PA4 MAG_CS CS \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef.dat new file mode 100644 index 00000000000000..e06a0a111c724a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef.dat @@ -0,0 +1,108 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + +#AUTOBUILD_TARGETS None + +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +FLASH_RESERVE_START_KB 36 + +STORAGE_FLASH_PAGE 16 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MFE_POS3_CAN + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +FLASH_SIZE_KB 2048 + + +# order of UARTs +SERIAL_ORDER USART1 USART2 + +# LEDs +PC6 LED OUTPUT LOW +define HAL_GPIO_LED_ON 1 + +# USART2, GPS +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART1, debug, disabled to save flash +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# I2C2 bus +PB11 I2C2_SDA I2C2 +PB10 I2C2_SCL I2C2 + + +# I2C buses +I2C_ORDER I2C2 + +# one SPI bus +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI CS +PA4 MAG_CS CS + +# GPS PPS +PA10 GPS_PPS_IN INPUT + +# SPI devices +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE3 1*MHZ 1*MHZ + +# compass +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE +COMPASS IST8310 I2C:0:0x0C false ROTATION_NONE + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +define HAL_NO_GPIO_IRQ +define HAL_USE_RTC FALSE +define DMA_RESERVE_SIZE 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +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 + +# GPS on 1st 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 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg new file mode 100644 index 00000000000000..d29fe9d108d5bf Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg new file mode 100644 index 00000000000000..7f53e471f74016 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md new file mode 100644 index 00000000000000..0c8b3973808296 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md @@ -0,0 +1,111 @@ +# MFT-SEMA100 Flight Controller + +The MFT-SEMA100 is a flight controller designed and produced by MFT Savunma ve Havacılık LTD. ŞTİ. + +## Features + + - STM32H743 microcontroller + - BMI088 IMU + - BMP390 barometer + - LIB3MDL magnetometer + - MicroSD Card Slot + - 5 UARTs + - 12 PWM outputs + - 2 CANs + - 2 I2Cs + +## Physical + +![MFT-SEMA100_Top_View](MFT-SEMA100_TopView.jpeg) + +![MFT-SEMA100_Bottom_View](MFT-SEMA100_BottomView.jpeg) + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART2 (MAVLink2, DMA-enabled) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART5 (GPS2, DMA-enabled) + - SERIAL5 -> UART7 (DMA-enabled) + - SERIAL6 -> UART8 (RX only) + +## Connectors + +All pins are 2.54 mm Pin Headers + +## Power Connector + +XT30-PW 5V Input for powering the board + +## RC Input + +The default RC input is configured on the UART8 RCIN pin. + + +## PWM Output + +The MFT-SEMA100 supports up to 12 PWM outputs. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2 are Group 1; + +3, 4 are Group 2; + +5, 6, 7, 8 are Group 3; + +9, 10 are Group 4; + +11, 12 are Group 5; + +Channels within the same group need to use the same output rate. + +## GPIOs +The numbering of the GPIOs for PIN variables in ArduPilot is: + +PWM1 50 +PWM2 51 +PWM3 52 +PWM4 53 +PWM5 54 +PWM6 55 +PWM7 56 +PWM8 57 + +PWM9 58 +PWM10 59 +PWM11 60 +PWM12 61 + + +## 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 19 + - BATT_CURR_PIN 8 + - BATT_VOLT_MULT 10 + - BATT_CURR_SCALE 10 + +## Compass + +The MFT-SEMA100 has a built-in compass sensor (LIB3MDL), and you can also attach an external compass using I2C on the SDA and SCL connector. + +## IMU Heater + +The IMU heater in the MFT-SEMA100 can be controlled with the BRD_HEAT_TARG parameter, which is in degrees C. + +## Mechanical + + - Mounting: 55 x 56 mm, Φ4 mm + - Dimensions: 64 x 65 x 10 mm + - Weight: 15g + +## Loading Firmware + +The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm new file mode 100644 index 00000000000000..8fbf2c05bc3e08 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm @@ -0,0 +1,4 @@ +# setup the temperature compensation +BRD_HEAT_TARG 45 +BRD_HEAT_P 50 +BRD_HEAT_I 0.07 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat new file mode 100644 index 00000000000000..3d0ffb248a8acf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat @@ -0,0 +1,51 @@ +# hw definition file for processing by chibios_hwdef.py +# for MFT-SEMA100 board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 2000 + +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 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + + + +PC13 LED_BOOTLOADER OUTPUT HIGH GPIO(0) +PC6 LED_ACTIVITY OUTPUT HIGH GPIO(1) # optional + + +define HAL_LED_ON 1 + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PC4 SDCARD_DETECT INPUT + +# Add CS pins to ensure they are high in bootloader +PE3 BMI088_A_CS CS +PE4 BMI088_G_CS CS +PA15 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat new file mode 100644 index 00000000000000..44b2632da77625 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat @@ -0,0 +1,217 @@ +# hw definition file for processing by chibios_hwdef.py for MFT-SEMA100 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 2000 + +FLASH_SIZE_KB 2048 + +# +env OPTIMIZE -Os + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +USB__STRING_MANUFACTURER "MFT" +USB_STRING_PRODUCT "MFT-SEMA100" + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART5 UART7 UART8 OTG2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS +PH15 USB_HS_ENABLE OUTPUT HIGH +define USB_HW_ENABLE_HS 0 + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - SD CARD +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PA15 SDCARD_CS CS +PC4 SDCARD_DETECT INPUT + +# SPI2 - External +PD3 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + + +# SPI4 - GYRO +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensor +PE3 BMI088_A_CS CS +PE4 BMI088_G_CS CS + + +# I2C buses + + +#I2C1 is External +PB8 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 for onboard mag +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# I2C3 for onboard BAROMETER +PA8 I2C3_SCL I2C3 +PC9 I2C3_SDA I2C3 + +# I2C4 is External +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C2 I2C3 I2C4 I2C1 + + +define HAL_I2C_INTERNAL_MASK 1 + +# drdy pins +PE11 DRDY1_LIS3MDL INPUT + + +# UARTs +#USART1 TX RX 1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 is TX RX 2 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 + +# USART3 is TX RX 3 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# UART5 is TX RX 4 +PD2 UART5_RX UART5 NODMA +PC12 UART5_TX UART5 NODMA + +# UART7 is TX RX 5 +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + + +# SBUS, DSM port +PE0 UART8_RX UART8 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN + + + +# PWM AUX channels +PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50) +PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51) +PC7 TIM8_CH2 TIM8 PWM(3) GPIO(52) +PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) +PA0 TIM5_CH1 TIM5 PWM(5) GPIO(54) +PA1 TIM5_CH2 TIM5 PWM(6) GPIO(55) +PA2 TIM5_CH3 TIM5 PWM(7) GPIO(56) +PA3 TIM5_CH4 TIM5 PWM(8) GPIO(57) + +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) +PA6 TIM3_CH1 TIM3 PWM(11) GPIO(60) +PA7 TIM3_CH2 TIM3 PWM(12) GPIO(61) + + +# allow for 14 PWMs by default + +# PWM output for buzzer +PB15 TIM12_CH2 TIM12 GPIO(77) ALARM + + +# analog in +PA5 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC5 BATT_CURRENT_SENS ADC1 SCALE(1) + + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 19 +define HAL_BATT_VOLT_SCALE 10 + +#define HAL_BATT2_VOLT_PIN 15 +#define HAL_BATT2_VOLT_SCALE 9 + +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_CURR_SCALE 10 + + + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# 2nd CAN bus +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +# control for silent (no output) for CAN +PD4 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PD11 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs + +PD10 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + + +#BARO +BARO BMP388 I2C:1:0x77 + +# SPI devices +SPIDEV bmi088_a SPI4 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI4 DEVID2 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV sdcard SPI1 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ + + +# IMU +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS LIS3MDL I2C:ALL_INTERNAL:0x1C false ROTATION_NONE + + +#LEDs +PC13 LED_BOOTLOADER OUTPUT HIGH GPIO(0) +PC6 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 + +#STORAGE +STORAGE_FLASH_PAGE 14 +define HAL_STORAGE_SIZE 32768 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +DMA_PRIORITY ADC* SPI4* TIM*UP* +DMA_NOSHARE SPI4* TIM*UP* + +define DEFAULT_NTF_LED_TYPES 743 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout1.png b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout1.png new file mode 100644 index 00000000000000..020bb3b6133bdb Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout1.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout2.png b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout2.png new file mode 100644 index 00000000000000..4181a731c50e37 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout2.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout3.png b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout3.png new file mode 100644 index 00000000000000..32090a0f8d997d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout3.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout4.png b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout4.png new file mode 100644 index 00000000000000..5f9a880728e96d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot-pinout4.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot.png b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot.png new file mode 100644 index 00000000000000..ef9a979ad866a9 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/MUPilot.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/README.md new file mode 100644 index 00000000000000..4706844c0884b3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/README.md @@ -0,0 +1,291 @@ +# MUPilot Flight Controller + +The MUPilot flight controller is sold by [MUGIN UAV](http://https://www.muginuav.com/) + +![MUPilot Board](MUPilot.png "MUPilot") + +## Features + + - STM32F765 Microcontroller + - STM32F103 IOMCU + - Three IMUs: ICM20689, MPU6000 and BMI055 + - Internal vibration isolation for IMUs + - Two MS5611 SPI barometers + - IST8310 magnetometer + - MicroSD card slot + - 6 UARTs plus USB + - 14 PWM outputs with selectable 5V or 3.3V output voltage + - Four I2C and two CAN ports + - External Buzzer + - builtin RGB LED + - external safety Switch + - voltage monitoring for servo rail and Vcc + - two dedicated power input ports for external power bricks + +## Mechanical + + - 91mm x 46mm x 31mm + - 106g + +## Connectors + +![MUPilot Pinout1](MUPilot-pinout1.png "Pinout1") +**CAN1/2** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | CAN_H | +3.3V | +| 3 | CAN_L | +3.3V | +| 4 | GND | GND | + +**GPS&SAFETY** + +| Pin | Signal | Volt | +| :--: | :-----------: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX1 | +3.3V | +| 3 | UART_RX1 | +3.3V | +| 4 | I2C1_SCL | +3.3V | +| 5 | I2C1_SDA | +3.3V | +| 6 | SAFETY_SW | +3.3V | +| 7 | SAFETY_SW_LED | +3.3V | +| 8 | 3V3_OUT | +3.3V | +| 9 | BUZZER | +3.3V | +| 10 | GND | GND | + +**I2C1/2/3/4** + +| Pin | Signal | Volt | +| :--: | :------: | :---: | +| 1 | VCC | +5V | +| 2 | I2Cx_SCL | +3.3V | +| 3 | I2Cx _SDA| +3.3V | +| 4 | GND | GND | + +**TELEM1** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX2| +3.3V | +| 3 | UART_RX2| +3.3V | +| 4 | CTS | +3.3V | +| 5 | RTS | +3.3V | +| 6 | GND | GND | + +**TELEM2** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX6| +3.3V | +| 3 | UART_RX6| +3.3V | +| 4 | CTS | +3.3V | +| 5 | RTS | +3.3V | +| 6 | GND | GND | + +**UART4(GPS2)** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 |UART_TX3 | +3.3V | +| 3 |UART_RX3 | +3.3V | +| 4 |I2C2_SCL | +3.3V | +| 5 |I2C2_SDA | +3.3V | +| 6 | GND | GND | + +**DEBUG** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 |UART_TX7| +3.3V | +| 3 |UART_RX7| +3.3V | +| 4 | SWDIO | +3.3V | +| 5 | SWCLK | +3.3V | +| 6 | GND | GND | + +![MUPilot Pinout2](MUPilot-pinout2.png "Pinout2") + +**POWER1** + +| Pin | Signal | Volt | +| :--: | :-------------: | :---: | +| 1 | VCC_IN | +5V | +| 2 | VCC_IN | +5V | +| 3 | CURRENT_ADC | +3.3V | +| 4 | VOLTAGE_ADC | +3.3V | +| 5 | GND | GND | +| 6 | GND | GND | + +**POWER2** + +| Pin | Signal | Volt | +| :--: | :----------------: | :---: | +| 1 | VCC_IN | +5V | +| 2 | VCC_IN | +5V | +| 3 |CURRENT_ADC/I2C1_SCL| +3.3V | +| 4 |VOLTAGE_ADC/I2C1_SDA| +3.3V | +| 5 | GND | GND | +| 6 | GND | GND | + +![MUPilot Pinout3](MUPilot-pinout3.png "Pinout3") + +**SBUS OUT** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | - | - | +| 2 |SBUS OUT| +3.3V | +| 3 | GND | GND | + +![MUPilot Pinout4](MUPilot-pinout4.png "Pinout4") + +**ADC** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | ADC_3V3 | +3.3V | +| 3 | ADC_6V6 | +6.6V | +| 4 | GND | GND | + +**SPI5** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | SCK | +3.3V | +| 3 | MISO | +3.3V | +| 5 | MOSI | +3.3V | +| 6 | CS1 | +3.3V | +| 7 | CS2 | +3.3V | +| 8 | GND | GND | + +**DSM/SBUS/RSSI** + +| Pin | Signal | Volt | +| :--: | :---------: | :---: | +| 1 | VCC | +5V | +| 2 | DSM/SBUS | +3.3V | +| 3 | RSSI | +3.3V | +| 4 | 3V3_OUT | +3.3V | +| 5 | GND | GND | + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART2 (Telem1) + - SERIAL2 -> UART3 (Telem2) + - SERIAL3 -> UART1 (GPS) + - SERIAL4 -> UART4 (GPS2) + - SERIAL5 -> UART6 (spare) + - SERIAL6 -> UART7 (spare, debug) + - SERIAL7 -> USB2 (SLCAN) + +The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not +have RTS/CTS. + +The UART7 connector is labelled debug, but is available as a general +purpose UART with ArduPilot. + +## RC Input + +RC input is configured on the PPM pin, at one end of the servo rail, +marked RC in the above diagram. This pin supports all unidirectional RC protocols including PPM. The DSM/SBUS pin is also tied to the PPM pin.For CRSF/ELRS/etc. protocols +a full UART will need to be used with its SERIALx_PROTOCOL set to "23". + +## PWM Output + +The MUPilot supports up to 14 PWM outputs. First first 8 outputs (labelled +"M1 to M8") are controlled by a dedicated STM32F103 IO controller. These 8 +outputs support all PWM output formats, but not DShot. + +The remaining 6 outputs (labelled A1 to A6) are the "auxiliary" +outputs. These are directly attached to the STM32F765 and support all +PWM protocols as well as DShot. + +All 14 PWM outputs have GND on the top row, 5V on the middle row and +signal on the bottom row. + +The 8 main PWM outputs are in 3 groups: + + - PWM 1 and 2 in group1 + - PWM 3 and 4 in group2 + - PWM 5, 6, 7 and 8 in group3 + +The 6 auxiliary PWM outputs are in 2 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5 and 6 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. + +The output levels of the auxiliary outputs can be selected by switch to be either 3.3V or 5V. The output level is 3.3V for the main outputs. + +## Battery Monitoring + +The board has two dedicated power monitor ports on 6 pin +connectors. The correct battery setting parameters are dependent on +the type of power brick which is connected. The first is analog only, the second may be either analog or I2C, depending on baseboard jumpers. +In order to enable monitoring, the BATT_MONITOR or BATT2_MONIOT parameter must be set. By default :ref:`BATT_MONITOR` is set to "4" for the included power module.. + +Default params for the first monitor are set and are: + +- BATT_VOLT_PIN = 2 +- BATT_CURR_PIN = 1 +- BATT_VOLT_MULT = 18.0 +- BATT_AMP_PERVLT = 24.0 (may need adjustment if supplied monitor is not used) + +## Compass + +The MUPilot has a builtin IST8310 compass. Due to potential +interference the board is usually used with an external I2C compass as +part of a GPS/Compass combination. + +## GPIOs + +The 6 auxiliary outputs can be used as GPIOs (relays, buttons, RPM etc). To +use them see https://ardupilot.org/rover/docs/common-gpios.html + +The numbering of the GPIOs for PIN variables in ArduPilot is: + + - MAIN1 101 + - MAIN2 102 + - MAIN3 103 + - MAIN4 104 + - MAIN5 105 + - MAIN6 106 + - MAIN7 107 + - MAIN8 108 + - AUX1 50 + - AUX2 51 + - AUX3 52 + - AUX4 53 + - AUX5 54 + - AUX6 55 + +## Analog inputs + +The MUPilot has 7 analog inputs + + - ADC Pin0 -> Battery Voltage + - ADC Pin1 -> Battery Current Sensor + - ADC Pin2 -> Battery Voltage 2 + - ADC Pin3 -> Battery Current Sensor 2 + - ADC Pin4 -> ADC port pin 2 + - ADC Pin14 -> ADC port pin 3 + - ADC Pin10 -> Board 5V Sense + - ADC Pin11 -> Board 3.3V Sense + - ADC Pin103 -> RSSI voltage monitoring + +## Loading Firmware + +The board comes pre-installed with an ArduPilot compatible bootloader, +allowing the loading of \*.apj firmware files with any ArduPilot +compatible ground station. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef-bl.dat new file mode 100644 index 00000000000000..400e9a0929942e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef-bl.dat @@ -0,0 +1,7 @@ +# hw definition file for processing by chibios_hwdef.py +# for MUPilot bootloader + +include ../fmuv5/hwdef-bl.dat + +undef APJ_BOARD_ID +APJ_BOARD_ID AP_HW_MUPilot diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef.dat new file mode 100644 index 00000000000000..bdcfd8454d54a6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MUPilot/hwdef.dat @@ -0,0 +1,57 @@ +# hw definition file for processing by chibios_hwdef.py +# for MUPilot hardware. + +include ../fmuv5/hwdef.dat + +undef APJ_BOARD_ID +APJ_BOARD_ID AP_HW_MUPilot + +# extra LEDs, active low, used using the pixracer LED scheme +PH10 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PH11 LED_G1 OUTPUT OPENDRAIN HIGH GPIO(1) +PH12 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +undef AP_NOTIFY_GPIO_LED_RGB_RED_PIN +undef AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 + +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +define HAL_BATT_MONITOR_DEFAULT 4 + +#heaters +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 + +undef PI6 +PI6 MS5611_BOARD_CS CS + +#SPI6 for extra BARO +PG13 SPI6_SCK SPI6 +PG12 SPI6_MISO SPI6 +PB5 SPI6_MOSI SPI6 + +SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ + +undef BARO +BARO MS56XX SPI:ms5611 +BARO MS56XX SPI:ms5611_board + + +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/MambaF405-2022/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm index 2244d788d4fc8e..ed3aebd9061db6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm @@ -1,7 +1,7 @@ # setup for LEDs on chan9 SERVO7_FUNCTION 120 # Default VTX power to on -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 # UART1 is RX input SERIAL1_PROTOCOL 23 # UART2 is GPS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat index 20b64689a4dda5..d4a9e9c20885b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat @@ -72,6 +72,7 @@ PC9 TIM3_CH4 TIM3 PWM(3) GPIO(52) PC8 TIM3_CH3 TIM3 PWM(4) GPIO(53) # Board LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PC15 LED1 OUTPUT LOW GPIO(1) PC14 LED2 OUTPUT LOW GPIO(2) define HAL_GPIO_A_LED_PIN 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat index 41ef077b8ac8b0..23225a97959ff0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat @@ -77,6 +77,7 @@ PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # Board LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PB5 LED_BLUE OUTPUT LOW GPIO(1) PB4 LED_GREEN OUTPUT LOW GPIO(2) define HAL_GPIO_A_LED_PIN 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm index 48efb2e98b8088..43c6d08d36b3de 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm @@ -1,5 +1,5 @@ # setup for LEDs on chan9 SERVO9_FUNCTION 120 # Default VTX power to on -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat index 201ffc4df0b927..8c1217136ffc8b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat @@ -33,8 +33,7 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat index 942924ad471a72..661909c0d70914 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat @@ -92,6 +92,7 @@ define HAL_BATT_CURR_SCALE 64 PC2 RSSI_ADC ADC1 define BOARD_RSSI_ANA_PIN 12 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PE5 LED0 OUTPUT LOW GPIO(90) # blue PE4 LED1 OUTPUT LOW GPIO(91) # orange define HAL_GPIO_A_LED_PIN 91 @@ -101,17 +102,18 @@ define HAL_GPIO_B_LED_PIN 90 PA9 USART1_TX USART1 PA10 USART1_RX USART1 -# USART2 -PD5 USART2_TX USART2 NODMA -PD6 USART2_RX USART2 NODMA +# USART2 (GPS) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS # USART3 (VTX) PD8 USART3_TX USART3 NODMA PD9 USART3_RX USART3 NODMA -# UART4 (GPS) -PD1 UART4_TX UART4 -PD0 UART4_RX UART4 +# UART4 (WiFi) +PD1 UART4_TX UART4 NODMA +PD0 UART4_RX UART4 NODMA # UART5 (SPORT) PC12 UART5_TX UART5 NODMA @@ -180,7 +182,7 @@ 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 +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX # DPS280 or SPL06 integrated on I2C bus BARO DPS280 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat index 84f6ebb815ab7a..661d3ab0c56b97 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat @@ -22,6 +22,7 @@ OSCILLATOR_HZ 8000000 # --------------------- LED ----------------------- +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA14 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT PA13 LED1 OUTPUT LOW GPIO(91) # green marked as B/E define HAL_GPIO_A_LED_PIN 91 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat index c9033143bdfd15..002fad46fd90f8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat @@ -22,6 +22,7 @@ OSCILLATOR_HZ 8000000 # --------------------- LED ----------------------- +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA14 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT PA13 LED1 OUTPUT LOW GPIO(91) # green marked as B/E define HAL_GPIO_A_LED_PIN 91 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat index 0af6d1efb76a1e..806c7494cdee0d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat @@ -72,6 +72,7 @@ PA10 USART1_RX USART1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA14 LED_BLUE OUTPUT LOW GPIO(0) PA13 LED_GREEN OUTPUT LOW GPIO(1) # optional diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat index ead1a2743f7da2..84a91d2324822e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat @@ -25,6 +25,7 @@ I2C_ORDER I2C1 SERIAL_ORDER OTG1 USART3 UART4 USART1 UART5 USART2 # LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PB9 LED_BLUE OUTPUT LOW GPIO(0) PA14 LED_GREEN OUTPUT LOW GPIO(1) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat index e00a9e36089676..1999f718adb378 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat @@ -90,6 +90,7 @@ define HAL_BATT2_CURR_PIN 15 PC1 RSSI_ADC ADC1 define BOARD_RSSI_ANA_PIN 11 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PD10 LED0 OUTPUT LOW GPIO(90) # blue PD11 LED1 OUTPUT LOW GPIO(91) # green define HAL_GPIO_A_LED_PIN 91 @@ -131,10 +132,10 @@ PE10 UART7_CTS UART7 PE9 UART7_RTS UART7 # telem1-UART7 RTS and CTS as GPIO in alternative configs -PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(2) # Cts7 pin as GPIO 1 (set RELAY_PINx = 1 to use it) -PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(2) # Rts7 pin as GPIO 2 (set RELAY_PINx = 2 to use it) -PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(3) # Cts7 pin as GPIO 1 (set RELAY_PINx = 1 to use it) -PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(3) # Rts7 pin as GPIO 2 (set RELAY_PINx = 2 to use it) +PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(2) # Cts7 pin as GPIO 1 (set RELAYx_PIN = 1 to use it) +PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(2) # Rts7 pin as GPIO 2 (set RELAYx_PIN = 2 to use it) +PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(3) # Cts7 pin as GPIO 1 (set RELAYx_PIN = 1 to use it) +PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(3) # Rts7 pin as GPIO 2 (set RELAYx_PIN = 2 to use it) # alternative configs: # 1: bidirectional receiver protocol on RX6 pin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm new file mode 100644 index 00000000000000..fdd32a445cc13b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm @@ -0,0 +1,22 @@ +# up to 11 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 +OUT10_FUNCTION 56 +OUT11_FUNCTION 57 + +# DShot 600 +ESC_PWM_TYPE 7 +OUT_BLH_OTYPE 6 + +OUT_BLH_MASK 15 + +# DShot telem on RX3 +ESC_TELEM_PORT 3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat new file mode 100644 index 00000000000000..ec9c59fa8b0faa --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekG474/hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat new file mode 100644 index 00000000000000..006e5872cfc553 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat @@ -0,0 +1,22 @@ +include ../MatekG474/hwdef.inc + +# --------------------- PWM ----------------------- +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) +PA6 TIM3_CH1 TIM3 PWM(5) GPIO(54) +PA7 TIM3_CH2 TIM3 PWM(6) GPIO(55) +PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) +PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) +PC6 TIM8_CH1 TIM8 PWM(9) GPIO(58) +PB9 TIM8_CH3 TIM8 PWM(10) GPIO(59) +PB2 TIM5_CH1 TIM5 PWM(11) GPIO(60) + +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/MatekG474-Periph/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm new file mode 100644 index 00000000000000..170696ab766295 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm @@ -0,0 +1,24 @@ +# ----setup for PORT defaults +#| EMPTY | USART1 | USART2 | USART3 | UART4 | +GPS_PORT 2 +MSP_PORT 3 +RNGFND_PORT 4 +ADSB_PORT -1 +RC_PORT 1 +EFI_PORT -1 +PRX_PORT -1 +ESC_TELEM_PORT -1 + +# ----I2C AirSpeed sensor, disabled by default +ARSPD_BUS 0 # I2C1 +ARSPD_TYPE 0 + +# ----I2C External Baro +BARO_EXT_BUS -1 +BARO_PROBE_EXT 4095 + +# ----I2C BATT_MONITOR INA2xx +BATT_I2C_BUS 0 +BATT_I2C_ADDR 0 +BATT_SHUNT 0.0002 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat new file mode 100644 index 00000000000000..ec9c59fa8b0faa --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekG474/hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat new file mode 100644 index 00000000000000..c0ca5bcfaeb38f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat @@ -0,0 +1,68 @@ +include ../MatekG474/hwdef.inc + +# ----------- GPS +define HAL_PERIPH_ENABLE_GPS +define GPS_MAX_RATE_MS 200 + +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 + +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 + + +# ----------- COMPASS +define HAL_PERIPH_ENABLE_MAG + +SPIDEV rm3100 SPI2 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 + +define HAL_COMPASS_MAX_SENSORS 1 + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + + +# ----------- I2C airspeed +define HAL_PERIPH_ENABLE_AIRSPEED +define AIRSPEED_MAX_SENSORS 1 + + +# ----------- I2C Barometer +define HAL_PERIPH_ENABLE_BARO +define HAL_BARO_ALLOW_INIT_NO_BARO + +# BARO SPL06 I2C:0:0x76 + +# ----------- I2C BATT_MONITOR INA2xx + +define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA2XX_ENABLED 1 +define HAL_BATT_MONITOR_DEFAULT 21 + + +# ----------- MSP +define HAL_PERIPH_ENABLE_MSP +define HAL_MSP_ENABLED 1 + + +# ----------- ADSB +define HAL_PERIPH_ENABLE_ADSB + + +# ----------- RC INPUT +define HAL_PERIPH_ENABLE_RCIN 1 + + +# ----------- EFI +define HAL_PERIPH_ENABLE_EFI +define HAL_EFI_ENABLED 1 + + +# ----------- proximity +define HAL_PERIPH_ENABLE_PROXIMITY +define HAL_PROXIMITY_ENABLED 1 + + +# ----------- rangefinder +define HAL_PERIPH_ENABLE_RANGEFINDER + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc new file mode 100644 index 00000000000000..77affead7761c4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc @@ -0,0 +1,57 @@ +# hw definition file Matek G474 CAN node + +# MCU class and specific type +MCU STM32G474 STM32G474xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MatekG474 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 32 +FLASH_SIZE_KB 512 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# --------------------------------------------- +PC13 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 + +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + + +# --------------------------------------------- + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 2500 + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define DMA_RESERVE_SIZE 0 +define HAL_DISABLE_LOOP_DELAY +define HAL_NO_TIMER_THREAD +define HAL_NO_RCIN_THREAD + +define HAL_USE_SERIAL FALSE + +# Add CS pins to ensure they are high in bootloader +PB12 MAG_CS CS +PC14 SPARE_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc new file mode 100644 index 00000000000000..edf92aa3449198 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc @@ -0,0 +1,115 @@ +# hw definition file for Matek G474 CAN node + +# MCU class and specific type +MCU STM32G474 STM32G474xx + +# bootloader starts firmware at 32k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 36 +FLASH_SIZE_KB 512 + +# store parameters in pages +STORAGE_FLASH_PAGE 16 +define HAL_STORAGE_SIZE 1800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MatekG474 + +# crystal frequency +OSCILLATOR_HZ 8000000 + + +env AP_PERIPH 1 + +define SERIAL_BUFFERS_SIZE 512 +# stack for fast interrupts +define PORT_INT_REQUIRED_STACK 64 + +define HAL_NO_GPIO_IRQ +define HAL_NO_MONITOR_THREAD +define HAL_USE_RTC FALSE +define HAL_DISABLE_LOOP_DELAY +define HAL_NO_GCS +define HAL_NO_LOGGING + + +define DMA_RESERVE_SIZE 2048 + +# don't share any DMA channels (there are enough for everyone) +DMA_NOSHARE * + + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# allow for reboot command for faster development +# define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + + +# blue LED0 marked as ACT +PC13 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# --------------------- SPI1 RM3100 ----------------------- +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 MAG_CS CS +PC14 SPARE_CS CS + +# ---------------------- I2C bus ------------------------ +I2C_ORDER I2C1 I2C2 + +# SWD debugging, disabled for I2C1 +# PA13 JTMS-SWDIO SWD +# PA14 JTCK-SWCLK SWD + +PA13 I2C1_SCL I2C1 +PA14 I2C1_SDA I2C1 + +PC4 I2C2_SCL I2C2 +PA8 I2C2_SDA I2C2 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 0 + +define HAL_USE_I2C TRUE + +# ---------------------- CAN bus ------------------------- +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +define HAL_CAN_POOL_SIZE 6000 + +# ---------------------- UARTs --------------------------- +# make the UARTn numbers in parameters match the silkscreen +# | sr0 | sr1 | sr2 | sr3 | sr4 | +SERIAL_ORDER EMPTY USART1 USART2 USART3 UART4 + +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH + +PB3 USART2_TX USART2 SPEED_HIGH +PB4 USART2_RX USART2 SPEED_HIGH + +PB10 USART3_TX USART3 SPEED_HIGH NODMA +PB11 USART3_RX USART3 SPEED_HIGH NODMA + +PC10 UART4_TX UART4 SPEED_HIGH +PC11 UART4_RX UART4 SPEED_HIGH + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# ----------- ADC +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat index c37b823031f090..2fcb8425692ff4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat @@ -40,7 +40,6 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3 # default ADSB off by setting 0 baudrate define HAL_PERIPH_ADSB_BAUD_DEFAULT 0 -define HAL_NO_MONITOR_THREAD define HAL_USE_RTC FALSE define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat index aa0776d7f5a75e..c26a193d149efb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat @@ -93,6 +93,7 @@ define BOARD_RSSI_ANA_PIN 8 # LED # green LED1 marked as B/E # blue LED0 marked as ACT +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PE3 LED0 OUTPUT LOW GPIO(90) # blue PE4 LED1 OUTPUT LOW GPIO(91) # green define HAL_GPIO_A_LED_PIN 91 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat index 5318c5d3eaebcb..12838b5618d908 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat @@ -8,7 +8,7 @@ MCU STM32H7xx STM32H7A3xx APJ_BOARD_ID AP_HW_MatekH7A3 # crystal frequency, setup to use external oscillator -OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 16000000 FLASH_SIZE_KB 2048 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat index e5544cbddef1bb..cb578f84b2aecc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat @@ -8,7 +8,7 @@ MCU STM32H7xx STM32H7A3xx APJ_BOARD_ID AP_HW_MatekH7A3 # crystal frequency, setup to use external oscillator -OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 16000000 FLASH_SIZE_KB 2048 env OPTIMIZE -Os @@ -76,6 +76,7 @@ define HAL_BATT2_VOLT_SCALE 21.0 # LED # green LED1 marked as B/E # blue LED0 marked as ACT +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA14 LED0 OUTPUT LOW GPIO(90) # blue PA13 LED1 OUTPUT LOW GPIO(91) # green define HAL_GPIO_A_LED_PIN 91 @@ -159,7 +160,7 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ define HAL_LOGGING_DATAFLASH_ENABLED 1 define HAL_OS_FATFS_IO 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX # ----------------- I2C compass & Baro ----------------- diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm new file mode 100644 index 00000000000000..3c63f226fb8af1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm @@ -0,0 +1,3 @@ +OUT1_FUNCTION 33 +OUT1_MIN 1000 +OUT1_MAX 2000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat new file mode 100644 index 00000000000000..b9005f84941a6a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../MatekL431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat new file mode 100644 index 00000000000000..06a9bcde6067a2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat @@ -0,0 +1,17 @@ +include ../MatekL431/hwdef.inc + +define HAL_USE_ADC FALSE + +# --------------------- 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) + +define HAL_PERIPH_ENABLE_RC_OUT + +# enable APD telemetry on rx1 +define HAL_PERIPH_ENABLE_ESC_APD +define APD_ESC_INSTANCES 1 +define APD_ESC_SERIAL_0 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat index 4a2612749ae486..cf3ace13ad2b48 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat @@ -13,7 +13,6 @@ SPIDEV INA23X SPI1 DEVID1 SPARE_CS MODE1 10*MHZ 10*MHZ define HAL_USE_ADC FALSE # disable unnecessary threads -define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat index 5c27d1c9e6756e..d74ef0f7cb173c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat @@ -32,3 +32,7 @@ define HAL_PERIPH_ENABLE_NOTIFY define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 + +# also enable relay output via hardpoint msgs +define HAL_PERIPH_ENABLE_RELAY +define AP_RELAY_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat index 45a49c8d71d6b0..3a46d72a0b7b88 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat @@ -37,7 +37,6 @@ PB11 USART3_RX USART3 SPEED_HIGH define HAL_USE_ADC FALSE # disable unnecessary threads -define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD undef HAL_RCIN_THREAD_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat index ded7e7d7a51db9..b576cfdb530a0c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat @@ -23,6 +23,10 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 2 # allow for F9P GPS modules with moving baseline define GPS_MOVING_BASELINE 1 +# restrict backends available to save flash (i.e. only UBLOX) +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_SBF_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 # ---------------------- COMPASS --------------------------- define HAL_PERIPH_ENABLE_MAG diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat index 0a2ddad9591362..99e189f4b3b39c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat @@ -6,6 +6,7 @@ define HAL_DISABLE_ADC_DRIVER TRUE # support all rangefinder types define HAL_PERIPH_ENABLE_RANGEFINDER +define RANGEFINDER_MAX_INSTANCES 2 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc index c172fe5ac57cbc..8c13942329c7de 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc @@ -38,8 +38,6 @@ MAIN_STACK 0x300 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0xA00 -define HAL_NO_MONITOR_THREAD - # we setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_BackView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_BackView.jpg new file mode 100644 index 00000000000000..e50a46c652a40b Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_BackView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_FrontView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_FrontView.jpg new file mode 100644 index 00000000000000..c6db37b04336a9 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_FrontView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_Pinout.xlsx b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_Pinout.xlsx new file mode 100644 index 00000000000000..9e5833b60a3d7e Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_Pinout.xlsx differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_PortsConnection.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_PortsConnection.jpg new file mode 100644 index 00000000000000..281d3b1e5c9a88 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/MicoAir405Mini_PortsConnection.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/README.md new file mode 100644 index 00000000000000..1bb91c3ecd8fb1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/README.md @@ -0,0 +1,95 @@ +# MicoAir405Mini Flight Controller + +The MicoAir405Mini is a flight controller designed and produced by [MicoAir Tech.](http://micoair.com/). + +## Features + + - STM32F405 microcontroller + - BMI270 IMU + - DPS310 barometer + - AT7456E OSD + - 9V 2.5A BEC; 5V 2.5A BEC + - SDCard + - 6 UARTs + - 9 PWM outputs + +## Physical + +![MicoAir F405 Mini V2.1 Front View](MicoAir405Mini_FrontView.jpg) + +![MicoAir F405 Mini V2.1 Back View](MicoAir405Mini_BackView.jpg) + + + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART2 (DisplayPort, TX only is DMA Enabled) + - SERIAL3 -> UART3 (GPS) + - SERIAL4 -> UART4 (MAVLink2, TX only is DMA Enabled) + - SERIAL5 -> UART5 (ESC Telemetry) + - SERIAL6 -> UART6 (RX6 is inverted from SBUS pin, RX only is DMA Enabled) + +## RC Input + +The default RC input is configured as SBUS via the SBUS pin. Other RC protocols should be applied at a UART port such as UART1 or UART4, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL6 _Protocol to something other than '23' + +## OSD Support + +The MicoAir405Mini supports onboard OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The SH1.0-6P connector supports a DJI O3 Air Unit connection. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The MicoAir405Mini supports up to 9 PWM outputs. + +Channels 1-8 support DShot. + +Channels 1-4 support bi-directional DShot. + +PWM outputs are grouped and every group must use the same output protocol: + +3, 4 are Group 1; + +1, 2, 5, 6 are Group 2; + +7, 8 are Group 3; + +9 is in Group 4; + +## 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 21.2 + - BATT_CURR_SCALE 40.2 + +## Compass + +The MicoAir405Mini does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL connector. + +## Mechanical + + - Mounting: 20 x 20mm, Φ3.5mm + - Dimensions: 30 x 30 x 8 mm + - Weight: 6g + +## Ports Connector + +![MicoAir F405 Mini V2.1 Ports Connection](MicoAir405Mini_PortsConnection.jpg) + +## 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 favorite 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/MicoAir405Mini/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/defaults.parm new file mode 100644 index 00000000000000..2f7a0adf212a5d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/defaults.parm @@ -0,0 +1,15 @@ +#BATTERY MONITOR ON +BATT_MONITOR 4 + +#enable second OSD type +OSD_TYPE2 = 5 + +#Serial Port defaults +SERIAL1_PROTOCOL 2 +SERIAL2_PROTOCOL 42 +SERIAL3_PROTOCOL 5 +SERIAL4_PROTOCOL 2 +SERIAL5_PROTOCOL 16 +SERIAL6_PROTOCOL 23 +LOG_FILE_BUFSIZE 8 +GPS_DRV_OPTIONS 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef-bl.dat new file mode 100644 index 00000000000000..efd6b50a50f0a1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef-bl.dat @@ -0,0 +1,36 @@ +# hw definition file for processing by chibios_pins.py +# for the MicoAir405Mini hardware + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir405Mini + +# crystal frequency & PPL, working at 168M +OSCILLATOR_HZ 8000000 +STM32_PLLM_VALUE 8 + +# chip flash size & bootloader & firmware +FLASH_SIZE_KB 1024 +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 48 + +# LEDs +PA8 LED_BOOTLOADER OUTPUT LOW #blue +PC4 LED_ACTIVITY OUTPUT LOW #green +define HAL_LED_ON 0 + +# order of UARTs and USB +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + + + +#CS pin +PB12 AT7456E_CS CS +PC14 BMI270_CS CS +PC13 DPS310_CS CS +PC9 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat new file mode 100644 index 00000000000000..3a2b63426c714c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat @@ -0,0 +1,150 @@ +# hw definition file for MicoAir405Mini hardware + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir405Mini + +# crystal frequency +OSCILLATOR_HZ 8000000 +STM32_PLLM_VALUE 8 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 16 + +# chip flash size & bootloader & firmware +FLASH_SIZE_KB 1024 +FLASH_RESERVE_START_KB 48 + +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# board voltage +STM32_VDD 330U + +# LEDs +PC5 LED_RED OUTPUT LOW GPIO(0) +PC4 LED_GREEN OUTPUT LOW GPIO(1) +PA8 LED_BLUE OUTPUT LOW GPIO(2) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 + +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# only one I2C bus +I2C_ORDER I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# spi1 bus for OSD +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# spi2 bus for IMU +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# spi3 bus for SDCARD +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +#CS pin +PB12 AT7456E_CS CS +PC14 BMI270_CS CS +PC13 DPS310_CS CS +PC9 SDCARD_CS CS + +# analog pins +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 21.2 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 40.2 + +# order of UARTs (and USB) +# SERIAL_NUM|SER0|SER1 |SER2 |SER3 |SER4 |SER5 |SER6 | +# FUNCTION |USB | |DJIO3 |GPS | |ESC |SBUS | +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 - DJIO3 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 NODMA + +# USART3 - GPS +PB10 USART3_TX USART3 NODMA +PB11 USART3_RX USART3 NODMA + +# UART4 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA + +# UART5 +PD2 UART5_RX UART5 NODMA + +# UART6 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 NODMA +PC15 SBUS_INV OUTPUT + +# 9 PWM available by default +define BOARD_PWM_COUNT_DEFAULT 9 + +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR +PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR +PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53) +PB4 TIM3_CH1 TIM3 PWM(5) GPIO(54) +PB5 TIM3_CH2 TIM3 PWM(6) GPIO(55) +PB8 TIM4_CH3 TIM4 PWM(7) GPIO(56) +PB9 TIM4_CH4 TIM4 PWM(8) GPIO(57) +PB14 TIM12_CH1 TIM12 PWM(9) GPIO(58) NODMA + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +# imu & baro +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 +BARO DPS310 SPI:dps310 + +# SPI devices +SPIDEV bmi270 SPI2 DEVID1 BMI270_CS MODE3 2*MHZ 10*MHZ +SPIDEV dps310 SPI2 DEVID2 DPS310_CS MODE3 5*MHZ 5*MHZ +SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ +SPIDEV osd SPI1 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + +# reduce flash usage +include ../include/minimize_fpv_osd.inc +undef AP_OPTICALFLOW_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/defaults.parm index 9f3a294361d526..2f7a0adf212a5d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/defaults.parm @@ -1,6 +1,9 @@ #BATTERY MONITOR ON BATT_MONITOR 4 +#enable second OSD type +OSD_TYPE2 = 5 + #Serial Port defaults SERIAL1_PROTOCOL 2 SERIAL2_PROTOCOL 42 @@ -8,4 +11,5 @@ SERIAL3_PROTOCOL 5 SERIAL4_PROTOCOL 2 SERIAL5_PROTOCOL 16 SERIAL6_PROTOCOL 23 +LOG_FILE_BUFSIZE 8 GPS_DRV_OPTIONS 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef-bl.dat index b205eae0797555..2422b9469911ff 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef-bl.dat @@ -31,8 +31,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + #CS pin PB12 AT7456E_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat index 7ee7100f644687..89f02950e55924 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat @@ -28,11 +28,11 @@ PA8 LED_BLUE OUTPUT LOW GPIO(0) PC4 LED_GREEN OUTPUT LOW GPIO(1) PC5 LED_RED OUTPUT LOW GPIO(2) -define HAL_GPIO_A_LED_PIN 2 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 0 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # only one I2C bus I2C_ORDER I2C1 @@ -143,26 +143,15 @@ SPIDEV sdcard SPI3 DEVID5 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/font0.bin +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + # reduce flash usage -define HAL_MOUNT_ENABLED 0 -define HAL_SPRAYER_ENABLED 0 -define HAL_GENERATOR_ENABLED 0 -define HAL_VISUALODOM_ENABLED 0 -define AP_WINCH_ENABLED 0 -define AP_BEACON_ENABLED 0 -define AP_GRIPPER_ENABLED 0 -define AP_ICENGINE_ENABLED 0 -define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 0 -define OFFBOARD_GUIDED 0 -define QAUTOTUNE_ENABLED 0 -define EK3_FEATURE_EXTERNAL_NAV 0 -define AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED 0 -define AC_PAYLOAD_PLACE_ENABLED 0 +include ../include/minimize_fpv_osd.inc +undef AP_OPTICALFLOW_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg new file mode 100644 index 00000000000000..45a264ab50d757 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg new file mode 100644 index 00000000000000..761acf766a5381 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx new file mode 100644 index 00000000000000..2025f82d678d0c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg new file mode 100644 index 00000000000000..9af8d732cd3555 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md new file mode 100644 index 00000000000000..2c77dec73cc0d9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md @@ -0,0 +1,98 @@ +# MicoAir743 Flight Controller + +The MicoAir743 is a flight controller designed and produced by [MicoAir Tech.](http://micoair.com/). + +## Features + + - STM32H743 microcontroller + - BMI088/BMI270 dual IMUs + - DPS310 barometer + - IST8310 magnetometer + - AT7456E OSD + - 9V 3A BEC; 5V 3A BEC + - MicroSD Card Slot + - 7 UARTs + - 10 PWM outputs + - 1 CAN + - 1 I2C + - 1 SWD + +## Physical + +![MicoAir H743 V1.3 Front View](MicoAir743_FrontView.jpg) + +![MicoAir H743 V1.3 Back View](MicoAir743_BackView.jpg) + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART2 (DisplayPort, DMA-enabled) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART4 (MAVLink2, DMA-enabled) + - SERIAL5 -> UART6 (RCIN, DMA-enabled) + - SERIAL6 -> UART7 (RX only, ESC Telemetry, DMA-enabled) + - SERIAL7 -> UART8 (User, DMA-enabled) + + +## RC Input + +The default RC input is configured on the UART6. The SBUS pin is inverted and connected to RX6. Non SBUS, single wire serial inputs can be directly tied to RX6 if SBUS pin is left unconnected. RC could be applied instead at a different UART port such as UART1, UART4 or UART8, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL5 _Protocol to something other than '23'. + +## OSD Support + +The MicoAir743 supports onboard OSD using OSD_TYPE 1 (MAX7456 driver). Simultaneously, DisplayPort OSD is available on the HD VTX connector, See below. + + +## VTX Support + +The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The MicoAir743 supports up to 10 PWM outputs. + +All the channels support DShot. + +Channels 1-8 support bi-directional DShot. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2, 3, 4 are Group 1; + +5, 6 are Group 2; + +7, 8, 9, 10 are Group 3; + +## 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 21.2 + - BATT_CURR_SCALE 40.2 + +## Compass + +The MicoAir743 has a built-in compass sensor (IST8310), and you can also attach an external compass using I2C on the SDA and SCL connector. + +## Mechanical + + - Mounting: 30.5 x 30.5mm, Φ4mm + - Dimensions: 36 x 36 x 8 mm + - Weight: 9g + +## Ports Connector + +![MicoAir H743 V1.3 Ports Connection](MicoAir743_PortsConnection.jpg) + +## 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 favorite 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/MicoAir743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/defaults.parm new file mode 100644 index 00000000000000..99da6e37676521 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/defaults.parm @@ -0,0 +1,11 @@ +#BATTERY MONITOR ON +BATT_MONITOR 4 + +#enable second OSD type +OSD_TYPE2 = 5 + +#Serial Port defaults +SERIAL2_PROTOCOL 42 +SERIAL4_PROTOCOL 2 +SERIAL5_PROTOCOL 23 +SERIAL6_PROTOCOL 16 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat new file mode 100644 index 00000000000000..c111bbb75abc0b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat @@ -0,0 +1,48 @@ +# hw definition file for processing by chibios_hwdef.py +# for the MicoAir743 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir743 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# flash size +FLASH_SIZE_KB 2048 + +# 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 + + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PB12 AT7456E_CS CS +PA15 BMI270_CS CS +PD5 GYRO_CS CS +PD4 ACCEL_CS CS + +# LEDs +PE6 LED_ACTIVITY OUTPUT LOW #green +PE4 LED_BOOTLOADER OUTPUT LOW #blue +define HAL_LED_ON 0 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat new file mode 100644 index 00000000000000..538baec0ef8600 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat @@ -0,0 +1,168 @@ +# hw definition file for processing by chibios_hwdef.py +# for the MicoAir743 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir743 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# flash size +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 UART8 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - TELEM1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 - DJIO3 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# USART3 - GPS +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# UART4 - TELEM2 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +# UART6 - RC_INPUT +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +PD0 SBUS_INV OUTPUT LOW + +# UART7 - ESC +PE7 UART7_RX UART7 + +# UART8 - TELEM3 +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 + +# SWD +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CAN +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +# two I2C bus +I2C_ORDER I2C2 I2C1 + +# I2C1 - CONNECTOR +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 - BARO & MAG +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# PWM output pins +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) BIDIR +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PB1 TIM3_CH4 TIM3 PWM(5) GPIO(54) BIDIR +PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) + +# 10 PWM available by default +define BOARD_PWM_COUNT_DEFAULT 10 + +# LEDs +PE5 LED_RED OUTPUT LOW GPIO(0) +PE6 LED_GREEN OUTPUT LOW GPIO(1) +PE4 LED_BLUE OUTPUT LOW GPIO(2) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 + +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# ADC for Power +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 21.12 +define HAL_BATT_CURR_SCALE 40.2 + +# compass +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90 + +# barometers +BARO DPS310 I2C:0:0x76 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# SPI1 - AT7456E +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PB12 AT7456E_CS CS + +# SPI2 - IMUs +PD3 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PD5 GYRO_CS CS +PD4 ACCEL_CS CS +PA15 BMI270_CS CS + +# SPI devices +SPIDEV bmi088_a SPI2 DEVID1 ACCEL_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI2 DEVID2 GYRO_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi270 SPI2 DEVID3 BMI270_CS MODE3 1*MHZ 10*MHZ +SPIDEV osd SPI1 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# 2 IMUs +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_270 +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat index 2334c17478e871..6349392a21e565 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat @@ -72,3 +72,4 @@ define STM32_ADC_USE_ADC1 TRUE PB11 BAT_CURR_SENS ADC1 SCALE(1) define HAL_RCIN_THREAD_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat index 3cd7b0f0dc7eb4..6db0ac1f72dedc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat @@ -87,9 +87,6 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA4 VSENSE ADC1 SCALE(2) -define HAL_NO_MONITOR_THREAD - - define AP_PARAM_MAX_EMBEDDED_PARAM 512 define HAL_PERIPH_ENABLE_GPS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat index e9441bbac6e010..e6b7f420183c2c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat @@ -59,8 +59,8 @@ MAIN_STACK 0x800 PROCESS_STACK 0x800 # enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 CAN_ORDER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat index 2532dfa2b9c51f..746325f7cd9fd6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat @@ -86,8 +86,8 @@ MAIN_STACK 0x300 PROCESS_STACK 0xA00 # enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 CAN_ORDER 1 @@ -95,8 +95,6 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA4 VSENSE ADC1 SCALE(2) -define HAL_NO_MONITOR_THREAD - define AP_PARAM_MAX_EMBEDDED_PARAM 512 define HAL_PERIPH_ENABLE_GPS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat index e1a4e30c826e3f..50feaed3c230e8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat @@ -98,6 +98,7 @@ define HAL_SPI_CHECK_CLOCK_FREQ PC7 MPU_CS CS # status LEDs +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 define HAL_LED_ON 0 PB0 LED OUTPUT HIGH GPIO(0) #Green PE1 LED1 OUTPUT HIGH GPIO(2) #Yellow diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg new file mode 100644 index 00000000000000..0c134b8abfc804 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg new file mode 100644 index 00000000000000..061d96c320f60c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx new file mode 100644 index 00000000000000..ba131825ff922d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md new file mode 100644 index 00000000000000..2e20e8d314d552 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md @@ -0,0 +1,92 @@ +# NxtPX4v2 Flight Controller + +The NxtPX4v2 is an open-source hardware designed and maintened by [HKUST UAV-Group](https://github.com/HKUST-Aerial-Robotics/Nxt-FC). And it is produced by [MicoAir Tech.](http://micoair.com/). + +## Features + + - STM32H743 microcontroller + - BMI088+BMI088(DUAL) IMU + - SPL06 barometer + - 12V 2.5A BEC; 5V 2.5A BEC + - SDCard +- 7x UART +- 8x PWM +- 1x I2C +- 1x SPI +- 1x SWD + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART2 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART4 (MAVLink2, DMA-enabled) + - SERIAL3 -> UART1 (GPS, DMA-enabled) + - SERIAL4 -> UART3 (VTX-HD, DMA-enabled) + - SERIAL5 -> UART7 (ESC Telemetry, DMA-enabled) + - SERIAL6 -> UART5 (RCIN, DMA-enabled) + - SERIAL7 -> UART8 (DMA-enabled) + +## RC Input + +The default RC input is configured on the UART5. The SBUS pin is inverted and connected to RX5. Non SBUS, single wire serial inputs can be directly tied to RX5 if SBUS pin is left unconnected. RC could be applied instead at a different UART port such as UART2, UART4 or UART8, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL6 _Protocol to something other than '23' + +## VTX Support + +The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 12v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The NxtPX4v2 supports up to 8 PWM outputs. All channels support bi-directional DShot. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2, 3, 4 are Group1; + +5, 6 are Group 2; + +7, 8 are Group 3; + +## 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 4 + - BATT_CURR_PIN 8 + - BATT_VOLT_MULT 10.2 + - BATT_CURR_SCALE 20.4 + +## Compass + +The NxtPX4v2 does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL connector. + +## GPIOs + +The remaining 3 outputs (labelled AUX1 to AUX3) are the "auxiliary" outputs. These are directly attached to the STM32H743. + +The numbering of the GPIOs for PIN variables in ardupilot is: + + - AUX1 - PA4 - 81 + - AUX2 - PC1 - 82 + - AUX3 - PC0 - 83 + +## Physical + + - Mounting: 20 x 20mm, Φ3mm +- Dimensions: 27 x 32 x 8 mm +- Weight: 6.5g + +## Ports Connector + +![NxtPX4v2 Front View](NxtPX4v2_FrontView.jpg) + +![NxtPX4v2 Back View](NxtPX4v2_BackView.jpg) + +## 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 favorite 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/NxtPX4v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/defaults.parm new file mode 100644 index 00000000000000..7bc08c2ca66fd8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/defaults.parm @@ -0,0 +1,10 @@ +#BATTERY MONITOR ON +BATT_MONITOR 4 + +#Serial Port defaults +SERIAL4_PROTOCOL 42 +SERIAL5_PROTOCOL 16 +SERIAL6_PROTOCOL 23 + +#MSP DisplayPort enable +OSD_TYPE 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat new file mode 100644 index 00000000000000..6a28cbbca1ffd6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat @@ -0,0 +1,44 @@ +# hw definition file for processing by chibios_hwdef.py +# for the NxtPX4v2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_NxtPX4v2 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# flash size +FLASH_SIZE_KB 2048 + +# 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 + + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS +PC2 BMI088_2_G_CS CS +PC13 BMI088_2_A_CS CS + +# LEDs +PD11 LED_ACTIVITY OUTPUT HIGH GPIO(91) #green +PB15 LED_BOOTLOADER OUTPUT HIGH GPIO(92) #blue +define HAL_LED_ON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat new file mode 100644 index 00000000000000..326d2c65fd70d2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat @@ -0,0 +1,161 @@ +# hw definition file for processing by chibios_hwdef.py +# for the NxtPX4v2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_NxtPX4v2 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# flash size +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 UART4 USART1 USART3 UART7 UART5 UART8 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PD0 VBUS INPUT OPENDRAIN + +# GPS1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# TELEM1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 + +# DJI O3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# TELEM2 +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# RC_INPUT +PB13 UART5_TX UART5 +PB12 UART5_RX UART5 +PD14 SBUS_INV OUTPUT LOW + +# ESC +PE7 UART7_RX UART7 + +# TELEM3 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# SWD +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# two I2C bus +I2C_ORDER I2C1 I2C4 + +# I2C1 - baro +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C4 - CONNECTOR +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# PWM output pins +PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR +PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PB10 TIM2_CH3 TIM2 PWM(5) GPIO(54) BIDIR +PB11 TIM2_CH4 TIM2 PWM(6) GPIO(55) +PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) BIDIR +PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) + +# GPIOs +PA4 PINIO1 OUTPUT GPIO(81) LOW +PC1 PINIO2 OUTPUT GPIO(82) LOW +PC0 PINIO3 OUTPUT GPIO(83) LOW + +# LEDs +PD15 LED_RED OUTPUT HIGH GPIO(90) +PD11 LED_GREEN OUTPUT HIGH GPIO(91) +PB15 LED_BLUE OUTPUT HIGH GPIO(92) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 + +define HAL_GPIO_LED_ON 1 +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# ADC for Power +PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC5 BATT_CURRENT_SENS ADC2 SCALE(1) + +define HAL_BATT_VOLT_PIN 4 +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_VOLT_SCALE 10.2 +define HAL_BATT_CURR_SCALE 20.4 + +# 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 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# SPI1 - IMU0 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS + +# SPI3 - CONNECTOR +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 + +# SPI4 - IMU1 +PE6 SPI4_MOSI SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PC2 BMI088_2_G_CS CS +PC13 BMI088_2_A_CS CS + +# barometers +BARO SPL06 I2C:0:0x77 + +# SPI devices +SPIDEV imu0_a SPI1 DEVID1 BMI088_1_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu0_g SPI1 DEVID2 BMI088_1_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu1_a SPI4 DEVID3 BMI088_2_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu1_g SPI4 DEVID4 BMI088_2_G_CS MODE3 10*MHZ 10*MHZ + +# 2 IMUs +IMU BMI088 SPI:imu0_a SPI:imu0_g ROTATION_ROLL_180_YAW_90 +IMU BMI088 SPI:imu1_a SPI:imu1_g ROTATION_ROLL_180_YAW_90 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat index d22ae701fddb04..f27224e751879a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat @@ -129,9 +129,8 @@ define HAL_PARACHUTE_ENABLED 0 # save FLASH, but leave above when flash issue is fixed include ../include/minimize_fpv_osd.inc -# disable SMBUS monitors to save flash -undef AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_ENABLED 0 +#not useable for quadplane +define HAL_QUADPLANE_ENABLED 0 # one baro BARO BMP280 SPI:bmp280 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat index 84a127f43e3619..1e068c119b4e56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat @@ -138,7 +138,8 @@ define HAL_BATT_CURR_SCALE 18.2 define BOARD_RSSI_ANA_PIN 0 -define HAL_GPIO_A_LED_PIN 41 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 41 define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef-bl.dat index f602396f6e6c27..78ad6e6362c823 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef.dat index dd0d0c1949e2b7..0d5a0f9d3f911f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OrqaF405Pro/hwdef.dat @@ -108,6 +108,7 @@ PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) # M7 PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) # M8 # LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 # Red PA15 LED0 OUTPUT LOW GPIO(90) define HAL_GPIO_B_LED_PIN 90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat index 311a727360e85a..5d25f1ae4f5888 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat @@ -278,9 +278,9 @@ PC6 LED_GREEN OUTPUT GPIO(91) LOW PC7 LED_BLUE OUTPUT GPIO(92) HIGH # setup for Board LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/README.md b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/README.md index 495eca8f9b9b98..8030bd8d2ef14e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/README.md @@ -55,8 +55,8 @@ Contact dheeranlabs@gmail.com for sales | 1 | VCC | +5V | | 2 | UART_TX6 | +3.3V | | 3 | UART_RX6 | +3.3V | -| 4 | CTS | +3.3V | -| 5 | RTS | +3.3V | +| 4 | X | X | +| 5 | X | X | | 6 | GND | GND | **GPS1** @@ -70,7 +70,7 @@ Contact dheeranlabs@gmail.com for sales | 5 | I2C2_SDA | +3.3V | | 6 | GND | GND | -**GPS2** +**SERIAL5** | Pin | Signal | Volt | | :--: | :-----: | :---: | @@ -78,8 +78,17 @@ Contact dheeranlabs@gmail.com for sales | 2 | UART_TX7 | +3.3V | | 3 | UART_RX7 | +3.3V | | 4 | X | X | -| 5 | X | X | -| 6 | GND | GND | +| 5 | GND | GND | + +**SERIAL6, GPIO** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | USART_TX2| +3.3V | +| 3 | USART_RX2| +3.3V | +| 4 | GPIO | +3.3V | +| 5 | GND | GND | **SAFETY** @@ -103,7 +112,7 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn. - SERIAL2 -> UART6 (TELEM2) with DMA Enabled - SERIAL3 -> UART1 (GPS1) Tx(NODMA), Rx(DMA Enabled) - SERIAL4 -> EMPTY - - SERIAL5 -> UART7 (GPS2) NODMA + - SERIAL5 -> UART7 (User) NODMA - SERIAL6 -> USART2 (User) NODMA ## RC Input diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/hwdef.dat index e32b238d94396f..b4e6704450b4c2 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo-F767/hwdef.dat @@ -157,20 +157,16 @@ SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ # enable FAT filesystem define HAL_OS_FATFS_IO 1 -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" - - # pixracer has 3 LEDs, Red, Green, Blue -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 PE10 LED_RED OUTPUT GPIO(0) PE8 LED_GREEN OUTPUT GPIO(1) PE7 LED_BLUE OUTPUT GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # battery setup define HAL_BATT_MONITOR_DEFAULT 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo/hwdef.dat index 8bf13bc5238f88..afd5f861c7fea6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixFlamingo/hwdef.dat @@ -141,16 +141,16 @@ SPIDEV lsm9ds0_g SPI2 DEVID4 GYRO_CS MODE3 11*MHZ 11*MHZ define HAL_OS_FATFS_IO 1 # pixracer has 3 LEDs, Red, Green, Blue -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # LED setup for PixracerLED driver PE8 LED_RED OUTPUT GPIO(0) PE7 LED_GREEN OUTPUT GPIO(1) PB2 LED_BLUE OUTPUT GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # battery setup define HAL_BATT_MONITOR_DEFAULT 4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat index 9677e35f25e105..f2a44efb12f52f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat @@ -155,11 +155,11 @@ PA8 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH PC15 LED_BLUE OUTPUT OPENDRAIN GPIO(13) HIGH -define HAL_GPIO_A_LED_PIN 11 -define HAL_GPIO_B_LED_PIN 12 -define HAL_GPIO_C_LED_PIN 13 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 13 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # SPI device table SPIDEV BMP388 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ @@ -183,10 +183,6 @@ BARO BMP388 SPI:BMP388_ext define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 - -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" - define HAL_STORAGE_SIZE 16384 define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat index 490fb17d2c8003..008a67702218dd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat @@ -164,11 +164,11 @@ PC11 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH PC10 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH PC12 LED_BLUE OUTPUT OPENDRAIN GPIO(13) HIGH -define HAL_GPIO_A_LED_PIN 11 -define HAL_GPIO_B_LED_PIN 12 -define HAL_GPIO_C_LED_PIN 13 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 13 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # SPI device table SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat index e5581ab3d3198c..08c2205d8b1a3d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat @@ -160,11 +160,11 @@ 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_A_LED_PIN 11 -define HAL_GPIO_B_LED_PIN 13 -define HAL_GPIO_C_LED_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 13 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-1.png b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-1.png new file mode 100644 index 00000000000000..3781777bbb9bcb Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-1.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-2.png b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-2.png new file mode 100644 index 00000000000000..504b02da67ad6c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/PixPilot-V6Pro-2.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/README.md b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/README.md new file mode 100644 index 00000000000000..55162fff69cdbd --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/README.md @@ -0,0 +1,427 @@ + +## PixPilot-V6PRO Flight Controller + +The PixPilot-V6PRO flight controller is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com) + +## Features + +• STM32H743VIT6 microcontroller + +•STM32F103C8T6 IOMCU 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, BMP388(SPI) + +• builtin RAMTRON(SPI) + +• microSD card slot + +• 5 UARTs, two with RTS/CTS flow control + +• USB(Type-C) + +• PPM & S.Bus input + +• 16 PWM outputs + +• twoI2C ports and two FDCAN ports + +• one S.Bus output + +• internal Buzzer + +• builtin RGB LED + +• Four voltage & current monitoring, Two analog and Two CAN + +• servo rail BEC independent power input for servos + +• external safety Switch + + +## Picture + +![PixPilot-V6PRO](PixPilot-V6Pro-1.png "PixPilot-V6Pro-1") +![PixPilot-V6PRO](PixPilot-V6Pro-2.png "PixPilot-V6Pro-2") + +## Pinout + +UART Mapping +============ + + - SERIAL0 -> console (primary mavlink, usually USB) +- SERIAL1 -> USART2 (Telem1,MAVLINK2) (DMA capable) +- SERIAL2 -> USART3 (Telem2, MAVLink2) (DMA capable) + - SERIAL3 -> UART4 (GPS1) (TX is DMA capable) + - SERIAL4 -> UART8 (GPS2) (RX is DMA capable) + - SERIAL5 -> UART7 (USER) + + Connector pin assignments +========================= +POWER_CAN1 port, POWER_CAN2 ports +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2VCC+5V
3CAN_H+12V
4CAN_L+12V
5GNDGND
6GNDGND
+ + +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
3Safety Switch+5V
+ +DSM port +----------- + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2DSM_IN+5V
3GNDGND
+ +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 4 CAN ports which allow connecting two independant CAN bus outputs. Each of these can have multiple CAN peripheral devices connected. There are also two separate CAN POWER ports for easy access to CAN-PMU. + +Where to Buy +============ + +`makeflyeasy `_ + + +[copywiki destination="plane,copter,rover,blimp"] diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/defaults.parm new file mode 100644 index 00000000000000..b6a70ce19cf6a0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/defaults.parm @@ -0,0 +1,3 @@ +# turn on the CAN power monitoring(default) +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef-bl.dat new file mode 100644 index 00000000000000..a18fd547ebb34d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef-bl.dat @@ -0,0 +1,62 @@ +# 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 1160 + +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 SERIAL5. +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 +PC13 42688_EXT_CS CS +PD7 BARO_EXT_CS CS +PC2 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef.dat new file mode 100644 index 00000000000000..69308467084fab --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6PRO/hwdef.dat @@ -0,0 +1,297 @@ +# 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 1160 + +FLASH_SIZE_KB 2048 + + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + + + +# order of I2C buses +I2C_ORDER 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 + + + + + + + +# 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 + + +# 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. +PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA3 BATT_CURRENT_SENS ADC1 SCALE(1) + +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. +PC13 42688_EXT_CS CS +PD7 BARO_EXT_CS CS +PC2 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) BIDIR +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) BIDIR +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR + +PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) NODMA +PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) NODMA + + + + +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_A_LED_PIN 11 +define HAL_GPIO_B_LED_PIN 13 +define HAL_GPIO_C_LED_PIN 12 + +# 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 BMP388 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ +SPIDEV BMP388_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 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 BMP388 SPI:BMP388 +BARO BMP388 SPI:BMP388_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 +AP_BOOTLOADER_FLASH_FROM_SD_ENABLED + +#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + + + +# Now setup the default battery pins driver analog pins and default +# scaling for the power brick. +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 14 +define HAL_BATT_CURR_PIN 15 + +define HAL_BATT2_VOLT_PIN 13 +define HAL_BATT2_CURR_PIN 4 + +define HAL_BATT_VOLT_SCALE 18.0 +define HAL_BATT_CURR_SCALE 24.0 + +define HAL_BATT2_VOLT_SCALE 18.0 +define HAL_BATT2_CURR_SCALE 24.0 + + +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# 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 + +# compensate for magnetic field generated by the heater on internal IST8310 +define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xe,0xa),Vector3f(0,2,-19)} + +# this board does not have heater detection pins, so force via features register +define AP_IOMCU_FORCE_ENABLE_HEATER 1 + +# Enable all IMUs to be used and therefore three active EKF Lanes +define HAL_EKF_IMU_MASK_DEFAULT 7 + + +#define HAL_GPIO_PWM_VOLT_PIN 3 +#define HAL_GPIO_PWM_VOLT_3v3 1 + +define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin + + +# enable support for dshot on iomcu + ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin + +define HAL_WITH_IO_MCU_DSHOT 1 + +DMA_NOSHARE SPI1* SPI4* USART6* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA2/hwdef.dat index 1c3f349d885f18..cd8f932bbd5ac6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA2/hwdef.dat @@ -5,6 +5,7 @@ include ../PixPilot-V6/hwdef.dat undef APJ_BOARD_ID APJ_BOARD_ID 1097 +undef AP_NOTIFY_GPIO_LED_RGB_ENABLED undef HAL_GPIO_A_LED_PIN undef HAL_GPIO_B_LED_PIN undef HAL_GPIO_C_LED_PIN diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat index 5b9a535f5ef225..73b2dc8ec527f3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat @@ -29,8 +29,7 @@ env OPTIMIZE -Os # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 UART5 USART2 USART3 -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # USB PA11 OTG_FS_DM OTG1 @@ -70,9 +69,9 @@ PD9 USART3_RX USART3 NODMA # armed indication PC12 nARMED OUTPUT HIGH -# start peripheral power off -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat index 0be4c176b5f2fe..6ce6a1bd9f493f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat @@ -214,11 +214,9 @@ 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 -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) @@ -253,9 +251,9 @@ PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(91) HIGH PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # ID pins PG0 HW_VER_REV_DRIVE OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat index da0f10b9928035..4f344eb61decf1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat @@ -29,8 +29,7 @@ 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 @@ -59,9 +58,9 @@ PD2 UART5_RX UART5 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 +# start peripheral power on +PC10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PE2 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PD10 LED_ACTIVITY OUTPUT OPENDRAIN GPIO(90) HIGH # red @@ -70,3 +69,30 @@ define HAL_LED_ON 0 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 + +# support flashing from SD card: + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 + +# 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 + +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 AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index 4677c93b2ab37a..d7a8bd14badd2d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -164,11 +164,9 @@ 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 +# start peripheral power on +PC10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PE2 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) @@ -179,7 +177,7 @@ define HAL_SPEKTRUM_PWR_ENABLED 1 # power sensing PE3 VDD_5V_PERIPH_nOC INPUT PULLUP -PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP +PC11 VDD_5V_HIPOWER_nOC INPUT PULLUP PA15 VDD_BRICK_nVALID INPUT PULLUP PB12 VDD_BRICK2_nVALID INPUT PULLUP @@ -198,9 +196,9 @@ PD10 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH PD11 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 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 @@ -258,6 +256,10 @@ DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM* define HAL_OS_FATFS_IO 1 ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_lowpolh.bin + +# build ABIN for flash-from-bootloader support: +env BUILD_ABIN True + # enable support for dshot on iomcu ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin define HAL_WITH_IO_MCU_BIDIR_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm index 89ab4beebb035b..d67da7a5fd6e36 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm @@ -1,5 +1,5 @@ NET_ENABLED 1 -NET_OPTIONS 1 +NET_OPTIONS 3 # enable hw flow control UART1_RTSCTS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat index a199216c91f2b1..8a3ca1c0793f9b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat @@ -24,8 +24,6 @@ define HAL_PERIPH_ENABLE_SERIAL_OPTIONS define AP_NETWORKING_BACKEND_PPP 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE # use blue LED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat index 8ca7a6488f8d64..b9901fa1c7f950 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat @@ -24,8 +24,7 @@ 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 @@ -60,9 +59,9 @@ 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 +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat index 1cf5be3a9f7430..aa427cb17592d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -227,11 +227,9 @@ PF4 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 -PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PG10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) @@ -267,12 +265,11 @@ 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # ID pins PG0 HW_VER_REV_DRIVE OUTPUT LOW @@ -357,6 +354,7 @@ IMU Invensensev3 SPI:icm45686-2 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_HOLY IMU Invensensev3 SPI:icm45686-3 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_45686) IMU Invensensev3 SPI:icm45686-1 ROTATION_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_45686) +define HAL_INS_HIGHRES_SAMPLE 7 define HAL_DEFAULT_INS_FAST_SAMPLE 7 # enable RAMTROM parameter storage diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat index 59e704a045145d..700fbd0cd0cc7a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat @@ -35,8 +35,6 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 -define HAL_NO_MONITOR_THREAD - define HAL_USE_RTC FALSE define HAL_BARO_ALLOW_INIT_NO_BARO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer/hwdef.dat index 47a9ccc82e5b3a..f1a16f3c87ac5d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer/hwdef.dat @@ -181,16 +181,16 @@ define HAL_WITH_RAMTRON 1 define HAL_OS_FATFS_IO 1 # pixracer has 3 LEDs, Red, Green, Blue -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # LED setup for PixracerLED driver PB11 LED_RED OUTPUT GPIO(0) PB1 LED_GREEN OUTPUT GPIO(1) PB3 LED_BLUE OUTPUT GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # battery setup define HAL_BATT_VOLT_PIN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm index fc20ce10087e45..c268d8d0156bfe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm @@ -12,12 +12,12 @@ BATT2_VOLT_MULT 20.000 BATT2_AMP_PERVLT 60.000 # setup the parameter for the two Relays GPIO others for reserve -RELAY_PIN 1 -RELAY_PIN2 2 -RELAY_PIN3 3 -RELAY_PIN4 4 -RELAY_PIN5 5 -RELAY_PIN6 6 +RELAY1_PIN 1 +RELAY2_PIN 2 +RELAY3_PIN 3 +RELAY4_PIN 4 +RELAY5_PIN 5 +RELAY6_PIN 6 # Disable the safety switch by default BRD_SAFETY_DEFLT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat index 1134e6616b1e0d..66dde13ae2afb4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat @@ -111,10 +111,6 @@ PD2 SDIO_CMD SDIO # 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 @@ -154,14 +150,14 @@ PE0 EXTERN_GPIO6 OUTPUT GPIO(6) PA15 TIM2_CH1 TIM2 RCININT PULLDOWN LOW # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 PE10 LED_RED OUTPUT GPIO(10) PE12 LED_GREEN OUTPUT GPIO(11) PE15 LED_BLUE OUTPUT GPIO(12) -define HAL_GPIO_A_LED_PIN 10 -define HAL_GPIO_B_LED_PIN 11 -define HAL_GPIO_C_LED_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 # analog in 6.6V PC1 ADC_1 ADC1 SCALE(2) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat index 1c5ca9d2da4d2e..0881d1172ba7e5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat @@ -170,15 +170,15 @@ define RELAY4_PIN_DEFAULT 4 PC7 TIM8_CH2 TIM8 RCININT PULLDOWN LOW # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 # analog in PC0 PRESSURE_SENS ADC1 SCALE(2) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743-bdshot/defaults.parm index 65b893da7cb7f0..699163155514dd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743-bdshot/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743-bdshot/defaults.parm @@ -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 -RELAY_PIN 1 -RELAY_PIN2 2 +RELAY1_PIN 1 +RELAY2_PIN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm index 7e5dd045aa6eae..ec79cb9dc29f32 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm @@ -5,5 +5,5 @@ BRD_HEAT_TARG 45 SERIAL2_BAUD 921600 # setup the parameter for the two Relays GPIO others for reserve -RELAY_PIN 1 -RELAY_PIN2 2 +RELAY1_PIN 1 +RELAY2_PIN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat index 2f97bf0f1ec2f2..04dbec92ff4bbf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat @@ -197,14 +197,14 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES # LED setup is similar to PixRacer -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 PE2 LED_RED OUTPUT GPIO(10) PE1 LED_GREEN OUTPUT GPIO(11) PE0 LED_BLUE OUTPUT GPIO(12) -define HAL_GPIO_A_LED_PIN 10 -define HAL_GPIO_B_LED_PIN 11 -define HAL_GPIO_C_LED_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 #define GPIOs diff --git a/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat index 110df4f7ad64e0..4104297370918a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat @@ -112,6 +112,7 @@ define BOARD_RSSI_ANA_PIN 15 PC0 PRESSURE_SENS ADC1 SCALE(2) define HAL_DEFAULT_AIRSPEED_PIN 10 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PE0 LED0 OUTPUT LOW GPIO(90) # blue PA3 LED1 OUTPUT LOW GPIO(91) # green define HAL_GPIO_A_LED_PIN 91 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/README.md b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/README.md index 7b5b1eeacc02c5..d77638e315fbb1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/README.md @@ -43,7 +43,7 @@ and how to use the "PWR:VBAT" jumper. - SERIAL1 -> UART1 (DMA-enabled, MSP DisplayPort OSD) - SERIAL2 -> UART2 (DMA-enabled, GPS) - SERIAL3 -> UART3 (DMA-enabled, RCin) - - SERIAL4 -> UART4 (spare) + - SERIAL4 -> UART4 (ESC telemetry) - SERIAL5 -> UART5 (spare) - SERIAL6 -> UART6 (spare, PWM 9 and 10 by default, use BRD_ALT_CONFIG = 1 for UART) - SERIAL7 -> UART7 (spare, RX is on HD connector for RC input, TX is not connected to external pad) @@ -87,29 +87,64 @@ In addition to voltage sensing, the board also has an input for an external curr ## Loading Firmware -The RADIX 2 HD uses a proprietary bootloader. To load firmware, download the firmware binary file -from the [BrainFPV website](https://www.brainfpv.com/firmware) and copy it to the USB drive -that appears when connecting the RADIX 2 HD to your computer when it is in bootloader mode -(hold the BOOT button and release when connecting to USB). +The RADIX 2 HD uses a proprietary bootloader which needs a firmware file in a custom +file format. There are several ways of obtaining the firmware file, as explained below. +Once you have obtained the file, copy it to the USB drive that appears when connecting +the RADIX 2 HD to your computer when it is in bootloader mode (hold the BOOT button and +release when connecting to USB). Once it finishes copying, safely remove the drive. +At this point the RADIX 2 HD will reboot and run the ArduPilot firmware. -Note: When using Ardupilot, it is necessary to have a microSD card inserted, without it +Note: When using ArduPilot, it is necessary to have a microSD card inserted, without it the firmware won't run. -Alternatively, you can create your own firmware file using the [BrainFPV Firmware Packer](https://github.com/BrainFPV/brainfpv_fw_packer). -To create a file for Ardupilot, install the BrainFPV Firmware Packer: +### Option 1: Download the Firmware File the BrainFPV Website - pip install git+https://github.com/BrainFPV/brainfpv_fw_packer.git +The easiest way to get firmware files for your RADIX 2 HD is to download them from the +BrainFPV website. You can do so [here](https://www.brainfpv.com/firmware). -After that, build the Copter firmware: +### Option 2: Download the Firmware From the ArduPilot Build Server + +Download the ELF file from the [ArduPilot Build Server](https://firmware.ardupilot.org/). +Make sure you download the file for the "RADIX2HD" target. For example, the ELF file for ArduCopter +is called "arducopter.elf". + +In order to use the ELF file with your RADIX 2 HD, it needs to be converted using the +[BrainFPV Firmware Packer](https://github.com/BrainFPV/brainfpv_fw_packer). This utility +is implemented in Python, so you will need a Python installation. + +If you are using Linux, use your package manager to install Python 3. If you are using +Windows, download the Python 3 installer from the [Python Website](https://www.python.org/downloads/) +and run it. When installing, make sure to select "Add Python to PATH", so you will +be able to use Python from the Windows Command Prompt. + +After installing Python, start the Command Prompt and install the BrainFPV Firmware Packer +using the following command: + + pip install https://github.com/BrainFPV/brainfpv_fw_packer/archive/main.zip + +After installing it, you can use the following command to convert the "arducopter.elf" (or other vehicle elf file) +file to a "arducopter.bin" file that can be used with the RADIX 2 HD: + + brainfpv_fw_packer.py --name arducopter --in arducopter.elf --out arducopter.bin ^ + --dev radix2hd -t firmware -b 0x90400000 -z --noheader + +### Option 3: Compile the Firmware Yourself + +If you have a working [ArduPilot build environment](https://ardupilot.org/dev/docs/building-the-code.html), +you can compile the firmware yourself and then convert it to the format needed by the BrainFPV +bootloader. You will also need the [BrainFPV Firmware Packer](https://github.com/BrainFPV/brainfpv_fw_packer) +to do so. Install it using the "pip install" command shown above. + +For Copter, build the firmware as follows: ./waf configure --board RADIX2HD ./waf copter -Finally, use the firmware packer script to create the firmware file that can be used with the +other vehicles can be built, but the RADIX 2 HD is used primarily for copter applications. +Then use the firmware packer script to create the firmware file that can be used with the BrainFPV bootloader: ./libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/pack_firmware.sh copter To use it, copy the resulting `arducopter_{VERSION}_brainfpv.bin` to the USB drive that appears -when the RADIX 2 HD is in bootloader mode. Once it finishes copying, safely remove the drive. -At this point the RADIX 2 HD will reboot and run the Copter firmware. +when the RADIX 2 HD is in bootloader mode. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm index b6cc0c5e93623a..4cbb8cacaa9698 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm @@ -13,4 +13,4 @@ SERIAL2_PROTOCOL 5 SERIAL4_PROTOCOL 16 # 9V regulator switch, ON on boot -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat index 5fdeaff78a1b40..b74ee1163cc5e9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat @@ -144,11 +144,11 @@ PE5 LED_RED OUTPUT HIGH OPENDRAIN GPIO(10) PE6 LED_GREEN OUTPUT HIGH OPENDRAIN GPIO(11) PA7 LED_BLUE OUTPUT HIGH OPENDRAIN GPIO(12) -define HAL_GPIO_A_LED_PIN 10 -define HAL_GPIO_B_LED_PIN 11 -define HAL_GPIO_C_LED_PIN 12 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # 9V regulator switch PC14 VTX_PWR OUTPUT HIGH GPIO(81) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/Readme.md index 173b0317e7f7f7..4f327da1ea17f1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/Readme.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/Readme.md @@ -15,7 +15,7 @@ Featuring STM32F7 cpu, vibration isolation of IMUs, redundant IMUs, integrated - Sensors - Bosh BMI088 IMU (accel, gyro) - InvenSense ICM-42688 IMU (accel, gyro) - - SPL06 barometer + - SPA06 barometer - IST8310 magnetometer - Power - SMBUS/I2C Power Module Inputs(I2C) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/hwdef.dat index 0cd8456398c726..c7edef50b09dbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/hwdef.dat @@ -171,9 +171,9 @@ SPIDEV osd SPI2 DEVID2 AT7456_CS MODE0 10*MHZ 10*MHZ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ # up to 2 IMUs -IMU Invensensev3 SPI:imu2 ROTATION_YAW_90 +IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_270 -IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 define HAL_DEFAULT_INS_FAST_SAMPLE 1 @@ -183,7 +183,7 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES # we need to stop the probe of an IST8310 as an internal compass with PITCH_180 define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE -COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180 +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_180 # one baro BARO SPL06 I2C:0:0x76 @@ -207,11 +207,11 @@ PC1 LED_GREEN OUTPUT GPIO(91) PC7 LED_BLUE OUTPUT GPIO(92) # 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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 @@ -227,9 +227,6 @@ DMA_PRIORITY SDMMC* UART8* ADC* USART3_RX TIM1_UP USART2_RX USART1_RX TIM1_CH3 S # 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 # setup for OSD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745/hwdef.dat index 1e3560cdb84ffa..870c162f68c03f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745/hwdef.dat @@ -121,6 +121,7 @@ define HAL_LOGGING_DATAFLASH_ENABLED 1 # spi devices bmi270(v2) icm42688 (v3) SPIDEV bmi270 SPI3 DEVID1 GYRO_CS MODE3 1*MHZ 4*MHZ SPIDEV icm42688 SPI3 DEVID1 GYRO_CS MODE3 2*MHZ 8*MHZ +SPIDEV mpu6000 SPI3 DEVID1 GYRO_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 @@ -129,9 +130,10 @@ define ALLOW_ARM_NO_COMPASS define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 -# one IMU: bmi270 or icm42688 +# one IMU: bmi270 or icm42688 or mpu6000 IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_90 +IMU Invensense SPI:mpu6000 ROTATION_YAW_90 define HAL_DEFAULT_INS_FAST_SAMPLE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg new file mode 100644 index 00000000000000..4e47709703266f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md new file mode 100644 index 00000000000000..016e8e8ce3d9f2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md @@ -0,0 +1,116 @@ +# SDMODEL SDH7 V2 Flight Controller + +## Features + + - STM32H743 microcontroller + - MPU6000 IMU + - BMP280 barometer + - IST8310 Compass + - microSD card slot + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![SDH7V2](SDMODEL_H7V2.png) + +![SDH7V2](H7V1_0502.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. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (Telem1) (MSP DisplayPort)(DMA Capable) + - SERIAL2 -> UART2 (Telem2) (connected to internal BT module, not useable by ArduPilot) + - SERIAL3 -> UART3 (RCin)(DMA Capable) + - SERIAL4 -> UART4 (GPS) + - SERIAL5 -> not available + - SERIAL6 -> UART6 (TELEM) + - SERIAL7 -> UART7 (RX pin only, ESC telem)(DMA Capable) + +## RC Input + +RC input is configured on the R6 (UART6_RX) pin. It supports all single wire unidirectional RC +protocols. For protocols requiring half-duplex or full duplex serial for operation +select another UART with DMA and set its protocol to "23". To use this UART for other uses, set +:ref:`BRD_ALT_CONFIG` to "1" + +## 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). Note this assumes the RC input is using default (ALT_BRD_CONFIG =0). Obviously, if using ALT_BRD_CONFIG = 1 for full duplex RC prtocols, you must a different UART for FrSky Telemetry. + + - SERIAL6_PROTOCOL 10 + - SERIAL6_OPTIONS 7 + +## OSD Support + +The SDMODEL SDH7 V2 supports OSD using OSD_TYPE 1 (MAX7456 driver).The defaults are also setup to allow DJI Goggle OSD support on UART1. Both OSDs can operate simultaneously. + +## 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 RELAY2_PIN set to GPIO 81 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2. + +## Camera Control + +The Cam pin is GPIO82 and is set to be controlled by RELAY4 by default. Relay pins can be controlled either by an RC switch or GCS command. See :ref:`common-relay` for more information. + +## PWM Output + +The SDMODEL SDH7 V2 supports up to 9 PWM or DShot outputs. Outputs 1-4 support BDShot. The pads for motor output +M1 to M8 on the two motor connectors, plus M9 preconfigured for LED strip or can be used as 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. + +.. note:: for users migrating from BetaflightX quads, the first four outputs M1-M4 have been configured for use with existing motor wiring using these default parameters: + +- :ref:`FRAME_CLASS` = 1 (Quad) +- :ref:`FRAME_TYPE` = 12 (BetaFlightX) + +## 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 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11 + - BATT_AMP_PERVLT 59.5 + +## Compass + +SDMODEL SDH7 V2 has a built-in compass IST8310, but you can add an external compass 2nd using the I2C connections on the SDA and SCL pads. + +## Firmware + +Firmware for these boards can be found `here `_ in sub-folders labeled "SDMODELH7V2". + + +## 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/SDMODELH7V2/SDMODEL_H7V2.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/SDMODEL_H7V2.jpg new file mode 100644 index 00000000000000..c6e336dc893707 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/SDMODEL_H7V2.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm new file mode 100644 index 00000000000000..4b63c6826647b7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm @@ -0,0 +1,8 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +#UART Protocol Defaults to allow DMA on RC,GPS on serial 4 +SERIAL3_PROTOCOL 23 +SERIAL6_PROTOCOL 2 +# UART1 for DisplayPort Goggles +SERIAL1_PROTOCOL 42 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat new file mode 100644 index 00000000000000..3fc10b4278836c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat @@ -0,0 +1,7 @@ +include ../KakuteH7-bdshot/hwdef-bl.dat + +# board ID for firmware load +APJ_BOARD_ID AP_HW_SDMODELH7V2 + +# VTX power switch +PB11 VTX_PWR OUTPUT HIGH PUSHPULL GPIO(81) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat new file mode 100644 index 00000000000000..a59687c3bf6c69 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat @@ -0,0 +1,18 @@ +include ../KakuteH7-bdshot/hwdef.dat + +# board ID for firmware load +APJ_BOARD_ID AP_HW_SDMODELH7V2 + +# VTX power switch +PB11 VTX_PWR OUTPUT HIGH PUSHPULL GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +# Camera control +PE9 CAM_C OUTPUT LOW GPIO(84) +define RELAY4_PIN_DEFAULT 84 + +# BetaFlight motor order +define HAL_FRAME_TYPE_DEFAULT 12 + +# builtin compass +COMPASS IST8310 I2C:0:0x0E false ROTATION_PITCH_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat index 75abd77fc6bcbb..69c02d554710bc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat @@ -189,9 +189,9 @@ PC6 LED_GREEN OUTPUT GPIO(91) LOW PC7 LED_BLUE OUTPUT GPIO(92) HIGH # setup for 2 LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat index 51200e048de844..f5ef8f9ad8563f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat @@ -53,7 +53,6 @@ QSPIDEV w25q-dtr QUADSPI1 MODE3 100*MHZ 24 1 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 -DEFAULTGPIO OUTPUT LOW PULLDOWN # Add CS pins to ensure they are high in bootloader PB12 ICM20602_2_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef-bl.dat index 4a2c734dc05aa9..7278d62b5e9658 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef-bl.dat @@ -56,7 +56,6 @@ OSPIDEV w25q OCTOSPI1 MODE3 130*MHZ 21 1 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 -DEFAULTGPIO OUTPUT LOW PULLDOWN # Add CS pins to ensure they are high in bootloader PA15 ICM42688_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat index be2be38e150df2..46b4ac476a7ef1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat @@ -34,8 +34,6 @@ define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat index 4952b98e5255f0..840e642e23e056 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat @@ -95,7 +95,6 @@ PA12 CAN1_TX CAN1 # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 -define HAL_NO_MONITOR_THREAD define HAL_DEVICE_THREAD_STACK 768 # disable dual GPS and GPS blending to save flash space diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat index 79cb3ce542be38..726e7869457d20 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat @@ -104,7 +104,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_NO_MONITOR_THREAD define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat index 515d3671b5f07c..4ae1b0a63d9362 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat @@ -92,7 +92,6 @@ define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE PA0 VDD_5V_SENS ADC1 SCALE(2) -define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 define HAL_PERIPH_ENABLE_MAG diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat index e6bd38b83c5203..c9a7dd156f06b4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat @@ -148,3 +148,4 @@ PC6 USB_SEL OUTPUT PUSHPULL SPEED_LOW HIGH define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat index 70d3d0163632da..61598a1eb00e01 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat @@ -37,7 +37,6 @@ PROCESS_STACK 0xA00 # save memory define HAL_GCS_ENABLED 0 -define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING define HAL_USE_ADC FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat index 3015e7714c02fb..994cce76fc65c5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat @@ -68,7 +68,6 @@ define HAL_NO_GPIO_IRQ define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -define HAL_NO_MONITOR_THREAD define HAL_DEVICE_THREAD_STACK 768 @@ -104,7 +103,7 @@ env ROMFS_UNCOMPRESSED True # PWM, WS2812 LED PA3 TIM2_CH4 TIM2 PWM(1) -DMA_NOSHARE USART2* +DMA_NOSHARE USART2* SPI1* define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro-G4" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat index f00cbdfd420dd0..115ae799ccfdaf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat @@ -36,7 +36,6 @@ MAIN_STACK 0x300 PROCESS_STACK 0xA00 # save memory -define HAL_NO_MONITOR_THREAD define HAL_USE_ADC FALSE # we setup a small defaults.parm @@ -98,9 +97,8 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define HAL_PERIPH_GPS_PORT_DEFAULT 0 - -# minimal GPS drivers to reduce flash usage -include ../include/minimal_GPS.inc +define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 # GPS PPS PA15 GPS_PPS_IN INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat index cb94ecf57f2fff..93d1f863d0a1d2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat @@ -36,7 +36,6 @@ MAIN_STACK 0x300 PROCESS_STACK 0xA00 # save memory -define HAL_NO_MONITOR_THREAD define HAL_USE_ADC FALSE # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat index 3509c384aa0c20..c831aece13cab1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat @@ -36,7 +36,6 @@ MAIN_STACK 0x300 PROCESS_STACK 0xA00 # save memory -define HAL_NO_MONITOR_THREAD define HAL_USE_ADC FALSE # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md new file mode 100644 index 00000000000000..e6a704a67342cf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/README.md @@ -0,0 +1,115 @@ +# SkySakura H743 Flight Controller + +The SkySakura H743 is a flight controller produced by [SkySakuraRC] + +## Features + + - MCU: STM32H743VIT6, 480MHz + - Gyro1: ICM42688 + - Gyro2: IIM42652 + - SD Card support + - BEC output: 5V 5A & 12V 5A (MAX 60W total) (switchable 12V) + - Barometer1: DPS310 + - Barometer2: ICP20100 + - Magnometer: IST8310 + - CAN bus support + - 7 UARTS: (USART1, USART2, USART3, UART4, USART6, UART7 with flow control, UART8) + - 2 I2C, I2C1 is used internally. + - 13 PWM outputs (12 motor outputs, 1 led) + - 4-12s wide voltage support + +## Pinout + +![SkySakura H743 Board](SkySakuraH743.png "SkySakura H743") + +## 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|RX7/TX7|UART7 (MAVLink2, flow-control-capable)| +|SERIAL2|TX1/RX1|UART1 (MAVLink2, DMA-enabled)| +|SERIAL3|TX2/RX2|UART2 (USER)| +|SERIAL4|TX3/RX3|UART3 (GPS1, DMA-enabled)| +|SERIAL5|TX4/RX4|UART4 (RCIN, DMA-enabled)| +|SERIAL6|TX6/RX6|UART6 (DisplayPort, DMA-enabled)| +|SERIAL7|TX8/RX8|UART8 (ESC-Telemetry, RX8 on ESC connectors, TX8 can be used if protocol is change from ESC telem)| +|SERIAL8|COMPUTER|USB| + +## Safety Button + +SkySakura H743 supports safety button, with connection to sh1.0 6 pin connector, with buzzer and safety led on the same connector. +Safety button is defaulted to be disabled but can be enabled by setting the following parameter: + - BRD_SAFETY_DEFLT 1 + +## RC Input + +RC input is configured on UART4 with an sh1.0 connector. It supports all RC protocols except PPM. The SBUS pin on the HD VTX connector is tied directly the UART4 RX. If ELRS is used on UART4, then the SBUS lead from a DJI VTX must not be connected to the SBUS to prevent ELRS lock up on boot. + +## OSD Support + +SkySakura H743 supports HD OSD through UART6 by default. + +## VTX Power Control + +The 12VSW output voltage on the HD VTX connector is controlled by GPIO 85, via RELAY1 by default. Low activates the voltage. + +## PWM Output + +The SkySakura H743 has 13 PWM outputs. M1-M8 are linked to sh1.0 8 pin connectors. The first 8 outputs support bi-directional DShot and DShot. Output 9-13 only support non-DShot protocols and 13 is configured as NEOPIXEL LED by default. + +The PWM are in in two groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5-6 in group3 + - PWM 7-8 in group4 + - PWM 9-12 in group5 + - PWM 13 in group6 + +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 and external current monitor inputs. The voltage sensor can handle up to 12S LiPo batteries. The current sensor scale's default range is 120A, but will need to be adjusted according to which sensor is used. These inputs are present on the first ESC connector. +A second battery monitor can be also used. Its voltage sensor is capable of reading up to 6.6V maximum and is available on the A3 solder pad. Its current monitor input is on the A4 solder pad. + +The default battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_VOLT_MULT 34 + - BATT_CURR_PIN 11 + - set BATT2_MONITOR 4 + - BATT2_VOLT_PIN 12 + - BATT2_CURR_PIN 13 + - BATT2_VOLT_MULT 10 + - set BATT2_AMP_PERVLT to appropriate value for second current sensor + +## Compass + +The SkySakura H743 have a builtin IST8310 compass. Due to motor interference, users often disable this compass and use an external compass attached via the external SDA/SCL pins. + +## NeoPixel LED + +PWM13 provides external NeoPixel LED support. + + +## Firmware + +Firmware can bee found on the `firmware server < https://firmware.ardupilot.org`__ in the "SkySakuraH743" folders + + +## 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/SkySakuraH743/SkySakuraH743-bottom.png b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743-bottom.png new file mode 100644 index 00000000000000..e516cbdf9dab8f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743-bottom.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743_top.png b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743_top.png new file mode 100644 index 00000000000000..96bc4932d2f872 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/SkySakuraH743_top.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/Wiring diagram.pdf b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/Wiring diagram.pdf new file mode 100644 index 00000000000000..bd512382304666 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/Wiring diagram.pdf differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm new file mode 100644 index 00000000000000..7200b83a92dda8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/defaults.parm @@ -0,0 +1,2 @@ +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat new file mode 100644 index 00000000000000..0c6bc0d525d7ed --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef-bl.dat @@ -0,0 +1,77 @@ +# hw definition file for processing by chibios_pins.py +# for SakuraH743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 2714 + +# USB setup +USB_STRING_MANUFACTURER "SkySakura" + +# 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 +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + + +# order of UARTs (and USB). Allow bootloading on USB and telem1 +SERIAL_ORDER OTG1 UART7 + +# UART7 (telem1) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# make sure Vsw is on during bootloader +PE15 PINIO1 OUTPUT HIGH + +PB5 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# Add CS pins to ensure they are high in bootloader +PA4 IMU1_CS CS +PE11 IMU2_CS CS +PC5 BARO2_CS CS +PB12 EXT_CS CS + + +# enable DFU by default +ENABLE_DFU_BOOT 1 + +# enable flashing from SD card: +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat new file mode 100644 index 00000000000000..6d8b8e7cd4b0a8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkySakuraH743/hwdef.dat @@ -0,0 +1,229 @@ +# hw definition file for processing by chibios_pins.py +# for SakuraH743 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 2714 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 +env OPTIMIZE -Os + +# USB setup +USB_STRING_MANUFACTURER "SkySakura" + +#debug on USART6 -- Uncomment if debugging +#STDOUT_SERIAL SD6 +#STDOUT_BAUDRATE 115200 + + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# DRDY pins +PC4 DRDY_IIM42652_SPI1 INPUT +PB2 DRDY_ICM42688_SPI4 INPUT + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# This is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN. +PD4 VBUS INPUT OPENDRAIN + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PD10 LED_SAFETY OUTPUT LOW +PD11 SAFETY_IN INPUT PULLDOWN +#disable safety button by default +define BOARD_SAFETY_ENABLE_DEFAULT 0 + +# SPI1 for IMU1 (IIM42652) +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 IMU1_CS CS + +# SPI2 - external (USER) +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 EXT_CS CS +#PB12 FLASH_CS CS + +# SPI1 for BARO2 (DPS310) +PC5 BARO2_CS CS + +# SPI4 for IMU2 (ICM42688) +PE11 IMU2_CS CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# two I2C bus +I2C_ORDER I2C1 I2C2 + +# I2C1 +PB6 I2C1_SCL I2C1 PULLUP +PB7 I2C1_SDA I2C1 PULLUP + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# ADC +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) +PC0 BATT2_VOLTAGE_SENS ADC2 SCALE(1) +PC1 BATT2_CURRENT_SENS ADC2 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT2_VOLT_PIN 10 +define HAL_BATT2_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 34.0 +define HAL_BATT_CURR_SCALE 40.0 +define HAL_BATT2_VOLT_SCALE 10 + +# LED setup +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 +PB5 LED_RED OUTPUT GPIO(83) +PB4 LED_GREEN OUTPUT GPIO(82) +PB3 LED_BLUE OUTPUT GPIO(81) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 83 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 82 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 81 + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART4 USART6 UART8 OTG2 + +# USART1 (TELEM2) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 (USER) +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# USART3 (GPS1) +PD9 USART3_RX USART3 +PD8 USART3_TX USART3 + +# UART4 (RCIN) +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_RCIN + +# USART6 (DisplayPort) +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_MSP_DisplayPort + +# UART7 (telem1) +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + +# UART8 (ESC Telemetry) +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry + + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(90) + +# Motors +PA2 TIM5_CH3 TIM5 PWM(1) GPIO(50) BIDIR +PA3 TIM5_CH4 TIM5 PWM(2) GPIO(51) +PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR +PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) +PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54) BIDIR +PA0 TIM2_CH1 TIM2 PWM(6) GPIO(55) +PE5 TIM15_CH1 TIM15 PWM(7) GPIO(56) BIDIR +PE6 TIM15_CH2 TIM15 PWM(8) GPIO(57) +PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) NODMA +PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) NODMA +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) NODMA +PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) NODMA + +#LED +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED + +# Beeper +PD7 BUZZER OUTPUT GPIO(84) LOW +define HAL_BUZZER_PIN 84 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# GPIOs +PE15 VTX_PWR OUTPUT LOW GPIO(85) +define RELAY1_PIN_DEFAULT 85 + + +define HAL_STORAGE_SIZE 32768 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 + +# spi devices +SPIDEV icm42688 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 16*MHZ +SPIDEV iim42652 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV dps310 SPI1 DEVID2 BARO2_CS MODE3 5*MHZ 5*MHZ + + +DMA_PRIORITY SPI1* SPI4* +DMA_NOSHARE SPI1* SPI4* TIM5* TIM3* TIM2* TIM15* + +# has an integreted mag, but still probe the i2c bus for all possible +# external compass types +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_90 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define ALLOW_ARM_NO_COMPASS + +# two IMUs +# H743-V1, ICM42688, IIM42652 +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180 +IMU Invensensev3 SPI:iim42652 ROTATION_YAW_180 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# DPS310 integrated on SPI1 bus +BARO ICP201XX I2C:0:0x63 +BARO DPS310 SPI:dps310 + +define HAL_OS_FATFS_IO 1 +define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN +define HAL_FRAME_TYPE_DEFAULT 12 + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm index 63b7262cc4fcdd..9badc8d8c53401 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm @@ -2,7 +2,8 @@ SERVO9_FUNCTION 120 NTF_LED_LEN 1 # Default VTX power to on -RELAY_DEFAULT 1 +RELAY2_DEFAULT 1 +RELAY3_DEFAULT 1 SERIAL3_PROTOCOL 16 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 index e51f307f0ea3ef..7453b722da8546 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef-bl.dat @@ -38,8 +38,7 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat index c36b9f7f194572..1af2d6a3640cfa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat @@ -115,6 +115,7 @@ define HAL_BATT2_CURR_SCALE 59.5 PC3 RSSI_ADC ADC1 define BOARD_RSSI_ANA_PIN 13 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat index e043e37c018fdc..9d8245d987c012 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat index 26235823dcfde4..292c0777d674aa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat @@ -113,8 +113,9 @@ PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) # M4 # LEDs PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC13 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # Dataflash setup SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat index 84d03b16a6f6b4..6e9056e32ff97b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat @@ -29,8 +29,6 @@ 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 MPU_CS CS PB12 OSD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat index 1194d0026a73ba..5bc0e9cbf912d9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat @@ -28,6 +28,7 @@ I2C_ORDER I2C1 SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 # LEDs +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PA13 LED_GREEN OUTPUT LOW GPIO(0) PA14 LED_BLUE OUTPUT LOW GPIO(1) @@ -116,10 +117,10 @@ PA12 OTG_FS_DP OTG1 # PWM out pins. Note that channel order follows the ArduPilot motor # order conventions -PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) +PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) BIDIR PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51) PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) -PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) PB14 TIM8_CH2N TIM8 PWM(7) GPIO(56) @@ -171,59 +172,12 @@ PC13 PINIO1 OUTPUT GPIO(81) LOW include ../include/minimize_fpv_osd.inc undef AP_CAMERA_MOUNT_ENABLED -undef AP_LANDINGGEAR_ENABLED undef HAL_MOUNT_ENABLED undef HAL_MOUNT_SERVO_ENABLED -undef QAUTOTUNE_ENABLED define AP_CAMERA_MOUNT_ENABLED 1 -define AP_LANDINGGEAR_ENABLED 1 define HAL_MOUNT_ENABLED 1 +define AP_MOUNT_BACKEND_DEFAULT_ENABLED 0 define HAL_MOUNT_SERVO_ENABLED 1 -define QAUTOTUNE_ENABLED 1 -# disable parachute and sprayer to save flash -define HAL_PARACHUTE_ENABLED 0 -define HAL_SPRAYER_ENABLED 0 -define AP_GRIPPER_ENABLED 0 -define HAL_GENERATOR_ENABLED 0 -define AP_ICENGINE_ENABLED 0 -#define LANDING_GEAR_ENABLED 0 -define WINCH_ENABLED 0 -define HAL_ADSB_ENABLED 0 - -define AC_OAPATHPLANNER_ENABLED 0 -define PRECISION_LANDING 0 -#define HAL_BARO_WIND_COMP_ENABLED 0 -define AP_OPTICALFLOW_ENABLED 0 - - -# Disable un-needed hardware drivers -define HAL_WITH_ESC_TELEM 0 -define AP_FETTEC_ONEWIRE_ENABLED 0 - -define AP_VOLZ_ENABLED 0 -define AP_ROBOTISSERVO_ENABLE 0 -define HAL_PICCOLO_CAN_ENABLE 0 -define HAL_TORQEEDO_ENABLED 0 -define HAL_RUNCAM_ENABLED 0 -define HAL_HOTT_TELEM_ENABLED 0 -define HAL_NMEA_OUTPUT_ENABLED 0 -define HAL_BUTTON_ENABLED 0 -define AP_NOTIFY_OREOLED_ENABLED 0 -define HAL_IRISORCA_ENABLED 0 - -#only support MS4525 ANALOG ASP5033 driver -define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0 -define AP_AIRSPEED_MS4525_ENABLED 1 -define AP_AIRSPEED_ANALOG_ENABLED 1 -define AP_AIRSPEED_ASP5033_ENABLED 1 - -#only support UBLOX and NMEA GPS driver -define AP_GPS_BACKEND_DEFAULT_ENABLED 0 -define AP_GPS_UBLOX_ENABLED 1 -define AP_GPS_NMEA_ENABLED 1 -define HAL_MSP_GPS_ENABLED 1 - -define AP_TRAMP_ENABLED 1 define DEFAULT_NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat index 5219afd50f217b..75965031cbb94e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat @@ -75,8 +75,9 @@ PA14 JTCK-SWCLK SWD # LED and buzzer PB4 TIM3_CH1 TIM3 GPIO(56) ALARM +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PB5 LED OUTPUT HIGH GPIO(57) -define HAL_GPIO_A_LED_PIN 57 +define AP_NOTIFY_GPIO_LED_1_PIN 57 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/Bottom.png b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/Bottom.png new file mode 100644 index 00000000000000..6113aa6bad9328 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/Bottom.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/README.md new file mode 100644 index 00000000000000..16b3a731c0f93f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/README.md @@ -0,0 +1,133 @@ +# TBS LUCID H7 Flight Controller + +The TBS LUCID H7 is a flight controller produced by [TBS](https://www.team-blacksheep.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - Dual ICM42688 + - Barometer - DPS310 + - OSD - AT7456E + - microSD card slot + - 7x UARTs + - CAN support + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 3.3V 0.5A + - BEC 5V 3A + - BEC 9V 3A for video, gpio controlled, pinned out on HD VTX connector + - Selectable 5V or VBAT pad, for analog VTX, gpio controlled on/off + - Dual switchable camera inputs + +## Pinout + +![TBS LUCID H7 Board Top](Top.png "TBS LUCID H7 Top") +![TBS LUCID H7 Board Bottom](Bottom.png "TBS LUCID H7 Bottom") + +## 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 (MAVLink2) + - SERIAL1 -> UART1 (RX1 is SBUS in HD VTX connector) + - SERIAL2 -> UART2 (GPS, DMA-enabled) + - SERIAL3 -> UART3 (DisplayPort, DMA-enabled) + - SERIAL4 -> UART4 (MAVLink2, Telem1) + - SERIAL6 -> UART6 (RC Input, DMA-enabled) + - SERIAL7 -> UART7 (MAVLink2, Telem2, DMA and flow-control enabled) + - SERIAL8 -> UART8 (ESC Telemetry, RX8 on ESC connector for telem) + +## RC Input + +RC input is configured by default via the USART6 RX input. It supports all serial RC protocols except PPM. + +Note: If the receiver is FPort the receiver must be tied to the USART6 TX pin , RSSI_TYPE set to 3, +and SERIAL6_OPTIONS must be set to 7 (invert TX/RX, half duplex). For full duplex like CRSF/ELRS use both +RX6 and TX6 and set RSSI_TYPE also to 3. + +If SBUS is used on HD VTX connector (DJI TX), then SERIAL1_PROTOCOl should be set to "23" and SERIAL6_PROTOCOL changed to something else. + +## FrSky Telemetry + +FrSky Telemetry is supported using an unused UART, such as the T1 pin (UART1 transmit). +You need to set the following parameters to enable support for FrSky S.PORT: + + - SERIAL1_PROTOCOL 10 + - SERIAL1_OPTIONS 7 + +## OSD Support + +The TBS LUCID H7 supports OSD using OSD_TYPE 1 (MAX7456 driver) and simultaneously DisplayPort using TX3/RX3 on the HD VTX connector. + +## PWM Output + +The TBS LUCID H7 supports up to 13 PWM or DShot outputs. The pads for motor output +M1 to M4 are provided on both the motor connectors and on separate pads, plus +M9-13 on a separate pads for LED strip and other PWM outputs. + +The PWM is in 4 groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5-6 in group3 + - PWM 7-10 in group4 + - PWM 11-12 in group5 + - PWM 13 in group6 + +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-10 support bi-directional dshot. + +## Battery Monitoring + +The board has a built-in voltage sensor and external current sensor input. 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.0 + - BATT_AMP_PERVLT 40 + +Pads for a second analog battery monitor are provided. To use: + +- Set BATT2_MONIOTOR 4 +- BATT2_VOLT_PIN 18 +- BATT2_CURR_PIN 7 +- BATT2_VOLT_MULT 11.0 +- BATT2_AMP_PERVLT as required + +## Analog RSSI and AIRSPEED inputs + +Analog RSSI uses RSSI_PIN 8 +Analog Airspeed sensor would use ARSPD_PIN 4 + +## Compass + +The TBS LUCID H7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## VTX power control + +GPIO 81 controls the VSW pins which can be set to output either VBAT or 5V via a board jumper. Setting this GPIO high removes voltage supply to pins. RELAY2 is configured by default to control this GPIO and is low by default. + +GPIO 83 controls the VTX BEC output to pins marked "9V" and is included on the HD VTX connector. Setting this GPIO low removes voltage supply to this pin/pad. + +By default RELAY4 is configured to control this pin and sets the GPIO high. + +## Camera control + +GPIO 82 controls the camera output to the connectors marked "CAM1" and "CAM2". Setting this GPIO low switches the video output from CAM1 to CAM2. By default RELAY3 is configured to control this pin and sets the GPIO high. + +## 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/TBS_LUCID_H7/Top.png b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/Top.png new file mode 100644 index 00000000000000..f7d725fc5f6f53 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/Top.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/defaults.parm new file mode 100644 index 00000000000000..a54227e016329a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan13 +SERVO13_FUNCTION 120 +# Default VTX power to on +RELAY4_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef-bl.dat new file mode 100644 index 00000000000000..6bb6be09ea0e7c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef-bl.dat @@ -0,0 +1,77 @@ +# hw definition file for processing by chibios_pins.py +# for TBS FCAPv1 H743 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_LUCID_H7 + +# 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 +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# order of UARTs (and USB). Allow bootloading on USB and telem1 +SERIAL_ORDER OTG1 UART7 + +# UART7 (telem1) +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE3 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# Add CS pins to ensure they are high in bootloader +PC15 IMU1_CS CS +PB12 MAX7456_CS CS +PE11 IMU2_CS CS +PD4 EXT_CS1 CS +PE2 EXT_CS2 CS + +# Ensure GPIOs are on during bootloader +# Vsw +PD10 VSW OUTPUT LOW +# CamSw +PD11 CAMSW OUTPUT LOW +# 9V_EN +PC13 VPWR OUTPUT LOW + +# support flashing from SD card: +# enable DFU by default +ENABLE_DFU_BOOT 1 + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define FATFS_HAL_DEVICE SDCD1 +define HAL_OS_FATFS_IO 1 +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef.dat new file mode 100644 index 00000000000000..614741e8a10db2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS_LUCID_H7/hwdef.dat @@ -0,0 +1,219 @@ +# hw definition file for processing by chibios_pins.py +# for TBS FCAPv1 H743 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_LUCID_H7 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 +env OPTIMIZE -Os +MCU_CLOCKRATE_MHZ 480 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for IMU1 (ICM42688) +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PC15 IMU1_CS CS + +# SPI2 for MAX7456 OSD +PB12 MAX7456_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 - external +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# external CS pins +PD4 EXT_CS1 CS +PE2 EXT_CS2 CS + +# SPI4 for IMU2 (ICM42688) +PE11 IMU2_CS CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# two I2C bus +I2C_ORDER I2C2 I2C1 + +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 - Internal Baro +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# ADC +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1) +PA7 BATT2_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT2_VOLT_PIN 18 +define HAL_BATT2_CURR_PIN 7 +define HAL_BATT_VOLT_SCALE 11.0 +define HAL_BATT_CURR_SCALE 40.0 +define HAL_BATT2_VOLT_SCALE 11.0 + +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 + +# LED +# green LED1 marked as B/E +# blue LED0 marked as ACT +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 +PE3 LED0 OUTPUT LOW GPIO(90) # blue +PE4 LED1 OUTPUT LOW GPIO(91) # green +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 OTG2 + +# USART1 (DJI SBUS in connector) +PA10 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None + +# USART2 (GPS1) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS + +# USART3 (DJI O3 in connector) +PD9 USART3_RX USART3 +PD8 USART3_TX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort + +# UART4 (Telem1) +PB9 UART4_TX UART4 NODMA +PB8 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MAVLink2 + +# USART6 (RCIN) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN + +# UART7 (Telem2) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2 + +# UART8 (ESC Telemetry) +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# 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) +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) +# Disable DMA on PWM11-12 so that the LEDs get a channel +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA +# Motors +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED + +# Beeper +PA15 BUZZER OUTPUT GPIO(32) LOW +define HAL_BUZZER_PIN 32 +define AP_NOTIFY_TONEALARM_ENABLED 1 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# GPIOs +# Vsw +PD10 VSW OUTPUT GPIO(81) LOW +# CamSw +PD11 CAMSW OUTPUT GPIO(82) LOW +# 9V_EN +PC13 VPWR OUTPUT GPIO(83) LOW + +define RELAY2_PIN_DEFAULT 81 +define RELAY3_PIN_DEFAULT 82 +define RELAY4_PIN_DEFAULT 83 + +DMA_PRIORITY SPI1* SPI4* +DMA_NOSHARE SPI1* SPI4* TIM3* TIM2* TIM5* TIM4* + +define HAL_STORAGE_SIZE 32768 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 + +# spi devices +SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8 +SPIDEV imu2 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8 +SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*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 2 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +IMU Invensensev3 SPI:imu1 ROTATION_YAW_270 +IMU Invensensev3 SPI:imu2 ROTATION_YAW_180 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# DPS310 integrated on I2C2 bus +BARO DPS310 I2C:0:0x76 + +define HAL_OS_FATFS_IO 1 + +# 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/TMotorH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat index 69385f40cf3c6d..9a8ae479eff2a7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat index d8d9c1aaf3a013..8fc32b1397605d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat @@ -125,6 +125,7 @@ PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4 # LEDs PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 PE5 LED1 OUTPUT LOW GPIO(91) define HAL_GPIO_A_LED_PIN 91 @@ -145,9 +146,9 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin # IMU setup SPIDEV icm42688 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ -SPIDEV bmi270 SPI4 DEVID1 GYRO2_CS MODE3 1*MHZ 8*MHZ +SPIDEV bmi270 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ -IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90 +IMU BMI270 SPI:bmi270 ROTATION_PITCH_180 IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 DMA_NOSHARE TIM5_UP TIM3_UP TIM8_UP SPI1* SPI4* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md new file mode 100644 index 00000000000000..4eb13fdb062110 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md @@ -0,0 +1,608 @@ +# VUAV-V7pro Flight Controller + +The VUAV-V7pro flight controller is manufactured and sold by [V-UAV](http://www.v-uav.com/). + +## Features + + - STM32H743 microcontroller + - Three IMUs: ADIS16470,ICM42688,ICM42688 + - Internal vibration isolation for IMUs + - Internal RM3100 SPI magnetometer + - Internal two MS5611 SPI barometer + - Internal RGB LED + - MicroSD card slot port + - 1 Analog power port + - 1 CAN power port + - 5 UARTs and 1 USB ports + - 1 RS232 port + - 14 PWM output ports + - 4 I2C and 2 CAN ports + - Safety switch port + - Buzzer port + - RC IN port + +## Pinout + +![VUAV-V7pro-interface.png](VUAV-V7pro-interface.png) + +![VUAV-V7pro-pinout.png](VUAV-V7pro-pinout.png) + +## UART Mapping + - SERIAL0 -> USB + - SERIAL1 -> UART2 (Telem1) (DMA enabled) + - SERIAL2 -> UART6 (Telem2) (DMA enabled) + - SERIAL3 -> UART1 (GPS1) + - SERIAL4 -> UART3 (GPS2) + - SERIAL5 -> UART8 (USER) TX only on pin, RX is tied to RCIN + - SERIAL6 -> UART4 (RS232) + - SERIAL7 -> USB2 (virtual port on same connector) + - SERIAL8 -> UART7 (DEBUG) + +The Telem1,Telem2 port has RTS/CTS pins, the other UARTs do not have RTS/CTS. + +## Connectors + +### TELEM1 ,TELEM2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4CTS+3.3V
5RTS+3.3V
6GNDGND
+ +### GPS1/I2C4 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SCL I2C4+3.3V (pullups)
5SDA I2C4+3.3V (pullups)
6SafetyButton+3.3V
7SafetyLED+3.3V
8--
9Buzzer+3.3V
10GNDGND
+ +### GPS2/I2C3 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SCL I2C3+3.3V (pullups)
5SDA I2C3+3.3V (pullups)
6GNDGND
+ +### CAN1,CAN2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2CAN_H+24V
3CAN_L+24V
4GNDGND
+ +### I2C1,I2C2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2SCL+3.3 (pullups)
3SDA+3.3 (pullups)
4GNDGND
+ +### USB Ex + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC IN+5V
2D_minus+3.3V
3D_plus+3.3V
4GNDGND
+ +### RSSI + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2RSSIup to +3.3V
3UART8_TX (OUT)+3.3
4GNDGND
+ +### RS232 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+ +### DEBUG + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SWDIO+3.3V
5SWCLK+3.3V
6GNDGND
+ +### ADC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2ADC_3V3up to +3.3V
3ADC_6V6up to +6.6V
4GNDGND
+ +### POWER1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC IN+5V
2VCC IN+5V
3CURRENTup to +3.3V
4VOLTAGEup to +3.3V
5GNDGND
6GNDGND
+ +### POWER2(CAN1) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC IN+5V
2VCC IN+5V
3CAN1_H+24V
4CAN1_L+24V
5GNDGND
6GNDGND
+ +## RC Input + +RC input is configured on the RCIN pin, at one end of the servo rail. This pin supports all unidirectional RC protocols. For bi-directional protocols, such as CRSF/ELRS, UART8 can be set to protocol "23" and the reciever tied to RCIN (shared with UART8 RX) and UART8 TX. In this case, the RC_PROTOCOLS parameter should be set to the expected protocol type to avoid accidental erroneous detection by the RCIN path. + +## PWM Output + +The VUAV-V7pro supports up to 14 PWM outputs,support all PWM protocols. Outputs 1-12 support DShot. Outputs 1-8 support bi-directional Dshot. All 14 PWM outputs have GND on the top row, 5V on the middle row and signal on the bottom row. + +The 14 PWM outputs are in 4 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5, 6, 7 and 8 in group2 + - PWM 9, 10, 11 and 12 in group3 + - PWM 13, 14 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 that group need to use DShot. + +## GPIOs + +All 14 PWM channels can be used for GPIO functions (relays, buttons, RPM etc). +The pin numbers for these PWM channels in ArduPilot are shown below: + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PWM ChannelsPinPWM ChannelsPin
PWM150PWM857
PWM251PWM958
PWM352PWM1059
PWM453PWM1160
PWM554PWM1261
PWM655PWM1362
PWM756PWM1463
+ +## Analog inputs + +The VUAV-V7pro flight controller has 5 Analog inputs + + - ADC Pin2-> Battery Current + - ADC Pin16 -> Battery Voltage + - ADC Pin19 -> ADC 3V3 Sense + - ADC Pin3 -> ADC 6V6 Sense + - ADC Pin9 -> RSSI voltage monitoring + +## Battery Monitor Configuration + +The board has voltage and current inputs sensor on the POWER1 ADC and POWER2 CAN connector. + +The correct battery setting parameters are: + +Enable Battery1 monitor: + - BATT_MONITOR 4 + - BATT_VOLT_PIN 16 + - BATT_CUR_PIN 2 + - BATT_VOLT_MULT 15.7 (may need adjustment if supplied monitor is not used) + - BATT_AMP_PERVLT 60.61 (may need adjustment if supplied monitor is not used) + +Enable Battery2 monitor (if used): + - BATT2_MONITOR 8 + +## Loading Firmware + +The VUAV-V7pro flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of \*.apj firmware files with any ArduPilot compatible ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png new file mode 100644 index 00000000000000..ea342dee5dbc98 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png new file mode 100644 index 00000000000000..443c8cf57aa590 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm new file mode 100644 index 00000000000000..181f066cecdb2f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm @@ -0,0 +1,5 @@ +BRD_HEAT_TARG 45 +BRD_HEAT_P 50 +BRD_HEAT_I 0.07 + +CAN_P1_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat new file mode 100644 index 00000000000000..5f031a2c46ef15 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat @@ -0,0 +1,70 @@ +# hw definition file for processing by chibios_hwdef.py +# for H743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 7100 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +FLASH_BOOTLOADER_LOAD_KB 128 + +PI5 LED_RED OUTPUT OPENDRAIN HIGH # red +PI7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +PI6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PF7 UART7_TX UART7 NODMA + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define BOOTLOADER_DEBUG SD7 + +# support flashing from SD card: +# power enable pins +PG7 VDD_3V3_SD_CARD_EN OUTPUT LOW + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define FATFS_HAL_DEVICE SDCD1 + +DMA_PRIORITY SDMMC* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 + +# Add CS pins to ensure they are high in bootloader +PG10 IMU1_CS CS +PJ2 IMU2_CS CS +PI4 IMU3_CS CS +PE8 RM3100_CS CS +PE4 BAROMETER1_CS CS +PI9 BAROMETER2_CS CS +PK2 FRAM_CS CS +PE10 RESERVE_CS1 CS +PI14 RESERVE_CS2 CS +PI15 RESERVE_CS3 CS \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat new file mode 100644 index 00000000000000..31aeb7cb44673d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat @@ -0,0 +1,285 @@ +# hw definition file for processing by chibios_hwdef.py + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 7100 + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART1 USART3 UART8 UART4 OTG2 UART7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# UARTs +# USART2 is telem1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART6 is telem2 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +PG15 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# USART1 is GPS1 +PB15 USART1_RX USART1 NODMA +PB14 USART1_TX USART1 NODMA + +# UART3 is GPS2 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# RS232 +PH14 UART4_RX UART4 NODMA +PH13 UART4_TX UART4 NODMA + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PF7 UART7_TX UART7 NODMA + +# debug pins +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - sensors1 +PG11 SPI1_SCK SPI1 +PG9 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 - compass +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI4 - sensors2 - baro1 +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI6 - sensors3 - baro2 +PG13 SPI6_SCK SPI6 +PB4 SPI6_MISO SPI6 +PG14 SPI6_MOSI SPI6 + +# SPI5 - FRAM +PK0 SPI5_SCK SPI5 +PJ11 SPI5_MISO SPI5 +PJ10 SPI5_MOSI SPI5 + +# sensor CS +PG10 IMU1_CS CS +PJ2 IMU2_CS CS +PI4 IMU3_CS CS +PE8 RM3100_CS CS +PE4 BAROMETER1_CS CS +PI9 BAROMETER2_CS CS +PK2 FRAM_CS CS + +# RESERVE CS +PE10 RESERVE_CS1 CS +PI14 RESERVE_CS2 CS +PI15 RESERVE_CS3 CS + +# drdy pins +PH4 DRDY1_ADIS16470 INPUT GPIO(93) +PH10 DRDY2_ICM42688 INPUT +PE9 DRDY3_RM3100 INPUT +PH5 DRDY4_ICM42688 INPUT + +# use GPIO(93) for data ready on ADIS16470 +define ADIS_DRDY_PIN 93 + +# I2C buses + +# I2C1 is on I2C1 port +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 on I2C2 port +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3 is on GPS2 port +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 is on GPS1 port +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C1 I2C2 I2C3 I2C4 + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE +define HAL_I2C_INTERNAL_MASK 0 + +# enable pins +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PD11 VDD_5V_HIPOWER_EN OUTPUT LOW +PG4 VDD_5V_PERIPH_EN OUTPUT LOW + +PD10 VDD_5V_RC_EN OUTPUT HIGH +PG7 VDD_3V3_SD_CARD_EN OUTPUT LOW + +# PWM AUX channels +PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PB3 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PB10 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PK1 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PJ9 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR +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) +PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA + +# PWM output for buzzer +PE5 TIM15_CH1 TIM15 GPIO(77) ALARM + +# RC input +PB1 TIM3_CH4 TIM3 RCININT PULLDOWN LOW + +# analog in +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PF11 BATT_CURRENT_SENS ADC1 SCALE(1) + +PA5 SPARE1_ADC1 ADC1 SCALE(1) +PA6 SPARE2_ADC1 ADC1 SCALE(2) + +PB0 RSSI_IN ADC1 SCALE(1) + +PC0 VDD_5V_SENS ADC1 SCALE(2) +PC2 SCALED_V3V3 ADC1 SCALE(2) + +PF12 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs +PA8 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +PG1 VDD_BRICK_nVALID INPUT PULLUP +PG2 VDD_BRICK2_nVALID INPUT PULLUP +PG0 VBUS_nVALID INPUT PULLUP +PJ3 VDD_5V_HIPOWER_nOC INPUT PULLUP +PJ4 VDD_5V_PERIPH_nOC INPUT PULLUP + +# SPI devices +SPIDEV adis16470 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 2*MHZ +SPIDEV imu1_res SPI1 DEVID2 RESERVE_CS1 MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI2 DEVID1 RM3100_CS MODE3 1*MHZ 1*MHZ +SPIDEV imu2 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV baro1 SPI4 DEVID2 BAROMETER1_CS MODE3 20*MHZ 20*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV imu3 SPI6 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ +SPIDEV baro2 SPI6 DEVID2 BAROMETER2_CS MODE3 20*MHZ 20*MHZ + +# two baro +BARO MS56XX SPI:baro1 +BARO MS56XX SPI:baro2 + +# three IMUs +IMU ADIS1647x SPI:adis16470 ROTATION_PITCH_180_YAW_270 ADIS_DRDY_PIN +IMU Invensensev3 SPI:imu1_res ROTATION_PITCH_180_YAW_270 +IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_270 +IMU Invensensev3 SPI:imu3 ROTATION_PITCH_180 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# compasses + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# red LED marked as B/E +PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 + +# use pixracer style 3-LED indicators +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# 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 +PE2 LED_SAFETY OUTPUT +PI13 SAFETY_IN INPUT PULLDOWN + +# build ABIN for flash-from-bootloader support: +env BUILD_ABIN False + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +DMA_PRIORITY ADC* SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* + +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_CURR_PIN 2 +define HAL_BATT_VOLT_PIN 16 +define HAL_BATT_CURR_SCALE 60.61 +define HAL_BATT_VOLT_SCALE 15.7 + +# setup the parameter for the ADC rssi +define BOARD_RSSI_ANA_PIN 9 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_BottomPort.png b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_BottomPort.png new file mode 100644 index 00000000000000..7114edcc9b2f4d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_BottomPort.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_TopPort.png b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_TopPort.png new file mode 100644 index 00000000000000..83ff77e19934a1 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/AP-H743v2_TopPort.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/README.md new file mode 100644 index 00000000000000..8c23137a9e396b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/README.md @@ -0,0 +1,97 @@ +# AP-H743v2 Flight Controller + +The AP-H743v2 is a flight controller designed and produced by X-MAV + +## Features + + - STM32H743 microcontroller + - BMI088/ICM42688P dual IMUs + - DPS310 barometer + - IST8310 magnetometer + - AT7456E OSD + - 9V 3A BEC; 5V 3A BEC + - MicroSD Card Slot + - 8 UARTs + - 8 PWM outputs + - 1 CAN + - 1 I2C + - 1 SWD + +## Physical + +![X-MAV AP-H743v2 Front View](AP-H743v2_TopPort.png) + +![X-MAV AP-H743v2 Back View](AP-H743v2_BottomPort.png) + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART2 (MAVLink2) + - SERIAL2 -> UART4 (User) + - SERIAL3 -> UART1 (GPS) + - SERIAL4 -> UART6 (User) + - SERIAL5 -> UART8 (User) + - SERIAL6 -> UART3 (DisplayPort) + - SERIAL7 -> UART5 (RCIN) + - SERIAL8 -> UART7 (RX only, ESC Telemetry) + + +## RC Input + +The default RC input is configured on the UART5 and supports all RC protocols except PPM. The SBUS pin is inverted and connected to RX5. When using RX5 or SBUS, the other input should be unconnected. RC can be attached to any UART port as long as the serial port protocol is set to `SERIALn_PROTOCOL=23` and SERIAL7_Protocol is changed to something other than '23'. + + +## OSD Support + +The AP-H743v2 supports onboard analog SD OSD using a MAX7456 chip. Simultaneously, DisplayPort HD OSD is available on the DJI connector for HD VTX. Both on board OSD and DisplayPort OSD can be operated simultaneously. + + + +## VTX Support + +The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The AP-H743v2 supports up to 8 PWM outputs. + +All the channels support DShot and BiDir DShot. + +Outputs are grouped and every output within a group must use the same output protocol: + + +1, 2, 3, 4 are Group 1; + +5, 6 are Group 2; + +7, 8 are Group 3; + +## 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 4 + - BATT_CURR_PIN 8 + - BATT_VOLT_MULT 10.2 + - BATT_CURR_SCALE 20.4 + +## Compass + +The AP-H743v2 has a built-in compass sensor (IST8310), and you can also attach an external compass using I2C on the SDA and SCL connector. + +## Mechanical + + - Mounting: 30.5 x 30.5mm, Φ4mm + - Dimensions: 36 x 36 x 8 mm + - Weight: 9g + +## 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 favorite 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/X-MAV-AP-H743v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef-bl.dat new file mode 100644 index 00000000000000..3749272a13644b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef-bl.dat @@ -0,0 +1,57 @@ +# hw definition file for processing by chibios_hwdef.py +# for the X-MAV-AP-H743V2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_X-MAV-AP-H743V2 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# flash size +FLASH_SIZE_KB 2048 + +# 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 + + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS +PC13 ICM42688P_CS CS + +# LEDs +PD11 LED_ACTIVITY OUTPUT HIGH GPIO(91) #green +PB15 LED_BOOTLOADER OUTPUT HIGH GPIO(92) #blue +define HAL_LED_ON 1 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef.dat new file mode 100644 index 00000000000000..231afa6a4fd55a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef.dat @@ -0,0 +1,184 @@ +# hw definition file for processing by chibios_hwdef.py +# for the X-MAV-AP-H743V2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_X-MAV-AP-H743V2 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# flash size +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART8 USART3 UART5 UART7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PE15 VBUS INPUT OPENDRAIN + +# Serial1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 + +# Serial2 +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# GPS1/Serial3 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# Serial4 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +# Serial5 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# DJI O3/Serial6 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# RC_INPUT/Serial7 +PB13 UART5_TX UART5 +PB12 UART5_RX UART5 +PD14 SBUS_INV OUTPUT LOW + +# ESC/Serial8 +PE7 UART7_RX UART7 + +# SWD +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CAN +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# two I2C bus +I2C_ORDER I2C1 I2C4 + +# I2C1 - baro +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C4 - CONNECTOR +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# PWM output pins +PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR +PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PB1 TIM3_CH4 TIM3 PWM(5) GPIO(54) BIDIR +PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) +PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR +PB11 TIM2_CH4 TIM2 PWM(8) GPIO(57) + +# GPIOs +PA4 PINIO1 OUTPUT GPIO(81) LOW +PC1 PINIO2 OUTPUT GPIO(82) LOW +PC0 PINIO3 OUTPUT GPIO(83) LOW + +# LEDs +PD15 LED_RED OUTPUT HIGH GPIO(90) +PD11 LED_GREEN OUTPUT HIGH GPIO(91) +PB15 LED_BLUE OUTPUT HIGH GPIO(92) + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 + +define HAL_GPIO_LED_ON 1 +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# ADC for Power +PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC5 BATT_CURRENT_SENS ADC2 SCALE(1) + +#BATTERY MONITOR ON +define BATT_MONITOR 4 +define HAL_BATT_VOLT_PIN 4 +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_VOLT_SCALE 10.2 +define HAL_BATT_CURR_SCALE 20.4 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# SPI1 - IMU0 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS + +# SPI3 - CONNECTOR +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 +PA15 AT7456E_CS CS + +# SPI4 - IMU1 +PE6 SPI4_MOSI SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PC13 ICM42688P_CS CS + +# barometers +BARO DPS310 I2C:0:0x76 + +# SPI devices +SPIDEV imu0_a SPI1 DEVID1 BMI088_1_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu0_g SPI1 DEVID2 BMI088_1_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu1 SPI4 DEVID3 ICM42688P_CS MODE3 10*MHZ 10*MHZ +SPIDEV osd SPI3 DEVID5 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# 2 IMUs +IMU BMI088 SPI:imu0_a SPI:imu0_g ROTATION_ROLL_180_YAW_90 +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +# compasses +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +#Serial Port defaults +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_MSP_DisplayPort +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_RCIN +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry + + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 5 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat index f885b7ff371eea..44d160c86d2dae 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat @@ -154,12 +154,12 @@ PE12 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PE15 LED_G1 OUTPUT OPENDRAIN HIGH GPIO(1) PB9 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat index 7a541d4e8e0483..b621c4973af081 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat @@ -167,12 +167,12 @@ PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 @@ -227,9 +227,6 @@ PD2 SDMMC1_CMD SDMMC1 # 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" - # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat index 1072cba1a83f8f..8b97b5cceb808f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat @@ -174,12 +174,12 @@ PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 @@ -226,9 +226,6 @@ PD2 SDMMC1_CMD SDMMC1 # 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" - # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6Ultra/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6Ultra/hwdef.dat index 744f7f2187b137..0f643b86b9f460 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6Ultra/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6Ultra/hwdef.dat @@ -186,12 +186,12 @@ PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) -define HAL_GPIO_A_LED_PIN 0 -define HAL_GPIO_B_LED_PIN 1 -define HAL_GPIO_C_LED_PIN 2 +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2 # use pixracer style 3-LED indicators -define HAL_HAVE_PIXRACER_LED +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 @@ -242,9 +242,6 @@ PD2 SDMMC1_CMD SDMMC1 # 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" - # enable RAMTROM parameter storage define HAL_STORAGE_SIZE 32768 define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/README.md b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/README.md new file mode 100644 index 00000000000000..0c34e35e269be7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/README.md @@ -0,0 +1,103 @@ +## ZeroOneX6 Flight Controller +The ZeroOne X6 is a flight controller manufactured by ZeroOne, which is based on the open-source FMU v6X architecture and Pixhawk Autopilot Bus open source specifications. +![Uploading ZeroOneX6.jpg…]() + + +## Features: +- Separate flight control core design. +- MCU + STM32H753IIK6 32-bit processor running at 480MHz + 2MB Flash + 1MB RAM +- IO MCU + STM32F103 +- Sensors +- IMU: + Internal Vibration Isolation for IMUs + IMU constant temperature heating(1 W heating power). + With Triple Synced IMUs, BalancedGyro technology, low noise and more shock-resistant: + IMU1-ICM45686(With vibration isolation) + IMU2-BMI088(With vibration isolation) + IMU3- ICM45686(No vibration isolation) +- Baro: + Two barometers:2 x ICP20100 + Magnetometer: Builtin RM3100 magnetometer + +## Pinout +![ZeroOneX6 Pinout](https://github.com/ZeroOne-Aero/ardupilot/blob/zeroOneBootLoader/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6Pinout.jpg "ZeroOneX6") + + +## 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 | Function | MCU PINS | DMA | +| :-----: | :------: | :------: | :------:| +| SERIAL0 | OTG1 | USB | +| SERIAL1 | Telem1 | UART7 |DMA Enabled | +| SERIAL2 | Telem2 | UART5 |DMA Enabled | +| SERIAL3 | GPS1 | USART1 |DMA Enabled | +| SERIAL4 | GPS2 | UART8 |DMA Enabled | +| SERIAL5 | Telem3 | USART2 |DMA Enabled | +| SERIAL6 | UART4 | UART4 |DMA Enabled | +| SERIAL7 |FMU DEBUG | USART3 |DMA Enabled | +| SERIAL8 | OTG-SLCAN| USB | + +## RC Input +The remote control signal should be connected to the SBUS RC IN port or DSM/PPM RC Port.It will support ALL unidirectional RC protocols. + +## PWM Output +The X6 flight controller supports up to 16 PWM outputs. +First 8 outputs (labelled 1 to 8) are controlled by a dedicated STM32F103 IO controller. +The remaining 8 outputs (labelled 9 to 16) are the "auxiliary" outputs. These are directly attached to the STM32H753 FMU controller . +All 16 outputs support normal PWM output formats. All 16 outputs support DShot, except 15 and 16. + +The 8 IO PWM outputs are in 4 groups: +- Outputs 1 and 2 in group1 +- Outputs 3 and 4 in group2 +- Outputs 5, 6, 7 and 8 in group3 + +The 8 FMU PWM outputs are in 4 groups: +- Outputs 1, 2, 3 and 4 in group1 +- Outputs 5 and 6 in group2 +- Outputs 7 and 8 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. + +## GPIO +All PWM outputs can be used as GPIOs (relays, camera, RPM etc). To use them you need to set the output’s SERVOx_FUNCTION to -1. The numbering of the GPIOs for PIN variables in ArduPilot is: + + + + + + + + + + + + + + + + + +
IO Pins FMU Pins
Name Value Option Name Value Option
M1 101 MainOut1 M9 50 AuxOut1
M2 102 MainOut2 M10 51 AuxOut2
M3 103 MainOut3 M11 52 AuxOut3
M4 104 MainOut4 M12 53 AuxOut4
M5 105 MainOut5 M13 54 AuxOut5
M6 106 MainOut6 M14 55 AuxOut6
M7 107 MainOut7 M15 56
M8 108 MainOut8 M16 57 BB Blue GPo pin 3
FCU CAP 58
+ +## Battery Monitoring +The X6 flight controller has two six-pin power connectors, supporting CAN interface power supply. +These are set by default in the firmware and shouldn't need to be adjusted. + +## Compass +The X6 flight controller built-in industrial-grade electronic compass chip RM3100. + +## Analog inputs +The X6 flight controller has 2 analog inputs. +- ADC Pin12 -> ADC 6.6V Sense +- ADC Pin13 -> ADC 3.3V Sense +- RSSI input pin = 103 + +## 5V PWM Voltage  +The X6 flight controller supports switching between 5V and 3.3V PWM levels. Switch PWM output pulse level by configuring parameter BRD_PWM_VOL_SEL. 0 for 3.3V and 1 for 5V output. + +## Where to Buy +https://www.01aero.cn diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.jpg new file mode 100644 index 00000000000000..60a0558f1753b9 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.png b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.png new file mode 100644 index 00000000000000..a2060ec4a1b70e Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6Pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6Pinout.jpg new file mode 100644 index 00000000000000..568a6686c5888d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/ZeroOneX6Pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/defaults.parm new file mode 100644 index 00000000000000..ffd8b6947c9087 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/defaults.parm @@ -0,0 +1,5 @@ +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 1 + +BATT_MONITOR 8 +GPS1_TYPE 9 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef-bl.dat new file mode 100644 index 00000000000000..0df8267ef48f91 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef-bl.dat @@ -0,0 +1,106 @@ +# hw definition file for processing by chibios_hwdef.py +# for the ZeroOneX6 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 5600 + +# 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 + +# Pin for PWM Voltage Selection +PG6 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) + +# 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 + +# support flashing from SD card: +# power enable pins +PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 + +# 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 + +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 AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef.dat new file mode 100644 index 00000000000000..c85cff4eb7e05c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZeroOneX6/hwdef.dat @@ -0,0 +1,343 @@ +# hw definition file for processing by chibios_hwdef.py +# for the ZeroOne X6 hardware + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# 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 5600 + +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 + +# supports upto 8MBits/s +CANFD_SUPPORTED 8 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 + +# 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 +#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_MAVLink2 + +# 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 + +# Ethernet +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PG13 ETH_RMII_TXD0 ETH1 +PG12 ETH_RMII_TXD1 ETH1 +PB11 ETH_RMII_TX_EN ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 +#PG15 ETH_POWER_EN ETH1 + +PG15 Ethernet_PWR_EN OUTPUT HIGH # disable power on ethernet + +define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_RMII + +# 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 - IMU3 ICM45686 +PA5 SPI1_SCK SPI1 +PB5 SPI1_MOSI SPI1 +PG9 SPI1_MISO SPI1 +PI9 SP1_CS1 CS + +# SPI2 -IMU1 ICM45686 +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 +PH5 SP2_CS1 CS +PA10 SP2_DRDY2 INPUT + +# SPI3 -IMU2 BMI088 +PB2 SPI3_MOSI SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PI4 SP3_CS1 CS +PI8 SP3_CS2 CS +PI6 SP3_DRDY1 INPUT +PI7 SP3_DRDY2 INPUT GPIO(93) +define SP3_DRDY2 93 + +# SPI4 - unused +#PE12 SPI4_SCK SPI4 +#PE13 SPI4_MISO SPI4 +#PE14 SPI4_MOSI SPI4 +#PF3 SP4_DRDY1 INPUT +PH15 SP4_CS1 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) + +# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v +PG6 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) +define HAL_GPIO_PWM_VOLT_PIN 3 +define HAL_GPIO_PWM_VOLT_3v3 0 + +# 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 + +# 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 + +# start peripheral power on +PG10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW + +# 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 + +# GPIO 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 + +define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90 +define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91 +define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92 + +define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1 + +# 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 (ZeroOne X6) +BARO ICP201XX I2C:0:0x64 +BARO ICP201XX I2C:2:0x63 + +# compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# builtin compass on ZeroOne X6 +COMPASS RM3100 I2C:0:0x20 false ROTATION_PITCH_180 + +# compensate for magnetic field generated by the heater on ZeroOne X6 RM3100 +define HAL_HEATER_MAG_OFFSET_RM3100 AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0x20,0x11),Vector3f(0,0,0) + +#define HAL_HEATER_MAG_OFFSET HAL_HEATER_MAG_OFFSET_RM3100 + +# IMU devices for ZeroOne X6 +SPIDEV icm45686_1 SPI2 DEVID1 SP2_CS1 MODE3 2*MHZ 16*MHZ +SPIDEV bmi088_g SPI3 DEVID1 SP3_CS2 MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI3 DEVID2 SP3_CS1 MODE3 10*MHZ 10*MHZ +SPIDEV icm45686_2 SPI1 DEVID1 SP1_CS1 MODE3 2*MHZ 16*MHZ + +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# ZeroOne X6 3 IMUs +IMU Invensensev3 SPI:icm45686_1 ROTATION_ROLL_180_YAW_270 +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 +IMU Invensensev3 SPI:icm45686_2 ROTATION_NONE + +define HAL_INS_HIGHRES_SAMPLE 7 +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# 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 TIM5* TIM4* SPI1* SPI2* SPI3* SDMMC* USART6* ADC* UART* USART* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_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 + +# build ABIN for flash-from-bootloader support: +env BUILD_ABIN True + +# enable support for dshot on iomcu +#github suggestion +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_highpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 +#V6X +#ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin +#define HAL_WITH_IO_MCU_BIDIR_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat index 6b74e3529ff719..6ac45e7d003631 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat @@ -87,8 +87,6 @@ define HAL_UART_MIN_RX_SIZE 128 define HAL_UART_STACK_SIZE 256 define STORAGE_THD_WA_SIZE 512 -define HAL_NO_MONITOR_THREAD - 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 260885221c8d6d..662e6d4cc571bc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -130,9 +130,6 @@ BARO MS56XX SPI:ms5611 define HAL_BARO_ALLOW_INIT_NO_BARO - -define HAL_NO_MONITOR_THREAD - define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat index f8cadff4e2e8cd..e1c7ddacac9e31 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat @@ -98,7 +98,8 @@ define HAL_BATT_CURR_PIN 11 define HAL_BATT_VOLT_SCALE 11 define HAL_BATT_CURR_SCALE 18.2 -define HAL_GPIO_A_LED_PIN 57 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 57 # 64kB FLASH_RESERVE_START_KB means we're lacking a lot of space: include ../include/minimize_features.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c index 99c48dfd6d5fb8..618fe597ac1fa4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c @@ -269,6 +269,9 @@ void __early_init(void) { STM32_NOCACHE_MPU_REGION_2_SIZE | MPU_RASR_ENABLE); #endif +#if defined(DUAL_CORE) + stm32_disable_cm4_core(); // disable second core +#endif #endif } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 893b358f549685..9d30c86701c856 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -9,7 +9,7 @@ ifeq ($(USE_OPT),) endif ifeq ($(ENABLE_DEBUG_SYMBOLS), yes) - USE_OPT += -g + USE_OPT += -g3 endif # C specific options here (added to USE_OPT). diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld index 8843b69dde6826..fe873acf1ca6cb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld @@ -105,8 +105,8 @@ SECTIONS . = ALIGN(4); __ram3_init_text__ = LOADADDR(.fastramfunc); __ram3_init__ = .; - /* ChibiOS won't boot unless these are excluded */ - EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *board.o) + /* ChibiOS won't boot unless some of these are excluded */ + EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *board.o *chprintf.o) /* performance critical sections of ChibiOS */ *libch.a:ch*.*(.text*) *libch.a:nvic.*(.text*) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h730.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h730.ld index d46fadcf7ca3a4..a0d7451d19c2aa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h730.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h730.ld @@ -106,8 +106,8 @@ SECTIONS __ram3_init_text__ = LOADADDR(.fastramfunc); __ram3_init__ = .; /* performance critical sections of ChibiOS */ - /* ChibiOS won't boot unless these are excluded */ - EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o) *libch.a:ch*.*(.text*) + /* ChibiOS won't boot unless some of these are excluded */ + EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *chprintf.o) *libch.a:ch*.*(.text*) *libch.a:nvic.*(.text*) *libch.a:bouncebuffer.*(.text*) *libch.a:stm32_util.*(.text*) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld index ab1f170f43ff60..ebe47db4a82114 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld @@ -106,8 +106,8 @@ SECTIONS __ram3_init_text__ = LOADADDR(.fastramfunc); __ram3_init__ = .; /* performance critical sections of ChibiOS */ - /* ChibiOS won't boot unless these are excluded */ - EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o) *libch.a:ch*.*(.text*) + /* ChibiOS won't boot unless some of these are excluded */ + EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *chprintf.o) *libch.a:ch*.*(.text*) *libch.a:nvic.*(.text*) *libch.a:bouncebuffer.*(.text*) *libch.a:stm32_util.*(.text*) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c b/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c index 8c60109e8b0cad..49e3d9f131a116 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c @@ -97,7 +97,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void); const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void) { // do a full dump if on serial - static CrashCatcherMemoryRegion regions[60] = { + static CrashCatcherMemoryRegion regions[80] = { {(uint32_t)&__ram0_start__, (uint32_t)&__ram0_end__, CRASH_CATCHER_BYTE}, {(uint32_t)&ch_system, (uint32_t)&ch_system + sizeof(ch_system), CRASH_CATCHER_BYTE}}; uint32_t total_dump_size = dump_size + buf_off + REMAINDER_MEM_REGION_SIZE; @@ -138,7 +138,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void) // log statically alocated memory int32_t bss_size = ((uint32_t)&__bss_end__) - ((uint32_t)&__bss_base__); int32_t available_space = stm32_crash_dump_max_size() - total_dump_size; - if (available_space < 0) { + if (available_space < 0 || curr_region >= (ARRAY_SIZE(regions) - 1)) { // we can't log anymore than this goto finalise; } @@ -157,7 +157,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void) // dump the Heap as well as much as we can int32_t heap_size = ((uint32_t)&__heap_end__) - ((uint32_t)&__heap_base__); available_space = stm32_crash_dump_max_size() - total_dump_size; - if (available_space < 0) { + if (available_space < 0 || curr_region >= (ARRAY_SIZE(regions) - 1)) { // we can't log anymore than this goto finalise; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 3f81cc9ce1ef99..74fcd2f0281fbf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -452,6 +452,65 @@ bool stm32_flash_ispageerased(uint32_t page) static uint32_t last_erase_ms; #endif +#if defined(STM32H7) + +/* + corrupt a flash to trigger ECC fault +*/ +void stm32_flash_corrupt(uint32_t addr) +{ + stm32_flash_unlock(); + + volatile uint32_t *CR = &FLASH->CR1; + volatile uint32_t *CCR = &FLASH->CCR1; + volatile uint32_t *SR = &FLASH->SR1; +#if STM32_FLASH_NBANKS > 1 + if (addr - STM32_FLASH_BASE >= STM32_FLASH_FIXED_PAGE_PER_BANK * STM32_FLASH_FIXED_PAGE_SIZE * 1024) { + CR = &FLASH->CR2; + CCR = &FLASH->CCR2; + SR = &FLASH->SR2; + } +#endif + stm32_flash_wait_idle(); + + *CCR = ~0; + *CR |= FLASH_CR_PG; + + for (uint32_t i=0; i<2; i++) { + while (*SR & (FLASH_SR_BSY|FLASH_SR_QW)) ; + putreg32(0xAAAA5555, addr); + if (*SR & FLASH_SR_INCERR) { + // clear the error + *SR &= ~FLASH_SR_INCERR; + } + addr += 4; + } + + *CR |= FLASH_CR_FW; // force write + stm32_flash_wait_idle(); + + for (uint32_t i=0; i<2; i++) { + while (*SR & (FLASH_SR_BSY|FLASH_SR_QW)) ; + putreg32(0x5555AAAA, addr); + if (*SR & FLASH_SR_INCERR) { + // clear the error + *SR &= ~FLASH_SR_INCERR; + } + addr += 4; + } + + *CR |= FLASH_CR_FW; // force write + stm32_flash_wait_idle(); + __DSB(); + + stm32_flash_wait_idle(); + *CCR = ~0; + *CR &= ~FLASH_CR_PG; + + stm32_flash_lock(); +} +#endif + /* erase a page */ @@ -520,10 +579,16 @@ bool stm32_flash_erasepage(uint32_t page) FLASH->CR |= FLASH_CR_STRT; #elif defined(STM32G4) FLASH->CR = FLASH_CR_PER; - // rather oddly, PNB is a 7 bit field that the ref manual says can - // contain 8 bits we assume that for 512k single bank devices - // there is an 8th bit +#ifdef FLASH_CR_BKER_Pos + /* + we assume dual bank mode, we set the bottom 7 bits of the page + into PNB and the 8th bit into BKER + */ + FLASH->CR |= (page&0x7F)<>7)<CR |= page<CR |= FLASH_CR_STRT; #elif defined(STM32L4PLUS) FLASH->CR |= FLASH_CR_PER; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.h b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.h index 7ec7c17031a2af..cbc7233aa6defe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.h @@ -30,6 +30,9 @@ bool stm32_flash_ispageerased(uint32_t page); void stm32_flash_protect_flash(bool bootloader, bool protect); void stm32_flash_unprotect_flash(void); void stm32_flash_set_NRST_MODE(uint8_t nrst_mode); +#if defined(STM32H7) +void stm32_flash_corrupt(uint32_t addr); +#endif #ifndef HAL_BOOTLOADER_BUILD bool stm32_flash_recent_erase(void); #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stdio.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stdio.h index 37bcb942eaa902..983daba0f74ff3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stdio.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stdio.h @@ -48,8 +48,6 @@ void *realloc(void* ptr, size_t size) __attribute__((deprecated)); extern int (*vprintf_console_hook)(const char *fmt, va_list arg); void malloc_check(const void *ptr); -#define L_tmpnam 32 - #ifdef __cplusplus } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index c91e68930f547f..755290b765d919 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -581,3 +581,31 @@ bool check_limit_flash_1M(void) return false; } #endif + + +#if defined(DUAL_CORE) +void stm32_disable_cm4_core() { + // Turn off second core for now + if ((FLASH->OPTSR_CUR & FLASH_OPTSR_BCM4)) { + //unlock flash + if (FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) { + /* Unlock sequence */ + FLASH->OPTKEYR = 0x08192A3B; + FLASH->OPTKEYR = 0x4C5D6E7F; + } + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + // disable core boot + FLASH->OPTSR_PRG &= ~FLASH_OPTSR_BCM4; + // start programming + FLASH->OPTCR |= FLASH_OPTCR_OPTSTART; + // wait for completion by checking busy bit + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + // lock flash + FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; + while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) { + } + } +} +#endif // DUAL_CORE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 828ceed09ca69a..7d78d41b82b15b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -191,6 +191,8 @@ extern stkalign_t __main_stack_end__; extern stkalign_t __main_thread_stack_base__; extern stkalign_t __main_thread_stack_end__; +void stm32_disable_cm4_core(void); + #ifdef __cplusplus } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 8268c4853f412d..e615ce33ab6ea0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -86,6 +86,8 @@ #define STM32_PWR_CR2 (PWR_CR2_BREN) #ifdef SMPS_PWR #define STM32_PWR_CR3 (PWR_CR3_SMPSEN | PWR_CR3_USB33DEN) +#elif defined(SMPS_EXT) +#define STM32_PWR_CR3 (PWR_CR3_BYPASS | PWR_CR3_USB33DEN) #else #define STM32_PWR_CR3 (PWR_CR3_LDOEN | PWR_CR3_USB33DEN) #endif @@ -200,6 +202,9 @@ #if HAL_CUSTOM_MCU_CLOCKRATE == 480000000 #define STM32_PLL1_DIVN_VALUE 120 #define STM32_PLL1_DIVQ_VALUE 12 +#elif HAL_CUSTOM_MCU_CLOCKRATE == 200000000 +#define STM32_PLL1_DIVN_VALUE 50 +#define STM32_PLL1_DIVQ_VALUE 5 #else #error "Unable to configure custom clockrate" #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c index eed51ebae3ea3e..e734179820926d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.c @@ -251,6 +251,18 @@ uint32_t get_usb_baud(uint16_t endpoint_id) } return 0; } + +/* + get the requested usb parity. Valid if get_usb_baud() returned non-zero +*/ +uint8_t get_usb_parity(uint16_t endpoint_id) +{ + if (endpoint_id == 0) { + return linecoding.bParityType; + } + + return 0; +} #endif /** * @brief IN EP1 state. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.h b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.h index 2add6e6c7f9bbf..79fa3446cb9b48 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg.h @@ -46,6 +46,7 @@ extern SerialUSBDriver SDU2; extern const SerialUSBConfig serusbcfg2; #endif //HAL_HAVE_DUAL_USB_CDC uint32_t get_usb_baud(uint16_t endpoint_id); +uint8_t get_usb_parity(uint16_t endpoint_id); #endif #define USB_DESC_MAX_STRLEN 100 void setup_usb_strings(void); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c index cb1a127287ca11..e3dab2bc2649d2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/usbcfg_dualcdc.c @@ -315,6 +315,19 @@ uint32_t get_usb_baud(uint16_t endpoint_id) } return 0; } + +/* + get the requested usb parity. Valid if get_usb_baud() returned non-zero +*/ +uint8_t get_usb_parity(uint16_t endpoint_id) +{ + for (uint8_t i = 0; i < ARRAY_SIZE(linecoding); i++) { + if (endpoint_id == ep_index[i]) { + return linecoding[i].bParityType; + } + } + return 0; +} #endif /** * @brief IN EP1 state. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c index c1a5eeb0493a97..689f9e4acc1c84 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c @@ -22,6 +22,16 @@ #error "Unsupported IWDG RCC MCU config" #endif +/* + define for controlling how long the watchdog is set for. +*/ +#ifndef STM32_WDG_TIMEOUT_MS +#define STM32_WDG_TIMEOUT_MS 2048 +#endif +#if STM32_WDG_TIMEOUT_MS > 4096 || STM32_WDG_TIMEOUT_MS < 20 +#error "Watchdog timeout out of range" +#endif + /* defines for working out if the reset was from the watchdog */ @@ -68,16 +78,17 @@ static bool watchdog_enabled; */ void stm32_watchdog_init(void) { - // setup for 2s reset + // setup the watchdog timeout + // t = 4 * 2^PR * (RLR+1) / 32KHz IWDGD.KR = 0x5555; - IWDGD.PR = 2; // div16 - IWDGD.RLR = 0xFFF; + IWDGD.PR = 3; // changing this would change the definition of STM32_WDG_TIMEOUT_MS + IWDGD.RLR = STM32_WDG_TIMEOUT_MS - 1; IWDGD.KR = 0xCCCC; watchdog_enabled = true; } /* - pat the dog, to prevent a reset. If not called for 1s + pat the dog, to prevent a reset. If not called for STM32_WDG_TIMEOUT_MS after stm32_watchdog_init() then MCU will reset */ void stm32_watchdog_pat(void) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h index f015dee9c1a135..de8e3941494b08 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h @@ -10,7 +10,7 @@ extern "C" { void stm32_watchdog_init(void); /* - pat the dog, to prevent a reset. If not called for 1s + pat the dog, to prevent a reset. If not called for STM32_WDG_TIMEOUT_MS after stm32_watchdog_init() then MCU will reset */ void stm32_watchdog_pat(void); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat index fa460f05c985c4..59f175d8428a0d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat @@ -1,10 +1,18 @@ include ../f103-periph/hwdef.inc -# and support all external compass types define HAL_PROBE_EXTERNAL_I2C_COMPASSES -# .... except BMM150: -define AP_COMPASS_BMM150_ENABLED 0 + +# support an expliclty defined set of compasses: +define AP_COMPASS_BACKEND_DEFAULT_ENABLED 0 +define AP_COMPASS_AK09916_ENABLED 1 +define AP_COMPASS_HMC5843_ENABLED 1 +define AP_COMPASS_IST8308_ENABLED 1 +define AP_COMPASS_IST8310_ENABLED 1 +define AP_COMPASS_LIS3MDL_ENABLED 1 +define AP_COMPASS_MMC3416_ENABLED 1 +define AP_COMPASS_QMC5883L_ENABLED 1 +define AP_COMPASS_RM3100_ENABLED 1 # increase TX size for RTCM undef HAL_UART_MIN_TX_SIZE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc index 7c076f657e6279..aa854499da5dbb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc @@ -98,9 +98,6 @@ define HAL_UART_STACK_SIZE 256 define STORAGE_THD_WA_SIZE 300 define IO_THD_WA_SIZE 300 -define HAL_NO_MONITOR_THREAD - - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index eee005173a0188..ffb9ae90aaf4cf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -142,3 +142,5 @@ define GPS_MAX_RATE_MS 200 # 10" DLVR sensor by default define HAL_AIRSPEED_TYPE_DEFAULT 9 define AIRSPEED_MAX_SENSORS 1 + +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc index bc022599a8e375..9306a674b1673a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc @@ -122,3 +122,5 @@ env ROMFS_UNCOMPRESSED True # reduce the number of CAN RX Buffer define HAL_CAN_RX_QUEUE_SIZE 64 + +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index 41e003499c9bbb..e2fb65b9ee147d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -43,8 +43,6 @@ define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 -define HAL_NO_MONITOR_THREAD - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat index 3d997e90986bd8..a40aaeda38268a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat @@ -279,9 +279,9 @@ PC6 LED_GREEN OUTPUT GPIO(91) LOW PC7 LED_BLUE OUTPUT GPIO(92) HIGH # setup for BoardLED2 +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 90 define HAL_GPIO_B_LED_PIN 92 -define HAL_GPIO_LED_ON 0 # enable RAMTROM parameter storage diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc deleted file mode 100644 index cd519bdd32839b..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc +++ /dev/null @@ -1,7 +0,0 @@ -# include file to reduce flash by including less GPS drivers - -define AP_GPS_BACKEND_DEFAULT_ENABLED 0 -define AP_GPS_UBLOX_ENABLED 1 -define AP_GPS_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS -undef HAL_MSP_GPS_ENABLED -define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc index 8047ea538c07ec..3c6e149ee06ec9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc @@ -101,8 +101,7 @@ define AP_LANDINGGEAR_ENABLED APM_BUILD_COPTER_OR_HELI # Plane-specific defines; these defines are only used in the Plane # directory, but are seen across the entire codebase: -define OFFBOARD_GUIDED 0 -define QAUTOTUNE_ENABLED 0 +define AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED 0 # Copter-specific defines; these defines are only used in the Copter # directory, but are seen across the entire codebase: @@ -133,3 +132,7 @@ define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS define AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED 0 # don't need the payload place flight behaviour either: define AC_PAYLOAD_PLACE_ENABLED 0 + +# disable extra camera messages +define AP_CAMERA_INFO_FROM_SCRIPT_ENABLED 0 +define AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc index 11be0caeab143f..71dafdf4a2c7de 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc @@ -28,3 +28,7 @@ define AP_TRAMP_ENABLED AP_VIDEOTX_ENABLED && OSD_ENABLED # force CRSF Telem text support even in face of normal 1MB limit: define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED OSD_ENABLED && OSD_PARAM_ENABLED && HAL_CRSF_TELEM_ENABLED + +# disable SMBUS battery monitors to save flash +undef AP_BATTERY_SMBUS_ENABLED +define AP_BATTERY_SMBUS_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/network_PPPGW.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/network_PPPGW.inc index c49bfa387cc845..b38e455947e85d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/network_PPPGW.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/network_PPPGW.inc @@ -5,6 +5,7 @@ define HAL_PERIPH_ENABLE_RTC define HAL_PERIPH_ENABLE_SERIAL_OPTIONS define AP_NETWORKING_BACKEND_PPP 1 +define AP_NETWORKING_CAN_MCAST_ENABLED 1 define AP_PERIPH_NET_PPP_PORT_DEFAULT 1 define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/network_bootloader.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/network_bootloader.inc index 0703f3397a7f61..e634e315760506 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/network_bootloader.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/network_bootloader.inc @@ -11,6 +11,7 @@ define CH_CFG_USE_DYNAMIC 1 define CH_CFG_USE_WAITEXIT 1 define AP_NETWORKING_ENABLED 1 +define AP_NETWORKING_CAN_MCAST_ENABLED 1 ROMFS_WILDCARD Tools/AP_Bootloader/Web/*.html env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-8MHz-dshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-8MHz-dshot/hwdef.dat new file mode 100644 index 00000000000000..50d29b16d59b05 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-8MHz-dshot/hwdef.dat @@ -0,0 +1,11 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F103 STM32F103xB + +include ../iomcu-f103-dshot/hwdef.inc + +undef OSCILLATOR_HZ + +# crystal frequency +OSCILLATOR_HZ 8000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat index 10b71b35a9a0ad..75c9ae299a3441 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat @@ -3,48 +3,4 @@ # MCU class and specific type MCU STM32F103 STM32F103xB -include ../iomcu-dshot/hwdef.inc - -undef STM32_ST_USE_TIMER - -# directly define DMA channels -DMA_NOMAP 1 - -# only four timers on F103xB so use TIM1 for system timer -STM32_ST_USE_TIMER 1 - -define HAL_WITH_ESC_TELEM 1 - -undef PA0 PA1 PB8 PB9 - -# the order is important here as it determines the order that timers are used to sending dshot -# TIM4 needs to go first so that TIM4_UP can be freed up to be used by input capture for TIM2 -PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103) BIDIR UP_SHARED -PB9 TIM4_CH4 TIM4 PWM(4) GPIO(104) -PA0 TIM2_CH1 TIM2 PWM(1) GPIO(101) -PA1 TIM2_CH2 TIM2 PWM(2) GPIO(102) BIDIR # DMA channel 7, shared with TIM4_UP and USART2_TX - -# currently no support for having mixed outputs on the same timer -# PB1 TIM3_CH4 TIM3 PWM(8) GPIO(108) BIDIR # DMA channel 3, shared with TIM3_UP - -# TIM2_UP - (1,2) -# TIM4_UP - (1,7) -# TIM3_UP - (1,3) - -# TIM2_CH2 (PWM 1/2) -define STM32_TIM_TIM2_CH2_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) -define STM32_TIM_TIM2_CH2_DMA_CHAN 1 - -# TIM4_CH3 (PWM 3/4) -define STM32_TIM_TIM4_CH3_DMA_STREAM STM32_DMA_STREAM_ID(1, 5) -define STM32_TIM_TIM4_CH3_DMA_CHAN 1 - -# TIM3_CH4 (PWM 7-8) -define STM32_TIM_TIM3_CH4_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) -define STM32_TIM_TIM3_CH4_DMA_CHAN 1 - -undef SHARED_DMA_MASK -define SHARED_DMA_MASK (1U< 0: - # Allow lua to load from ROMFS if any lua files are added - for file in self.romfs.keys(): - if file.startswith("scripts") and file.endswith(".lua"): - f.write('#define HAL_HAVE_AP_ROMFS_EMBEDDED_LUA 1\n') - break - f.write('#define HAL_HAVE_AP_ROMFS_EMBEDDED_H 1\n') - if self.mcu_series.startswith('STM32F1'): f.write(''' /* @@ -2821,8 +2890,8 @@ def get_processed_defaults_file(self, defaults_filepath, depth=0): def write_processed_defaults_file(self, filepath): # see if board has a defaults.parm file or a --default-parameters file was specified - defaults_filename = os.path.join(os.path.dirname(args.hwdef[0]), 'defaults.parm') - defaults_path = os.path.join(os.path.dirname(args.hwdef[0]), args.params) + defaults_filename = os.path.join(os.path.dirname(self.hwdef[0]), 'defaults.parm') + defaults_path = os.path.join(os.path.dirname(self.hwdef[0]), args.params) defaults_abspath = None if os.path.exists(defaults_path): @@ -2867,7 +2936,7 @@ def romfs_add_dir(self, subdirs, relative_to_base=False): if relative_to_base: romfs_dir = os.path.join(os.path.dirname(__file__), '..', '..', '..', '..', dirname) else: - romfs_dir = os.path.join(os.path.dirname(args.hwdef[0]), dirname) + romfs_dir = os.path.join(os.path.dirname(self.hwdef[0]), dirname) if not self.is_bootloader_fw() and os.path.exists(romfs_dir): for root, d, files in os.walk(romfs_dir): for f in files: @@ -2908,12 +2977,12 @@ def valid_type(self, ptype, label): if ptype == 'OUTPUT' and re.match(r'US?ART\d+_(TXINV|RXINV)', label): return True m1 = re.match(r'USART(\d+)', ptype) - m2 = re.match(r'USART(\d+)_(RX|TX|CTS|RTS)', label) + m2 = re.match(r'USART(\d+)_(RX|TX|CTS|RTS|CTS_GPIO)', label) if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)): '''usart numbers need to match''' return False m1 = re.match(r'UART(\d+)', ptype) - m2 = re.match(r'UART(\d+)_(RX|TX|CTS|RTS)', label) + m2 = re.match(r'UART(\d+)_(RX|TX|CTS|RTS|CTS_GPIO)', label) if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)): '''uart numbers need to match''' return False @@ -3139,7 +3208,40 @@ def add_iomcu_firmware_defaults(self, f): self.add_firmware_defaults_from_file(f, "defaults_iofirmware.h", "IOMCU Firmware") + def is_periph_fw_unprocessed_file(self, hwdef, includer=None): + '''helper/recursion function for is_periph_fw_unprocessed''' + if not os.path.exists(hwdef): + raise ChibiOSHWDefIncludeNotFoundException( + os.path.normpath(hwdef), + os.path.normpath(includer) + ) + with open(hwdef, "r") as f: + content = f.read() + if 'AP_PERIPH' in content: + return True + # process any include lines: + for m in re.finditer(r"^include\s+([^\s]*)", content, re.MULTILINE): + include_path = os.path.join(os.path.dirname(hwdef), m.group(1)) + if self.is_periph_fw_unprocessed_file(include_path, includer=hwdef): + return True + + def is_periph_fw_unprocessed(self): + '''it takes ~2 seconds to process all hwdefs. This is a shortcut to + make things much faster in the case we are filtering boards to + just peripherals. Note that this parsing is very coarse - + AP_PERIPH could be in a comment or part of a define + (e.g. AP_PERIPH_GPS_SUPPORT), for example, and this method + will still return True. Also can't "undef" AP_PERIPH - if we + ever see the string we return true. + ''' + for hwdef in self.hwdef: + if self.is_periph_fw_unprocessed_file(hwdef): + return True + return False + def is_periph_fw(self): + if not self.processed_hwdefs: + raise ValueError("Need to process_hwdefs() first") return int(self.env_vars.get('AP_PERIPH', 0)) != 0 def is_normal_fw(self): @@ -3185,12 +3287,16 @@ def write_default_parameters(self): return self.romfs_add('defaults.parm', filepath) + self.have_defaults_file = True - def run(self): - - # process input file + def process_hwdefs(self): for fname in self.hwdef: self.process_file(fname) + self.processed_hwdefs = True + + def run(self): + # process input file + self.process_hwdefs() if "MCU" not in self.config: self.error("Missing MCU type in config") diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py index ba4ad7e09185be..29ef61b9836c39 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -255,14 +255,20 @@ def convert_file(fname, board_id): if (spin != int(spi[0])): spin = int(spi[0]) f.write("\n# SPI%s\n" % spin) - f.write("%s SPI%s_%s SPI%s\n" % (spi[1], spin, spi[3].split('_')[1], spin)) + fn = spi[3].split('_')[1] + if fn == "SDI": + fn = "MISO" + elif fn == "SDO": + fn = "MOSI" + f.write("%s SPI%s_%s SPI%s\n" % (spi[1], spin, fn, spin)) f.write("\n# Chip select pins\n") for cs in chip_select.values(): f.write("%s %s%s_CS CS\n" % (cs[1], cs[2], int(cs[0]))) - beeper = list(functions["BEEPER"].values())[0] - f.write('''\n# Beeper + if len(functions["BEEPER"].values()) > 0: + beeper = list(functions["BEEPER"].values())[0] + f.write('''\n# Beeper %s BUZZER OUTPUT GPIO(80) LOW define HAL_BUZZER_PIN 80 ''' % beeper[1]) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h index ce6514e51f2df0..205a2002304d26 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h @@ -15,11 +15,6 @@ #define HAL_GCS_ENABLED 0 #endif -// by default bootloaders don't use INS: -#ifndef AP_INERTIALSENSOR_ENABLED -#define AP_INERTIALSENSOR_ENABLED 0 -#endif - #define HAL_MAX_CAN_PROTOCOL_DRIVERS 0 // bootloader does not save temperature cals etc: @@ -38,9 +33,9 @@ // less LWIP functionality in the bootloader #define LWIP_DHCP 0 -#define LWIP_UDP 0 +#define LWIP_UDP 1 #define LWIP_PPP 0 -#define LWIP_IGMP 0 +#define LWIP_IGMP 1 #define LWIP_ALTCP 0 #define IP_FORWARD 0 #define LWIP_SINGLE_NETIF 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h index 64e913c6f6a03e..bdb08a73103d4a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h @@ -69,3 +69,7 @@ #ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED #define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0 #endif + +#ifndef HAL_MONITOR_THREAD_ENABLED +#define HAL_MONITOR_THREAD_ENABLED 0 +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 49dd1a76bcb061..d469b87109c59a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -118,10 +118,6 @@ #endif #endif -#ifndef AP_STATS_ENABLED -#define AP_STATS_ENABLED 0 -#endif - #ifndef AP_BATTERY_ESC_ENABLED #define AP_BATTERY_ESC_ENABLED 0 #endif @@ -274,9 +270,12 @@ #define RANGEFINDER_MAX_INSTANCES 1 #endif -// by default AP_Periphs don't use INS: -#ifndef AP_INERTIALSENSOR_ENABLED -#define AP_INERTIALSENSOR_ENABLED 0 +#ifndef HAL_ADSB_ENABLED +#define HAL_ADSB_ENABLED 0 +#endif + +#ifndef AP_AIS_ENABLED +#define AP_AIS_ENABLED 0 #endif // no fence by default in AP_Periph: @@ -329,6 +328,10 @@ #define HAL_RCIN_THREAD_ENABLED 0 #endif +#ifndef HAL_MONITOR_THREAD_ENABLED +#define HAL_MONITOR_THREAD_ENABLED 0 +#endif + #ifndef HAL_SCHEDULER_LOOP_DELAY_ENABLED #define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0 #endif @@ -346,10 +349,14 @@ #define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG) #define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO) #define AP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#define AP_RANGEFINDER_ENABLED defined(HAL_PERIPH_ENABLE_RANGEFINDER) #define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM) #define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN) #define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC) #define HAL_VISUALODOM_ENABLED defined(HAL_PERIPH_ENABLE_VISUALODOM) +#define AP_INERTIALSENSOR_ENABLED defined(HAL_PERIPH_ENABLE_IMU) +#define AP_INERTIALSENSOR_ALLOW_NO_SENSORS defined(HAL_PERIPH_ENABLE_IMU) +#define AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED 0 #ifndef AP_BOOTLOADER_ALWAYS_ERASE #define AP_BOOTLOADER_ALWAYS_ERASE 1 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 602edd8721cb7f..81c74881dda0d1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat @@ -109,16 +109,20 @@ IMU Invensense SPI:icm20789 ROTATION_NONE # radio IRQ is on GPIO(100) define HAL_GPIO_RADIO_IRQ 100 -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 + STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 15360 # setup defines for ArduCopter config -define TOY_MODE_ENABLED ENABLED +define TOY_MODE_ENABLED 1 define ARMING_DELAY_SEC 0 define LAND_START_ALT 700 define LAND_DETECTOR_ACCEL_MAX 2.0f diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm index 8d59dc3697b073..a845852dab1f8e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm @@ -24,9 +24,10 @@ TMODE_FLAGS 63 TMODE_TMIN 0.9 # LEDs. pin0 is green, pin1 is red -RELAY_PIN 0 -RELAY_PIN2 1 -RELAY_DEFAULT 1 +RELAY1_PIN 0 +RELAY2_PIN 1 +RELAY1_DEFAULT 1 +RELAY2_DEFAULT 1 AHRS_ORIENTATION 2 COMPASS_EXTERNAL 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat index a6711bd7eafb2a..64d400165f8895 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat @@ -99,17 +99,21 @@ IMU Invensense I2C:1:0x68 ROTATION_NONE # radio IRQ is on GPIO(100) define HAL_GPIO_RADIO_IRQ 100 -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 define AP_RADIO_BK2425_ENABLED 1 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 + STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 15360 # setup defines for ArduCopter config -define TOY_MODE_ENABLED ENABLED +define TOY_MODE_ENABLED 1 define ARMING_DELAY_SEC 0 define LAND_START_ALT 700 define LAND_DETECTOR_ACCEL_MAX 2.0f @@ -126,6 +130,7 @@ define HAL_BARO_20789_I2C_ADDR_ICM 0x68 define HAL_I2C_CLEAR_BUS define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 +define OPTICAL_FLOW_TYPE_DEFAULT Type::PIXART # the web UI uses an abin file for firmware uploads env BUILD_ABIN True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm index 8d4831d89e0d46..5eaaf8c8843052 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm @@ -22,9 +22,10 @@ TMODE_FLAGS 23 TMODE_TMIN 0.9 # LEDs. pin54 is green, pin55 is red -RELAY_PIN 54 -RELAY_PIN2 55 -RELAY_DEFAULT 1 +RELAY1_PIN 54 +RELAY2_PIN 55 +RELAY1_DEFAULT 1 +RELAY2_DEFAULT 1 # Set to GPIO so they are used as RELAY SERVO5_FUNCTION -1 SERVO6_FUNCTION -1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index a37c97f5508975..d1e058a74ec152 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -31,7 +31,7 @@ define CHIBIOS_SHORT_BOARD_NAME "skyviper-v245" SERIAL_ORDER OTG1 USART2 EMPTY UART4 # enable AP_Radio support -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 @@ -44,7 +44,7 @@ PD15 MPU_DRDY INPUT GPIO(100) define HAL_GPIO_RADIO_IRQ 100 # setup defines for ArduCopter config -define TOY_MODE_ENABLED ENABLED +define TOY_MODE_ENABLED 1 define ARMING_DELAY_SEC 0 define LAND_START_ALT 700 define LAND_DETECTOR_ACCEL_MAX 2.0f @@ -132,8 +132,9 @@ define BARO_MAX_INSTANCES 1 define INS_MAX_INSTANCES 1 # SkyViper doesn't have any rangefinder, but might get mavlink? +define AP_RANGEFINDER_ENABLED 1 define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0 -define AP_RANGEFINDER_MAVLINK_ENABLED 1 +define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_ENABLED # SkyViper doesn't have RPM sensors: define AP_RPM_ENABLED 0 @@ -171,7 +172,9 @@ define AP_CAMERA_BACKEND_DEFAULT_ENABLED 0 define AP_CAMERA_MAVLINK_ENABLED 1 # SkyViper uses AP_Radio, which does its own RC protocol decoding: -define AP_RCPROTOCOL_ENABLED 0 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 // few prelcnad backends are applicable define AC_PRECLAND_BACKEND_DEFAULT_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat index 2f03aa1ac7f94f..8f4a3e48095c8d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat @@ -24,6 +24,7 @@ PB5 LED_BLUE OUTPUT LOW GPIO(0) PB6 LED_YELLOW OUTPUT LOW GPIO(1) # optional PB4 LED_RED OUTPUT LOW GPIO(2) +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 define HAL_GPIO_A_LED_PIN 0 define HAL_GPIO_B_LED_PIN 1 define HAL_GPIO_C_LED_PIN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat index d22798c436d813..07010b0ad6ea68 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat @@ -27,6 +27,7 @@ SERIAL_ORDER OTG1 USART1 UART4 USART3 UART5 PB9 LED_BLUE OUTPUT LOW GPIO(0) PA14 LED_GREEN OUTPUT LOW GPIO(1) +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 define HAL_GPIO_A_LED_PIN 0 define HAL_GPIO_B_LED_PIN 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat index 658ee1b32f034e..b1fd316c40769e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat @@ -31,8 +31,6 @@ 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat index f313a8b83f47d3..752745b3922479 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat @@ -24,7 +24,8 @@ SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 # LEDs PC8 LED_BLUE OUTPUT LOW GPIO(0) -define HAL_GPIO_A_LED_PIN 0 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 +define AP_NOTIFY_GPIO_LED_1_PIN 0 # buzzer PC5 BUZZER OUTPUT GPIO(80) LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat index 743300b3b8c81d..e392dc619986ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat @@ -30,8 +30,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + # Chip select pins diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat index a70e3b80e83da1..80e58d65d90f08 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat @@ -121,8 +121,9 @@ PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) # M8 # LEDs PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 +define AP_NOTIFY_GPIO_LED_1_ENABLED 1 PC13 LED0 OUTPUT LOW GPIO(90) -define HAL_GPIO_A_LED_PIN 90 +define AP_NOTIFY_GPIO_LED_1_PIN 90 # OSD setup SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-boom-f407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-boom-f407/hwdef.dat index 544340b49f7b91..9b90331d95492a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sw-boom-f407/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-boom-f407/hwdef.dat @@ -115,5 +115,7 @@ define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 1 define AP_SCRIPTING_ENABLED 1 define AP_FILESYSTEM_ROMFS_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 + # don't build on firmware.ardupilot.org AUTOBUILD_TARGETS None diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat index 22caeff5488b6f..18e17fe6829c0c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat @@ -81,6 +81,7 @@ define DISCRETE_RGB_POLARITY true define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 # don't build on firmware.ardupilot.org AUTOBUILD_TARGETS None diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat index da4d3c33404203..0e1a5844dd6a72 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat @@ -126,3 +126,4 @@ AUTOBUILD_TARGETS None define HAL_SERIAL_ESC_COMM_ENABLED 1 define HAL_RCIN_THREAD_ENABLED 1 define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 +define HAL_MONITOR_THREAD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef-bl.dat index b88c8ea99976d9..7891eecab2f506 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef-bl.dat @@ -77,5 +77,4 @@ PC15 ICM20602_CS CS PD7 MS5611_CS CS PD10 FRAM_CS CS SPEED_VERYLOW -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef-bl.dat index 6e85b461092093..23bf5178fb5577 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef-bl.dat @@ -77,5 +77,4 @@ PC15 ICM20602_CS CS PD7 MS5611_CS CS PD10 FRAM_CS CS SPEED_VERYLOW -# default to all pins low to avoid ESD issues -DEFAULTGPIO OUTPUT LOW PULLDOWN + diff --git a/libraries/AP_HAL_ChibiOS/shared_dma.cpp b/libraries/AP_HAL_ChibiOS/shared_dma.cpp index 68b86d4b27f64d..7d72700cf61ba2 100644 --- a/libraries/AP_HAL_ChibiOS/shared_dma.cpp +++ b/libraries/AP_HAL_ChibiOS/shared_dma.cpp @@ -249,7 +249,7 @@ void Shared_DMA::dma_info(ExpandingString &str) { // no buffer allocated, start counting if (_contention_stats == nullptr) { - _contention_stats = new dma_stats[SHARED_DMA_MAX_STREAM_ID+1]; + _contention_stats = NEW_NOTHROW dma_stats[SHARED_DMA_MAX_STREAM_ID+1]; // return zeros on first fetch } diff --git a/libraries/AP_HAL_ESP32/AnalogIn.cpp b/libraries/AP_HAL_ESP32/AnalogIn.cpp index 6ae04bc489591e..7f027a31a31e97 100644 --- a/libraries/AP_HAL_ESP32/AnalogIn.cpp +++ b/libraries/AP_HAL_ESP32/AnalogIn.cpp @@ -12,7 +12,7 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * - * Code by Charles Villard + * Code by Charles Villard, ARg and Bayu Laksono */ #include #include @@ -22,10 +22,10 @@ #include "freertos/FreeRTOS.h" #include "freertos/task.h" -#include "driver/gpio.h" -#include "driver/adc.h" -#include "esp_adc_cal.h" #include "soc/adc_channel.h" +#include "esp_adc/adc_oneshot.h" +#include "esp_adc/adc_cali.h" +#include "esp_adc/adc_cali_scheme.h" #if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER) @@ -41,7 +41,7 @@ #define ANALOGIN_DEBUGGING 0 // base voltage scaling for 12 bit 3.3V ADC -#define VOLTAGE_SCALING (3.3f/4096.0f) +#define VOLTAGE_SCALING (3300.0f/4096.0f) #if ANALOGIN_DEBUGGING # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) @@ -49,6 +49,10 @@ # define Debug(fmt, args ...) #endif + +//ADC handle +static adc_oneshot_unit_handle_t g_adc1_handle = NULL; + // we are limited to using adc1, and it supports 8 channels max, on gpio, in this order: // ADC1_CH0=D36,ADC1_CH1=D37,ADC1_CH2=D38,ADC1_CH3=D39,ADC1_CH4=D32,ADC1_CH5=D33,ADC1_CH6=D34,ADC1_CH7=D35 // this driver will only configure the ADCs from a subset of these that the board exposes on pins. @@ -67,46 +71,96 @@ const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ESP32_ADC_PINS; #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config) -#define DEFAULT_VREF 1100 //Use adc2_vref_to_gpio() to obtain a better estimate +#define DEFAULT_VREF 3300 //Use adc2_vref_to_gpio() to obtain a better estimate #define NO_OF_SAMPLES 256 //Multisampling static const adc_atten_t atten = ADC_ATTEN_DB_12; -//ardupin is the ardupilot assigned number, starting from 1-8(max) -// 'pin' and _pin is a macro like 'ADC1_GPIO35_CHANNEL' from board config .h -AnalogSource::AnalogSource(int16_t ardupin,int16_t pin,float scaler, float initial_value, uint8_t unit) : +/*--------------------------------------------------------------- + ADC Calibration +---------------------------------------------------------------*/ +bool adc_calibration_init(adc_unit_t unit, adc_channel_t channel, adc_atten_t atten, adc_cali_handle_t *out_handle) +{ + adc_cali_handle_t handle = NULL; + esp_err_t ret = ESP_FAIL; + bool calibrated = false; + +#if ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED + if (!calibrated) { + Debug("AnalogIn: calibration scheme version is %s", "Curve Fitting"); + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = unit, + .chan = channel, + .atten = atten, + .bitwidth = ADC_BITWIDTH_12, + }; + ret = adc_cali_create_scheme_curve_fitting(&cali_config, &handle); + if (ret == ESP_OK) { + calibrated = true; + } + } +#endif - _unit(unit), +#if ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED + if (!calibrated) { + Debug("AnalogIn: calibration scheme version is %s", "Line Fitting"); + adc_cali_line_fitting_config_t cali_config = { + .unit_id = unit, + .atten = atten, + .bitwidth = ADC_BITWIDTH_12, + }; + ret = adc_cali_create_scheme_line_fitting(&cali_config, &handle); + if (ret == ESP_OK) { + calibrated = true; + } + } +#endif + + *out_handle = handle; + if (ret == ESP_OK) { + Debug("AnalogIn: Calibration Success for channel %d:%d", unit, channel); + } else if (ret == ESP_ERR_NOT_SUPPORTED || !calibrated) { + Debug("AnalogIn: eFuse not burnt, skip software calibration"); + } else { + Debug("AnalogIn: Invalid arg or no memory"); + } + + return calibrated; +} + +void adc_calibration_deinit(adc_cali_handle_t handle) +{ +#if ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED + Debug("AnalogIn: deregister %s calibration scheme", "Curve Fitting"); + adc_cali_delete_scheme_curve_fitting(handle); +#elif ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED + Debug("AnalogIn: deregister %s calibration scheme", "Line Fitting"); + adc_cali_delete_scheme_line_fitting(handle); +#endif +} + +//ardupin is the ardupilot assigned number, starting from 1-8(max) +AnalogSource::AnalogSource(int16_t ardupin, adc_channel_t adc_channel, float scaler, float initial_value) : + _adc_channel(adc_channel), _ardupin(ardupin), - _pin(pin), _scaler(scaler), _value(initial_value), _latest_value(initial_value), _sum_count(0), _sum_value(0) { - printf("AnalogIn: adding ardupin:%d-> which is adc1_offset:%d\n", _ardupin,_pin); + Debug("AnalogIn: adding ardupin:%d-> which is adc1_channel:%d\n", _ardupin, _adc_channel); - // init the pin now if possible, otherwise doo it later from set_pin - if ( _ardupin != ANALOG_INPUT_NONE ) { - - // dertermine actial gpio from adc offset and configure it - gpio_num_t gpio; - //Configure ADC - if (unit == 1) { - adc1_config_channel_atten((adc1_channel_t)_pin, atten); - adc1_pad_get_io_num((adc1_channel_t)_pin, &gpio); - } else { - adc2_config_channel_atten((adc2_channel_t)_pin, atten); - } - - esp_adc_cal_characteristics_t adc_chars; - esp_adc_cal_characterize(ADC_UNIT_1, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, &adc_chars); - printf("AnalogIn: determined actual gpio as: %d\n", gpio); - - _gpio = gpio;// save it for later + // for now, hard coded using adc1 + _adc_unit = ADC_UNIT_1; + adc_oneshot_unit_init_cfg_t init_config = { .unit_id = _adc_unit }; + if (!g_adc1_handle && ESP_OK != adc_oneshot_new_unit(&init_config, &g_adc1_handle)) { + Debug("AnalogIn: adc_oneshot_new_unit failed for unit_id = %d\n", _adc_unit); + return; } + + adc_init(); } @@ -119,16 +173,10 @@ float AnalogSource::read_average() WITH_SEMAPHORE(_semaphore); if (_sum_count == 0) { - uint32_t adc_reading = 0; + float adc_reading = 0; //Multisampling for (int i = 0; i < NO_OF_SAMPLES; i++) { - if (_unit == 1) { - adc_reading += adc1_get_raw((adc1_channel_t)_pin); - } else { - int raw; - adc2_get_raw((adc2_channel_t)_pin, ADC_WIDTH_BIT_12, &raw); - adc_reading += raw; - } + adc_reading += adc_read(); } adc_reading /= NO_OF_SAMPLES; return adc_reading; @@ -176,46 +224,37 @@ bool AnalogSource::set_pin(uint8_t ardupin) if (_ardupin == ardupin) { return true; } + _ardupin = ardupin; int8_t pinconfig_offset = AnalogIn::find_pinconfig(ardupin); if (pinconfig_offset == -1 ) { - DEV_PRINTF("AnalogIn: sorry set_pin() can't determine ADC1 offset from ardupin : %d \n",ardupin); + Debug("AnalogIn: sorry set_pin() can't determine ADC1 offset from ardupin : %d \n",ardupin); return false; } - int16_t newgpioAdcPin = AnalogIn::pin_config[(uint8_t)pinconfig_offset].channel; + adc_channel_t newChannel = (adc_channel_t)AnalogIn::pin_config[(uint8_t)pinconfig_offset].channel; float newscaler = AnalogIn::pin_config[(uint8_t)pinconfig_offset].scaling; - if (_pin == newgpioAdcPin) { + Debug("AnalogIn: ardupin = %d, new channel = %d\n", ardupin, newChannel); + + if (_adc_channel == newChannel) { return true; } WITH_SEMAPHORE(_semaphore); - // init the target pin now if possible - if ( ardupin != ANALOG_INPUT_NONE ) { + if (_adc_cali_handle) { + + Debug("AnalogIn: adc_calibration_deinit(%x)\n", (uint)_adc_cali_handle); - gpio_num_t gpio; // new gpio - //Configure ADC - if (_unit == 1) { - adc1_config_channel_atten((adc1_channel_t)newgpioAdcPin, atten); - adc1_pad_get_io_num((adc1_channel_t)newgpioAdcPin, &gpio); - } else { - adc2_config_channel_atten((adc2_channel_t)newgpioAdcPin, atten); - } + adc_calibration_deinit(_adc_cali_handle); + _adc_cali_handle = 0; + } - esp_adc_cal_characteristics_t adc_chars; - esp_adc_cal_characterize(ADC_UNIT_1, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, &adc_chars); - printf("AnalogIn: Adding gpio on: %d\n", gpio); + _adc_channel = newChannel; + _scaler = newscaler; - 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; - _gpio = gpio; - _scaler = newscaler; - - } + adc_init(); _sum_value = 0; _sum_count = 0; @@ -226,6 +265,60 @@ bool AnalogSource::set_pin(uint8_t ardupin) } +// init ADC +bool AnalogSource::adc_init() +{ + // init the pin now if possible, otherwise doo it later from set_pin + if ( _ardupin != ANALOG_INPUT_NONE ) { + + adc_oneshot_chan_cfg_t config = { + .atten = atten, + .bitwidth = ADC_BITWIDTH_12 + }; + if (ESP_OK != adc_oneshot_config_channel(g_adc1_handle, _adc_channel, &config)) { + Debug("AnalogIn: adc_oneshot_config_channel failed for adc_channel = %d\n", _adc_channel); + return false; + } + else { + Debug("AnalogIn: adc_oneshot_config_channel for adc_channel = %d\n completed successfully", _adc_channel); + } + + if (!adc_calibration_init(_adc_unit, _adc_channel, atten, &_adc_cali_handle)){ + Debug("AnalogIn: adc_calibration_init failed for adc_channel = %d\n", _adc_channel); + return false; + } + else { + Debug("AnalogIn: adc_calibration_init for adc_channel = %d\n completed successfully", _adc_channel); + } + } + else { + Debug("AnalogIn: adc_init(%d) skipped.\n", _ardupin); + } + return true; +} + +// read value from ADC +float AnalogSource::adc_read() +{ + int raw, value = 0; + + if (ESP_OK != adc_oneshot_read(g_adc1_handle, _adc_channel, &raw)) { + Debug("AnalogIn: adc_oneshot_read failed\n"); + return 0; + } + + if (_adc_cali_handle) { + if(ESP_OK != adc_cali_raw_to_voltage(_adc_cali_handle, raw, &value)) { + Debug("AnalogIn: adc_oneshot_read failed\n"); + return 0; + } + } + else { + value = raw * VOLTAGE_SCALING; + } + return (float)value / 1000; +} + /* apply a reading in ADC counts */ @@ -237,12 +330,7 @@ void AnalogSource::_add_value() WITH_SEMAPHORE(_semaphore); - int value = 0; - if (_unit == 1) { - value = adc1_get_raw((adc1_channel_t)_pin); - } else { - adc2_get_raw((adc2_channel_t)_pin, ADC_WIDTH_BIT_12, &value); - } + float value = adc_read(); _latest_value = value; _sum_value += value; @@ -254,31 +342,11 @@ void AnalogSource::_add_value() } } -static void check_efuse() -{ - //Check TP is burned into eFuse - if (esp_adc_cal_check_efuse(ESP_ADC_CAL_VAL_EFUSE_TP) == ESP_OK) { - printf("AnalogIn: eFuse Two Point: Supported\n"); - } else { - printf("AnalogIn: eFuse Two Point: NOT supported\n"); - } - - //Check Vref is burned into eFuse - if (esp_adc_cal_check_efuse(ESP_ADC_CAL_VAL_EFUSE_VREF) == ESP_OK) { - printf("AnalogIn: eFuse Vref: Supported\n"); - } else { - printf("AnalogIn: eFuse Vref: NOT supported\n"); - } -} - /* setup adc peripheral to capture samples with DMA into a buffer */ void AnalogIn::init() { - check_efuse(); - - adc1_config_width(ADC_WIDTH_BIT_12); } /* @@ -290,7 +358,7 @@ void AnalogIn::_timer_tick() ESP32::AnalogSource *c = _channels[j]; if (c != nullptr) { // add a value - //c->_add_value(); + c->_add_value(); } } @@ -330,39 +398,44 @@ int8_t AnalogIn::find_pinconfig(int16_t ardupin) // AP_HAL::AnalogSource *AnalogIn::channel(int16_t ardupin) { + if (ardupin < 0) ardupin = ANALOG_INPUT_NONE; + + Debug("AnalogIn: configuring channel %d\n", ardupin); + int8_t pinconfig_offset = find_pinconfig(ardupin); - int16_t gpioAdcPin = -1; - float scaler = -1; + adc_channel_t adc_channel = (adc_channel_t)ANALOG_INPUT_NONE; + float scaler = 0; if ((ardupin != ANALOG_INPUT_NONE) && (pinconfig_offset == -1 )) { - DEV_PRINTF("AnalogIn: sorry channel() can't determine ADC1 offset from ardupin : %d \n",ardupin); + Debug("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 // a special case, so that it can be changed with set_pin(..) later. if (ardupin != ANALOG_INPUT_NONE) { - gpioAdcPin = pin_config[(uint8_t)pinconfig_offset].channel; + adc_channel = (adc_channel_t)pin_config[(uint8_t)pinconfig_offset].channel; scaler = pin_config[(uint8_t)pinconfig_offset].scaling; } for (uint8_t j = 0; j < ANALOG_MAX_CHANNELS; j++) { if (_channels[j] == nullptr) { - _channels[j] = new AnalogSource(ardupin,gpioAdcPin, scaler,0.0f,1); + + _channels[j] = NEW_NOTHROW AnalogSource(ardupin, adc_channel, scaler, 0.0f); if (ardupin != ANALOG_INPUT_NONE) { - DEV_PRINTF("AnalogIn: channel:%d attached to ardupin:%d at adc1_offset:%d on gpio:%d\n",\ - j,ardupin, gpioAdcPin, _channels[j]->_gpio); + Debug("AnalogIn: channel: %d attached to ardupin:%d at adc1_offset:%d\n",\ + j, ardupin, adc_channel); } - - if (ardupin == ANALOG_INPUT_NONE) { - DEV_PRINTF("AnalogIn: channel:%d created but using delayed adc and gpio pin configuration\n",j ); + else { + Debug("AnalogIn: channel: %d created but using delayed adc and gpio pin configuration\n", j); } return _channels[j]; } } - DEV_PRINTF("AnalogIn: out of channels\n"); + Debug("AnalogIn: out of channels\n"); return nullptr; } diff --git a/libraries/AP_HAL_ESP32/AnalogIn.h b/libraries/AP_HAL_ESP32/AnalogIn.h index 2814e57790589e..a4531fe47edd2b 100644 --- a/libraries/AP_HAL_ESP32/AnalogIn.h +++ b/libraries/AP_HAL_ESP32/AnalogIn.h @@ -12,13 +12,17 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * - * Code by Charles Villard + * Code by Charles Villard, ARg and Bayu Laksono */ #pragma once #include "AP_HAL_ESP32.h" +#include "esp_adc/adc_oneshot.h" +#include "esp_adc/adc_cali.h" +#include "esp_adc/adc_cali_scheme.h" + #if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER) #define ANALOG_MAX_CHANNELS 8 @@ -30,7 +34,7 @@ class AnalogSource : public AP_HAL::AnalogSource { public: friend class AnalogIn; - AnalogSource(int16_t ardupin,int16_t pin,float scaler, float initial_value, uint8_t unit); + AnalogSource(int16_t ardupin, adc_channel_t adc_channel, float scaler, float initial_value); float read_average() override; float read_latest() override; bool set_pin(uint8_t p) override; @@ -42,18 +46,16 @@ class AnalogSource : public AP_HAL::AnalogSource private: //ADC number (1 or 2). ADC2 is unavailable when WIFI on - uint8_t _unit; + adc_unit_t _adc_unit; - //adc Pin number (1-8) - // gpio-adc lower level pin name - int16_t _pin; + //ADC channel + adc_channel_t _adc_channel; //human readable Pin number used in ardu params int16_t _ardupin; //scaling from ADC count to Volts - int16_t _scaler; - // gpio pin number on esp32: - gpio_num_t _gpio; + float _scaler; + adc_cali_handle_t _adc_cali_handle; //Current computed value (average) float _value; @@ -64,6 +66,8 @@ class AnalogSource : public AP_HAL::AnalogSource //Sum of fetched values float _sum_value; + bool adc_init(); + float adc_read(); void _add_value(); HAL_Semaphore _semaphore; @@ -93,7 +97,6 @@ class AnalogIn : public AP_HAL::AnalogIn uint8_t channel; // adc1 pin offset float scaling; uint8_t ardupin; // eg 3 , as typed into an ardupilot parameter - uint8_t gpio; // eg 32 for D32 esp pin number/s }; static const pin_info pin_config[]; diff --git a/libraries/AP_HAL_ESP32/DeviceBus.cpp b/libraries/AP_HAL_ESP32/DeviceBus.cpp index 5e99e4ac95f2c0..12a46fbb61159f 100644 --- a/libraries/AP_HAL_ESP32/DeviceBus.cpp +++ b/libraries/AP_HAL_ESP32/DeviceBus.cpp @@ -31,7 +31,8 @@ using namespace ESP32; extern const AP_HAL::HAL& hal; DeviceBus::DeviceBus(uint8_t _thread_priority) : - thread_priority(_thread_priority), semaphore() + semaphore(), + thread_priority(_thread_priority) { #ifdef BUSDEBUG printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); @@ -124,7 +125,7 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe xTaskCreate(DeviceBus::bus_thread, name, Scheduler::DEVICE_SS, this, thread_priority, &bus_thread_handle); } - DeviceBus::callback_info *callback = new DeviceBus::callback_info; + DeviceBus::callback_info *callback = NEW_NOTHROW DeviceBus::callback_info; if (callback == nullptr) { return nullptr; } diff --git a/libraries/AP_HAL_ESP32/GPIO.cpp b/libraries/AP_HAL_ESP32/GPIO.cpp new file mode 100644 index 00000000000000..66cbff5b31e8ab --- /dev/null +++ b/libraries/AP_HAL_ESP32/GPIO.cpp @@ -0,0 +1,141 @@ +/* + * 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 Bayu Laksono + */ + +#include "AP_HAL_ESP32.h" +#include "GPIO.h" + +#include "hal/gpio_types.h" +#include "driver/gpio.h" + +using namespace ESP32; + +static gpio_num_t gpio_by_pin_num(uint8_t pin) +{ + if (pin < GPIO_NUM_MAX) { + return (gpio_num_t)pin; + } + return GPIO_NUM_NC; +} + +GPIO::GPIO() +{} + +void GPIO::init() +{} + +void GPIO::pinMode(uint8_t pin, uint8_t output) +{ + gpio_num_t g = gpio_by_pin_num(pin); + if (g != GPIO_NUM_NC) { + gpio_config_t io_conf = {}; + io_conf.intr_type = GPIO_INTR_DISABLE; + io_conf.mode = output ? GPIO_MODE_OUTPUT : GPIO_MODE_INPUT; + io_conf.pin_bit_mask = 1ULL<. + */ + +#pragma once + +#include "AP_HAL_ESP32.h" + +class ESP32::GPIO : public AP_HAL::GPIO { +public: + GPIO(); + void init() override; + void pinMode(uint8_t pin, uint8_t output) override; + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; + void toggle(uint8_t pin) override; + + /* Alternative interface: */ + AP_HAL::DigitalSource* channel(uint16_t n) override; + + /* return true if USB cable is connected */ + bool usb_connected(void) override; +}; + +class ESP32::DigitalSource : public AP_HAL::DigitalSource { +public: + DigitalSource(uint8_t pin); + void mode(uint8_t output) override; + uint8_t read() override; + void write(uint8_t value) override; + void toggle() override; +private: + uint8_t _pin; +}; diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index b00af1bc543c09..c0b039e386e160 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -25,6 +25,7 @@ #include "WiFiUdpDriver.h" #include "RCInput.h" #include "RCOutput.h" +#include "GPIO.h" #include "Storage.h" #include "AnalogIn.h" #include "Util.h" @@ -32,13 +33,14 @@ #include #endif - static ESP32::UARTDriver cons(0); #ifdef HAL_ESP32_WIFI #if HAL_ESP32_WIFI == 1 static ESP32::WiFiDriver serial1Driver; //tcp, client should connect to 192.168.4.1 port 5760 #elif HAL_ESP32_WIFI == 2 static ESP32::WiFiUdpDriver serial1Driver; //udp +#else +static Empty::UARTDriver serial1Driver; #endif #else static Empty::UARTDriver serial1Driver; @@ -68,7 +70,7 @@ static Empty::Storage storageDriver; #else static ESP32::Storage storageDriver; #endif -static Empty::GPIO gpioDriver; +static ESP32::GPIO gpioDriver; #if AP_SIM_ENABLED static Empty::RCOutput rcoutDriver; #else diff --git a/libraries/AP_HAL_ESP32/I2CDevice.cpp b/libraries/AP_HAL_ESP32/I2CDevice.cpp index 07301a19624402..e2bcc9071ec81f 100644 --- a/libraries/AP_HAL_ESP32/I2CDevice.cpp +++ b/libraries/AP_HAL_ESP32/I2CDevice.cpp @@ -59,9 +59,9 @@ I2CDeviceManager::I2CDeviceManager(void) } I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) : + bus(I2CDeviceManager::businfo[busnum]), _retries(10), - _address(address), - bus(I2CDeviceManager::businfo[busnum]) + _address(address) { set_device_bus(busnum); set_device_address(address); @@ -159,7 +159,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address, if (bus >= ARRAY_SIZE(i2c_bus_desc)) { return AP_HAL::OwnPtr(nullptr); } - auto dev = AP_HAL::OwnPtr(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); + auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); return dev; } diff --git a/libraries/AP_HAL_ESP32/RCInput.cpp b/libraries/AP_HAL_ESP32/RCInput.cpp index 704877962d4e08..8e8a3dea6bdc1e 100644 --- a/libraries/AP_HAL_ESP32/RCInput.cpp +++ b/libraries/AP_HAL_ESP32/RCInput.cpp @@ -12,14 +12,24 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . */ -#include + #include #include "AP_HAL_ESP32.h" #include "RCInput.h" +#include + +#include + +#ifndef HAL_NO_UARTDRIVER +#include +#endif + using namespace ESP32; +extern const AP_HAL::HAL& hal; + void RCInput::init() { if (_init) { @@ -31,10 +41,26 @@ void RCInput::init() #ifdef HAL_ESP32_RCIN sig_reader.init(); + pulse_input_enabled = true; #endif + _init = true; } +/* + enable or disable pulse input for RC input. This is used to reduce + load when we are decoding R/C via a UART +*/ +void RCInput::pulse_input_enable(bool enable) +{ + pulse_input_enabled = enable; +#if HAL_ESP32_RCIN + if (!enable) { + sig_reader.disable(); + } +#endif +} + bool RCInput::new_input() { if (!_init) { @@ -89,23 +115,29 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) void RCInput::_timer_tick(void) { -#if AP_RCPROTOCOL_ENABLED if (!_init) { return; } +#ifndef HAL_NO_UARTDRIVER + const char *rc_protocol = nullptr; + RCSource source = last_source; +#endif + +#if AP_RCPROTOCOL_ENABLED AP_RCProtocol &rcprot = AP::RC(); #ifdef HAL_ESP32_RCIN - uint32_t width_s0, width_s1; - while (sig_reader.read(width_s0, width_s1)) { - rcprot.process_pulse(width_s0, width_s1); - + if (pulse_input_enabled) { + uint32_t width_s0, width_s1; + while (sig_reader.read(width_s0, width_s1)) { + rcprot.process_pulse(width_s0, width_s1); + } } - -#ifndef HAL_NO_UARTDRIVER - const char *rc_protocol = nullptr; #endif +#endif // AP_RCPROTOCOL_ENABLED + +#if AP_RCPROTOCOL_ENABLED if (rcprot.new_input()) { WITH_SEMAPHORE(rcin_mutex); _rcin_timestamp_last_signal = AP_HAL::micros(); @@ -113,18 +145,36 @@ void RCInput::_timer_tick(void) _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS); rcprot.read(_rc_values, _num_channels); _rssi = rcprot.get_RSSI(); + _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; + // printf("RCInput: decoding %s", last_protocol); #endif } +#endif // AP_RCPROTOCOL_ENABLED #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 + // note, we rely on the vehicle code checking new_input() + // and a timeout for the last valid input to handle failsafe +} + +/* + start a bind operation, if supported + */ +bool RCInput::rc_bind(int dsmMode) +{ +#if AP_RCPROTOCOL_ENABLED + // ask AP_RCProtocol to start a bind + AP::RC().start_bind(); #endif -#endif // AP_RCPROTOCOL_ENABLED + + return true; } diff --git a/libraries/AP_HAL_ESP32/RCInput.h b/libraries/AP_HAL_ESP32/RCInput.h index 370753d07f776f..7e8e885b1b90ac 100644 --- a/libraries/AP_HAL_ESP32/RCInput.h +++ b/libraries/AP_HAL_ESP32/RCInput.h @@ -17,9 +17,10 @@ #include "AP_HAL_ESP32.h" #include "Semaphores.h" -#include "RmtSigReader.h" + #include +#include "RmtSigReader.h" #ifndef RC_INPUT_MAX_CHANNELS #define RC_INPUT_MAX_CHANNELS 18 @@ -33,21 +34,42 @@ class ESP32::RCInput : public AP_HAL::RCInput uint8_t num_channels() override; uint16_t read(uint8_t ch) override; uint8_t read(uint16_t* periods, uint8_t len) override; - void _timer_tick(void); - const char *protocol() const override - { - return last_protocol; + /* enable or disable pulse input for RC input. This is used to + reduce load when we are decoding R/C via a UART */ + void pulse_input_enable(bool enable) override; + + int16_t get_rssi(void) override { + return _rssi; + } + int16_t get_rx_link_quality(void) override { + return _rx_link_quality; } + const char *protocol() const override { return last_protocol; } + + void _timer_tick(void); + bool rc_bind(int dsmMode) override; + private: uint16_t _rc_values[RC_INPUT_MAX_CHANNELS] = {0}; + uint64_t _last_read; uint8_t _num_channels; Semaphore rcin_mutex; int16_t _rssi = -1; + int16_t _rx_link_quality = -1; uint32_t _rcin_timestamp_last_signal; bool _init; const char *last_protocol; + enum class RCSource { + NONE = 0, + IOMCU = 1, + RCPROT_PULSES = 2, + RCPROT_BYTES = 3, + } last_source; + + bool pulse_input_enabled; + ESP32::RmtSigReader sig_reader; }; diff --git a/libraries/AP_HAL_ESP32/RCOutput.cpp b/libraries/AP_HAL_ESP32/RCOutput.cpp index 20d8630194ef29..2c6a7ac5307432 100644 --- a/libraries/AP_HAL_ESP32/RCOutput.cpp +++ b/libraries/AP_HAL_ESP32/RCOutput.cpp @@ -12,7 +12,7 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * - * Code by Charles "Silvanosky" Villard and David "Buzz" Bussenschutt + * Code by Charles "Silvanosky" Villard, David "Buzz" Bussenschutt and Andrey "ARg" Romanov * */ @@ -27,6 +27,13 @@ #include +#include "esp_log.h" + +#define SERVO_TIMEBASE_RESOLUTION_HZ 1000000 // 1MHz, 1us per tick +#define SERVO_TIMEBASE_PERIOD 20000 // 20000 ticks, 20ms + +#define TAG "RCOut" + extern const AP_HAL::HAL& hal; using namespace ESP32; @@ -50,63 +57,90 @@ void RCOutput::init() { _max_channels = MAX_CHANNELS; - - //32 and 33 are special as they dont default to gpio, but can be if u disable their rtc setup: +#ifdef CONFIG_IDF_TARGET_ESP32 + // only on plain esp32 + // 32 and 33 are special as they dont default to gpio, but can be if u disable their rtc setup: rtc_gpio_deinit(GPIO_NUM_32); rtc_gpio_deinit(GPIO_NUM_33); +#endif printf("oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo\n"); printf("RCOutput::init() - channels available: %d \n",(int)MAX_CHANNELS); printf("oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo\n"); - static const mcpwm_io_signals_t signals[] = { - MCPWM0A, - MCPWM0B, - MCPWM1A, - MCPWM1B, - MCPWM2A, - MCPWM2B - }; - static const mcpwm_timer_t timers[] = { - MCPWM_TIMER_0, - MCPWM_TIMER_1, - MCPWM_TIMER_2 - - }; - static const mcpwm_unit_t units[] = { - MCPWM_UNIT_0, - MCPWM_UNIT_1 - }; - static const mcpwm_operator_t operators[] = { - MCPWM_OPR_A, - MCPWM_OPR_B - }; - - for (uint8_t i = 0; i < MAX_CHANNELS; ++i) { - auto unit = units[i/6]; - auto signal = signals[i % 6]; - auto timer = timers[i/2]; + const int MCPWM_CNT = SOC_MCPWM_OPERATORS_PER_GROUP*SOC_MCPWM_GENERATORS_PER_OPERATOR; + + for (int i = 0; i < MAX_CHANNELS; ++i) { + + mcpwm_timer_handle_t h_timer; + mcpwm_oper_handle_t h_oper; + + ESP_LOGI(TAG, "Initialize CH%02d", i+1); //Save struct infos pwm_out &out = pwm_group_list[i]; + out.group_id = i/MCPWM_CNT; out.gpio_num = outputs_pins[i]; - out.unit_num = unit; - out.timer_num = timer; - out.io_signal = signal; - out.op = operators[i%2]; out.chan = i; - //Setup gpio - mcpwm_gpio_init(unit, signal, outputs_pins[i]); - //Setup MCPWM module - mcpwm_config_t pwm_config; - pwm_config.frequency = 50; //frequency = 50Hz, i.e. for every servo motor time period should be 20ms - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 0 - pwm_config.cmpr_b = 0; //duty cycle of PWMxb = 0 - pwm_config.counter_mode = MCPWM_UP_COUNTER; - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; - mcpwm_init(unit, timer, &pwm_config); - mcpwm_start(unit, timer); + if (0 == i % MCPWM_CNT) { + + mcpwm_timer_config_t timer_config = { + .group_id = out.group_id, + .clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT, + .resolution_hz = SERVO_TIMEBASE_RESOLUTION_HZ, + .count_mode = MCPWM_TIMER_COUNT_MODE_UP, + .period_ticks = SERVO_TIMEBASE_PERIOD, + }; + + ESP_LOGI(TAG, "Initialize timer"); + ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config, &h_timer)); + + out.freq = timer_config.resolution_hz/timer_config.period_ticks; + + ESP_LOGI(TAG, "Enable and start timer"); + ESP_ERROR_CHECK(mcpwm_timer_enable(h_timer)); + ESP_ERROR_CHECK(mcpwm_timer_start_stop(h_timer, MCPWM_TIMER_START_NO_STOP)); + } + out.h_timer = h_timer; + + + if (0 == i % SOC_MCPWM_GENERATORS_PER_OPERATOR) { + + ESP_LOGI(TAG, "Initialize operator"); + + mcpwm_operator_config_t operator_config = { + .group_id = out.group_id, // operator must be in the same group to the timer + }; + ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config, &h_oper)); + } + out.h_oper = h_oper; + + ESP_LOGI(TAG, "Connect timer and operator"); + ESP_ERROR_CHECK(mcpwm_operator_connect_timer(out.h_oper, out.h_timer)); + + ESP_LOGI(TAG, "Create comparator and generator from the operator"); + mcpwm_comparator_config_t comparator_config = {}; + comparator_config.flags.update_cmp_on_tez = true; + + ESP_ERROR_CHECK(mcpwm_new_comparator(out.h_oper, &comparator_config, &out.h_cmpr)); + + mcpwm_generator_config_t generator_config = { + .gen_gpio_num = out.gpio_num, + }; + ESP_ERROR_CHECK(mcpwm_new_generator(out.h_oper, &generator_config, &out.h_gen)); + + ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(out.h_cmpr, 1500)); + out.value = 1500; + + ESP_LOGI(TAG, "Set generator action on timer and compare event"); + // go high on counter empty + ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(out.h_gen, + MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH))); + // go low on compare threshold + ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(out.h_gen, + MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, out.h_cmpr, MCPWM_GEN_ACTION_LOW))); + } _initialized = true; @@ -123,7 +157,8 @@ void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) for (uint8_t i = 0; i < MAX_CHANNELS; i++) { if (chmask & 1 << i) { pwm_out &out = pwm_group_list[i]; - mcpwm_set_frequency(out.unit_num, out.timer_num, freq_hz); + ESP_ERROR_CHECK(mcpwm_timer_set_period( out.h_timer, SERVO_TIMEBASE_RESOLUTION_HZ/freq_hz)); + out.freq = freq_hz; } } } @@ -143,7 +178,7 @@ uint16_t RCOutput::get_freq(uint8_t chan) } pwm_out &out = pwm_group_list[chan]; - return mcpwm_get_frequency(out.unit_num, out.timer_num); + return out.freq; } void RCOutput::enable_ch(uint8_t chan) @@ -153,7 +188,7 @@ void RCOutput::enable_ch(uint8_t chan) } pwm_out &out = pwm_group_list[chan]; - mcpwm_start(out.unit_num, out.timer_num); + ESP_ERROR_CHECK(mcpwm_timer_start_stop(out.h_timer, MCPWM_TIMER_START_NO_STOP)); } void RCOutput::disable_ch(uint8_t chan) @@ -164,7 +199,7 @@ void RCOutput::disable_ch(uint8_t chan) write(chan, 0); pwm_out &out = pwm_group_list[chan]; - mcpwm_stop(out.unit_num, out.timer_num); + ESP_ERROR_CHECK(mcpwm_timer_start_stop(out.h_timer, MCPWM_TIMER_STOP_EMPTY)); } void RCOutput::write(uint8_t chan, uint16_t period_us) @@ -189,9 +224,7 @@ uint16_t RCOutput::read(uint8_t chan) } pwm_out &out = pwm_group_list[chan]; - double freq = mcpwm_get_frequency(out.unit_num, out.timer_num); - double dprc = mcpwm_get_duty(out.unit_num, out.timer_num, out.op); - return (1000000.0 * (dprc / 100.)) / freq; + return out.value; } void RCOutput::read(uint16_t *period_us, uint8_t len) @@ -248,7 +281,8 @@ void RCOutput::write_int(uint8_t chan, uint16_t period_us) } pwm_out &out = pwm_group_list[chan]; - mcpwm_set_duty_in_us(out.unit_num, out.timer_num, out.op, period_us); + ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(out.h_cmpr, period_us)); + out.value = period_us; } /* @@ -312,12 +346,12 @@ void RCOutput::safety_update(void) } #ifdef HAL_GPIO_PIN_SAFETY_IN - //TODO replace palReadLine - // handle safety button - bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN); + gpio_set_direction((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN, GPIO_MODE_INPUT); + gpio_set_pull_mode((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN, GPIO_PULLDOWN_ONLY); + bool safety_pressed = gpio_get_level((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN); if (safety_pressed) { AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton(); - if (safety_press_count < 255) { + if (safety_press_count < UINT8_MAX) { safety_press_count++; } if (brdconfig && brdconfig->safety_button_handle_pressed(safety_press_count)) { @@ -335,8 +369,7 @@ void RCOutput::safety_update(void) #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; - palWriteLine(HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1); - //TODO replace palReadwrite + gpio_set_level((gpio_num_t)HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1); #endif } diff --git a/libraries/AP_HAL_ESP32/RCOutput.h b/libraries/AP_HAL_ESP32/RCOutput.h index cf70a8fb89d4e4..bdaf4f348322a9 100644 --- a/libraries/AP_HAL_ESP32/RCOutput.h +++ b/libraries/AP_HAL_ESP32/RCOutput.h @@ -12,7 +12,7 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * - * Code by Charles "Silvanosky" Villard and David "Buzz" Bussenschutt + * Code by Charles "Silvanosky" Villard, David "Buzz" Bussenschutt and Andrey "ARg" Romanov * */ @@ -21,10 +21,12 @@ #include #include "HAL_ESP32_Namespace.h" -#include "driver/mcpwm.h" #define HAL_PARAM_DEFAULTS_PATH nullptr #include +#include "driver/gpio.h" +#include "driver/mcpwm_prelude.h" + namespace ESP32 { @@ -96,13 +98,19 @@ class RCOutput : public AP_HAL::RCOutput private: + struct pwm_out { - int gpio_num; - mcpwm_unit_t unit_num; - mcpwm_timer_t timer_num; - mcpwm_io_signals_t io_signal; - mcpwm_operator_t op; - uint8_t chan; + + uint8_t chan; + uint8_t gpio_num; + uint8_t group_id; + int freq; + int value; + + mcpwm_timer_handle_t h_timer; + mcpwm_oper_handle_t h_oper; + mcpwm_cmpr_handle_t h_cmpr; + mcpwm_gen_handle_t h_gen; }; diff --git a/libraries/AP_HAL_ESP32/README.md b/libraries/AP_HAL_ESP32/README.md index e891fa9571edad..cfd829fcde7669 100644 --- a/libraries/AP_HAL_ESP32/README.md +++ b/libraries/AP_HAL_ESP32/README.md @@ -14,11 +14,11 @@ or Tools/environment_install/install-prereqs-arch.sh ``` -3. install esp-idf python deps: +2. install esp-idf python deps: ``` # from: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/get-started/linux-setup.html -sudo apt-get install git wget flex bison gperf python-setuptools cmake ninja-build ccache libffi-dev libssl-dev dfu-util +sudo apt-get install git wget flex bison gperf cmake ninja-build ccache libffi-dev libssl-dev dfu-util sudo apt-get install python3 python3-pip python3-setuptools sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10 @@ -61,7 +61,7 @@ TIPS: - we use toolchain and esp-idf from espressif , as a 'git submodule', so no need to preinstall etc. https://docs.espressif.com/projects/esp-idf/en/latest/get-started/ - - (note we currently use https://github.com/espressif/esp-idf/tree/release/v4.0 ) + (note we currently use https://github.com/espressif/esp-idf/tree/release/v5.3 ) - if you get compile error/s to do with CONFIG... such as @@ -69,7 +69,12 @@ in expansion of macro 'configSUPPORT_STATIC_ALLOCATION' warning: "CONFIG_SUPPORT_STATIC_ALLOCATION" is not defined this means your 'sdkconfig' file that the IDF relies on is perhaps a bit out of date or out of sync with your IDF. -So double check you are using the correct IDF version ( buzz's branch uses v3.3 , sh83's probably does not.. and then if you are sure: + +You can simply remove sdkconfig file and idf build system will recreate it using sdkconfig.defaults, which should fix the problem. + +If you need to change sdkconfig, you can edit sdkconfig manually or to use ninja menuconfig: + +So double check you are using the correct IDF version: ``` cd build/esp32{BOARD}/esp-idf_build ninja menuconfig @@ -81,11 +86,7 @@ press [tab] then enter on the [exit] box to exit the app done. the 'sdkconfig' file in this folder should have been updated cd ../../../.. -OR locate the 'libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig' and delete it, as it should call back to the 'sdkconfig.defaults' file if its not there. - -'cd libraries/AP_HAL_ESP32/targets/esp32/esp-idf ; idf.py defconfig' is the command that updates it, but that shouldn't be needed manually, we don't think. - -... try ./waf plane" +If you want to make changes to sdkconfig (sdkconfig is in git ignore list) permanent and to commit them back in git, you should edit sdkconfig.defaults manually or to use ninja save-defconfig tool after menuconfig. 5. Recommanded way to flash the firmware : ``` @@ -114,9 +115,6 @@ ESPTOOL_BAUD=921600 You can find more info here : [ESPTOOL](https://github.com/espressif/esptool) -You can also find the cmake esp-idf project at `libraries/AP_HAL_ESP32/targets/esp32/esp-idf` for idf.py command. But see next section to understand how ardupilot is compiled on ESP32. - - For flashing from another machine you need the following files: ``` build//esp-idf_build/bootloader/bootloader.bin diff --git a/libraries/AP_HAL_ESP32/RmtSigReader.cpp b/libraries/AP_HAL_ESP32/RmtSigReader.cpp index c0b1e2c1a5ee6b..54d1d42fb3b758 100644 --- a/libraries/AP_HAL_ESP32/RmtSigReader.cpp +++ b/libraries/AP_HAL_ESP32/RmtSigReader.cpp @@ -9,7 +9,7 @@ void RmtSigReader::init() { rmt_config_t config; config.rmt_mode = RMT_MODE_RX; - config.channel = RMT_CHANNEL_0; + config.channel = RMT_CHANNEL_4; // On S3, Channel 0 ~ 3 (TX channel) are dedicated to sending signals. Channel 4 ~ 7 (RX channel) are dedicated to receiving signals, so this pin choice is compatible with both. config.clk_div = 80; //80MHZ APB clock to the 1MHZ target frequency config.gpio_num = HAL_ESP32_RCIN; config.mem_block_num = 2; //each block could store 64 pulses diff --git a/libraries/AP_HAL_ESP32/SPIDevice.cpp b/libraries/AP_HAL_ESP32/SPIDevice.cpp index 2fa7bd463a5af2..98e5f126198dd4 100644 --- a/libraries/AP_HAL_ESP32/SPIDevice.cpp +++ b/libraries/AP_HAL_ESP32/SPIDevice.cpp @@ -60,7 +60,7 @@ SPIDevice::SPIDevice(SPIBus &_bus, SPIDeviceDesc &_device_desc) set_device_bus(bus.bus); set_device_address(_device_desc.device); set_speed(AP_HAL::Device::SPEED_LOW); - gpio_pad_select_gpio(device_desc.cs); + esp_rom_gpio_pad_select_gpio(device_desc.cs); gpio_set_direction(device_desc.cs, GPIO_MODE_OUTPUT); gpio_set_level(device_desc.cs, 1); @@ -220,7 +220,7 @@ SPIDeviceManager::get_device(const char *name) #endif if (busp == nullptr) { // create a new one - busp = new SPIBus(desc.bus); + busp = NEW_NOTHROW SPIBus(desc.bus); if (busp == nullptr) { return nullptr; } @@ -233,6 +233,6 @@ SPIDeviceManager::get_device(const char *name) printf("%s:%d 444\n", __PRETTY_FUNCTION__, __LINE__); #endif - return AP_HAL::OwnPtr(new SPIDevice(*busp, desc)); + return AP_HAL::OwnPtr(NEW_NOTHROW SPIDevice(*busp, desc)); } diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index f4a69e2b105d60..39413f9331b2b3 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -23,8 +23,6 @@ #include "freertos/FreeRTOS.h" #include "freertos/task.h" -#include "soc/rtc_wdt.h" -#include "esp_int_wdt.h" #include "esp_task_wdt.h" #include @@ -38,39 +36,33 @@ using namespace ESP32; extern const AP_HAL::HAL& hal; bool Scheduler::_initialized = true; -TaskHandle_t idle_0 = NULL; -TaskHandle_t idle_1 = NULL; Scheduler::Scheduler() { _initialized = false; } -void disableCore0WDT() +Scheduler::~Scheduler() { - idle_0 = xTaskGetIdleTaskHandleForCPU(0); - if (idle_0 == NULL || esp_task_wdt_delete(idle_0) != ESP_OK) { - //print("Failed to remove Core 0 IDLE task from WDT"); + if (_initialized) { + esp_task_wdt_deinit(); } } -void disableCore1WDT() +void Scheduler::wdt_init(uint32_t timeout, uint32_t core_mask) { - idle_1 = xTaskGetIdleTaskHandleForCPU(1); - if (idle_1 == NULL || esp_task_wdt_delete(idle_1) != ESP_OK) { - //print("Failed to remove Core 1 IDLE task from WDT"); - } -} -void enableCore0WDT() -{ - if (idle_0 != NULL && esp_task_wdt_add(idle_0) != ESP_OK) { - //print("Failed to add Core 0 IDLE task to WDT"); + esp_task_wdt_config_t config = { + .timeout_ms = timeout, + .idle_core_mask = core_mask, + .trigger_panic = true + }; + + if ( ESP_OK != esp_task_wdt_init(&config) ) { + printf("esp_task_wdt_init() failed\n"); } -} -void enableCore1WDT() -{ - if (idle_1 != NULL && esp_task_wdt_add(idle_1) != ESP_OK) { - //print("Failed to add Core 1 IDLE task to WDT"); + + if (ESP_OK != esp_task_wdt_add(NULL)) { + printf("esp_task_wdt_add(NULL) failed"); } } @@ -81,11 +73,6 @@ void Scheduler::init() printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); #endif - // disable wd while booting, as things like mounting the sd-card in the io thread can take a while, especially if there isn't hardware attached. - disableCore0WDT(); //FASTCPU - disableCore1WDT(); //SLOWCPU - - hal.console->printf("%s:%d running with CONFIG_FREERTOS_HZ=%d\n", __PRETTY_FUNCTION__, __LINE__,CONFIG_FREERTOS_HZ); // keep main tasks that need speed on CPU 0 @@ -140,11 +127,6 @@ void Scheduler::init() } // xTaskCreatePinnedToCore(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr,SLOWCPU); - - hal.console->printf("OK Sched Init, enabling WD\n"); - enableCore0WDT(); //FASTCPU - //enableCore1WDT(); //we don't enable WD on SLOWCPU right now. - } template @@ -153,7 +135,7 @@ void executor(T oui) oui(); } -void Scheduler::thread_create_trampoline(void *ctx) +void IRAM_ATTR Scheduler::thread_create_trampoline(void *ctx) { AP_HAL::MemberProc *t = (AP_HAL::MemberProc *)ctx; (*t)(); @@ -216,7 +198,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ return true; } -void Scheduler::delay(uint16_t ms) +void IRAM_ATTR Scheduler::delay(uint16_t ms) { uint64_t start = AP_HAL::micros64(); while ((AP_HAL::micros64() - start)/1000 < ms) { @@ -229,10 +211,10 @@ void Scheduler::delay(uint16_t ms) } } -void Scheduler::delay_microseconds(uint16_t us) +void IRAM_ATTR Scheduler::delay_microseconds(uint16_t us) { if (in_main_thread() && us < 100) { - ets_delay_us(us); + esp_rom_delay_us(us); } else { // Minimum delay for FreeRTOS is 1ms uint32_t tick = portTICK_PERIOD_MS * 1000; @@ -240,7 +222,7 @@ void Scheduler::delay_microseconds(uint16_t us) } } -void Scheduler::register_timer_process(AP_HAL::MemberProc proc) +void IRAM_ATTR Scheduler::register_timer_process(AP_HAL::MemberProc proc) { #ifdef SCHEDDEBUG printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); @@ -260,7 +242,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc) _timer_sem.give(); } -void Scheduler::register_io_process(AP_HAL::MemberProc proc) +void IRAM_ATTR Scheduler::register_io_process(AP_HAL::MemberProc proc) { #ifdef SCHEDDEBUG printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); @@ -281,7 +263,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc) _io_sem.give(); } -void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) +void IRAM_ATTR Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) { _failsafe = failsafe; } @@ -294,7 +276,7 @@ void Scheduler::reboot(bool hold_in_bootloader) esp_restart(); } -bool Scheduler::in_main_thread() const +bool IRAM_ATTR Scheduler::in_main_thread() const { return _main_task_handle == xTaskGetCurrentTaskHandle(); } @@ -316,7 +298,7 @@ bool Scheduler::is_system_initialized() return _initialized; } -void Scheduler::_timer_thread(void *arg) +void IRAM_ATTR Scheduler::_timer_thread(void *arg) { #ifdef SCHEDDEBUG printf("%s:%d start\n", __PRETTY_FUNCTION__, __LINE__); @@ -343,7 +325,7 @@ void Scheduler::_timer_thread(void *arg) } } -void Scheduler::_rcout_thread(void* arg) +void IRAM_ATTR Scheduler::_rcout_thread(void* arg) { Scheduler *sched = (Scheduler *)arg; while (!_initialized) { @@ -357,7 +339,7 @@ void Scheduler::_rcout_thread(void* arg) } } -void Scheduler::_run_timers() +void IRAM_ATTR Scheduler::_run_timers() { #ifdef SCHEDULERDEBUG printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); @@ -391,7 +373,7 @@ void Scheduler::_run_timers() _in_timer_proc = false; } -void Scheduler::_rcin_thread(void *arg) +void IRAM_ATTR Scheduler::_rcin_thread(void *arg) { Scheduler *sched = (Scheduler *)arg; while (!_initialized) { @@ -404,7 +386,7 @@ void Scheduler::_rcin_thread(void *arg) } } -void Scheduler::_run_io(void) +void IRAM_ATTR Scheduler::_run_io(void) { #ifdef SCHEDULERDEBUG printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); @@ -430,7 +412,7 @@ void Scheduler::_run_io(void) _in_io_proc = false; } -void Scheduler::_io_thread(void* arg) +void IRAM_ATTR Scheduler::_io_thread(void* arg) { #ifdef SCHEDDEBUG printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); @@ -496,7 +478,7 @@ void Scheduler::_print_profile(void* arg) } -void Scheduler::_uart_thread(void *arg) +void IRAM_ATTR Scheduler::_uart_thread(void *arg) { #ifdef SCHEDDEBUG printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); @@ -519,7 +501,7 @@ void Scheduler::_uart_thread(void *arg) // get the active main loop rate -uint16_t Scheduler::get_loop_rate_hz(void) +uint16_t IRAM_ATTR Scheduler::get_loop_rate_hz(void) { if (_active_loop_rate_hz == 0) { _active_loop_rate_hz = _loop_rate_hz; @@ -549,9 +531,9 @@ void Scheduler::print_main_loop_rate(void) if (AP_HAL::millis64() - last_run > 10000) { last_run = AP_HAL::millis64(); // null pointer in here... - //const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz(); - //const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz(); - //hal.console->printf("loop_rate: actual: %uHz, expected: %uHz\n", + const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz(); + const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz(); + hal.console->printf("loop_rate: actual: %fHz, expected: %uHz\n", actual_loop_rate, expected_loop_rate); } } @@ -571,6 +553,10 @@ void IRAM_ATTR Scheduler::_main_thread(void *arg) sched->set_system_initialized(); + //initialize WTD for current thread on FASTCPU, all cores will be (1 << CONFIG_FREERTOS_NUMBER_OF_CORES) - 1 + wdt_init( TWDT_TIMEOUT_MS, 1 << FASTCPU ); // 3 sec + + #ifdef SCHEDDEBUG printf("%s:%d initialised\n", __PRETTY_FUNCTION__, __LINE__); #endif @@ -579,8 +565,14 @@ void IRAM_ATTR Scheduler::_main_thread(void *arg) sched->delay_microseconds(250); // run stats periodically +#ifdef SCHEDDEBUG sched->print_stats(); +#endif sched->print_main_loop_rate(); + + if (ESP_OK != esp_task_wdt_reset()) { + printf("esp_task_wdt_reset() failed\n"); + }; } } diff --git a/libraries/AP_HAL_ESP32/Scheduler.h b/libraries/AP_HAL_ESP32/Scheduler.h index 237f9532eaef2d..4946735f6c7da4 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.h +++ b/libraries/AP_HAL_ESP32/Scheduler.h @@ -23,7 +23,7 @@ #define ESP32_SCHEDULER_MAX_TIMER_PROCS 10 #define ESP32_SCHEDULER_MAX_IO_PROCS 10 - +#define TWDT_TIMEOUT_MS 3000 /* Scheduler implementation: */ class ESP32::Scheduler : public AP_HAL::Scheduler @@ -31,6 +31,7 @@ class ESP32::Scheduler : public AP_HAL::Scheduler public: Scheduler(); + ~Scheduler(); /* AP_HAL::Scheduler methods */ void init() override; void set_callbacks(AP_HAL::HAL::Callbacks *cb) @@ -69,28 +70,31 @@ class ESP32::Scheduler : public AP_HAL::Scheduler static const int IO_PRIO = 6; static const int STORAGE_PRIO = 6; */ + // configMAX_PRIORITIES=25 + + static const int SPI_PRIORITY = 24; // if your primary imu is spi, this should be above the i2c value, spi is better. - static const int MAIN_PRIO = 22; // cpu0: we want schuler running at full tilt. + static const int MAIN_PRIO = 24; // cpu0: we want scheduler running at full tilt. static const int I2C_PRIORITY = 5; // if your primary imu is i2c, this should be above the spi value, i2c is not preferred. - static const int TIMER_PRIO = 22; // a low priority mere might cause wifi thruput to suffer - static const int RCIN_PRIO = 15; + static const int TIMER_PRIO = 23; //dont make 24. a low priority mere might cause wifi thruput to suffer + static const int RCIN_PRIO = 5; static const int RCOUT_PRIO = 10; static const int WIFI_PRIO1 = 20; //cpu1: static const int WIFI_PRIO2 = 12; //cpu1: - static const int UART_PRIO = 24; //cpu1: a low priority mere might cause wifi thruput to suffer, as wifi gets passed its data frim the uart subsustem in _writebuf/_readbuf + static const int UART_PRIO = 23; //dont make 24, scheduler suffers a bit. cpu1: a low priority mere might cause wifi thruput to suffer, as wifi gets passed its data frim the uart subsustem in _writebuf/_readbuf static const int IO_PRIO = 5; static const int STORAGE_PRIO = 4; - static const int TIMER_SS = 4096; - static const int MAIN_SS = 8192; - static const int RCIN_SS = 4096; - static const int RCOUT_SS = 4096; - static const int WIFI_SS1 = 6192; - static const int WIFI_SS2 = 6192; - static const int UART_SS = 2048; - static const int DEVICE_SS = 4096; - static const int IO_SS = 4096; - static const int STORAGE_SS = 8192; + static const int TIMER_SS = 1024*3; + static const int MAIN_SS = 1024*5; + static const int RCIN_SS = 1024*3; + static const int RCOUT_SS = 1024*1.5; + static const int WIFI_SS1 = 1024*2.25; + static const int WIFI_SS2 = 1024*2.25; + static const int UART_SS = 1024*2.25; + static const int DEVICE_SS = 1024*4; // DEVICEBUS/s + static const int IO_SS = 1024*3.5; // APM_IO + static const int STORAGE_SS = 1024*2; // APM_STORAGE private: AP_HAL::HAL::Callbacks *callbacks; @@ -127,6 +131,8 @@ class ESP32::Scheduler : public AP_HAL::Scheduler static void test_esc(void* arg); + static void wdt_init(uint32_t timeout, uint32_t core_mask); + bool _in_timer_proc; void _run_timers(); Semaphore _timer_sem; diff --git a/libraries/AP_HAL_ESP32/SdCard.cpp b/libraries/AP_HAL_ESP32/SdCard.cpp index 0f91711e1a9a90..4644797cf32e3a 100644 --- a/libraries/AP_HAL_ESP32/SdCard.cpp +++ b/libraries/AP_HAL_ESP32/SdCard.cpp @@ -32,8 +32,6 @@ #include #include "SPIDevice.h" -#include "soc/rtc_wdt.h" - #ifdef HAL_ESP32_SDCARD #if CONFIG_IDF_TARGET_ESP32S2 ||CONFIG_IDF_TARGET_ESP32C3 @@ -254,8 +252,8 @@ void mount_sdcard() { mount_sdcard_spi(); } -#endif // end spi +#endif // end spi bool sdcard_retry(void) { @@ -265,16 +263,14 @@ bool sdcard_retry(void) return sdcard_running; } - void unmount_sdcard() { if (card != nullptr) { - esp_vfs_fat_sdmmc_unmount(); + esp_vfs_fat_sdcard_unmount( "/SDCARD", card); } sdcard_running = false; } - #else // empty impl's void mount_sdcard() diff --git a/libraries/AP_HAL_ESP32/Semaphores.cpp b/libraries/AP_HAL_ESP32/Semaphores.cpp index d76ca820aeae18..cd4189ca1ea9ef 100644 --- a/libraries/AP_HAL_ESP32/Semaphores.cpp +++ b/libraries/AP_HAL_ESP32/Semaphores.cpp @@ -106,7 +106,7 @@ void BinarySemaphore::signal_ISR() { BaseType_t xHigherPriorityTaskWoken = pdFALSE; xSemaphoreGiveFromISR(_sem, &xHigherPriorityTaskWoken); - portYIELD_FROM_ISR(xHigherPriorityTaskWoken); + portYIELD_FROM_ISR_ARG(xHigherPriorityTaskWoken); } BinarySemaphore::~BinarySemaphore(void) diff --git a/libraries/AP_HAL_ESP32/UARTDriver.cpp b/libraries/AP_HAL_ESP32/UARTDriver.cpp index 2cf293a3504821..90befdb6cc1bf3 100644 --- a/libraries/AP_HAL_ESP32/UARTDriver.cpp +++ b/libraries/AP_HAL_ESP32/UARTDriver.cpp @@ -55,7 +55,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) uart_desc[uart_num].rx, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); //uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0); - uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0); + uart_driver_install(p, 2*UART_HW_FIFO_LEN(p), 0, 0, nullptr, 0); _readbuf.set_size(RX_BUF_SIZE); _writebuf.set_size(TX_BUF_SIZE); diff --git a/libraries/AP_HAL_ESP32/Util.cpp b/libraries/AP_HAL_ESP32/Util.cpp index d232ff890765e5..6c4f66d18d2d78 100644 --- a/libraries/AP_HAL_ESP32/Util.cpp +++ b/libraries/AP_HAL_ESP32/Util.cpp @@ -35,6 +35,7 @@ #include "esp_heap_caps.h" #include +#include "esp_mac.h" extern const AP_HAL::HAL& hal; @@ -90,37 +91,11 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) } -#ifdef ENABLE_HEAP - -void *Util::allocate_heap_memory(size_t size) -{ - void *buf = calloc(1, size); - if (buf == nullptr) { - return nullptr; - } - - multi_heap_handle_t *heap = (multi_heap_handle_t *)calloc(1, sizeof(multi_heap_handle_t)); - if (heap != nullptr) { - auto hp = multi_heap_register(buf, size); - memcpy(heap, &hp, sizeof(multi_heap_handle_t)); - } - - return heap; -} - -void *Util::heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) -{ - if (heap == nullptr) { - return nullptr; - } - - return multi_heap_realloc(*(multi_heap_handle_t *)heap, ptr, new_size); -} - +#if ENABLE_HEAP /* - realloc implementation thanks to wolfssl, used by AP_Scripting + realloc implementation thanks to wolfssl, used by ExpandingString */ -void *Util::std_realloc(void *addr, size_t size) +void *Util::std_realloc(void *addr, uint32_t size) { if (size == 0) { free(addr); @@ -200,7 +175,7 @@ uint64_t Util::get_hw_rtc() const #define Debug(fmt, args ...) do { hal.console->printf(fmt, ## args); } while (0) #else #include -#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0) +#define Debug(fmt, args ...) do { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } while (0) #endif Util::FlashBootloader Util::flash_bootloader() @@ -243,15 +218,13 @@ bool Util::get_system_id(char buf[50]) bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len) { - len = MIN(12, len); - - uint8_t base_mac_addr[6] = {0}; esp_err_t ret = esp_efuse_mac_get_custom(base_mac_addr); if (ret != ESP_OK) { ret = esp_efuse_mac_get_default(base_mac_addr); } + len = MIN(len, ARRAY_SIZE(base_mac_addr)); memcpy(buf, (const void *)base_mac_addr, len); return true; diff --git a/libraries/AP_HAL_ESP32/Util.h b/libraries/AP_HAL_ESP32/Util.h index 3360e1ad5a1974..1e5a78bf097961 100644 --- a/libraries/AP_HAL_ESP32/Util.h +++ b/libraries/AP_HAL_ESP32/Util.h @@ -28,21 +28,15 @@ class ESP32::Util : public AP_HAL::Util return static_cast(util); } - bool run_debug_shell(AP_HAL::BetterStream *stream) override - { - return false; - } uint32_t available_memory() override; // Special Allocation Routines void *malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override; void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override; -#ifdef ENABLE_HEAP +#if ENABLE_HEAP // heap functions, note that a heap once alloc'd cannot be dealloc'd - virtual void *allocate_heap_memory(size_t size) override; - virtual void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override; - virtual void *std_realloc(void *ptr, size_t new_size) override; + virtual void *std_realloc(void *ptr, uint32_t new_size) override; #endif // ENABLE_HEAP /* @@ -89,10 +83,6 @@ class ESP32::Util : public AP_HAL::Util FlashBootloader flash_bootloader() override; #endif -#ifdef ENABLE_HEAP - // static memory_heap_t scripting_heap; -#endif // ENABLE_HEAP - // stm32F4 and F7 have 20 total RTC backup registers. We use the first one for boot type // flags, so 19 available for persistent data static_assert(sizeof(persistent_data) <= 19*4, "watchdog persistent data too large"); diff --git a/libraries/AP_HAL_ESP32/WiFiDriver.cpp b/libraries/AP_HAL_ESP32/WiFiDriver.cpp index 9d8b5cfd5c4698..fbc9e85ddb8391 100644 --- a/libraries/AP_HAL_ESP32/WiFiDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiDriver.cpp @@ -56,10 +56,10 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) #define FASTCPU 0 #define SLOWCPU 1 - if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread on FASTCPU\n"); + if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle, SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread for TCP with PORT 5760 on FASTCPU\n"); + hal.console->printf("OK created task _wifi_thread for TCP with PORT 5760 on SLOWCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); @@ -145,7 +145,7 @@ bool WiFiDriver::start_listen() bool WiFiDriver::try_accept() { struct sockaddr_in sourceAddr; - uint addrLen = sizeof(sourceAddr); + socklen_t addrLen = sizeof(sourceAddr); short i = available_socket(); if (i != WIFI_MAX_CONNECTION) { socket_list[i] = accept(accept_socket, (struct sockaddr *)&sourceAddr, &addrLen); @@ -246,7 +246,7 @@ static void _sta_event_handler(void* arg, esp_event_base_t event_base, void WiFiDriver::initialize_wifi() { #ifndef WIFI_PWD - #default WIFI_PWD "ardupilot1" + #define WIFI_PWD "ardupilot1" #endif //Initialize NVS esp_err_t ret = nvs_flash_init(); diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index 9348f56cc7ac89..2d97b4f4910081 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -32,7 +32,7 @@ #include "lwip/sys.h" #include "lwip/netdb.h" -#include "soc/rtc_wdt.h" +#include "freertos/idf_additions.h" using namespace ESP32; @@ -59,10 +59,10 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) #define FASTCPU 0 #define SLOWCPU 1 - if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread2 on FASTCPU\n"); + if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle, SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread2 on SLOWCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread2 for UDP on port 14550 on FASTCPU\n"); //UDP_PORT + hal.console->printf("OK created task _wifi_thread2 for UDP on port 14550 on SLOWCPU\n"); //UDP_PORT } _readbuf.set_size(RX_BUF_SIZE); @@ -215,7 +215,7 @@ static void _sta_event_handler(void* arg, esp_event_base_t event_base, void WiFiUdpDriver::initialize_wifi() { #ifndef WIFI_PWD - #default WIFI_PWD "ardupilot1" + #define WIFI_PWD "ardupilot1" #endif //Initialize NVS esp_err_t ret = nvs_flash_init(); diff --git a/libraries/AP_HAL_ESP32/boards/esp32empty.h b/libraries/AP_HAL_ESP32/boards/esp32empty.h index d95e30f9b2af95..bfea30b74d8cce 100644 --- a/libraries/AP_HAL_ESP32/boards/esp32empty.h +++ b/libraries/AP_HAL_ESP32/boards/esp32empty.h @@ -78,8 +78,10 @@ //SPI Devices #define HAL_ESP32_SPI_DEVICES {} -//RCIN -#define HAL_ESP32_RCIN GPIO_NUM_36 +//RMT pin number +#define HAL_ESP32_RMT_RX_PIN_NUMBER 4 +//RCIN pin number - NOTE: disabled due to issue with legacy rmt library. +// #define HAL_ESP32_RCIN GPIO_NUM_36 //RCOUT #define HAL_ESP32_RCOUT {GPIO_NUM_25, GPIO_NUM_27, GPIO_NUM_33, GPIO_NUM_32, GPIO_NUM_22, GPIO_NUM_21} @@ -124,9 +126,6 @@ //LED #define DEFAULT_NTF_LED_TYPES Notify_LED_None -//RMT pin number -#define HAL_ESP32_RMT_RX_PIN_NUMBER 4 - //SD CARD // Do u want to use mmc or spi mode for the sd card, this is board specific, // as mmc uses specific pins but is quicker, diff --git a/libraries/AP_HAL_ESP32/i2c_sw.c b/libraries/AP_HAL_ESP32/i2c_sw.c index 6caf9e5c6064ed..e2ae274774cb44 100644 --- a/libraries/AP_HAL_ESP32/i2c_sw.c +++ b/libraries/AP_HAL_ESP32/i2c_sw.c @@ -126,8 +126,9 @@ void i2c_init(_i2c_bus_t* bus) case 160: bus->delay = _i2c_delays[bus->speed][1]; break; case 240: bus->delay = _i2c_delays[bus->speed][2]; break; default : DEBUG("i2c I2C software implementation is not " - "supported for this CPU frequency: %d MHz\n", - ets_get_cpu_frequency()); + "supported for this CPU frequency: %u MHz\n", + (unsigned int)ets_get_cpu_frequency() + ); return; } diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt index 5c03820e3f827e..10cca76197529b 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt @@ -15,15 +15,22 @@ idf_build_process(esp32 # although esptool_py does not generate static library, # processing the component is needed for flashing related # targets and file generation - COMPONENTS esp32 - freertos - tcpip_adapter - fatfs - esp_adc_cal - nvs_flash - esptool_py - app_update + COMPONENTS freertos + fatfs + nvs_flash + esptool_py + app_update + esp_adc + esp_driver_mcpwm + driver + lwip + esp_wifi + esp_system + esp_rom + esp_timer + SDKCONFIG ${CMAKE_CURRENT_LIST_DIR}/sdkconfig + SDKCONFIG_DEFAULTS ${CMAKE_CURRENT_LIST_DIR}/sdkconfig.defaults BUILD_DIR ${CMAKE_BINARY_DIR}) set(elf_file ardupilot.elf) @@ -94,14 +101,19 @@ add_custom_target(showinc ALL # Link the static libraries to the executable target_link_libraries(${elf_file} - idf::esp32 idf::freertos idf::fatfs - idf::esp_adc_cal idf::nvs_flash idf::spi_flash - idf::tcpip_adapter idf::app_update + idf::esp_adc + idf::esp_driver_mcpwm + idf::driver + idf::lwip + idf::esp_wifi + idf::esp_system + idf::esp_rom + idf::esp_timer ) # Attach additional targets to the executable file for flashing, diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig deleted file mode 100644 index d5823701001e8f..00000000000000 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +++ /dev/null @@ -1,1219 +0,0 @@ -# -# Automatically generated file. DO NOT EDIT. -# Espressif IoT Development Framework (ESP-IDF) Project Configuration -# -CONFIG_IDF_CMAKE=y -CONFIG_IDF_TARGET_ARCH_XTENSA=y -CONFIG_IDF_TARGET="esp32" -CONFIG_IDF_TARGET_ESP32=y -CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000 - -# -# SDK tool configuration -# -CONFIG_SDK_TOOLPREFIX="xtensa-esp32-elf-" -# CONFIG_SDK_TOOLCHAIN_SUPPORTS_TIME_WIDE_64_BITS is not set -# end of SDK tool configuration - -# -# Build type -# -CONFIG_APP_BUILD_TYPE_APP_2NDBOOT=y -# CONFIG_APP_BUILD_TYPE_ELF_RAM is not set -CONFIG_APP_BUILD_GENERATE_BINARIES=y -CONFIG_APP_BUILD_BOOTLOADER=y -CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y -# end of Build type - -# -# Application manager -# -# CONFIG_APP_COMPILE_TIME_DATE is not set -CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y -CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y -# CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set -CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 -# end of Application manager - -# -# Bootloader config -# -CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x1000 -CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_NONE is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_NONE is not set -CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y -# CONFIG_BOOTLOADER_LOG_LEVEL_WARN is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_INFO is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_DEBUG is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_VERBOSE is not set -CONFIG_BOOTLOADER_LOG_LEVEL=1 -# CONFIG_BOOTLOADER_SPI_CUSTOM_WP_PIN is not set -CONFIG_BOOTLOADER_SPI_WP_PIN=7 -CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y -# CONFIG_BOOTLOADER_FACTORY_RESET is not set -# CONFIG_BOOTLOADER_APP_TEST is not set -CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y -CONFIG_BOOTLOADER_WDT_ENABLE=n -# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set -CONFIG_BOOTLOADER_WDT_TIME_MS=9000 -# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_ALWAYS is not set -CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0 -# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set -CONFIG_BOOTLOADER_FLASH_XMC_SUPPORT=y -# end of Bootloader config - -# -# Security features -# -# CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set -# CONFIG_SECURE_BOOT is not set -# CONFIG_SECURE_FLASH_ENC_ENABLED is not set -# end of Security features - -# -# Serial flasher config -# -CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200 -# CONFIG_ESPTOOLPY_NO_STUB is not set -CONFIG_ESPTOOLPY_FLASHMODE_QIO=y -# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set -# CONFIG_ESPTOOLPY_FLASHMODE_DIO is not set -# CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set -CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y -CONFIG_ESPTOOLPY_FLASHMODE="dio" -CONFIG_ESPTOOLPY_FLASHFREQ_80M=y -# CONFIG_ESPTOOLPY_FLASHFREQ_40M is not set -# CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set -# CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set -CONFIG_ESPTOOLPY_FLASHFREQ="80m" -# CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_2MB is not set -CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y -# CONFIG_ESPTOOLPY_FLASHSIZE_8MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_32MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_64MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_128MB is not set -CONFIG_ESPTOOLPY_FLASHSIZE="4MB" -CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y -CONFIG_ESPTOOLPY_BEFORE_RESET=y -# CONFIG_ESPTOOLPY_BEFORE_NORESET is not set -CONFIG_ESPTOOLPY_BEFORE="default_reset" -CONFIG_ESPTOOLPY_AFTER_RESET=y -# CONFIG_ESPTOOLPY_AFTER_NORESET is not set -CONFIG_ESPTOOLPY_AFTER="hard_reset" -# CONFIG_ESPTOOLPY_MONITOR_BAUD_CONSOLE is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_9600B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set -CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y -# CONFIG_ESPTOOLPY_MONITOR_BAUD_230400B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_921600B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_2MB is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER is not set -CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER_VAL=115200 -CONFIG_ESPTOOLPY_MONITOR_BAUD=115200 -# end of Serial flasher config - -# -# Partition Table -# -# CONFIG_PARTITION_TABLE_SINGLE_APP is not set -# CONFIG_PARTITION_TABLE_SINGLE_APP_LARGE is not set -# CONFIG_PARTITION_TABLE_TWO_OTA is not set -CONFIG_PARTITION_TABLE_CUSTOM=y -CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv" -CONFIG_PARTITION_TABLE_FILENAME="../partitions.csv" -CONFIG_PARTITION_TABLE_OFFSET=0x8000 -CONFIG_PARTITION_TABLE_MD5=y -# end of Partition Table - -# -# Compiler options -# -# CONFIG_COMPILER_OPTIMIZATION_DEFAULT is not set -# CONFIG_COMPILER_OPTIMIZATION_SIZE is not set -CONFIG_COMPILER_OPTIMIZATION_PERF=y -# CONFIG_COMPILER_OPTIMIZATION_NONE is not set -CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y -# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set -# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE is not set -CONFIG_COMPILER_OPTIMIZATION_ASSERTION_LEVEL=2 -# CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT is not set -CONFIG_COMPILER_HIDE_PATHS_MACROS=y -# CONFIG_COMPILER_CXX_EXCEPTIONS is not set -# CONFIG_COMPILER_CXX_RTTI is not set -CONFIG_COMPILER_STACK_CHECK_MODE_NONE=y -# CONFIG_COMPILER_STACK_CHECK_MODE_NORM is not set -# CONFIG_COMPILER_STACK_CHECK_MODE_STRONG is not set -# CONFIG_COMPILER_STACK_CHECK_MODE_ALL is not set -# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set -# CONFIG_COMPILER_DISABLE_GCC8_WARNINGS is not set -# CONFIG_COMPILER_DUMP_RTL_FILES is not set -# end of Compiler options - -# -# Component config -# - -# -# Application Level Tracing -# -# CONFIG_APPTRACE_DEST_JTAG is not set -CONFIG_APPTRACE_DEST_NONE=y -CONFIG_APPTRACE_LOCK_ENABLE=y -# end of Application Level Tracing - -# -# Driver configurations -# - -# -# ADC configuration -# -# CONFIG_ADC_FORCE_XPD_FSM is not set -CONFIG_ADC_DISABLE_DAC=y -# end of ADC configuration - -# -# MCPWM configuration -# -# CONFIG_MCPWM_ISR_IN_IRAM is not set -# end of MCPWM configuration - -# -# SPI configuration -# -CONFIG_SPI_MASTER_IN_IRAM=y -CONFIG_SPI_MASTER_ISR_IN_IRAM=y -# CONFIG_SPI_SLAVE_IN_IRAM is not set -CONFIG_SPI_SLAVE_ISR_IN_IRAM=y -# end of SPI configuration - -# -# TWAI configuration -# -# CONFIG_TWAI_ISR_IN_IRAM is not set -# CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC is not set -# CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set -# CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID is not set -# CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT is not set -# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set -# end of TWAI configuration - -# -# UART configuration -# -# CONFIG_UART_ISR_IN_IRAM is not set -# end of UART configuration - -# -# RTCIO configuration -# -# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set -# end of RTCIO configuration - -# -# GPIO Configuration -# -# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set -# end of GPIO Configuration - -# -# GDMA Configuration -# -# CONFIG_GDMA_CTRL_FUNC_IN_IRAM is not set -# CONFIG_GDMA_ISR_IRAM_SAFE is not set -# end of GDMA Configuration -# end of Driver configurations - -# -# eFuse Bit Manager -# -# CONFIG_EFUSE_CUSTOM_TABLE is not set -# CONFIG_EFUSE_VIRTUAL is not set -# CONFIG_EFUSE_CODE_SCHEME_COMPAT_NONE is not set -CONFIG_EFUSE_CODE_SCHEME_COMPAT_3_4=y -# CONFIG_EFUSE_CODE_SCHEME_COMPAT_REPEAT is not set -CONFIG_EFUSE_MAX_BLK_LEN=192 -# end of eFuse Bit Manager - -# -# ESP32-specific -# -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_1_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -# CONFIG_ESP32_REV_MIN_3_1 is not set -CONFIG_ESP32_REV_MIN=0 -CONFIG_ESP32_REV_MIN_FULL=0 -CONFIG_ESP_REV_MIN_FULL=0 -CONFIG_ESP32_REV_MAX_FULL_STR_OPT=y -CONFIG_ESP32_REV_MAX_FULL=399 -CONFIG_ESP_REV_MAX_FULL=399 -CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 -# CONFIG_ESP32_SPIRAM_SUPPORT is not set -# CONFIG_ESP32_TRAX is not set -CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -# CONFIG_ESP32_ULP_COPROC_ENABLED is not set -CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0 -CONFIG_ESP32_DEBUG_OCDAWARE=y -CONFIG_ESP32_BROWNOUT_DET=y -CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_1 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_2 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_3 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_4 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_5 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_6 is not set -# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_7 is not set -CONFIG_ESP32_BROWNOUT_DET_LVL=0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 -CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 -CONFIG_ESP32_XTAL_FREQ_40=y -# CONFIG_ESP32_XTAL_FREQ_26 is not set -# CONFIG_ESP32_XTAL_FREQ_AUTO is not set -CONFIG_ESP32_XTAL_FREQ=40 -# CONFIG_ESP32_DISABLE_BASIC_ROM_CONSOLE is not set -# CONFIG_ESP32_NO_BLOBS is not set -# CONFIG_ESP32_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set -# CONFIG_ESP32_COMPATIBLE_PRE_V3_1_BOOTLOADERS is not set -# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set -CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5 -# end of ESP32-specific - -# -# ADC-Calibration -# -CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y -CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y -CONFIG_ADC_CAL_LUT_ENABLE=y -# end of ADC-Calibration - -# -# Common ESP-related -# -CONFIG_ESP_ERR_TO_NAME_LOOKUP=y -# end of Common ESP-related - -# -# Ethernet -# -CONFIG_ETH_ENABLED=y -CONFIG_ETH_USE_ESP32_EMAC=y -CONFIG_ETH_PHY_INTERFACE_RMII=y -CONFIG_ETH_RMII_CLK_INPUT=y -# CONFIG_ETH_RMII_CLK_OUTPUT is not set -CONFIG_ETH_RMII_CLK_IN_GPIO=0 -CONFIG_ETH_DMA_BUFFER_SIZE=512 -CONFIG_ETH_DMA_RX_BUFFER_NUM=10 -CONFIG_ETH_DMA_TX_BUFFER_NUM=10 -CONFIG_ETH_USE_SPI_ETHERNET=y -CONFIG_ETH_SPI_ETHERNET_DM9051=y -# CONFIG_ETH_SPI_ETHERNET_W5500 is not set -# CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set -# CONFIG_ETH_USE_OPENETH is not set -# end of Ethernet - -# -# Event Loop Library -# -# CONFIG_ESP_EVENT_LOOP_PROFILING is not set -CONFIG_ESP_EVENT_POST_FROM_ISR=y -CONFIG_ESP_EVENT_POST_FROM_IRAM_ISR=y -# end of Event Loop Library - -# -# GDB Stub -# -# end of GDB Stub - -# -# Hardware Settings -# - -# -# MAC Config -# -CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y -CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y -CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y -# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set -CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 -# CONFIG_ESP_MAC_IGNORE_MAC_CRC_ERROR is not set -# end of MAC Config - -# -# Sleep Config -# -# CONFIG_ESP_SLEEP_POWER_DOWN_FLASH is not set -CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y -# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set -CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y -# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set -CONFIG_ESP_SLEEP_GPIO_ENABLE_INTERNAL_RESISTORS=y -# end of Sleep Config - -# -# RTC Clock Config -# -# end of RTC Clock Config -# end of Hardware Settings - -# -# IPC (Inter-Processor Call) -# -CONFIG_ESP_IPC_TASK_STACK_SIZE=1024 -CONFIG_ESP_IPC_USES_CALLERS_PRIORITY=y -CONFIG_ESP_IPC_ISR_ENABLE=y -# end of IPC (Inter-Processor Call) - -# -# ESP NETIF Adapter -# -CONFIG_ESP_NETIF_IP_LOST_TIMER_INTERVAL=120 -CONFIG_ESP_NETIF_TCPIP_LWIP=y -# CONFIG_ESP_NETIF_LOOPBACK is not set -CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y -# end of ESP NETIF Adapter - -# -# PHY -# -CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y -# CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set -CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 -CONFIG_ESP_PHY_MAX_TX_POWER=20 -CONFIG_ESP_PHY_REDUCE_TX_POWER=y -CONFIG_ESP_PHY_RF_CAL_PARTIAL=y -# CONFIG_ESP_PHY_RF_CAL_NONE is not set -# CONFIG_ESP_PHY_RF_CAL_FULL is not set -CONFIG_ESP_PHY_CALIBRATION_MODE=0 -# end of PHY - -# -# Power Management -# -CONFIG_PM_ENABLE=y -# CONFIG_PM_DFS_INIT_AUTO is not set -# CONFIG_PM_PROFILING is not set -# CONFIG_PM_TRACE is not set -# end of Power Management - -# -# ESP Ringbuf -# -# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set -# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set -# end of ESP Ringbuf - -# -# ESP System Settings -# -# CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set -CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y -# CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set -# CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set -# CONFIG_ESP_SYSTEM_GDBSTUB_RUNTIME is not set - -# -# Memory protection -# -# end of Memory protection - -CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32 -CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2304 -CONFIG_ESP_MAIN_TASK_STACK_SIZE=3584 -CONFIG_ESP_MAIN_TASK_AFFINITY_CPU0=y -# CONFIG_ESP_MAIN_TASK_AFFINITY_CPU1 is not set -# CONFIG_ESP_MAIN_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_ESP_MAIN_TASK_AFFINITY=0x0 -CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048 -CONFIG_ESP_CONSOLE_UART_DEFAULT=y -# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set -# CONFIG_ESP_CONSOLE_NONE is not set -CONFIG_ESP_CONSOLE_UART=y -CONFIG_ESP_CONSOLE_MULTIPLE_UART=y -CONFIG_ESP_CONSOLE_UART_NUM=0 -CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200 -CONFIG_ESP_INT_WDT=n -CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000 -CONFIG_ESP_INT_WDT_CHECK_CPU1=y -CONFIG_ESP_TASK_WDT=n -# CONFIG_ESP_TASK_WDT_PANIC is not set -CONFIG_ESP_TASK_WDT_TIMEOUT_S=5 -CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y -CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU1=y -# CONFIG_ESP_PANIC_HANDLER_IRAM is not set -# CONFIG_ESP_DEBUG_STUBS_ENABLE is not set -# CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_5 is not set -CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_4=y -# end of ESP System Settings - -# -# High resolution timer (esp_timer) -# -# CONFIG_ESP_TIMER_PROFILING is not set -CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y -CONFIG_ESP_TIME_FUNCS_USE_ESP_TIMER=y -CONFIG_ESP_TIMER_TASK_STACK_SIZE=3584 -CONFIG_ESP_TIMER_INTERRUPT_LEVEL=1 -# CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set -# CONFIG_ESP_TIMER_IMPL_FRC2 is not set -CONFIG_ESP_TIMER_IMPL_TG0_LAC=y -# end of High resolution timer (esp_timer) - -# -# Wi-Fi -# -CONFIG_ESP32_WIFI_ENABLED=y -CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=2 -CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=16 -# CONFIG_ESP32_WIFI_STATIC_TX_BUFFER is not set -CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y -CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 -CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=16 -CONFIG_ESP_WIFI_STATIC_RX_MGMT_BUFFER=y -# CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUFFER is not set -CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUF=0 -CONFIG_ESP_WIFI_RX_MGMT_BUF_NUM_DEF=5 -# CONFIG_ESP32_WIFI_CSI_ENABLED is not set -# CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED is not set -# CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED is not set -# CONFIG_ESP32_WIFI_NVS_ENABLED is not set -CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y -# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set -CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 -CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32 -CONFIG_ESP32_WIFI_IRAM_OPT=y -CONFIG_ESP32_WIFI_RX_IRAM_OPT=y -CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y -# CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set -# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set -# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set -CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y -# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set -CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 -# end of Wi-Fi - -# -# Core dump -# -# CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set -CONFIG_ESP_COREDUMP_ENABLE_TO_UART=y -# CONFIG_ESP_COREDUMP_ENABLE_TO_NONE is not set -# CONFIG_ESP_COREDUMP_DATA_FORMAT_BIN is not set -CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y -CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y -# CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set -CONFIG_ESP_COREDUMP_ENABLE=y -CONFIG_ESP_COREDUMP_LOGS=y -CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 -CONFIG_ESP_COREDUMP_UART_DELAY=0 -CONFIG_ESP_COREDUMP_STACK_SIZE=0 -CONFIG_ESP_COREDUMP_DECODE_INFO=y -# CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set -CONFIG_ESP_COREDUMP_DECODE="info" -# end of Core dump - -# -# FAT Filesystem support -# -# CONFIG_FATFS_CODEPAGE_DYNAMIC is not set -CONFIG_FATFS_CODEPAGE_437=y -# CONFIG_FATFS_CODEPAGE_720 is not set -# CONFIG_FATFS_CODEPAGE_737 is not set -# CONFIG_FATFS_CODEPAGE_771 is not set -# CONFIG_FATFS_CODEPAGE_775 is not set -# CONFIG_FATFS_CODEPAGE_850 is not set -# CONFIG_FATFS_CODEPAGE_852 is not set -# CONFIG_FATFS_CODEPAGE_855 is not set -# CONFIG_FATFS_CODEPAGE_857 is not set -# CONFIG_FATFS_CODEPAGE_860 is not set -# CONFIG_FATFS_CODEPAGE_861 is not set -# CONFIG_FATFS_CODEPAGE_862 is not set -# CONFIG_FATFS_CODEPAGE_863 is not set -# CONFIG_FATFS_CODEPAGE_864 is not set -# CONFIG_FATFS_CODEPAGE_865 is not set -# CONFIG_FATFS_CODEPAGE_866 is not set -# CONFIG_FATFS_CODEPAGE_869 is not set -# CONFIG_FATFS_CODEPAGE_932 is not set -# CONFIG_FATFS_CODEPAGE_936 is not set -# CONFIG_FATFS_CODEPAGE_949 is not set -# CONFIG_FATFS_CODEPAGE_950 is not set -CONFIG_FATFS_CODEPAGE=437 -CONFIG_FATFS_LFN_NONE=y -# CONFIG_FATFS_LFN_HEAP is not set -# CONFIG_FATFS_LFN_STACK is not set -CONFIG_FATFS_FS_LOCK=0 -CONFIG_FATFS_TIMEOUT_MS=10000 -CONFIG_FATFS_PER_FILE_CACHE=y -# CONFIG_FATFS_USE_FASTSEEK is not set -# end of FAT Filesystem support - -# -# FreeRTOS -# -# CONFIG_FREERTOS_UNICORE is not set -CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF -CONFIG_FREERTOS_TICK_SUPPORT_CORETIMER=y -# CONFIG_FREERTOS_CORETIMER_0 is not set -CONFIG_FREERTOS_CORETIMER_1=y -CONFIG_FREERTOS_SYSTICK_USES_CCOUNT=y -CONFIG_FREERTOS_HZ=1000 -CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y -# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set -# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set -CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y -# CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK is not set -CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y -CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10 -# CONFIG_FREERTOS_ASSERT_FAIL_ABORT is not set -CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE=y -# CONFIG_FREERTOS_ASSERT_DISABLE is not set -CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536 -CONFIG_FREERTOS_ISR_STACKSIZE=2100 -# CONFIG_FREERTOS_LEGACY_HOOKS is not set -CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 -CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y -# CONFIG_FREERTOS_ENABLE_STATIC_TASK_CLEAN_UP is not set -CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1 -CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048 -CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10 -CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0 -CONFIG_FREERTOS_USE_TRACE_FACILITY=y -CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y -CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y -CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y -CONFIG_FREERTOS_RUN_TIME_STATS_USING_ESP_TIMER=y -# CONFIG_FREERTOS_RUN_TIME_STATS_USING_CPU_CLK is not set -# CONFIG_FREERTOS_USE_TICKLESS_IDLE is not set -CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y -# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set -# CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH is not set -CONFIG_FREERTOS_DEBUG_OCDAWARE=y -# CONFIG_FREERTOS_FPU_IN_ISR is not set -CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y -# CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH is not set -# end of FreeRTOS - -# -# Hardware Abstraction Layer (HAL) and Low Level (LL) -# -CONFIG_HAL_ASSERTION_EQUALS_SYSTEM=y -# CONFIG_HAL_ASSERTION_DISABLE is not set -# CONFIG_HAL_ASSERTION_SILIENT is not set -# CONFIG_HAL_ASSERTION_ENABLE is not set -CONFIG_HAL_DEFAULT_ASSERTION_LEVEL=2 -# end of Hardware Abstraction Layer (HAL) and Low Level (LL) - -# -# Heap memory debugging -# -CONFIG_HEAP_POISONING_DISABLED=y -# CONFIG_HEAP_POISONING_LIGHT is not set -# CONFIG_HEAP_POISONING_COMPREHENSIVE is not set -CONFIG_HEAP_TRACING_OFF=y -# CONFIG_HEAP_TRACING_STANDALONE is not set -# CONFIG_HEAP_TRACING_TOHOST is not set -# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set -# end of Heap memory debugging - -# -# Log output -# -# CONFIG_LOG_DEFAULT_LEVEL_NONE is not set -# CONFIG_LOG_DEFAULT_LEVEL_ERROR is not set -# CONFIG_LOG_DEFAULT_LEVEL_WARN is not set -CONFIG_LOG_DEFAULT_LEVEL_INFO=y -# CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set -# CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set -CONFIG_LOG_DEFAULT_LEVEL=3 -CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT=y -# CONFIG_LOG_MAXIMUM_LEVEL_DEBUG is not set -# CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE is not set -CONFIG_LOG_MAXIMUM_LEVEL=3 -CONFIG_LOG_COLORS=y -CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y -# CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set -# end of Log output - -# -# LWIP -# -CONFIG_LWIP_LOCAL_HOSTNAME="espressif" -# CONFIG_LWIP_NETIF_API is not set -CONFIG_LWIP_TCPIP_TASK_PRIO=18 -# CONFIG_LWIP_TCPIP_CORE_LOCKING is not set -# CONFIG_LWIP_CHECK_THREAD_SAFETY is not set -CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y -# CONFIG_LWIP_L2_TO_L3_COPY is not set -# CONFIG_LWIP_IRAM_OPTIMIZATION is not set -CONFIG_LWIP_TIMERS_ONDEMAND=y -CONFIG_LWIP_MAX_SOCKETS=5 -# CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set -# CONFIG_LWIP_SO_LINGER is not set -CONFIG_LWIP_SO_REUSE=y -CONFIG_LWIP_SO_REUSE_RXTOALL=y -# CONFIG_LWIP_SO_RCVBUF is not set -# CONFIG_LWIP_NETBUF_RECVINFO is not set -CONFIG_LWIP_IP4_FRAG=y -CONFIG_LWIP_IP6_FRAG=y -# CONFIG_LWIP_IP4_REASSEMBLY is not set -# CONFIG_LWIP_IP6_REASSEMBLY is not set -# CONFIG_LWIP_IP_FORWARD is not set -# CONFIG_LWIP_STATS is not set -# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set -CONFIG_LWIP_ESP_GRATUITOUS_ARP=y -CONFIG_LWIP_GARP_TMR_INTERVAL=60 -CONFIG_LWIP_ESP_MLDV6_REPORT=y -CONFIG_LWIP_MLDV6_TMR_INTERVAL=40 -CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 -CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y -# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set -CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y -# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set -CONFIG_LWIP_DHCP_OPTIONS_LEN=68 -CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1 - -# -# DHCP server -# -CONFIG_LWIP_DHCPS=y -CONFIG_LWIP_DHCPS_LEASE_UNIT=60 -CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8 -# end of DHCP server - -# CONFIG_LWIP_AUTOIP is not set -CONFIG_LWIP_IPV6=y -# CONFIG_LWIP_IPV6_AUTOCONFIG is not set -CONFIG_LWIP_IPV6_NUM_ADDRESSES=3 -# CONFIG_LWIP_IPV6_FORWARD is not set -# CONFIG_LWIP_NETIF_STATUS_CALLBACK is not set -CONFIG_LWIP_NETIF_LOOPBACK=y -CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8 - -# -# TCP -# -CONFIG_LWIP_MAX_ACTIVE_TCP=16 -CONFIG_LWIP_MAX_LISTENING_TCP=16 -CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y -CONFIG_LWIP_TCP_MAXRTX=12 -CONFIG_LWIP_TCP_SYNMAXRTX=6 -CONFIG_LWIP_TCP_MSS=1436 -CONFIG_LWIP_TCP_TMR_INTERVAL=250 -CONFIG_LWIP_TCP_MSL=60000 -CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 -CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 -CONFIG_LWIP_TCP_WND_DEFAULT=5744 -CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 -CONFIG_LWIP_TCP_QUEUE_OOSEQ=y -CONFIG_LWIP_TCP_OOSEQ_TIMEOUT=6 -CONFIG_LWIP_TCP_OOSEQ_MAX_PBUFS=4 -# CONFIG_LWIP_TCP_SACK_OUT is not set -# CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set -CONFIG_LWIP_TCP_OVERSIZE_MSS=y -# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set -# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set -CONFIG_LWIP_TCP_RTO_TIME=3000 -# end of TCP - -# -# UDP -# -CONFIG_LWIP_MAX_UDP_PCBS=16 -CONFIG_LWIP_UDP_RECVMBOX_SIZE=6 -# end of UDP - -# -# Checksums -# -# CONFIG_LWIP_CHECKSUM_CHECK_IP is not set -# CONFIG_LWIP_CHECKSUM_CHECK_UDP is not set -CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y -# end of Checksums - -CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072 -CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y -# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set -# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set -CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF -# CONFIG_LWIP_PPP_SUPPORT is not set -CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3 -CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5 -# CONFIG_LWIP_SLIP_SUPPORT is not set - -# -# ICMP -# -CONFIG_LWIP_ICMP=y -# CONFIG_LWIP_MULTICAST_PING is not set -# CONFIG_LWIP_BROADCAST_PING is not set -# end of ICMP - -# -# LWIP RAW API -# -CONFIG_LWIP_MAX_RAW_PCBS=16 -# end of LWIP RAW API - -# -# SNTP -# -CONFIG_LWIP_SNTP_MAX_SERVERS=1 -# CONFIG_LWIP_DHCP_GET_NTP_SRV is not set -CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000 -# end of SNTP - -CONFIG_LWIP_ESP_LWIP_ASSERT=y - -# -# Hooks -# -# CONFIG_LWIP_HOOK_TCP_ISN_NONE is not set -CONFIG_LWIP_HOOK_TCP_ISN_DEFAULT=y -# CONFIG_LWIP_HOOK_TCP_ISN_CUSTOM is not set -CONFIG_LWIP_HOOK_IP6_ROUTE_NONE=y -# CONFIG_LWIP_HOOK_IP6_ROUTE_DEFAULT is not set -# CONFIG_LWIP_HOOK_IP6_ROUTE_CUSTOM is not set -CONFIG_LWIP_HOOK_ND6_GET_GW_NONE=y -# CONFIG_LWIP_HOOK_ND6_GET_GW_DEFAULT is not set -# CONFIG_LWIP_HOOK_ND6_GET_GW_CUSTOM is not set -CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_NONE=y -# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_DEFAULT is not set -# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_CUSTOM is not set -# end of Hooks - -# CONFIG_LWIP_DEBUG is not set -# end of LWIP - -# -# mbedTLS -# -CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y -# CONFIG_MBEDTLS_DEFAULT_MEM_ALLOC is not set -# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set -CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384 -# CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN is not set -# CONFIG_MBEDTLS_DEBUG is not set - -# -# mbedTLS v2.28.x related -# -# CONFIG_MBEDTLS_SSL_VARIABLE_BUFFER_LENGTH is not set -# CONFIG_MBEDTLS_X509_TRUSTED_CERT_CALLBACK is not set -# CONFIG_MBEDTLS_SSL_CONTEXT_SERIALIZATION is not set -CONFIG_MBEDTLS_SSL_KEEP_PEER_CERTIFICATE=y - -# -# DTLS-based configurations -# -# CONFIG_MBEDTLS_SSL_DTLS_CONNECTION_ID is not set -# CONFIG_MBEDTLS_SSL_DTLS_SRTP is not set -# end of DTLS-based configurations -# end of mbedTLS v2.28.x related - -# -# Certificate Bundle -# -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y -# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set -# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set -# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 -# end of Certificate Bundle - -# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set -# CONFIG_MBEDTLS_CMAC_C is not set -CONFIG_MBEDTLS_HARDWARE_AES=y -# CONFIG_MBEDTLS_HARDWARE_MPI is not set -# CONFIG_MBEDTLS_HARDWARE_SHA is not set -CONFIG_MBEDTLS_ROM_MD5=y -# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set -# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set -CONFIG_MBEDTLS_HAVE_TIME=y -# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set -CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y -CONFIG_MBEDTLS_SHA512_C=y -CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y -# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set -# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set -# CONFIG_MBEDTLS_TLS_DISABLED is not set -CONFIG_MBEDTLS_TLS_SERVER=y -CONFIG_MBEDTLS_TLS_CLIENT=y -CONFIG_MBEDTLS_TLS_ENABLED=y - -# -# TLS Key Exchange Methods -# -CONFIG_MBEDTLS_PSK_MODES=y -CONFIG_MBEDTLS_KEY_EXCHANGE_PSK=y -CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_PSK=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_PSK=y -CONFIG_MBEDTLS_KEY_EXCHANGE_RSA_PSK=y -CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y -# end of TLS Key Exchange Methods - -CONFIG_MBEDTLS_SSL_RENEGOTIATION=y -# CONFIG_MBEDTLS_SSL_PROTO_SSL3 is not set -CONFIG_MBEDTLS_SSL_PROTO_TLS1=y -CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y -CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y -# CONFIG_MBEDTLS_SSL_PROTO_GMTSSL1_1 is not set -CONFIG_MBEDTLS_SSL_PROTO_DTLS=y -CONFIG_MBEDTLS_SSL_ALPN=y -CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y -CONFIG_MBEDTLS_X509_CHECK_KEY_USAGE=y -CONFIG_MBEDTLS_X509_CHECK_EXTENDED_KEY_USAGE=y -CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y - -# -# Symmetric Ciphers -# -CONFIG_MBEDTLS_AES_C=y -# CONFIG_MBEDTLS_CAMELLIA_C is not set -# CONFIG_MBEDTLS_DES_C is not set -CONFIG_MBEDTLS_RC4_DISABLED=y -# CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT is not set -# CONFIG_MBEDTLS_RC4_ENABLED is not set -# CONFIG_MBEDTLS_BLOWFISH_C is not set -# CONFIG_MBEDTLS_XTEA_C is not set -CONFIG_MBEDTLS_CCM_C=y -CONFIG_MBEDTLS_GCM_C=y -# CONFIG_MBEDTLS_NIST_KW_C is not set -# end of Symmetric Ciphers - -# CONFIG_MBEDTLS_RIPEMD160_C is not set - -# -# Certificates -# -CONFIG_MBEDTLS_PEM_PARSE_C=y -CONFIG_MBEDTLS_PEM_WRITE_C=y -CONFIG_MBEDTLS_X509_CRL_PARSE_C=y -CONFIG_MBEDTLS_X509_CSR_PARSE_C=y -# end of Certificates - -CONFIG_MBEDTLS_ECP_C=y -CONFIG_MBEDTLS_ECDH_C=y -CONFIG_MBEDTLS_ECDSA_C=y -# CONFIG_MBEDTLS_ECJPAKE_C is not set -CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y -CONFIG_MBEDTLS_ECP_NIST_OPTIM=y -# CONFIG_MBEDTLS_POLY1305_C is not set -# CONFIG_MBEDTLS_CHACHA20_C is not set -# CONFIG_MBEDTLS_HKDF_C is not set -# CONFIG_MBEDTLS_THREADING_C is not set -# CONFIG_MBEDTLS_SECURITY_RISKS is not set -# end of mbedTLS - -# -# Newlib -# -CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y -# CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF is not set -# CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR is not set -# CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF is not set -# CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set -CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y -# CONFIG_NEWLIB_NANO_FORMAT is not set -# end of Newlib - -# -# NVS -# -# CONFIG_NVS_ASSERT_ERROR_CHECK is not set -# end of NVS - -# -# OpenThread -# -# CONFIG_OPENTHREAD_ENABLED is not set -# end of OpenThread - -# -# PThreads -# -CONFIG_PTHREAD_TASK_PRIO_DEFAULT=5 -CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 -CONFIG_PTHREAD_STACK_MIN=768 -CONFIG_PTHREAD_DEFAULT_CORE_NO_AFFINITY=y -# CONFIG_PTHREAD_DEFAULT_CORE_0 is not set -# CONFIG_PTHREAD_DEFAULT_CORE_1 is not set -CONFIG_PTHREAD_TASK_CORE_DEFAULT=-1 -CONFIG_PTHREAD_TASK_NAME_DEFAULT="pthread" -# end of PThreads - -# -# SPI Flash driver -# -# CONFIG_SPI_FLASH_VERIFY_WRITE is not set -# CONFIG_SPI_FLASH_ENABLE_COUNTERS is not set -CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y -CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y -# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set -# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set -# CONFIG_SPI_FLASH_USE_LEGACY_IMPL is not set -# CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set -# CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set -CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y -CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20 -CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1 -CONFIG_SPI_FLASH_WRITE_CHUNK_SIZE=8192 -# CONFIG_SPI_FLASH_SIZE_OVERRIDE is not set -# CONFIG_SPI_FLASH_CHECK_ERASE_TIMEOUT_DISABLED is not set -# CONFIG_SPI_FLASH_OVERRIDE_CHIP_DRIVER_LIST is not set - -# -# Auto-detect flash chips -# -CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y -# CONFIG_SPI_FLASH_SUPPORT_BOYA_CHIP is not set -# CONFIG_SPI_FLASH_SUPPORT_TH_CHIP is not set -# end of Auto-detect flash chips - -CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y -# end of SPI Flash driver - -# -# Virtual file system -# -CONFIG_VFS_SUPPORT_IO=y -CONFIG_VFS_SUPPORT_DIR=y -CONFIG_VFS_SUPPORT_SELECT=y -CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y -CONFIG_VFS_SUPPORT_TERMIOS=y - -# -# Host File System I/O (Semihosting) -# -CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -# end of Host File System I/O (Semihosting) -# end of Virtual file system - -# -# Wear Levelling -# -# CONFIG_WL_SECTOR_SIZE_512 is not set -CONFIG_WL_SECTOR_SIZE_4096=y -CONFIG_WL_SECTOR_SIZE=4096 -# end of Wear Levelling - -# -# Supplicant -# -CONFIG_WPA_MBEDTLS_CRYPTO=y -# CONFIG_WPA_WAPI_PSK is not set -# CONFIG_WPA_SUITE_B_192 is not set -# CONFIG_WPA_DEBUG_PRINT is not set -# CONFIG_WPA_TESTING_OPTIONS is not set -# CONFIG_WPA_WPS_STRICT is not set -# CONFIG_WPA_11KV_SUPPORT is not set -# CONFIG_WPA_MBO_SUPPORT is not set -# CONFIG_WPA_DPP_SUPPORT is not set -# end of Supplicant -# end of Component config - -# -# Compatibility options -# -# CONFIG_LEGACY_INCLUDE_COMMON_HEADERS is not set -# end of Compatibility options - -# Deprecated options for backward compatibility -CONFIG_TOOLPREFIX="xtensa-esp32-elf-" -# CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set -CONFIG_LOG_BOOTLOADER_LEVEL_ERROR=y -# CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_INFO is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE is not set -CONFIG_LOG_BOOTLOADER_LEVEL=1 -# CONFIG_APP_ROLLBACK_ENABLE is not set -# CONFIG_FLASH_ENCRYPTION_ENABLED is not set -CONFIG_FLASHMODE_QIO=y -# CONFIG_FLASHMODE_QOUT is not set -# CONFIG_FLASHMODE_DIO is not set -# CONFIG_FLASHMODE_DOUT is not set -# CONFIG_MONITOR_BAUD_9600B is not set -# CONFIG_MONITOR_BAUD_57600B is not set -CONFIG_MONITOR_BAUD_115200B=y -# CONFIG_MONITOR_BAUD_230400B is not set -# CONFIG_MONITOR_BAUD_921600B is not set -# CONFIG_MONITOR_BAUD_2MB is not set -# CONFIG_MONITOR_BAUD_OTHER is not set -CONFIG_MONITOR_BAUD_OTHER_VAL=115200 -CONFIG_MONITOR_BAUD=115200 -# CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG is not set -# CONFIG_COMPILER_OPTIMIZATION_LEVEL_RELEASE is not set -CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y -# CONFIG_OPTIMIZATION_ASSERTIONS_SILENT is not set -# CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED is not set -CONFIG_OPTIMIZATION_ASSERTION_LEVEL=2 -# CONFIG_CXX_EXCEPTIONS is not set -CONFIG_STACK_CHECK_NONE=y -# CONFIG_STACK_CHECK_NORM is not set -# CONFIG_STACK_CHECK_STRONG is not set -# CONFIG_STACK_CHECK_ALL is not set -# CONFIG_WARN_WRITE_STRINGS is not set -# CONFIG_DISABLE_GCC8_WARNINGS is not set -# CONFIG_ESP32_APPTRACE_DEST_TRAX is not set -CONFIG_ESP32_APPTRACE_DEST_NONE=y -CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y -CONFIG_ADC2_DISABLE_DAC=y -# CONFIG_SPIRAM_SUPPORT is not set -CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -# CONFIG_ULP_COPROC_ENABLED is not set -CONFIG_ULP_COPROC_RESERVE_MEM=0 -CONFIG_BROWNOUT_DET=y -CONFIG_BROWNOUT_DET_LVL_SEL_0=y -# CONFIG_BROWNOUT_DET_LVL_SEL_1 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_2 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_3 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_4 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_5 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_6 is not set -# CONFIG_BROWNOUT_DET_LVL_SEL_7 is not set -CONFIG_BROWNOUT_DET_LVL=0 -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set -# CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set -# CONFIG_NO_BLOBS is not set -# CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set -# CONFIG_EVENT_LOOP_PROFILING is not set -CONFIG_POST_EVENTS_FROM_ISR=y -CONFIG_POST_EVENTS_FROM_IRAM_ISR=y -CONFIG_TWO_UNIVERSAL_MAC_ADDRESS=y -# CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS is not set -CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=2 -# CONFIG_ESP_SYSTEM_PD_FLASH is not set -# CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND is not set -CONFIG_IPC_TASK_STACK_SIZE=1024 -CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y -# CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set -CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 -CONFIG_ESP32_PHY_MAX_TX_POWER=20 -CONFIG_ESP32_REDUCE_PHY_TX_POWER=y -# CONFIG_ESP32S2_PANIC_PRINT_HALT is not set -CONFIG_ESP32S2_PANIC_PRINT_REBOOT=y -# CONFIG_ESP32S2_PANIC_SILENT_REBOOT is not set -# CONFIG_ESP32S2_PANIC_GDBSTUB is not set -CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32 -CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2304 -CONFIG_MAIN_TASK_STACK_SIZE=3584 -CONFIG_CONSOLE_UART_DEFAULT=y -# CONFIG_CONSOLE_UART_CUSTOM is not set -# CONFIG_ESP_CONSOLE_UART_NONE is not set -CONFIG_CONSOLE_UART=y -CONFIG_CONSOLE_UART_NUM=0 -CONFIG_CONSOLE_UART_BAUDRATE=115200 -CONFIG_INT_WDT=n -CONFIG_INT_WDT_TIMEOUT_MS=1000 -CONFIG_INT_WDT_CHECK_CPU1=y -CONFIG_TASK_WDT=n -# CONFIG_TASK_WDT_PANIC is not set -CONFIG_TASK_WDT_TIMEOUT_S=5 -CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y -CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y -# CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set -CONFIG_TIMER_TASK_STACK_SIZE=3584 -# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set -CONFIG_ESP32_ENABLE_COREDUMP_TO_UART=y -# CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE is not set -# CONFIG_ESP32_COREDUMP_DATA_FORMAT_BIN is not set -CONFIG_ESP32_COREDUMP_DATA_FORMAT_ELF=y -CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y -# CONFIG_ESP32_COREDUMP_CHECKSUM_SHA256 is not set -CONFIG_ESP32_ENABLE_COREDUMP=y -CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 -CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 -CONFIG_ESP32_CORE_DUMP_STACK_SIZE=0 -CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y -# CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set -CONFIG_ESP32_CORE_DUMP_DECODE="info" -# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set -CONFIG_TIMER_TASK_PRIORITY=1 -CONFIG_TIMER_TASK_STACK_DEPTH=2048 -CONFIG_TIMER_QUEUE_LENGTH=10 -# CONFIG_L2_TO_L3_COPY is not set -# CONFIG_USE_ONLY_LWIP_SELECT is not set -CONFIG_ESP_GRATUITOUS_ARP=y -CONFIG_GARP_TMR_INTERVAL=60 -CONFIG_TCPIP_RECVMBOX_SIZE=32 -CONFIG_TCP_MAXRTX=12 -CONFIG_TCP_SYNMAXRTX=6 -CONFIG_TCP_MSS=1436 -CONFIG_TCP_MSL=60000 -CONFIG_TCP_SND_BUF_DEFAULT=5744 -CONFIG_TCP_WND_DEFAULT=5744 -CONFIG_TCP_RECVMBOX_SIZE=6 -CONFIG_TCP_QUEUE_OOSEQ=y -# CONFIG_ESP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set -CONFIG_TCP_OVERSIZE_MSS=y -# CONFIG_TCP_OVERSIZE_QUARTER_MSS is not set -# CONFIG_TCP_OVERSIZE_DISABLE is not set -CONFIG_UDP_RECVMBOX_SIZE=6 -CONFIG_TCPIP_TASK_STACK_SIZE=3072 -CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y -# CONFIG_TCPIP_TASK_AFFINITY_CPU0 is not set -# CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set -CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF -# CONFIG_PPP_SUPPORT is not set -CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 -CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 -CONFIG_ESP32_PTHREAD_STACK_MIN=768 -CONFIG_ESP32_DEFAULT_PTHREAD_CORE_NO_AFFINITY=y -# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_0 is not set -# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_1 is not set -CONFIG_ESP32_PTHREAD_TASK_CORE_DEFAULT=-1 -CONFIG_ESP32_PTHREAD_TASK_NAME_DEFAULT="pthread" -CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y -# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS is not set -# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set -CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y -CONFIG_SUPPORT_TERMIOS=y -CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -# End of deprecated options diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig.defaults b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig.defaults new file mode 100644 index 00000000000000..b94fe2d026695e --- /dev/null +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig.defaults @@ -0,0 +1,51 @@ +# This file was generated using idf.py save-defconfig. It can be edited manually. +# Espressif IoT Development Framework (ESP-IDF) 5.3.1 Project Minimal Configuration +# +CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y +CONFIG_BOOTLOADER_WDT_ENABLE=n +CONFIG_APP_COMPILE_TIME_DATE=n +CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y +CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y +CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 +CONFIG_ESPTOOLPY_FLASHMODE_QIO=y +CONFIG_ESPTOOLPY_FLASHFREQ_80M=y +CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y +CONFIG_PARTITION_TABLE_CUSTOM=y +CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv" +CONFIG_COMPILER_OPTIMIZATION_PERF=y +CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC=n +CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST=n +CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID=n +CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT=n +CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=n +CONFIG_SPI_MASTER_IN_IRAM=y +CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y +CONFIG_ESP_PHY_REDUCE_TX_POWER=y +CONFIG_PM_ENABLE=y +CONFIG_ESP_INT_WDT=n +CONFIG_ESP_TASK_WDT_INIT=n +CONFIG_ESP_WIFI_STATIC_RX_BUFFER_NUM=2 +CONFIG_ESP_WIFI_DYNAMIC_RX_BUFFER_NUM=16 +CONFIG_ESP_WIFI_DYNAMIC_TX_BUFFER_NUM=16 +CONFIG_ESP_WIFI_RX_BA_WIN=4 +CONFIG_ESP_WIFI_TASK_PINNED_TO_CORE_1=y +CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE=n +CONFIG_ESP_WIFI_GMAC_SUPPORT=n +CONFIG_FREERTOS_HZ=1000 +CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10 +CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y +CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y +CONFIG_FREERTOS_ISR_STACKSIZE=2100 +CONFIG_FREERTOS_CORETIMER_1=y +CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY=y +CONFIG_LWIP_MAX_SOCKETS=5 +CONFIG_LWIP_TCP_SYNMAXRTX=6 +CONFIG_LWIP_TCP_MSS=1436 +CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 +CONFIG_LWIP_TCP_WND_DEFAULT=5744 +CONFIG_LWIP_TCP_RTO_TIME=3000 +CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y +CONFIG_ADC_SUPPRESS_DEPRECATE_WARN=y +CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN=y +CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN=y +CONFIG_RMT_SUPPRESS_DEPRECATE_WARN=y diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt index 4e0fafb3eac05f..c00f753174fea0 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt @@ -15,16 +15,24 @@ idf_build_process(esp32s3 # although esptool_py does not generate static library, # processing the component is needed for flashing related # targets and file generation - COMPONENTS esp32s3 - freertos - tcpip_adapter + COMPONENTS freertos fatfs - esp_adc_cal nvs_flash esptool_py app_update + esp_adc + esp_driver_mcpwm + driver + lwip + esp_wifi + esp_system + esp_rom + esp_timer + SDKCONFIG ${CMAKE_CURRENT_LIST_DIR}/sdkconfig - BUILD_DIR ${CMAKE_BINARY_DIR}) + SDKCONFIG_DEFAULTS ${CMAKE_CURRENT_LIST_DIR}/sdkconfig.defaults + BUILD_DIR ${CMAKE_BINARY_DIR} +) set(elf_file ardupilot.elf) @@ -93,14 +101,19 @@ add_custom_target(showinc ALL # Link the static libraries to the executable target_link_libraries(${elf_file} - idf::esp32s3 idf::freertos idf::fatfs - idf::esp_adc_cal idf::nvs_flash idf::spi_flash - idf::tcpip_adapter idf::app_update + idf::esp_adc + idf::esp_driver_mcpwm + idf::driver + idf::lwip + idf::esp_wifi + idf::esp_system + idf::esp_rom + idf::esp_timer ) # Attach additional targets to the executable file for flashing, diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig deleted file mode 100644 index 21c2a67c1cc01c..00000000000000 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig +++ /dev/null @@ -1,1156 +0,0 @@ -# -# Automatically generated file. DO NOT EDIT. -# Espressif IoT Development Framework (ESP-IDF) Project Configuration -# -CONFIG_IDF_CMAKE=y -CONFIG_IDF_TARGET_ARCH_XTENSA=y -CONFIG_IDF_TARGET="esp32s3" -CONFIG_IDF_TARGET_ESP32S3=y -CONFIG_IDF_FIRMWARE_CHIP_ID=0x0009 - -# -# SDK tool configuration -# -CONFIG_SDK_TOOLPREFIX="xtensa-esp32s3-elf-" -# CONFIG_SDK_TOOLCHAIN_SUPPORTS_TIME_WIDE_64_BITS is not set -# end of SDK tool configuration - -# -# Build type -# -CONFIG_APP_BUILD_TYPE_APP_2NDBOOT=y -# CONFIG_APP_BUILD_TYPE_ELF_RAM is not set -CONFIG_APP_BUILD_GENERATE_BINARIES=y -CONFIG_APP_BUILD_BOOTLOADER=y -CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y -# end of Build type - -# -# Application manager -# -# CONFIG_APP_COMPILE_TIME_DATE is not set -CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y -CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y -# CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set -CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 -# end of Application manager - -# -# Bootloader config -# -CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x0 -CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set -# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_NONE is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_NONE is not set -CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y -# CONFIG_BOOTLOADER_LOG_LEVEL_WARN is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_INFO is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_DEBUG is not set -# CONFIG_BOOTLOADER_LOG_LEVEL_VERBOSE is not set -CONFIG_BOOTLOADER_LOG_LEVEL=1 -# CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_8V is not set -CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y -# CONFIG_BOOTLOADER_FACTORY_RESET is not set -# CONFIG_BOOTLOADER_APP_TEST is not set -CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y -CONFIG_BOOTLOADER_WDT_ENABLE=n -# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set -CONFIG_BOOTLOADER_WDT_TIME_MS=9000 -# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set -# CONFIG_BOOTLOADER_SKIP_VALIDATE_ALWAYS is not set -CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0 -# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set -CONFIG_BOOTLOADER_FLASH_XMC_SUPPORT=y -# end of Bootloader config - -# -# Security features -# -# CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set -# CONFIG_SECURE_BOOT is not set -# CONFIG_SECURE_FLASH_ENC_ENABLED is not set -# end of Security features - -# -# Boot ROM Behavior -# -CONFIG_BOOT_ROM_LOG_ALWAYS_ON=y -# CONFIG_BOOT_ROM_LOG_ALWAYS_OFF is not set -# CONFIG_BOOT_ROM_LOG_ON_GPIO_HIGH is not set -# CONFIG_BOOT_ROM_LOG_ON_GPIO_LOW is not set -# end of Boot ROM Behavior - -# -# Serial flasher config -# -CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200 -# CONFIG_ESPTOOLPY_NO_STUB is not set -# CONFIG_ESPTOOLPY_OCT_FLASH is not set -# CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set -# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set -CONFIG_ESPTOOLPY_FLASHMODE_DIO=y -# CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set -CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y -CONFIG_ESPTOOLPY_FLASHMODE="dio" -CONFIG_ESPTOOLPY_FLASHFREQ_80M=y -# CONFIG_ESPTOOLPY_FLASHFREQ_40M is not set -# CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set -# CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set -CONFIG_ESPTOOLPY_FLASHFREQ="80m" -# CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_2MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_4MB is not set -CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y -# CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_32MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_64MB is not set -# CONFIG_ESPTOOLPY_FLASHSIZE_128MB is not set -CONFIG_ESPTOOLPY_FLASHSIZE="8MB" -CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y -CONFIG_ESPTOOLPY_BEFORE_RESET=y -# CONFIG_ESPTOOLPY_BEFORE_NORESET is not set -CONFIG_ESPTOOLPY_BEFORE="default_reset" -CONFIG_ESPTOOLPY_AFTER_RESET=y -# CONFIG_ESPTOOLPY_AFTER_NORESET is not set -CONFIG_ESPTOOLPY_AFTER="hard_reset" -# CONFIG_ESPTOOLPY_MONITOR_BAUD_CONSOLE is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_9600B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set -CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y -# CONFIG_ESPTOOLPY_MONITOR_BAUD_230400B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_921600B is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_2MB is not set -# CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER is not set -CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER_VAL=115200 -CONFIG_ESPTOOLPY_MONITOR_BAUD=115200 -# end of Serial flasher config - -# -# Partition Table -# -# CONFIG_PARTITION_TABLE_SINGLE_APP is not set -# CONFIG_PARTITION_TABLE_SINGLE_APP_LARGE is not set -# CONFIG_PARTITION_TABLE_TWO_OTA is not set -CONFIG_PARTITION_TABLE_CUSTOM=y -CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv" -CONFIG_PARTITION_TABLE_FILENAME="../partitions.csv" -CONFIG_PARTITION_TABLE_OFFSET=0x10000 -CONFIG_PARTITION_TABLE_MD5=y -# end of Partition Table - -# -# Compiler options -# -# CONFIG_COMPILER_OPTIMIZATION_DEFAULT is not set -# CONFIG_COMPILER_OPTIMIZATION_SIZE is not set -CONFIG_COMPILER_OPTIMIZATION_PERF=y -# CONFIG_COMPILER_OPTIMIZATION_NONE is not set -CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y -# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set -# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE is not set -CONFIG_COMPILER_OPTIMIZATION_ASSERTION_LEVEL=2 -# CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT is not set -CONFIG_COMPILER_HIDE_PATHS_MACROS=y -# CONFIG_COMPILER_CXX_EXCEPTIONS is not set -# CONFIG_COMPILER_CXX_RTTI is not set -CONFIG_COMPILER_STACK_CHECK_MODE_NONE=y -# CONFIG_COMPILER_STACK_CHECK_MODE_NORM is not set -# CONFIG_COMPILER_STACK_CHECK_MODE_STRONG is not set -# CONFIG_COMPILER_STACK_CHECK_MODE_ALL is not set -# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set -# CONFIG_COMPILER_DISABLE_GCC8_WARNINGS is not set -# CONFIG_COMPILER_DUMP_RTL_FILES is not set -# end of Compiler options - -# -# Component config -# - -# -# Application Level Tracing -# -# CONFIG_APPTRACE_DEST_JTAG is not set -CONFIG_APPTRACE_DEST_NONE=y -CONFIG_APPTRACE_LOCK_ENABLE=y -# end of Application Level Tracing - -# -# Driver configurations -# - -# -# ADC configuration -# -# CONFIG_ADC_FORCE_XPD_FSM is not set -CONFIG_ADC_DISABLE_DAC=y -# end of ADC configuration - -# -# MCPWM configuration -# -# CONFIG_MCPWM_ISR_IN_IRAM is not set -# end of MCPWM configuration - -# -# SPI configuration -# -CONFIG_SPI_MASTER_IN_IRAM=y -CONFIG_SPI_MASTER_ISR_IN_IRAM=y -# CONFIG_SPI_SLAVE_IN_IRAM is not set -CONFIG_SPI_SLAVE_ISR_IN_IRAM=y -# end of SPI configuration - -# -# TWAI configuration -# -# CONFIG_TWAI_ISR_IN_IRAM is not set -# end of TWAI configuration - -# -# UART configuration -# -# CONFIG_UART_ISR_IN_IRAM is not set -# end of UART configuration - -# -# GDMA Configuration -# -# CONFIG_GDMA_CTRL_FUNC_IN_IRAM is not set -# CONFIG_GDMA_ISR_IRAM_SAFE is not set -# end of GDMA Configuration -# end of Driver configurations - -# -# eFuse Bit Manager -# -# CONFIG_EFUSE_CUSTOM_TABLE is not set -# CONFIG_EFUSE_VIRTUAL is not set -CONFIG_EFUSE_MAX_BLK_LEN=256 -# end of eFuse Bit Manager - -# -# ESP32S3-Specific -# -# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_80 is not set -#CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32S3_DEFAULT_CPU_FREQ_MHZ=240 - -# -# Cache config -# -CONFIG_ESP32S3_INSTRUCTION_CACHE_16KB=y -# CONFIG_ESP32S3_INSTRUCTION_CACHE_32KB is not set -CONFIG_ESP32S3_INSTRUCTION_CACHE_SIZE=0x4000 -# CONFIG_ESP32S3_INSTRUCTION_CACHE_4WAYS is not set -CONFIG_ESP32S3_INSTRUCTION_CACHE_8WAYS=y -CONFIG_ESP32S3_ICACHE_ASSOCIATED_WAYS=8 -# CONFIG_ESP32S3_INSTRUCTION_CACHE_LINE_16B is not set -CONFIG_ESP32S3_INSTRUCTION_CACHE_LINE_32B=y -CONFIG_ESP32S3_INSTRUCTION_CACHE_LINE_SIZE=32 -# CONFIG_ESP32S3_INSTRUCTION_CACHE_WRAP is not set -# CONFIG_ESP32S3_DATA_CACHE_16KB is not set -CONFIG_ESP32S3_DATA_CACHE_32KB=y -# CONFIG_ESP32S3_DATA_CACHE_64KB is not set -CONFIG_ESP32S3_DATA_CACHE_SIZE=0x8000 -# CONFIG_ESP32S3_DATA_CACHE_4WAYS is not set -CONFIG_ESP32S3_DATA_CACHE_8WAYS=y -CONFIG_ESP32S3_DCACHE_ASSOCIATED_WAYS=8 -# CONFIG_ESP32S3_DATA_CACHE_LINE_16B is not set -CONFIG_ESP32S3_DATA_CACHE_LINE_32B=y -# CONFIG_ESP32S3_DATA_CACHE_LINE_64B is not set -CONFIG_ESP32S3_DATA_CACHE_LINE_SIZE=32 -# CONFIG_ESP32S3_DATA_CACHE_WRAP is not set -# end of Cache config - -# CONFIG_ESP32S3_SPIRAM_SUPPORT is not set -# CONFIG_ESP32S3_TRAX is not set -CONFIG_ESP32S3_TRACEMEM_RESERVE_DRAM=0x0 -# CONFIG_ESP32S3_ULP_COPROC_ENABLED is not set -CONFIG_ESP32S3_ULP_COPROC_RESERVE_MEM=0 -CONFIG_ESP32S3_DEBUG_OCDAWARE=y -CONFIG_ESP32S3_BROWNOUT_DET=y -CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_7=y -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_6 is not set -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_5 is not set -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_4 is not set -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_3 is not set -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_2 is not set -# CONFIG_ESP32S3_BROWNOUT_DET_LVL_SEL_1 is not set -CONFIG_ESP32S3_BROWNOUT_DET_LVL=7 -CONFIG_ESP32S3_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32S3_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32S3_TIME_SYSCALL_USE_FRC1 is not set -# CONFIG_ESP32S3_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32S3_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32S3_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32S3_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32S3_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32S3_RTC_CLK_CAL_CYCLES=1024 -CONFIG_ESP32S3_DEEP_SLEEP_WAKEUP_DELAY=2000 -# CONFIG_ESP32S3_NO_BLOBS is not set -# CONFIG_ESP32S3_RTCDATA_IN_FAST_MEM is not set -# CONFIG_ESP32S3_USE_FIXED_STATIC_RAM_SIZE is not set -# end of ESP32S3-Specific - -# -# ADC-Calibration -# -CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y -CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y -CONFIG_ADC_CAL_LUT_ENABLE=y -# end of ADC-Calibration - -# -# Common ESP-related -# -CONFIG_ESP_ERR_TO_NAME_LOOKUP=y -# end of Common ESP-related - -# -# Ethernet -# -CONFIG_ETH_ENABLED=y -CONFIG_ETH_USE_SPI_ETHERNET=y -# CONFIG_ETH_SPI_ETHERNET_DM9051 is not set -# CONFIG_ETH_SPI_ETHERNET_W5500 is not set -# CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set -# CONFIG_ETH_USE_OPENETH is not set -# end of Ethernet - -# -# Event Loop Library -# -# CONFIG_ESP_EVENT_LOOP_PROFILING is not set -CONFIG_ESP_EVENT_POST_FROM_ISR=y -CONFIG_ESP_EVENT_POST_FROM_IRAM_ISR=y -# end of Event Loop Library - -# -# GDB Stub -# -# end of GDB Stub - -# -# Hardware Settings -# - -# -# MAC Config -# -CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y -CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y -CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y -CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y -CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_TWO=y -#CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_FOUR is not set -CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES=2 -# end of MAC Config - -# -# Sleep Config -# -# CONFIG_ESP_SLEEP_POWER_DOWN_FLASH is not set -CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y -# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set -# CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND is not set -# end of Sleep Config - -# -# RTC Clock Config -# -CONFIG_RTC_CLOCK_BBPLL_POWER_ON_WITH_USB=y -# end of RTC Clock Config -# end of Hardware Settings - -# -# IPC (Inter-Processor Call) -# -CONFIG_ESP_IPC_TASK_STACK_SIZE=1536 -CONFIG_ESP_IPC_USES_CALLERS_PRIORITY=y -CONFIG_ESP_IPC_ISR_ENABLE=y -# end of IPC (Inter-Processor Call) - -# -# ESP NETIF Adapter -# -CONFIG_ESP_NETIF_IP_LOST_TIMER_INTERVAL=120 -CONFIG_ESP_NETIF_TCPIP_LWIP=y -# CONFIG_ESP_NETIF_LOOPBACK is not set -CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y -# end of ESP NETIF Adapter - -# -# PHY -# -CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y -# CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set -CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 -CONFIG_ESP_PHY_MAX_TX_POWER=20 -CONFIG_ESP_PHY_ENABLE_USB=y -# end of PHY - -# -# Power Management -# -# CONFIG_PM_ENABLE is not set -CONFIG_PM_POWER_DOWN_CPU_IN_LIGHT_SLEEP=y -CONFIG_PM_POWER_DOWN_TAGMEM_IN_LIGHT_SLEEP=y -# end of Power Management - -# -# ESP System Settings -# -# CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set -CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y -# CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set -# CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set -# CONFIG_ESP_SYSTEM_GDBSTUB_RUNTIME is not set -CONFIG_ESP_SYSTEM_RTC_FAST_MEM_AS_HEAP_DEPCHECK=y -CONFIG_ESP_SYSTEM_ALLOW_RTC_FAST_MEM_AS_HEAP=y - -# -# Memory protection -# -# end of Memory protection - -CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32 -CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2304 -CONFIG_ESP_MAIN_TASK_STACK_SIZE=3584 -CONFIG_ESP_MAIN_TASK_AFFINITY_CPU0=y -# CONFIG_ESP_MAIN_TASK_AFFINITY_CPU1 is not set -# CONFIG_ESP_MAIN_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_ESP_MAIN_TASK_AFFINITY=0x0 -CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048 -CONFIG_ESP_CONSOLE_UART_DEFAULT=y -# CONFIG_ESP_CONSOLE_USB_CDC is not set -# CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG is not set -# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set -# CONFIG_ESP_CONSOLE_NONE is not set -# CONFIG_ESP_CONSOLE_SECONDARY_NONE is not set -CONFIG_ESP_CONSOLE_SECONDARY_USB_SERIAL_JTAG=y -CONFIG_ESP_CONSOLE_UART=y -CONFIG_ESP_CONSOLE_MULTIPLE_UART=y -CONFIG_ESP_CONSOLE_UART_NUM=0 -CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200 -CONFIG_ESP_INT_WDT=n -CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000 -CONFIG_ESP_INT_WDT_CHECK_CPU1=y -CONFIG_ESP_TASK_WDT=n -# CONFIG_ESP_TASK_WDT_PANIC is not set -CONFIG_ESP_TASK_WDT_TIMEOUT_S=5 -CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y -CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU1=y -# CONFIG_ESP_PANIC_HANDLER_IRAM is not set -# CONFIG_ESP_DEBUG_STUBS_ENABLE is not set -CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_4=y -# end of ESP System Settings - -# -# High resolution timer (esp_timer) -# -# CONFIG_ESP_TIMER_PROFILING is not set -CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y -CONFIG_ESP_TIME_FUNCS_USE_ESP_TIMER=y -CONFIG_ESP_TIMER_TASK_STACK_SIZE=3584 -CONFIG_ESP_TIMER_INTERRUPT_LEVEL=1 -# CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set -CONFIG_ESP_TIMER_IMPL_SYSTIMER=y -# end of High resolution timer (esp_timer) - -# -# Wi-Fi -# -CONFIG_ESP32_WIFI_ENABLED=y -CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=10 -CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=32 -# CONFIG_ESP32_WIFI_STATIC_TX_BUFFER is not set -CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y -CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 -CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=32 -# CONFIG_ESP32_WIFI_CSI_ENABLED is not set -CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y -CONFIG_ESP32_WIFI_TX_BA_WIN=6 -CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y -CONFIG_ESP32_WIFI_RX_BA_WIN=6 -CONFIG_ESP32_WIFI_NVS_ENABLED=y -CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y -# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set -CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 -CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32 -CONFIG_ESP32_WIFI_IRAM_OPT=y -CONFIG_ESP32_WIFI_RX_IRAM_OPT=y -CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y -# CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set -# CONFIG_ESP_WIFI_FTM_ENABLE is not set -# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set -# CONFIG_ESP_WIFI_GCMP_SUPPORT is not set -# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set -CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y -# end of Wi-Fi - -# -# Core dump -# -# CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set -CONFIG_ESP_COREDUMP_ENABLE_TO_UART=y -# CONFIG_ESP_COREDUMP_ENABLE_TO_NONE is not set -# CONFIG_ESP_COREDUMP_DATA_FORMAT_BIN is not set -CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y -CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y -# CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set -CONFIG_ESP_COREDUMP_ENABLE=y -CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 -CONFIG_ESP_COREDUMP_UART_DELAY=0 -CONFIG_ESP_COREDUMP_DECODE_INFO=y -# CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set -CONFIG_ESP_COREDUMP_DECODE="info" -# end of Core dump - -# -# FAT Filesystem support -# -# CONFIG_FATFS_CODEPAGE_DYNAMIC is not set -CONFIG_FATFS_CODEPAGE_437=y -# CONFIG_FATFS_CODEPAGE_720 is not set -# CONFIG_FATFS_CODEPAGE_737 is not set -# CONFIG_FATFS_CODEPAGE_771 is not set -# CONFIG_FATFS_CODEPAGE_775 is not set -# CONFIG_FATFS_CODEPAGE_850 is not set -# CONFIG_FATFS_CODEPAGE_852 is not set -# CONFIG_FATFS_CODEPAGE_855 is not set -# CONFIG_FATFS_CODEPAGE_857 is not set -# CONFIG_FATFS_CODEPAGE_860 is not set -# CONFIG_FATFS_CODEPAGE_861 is not set -# CONFIG_FATFS_CODEPAGE_862 is not set -# CONFIG_FATFS_CODEPAGE_863 is not set -# CONFIG_FATFS_CODEPAGE_864 is not set -# CONFIG_FATFS_CODEPAGE_865 is not set -# CONFIG_FATFS_CODEPAGE_866 is not set -# CONFIG_FATFS_CODEPAGE_869 is not set -# CONFIG_FATFS_CODEPAGE_932 is not set -# CONFIG_FATFS_CODEPAGE_936 is not set -# CONFIG_FATFS_CODEPAGE_949 is not set -# CONFIG_FATFS_CODEPAGE_950 is not set -CONFIG_FATFS_CODEPAGE=437 -CONFIG_FATFS_LFN_NONE=y -# CONFIG_FATFS_LFN_HEAP is not set -# CONFIG_FATFS_LFN_STACK is not set -CONFIG_FATFS_FS_LOCK=0 -CONFIG_FATFS_TIMEOUT_MS=10000 -CONFIG_FATFS_PER_FILE_CACHE=y -# CONFIG_FATFS_USE_FASTSEEK is not set -# end of FAT Filesystem support - -# -# FreeRTOS -# -# CONFIG_FREERTOS_UNICORE is not set -CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF -CONFIG_FREERTOS_TICK_SUPPORT_SYSTIMER=y -CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1=y -# CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3 is not set -CONFIG_FREERTOS_SYSTICK_USES_SYSTIMER=y -CONFIG_FREERTOS_HZ=1000 -CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y -# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set -# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set -CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y -# CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK is not set -CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y -CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1 -CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y -# CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE is not set -# CONFIG_FREERTOS_ASSERT_DISABLE is not set -CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536 -CONFIG_FREERTOS_ISR_STACKSIZE=2100 -# CONFIG_FREERTOS_LEGACY_HOOKS is not set -CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 -CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y -# CONFIG_FREERTOS_ENABLE_STATIC_TASK_CLEAN_UP is not set -CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1 -CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048 -CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10 -CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0 -CONFIG_FREERTOS_USE_TRACE_FACILITY=y -CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y -CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y -CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y -CONFIG_FREERTOS_RUN_TIME_STATS_USING_ESP_TIMER=y -CONFIG_FREERTOS_TASK_FUNCTION_WRAPPER=y -CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y -# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set -# CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH is not set -CONFIG_FREERTOS_DEBUG_OCDAWARE=y -CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y -# CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH is not set -# end of FreeRTOS - -# -# Hardware Abstraction Layer (HAL) and Low Level (LL) -# -CONFIG_HAL_ASSERTION_EQUALS_SYSTEM=y -# CONFIG_HAL_ASSERTION_DISABLE is not set -# CONFIG_HAL_ASSERTION_SILIENT is not set -# CONFIG_HAL_ASSERTION_ENABLE is not set -CONFIG_HAL_DEFAULT_ASSERTION_LEVEL=2 -# end of Hardware Abstraction Layer (HAL) and Low Level (LL) - -# -# Heap memory debugging -# -CONFIG_HEAP_POISONING_DISABLED=y -# CONFIG_HEAP_POISONING_LIGHT is not set -# CONFIG_HEAP_POISONING_COMPREHENSIVE is not set -CONFIG_HEAP_TRACING_OFF=y -# CONFIG_HEAP_TRACING_STANDALONE is not set -# CONFIG_HEAP_TRACING_TOHOST is not set -# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set -# end of Heap memory debugging - -# -# Log output -# -# CONFIG_LOG_DEFAULT_LEVEL_NONE is not set -# CONFIG_LOG_DEFAULT_LEVEL_ERROR is not set -# CONFIG_LOG_DEFAULT_LEVEL_WARN is not set -CONFIG_LOG_DEFAULT_LEVEL_INFO=y -# CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set -# CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set -CONFIG_LOG_DEFAULT_LEVEL=3 -CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT=y -# CONFIG_LOG_MAXIMUM_LEVEL_DEBUG is not set -# CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE is not set -CONFIG_LOG_MAXIMUM_LEVEL=3 -CONFIG_LOG_COLORS=y -CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y -# CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set -# end of Log output - -# -# LWIP -# -CONFIG_LWIP_LOCAL_HOSTNAME="espressif" -# CONFIG_LWIP_NETIF_API is not set -# CONFIG_LWIP_TCPIP_CORE_LOCKING is not set -CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y -# CONFIG_LWIP_L2_TO_L3_COPY is not set -# CONFIG_LWIP_IRAM_OPTIMIZATION is not set -CONFIG_LWIP_TIMERS_ONDEMAND=y -CONFIG_LWIP_MAX_SOCKETS=10 -# CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set -# CONFIG_LWIP_SO_LINGER is not set -CONFIG_LWIP_SO_REUSE=y -CONFIG_LWIP_SO_REUSE_RXTOALL=y -# CONFIG_LWIP_SO_RCVBUF is not set -# CONFIG_LWIP_NETBUF_RECVINFO is not set -CONFIG_LWIP_IP4_FRAG=y -CONFIG_LWIP_IP6_FRAG=y -# CONFIG_LWIP_IP4_REASSEMBLY is not set -# CONFIG_LWIP_IP6_REASSEMBLY is not set -# CONFIG_LWIP_IP_FORWARD is not set -# CONFIG_LWIP_STATS is not set -# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set -CONFIG_LWIP_ESP_GRATUITOUS_ARP=y -CONFIG_LWIP_GARP_TMR_INTERVAL=60 -CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 -CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y -# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set -CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y -# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set -CONFIG_LWIP_DHCP_OPTIONS_LEN=68 - -# -# DHCP server -# -CONFIG_LWIP_DHCPS=y -CONFIG_LWIP_DHCPS_LEASE_UNIT=60 -CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8 -# end of DHCP server - -# CONFIG_LWIP_AUTOIP is not set -CONFIG_LWIP_IPV6=y -# CONFIG_LWIP_IPV6_AUTOCONFIG is not set -CONFIG_LWIP_IPV6_NUM_ADDRESSES=3 -# CONFIG_LWIP_IPV6_FORWARD is not set -# CONFIG_LWIP_NETIF_STATUS_CALLBACK is not set -CONFIG_LWIP_NETIF_LOOPBACK=y -CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8 - -# -# TCP -# -CONFIG_LWIP_MAX_ACTIVE_TCP=16 -CONFIG_LWIP_MAX_LISTENING_TCP=16 -CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y -CONFIG_LWIP_TCP_MAXRTX=12 -CONFIG_LWIP_TCP_SYNMAXRTX=12 -CONFIG_LWIP_TCP_MSS=1440 -CONFIG_LWIP_TCP_TMR_INTERVAL=250 -CONFIG_LWIP_TCP_MSL=60000 -CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 -CONFIG_LWIP_TCP_WND_DEFAULT=5744 -CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 -CONFIG_LWIP_TCP_QUEUE_OOSEQ=y -# CONFIG_LWIP_TCP_SACK_OUT is not set -# CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set -CONFIG_LWIP_TCP_OVERSIZE_MSS=y -# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set -# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set -CONFIG_LWIP_TCP_RTO_TIME=1500 -# end of TCP - -# -# UDP -# -CONFIG_LWIP_MAX_UDP_PCBS=16 -CONFIG_LWIP_UDP_RECVMBOX_SIZE=6 -# end of UDP - -# -# Checksums -# -# CONFIG_LWIP_CHECKSUM_CHECK_IP is not set -# CONFIG_LWIP_CHECKSUM_CHECK_UDP is not set -CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y -# end of Checksums - -CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072 -CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y -# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set -# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set -CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF -# CONFIG_LWIP_PPP_SUPPORT is not set -CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3 -CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5 -# CONFIG_LWIP_SLIP_SUPPORT is not set - -# -# ICMP -# -CONFIG_LWIP_ICMP=y -# CONFIG_LWIP_MULTICAST_PING is not set -# CONFIG_LWIP_BROADCAST_PING is not set -# end of ICMP - -# -# LWIP RAW API -# -CONFIG_LWIP_MAX_RAW_PCBS=16 -# end of LWIP RAW API - -# -# SNTP -# -CONFIG_LWIP_SNTP_MAX_SERVERS=1 -# CONFIG_LWIP_DHCP_GET_NTP_SRV is not set -CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000 -# end of SNTP - -CONFIG_LWIP_ESP_LWIP_ASSERT=y - -# -# Hooks -# -# CONFIG_LWIP_HOOK_TCP_ISN_NONE is not set -CONFIG_LWIP_HOOK_TCP_ISN_DEFAULT=y -# CONFIG_LWIP_HOOK_TCP_ISN_CUSTOM is not set -CONFIG_LWIP_HOOK_IP6_ROUTE_NONE=y -# CONFIG_LWIP_HOOK_IP6_ROUTE_DEFAULT is not set -# CONFIG_LWIP_HOOK_IP6_ROUTE_CUSTOM is not set -CONFIG_LWIP_HOOK_ND6_GET_GW_NONE=y -# CONFIG_LWIP_HOOK_ND6_GET_GW_DEFAULT is not set -# CONFIG_LWIP_HOOK_ND6_GET_GW_CUSTOM is not set -CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_NONE=y -# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_DEFAULT is not set -# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_CUSTOM is not set -# end of Hooks - -# CONFIG_LWIP_DEBUG is not set -# end of LWIP - -# -# mbedTLS -# -CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y -# CONFIG_MBEDTLS_DEFAULT_MEM_ALLOC is not set -# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set -CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN=y -CONFIG_MBEDTLS_SSL_IN_CONTENT_LEN=16384 -CONFIG_MBEDTLS_SSL_OUT_CONTENT_LEN=4096 -# CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set -# CONFIG_MBEDTLS_DEBUG is not set - -# -# mbedTLS v2.28.x related -# -# CONFIG_MBEDTLS_SSL_VARIABLE_BUFFER_LENGTH is not set -# CONFIG_MBEDTLS_X509_TRUSTED_CERT_CALLBACK is not set -# CONFIG_MBEDTLS_SSL_CONTEXT_SERIALIZATION is not set -CONFIG_MBEDTLS_SSL_KEEP_PEER_CERTIFICATE=y -# end of mbedTLS v2.28.x related - -# -# Certificate Bundle -# -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y -# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set -# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set -# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set -# end of Certificate Bundle - -# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set -# CONFIG_MBEDTLS_CMAC_C is not set -CONFIG_MBEDTLS_HARDWARE_AES=y -CONFIG_MBEDTLS_AES_USE_INTERRUPT=y -CONFIG_MBEDTLS_HARDWARE_MPI=y -CONFIG_MBEDTLS_HARDWARE_SHA=y -CONFIG_MBEDTLS_ROM_MD5=y -# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set -# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set -CONFIG_MBEDTLS_HAVE_TIME=y -# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set -CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y -CONFIG_MBEDTLS_SHA512_C=y -CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y -# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set -# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set -# CONFIG_MBEDTLS_TLS_DISABLED is not set -CONFIG_MBEDTLS_TLS_SERVER=y -CONFIG_MBEDTLS_TLS_CLIENT=y -CONFIG_MBEDTLS_TLS_ENABLED=y - -# -# TLS Key Exchange Methods -# -# CONFIG_MBEDTLS_PSK_MODES is not set -CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y -CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y -# end of TLS Key Exchange Methods - -CONFIG_MBEDTLS_SSL_RENEGOTIATION=y -# CONFIG_MBEDTLS_SSL_PROTO_SSL3 is not set -CONFIG_MBEDTLS_SSL_PROTO_TLS1=y -CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y -CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y -# CONFIG_MBEDTLS_SSL_PROTO_GMTSSL1_1 is not set -# CONFIG_MBEDTLS_SSL_PROTO_DTLS is not set -CONFIG_MBEDTLS_SSL_ALPN=y -CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y -CONFIG_MBEDTLS_X509_CHECK_KEY_USAGE=y -CONFIG_MBEDTLS_X509_CHECK_EXTENDED_KEY_USAGE=y -CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y - -# -# Symmetric Ciphers -# -CONFIG_MBEDTLS_AES_C=y -# CONFIG_MBEDTLS_CAMELLIA_C is not set -# CONFIG_MBEDTLS_DES_C is not set -CONFIG_MBEDTLS_RC4_DISABLED=y -# CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT is not set -# CONFIG_MBEDTLS_RC4_ENABLED is not set -# CONFIG_MBEDTLS_BLOWFISH_C is not set -# CONFIG_MBEDTLS_XTEA_C is not set -CONFIG_MBEDTLS_CCM_C=y -CONFIG_MBEDTLS_GCM_C=y -# CONFIG_MBEDTLS_NIST_KW_C is not set -# end of Symmetric Ciphers - -# CONFIG_MBEDTLS_RIPEMD160_C is not set - -# -# Certificates -# -CONFIG_MBEDTLS_PEM_PARSE_C=y -CONFIG_MBEDTLS_PEM_WRITE_C=y -CONFIG_MBEDTLS_X509_CRL_PARSE_C=y -CONFIG_MBEDTLS_X509_CSR_PARSE_C=y -# end of Certificates - -CONFIG_MBEDTLS_ECP_C=y -CONFIG_MBEDTLS_ECDH_C=y -CONFIG_MBEDTLS_ECDSA_C=y -# CONFIG_MBEDTLS_ECJPAKE_C is not set -CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y -CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y -CONFIG_MBEDTLS_ECP_NIST_OPTIM=y -# CONFIG_MBEDTLS_POLY1305_C is not set -# CONFIG_MBEDTLS_CHACHA20_C is not set -# CONFIG_MBEDTLS_HKDF_C is not set -# CONFIG_MBEDTLS_THREADING_C is not set -# CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set -# CONFIG_MBEDTLS_SECURITY_RISKS is not set -# end of mbedTLS - -# -# Newlib -# -CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y -# CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF is not set -# CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR is not set -# CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF is not set -# CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set -CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y -# CONFIG_NEWLIB_NANO_FORMAT is not set -# end of Newlib - -# -# NVS -# -# end of NVS - -# -# OpenThread -# -# CONFIG_OPENTHREAD_ENABLED is not set -# end of OpenThread - -# -# PThreads -# -CONFIG_PTHREAD_TASK_PRIO_DEFAULT=5 -CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 -CONFIG_PTHREAD_STACK_MIN=768 -CONFIG_PTHREAD_DEFAULT_CORE_NO_AFFINITY=y -# CONFIG_PTHREAD_DEFAULT_CORE_0 is not set -# CONFIG_PTHREAD_DEFAULT_CORE_1 is not set -CONFIG_PTHREAD_TASK_CORE_DEFAULT=-1 -CONFIG_PTHREAD_TASK_NAME_DEFAULT="pthread" -# end of PThreads - -# -# SPI Flash driver -# -# CONFIG_SPI_FLASH_VERIFY_WRITE is not set -# CONFIG_SPI_FLASH_ENABLE_COUNTERS is not set -CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y -# CONFIG_SPI_FLASH_ROM_IMPL is not set -CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y -# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set -# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set -# CONFIG_SPI_FLASH_USE_LEGACY_IMPL is not set -# CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set -# CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set -CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y -CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20 -CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1 -CONFIG_SPI_FLASH_WRITE_CHUNK_SIZE=8192 -# CONFIG_SPI_FLASH_SIZE_OVERRIDE is not set -# CONFIG_SPI_FLASH_CHECK_ERASE_TIMEOUT_DISABLED is not set -# CONFIG_SPI_FLASH_OVERRIDE_CHIP_DRIVER_LIST is not set - -# -# Auto-detect flash chips -# -CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_BOYA_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_TH_CHIP=y -CONFIG_SPI_FLASH_SUPPORT_MXIC_OPI_CHIP=y -# end of Auto-detect flash chips - -CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y -# end of SPI Flash driver - -# -# Virtual file system -# -CONFIG_VFS_SUPPORT_IO=y -CONFIG_VFS_SUPPORT_DIR=y -CONFIG_VFS_SUPPORT_SELECT=y -CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y -CONFIG_VFS_SUPPORT_TERMIOS=y - -# -# Host File System I/O (Semihosting) -# -CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 -# end of Host File System I/O (Semihosting) -# end of Virtual file system - -# -# Wear Levelling -# -# CONFIG_WL_SECTOR_SIZE_512 is not set -CONFIG_WL_SECTOR_SIZE_4096=y -CONFIG_WL_SECTOR_SIZE=4096 -# end of Wear Levelling - -# -# Supplicant -# -CONFIG_WPA_MBEDTLS_CRYPTO=y -# CONFIG_WPA_WAPI_PSK is not set -# CONFIG_WPA_SUITE_B_192 is not set -# CONFIG_WPA_DEBUG_PRINT is not set -# CONFIG_WPA_TESTING_OPTIONS is not set -# CONFIG_WPA_WPS_STRICT is not set -# CONFIG_WPA_11KV_SUPPORT is not set -# CONFIG_WPA_MBO_SUPPORT is not set -# CONFIG_WPA_DPP_SUPPORT is not set -# end of Supplicant -# end of Component config - -# -# Compatibility options -# -# CONFIG_LEGACY_INCLUDE_COMMON_HEADERS is not set -# end of Compatibility options - -# Deprecated options for backward compatibility -CONFIG_TOOLPREFIX="xtensa-esp32s3-elf-" -# CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set -CONFIG_LOG_BOOTLOADER_LEVEL_ERROR=y -# CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_INFO is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG is not set -# CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE is not set -CONFIG_LOG_BOOTLOADER_LEVEL=1 -# CONFIG_APP_ROLLBACK_ENABLE is not set -# CONFIG_FLASH_ENCRYPTION_ENABLED is not set -CONFIG_FLASHMODE_QIO=y -# CONFIG_FLASHMODE_QOUT is not set -# CONFIG_FLASHMODE_DIO is not set -# CONFIG_FLASHMODE_DOUT is not set -# CONFIG_MONITOR_BAUD_9600B is not set -# CONFIG_MONITOR_BAUD_57600B is not set -CONFIG_MONITOR_BAUD_115200B=y -# CONFIG_MONITOR_BAUD_230400B is not set -# CONFIG_MONITOR_BAUD_921600B is not set -# CONFIG_MONITOR_BAUD_2MB is not set -# CONFIG_MONITOR_BAUD_OTHER is not set -CONFIG_MONITOR_BAUD_OTHER_VAL=115200 -CONFIG_MONITOR_BAUD=115200 -# CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG is not set -# CONFIG_COMPILER_OPTIMIZATION_LEVEL_RELEASE is not set -CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y -# CONFIG_OPTIMIZATION_ASSERTIONS_SILENT is not set -# CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED is not set -CONFIG_OPTIMIZATION_ASSERTION_LEVEL=2 -# CONFIG_CXX_EXCEPTIONS is not set -CONFIG_STACK_CHECK_NONE=y -# CONFIG_STACK_CHECK_NORM is not set -# CONFIG_STACK_CHECK_STRONG is not set -# CONFIG_STACK_CHECK_ALL is not set -# CONFIG_WARN_WRITE_STRINGS is not set -# CONFIG_DISABLE_GCC8_WARNINGS is not set -# CONFIG_ESP32_APPTRACE_DEST_TRAX is not set -CONFIG_ESP32_APPTRACE_DEST_NONE=y -CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y -CONFIG_ADC2_DISABLE_DAC=y -# CONFIG_EVENT_LOOP_PROFILING is not set -CONFIG_POST_EVENTS_FROM_ISR=y -CONFIG_POST_EVENTS_FROM_IRAM_ISR=y -CONFIG_ESP_SYSTEM_PD_FLASH=y -# CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND is not set -CONFIG_IPC_TASK_STACK_SIZE=1536 -CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y -# CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set -CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 -CONFIG_ESP32_PHY_MAX_TX_POWER=20 -CONFIG_ESP_SYSTEM_PM_POWER_DOWN_CPU=y -# CONFIG_ESP32S2_PANIC_PRINT_HALT is not set -CONFIG_ESP32S2_PANIC_PRINT_REBOOT=y -# CONFIG_ESP32S2_PANIC_SILENT_REBOOT is not set -# CONFIG_ESP32S2_PANIC_GDBSTUB is not set -CONFIG_ESP32S2_ALLOW_RTC_FAST_MEM_AS_HEAP=y -CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32 -CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2304 -CONFIG_MAIN_TASK_STACK_SIZE=3584 -CONFIG_CONSOLE_UART_DEFAULT=y -# CONFIG_CONSOLE_UART_CUSTOM is not set -# CONFIG_ESP_CONSOLE_UART_NONE is not set -CONFIG_CONSOLE_UART=y -CONFIG_CONSOLE_UART_NUM=0 -CONFIG_CONSOLE_UART_BAUDRATE=115200 -CONFIG_INT_WDT=n -CONFIG_INT_WDT_TIMEOUT_MS=1000 -CONFIG_INT_WDT_CHECK_CPU1=y -CONFIG_TASK_WDT=n -# CONFIG_TASK_WDT_PANIC is not set -CONFIG_TASK_WDT_TIMEOUT_S=5 -CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y -CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y -# CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set -CONFIG_TIMER_TASK_STACK_SIZE=3584 -# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set -CONFIG_ESP32_ENABLE_COREDUMP_TO_UART=y -# CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE is not set -# CONFIG_ESP32_COREDUMP_DATA_FORMAT_BIN is not set -CONFIG_ESP32_COREDUMP_DATA_FORMAT_ELF=y -CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y -# CONFIG_ESP32_COREDUMP_CHECKSUM_SHA256 is not set -CONFIG_ESP32_ENABLE_COREDUMP=y -CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 -CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 -CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y -# CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set -CONFIG_ESP32_CORE_DUMP_DECODE="info" -# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set -CONFIG_TIMER_TASK_PRIORITY=1 -CONFIG_TIMER_TASK_STACK_DEPTH=2048 -CONFIG_TIMER_QUEUE_LENGTH=10 -# CONFIG_L2_TO_L3_COPY is not set -# CONFIG_USE_ONLY_LWIP_SELECT is not set -CONFIG_ESP_GRATUITOUS_ARP=y -CONFIG_GARP_TMR_INTERVAL=60 -CONFIG_TCPIP_RECVMBOX_SIZE=32 -CONFIG_TCP_MAXRTX=12 -CONFIG_TCP_SYNMAXRTX=12 -CONFIG_TCP_MSS=1440 -CONFIG_TCP_MSL=60000 -CONFIG_TCP_SND_BUF_DEFAULT=5744 -CONFIG_TCP_WND_DEFAULT=5744 -CONFIG_TCP_RECVMBOX_SIZE=6 -CONFIG_TCP_QUEUE_OOSEQ=y -# CONFIG_ESP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set -CONFIG_TCP_OVERSIZE_MSS=y -# CONFIG_TCP_OVERSIZE_QUARTER_MSS is not set -# CONFIG_TCP_OVERSIZE_DISABLE is not set -CONFIG_UDP_RECVMBOX_SIZE=6 -CONFIG_TCPIP_TASK_STACK_SIZE=3072 -CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y -# CONFIG_TCPIP_TASK_AFFINITY_CPU0 is not set -# CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set -CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF -# CONFIG_PPP_SUPPORT is not set -CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 -CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 -CONFIG_ESP32_PTHREAD_STACK_MIN=768 -CONFIG_ESP32_DEFAULT_PTHREAD_CORE_NO_AFFINITY=y -# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_0 is not set -# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_1 is not set -CONFIG_ESP32_PTHREAD_TASK_CORE_DEFAULT=-1 -CONFIG_ESP32_PTHREAD_TASK_NAME_DEFAULT="pthread" -CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y -# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS is not set -# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set -CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y -CONFIG_SUPPORT_TERMIOS=y -CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 -# End of deprecated options diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig.defaults b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig.defaults new file mode 100644 index 00000000000000..22da63b62b92a7 --- /dev/null +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig.defaults @@ -0,0 +1,43 @@ +# This file was generated using idf.py save-defconfig. It can be edited manually. +# Espressif IoT Development Framework (ESP-IDF) 5.3.1 Project Minimal Configuration +# +CONFIG_IDF_TARGET="esp32s3" +CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y +CONFIG_BOOTLOADER_WDT_ENABLE=n +CONFIG_APP_COMPILE_TIME_DATE=n +CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y +CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y +CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 +CONFIG_ESPTOOLPY_FLASHMODE_QIO=y +CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y +CONFIG_PARTITION_TABLE_CUSTOM=y +CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv" +CONFIG_PARTITION_TABLE_OFFSET=0x10000 +CONFIG_COMPILER_OPTIMIZATION_PERF=y +CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=n +CONFIG_SPI_MASTER_IN_IRAM=y +CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_TWO=y +CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=n +CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND=n +CONFIG_ESP32S3_INSTRUCTION_CACHE_32KB=y +CONFIG_ESP_INT_WDT=n +CONFIG_ESP_TASK_WDT_INIT=n +CONFIG_ESP_IPC_TASK_STACK_SIZE=1536 +CONFIG_ESP_WIFI_TASK_PINNED_TO_CORE_1=y +CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE=n +CONFIG_ESP_WIFI_GMAC_SUPPORT=n +CONFIG_FREERTOS_HZ=1000 +CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10 +CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y +CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y +CONFIG_FREERTOS_ISR_STACKSIZE=2100 +CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3=y +CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY=y +CONFIG_LWIP_MAX_SOCKETS=5 +CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 +CONFIG_LWIP_TCP_WND_DEFAULT=5744 +CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y +CONFIG_ADC_SUPPRESS_DEPRECATE_WARN=y +CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN=y +CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN=y +CONFIG_RMT_SUPPRESS_DEPRECATE_WARN=y diff --git a/libraries/AP_HAL_Empty/AnalogIn.cpp b/libraries/AP_HAL_Empty/AnalogIn.cpp index 2ce5b286a552d8..9430aec6d329ec 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.cpp +++ b/libraries/AP_HAL_Empty/AnalogIn.cpp @@ -33,7 +33,7 @@ void AnalogIn::init() {} AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) { - return new AnalogSource(1.11); + return NEW_NOTHROW AnalogSource(1.11); } float AnalogIn::board_voltage(void) diff --git a/libraries/AP_HAL_Empty/GPIO.cpp b/libraries/AP_HAL_Empty/GPIO.cpp index 694f69e563e838..19f8245ee229bd 100644 --- a/libraries/AP_HAL_Empty/GPIO.cpp +++ b/libraries/AP_HAL_Empty/GPIO.cpp @@ -24,7 +24,7 @@ void GPIO::toggle(uint8_t pin) /* Alternative interface: */ AP_HAL::DigitalSource* GPIO::channel(uint16_t n) { - return new DigitalSource(0); + return NEW_NOTHROW DigitalSource(0); } bool GPIO::usb_connected(void) diff --git a/libraries/AP_HAL_Empty/SPIDevice.h b/libraries/AP_HAL_Empty/SPIDevice.h index be25c2873c45db..62849e7de2d6bb 100644 --- a/libraries/AP_HAL_Empty/SPIDevice.h +++ b/libraries/AP_HAL_Empty/SPIDevice.h @@ -77,7 +77,7 @@ class SPIDeviceManager : public AP_HAL::SPIDeviceManager { SPIDeviceManager() { } AP_HAL::OwnPtr get_device(const char *name) override { - return AP_HAL::OwnPtr(new SPIDevice()); + return AP_HAL::OwnPtr(NEW_NOTHROW SPIDevice()); } }; diff --git a/libraries/AP_HAL_Empty/Util.h b/libraries/AP_HAL_Empty/Util.h index 3dae90c2f82e5a..55e590a20e37ba 100644 --- a/libraries/AP_HAL_Empty/Util.h +++ b/libraries/AP_HAL_Empty/Util.h @@ -4,6 +4,4 @@ #include "AP_HAL_Empty_Namespace.h" class Empty::Util : public AP_HAL::Util { -public: - bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; } }; diff --git a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp index 24adaab39a7fa6..9e1a3f04ab25c8 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp @@ -44,7 +44,7 @@ extern const AP_HAL::HAL &hal; AnalogIn_ADS1115::AnalogIn_ADS1115() { - _adc = new AP_ADC_ADS1115(); + _adc = NEW_NOTHROW AP_ADC_ADS1115(); _channels_number = _adc->get_channels_number(); } @@ -53,7 +53,7 @@ AP_HAL::AnalogSource* AnalogIn_ADS1115::channel(int16_t pin) WITH_SEMAPHORE(_semaphore); for (uint8_t j = 0; j < _channels_number; j++) { if (_channels[j] == nullptr) { - _channels[j] = new AnalogSource_ADS1115(pin); + _channels[j] = NEW_NOTHROW AnalogSource_ADS1115(pin); return _channels[j]; } } diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp index fff9815f43bca8..5ad670791c545c 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp @@ -16,11 +16,11 @@ const char* AnalogSource_IIO::analog_sources[] = { }; AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) : - _pin(pin), _value(initial_value), - _voltage_scaling(voltage_scaling), _sum_value(0), + _voltage_scaling(voltage_scaling), _sum_count(0), + _pin(pin), _pin_fd(-1) { init_pins(); @@ -29,6 +29,8 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float volta void AnalogSource_IIO::init_pins(void) { + static_assert(ARRAY_SIZE(AnalogSource_IIO::analog_sources) == ARRAY_SIZE(fd_analog_sources), "AnalogIn_IIO channels count mismatch"); + char buf[100]; for (unsigned int i = 0; i < ARRAY_SIZE(AnalogSource_IIO::analog_sources); i++) { // Construct the path by appending strings @@ -44,7 +46,11 @@ void AnalogSource_IIO::init_pins(void) */ void AnalogSource_IIO::select_pin(void) { - _pin_fd = fd_analog_sources[_pin]; + if (0 <= _pin && (size_t)_pin < ARRAY_SIZE(fd_analog_sources)) { + _pin_fd = fd_analog_sources[_pin]; + } else { + _pin_fd = -1; + } } float AnalogSource_IIO::read_average() @@ -123,5 +129,5 @@ void AnalogIn_IIO::init() AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) { - return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING); + return NEW_NOTHROW AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING); } diff --git a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp index 0d05ad641ef382..faf450ee98701c 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp @@ -111,7 +111,7 @@ AP_HAL::AnalogSource *AnalogIn_Navio2::channel(int16_t pin) WITH_SEMAPHORE(_semaphore); for (uint8_t j = 0; j < _channels_number; j++) { if (_channels[j] == nullptr) { - _channels[j] = new AnalogSource_Navio2(pin); + _channels[j] = NEW_NOTHROW AnalogSource_Navio2(pin); return _channels[j]; } } diff --git a/libraries/AP_HAL_Linux/CANSocketIface.cpp b/libraries/AP_HAL_Linux/CANSocketIface.cpp index 05a02280ce9cec..b295c69077a918 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.cpp +++ b/libraries/AP_HAL_Linux/CANSocketIface.cpp @@ -34,6 +34,7 @@ #include #include +#include #include #include #include diff --git a/libraries/AP_HAL_Linux/CANSocketIface.h b/libraries/AP_HAL_Linux/CANSocketIface.h index 1e4d01a7b4666f..32bdcbf3d387ff 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.h +++ b/libraries/AP_HAL_Linux/CANSocketIface.h @@ -58,8 +58,8 @@ class CANIface: public AP_HAL::CANIface { public: CANIface(int index) : _self_index(index) - , _frames_in_socket_tx_queue(0) , _max_frames_in_socket_tx_queue(2) + , _frames_in_socket_tx_queue(0) { } ~CANIface() { } diff --git a/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp b/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp index 32fe9ed363d6d5..ba53789c8a0bce 100644 --- a/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp +++ b/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp @@ -113,8 +113,8 @@ CameraSensor_Mt9v117::CameraSensor_Mt9v117(const char *device_path, uint16_t nrst_gpio, uint32_t clock_freq) : CameraSensor(device_path) , _dev(std::move(dev)) - , _nrst_gpio(nrst_gpio) , _clock_freq(clock_freq) + , _nrst_gpio(nrst_gpio) { if (!_dev) { AP_HAL::panic("Could not find I2C bus for CameraSensor_Mt9v117"); diff --git a/libraries/AP_HAL_Linux/Flow_PX4.cpp b/libraries/AP_HAL_Linux/Flow_PX4.cpp index e285763c4fa57f..08939bccf9193e 100644 --- a/libraries/AP_HAL_Linux/Flow_PX4.cpp +++ b/libraries/AP_HAL_Linux/Flow_PX4.cpp @@ -53,8 +53,8 @@ Flow_PX4::Flow_PX4(uint32_t width, uint32_t bytesperline, float bottom_flow_feature_threshold, float bottom_flow_value_threshold) : _width(width), - _bytesperline(bytesperline), _search_size(max_flow_pixel), + _bytesperline(bytesperline), _bottom_flow_feature_threshold(bottom_flow_feature_threshold), _bottom_flow_value_threshold(bottom_flow_value_threshold) { diff --git a/libraries/AP_HAL_Linux/GPIO_BBB.cpp b/libraries/AP_HAL_Linux/GPIO_BBB.cpp index 69c2c222eef292..6aebf133bdc49d 100644 --- a/libraries/AP_HAL_Linux/GPIO_BBB.cpp +++ b/libraries/AP_HAL_Linux/GPIO_BBB.cpp @@ -114,7 +114,7 @@ void GPIO_BBB::toggle(uint8_t pin) /* Alternative interface: */ AP_HAL::DigitalSource* GPIO_BBB::channel(uint16_t n) { - return new DigitalSource(n); + return NEW_NOTHROW DigitalSource(n); } bool GPIO_BBB::usb_connected(void) diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index 974e6523e4a61b..68d0bc9ea0a4d8 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -8,243 +8,70 @@ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_CANZERO -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - #include "GPIO.h" +#include "GPIO_RPI.h" +#include "GPIO_RPI_BCM.h" +#include "GPIO_RPI_RP1.h" #include "Util_RPI.h" -#define GPIO_RPI_MAX_NUMBER_PINS 32 - -using namespace Linux; - extern const AP_HAL::HAL& hal; -// Range based in the first memory address of the first register and the last memory addres -// for the GPIO section (0x7E20'00B4 - 0x7E20'0000). -const uint8_t GPIO_RPI::_gpio_registers_memory_range = 0xB4; -const char* GPIO_RPI::_system_memory_device_path = "/dev/mem"; +using namespace Linux; GPIO_RPI::GPIO_RPI() { } -void GPIO_RPI::set_gpio_mode_alt(int pin, int alternative) -{ - // Each register can contain 10 pins - const uint8_t pins_per_register = 10; - // Calculates the position of the 3 bit mask in the 32 bits register - const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; - /** Creates a mask to enable the alternative function based in the following logic: - * - * | Alternative Function | 3 bits value | - * |:--------------------:|:------------:| - * | Function 0 | 0b100 | - * | Function 1 | 0b101 | - * | Function 2 | 0b110 | - * | Function 3 | 0b111 | - * | Function 4 | 0b011 | - * | Function 5 | 0b010 | - */ - const uint8_t alternative_value = - (alternative < 4 ? (alternative + 4) : (alternative == 4 ? 3 : 2)); - // 0b00'000'000'000'000'000'000'ALT'000'000'000 enables alternative for the 4th pin - const uint32_t mask_with_alt = static_cast(alternative_value) << tree_bits_position_in_register; - const uint32_t mask = 0b111 << tree_bits_position_in_register; - // Clear all bits in our position and apply our mask with alt values - uint32_t register_value = _gpio[pin / pins_per_register]; - register_value &= ~mask; - _gpio[pin / pins_per_register] = register_value | mask_with_alt; -} - -void GPIO_RPI::set_gpio_mode_in(int pin) -{ - // Each register can contain 10 pins - const uint8_t pins_per_register = 10; - // Calculates the position of the 3 bit mask in the 32 bits register - const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; - // Create a mask that only removes the bits in this specific GPIO pin, E.g: - // 0b11'111'111'111'111'111'111'000'111'111'111 for the 4th pin - const uint32_t mask = ~(0b111<(address) + static_cast(offset); -} - -volatile uint32_t* GPIO_RPI::get_memory_pointer(uint32_t address, uint32_t range) const -{ - auto pointer = mmap( - nullptr, // Any adddress in our space will do - range, // Map length - PROT_READ|PROT_WRITE|PROT_EXEC, // Enable reading & writing to mapped memory - MAP_SHARED|MAP_LOCKED, // Shared with other processes - _system_memory_device, // File to map - address // Offset to GPIO peripheral - ); - - if (pointer == MAP_FAILED) { - return nullptr; - } - - return static_cast(pointer); -} - -bool GPIO_RPI::openMemoryDevice() -{ - _system_memory_device = open(_system_memory_device_path, O_RDWR|O_SYNC|O_CLOEXEC); - if (_system_memory_device < 0) { - AP_HAL::panic("Can't open %s", GPIO_RPI::_system_memory_device_path); - return false; - } - - return true; -} - -void GPIO_RPI::closeMemoryDevice() -{ - close(_system_memory_device); - // Invalidate device variable - _system_memory_device = -1; -} - void GPIO_RPI::init() { const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type(); - GPIO_RPI::Address peripheral_base; - if(rpi_version == LINUX_BOARD_TYPE::RPI_ZERO_1) { - peripheral_base = Address::BCM2708_PERIPHERAL_BASE; - } else if (rpi_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) { - peripheral_base = Address::BCM2709_PERIPHERAL_BASE; - } else if (rpi_version == LINUX_BOARD_TYPE::RPI_4) { - peripheral_base = Address::BCM2711_PERIPHERAL_BASE; - } else { - AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); - return; - } - - if (!openMemoryDevice()) { - AP_HAL::panic("Failed to initialize memory device."); - return; - } - - const uint32_t gpio_address = get_address(peripheral_base, PeripheralOffset::GPIO); - - _gpio = get_memory_pointer(gpio_address, _gpio_registers_memory_range); - if (!_gpio) { - AP_HAL::panic("Failed to get GPIO memory map."); + switch (rpi_version) { + case LINUX_BOARD_TYPE::RPI_ZERO_1: + case LINUX_BOARD_TYPE::RPI_2_3_ZERO2: + case LINUX_BOARD_TYPE::RPI_4: + gpioDriver = NEW_NOTHROW GPIO_RPI_BCM(); + gpioDriver->init(); + break; + case LINUX_BOARD_TYPE::RPI_5: + gpioDriver = NEW_NOTHROW GPIO_RPI_RP1(); + gpioDriver->init(); + break; + default: + AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); + return; } - - // No need to keep mem_fd open after mmap - closeMemoryDevice(); } void GPIO_RPI::pinMode(uint8_t pin, uint8_t output) { - if (output == HAL_GPIO_INPUT) { - set_gpio_mode_in(pin); - } else { - set_gpio_mode_in(pin); - set_gpio_mode_out(pin); - } + gpioDriver->pinMode(pin, output); } void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt) { - if (output == HAL_GPIO_INPUT) { - set_gpio_mode_in(pin); - } else if (output == HAL_GPIO_ALT) { - set_gpio_mode_in(pin); - set_gpio_mode_alt(pin, alt); - } else { - set_gpio_mode_in(pin); - set_gpio_mode_out(pin); - } + gpioDriver->pinMode(pin, output, alt); } uint8_t GPIO_RPI::read(uint8_t pin) { - if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { - return 0; - } - return static_cast(get_gpio_logic_state(pin)); + return gpioDriver->read(pin); } void GPIO_RPI::write(uint8_t pin, uint8_t value) { - if (value != 0) { - set_gpio_high(pin); - } else { - set_gpio_low(pin); - } + gpioDriver->write(pin, value); } void GPIO_RPI::toggle(uint8_t pin) { - if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { - return ; - } - uint32_t flag = (1 << pin); - _gpio_output_port_status ^= flag; - write(pin, (_gpio_output_port_status & flag) >> pin); + gpioDriver->toggle(pin); } /* Alternative interface: */ AP_HAL::DigitalSource* GPIO_RPI::channel(uint16_t n) { - return new DigitalSource(n); + return NEW_NOTHROW DigitalSource(n); } bool GPIO_RPI::usb_connected(void) diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.h b/libraries/AP_HAL_Linux/GPIO_RPI.h index f694dce679041a..ac934a42ef8418 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.h +++ b/libraries/AP_HAL_Linux/GPIO_RPI.h @@ -2,6 +2,7 @@ #include #include "AP_HAL_Linux.h" +#include "GPIO_RPI_HAL.h" /** * @brief Check for valid Raspberry Pi pin range @@ -15,13 +16,12 @@ template constexpr uint8_t RPI_GPIO_() return pin; } + namespace Linux { /** * @brief Class for Raspberry PI GPIO control * - * For more information: https://elinux.org/RPi_BCM2835_GPIOs - * */ class GPIO_RPI : public AP_HAL::GPIO { public: @@ -40,161 +40,7 @@ class GPIO_RPI : public AP_HAL::GPIO { bool usb_connected(void) override; private: - // Raspberry Pi BASE memory address - enum class Address : uint32_t { - BCM2708_PERIPHERAL_BASE = 0x20000000, // Raspberry Pi 0/1 - BCM2709_PERIPHERAL_BASE = 0x3F000000, // Raspberry Pi 2/3 - BCM2711_PERIPHERAL_BASE = 0xFE000000, // Raspberry Pi 4 - }; - - // Offset between peripheral base address - enum class PeripheralOffset : uint32_t { - GPIO = 0x200000, - }; - - /** - * @brief Open memory device to allow gpio address access - * Should be used before get_memory_pointer calls in the initialization - * - * @return true - * @return false - */ - bool openMemoryDevice(); - - /** - * @brief Close open memory device - * - */ - void closeMemoryDevice(); - - /** - * @brief Return pointer to memory location with specific range access - * - * @param address - * @param range - * @return volatile uint32_t* - */ - volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; - - /** - * @brief Get memory address based in base address and peripheral offset - * - * @param address - * @param offset - * @return uint32_t - */ - uint32_t get_address(GPIO_RPI::Address address, GPIO_RPI::PeripheralOffset offset) const; - - /** - * @brief Change functionality of GPIO Function Select Registers (GPFSELn) to any alternative function. - * Each GPIO pin is mapped to 3 bits inside a 32 bits register, E.g: - * - * 0b00...'010'101 - * ││ │││ ││└── GPIO Pin N, 1st bit, LSBit - * ││ │││ │└─── GPIO Pin N, 2nd bit - * ││ │││ └──── GPIO Pin N, 3rd bit, MSBit - * ││ ││└────── GPIO Pin N+1, 1st bit, LSBit - * ││ │└─────── GPIO Pin N+1, 2nd bit, - * ││ └──────── GPIO Pin N+1, 3rd bit, MSBit - * ││ ... - * │└───────────── Reserved - * └────────────── Reserved - * - * And the value of this 3 bits selects the functionality of the GPIO pin, E.g: - * 000 = GPIO Pin N is an input - * 001 = GPIO Pin N is an output - * 100 = GPIO Pin N takes alternate function 0 - * 101 = GPIO Pin N takes alternate function 1 - * 110 = GPIO Pin N takes alternate function 2 - * 111 = GPIO Pin N takes alternate function 3 - * 011 = GPIO Pin N takes alternate function 4 - * 010 = GPIO Pin N takes alternate function 5 - * - * The alternative functions are defined in the BCM datasheet under "Alternative Function" - * section for each pin. - * - * This information is also valid for: - * - Linux::GPIO_RPI::set_gpio_mode_in - * - Linux::GPIO_RPI::set_gpio_mode_out - * - * @param pin - */ - void set_gpio_mode_alt(int pin, int alternative); - - /** - * @brief Set a specific GPIO as input - * Check Linux::GPIO_RPI::set_gpio_mode_alt for more information. - * - * @param pin - */ - void set_gpio_mode_in(int pin); - - /** - * @brief Set a specific GPIO as output - * Check Linux::GPIO_RPI::set_gpio_mode_alt for more information. - * - * @param pin - */ - void set_gpio_mode_out(int pin); - - /** - * @brief Modify GPSET0 (GPIO Pin Output Set 0) register to set pin as high - * Writing zero to this register has no effect, please use Linux::GPIO_RPI::set_gpio_low - * to set pin as low. - * - * GPSET0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, defined as High - * │└─── GPIO Pin 2, 2nd bit, No effect - * └──── GPIO Pin 3, 3rd bit, defined as High - * ... - * - * @param pin - */ - void set_gpio_high(int pin); - - /** - * @brief Modify GPCLR0 (GPIO Pin Output Clear 0) register to set pin as low - * Writing zero to this register has no effect, please use Linux::GPIO_RPI::set_gpio_high - * to set pin as high. - * - * GPCLR0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, defined as Low - * │└─── GPIO Pin 2, 2nd bit, No effect - * └──── GPIO Pin 3, 3rd bit, defined as Low - * - * @param pin - */ - void set_gpio_low(int pin); - - /** - * @brief Read GPLEV0 (GPIO Pin Level 0) register check the logic state of a specific pin - * - * GPLEV0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, Pin is in High state - * │└─── GPIO Pin 2, 2nd bit, Pin is in Low state - * └──── GPIO Pin 3, 3rd bit, Pin is in High state - * - * @param pin - * @return true - * @return false - */ - bool get_gpio_logic_state(int pin); - - // Memory pointer to gpio registers - volatile uint32_t* _gpio; - // Memory range for the gpio registers - static const uint8_t _gpio_registers_memory_range; - // Path to memory device (E.g: /dev/mem) - static const char* _system_memory_device_path; - // File descriptor for the memory device file - // If it's negative, then there was an error opening the file. - int _system_memory_device; - // store GPIO output status. - uint32_t _gpio_output_port_status = 0x00; - + GPIO_RPI_HAL* gpioDriver; }; } diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp new file mode 100644 index 00000000000000..b00624c7ba8444 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp @@ -0,0 +1,241 @@ +#include + +#include +#include +#include +#include +#include + +#include "GPIO.h" +#include "Util_RPI.h" +#include "GPIO_RPI_BCM.h" + +#define GPIO_RPI_MAX_NUMBER_PINS 32 + +using namespace Linux; + +extern const AP_HAL::HAL& hal; + +// Range based in the first memory address of the first register and the last memory addres +// for the GPIO section (0x7E20'00B4 - 0x7E20'0000). +const uint8_t GPIO_RPI_BCM::_gpio_registers_memory_range = 0xB4; +const char* GPIO_RPI_BCM::_system_memory_device_path = "/dev/mem"; + +GPIO_RPI_BCM::GPIO_RPI_BCM() +{ +} + +void GPIO_RPI_BCM::set_gpio_mode_alt(int pin, int alternative) +{ + // Each register can contain 10 pins + const uint8_t pins_per_register = 10; + // Calculates the position of the 3 bit mask in the 32 bits register + const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; + /** Creates a mask to enable the alternative function based in the following logic: + * + * | Alternative Function | 3 bits value | + * |:--------------------:|:------------:| + * | Function 0 | 0b100 | + * | Function 1 | 0b101 | + * | Function 2 | 0b110 | + * | Function 3 | 0b111 | + * | Function 4 | 0b011 | + * | Function 5 | 0b010 | + */ + const uint8_t alternative_value = + (alternative < 4 ? (alternative + 4) : (alternative == 4 ? 3 : 2)); + // 0b00'000'000'000'000'000'000'ALT'000'000'000 enables alternative for the 4th pin + const uint32_t mask_with_alt = static_cast(alternative_value) << tree_bits_position_in_register; + const uint32_t mask = 0b111 << tree_bits_position_in_register; + // Clear all bits in our position and apply our mask with alt values + uint32_t register_value = _gpio[pin / pins_per_register]; + register_value &= ~mask; + _gpio[pin / pins_per_register] = register_value | mask_with_alt; +} + +void GPIO_RPI_BCM::set_gpio_mode_in(int pin) +{ + // Each register can contain 10 pins + const uint8_t pins_per_register = 10; + // Calculates the position of the 3 bit mask in the 32 bits register + const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; + // Create a mask that only removes the bits in this specific GPIO pin, E.g: + // 0b11'111'111'111'111'111'111'000'111'111'111 for the 4th pin + const uint32_t mask = ~(0b111<(address) + static_cast(offset); +} + +volatile uint32_t* GPIO_RPI_BCM::get_memory_pointer(uint32_t address, uint32_t range) const +{ + auto pointer = mmap( + nullptr, // Any adddress in our space will do + range, // Map length + PROT_READ|PROT_WRITE|PROT_EXEC, // Enable reading & writing to mapped memory + MAP_SHARED|MAP_LOCKED, // Shared with other processes + _system_memory_device, // File to map + address // Offset to GPIO peripheral + ); + + if (pointer == MAP_FAILED) { + return nullptr; + } + + return static_cast(pointer); +} + +bool GPIO_RPI_BCM::openMemoryDevice() +{ + _system_memory_device = open(_system_memory_device_path, O_RDWR|O_SYNC|O_CLOEXEC); + if (_system_memory_device < 0) { + AP_HAL::panic("Can't open %s", GPIO_RPI_BCM::_system_memory_device_path); + return false; + } + + return true; +} + +void GPIO_RPI_BCM::closeMemoryDevice() +{ + close(_system_memory_device); + // Invalidate device variable + _system_memory_device = -1; +} + +void GPIO_RPI_BCM::init() +{ + const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type(); + + GPIO_RPI_BCM::Address peripheral_base; + if(rpi_version == LINUX_BOARD_TYPE::RPI_ZERO_1) { + peripheral_base = Address::BCM2708_PERIPHERAL_BASE; + } else if (rpi_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) { + peripheral_base = Address::BCM2709_PERIPHERAL_BASE; + } else if (rpi_version == LINUX_BOARD_TYPE::RPI_4) { + peripheral_base = Address::BCM2711_PERIPHERAL_BASE; + } else { + AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); + return; + } + + if (!openMemoryDevice()) { + AP_HAL::panic("Failed to initialize memory device."); + return; + } + + const uint32_t gpio_address = get_address(peripheral_base, PeripheralOffset::GPIO); + + _gpio = get_memory_pointer(gpio_address, _gpio_registers_memory_range); + if (!_gpio) { + AP_HAL::panic("Failed to get GPIO memory map."); + } + + // No need to keep mem_fd open after mmap + closeMemoryDevice(); +} + +void GPIO_RPI_BCM::pinMode(uint8_t pin, uint8_t output) +{ + if (output == HAL_GPIO_INPUT) { + set_gpio_mode_in(pin); + } else { + set_gpio_mode_in(pin); + set_gpio_mode_out(pin); + } +} + +void GPIO_RPI_BCM::pinMode(uint8_t pin, uint8_t output, uint8_t alt) +{ + if (output == HAL_GPIO_INPUT) { + set_gpio_mode_in(pin); + } else if (output == HAL_GPIO_ALT) { + set_gpio_mode_in(pin); + set_gpio_mode_alt(pin, alt); + } else { + set_gpio_mode_in(pin); + set_gpio_mode_out(pin); + } +} + +uint8_t GPIO_RPI_BCM::read(uint8_t pin) +{ + if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { + return 0; + } + return static_cast(get_gpio_logic_state(pin)); +} + +void GPIO_RPI_BCM::write(uint8_t pin, uint8_t value) +{ + if (value != 0) { + set_gpio_high(pin); + } else { + set_gpio_low(pin); + } +} + +void GPIO_RPI_BCM::toggle(uint8_t pin) +{ + if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { + return ; + } + uint32_t flag = (1 << pin); + _gpio_output_port_status ^= flag; + write(pin, (_gpio_output_port_status & flag) >> pin); +} + +/* Alternative interface: */ +AP_HAL::DigitalSource* GPIO_RPI_BCM::channel(uint16_t n) +{ + return NEW_NOTHROW DigitalSource(n); +} + +bool GPIO_RPI_BCM::usb_connected(void) +{ + return false; +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h new file mode 100644 index 00000000000000..f0bf6c293bfd74 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h @@ -0,0 +1,188 @@ +#pragma once + +#include +#include "GPIO_RPI_HAL.h" + +namespace Linux { + +/** + * @brief Class for Raspberry PI GPIO control + * + * For more information: https://elinux.org/RPi_BCM2835_GPIOs + * + */ +class GPIO_RPI_BCM : public GPIO_RPI_HAL { +public: + GPIO_RPI_BCM(); + void init() override; + 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; + void toggle(uint8_t pin) override; + + /* Alternative interface: */ + AP_HAL::DigitalSource* channel(uint16_t n); + + /* return true if USB cable is connected */ + bool usb_connected(void); + +private: + // Raspberry Pi BASE memory address + enum class Address : uint32_t { + BCM2708_PERIPHERAL_BASE = 0x20000000, // Raspberry Pi 0/1 + BCM2709_PERIPHERAL_BASE = 0x3F000000, // Raspberry Pi 2/3 + BCM2711_PERIPHERAL_BASE = 0xFE000000, // Raspberry Pi 4 + }; + + // Offset between peripheral base address + enum class PeripheralOffset : uint32_t { + GPIO = 0x200000, + }; + + /** + * @brief Open memory device to allow gpio address access + * Should be used before get_memory_pointer calls in the initialization + * + * @return true + * @return false + */ + bool openMemoryDevice(); + + /** + * @brief Close open memory device + * + */ + void closeMemoryDevice(); + + /** + * @brief Return pointer to memory location with specific range access + * + * @param address + * @param range + * @return volatile uint32_t* + */ + volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; + + /** + * @brief Get memory address based in base address and peripheral offset + * + * @param address + * @param offset + * @return uint32_t + */ + uint32_t get_address(GPIO_RPI_BCM::Address address, GPIO_RPI_BCM::PeripheralOffset offset) const; + + /** + * @brief Change functionality of GPIO Function Select Registers (GPFSELn) to any alternative function. + * Each GPIO pin is mapped to 3 bits inside a 32 bits register, E.g: + * + * 0b00...'010'101 + * ││ │││ ││└── GPIO Pin N, 1st bit, LSBit + * ││ │││ │└─── GPIO Pin N, 2nd bit + * ││ │││ └──── GPIO Pin N, 3rd bit, MSBit + * ││ ││└────── GPIO Pin N+1, 1st bit, LSBit + * ││ │└─────── GPIO Pin N+1, 2nd bit, + * ││ └──────── GPIO Pin N+1, 3rd bit, MSBit + * ││ ... + * │└───────────── Reserved + * └────────────── Reserved + * + * And the value of this 3 bits selects the functionality of the GPIO pin, E.g: + * 000 = GPIO Pin N is an input + * 001 = GPIO Pin N is an output + * 100 = GPIO Pin N takes alternate function 0 + * 101 = GPIO Pin N takes alternate function 1 + * 110 = GPIO Pin N takes alternate function 2 + * 111 = GPIO Pin N takes alternate function 3 + * 011 = GPIO Pin N takes alternate function 4 + * 010 = GPIO Pin N takes alternate function 5 + * + * The alternative functions are defined in the BCM datasheet under "Alternative Function" + * section for each pin. + * + * This information is also valid for: + * - Linux::GPIO_RPI_BCM::set_gpio_mode_in + * - Linux::GPIO_RPI_BCM::set_gpio_mode_out + * + * @param pin + */ + void set_gpio_mode_alt(int pin, int alternative); + + /** + * @brief Set a specific GPIO as input + * Check Linux::GPIO_RPI_BCM::set_gpio_mode_alt for more information. + * + * @param pin + */ + void set_gpio_mode_in(int pin); + + /** + * @brief Set a specific GPIO as output + * Check Linux::GPIO_RPI_BCM::set_gpio_mode_alt for more information. + * + * @param pin + */ + void set_gpio_mode_out(int pin); + + /** + * @brief Modify GPSET0 (GPIO Pin Output Set 0) register to set pin as high + * Writing zero to this register has no effect, please use Linux::GPIO_RPI_BCM::set_gpio_low + * to set pin as low. + * + * GPSET0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, defined as High + * │└─── GPIO Pin 2, 2nd bit, No effect + * └──── GPIO Pin 3, 3rd bit, defined as High + * ... + * + * @param pin + */ + void set_gpio_high(int pin); + + /** + * @brief Modify GPCLR0 (GPIO Pin Output Clear 0) register to set pin as low + * Writing zero to this register has no effect, please use Linux::GPIO_RPI_BCM::set_gpio_high + * to set pin as high. + * + * GPCLR0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, defined as Low + * │└─── GPIO Pin 2, 2nd bit, No effect + * └──── GPIO Pin 3, 3rd bit, defined as Low + * + * @param pin + */ + void set_gpio_low(int pin); + + /** + * @brief Read GPLEV0 (GPIO Pin Level 0) register check the logic state of a specific pin + * + * GPLEV0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, Pin is in High state + * │└─── GPIO Pin 2, 2nd bit, Pin is in Low state + * └──── GPIO Pin 3, 3rd bit, Pin is in High state + * + * @param pin + * @return true + * @return false + */ + bool get_gpio_logic_state(int pin); + + // Memory pointer to gpio registers + volatile uint32_t* _gpio; + // Memory range for the gpio registers + static const uint8_t _gpio_registers_memory_range; + // Path to memory device (E.g: /dev/mem) + static const char* _system_memory_device_path; + // File descriptor for the memory device file + // If it's negative, then there was an error opening the file. + int _system_memory_device; + // store GPIO output status. + uint32_t _gpio_output_port_status = 0x00; + +}; + +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h b/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h new file mode 100644 index 00000000000000..7cec066a94340d --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h @@ -0,0 +1,13 @@ +#pragma once + +class GPIO_RPI_HAL { +public: + GPIO_RPI_HAL() {} + virtual void init() = 0; + virtual void pinMode(uint8_t pin, uint8_t output) = 0; + virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {}; + + virtual uint8_t read(uint8_t pin) = 0; + virtual void write(uint8_t pin, uint8_t value) = 0; + virtual void toggle(uint8_t pin) = 0; +}; diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp new file mode 100644 index 00000000000000..bef2897ba430d2 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp @@ -0,0 +1,178 @@ +#include + +#include "GPIO_RPI_RP1.h" + +#include +#include +#include +#include +#include +#include +#include + +using namespace Linux; + +using namespace AP_HAL; + +GPIO_RPI_RP1::GPIO_RPI_RP1() { +} + +bool GPIO_RPI_RP1::openMemoryDevice() { + _system_memory_device = open(PATH_DEV_GPIOMEM, O_RDWR | O_SYNC | O_CLOEXEC); + if (_system_memory_device < 0) { + AP_HAL::panic("Can't open %s", PATH_DEV_GPIOMEM); + return false; + } + return true; +} + +void GPIO_RPI_RP1::closeMemoryDevice() { + close(_system_memory_device); + _system_memory_device = -1; +} + +volatile uint32_t* GPIO_RPI_RP1::get_memory_pointer(uint32_t address, uint32_t length) const { + auto pointer = mmap( + nullptr, + length, + PROT_READ | PROT_WRITE | PROT_EXEC, + MAP_SHARED | MAP_LOCKED, // Shared with other processes + _system_memory_device, // File to map + address // Offset to GPIO peripheral + ); + + if (pointer == MAP_FAILED) { + return nullptr; + } + + return static_cast(pointer); +} + +void GPIO_RPI_RP1::init() { + if (!openMemoryDevice()) { + AP_HAL::panic("Failed to initialize memory device."); + return; + } + + _gpio = get_memory_pointer(IO_BANK0_OFFSET, MEM_SIZE); + if (!_gpio) { + AP_HAL::panic("Failed to get GPIO memory map."); + } + + closeMemoryDevice(); +} + +uint32_t GPIO_RPI_RP1::read_register(uint32_t offset) const { + return _gpio[offset]; +} + +void GPIO_RPI_RP1::write_register(uint32_t offset, uint32_t value) { + _gpio[offset] = value; +} + +GPIO_RPI_RP1::Mode GPIO_RPI_RP1::direction(uint8_t pin) const { + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OE) / REG_SIZE; + uint32_t value = (read_register(offset) >> pin) & 0b1; + return value > 0 ? Mode::Output : Mode::Input; +} + +void GPIO_RPI_RP1::set_direction(uint8_t pin, Mode mode) { + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OE) / REG_SIZE; + offset += (mode == Mode::Output ? SET_OFFSET : CLR_OFFSET) / REG_SIZE; + write_register(offset, 1 << pin); +} + +void GPIO_RPI_RP1::input_enable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + SET_OFFSET) / REG_SIZE; + write_register(offset, PADS_IN_ENABLE_MASK); +} + +void GPIO_RPI_RP1::input_disable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + CLR_OFFSET) / REG_SIZE; + write_register(offset, PADS_IN_ENABLE_MASK); +} + +void GPIO_RPI_RP1::output_enable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + CLR_OFFSET) / REG_SIZE; + write_register(offset, PADS_OUT_DISABLE_MASK); +} + +void GPIO_RPI_RP1::output_disable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + SET_OFFSET) / REG_SIZE; + write_register(offset, PADS_OUT_DISABLE_MASK); +} + +void GPIO_RPI_RP1::pinMode(uint8_t pin, uint8_t mode) { + if (mode == HAL_GPIO_INPUT) { + input_enable(pin); + set_direction(pin, Mode::Input); + set_mode(pin, Mode::Input); + } else if (mode == HAL_GPIO_OUTPUT) { + output_enable(pin); + set_direction(pin, Mode::Output); + set_mode(pin, Mode::Input); + } +} + +void GPIO_RPI_RP1::pinMode(uint8_t pin, uint8_t mode, uint8_t alt) { + if (mode == HAL_GPIO_ALT) { + set_mode(pin, static_cast(alt)); + return; + } + pinMode(pin, mode); +} + +void GPIO_RPI_RP1::set_mode(uint8_t pin, Mode mode) { + FunctionSelect alt_value; + + switch (mode) { + // ALT5 is used for GPIO, check datasheet pinout alternative functions + case Mode::Alt5: + case Mode::Input: + case Mode::Output: + alt_value = FunctionSelect::Alt5; + break; + case Mode::Alt0: alt_value = FunctionSelect::Alt0; break; + case Mode::Alt1: alt_value = FunctionSelect::Alt1; break; + case Mode::Alt2: alt_value = FunctionSelect::Alt2; break; + case Mode::Alt3: alt_value = FunctionSelect::Alt3; break; + case Mode::Alt4: alt_value = FunctionSelect::Alt4; break; + case Mode::Alt6: alt_value = FunctionSelect::Alt6; break; + case Mode::Alt7: alt_value = FunctionSelect::Alt7; break; + case Mode::Alt8: alt_value = FunctionSelect::Alt8; break; + default: alt_value = FunctionSelect::Null; break; + } + + uint32_t ctrl_offset = (IO_BANK0_OFFSET + GPIO_CTRL + (pin * GPIO_OFFSET) + RW_OFFSET) / REG_SIZE; + uint32_t reg_val = read_register(ctrl_offset); + reg_val &= ~CTRL_FUNCSEL_MASK; // Clear existing function select bits + reg_val |= (static_cast(alt_value) << CTRL_FUNCSEL_LSB); + write_register(ctrl_offset, reg_val); + +} + +void GPIO_RPI_RP1::set_pull(uint8_t pin, PadsPull mode) { + uint32_t pads_offset = (PADS_BANK0_OFFSET + PADS_GPIO + (pin * PADS_OFFSET) + RW_OFFSET) / REG_SIZE; + uint32_t reg_val = read_register(pads_offset); + reg_val &= ~PADS_PULL_MASK; // Clear existing bias bits + reg_val |= (static_cast(mode) << PADS_PULL_LSB); + write_register(pads_offset, reg_val); +} + +uint8_t GPIO_RPI_RP1::read(uint8_t pin) { + uint32_t in_offset = (SYS_RIO0_OFFSET + RIO_IN) / REG_SIZE; + uint32_t reg_val = read_register(in_offset); + return (reg_val >> pin) & 0x1; +} + +void GPIO_RPI_RP1::write(uint8_t pin, uint8_t value) { + uint32_t register_offset = value ? SET_OFFSET : CLR_OFFSET; + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OUT + register_offset) / REG_SIZE; + write_register(offset, 1 << pin); +} + +void GPIO_RPI_RP1::toggle(uint8_t pin) { + uint32_t flag = (1 << pin); + _gpio_output_port_status ^= flag; + write(pin, (_gpio_output_port_status & flag) >> pin); +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h new file mode 100644 index 00000000000000..8ea1f342fd4c1d --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h @@ -0,0 +1,169 @@ +#pragma once + +#include +#include "GPIO_RPI_HAL.h" + +namespace Linux { + +/** + * @brief Class for Raspberry PI 5 GPIO control + * + * For more information: + * - RP1 datasheet: https://datasheets.raspberrypi.com/rp1/rp1-peripherals.pdf + * - gpiomem0: https://github.com/raspberrypi/linux/blob/1e53604087930e7cf42eee3d42572d0d6f54c86a/arch/arm/boot/dts/broadcom/bcm2712-rpi.dtsi#L178 + * - Address: 0x400d'0000, Size: 0x3'0000 + * + */ +class GPIO_RPI_RP1 : public GPIO_RPI_HAL { +public: + GPIO_RPI_RP1(); + void init() override; + void pinMode(uint8_t pin, uint8_t mode) override; + void pinMode(uint8_t pin, uint8_t mode, uint8_t alt) override; + + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; + void toggle(uint8_t pin) override; + + enum class PadsPull : uint8_t { + Off = 0, + Down = 1, + Up = 2, + }; + + void set_pull(uint8_t pin, PadsPull mode); + +private: + // gpiomem0 already maps the 0x400d'0000 address for us + static constexpr const char* PATH_DEV_GPIOMEM = "/dev/gpiomem0"; + static constexpr uint32_t MEM_SIZE = 0x30000; + static constexpr uint32_t REG_SIZE = sizeof(uint32_t); + + // Register offsets from RP1 datasheet 'Table 2. Peripheral Address Map' + // E.g: + // - IO_BANK0_OFFSET: 0x0'0000 result in 0x400d'0000 + // - SYS_RIO0_OFFSET: 0x1'0000 result in 0x400e'0000 + // ... + static constexpr uint32_t IO_BANK0_OFFSET = 0x00000; + static constexpr uint32_t SYS_RIO0_OFFSET = 0x10000; + static constexpr uint32_t PADS_BANK0_OFFSET = 0x20000; + + // GPIO control from https://github.com/raspberrypi/linux/blob/21012295fe87a7ccc1c356d1e268fd289aafbad1/drivers/pinctrl/pinctrl-rp1.c + static constexpr uint32_t RIO_OUT = 0x00; + static constexpr uint32_t RIO_OE = 0x04; + static constexpr uint32_t RIO_IN = 0x08; + + // GPIO control from '2.4. Atomic register access' + static constexpr uint32_t RW_OFFSET = 0x0000; + static constexpr uint32_t XOR_OFFSET = 0x1000; + static constexpr uint32_t SET_OFFSET = 0x2000; + static constexpr uint32_t CLR_OFFSET = 0x3000; + + static constexpr uint32_t GPIO_CTRL = 0x0004; + static constexpr uint32_t GPIO_OFFSET = 8; + + static constexpr uint32_t PADS_GPIO = 0x04; + static constexpr uint32_t PADS_OFFSET = 4; + + /** + * GPIO control from 'Table 8. GPI0_CTRL, GPI1_CTRL, ...' + * + * 0b0000'0000'0000'0000'0000'0000'0001'1101 + * ├┘│├─┘├┘├─┘├┘├─┘├┘├─┘├┘│ ├──────┘└────┴─ Bits 4:0 FUNCSEL: Function select + * │ ││ │ │ │ │ │ │ │ │ └────────────── Bits 11:5 F_M: Filter/debounce time constant M + * │ ││ │ │ │ │ │ │ │ └──────────────── Bits 13:12 OUTOVER: Output control + * │ ││ │ │ │ │ │ │ └────────────────── Bits 15:14 OEOVER: Output enable control + * │ ││ │ │ │ │ │ └───────────────────── Bits 17:16 INOVER: Input control + * │ ││ │ │ │ │ └─────────────────────── Bits 19:18 Reserved + * │ ││ │ │ │ └────────────────────────── Bits 20:21 IRQMASK_EDGE_LOW/HIGH + * │ ││ │ │ └──────────────────────────── Bits 22:23 IRQMASK_LEVEL_LOW/HIGH + * │ ││ │ └─────────────────────────────── Bits 24:25 IRQMASK_F_EDGE_LOW/HIGH + * │ ││ └───────────────────────────────── Bits 26:27 IRQMASK_DB_LEVEL_LOW/HIGH + * │ │└──────────────────────────────────── Bit 28 IRQRESET: Interrupt edge detector reset + * │ └───────────────────────────────────── Bit 29 Reserved + * └─────────────────────────────────────── Bits 31:30 IRQOVER: Interrupt control + */ + static constexpr uint32_t CTRL_FUNCSEL_MASK = 0x001f; + static constexpr uint32_t CTRL_FUNCSEL_LSB = 0; + static constexpr uint32_t CTRL_OUTOVER_MASK = 0x3000; + static constexpr uint32_t CTRL_OUTOVER_LSB = 12; + static constexpr uint32_t CTRL_OEOVER_MASK = 0xc000; + static constexpr uint32_t CTRL_OEOVER_LSB = 14; + static constexpr uint32_t CTRL_INOVER_MASK = 0x30000; + static constexpr uint32_t CTRL_INOVER_LSB = 16; + static constexpr uint32_t CTRL_IRQOVER_MASK = 0xc0000000; + static constexpr uint32_t CTRL_IRQOVER_LSB = 30; + + /** + * Mask for PADS_BANK control from 'Table 21.' + * + * 0b0...001'1101 + * ├──┘││├─┘││└─ Bit 1 SLEWFAST: Slew rate control. 1 = Fast, 0 = Slow + * │ │││ │└── Bit 2 SCHMITT: Enable schmitt trigger + * │ │││ └─── Bit 3 PDE: Pull down enable + * │ ││└────── Bits 4:5 DRIVE: Drive strength + * │ │└─────── Bit 6 IE: Input enable + * │ └──────── Bit 7 OD: Output disable. Has priority over output enable from + * └──────────── Bits 31:8 Reserved + */ + static constexpr uint32_t PADS_IN_ENABLE_MASK = 0x40; + static constexpr uint32_t PADS_OUT_DISABLE_MASK = 0x80; + static constexpr uint32_t PADS_PULL_MASK = 0x0c; + static constexpr uint32_t PADS_PULL_LSB = 2; + + enum class FunctionSelect : uint8_t { + Alt0 = 0, + Alt1 = 1, + Alt2 = 2, + Alt3 = 3, + Alt4 = 4, + Alt5 = 5, + Alt6 = 6, + Alt7 = 7, + Alt8 = 8, + Null = 31 + }; + + enum Mode { + Input, + Output, + Alt0, + Alt1, + Alt2, + Alt3, + Alt4, + Alt5, + Alt6, + Alt7, + Alt8, + Null + }; + + enum Bias { + Off, + PullDown, + PullUp + }; + + volatile uint32_t* _gpio; + int _system_memory_device; + uint32_t _gpio_output_port_status = 0; + + bool openMemoryDevice(); + void closeMemoryDevice(); + volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; + + uint32_t read_register(uint32_t offset) const; + void write_register(uint32_t offset, uint32_t value); + + Mode direction(uint8_t pin) const; + void set_direction(uint8_t pin, Mode mode); + void input_enable(uint8_t pin); + void input_disable(uint8_t pin); + void output_enable(uint8_t pin); + void output_disable(uint8_t pin); + + void set_mode(uint8_t pin, Mode mode); +}; + +} diff --git a/libraries/AP_HAL_Linux/GPIO_Sysfs.cpp b/libraries/AP_HAL_Linux/GPIO_Sysfs.cpp index eab54f49de9269..9e38e53ccfd82d 100644 --- a/libraries/AP_HAL_Linux/GPIO_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/GPIO_Sysfs.cpp @@ -36,8 +36,8 @@ union gpio_params { #define GPIO_PATH_MAX (sizeof(GPIO_BASE_PATH) + sizeof(gpio_params) - 1) DigitalSource_Sysfs::DigitalSource_Sysfs(unsigned pin, int value_fd) - : _pin(pin) - , _value_fd(value_fd) + : _value_fd(value_fd) + , _pin(pin) { } @@ -205,7 +205,7 @@ AP_HAL::DigitalSource* GPIO_Sysfs::channel(uint16_t vpin) /* Even if we couldn't open the fd, return a new DigitalSource and let * reads and writes fail later due to invalid. Otherwise we * could crash in undesired places */ - return new DigitalSource_Sysfs(pin, value_fd); + return NEW_NOTHROW DigitalSource_Sysfs(pin, value_fd); } bool GPIO_Sysfs::usb_connected(void) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index a0be63c44ab906..bd7dc4122d5def 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -165,7 +165,7 @@ static RCInput_PRU rcinDriver; CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET static RCInput_AioPRU rcinDriver; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE -static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol(NULL, "/dev/ttyO4")}; +static RCInput_Multi rcinDriver{2, NEW_NOTHROW RCInput_AioPRU, NEW_NOTHROW RCInput_RCProtocol(NULL, "/dev/ttyO4")}; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ @@ -180,7 +180,7 @@ static RCInput_ZYNQ rcinDriver; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP static RCInput_UDP rcinDriver; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO -static RCInput_Multi rcinDriver{2, new RCInput_RCProtocol("/dev/uart-sbus", "/dev/uart-sumd"), new RCInput_UDP()}; +static RCInput_Multi rcinDriver{2, NEW_NOTHROW RCInput_RCProtocol("/dev/uart-sbus", "/dev/uart-sumd"), NEW_NOTHROW RCInput_UDP()}; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO static RCInput_SoloLink rcinDriver; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \ diff --git a/libraries/AP_HAL_Linux/Heat_Pwm.cpp b/libraries/AP_HAL_Linux/Heat_Pwm.cpp index 75eafcb94927ef..91dddfd40c2e78 100644 --- a/libraries/AP_HAL_Linux/Heat_Pwm.cpp +++ b/libraries/AP_HAL_Linux/Heat_Pwm.cpp @@ -42,11 +42,11 @@ HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) : _period_ns(period_ns) { #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE - _pwm = new PWM_Sysfs(0, pwm_num); + _pwm = NEW_NOTHROW PWM_Sysfs(0, pwm_num); hal.gpio->pinMode(EDGE_GPIO_HEAT_ENABLE, HAL_GPIO_OUTPUT); hal.gpio->write(EDGE_GPIO_HEAT_ENABLE, 1); #else - _pwm = new PWM_Sysfs_Bebop(pwm_num); + _pwm = NEW_NOTHROW PWM_Sysfs_Bebop(pwm_num); #endif _pwm->init(); _pwm->set_period(_period_ns); diff --git a/libraries/AP_HAL_Linux/I2CDevice.cpp b/libraries/AP_HAL_Linux/I2CDevice.cpp index 17a9fd4fcdbe3a..0418e2fcc9881a 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.cpp +++ b/libraries/AP_HAL_Linux/I2CDevice.cpp @@ -280,67 +280,6 @@ I2CDeviceManager::I2CDeviceManager() _buses.reserve(4); } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(std::vector devpaths, uint8_t address) -{ - const char *dirname = "/sys/class/i2c-dev/"; - struct dirent *de = nullptr; - DIR *d; - - d = opendir(dirname); - if (!d) { - AP_HAL::panic("Could not get list of I2C buses"); - } - - for (de = readdir(d); de; de = readdir(d)) { - char *str_device, *abs_str_device; - const char *p; - - if (strcmp(de->d_name, ".") == 0 || strcmp(de->d_name, "..") == 0) { - continue; - } - - if (asprintf(&str_device, "%s/%s", dirname, de->d_name) < 0) { - continue; - } - - abs_str_device = realpath(str_device, nullptr); - if (!abs_str_device || !(p = startswith(abs_str_device, "/sys/devices/"))) { - free(abs_str_device); - free(str_device); - continue; - } - - auto t = std::find_if(std::begin(devpaths), std::end(devpaths), - [p](const char *prefix) { - return startswith(p, prefix) != nullptr; - }); - - free(abs_str_device); - free(str_device); - - if (t != std::end(devpaths)) { - unsigned int n; - - /* Found the bus, try to create the device now */ - if (sscanf(de->d_name, "i2c-%u", &n) != 1) { - AP_HAL::panic("I2CDevice: can't parse %s", de->d_name); - } - if (n > UINT8_MAX) { - AP_HAL::panic("I2CDevice: bus with number n=%u higher than %u", - n, UINT8_MAX); - } - - closedir(d); - return get_device(n, address); - } - } - - /* not found */ - closedir(d); - return nullptr; -} - AP_HAL::OwnPtr I2CDeviceManager::get_device(uint8_t bus, uint8_t address, uint32_t bus_clock, @@ -377,7 +316,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address, AP_HAL::OwnPtr I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const { - auto dev = AP_HAL::OwnPtr(new I2CDevice(b, address)); + auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(b, address)); if (!dev) { return nullptr; } diff --git a/libraries/AP_HAL_Linux/I2CDevice.h b/libraries/AP_HAL_Linux/I2CDevice.h index d26d5860e19b86..92c57c2534f00e 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.h +++ b/libraries/AP_HAL_Linux/I2CDevice.h @@ -94,9 +94,6 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager { I2CDeviceManager(); - AP_HAL::OwnPtr get_device( - std::vector devpaths, uint8_t address) override; - /* AP_HAL::I2CDeviceManager implementation */ AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, diff --git a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp index 9f597ace534133..2429449950bd42 100644 --- a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp +++ b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp @@ -55,7 +55,7 @@ void OpticalFlow_Onboard::init() return; } - _videoin = new VideoIn; + _videoin = NEW_NOTHROW VideoIn; const char* device_path = HAL_OPTFLOW_ONBOARD_VDEV_PATH; memtype = V4L2_MEMORY_MMAP; nbufs = HAL_OPTFLOW_ONBOARD_NBUFS; @@ -75,12 +75,12 @@ void OpticalFlow_Onboard::init() } #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP - _pwm = new PWM_Sysfs_Bebop(BEBOP_CAMV_PWM); + _pwm = NEW_NOTHROW PWM_Sysfs_Bebop(BEBOP_CAMV_PWM); _pwm->init(); _pwm->set_freq(BEBOP_CAMV_PWM_FREQ); _pwm->enable(true); - _camerasensor = new CameraSensor_Mt9v117(HAL_OPTFLOW_ONBOARD_SUBDEV_PATH, + _camerasensor = NEW_NOTHROW CameraSensor_Mt9v117(HAL_OPTFLOW_ONBOARD_SUBDEV_PATH, hal.i2c_mgr->get_device(0, 0x5D), MT9V117_QVGA, BEBOP_GPIO_CAMV_NRST, @@ -146,7 +146,7 @@ void OpticalFlow_Onboard::init() _videoin->prepare_capture(); /* Use px4 algorithm for optical flow */ - _flow = new Flow_PX4(_width, _bytesperline, + _flow = NEW_NOTHROW Flow_PX4(_width, _bytesperline, HAL_FLOW_PX4_MAX_FLOW_PIXEL, HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD, HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD); @@ -170,7 +170,7 @@ void OpticalFlow_Onboard::init() AP_HAL::panic("OpticalFlow_Onboard: failed to create thread"); } - _gyro_ring_buffer = new ObjectBuffer(OPTICAL_FLOW_GYRO_BUFFER_LEN); + _gyro_ring_buffer = NEW_NOTHROW ObjectBuffer(OPTICAL_FLOW_GYRO_BUFFER_LEN); if (_gyro_ring_buffer != nullptr && _gyro_ring_buffer->get_size() == 0) { // allocation failed delete _gyro_ring_buffer; diff --git a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp index 680f82ec51d09e..9c7997e2423756 100644 --- a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp @@ -33,12 +33,12 @@ namespace Linux { PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path, char* enable_path, char* duty_path, char* period_path, uint8_t channel) - : _export_path(export_path) + : _channel(channel) + , _export_path(export_path) , _polarity_path(polarity_path) , _enable_path(enable_path) , _duty_path(duty_path) , _period_path(period_path) - , _channel(channel) { } diff --git a/libraries/AP_HAL_Linux/PollerThread.cpp b/libraries/AP_HAL_Linux/PollerThread.cpp index ab46403465068c..9dcd3b0336a833 100644 --- a/libraries/AP_HAL_Linux/PollerThread.cpp +++ b/libraries/AP_HAL_Linux/PollerThread.cpp @@ -93,7 +93,7 @@ TimerPollable *PollerThread::add_timer(TimerPollable::PeriodicCb cb, if (!_poller) { return nullptr; } - TimerPollable *p = new TimerPollable(cb, wrapper); + TimerPollable *p = NEW_NOTHROW TimerPollable(cb, wrapper); if (!p || !p->setup_timer(timeout_usec) || !_poller.register_pollable(p, POLLIN)) { delete p; diff --git a/libraries/AP_HAL_Linux/RCInput.cpp b/libraries/AP_HAL_Linux/RCInput.cpp index b4e933d096450b..09bfd63c7de112 100644 --- a/libraries/AP_HAL_Linux/RCInput.cpp +++ b/libraries/AP_HAL_Linux/RCInput.cpp @@ -330,229 +330,3 @@ void RCInput::_update_periods(uint16_t *periods, uint8_t len) _num_channels = len; rc_input_count++; } - - -/* - add some bytes of input in DSM serial stream format, coping with partial packets - */ -bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes) -{ - if (nbytes == 0) { - return false; - } - const uint8_t dsm_frame_size = sizeof(dsm.frame); - bool ret = false; - - uint32_t now = AP_HAL::millis(); - if (now - dsm.last_input_ms > 5) { - // resync based on time - dsm.partial_frame_count = 0; - } - dsm.last_input_ms = now; - - while (nbytes > 0) { - size_t n = nbytes; - if (dsm.partial_frame_count + n > dsm_frame_size) { - n = dsm_frame_size - dsm.partial_frame_count; - } - if (n > 0) { - memcpy(&dsm.frame[dsm.partial_frame_count], bytes, n); - dsm.partial_frame_count += n; - nbytes -= n; - bytes += n; - } - - if (dsm.partial_frame_count == dsm_frame_size) { - dsm.partial_frame_count = 0; - uint16_t values[16] {}; - uint16_t num_values=0; - /* - we only accept input when nbytes==0 as dsm is highly - sensitive to framing, and extra bytes may be an - indication this is really SRXL - */ - if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) && - num_values >= MIN_NUM_CHANNELS && - nbytes == 0) { - for (uint8_t i=0; i _num_channels) { - _num_channels = num_values; - } - rc_input_count++; -#if 0 - printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n", - (unsigned)num_values, - values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7]); -#endif - ret = true; - } - } - } - return ret; -} - - -/* - add some bytes of input in SUMD serial stream format, coping with partial packets - */ -bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes) -{ - uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS]; - uint8_t rssi; - uint8_t rx_count; - uint16_t channel_count; - bool ret = false; - - while (nbytes > 0) { - if (sumd_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 0) { - if (st24_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 0) { - if (srxl_decode(now, *bytes++, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS, &failsafe_state) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 5) { - // resync based on time - sbus.partial_frame_count = 0; - } - sbus.last_input_ms = now; - - while (nbytes > 0) { - size_t n = nbytes; - if (sbus.partial_frame_count + n > sbus_frame_size) { - n = sbus_frame_size - sbus.partial_frame_count; - } - if (n > 0) { - memcpy(&sbus.frame[sbus.partial_frame_count], bytes, n); - sbus.partial_frame_count += n; - nbytes -= n; - bytes += n; - } - - if (sbus.partial_frame_count == sbus_frame_size) { - sbus.partial_frame_count = 0; - uint16_t values[16] {}; - uint16_t num_values=0; - bool sbus_failsafe; - if (AP_RCProtocol_SBUS::sbus_decode(sbus.frame, values, &num_values, sbus_failsafe, 16) && - num_values >= MIN_NUM_CHANNELS) { - for (uint8_t i=0; i _num_channels) { - _num_channels = num_values; - } - if (!sbus_failsafe) { - rc_input_count++; - } -#if 0 - printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n", - (unsigned)num_values, - values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7], - sbus_failsafe?"FAIL":"OK"); -#endif - } - } - } -} diff --git a/libraries/AP_HAL_Linux/RCInput.h b/libraries/AP_HAL_Linux/RCInput.h index a639cb4533b1bb..ef7022d50caf6c 100644 --- a/libraries/AP_HAL_Linux/RCInput.h +++ b/libraries/AP_HAL_Linux/RCInput.h @@ -33,21 +33,6 @@ class RCInput : public AP_HAL::RCInput { // specific implementations virtual void _timer_tick() {} - // add some DSM input bytes, for RCInput over a serial port - bool add_dsm_input(const uint8_t *bytes, size_t nbytes); - - // add some SBUS input bytes, for RCInput over a serial port - void add_sbus_input(const uint8_t *bytes, size_t nbytes); - - // add some SUMD input bytes, for RCInput over a serial port - bool add_sumd_input(const uint8_t *bytes, size_t nbytes); - - // add some st24 input bytes, for RCInput over a serial port - bool add_st24_input(const uint8_t *bytes, size_t nbytes); - - // add some srxl input bytes, for RCInput over a serial port - bool add_srxl_input(const uint8_t *bytes, size_t nbytes); - protected: void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1); void _update_periods(uint16_t *periods, uint8_t len); @@ -81,20 +66,6 @@ class RCInput : public AP_HAL::RCInput { uint16_t bit_ofs; } dsm_state; - // state of add_dsm_input - struct { - uint8_t frame[16]; - uint8_t partial_frame_count; - uint32_t last_input_ms; - } dsm; - - // state of add_sbus_input - struct { - uint8_t frame[25]; - uint8_t partial_frame_count; - uint32_t last_input_ms; - } sbus; - int16_t _rssi = -1; }; diff --git a/libraries/AP_HAL_Linux/RCInput_Multi.cpp b/libraries/AP_HAL_Linux/RCInput_Multi.cpp index 2ebcfc42a0140e..093f513c0b0c77 100644 --- a/libraries/AP_HAL_Linux/RCInput_Multi.cpp +++ b/libraries/AP_HAL_Linux/RCInput_Multi.cpp @@ -31,7 +31,7 @@ RCInput_Multi::RCInput_Multi(uint8_t _num_inputs, ...) : num_inputs(_num_inputs) { va_list ap; - inputs = new RCInput*[num_inputs]; + inputs = NEW_NOTHROW RCInput*[num_inputs]; if (inputs == nullptr) { AP_HAL::panic("failed to allocated RCInput array"); } diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.cpp b/libraries/AP_HAL_Linux/RCInput_RPI.cpp index c2d24f3c29c738..5201802ae70bc2 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RPI.cpp @@ -534,8 +534,8 @@ void RCInput_RPI::init() set_physical_addresses(); // Init memory for buffer and for DMA control blocks. // See comments in "init_ctrl_data()" to understand values "2" and "15" - circle_buffer = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 2, _version); - con_blocks = new Memory_table(RCIN_RPI_BUFFER_LENGTH * 15, _version); + circle_buffer = NEW_NOTHROW Memory_table(RCIN_RPI_BUFFER_LENGTH * 2, _version); + con_blocks = NEW_NOTHROW Memory_table(RCIN_RPI_BUFFER_LENGTH * 15, _version); init_registers(); diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.h b/libraries/AP_HAL_Linux/RCInput_RPI.h index 8d398eec5f2513..84ca95295be068 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.h +++ b/libraries/AP_HAL_Linux/RCInput_RPI.h @@ -116,7 +116,8 @@ class RCInput_RPI : public RCInput prev_tick(0), delta_time(0), width_s0(0), width_s1(0), curr_signal(0), last_signal(0), - enable_pin(0), state(RCIN_RPI_INITIAL_STATE) + state(RCIN_RPI_INITIAL_STATE), + enable_pin(0) {} uint64_t prev_tick; diff --git a/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp b/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp index 1f61cf73259d51..fed355bab1f0eb 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp @@ -94,8 +94,8 @@ using namespace Linux; extern const AP_HAL::HAL& hal; RCOutput_AeroIO::RCOutput_AeroIO() - : _freq_buffer(new uint16_t[PWM_CHAN_COUNT]) - , _duty_buffer(new uint16_t[PWM_CHAN_COUNT]) + : _freq_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT]) + , _duty_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT]) { } diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index d6c1fed519c3f4..3b8a4877b31fb4 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -62,10 +62,10 @@ RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr dev, uint32_t external_clock, uint8_t channel_offset, int16_t oe_pin_number) : - _dev(std::move(dev)), _enable_pin(nullptr), + _dev(std::move(dev)), _frequency(50), - _pulses_buffer(new uint16_t[PWM_CHAN_COUNT - channel_offset]), + _pulses_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT - channel_offset]), _external_clock(external_clock), _channel_offset(channel_offset), _oe_pin_number(oe_pin_number) diff --git a/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp b/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp index 5ffbf9ed224dbd..5f43e76294489f 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp @@ -25,8 +25,8 @@ RCOutput_Sysfs::RCOutput_Sysfs(uint8_t chip, uint8_t channel_base, uint8_t chann : _chip(chip) , _channel_base(channel_base) , _channel_count(channel_count) - , _pwm_channels(new PWM_Sysfs_Base *[_channel_count]) - , _pending(new uint16_t[_channel_count]) + , _pwm_channels(NEW_NOTHROW PWM_Sysfs_Base *[_channel_count]) + , _pending(NEW_NOTHROW uint16_t[_channel_count]) { } @@ -43,11 +43,11 @@ void RCOutput_Sysfs::init() { for (uint8_t i = 0; i < _channel_count; i++) { #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO - _pwm_channels[i] = new PWM_Sysfs_Bebop(_channel_base+i); + _pwm_channels[i] = NEW_NOTHROW PWM_Sysfs_Bebop(_channel_base+i); #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ - _pwm_channels[i] = new PWM_Sysfs(_chip+i, 0); + _pwm_channels[i] = NEW_NOTHROW PWM_Sysfs(_chip+i, 0); #else - _pwm_channels[i] = new PWM_Sysfs(_chip, _channel_base+i); + _pwm_channels[i] = NEW_NOTHROW PWM_Sysfs(_chip, _channel_base+i); #endif if (!_pwm_channels[i]) { AP_HAL::panic("RCOutput_Sysfs_PWM: Unable to setup PWM pin."); diff --git a/libraries/AP_HAL_Linux/SPIDevice.cpp b/libraries/AP_HAL_Linux/SPIDevice.cpp index a23ab1ca7d174f..1f66cc723197a6 100644 --- a/libraries/AP_HAL_Linux/SPIDevice.cpp +++ b/libraries/AP_HAL_Linux/SPIDevice.cpp @@ -503,7 +503,7 @@ SPIDeviceManager::_create_device(SPIBus &b, SPIDesc &desc) const // Ensure bus is open b.open(desc.subdev); - auto dev = AP_HAL::OwnPtr(new SPIDevice(b, desc)); + auto dev = AP_HAL::OwnPtr(NEW_NOTHROW SPIDevice(b, desc)); if (!dev) { return nullptr; } diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp index e6a266b564135b..e88b388b342b2f 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp @@ -54,7 +54,7 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) if (_buffer == nullptr) { /* Do not allocate new buffer, if we're just changing speed */ - _buffer = new uint8_t[rxS]; + _buffer = NEW_NOTHROW uint8_t[rxS]; if (_buffer == nullptr) { hal.console->printf("Not enough memory\n"); AP_HAL::panic("Not enough memory\n"); @@ -69,14 +69,17 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) * it's sage to update speed */ _dev->set_speed(AP_HAL::Device::SPEED_HIGH); + high_speed_set = true; debug("Set higher SPI-frequency"); } else { _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); } break; default: _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b); break; diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.h b/libraries/AP_HAL_Linux/SPIUARTDriver.h index 05be43b9ecce0c..07e451d243bc48 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.h +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.h @@ -11,6 +11,9 @@ class SPIUARTDriver : public UARTDriver { SPIUARTDriver(); void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; void _timer_tick(void) override; + uint32_t get_baud_rate() const override { + return high_speed_set ? 4000000U : 1000000U; + } protected: int _write_fd(const uint8_t *buf, uint16_t n) override; @@ -23,6 +26,8 @@ class SPIUARTDriver : public UARTDriver { uint32_t _last_update_timestamp; bool _external; + + bool high_speed_set; }; } diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 98e3914332274a..8e35ba97b4c77f 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -408,7 +408,7 @@ uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority */ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) { - Thread *thread = new Thread{(Thread::task_t)proc}; + Thread *thread = NEW_NOTHROW Thread{(Thread::task_t)proc}; if (!thread) { return false; } diff --git a/libraries/AP_HAL_Linux/Storage.cpp b/libraries/AP_HAL_Linux/Storage.cpp index 4fc401c76405b3..377a42867bd956 100644 --- a/libraries/AP_HAL_Linux/Storage.cpp +++ b/libraries/AP_HAL_Linux/Storage.cpp @@ -9,7 +9,6 @@ #include #include -#include using namespace Linux; @@ -102,11 +101,8 @@ int Storage::_storage_create(const char *dpath) return -1; } - unlinkat(dfd, dpath, 0); int fd = openat(dfd, STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666); - close(dfd); - if (fd == -1) { fprintf(stderr, "Failed to create storage file %s/%s\n", dpath, STORAGE_FILE); @@ -117,6 +113,7 @@ int Storage::_storage_create(const char *dpath) if (ftruncate(fd, sizeof(_buffer)) == -1) { fprintf(stderr, "Failed to set file size to %u kB (%m)\n", unsigned(sizeof(_buffer) / 1024)); + close(fd); goto fail; } @@ -148,26 +145,16 @@ void Storage::init() dpath = HAL_BOARD_STORAGE_DIRECTORY; } - int fd = open(dpath, O_RDWR|O_CLOEXEC); + int fd = _storage_create(dpath); if (fd == -1) { - fd = _storage_create(dpath); - if (fd == -1) { - AP_HAL::panic("Cannot create storage %s (%m)", dpath); - } + AP_HAL::panic("Cannot create storage %s (%m)", dpath); } ssize_t ret = read(fd, _buffer, sizeof(_buffer)); if (ret != sizeof(_buffer)) { close(fd); - _storage_create(dpath); - fd = open(dpath, O_RDONLY|O_CLOEXEC); - if (fd == -1) { - AP_HAL::panic("Failed to open %s (%m)", dpath); - } - if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) { - AP_HAL::panic("Failed to read %s (%m)", dpath); - } + AP_HAL::panic("Failed to read %s (%m)", dpath); } _fd = fd; diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index fb0be43ceec478..0ccedaa4786b90 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -23,7 +23,6 @@ #include "TCPServerDevice.h" #include "UARTDevice.h" #include "UDPDevice.h" - #include #if HAL_GCS_ENABLED #include @@ -53,7 +52,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) { if (!_initialised) { if (device_path == nullptr && _console) { - _device = new ConsoleDevice(); + _device = NEW_NOTHROW ConsoleDevice(); } else { if (device_path == nullptr) { return; @@ -64,7 +63,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) if (!_device.get()) { ::fprintf(stderr, "Argument is not valid. Fallback to console.\n" "Launch with --help to see an example.\n"); - _device = new ConsoleDevice(); + _device = NEW_NOTHROW ConsoleDevice(); } } } @@ -133,7 +132,7 @@ AP_HAL::OwnPtr UARTDriver::_parseDevicePath(const char *arg) struct stat st; if (stat(arg, &st) == 0 && S_ISCHR(st.st_mode)) { - return AP_HAL::OwnPtr(new UARTDevice(arg)); + return AP_HAL::OwnPtr(NEW_NOTHROW UARTDevice(arg)); } else if (strncmp(arg, "tcp:", 4) != 0 && strncmp(arg, "udp:", 4) != 0 && strncmp(arg, "udpin:", 6)) { @@ -185,17 +184,17 @@ AP_HAL::OwnPtr UARTDriver::_parseDevicePath(const char *arg) _packetise = true; #endif if (strcmp(protocol, "udp") == 0) { - device = new UDPDevice(_ip, _base_port, bcast, false); + device = NEW_NOTHROW UDPDevice(_ip, _base_port, bcast, false); } else { if (bcast) { AP_HAL::panic("Can't combine udpin with bcast"); } - device = new UDPDevice(_ip, _base_port, false, true); + device = NEW_NOTHROW UDPDevice(_ip, _base_port, false, true); } } else { bool wait = (_flag && strcmp(_flag, "wait") == 0); - device = new TCPServerDevice(_ip, _base_port, wait); + device = NEW_NOTHROW TCPServerDevice(_ip, _base_port, wait); } free(devstr); @@ -417,6 +416,7 @@ void UARTDriver::_timer_tick(void) } void UARTDriver::configure_parity(uint8_t v) { + UARTDriver::parity = v; _device->set_parity(v); } diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index ec47114cc6ee3d..02a1afba7b88e9 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -56,7 +56,7 @@ class UARTDriver : public AP_HAL::UARTDriver { uint32_t bw_in_bytes_per_second() const override; - uint32_t get_baud_rate() const override { return _baudrate; } + virtual uint32_t get_baud_rate() const override { return _baudrate; } private: AP_HAL::OwnPtr _device; diff --git a/libraries/AP_HAL_Linux/Util.cpp b/libraries/AP_HAL_Linux/Util.cpp index dc9d8083a17b16..0a03fe4c81ac40 100644 --- a/libraries/AP_HAL_Linux/Util.cpp +++ b/libraries/AP_HAL_Linux/Util.cpp @@ -10,7 +10,6 @@ #include #include "Heat_Pwm.h" -#include "ToneAlarm_Disco.h" #include "Util.h" using namespace Linux; @@ -29,7 +28,7 @@ void Util::init(int argc, char * const *argv) { #ifdef HAL_UTILS_HEAT #if HAL_UTILS_HEAT == HAL_LINUX_HEAT_PWM - _heat = new Linux::HeatPwm(HAL_LINUX_HEAT_PWM_NUM, + _heat = NEW_NOTHROW Linux::HeatPwm(HAL_LINUX_HEAT_PWM_NUM, HAL_LINUX_HEAT_KP, HAL_LINUX_HEAT_KI, HAL_LINUX_HEAT_PERIOD_NS); @@ -37,7 +36,7 @@ void Util::init(int argc, char * const *argv) { #error Unrecognized Heat #endif // #if #else - _heat = new Linux::Heat(); + _heat = NEW_NOTHROW Linux::Heat(); #endif // #ifdef } @@ -242,65 +241,6 @@ int Util::get_hw_arm32() return -ENOENT; } -#ifdef ENABLE_HEAP -void *Util::allocate_heap_memory(size_t size) -{ - struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap)); - if (new_heap != nullptr) { - new_heap->max_heap_size = size; - new_heap->current_heap_usage = 0; - } - return (void *)new_heap; -} - -void *Util::heap_realloc(void *h, void *ptr, size_t old_size, size_t new_size) -{ - if (h == nullptr) { - return nullptr; - } - - struct heap *heapp = (struct heap*)h; - - // extract appropriate headers. We use the old_size from the - // header not from the caller. We use SITL to catch cases they - // don't match (which would be a lua bug) - old_size = 0; - heap_allocation_header *old_header = nullptr; - if (ptr != nullptr) { - old_header = ((heap_allocation_header *)ptr) - 1; - old_size = old_header->allocation_size; - } - - if ((heapp->current_heap_usage + new_size - old_size) > heapp->max_heap_size) { - // fail the allocation as we don't have the memory. Note that we don't simulate fragmentation - return nullptr; - } - - heapp->current_heap_usage -= old_size; - if (new_size == 0) { - free(old_header); - return nullptr; - } - - heap_allocation_header *new_header = (heap_allocation_header *)malloc(new_size + sizeof(heap_allocation_header)); - if (new_header == nullptr) { - // total failure to allocate, this is very surprising in SITL - return nullptr; - } - heapp->current_heap_usage += new_size; - new_header->allocation_size = new_size; - void *new_mem = new_header + 1; - - if (ptr == nullptr) { - return new_mem; - } - memcpy(new_mem, ptr, old_size > new_size ? new_size : old_size); - free(old_header); - return new_mem; -} - -#endif // ENABLE_HEAP - /** * This method will read random values with set size. */ diff --git a/libraries/AP_HAL_Linux/Util.h b/libraries/AP_HAL_Linux/Util.h index 9aa0a823146780..5374b1d95df128 100644 --- a/libraries/AP_HAL_Linux/Util.h +++ b/libraries/AP_HAL_Linux/Util.h @@ -29,7 +29,6 @@ class Util : public AP_HAL::Util { } void init(int argc, char *const *argv); - bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; } /** return commandline arguments, if available @@ -72,12 +71,6 @@ class Util : public AP_HAL::Util { bool get_system_id(char buf[50]) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; -#ifdef ENABLE_HEAP - // heap functions, note that a heap once alloc'd cannot be dealloc'd - virtual void *allocate_heap_memory(size_t size) override; - virtual void *heap_realloc(void *h, void *ptr, size_t old_size, size_t new_size) override; -#endif // ENABLE_HEAP - /* * Write a string as specified by @fmt to the file in @path. Note this * should not be used on hot path since it will open, write and close the @@ -116,18 +109,6 @@ class Util : public AP_HAL::Util { const char *custom_storage_directory = nullptr; const char *custom_defaults = HAL_PARAM_DEFAULTS_PATH; static const char *_hw_names[UTIL_NUM_HARDWARES]; - -#ifdef ENABLE_HEAP - struct heap_allocation_header { - size_t allocation_size; // size of allocated block, not including this header - }; - - struct heap { - size_t max_heap_size; - size_t current_heap_usage; - }; -#endif // ENABLE_HEAP - }; } diff --git a/libraries/AP_HAL_Linux/Util_RPI.cpp b/libraries/AP_HAL_Linux/Util_RPI.cpp index 9f464374d7c191..f39606675e77f7 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.cpp +++ b/libraries/AP_HAL_Linux/Util_RPI.cpp @@ -62,25 +62,29 @@ void UtilRPI::_get_board_type_using_peripheral_base() _linux_board_version = LINUX_BOARD_TYPE::UNKNOWN_BOARD; printf("Cannot detect board-type \r\n"); break; + case 0x10: + _linux_board_version = LINUX_BOARD_TYPE::RPI_5; + printf("RPI 5 \r\n"); + break; case 0x20000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_ZERO_1; printf("RPI Zero / 1 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0x3f000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_2_3_ZERO2; printf("RPI 2, 3 or Zero-2 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0xfe000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_4; printf("RPI 4 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0x40000000: _linux_board_version = LINUX_BOARD_TYPE::ALLWINNWER_H616; printf("AllWinner-H616 \r\n"); break; + default: + printf("Unknown board \n\r"); + printf("Peripheral base address is %x\n", base); } return ; diff --git a/libraries/AP_HAL_Linux/Util_RPI.h b/libraries/AP_HAL_Linux/Util_RPI.h index 67a6fc8ead44fe..4aa3427dca88fc 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.h +++ b/libraries/AP_HAL_Linux/Util_RPI.h @@ -8,6 +8,7 @@ enum class LINUX_BOARD_TYPE: int { RPI_ZERO_1=0, RPI_2_3_ZERO2=1, RPI_4=2, + RPI_5=3, ALLWINNWER_H616=100, UNKNOWN_BOARD=999 }; diff --git a/libraries/AP_HAL_Linux/VideoIn.h b/libraries/AP_HAL_Linux/VideoIn.h index ed4fd90180ac78..2f2652f3f1daaf 100644 --- a/libraries/AP_HAL_Linux/VideoIn.h +++ b/libraries/AP_HAL_Linux/VideoIn.h @@ -15,6 +15,7 @@ #pragma once #include "AP_HAL_Linux.h" +#include #include #include diff --git a/libraries/AP_HAL_QURT/AP_HAL_QURT.h b/libraries/AP_HAL_QURT/AP_HAL_QURT.h new file mode 100644 index 00000000000000..2c753c203d9736 --- /dev/null +++ b/libraries/AP_HAL_QURT/AP_HAL_QURT.h @@ -0,0 +1,25 @@ +/* + 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 + +/* Your layer exports should depend on AP_HAL.h ONLY. */ +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_QURT + +#include "HAL_QURT_Class.h" +#include "AP_HAL_QURT_Main.h" + +#endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_QURT/AP_HAL_QURT_Main.h b/libraries/AP_HAL_QURT/AP_HAL_QURT_Main.h new file mode 100644 index 00000000000000..5bb282c3f06106 --- /dev/null +++ b/libraries/AP_HAL_QURT/AP_HAL_QURT_Main.h @@ -0,0 +1,18 @@ +/* + 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 + +#define AP_MAIN qurt_ardupilot_main + diff --git a/libraries/AP_HAL_QURT/AP_HAL_QURT_Namespace.h b/libraries/AP_HAL_QURT/AP_HAL_QURT_Namespace.h new file mode 100644 index 00000000000000..6ddfdb71420231 --- /dev/null +++ b/libraries/AP_HAL_QURT/AP_HAL_QURT_Namespace.h @@ -0,0 +1,35 @@ +/* + 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 + +namespace QURT +{ +class UARTDriver; +class UARTDriver_Console; +class UARTDriver_MAVLinkUDP; +class UARTDriver_Local; +class UDPDriver; +class Util; +class Scheduler; +class Storage; +class Util; +class Semaphore; +class RCInput; +class RCOutput; +class AnalogSource; +class AnalogIn; +} + diff --git a/libraries/AP_HAL_QURT/AP_HAL_QURT_Private.h b/libraries/AP_HAL_QURT/AP_HAL_QURT_Private.h new file mode 100644 index 00000000000000..95a6b970037a2f --- /dev/null +++ b/libraries/AP_HAL_QURT/AP_HAL_QURT_Private.h @@ -0,0 +1,22 @@ +/* + 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 + +/* Umbrella header for all private headers of the AP_HAL_QURT module. + * Only import this header from inside AP_HAL_QURT + */ + +#include "UARTDriver.h" +#include "Util.h" diff --git a/libraries/AP_HAL_QURT/AnalogIn.cpp b/libraries/AP_HAL_QURT/AnalogIn.cpp new file mode 100644 index 00000000000000..88e051a52d760f --- /dev/null +++ b/libraries/AP_HAL_QURT/AnalogIn.cpp @@ -0,0 +1,80 @@ +#include "AnalogIn.h" +#include "RCOutput.h" + +using namespace QURT; + +#define ANALOG_PIN_VOLTAGE 1 +#define ANALOG_PIN_CURRENT 2 + +#define NUM_CHANNELS 10 + +extern const AP_HAL::HAL &hal; + +// static table of voltage sources +static AnalogSource sources[NUM_CHANNELS]; + +AnalogIn::AnalogIn() +{ +} + +float AnalogSource::read_average() +{ + return read_latest(); +} + +float AnalogSource::voltage_average() +{ + return read_latest(); +} + +float AnalogSource::voltage_latest() +{ + return read_latest(); +} + +float AnalogSource::read_latest() +{ + const auto *rcout = (QURT::RCOutput *)hal.rcout; + switch (pin) { + case ANALOG_PIN_VOLTAGE: + return rcout->get_voltage(); + case ANALOG_PIN_CURRENT: + return rcout->get_current(); + default: + break; + } + return 0; +} + +bool AnalogSource::set_pin(uint8_t p) +{ + switch (p) { + case ANALOG_PIN_VOLTAGE: + case ANALOG_PIN_CURRENT: + pin = p; + return true; + default: + break; + } + return false; +} + +void AnalogIn::init() +{ +} + +AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) +{ + if (next_chan >= ARRAY_SIZE(sources)) { + return nullptr; + } + return &sources[next_chan++]; +} + +/* + not available, report 5v to keep GCS happy + */ +float AnalogIn::board_voltage(void) +{ + return 5.0f; +} diff --git a/libraries/AP_HAL_QURT/AnalogIn.h b/libraries/AP_HAL_QURT/AnalogIn.h new file mode 100644 index 00000000000000..cecd6fb7352a8f --- /dev/null +++ b/libraries/AP_HAL_QURT/AnalogIn.h @@ -0,0 +1,29 @@ +#pragma once + +#include "AP_HAL_QURT.h" + +class QURT::AnalogSource : public AP_HAL::AnalogSource +{ +public: + float read_average() override; + float read_latest() override; + bool set_pin(uint8_t p) override; + float voltage_average() override; + float voltage_latest() override; + float voltage_average_ratiometric() override + { + return voltage_average(); + } + uint8_t pin; +}; + +class QURT::AnalogIn : public AP_HAL::AnalogIn +{ +public: + AnalogIn(); + void init() override; + AP_HAL::AnalogSource* channel(int16_t n) override; + float board_voltage(void) override; +private: + uint8_t next_chan; +}; diff --git a/libraries/AP_HAL_QURT/DeviceBus.cpp b/libraries/AP_HAL_QURT/DeviceBus.cpp new file mode 100644 index 00000000000000..1e90978b3231d6 --- /dev/null +++ b/libraries/AP_HAL_QURT/DeviceBus.cpp @@ -0,0 +1,134 @@ +/* + * 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 . + */ + +#include "DeviceBus.h" + +#include +#include +#include + +#include "Scheduler.h" +#include "Semaphores.h" + +using namespace QURT; + +extern const AP_HAL::HAL& hal; + +DeviceBus::DeviceBus(AP_HAL::Scheduler::priority_base _thread_priority) : + semaphore(), + thread_priority(_thread_priority) +{ +} + +/* + per-bus callback thread +*/ +void DeviceBus::bus_thread(void) +{ + while (true) { + uint64_t now = AP_HAL::micros64(); + DeviceBus::callback_info *callback; + + // find a callback to run + for (callback = callbacks; callback; callback = callback->next) { + if (now >= callback->next_usec) { + while (now >= callback->next_usec) { + callback->next_usec += callback->period_usec; + } + // call it with semaphore held + WITH_SEMAPHORE(semaphore); + callback->cb(); + } + } + + // work out when next loop is needed + uint64_t next_needed = 0; + now = AP_HAL::micros64(); + + for (callback = callbacks; callback; callback = callback->next) { + if (next_needed == 0 || + callback->next_usec < next_needed) { + next_needed = callback->next_usec; + if (next_needed < now) { + next_needed = now; + } + } + } + + // delay for at most 50ms, to handle newly added callbacks + uint32_t delay = 50000; + if (next_needed >= now && next_needed - now < delay) { + delay = next_needed - now; + } + // don't delay for less than 100usec, so one thread doesn't + // completely dominate the CPU + if (delay < 100) { + delay = 100; + } + hal.scheduler->delay_microseconds(delay); + } + return; +} + +AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb, AP_HAL::Device *_hal_device) +{ + if (!thread_started) { + thread_started = true; + hal_device = _hal_device; + // setup a name for the thread + char name[30]; + switch (hal_device->bus_type()) { + case AP_HAL::Device::BUS_TYPE_I2C: + snprintf(name, sizeof(name), "APM_I2C:%u", + hal_device->bus_num()); + break; + + case AP_HAL::Device::BUS_TYPE_SPI: + snprintf(name, sizeof(name), "APM_SPI:%u", + hal_device->bus_num()); + break; + default: + break; + } +#ifdef BUSDEBUG + printf("%s:%d Thread Start\n", __PRETTY_FUNCTION__, __LINE__); +#endif + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&DeviceBus::bus_thread, void), + name, HAL_QURT_DEVICE_STACK_SIZE, thread_priority, 0); + } + DeviceBus::callback_info *callback = new DeviceBus::callback_info; + if (callback == nullptr) { + return nullptr; + } + callback->cb = cb; + callback->period_usec = period_usec; + callback->next_usec = AP_HAL::micros64() + period_usec; + + // add to linked list of callbacks on thread + callback->next = callbacks; + callbacks = callback; + + return callback; +} + +/* + * Adjust the timer for the next call: it needs to be called from the bus + * thread, otherwise it will race with it + */ +bool DeviceBus::adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) +{ + // TODO: add timer adjustment + return true; +} diff --git a/libraries/AP_HAL_QURT/DeviceBus.h b/libraries/AP_HAL_QURT/DeviceBus.h new file mode 100644 index 00000000000000..d62db9ccf2ded8 --- /dev/null +++ b/libraries/AP_HAL_QURT/DeviceBus.h @@ -0,0 +1,55 @@ +/* + * 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 +#include "Semaphores.h" +#include "AP_HAL_QURT.h" +#include "Scheduler.h" + +#define HAL_QURT_DEVICE_STACK_SIZE 8192 + +namespace QURT +{ + +class DeviceBus +{ +public: + DeviceBus(AP_HAL::Scheduler::priority_base _thread_priority); + + struct DeviceBus *next; + HAL_Semaphore semaphore; + + AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device); + bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec); + void bus_thread(void); + +private: + struct callback_info { + struct callback_info *next; + AP_HAL::Device::PeriodicCb cb; + uint32_t period_usec; + uint64_t next_usec; + } *callbacks; + AP_HAL::Scheduler::priority_base thread_priority; + bool thread_started; + AP_HAL::Device *hal_device; +}; + +} + + diff --git a/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp b/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp new file mode 100644 index 00000000000000..0200b9d27d3620 --- /dev/null +++ b/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp @@ -0,0 +1,153 @@ +/* + 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 "HAL_QURT_Class.h" +#include "AP_HAL_QURT_Private.h" +#include "Scheduler.h" +#include "Storage.h" +#include "Semaphores.h" +#include "RCInput.h" +#include "RCOutput.h" +#include "AnalogIn.h" +#include "I2CDevice.h" +#include "SPIDevice.h" +#include +#include +#include +#include +#include "interface.h" +#include "ap_host/src/protocol.h" + + +extern "C" { + typedef void (*external_error_handler_t)(void); +}; + +static void crash_error_handler(void) +{ + HAP_PRINTF("CRASH_ERROR_HANDLER: at %p", &crash_error_handler); +} + +using namespace QURT; + +static UARTDriver_Console consoleDriver; +static UARTDriver_MAVLinkUDP serial0Driver(0); +static UARTDriver_MAVLinkUDP serial1Driver(1); +static UARTDriver_Local serial3Driver(QURT_UART_GPS); +static UARTDriver_Local serial4Driver(QURT_UART_RCIN); + +static SPIDeviceManager spiDeviceManager; +static AnalogIn analogIn; +static Storage storageDriver; +static Empty::GPIO gpioDriver; +static RCInput rcinDriver; +static RCOutput rcoutDriver; +static Util utilInstance; +static Scheduler schedulerInstance; +static I2CDeviceManager i2c_mgr_instance; + +bool qurt_ran_overtime; + +HAL_QURT::HAL_QURT() : + AP_HAL::HAL( + &serial0Driver, + &serial1Driver, + nullptr, + &serial3Driver, + &serial4Driver, + nullptr, + nullptr, + nullptr, + nullptr, + nullptr, + &i2c_mgr_instance, + &spiDeviceManager, + nullptr, + &analogIn, + &storageDriver, + &consoleDriver, + &gpioDriver, + &rcinDriver, + &rcoutDriver, + &schedulerInstance, + &utilInstance, + nullptr, + nullptr, + nullptr) +{ +} + +static HAL_QURT::Callbacks *_callbacks; + +void HAL_QURT::main_thread(void) +{ + sl_client_register_fatal_error_cb(crash_error_handler); + + // Let SLPI image send out it's initialization response before we + // try to send anything out. + qurt_timer_sleep(1000000); + + rcinDriver.init(); + analogIn.init(); + rcoutDriver.init(); + _callbacks->setup(); + scheduler->set_system_initialized(); + + HAP_PRINTF("starting loop"); + + for (;;) { + // ensure other threads get some time + qurt_timer_sleep(200); + + // call main loop + _callbacks->loop(); + } +} + +void HAL_QURT::start_main_thread(Callbacks* callbacks) +{ + _callbacks = callbacks; + scheduler->thread_create(FUNCTOR_BIND_MEMBER(&HAL_QURT::main_thread, void), "main_thread", + (20 * 1024), + AP_HAL::Scheduler::PRIORITY_MAIN, + 0); +} + +void HAL_QURT::run(int argc, char* const argv[], Callbacks* callbacks) const +{ + assert(callbacks); + + /* initialize all drivers and private members here. + * up to the programmer to do this in the correct order. + * Scheduler should likely come first. */ + scheduler->init(); + schedulerInstance.hal_initialized(); + serial0Driver.begin(115200); + + HAP_PRINTF("Creating main thread"); + + const_cast(this)->start_main_thread(callbacks); +} + +const AP_HAL::HAL& AP_HAL::get_HAL() +{ + static const HAL_QURT *hal; + if (hal == nullptr) { + hal = new HAL_QURT; + } + return *hal; +} diff --git a/libraries/AP_HAL_QURT/HAL_QURT_Class.h b/libraries/AP_HAL_QURT/HAL_QURT_Class.h new file mode 100644 index 00000000000000..9c23f889af2a97 --- /dev/null +++ b/libraries/AP_HAL_QURT/HAL_QURT_Class.h @@ -0,0 +1,29 @@ +/* + 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 "AP_HAL_QURT_Namespace.h" +#include "interface.h" + +class HAL_QURT : public AP_HAL::HAL +{ +public: + HAL_QURT(); + void run(int argc, char* const* argv, Callbacks* callbacks) const override; + void start_main_thread(Callbacks* callbacks); + void main_thread(void); +}; diff --git a/libraries/AP_HAL_QURT/I2CDevice.cpp b/libraries/AP_HAL_QURT/I2CDevice.cpp new file mode 100644 index 00000000000000..0d5317f3f27ca6 --- /dev/null +++ b/libraries/AP_HAL_QURT/I2CDevice.cpp @@ -0,0 +1,136 @@ +/* + * 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 . + */ +#include "I2CDevice.h" + +#include +#include +#include +#include "Scheduler.h" +#include "interface.h" + +using namespace QURT; + +/* + 4 I2C buses + + bus1: mag + bus2: power manager + bus5: barometer (internal)* + bus4: external spare bus (unused) +*/ +static uint8_t i2c_bus_ids[] = { 1, 2, 5 }; + +static uint32_t i2c_internal_mask = (1U<<3); + +I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(i2c_bus_ids)]; + +I2CDeviceManager::I2CDeviceManager(void) +{ +} + +I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) : + bus(I2CDeviceManager::businfo[busnum]), + _address(address) +{ + if (busnum >= ARRAY_SIZE(i2c_bus_ids)) { + bus.fd = -1; + HAP_PRINTF("Invalid I2C bus %u", unsigned(busnum)); + return; + } + HAP_PRINTF("Constructing I2CDevice %u 0x%02x %u", unsigned(busnum), unsigned(address), unsigned(bus_clock)); + + if (bus.fd == -2) { + bus.fd = sl_client_config_i2c_bus(i2c_bus_ids[busnum], address, bus_clock/1000); + } + set_device_bus(busnum); + set_device_address(address); + asprintf(&pname, "I2C:%u:%02x", + (unsigned)busnum, (unsigned)address); +} + +I2CDevice::~I2CDevice() +{ + free(pname); +} + +bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, + uint8_t *recv, uint32_t recv_len) +{ + if (bus.fd < 0) { + return false; + } + if (!bus.semaphore.check_owner()) { + return false; + } + if (bus.last_address != _address) { + sl_client_set_address_i2c_bus(bus.fd, _address); + bus.last_address = _address; + } + return sl_client_i2c_transfer(bus.fd, send, send_len, recv, recv_len) == 0; +} + +/* + register a periodic callback +*/ +AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) +{ + return bus.register_periodic_callback(period_usec, cb, this); +} + + +/* + adjust a periodic callback +*/ +bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) +{ + return bus.adjust_timer(h, period_usec); +} + +AP_HAL::OwnPtr +I2CDeviceManager::get_device(uint8_t bus, uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) +{ + if (bus >= ARRAY_SIZE(i2c_bus_ids)) { + return AP_HAL::OwnPtr(nullptr); + } + auto dev = AP_HAL::OwnPtr(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); + return dev; +} + +/* + get mask of bus numbers for all configured I2C buses +*/ +uint32_t I2CDeviceManager::get_bus_mask(void) const +{ + return ((1U << ARRAY_SIZE(i2c_bus_ids)) - 1); +} + +/* + get mask of bus numbers for all configured internal I2C buses +*/ +uint32_t I2CDeviceManager::get_bus_mask_internal(void) const +{ + return i2c_internal_mask; +} + +/* + get mask of bus numbers for all configured external I2C buses +*/ +uint32_t I2CDeviceManager::get_bus_mask_external(void) const +{ + return get_bus_mask() & ~get_bus_mask_internal(); +} diff --git a/libraries/AP_HAL_QURT/I2CDevice.h b/libraries/AP_HAL_QURT/I2CDevice.h new file mode 100644 index 00000000000000..4e1c44e8f0130c --- /dev/null +++ b/libraries/AP_HAL_QURT/I2CDevice.h @@ -0,0 +1,134 @@ +/* + * 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 +#include +#include + +#include "Semaphores.h" +#include "Scheduler.h" +#include "DeviceBus.h" + +namespace QURT +{ + +class I2CBus : public DeviceBus +{ +public: + I2CBus():DeviceBus(AP_HAL::Scheduler::PRIORITY_I2C) {}; + uint32_t bus_clock; + int fd = -2; + uint8_t last_address; +}; + +class I2CDevice : public AP_HAL::I2CDevice +{ +public: + static I2CDevice *from(AP_HAL::I2CDevice *dev) + { + return static_cast(dev); + } + + I2CDevice(uint8_t bus, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms); + ~I2CDevice(); + + /* See AP_HAL::I2CDevice::set_address() */ + void set_address(uint8_t address) override + { + _address = address; + } + + /* See AP_HAL::I2CDevice::set_retries() */ + void set_retries(uint8_t retries) override + { + _retries = retries; + } + + /* See AP_HAL::Device::set_speed(): Empty implementation, not supported. */ + bool set_speed(enum Device::Speed speed) override + { + return true; + } + + /* See AP_HAL::Device::transfer() */ + bool transfer(const uint8_t *send, uint32_t send_len, + uint8_t *recv, uint32_t recv_len) override; + + bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, + uint32_t recv_len, uint8_t times) override + { + return false; + }; + + /* See AP_HAL::Device::register_periodic_callback() */ + AP_HAL::Device::PeriodicHandle register_periodic_callback( + uint32_t period_usec, AP_HAL::Device::PeriodicCb) override; + + /* See AP_HAL::Device::adjust_periodic_callback() */ + bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override; + + AP_HAL::Semaphore* get_semaphore() override //TODO check all + { + // if asking for invalid bus number use bus 0 semaphore + return &bus.semaphore; + } + +protected: + I2CBus &bus; + uint8_t _retries; + uint8_t _address; + char *pname; + +}; + +class I2CDeviceManager : public AP_HAL::I2CDeviceManager +{ +public: + friend class I2CDevice; + + static I2CBus businfo[]; + + // constructor + I2CDeviceManager(); + + static I2CDeviceManager *from(AP_HAL::I2CDeviceManager *i2c_mgr) + { + return static_cast(i2c_mgr); + } + + AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, + uint32_t bus_clock=100000, + bool use_smbus = false, + uint32_t timeout_ms=4) override; + + /* + get mask of bus numbers for all configured I2C buses + */ + uint32_t get_bus_mask(void) const override; + + /* + get mask of bus numbers for all configured external I2C buses + */ + uint32_t get_bus_mask_external(void) const override; + + /* + get mask of bus numbers for all configured internal I2C buses + */ + uint32_t get_bus_mask_internal(void) const override; +}; +} diff --git a/libraries/AP_HAL_QURT/RCInput.cpp b/libraries/AP_HAL_QURT/RCInput.cpp new file mode 100644 index 00000000000000..a52f95bf510ca3 --- /dev/null +++ b/libraries/AP_HAL_QURT/RCInput.cpp @@ -0,0 +1,58 @@ +#include "RCInput.h" +#include + +using namespace QURT; + +void RCInput::init() +{ + AP::RC().init(); +} + +const char *RCInput::protocol() const +{ + return AP::RC().protocol_name(); +} + +bool RCInput::new_input() +{ + bool ret = updated; + updated = false; + return ret; +} + +uint8_t RCInput::num_channels() +{ + return num_chan; +} + +uint16_t RCInput::read(uint8_t channel) +{ + if (channel >= MIN(RC_INPUT_MAX_CHANNELS, num_chan)) { + return 0; + } + return values[channel]; +} + +uint8_t RCInput::read(uint16_t* periods, uint8_t len) +{ + WITH_SEMAPHORE(mutex); + len = MIN(len, num_chan); + memcpy(periods, values, len*sizeof(periods[0])); + return len; +} + +void RCInput::_timer_tick(void) +{ + auto &rcprot = AP::RC(); + + WITH_SEMAPHORE(mutex); + + rcprot.update(); + + if (rcprot.new_input()) { + num_chan = rcprot.num_channels(); + num_chan = MIN(num_chan, RC_INPUT_MAX_CHANNELS); + rcprot.read(values, num_chan); + updated = true; + } +} diff --git a/libraries/AP_HAL_QURT/RCInput.h b/libraries/AP_HAL_QURT/RCInput.h new file mode 100644 index 00000000000000..96befb40769365 --- /dev/null +++ b/libraries/AP_HAL_QURT/RCInput.h @@ -0,0 +1,28 @@ +#pragma once + +#include "AP_HAL_QURT.h" +#include + +#ifndef RC_INPUT_MAX_CHANNELS +#define RC_INPUT_MAX_CHANNELS 18 +#endif + +class QURT::RCInput : public AP_HAL::RCInput +{ +public: + void init() override; + bool new_input() override; + uint8_t num_channels() override; + uint16_t read(uint8_t ch) override; + uint8_t read(uint16_t* periods, uint8_t len) override; + + const char *protocol() const override; + + void _timer_tick(void); + +private: + HAL_Semaphore mutex; + uint16_t values[RC_INPUT_MAX_CHANNELS]; + uint8_t num_chan; + bool updated; +}; diff --git a/libraries/AP_HAL_QURT/RCOutput.cpp b/libraries/AP_HAL_QURT/RCOutput.cpp new file mode 100644 index 00000000000000..eb509d070954ae --- /dev/null +++ b/libraries/AP_HAL_QURT/RCOutput.cpp @@ -0,0 +1,239 @@ +#include + +#include "RCOutput.h" +#include +#include + +extern const AP_HAL::HAL& hal; + +using namespace QURT; + +#define ESC_PACKET_TYPE_PWM_CMD 1 +#define ESC_PACKET_TYPE_FB_RESPONSE 128 +#define ESC_PACKET_TYPE_FB_POWER_STATUS 132 + +#define ESC_PKT_HEADER 0xAF + +void RCOutput::init() +{ + fd = sl_client_config_uart(QURT_UART_ESC, baudrate); + if (fd == -1) { + HAP_PRINTF("Failed to open ESC UART"); + } + HAP_PRINTF("ESC UART: %d", fd); +} + +void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) +{ + // no support for changing frequency +} + +uint16_t RCOutput::get_freq(uint8_t ch) +{ + // return fixed fake value + return 490; +} + +void RCOutput::enable_ch(uint8_t ch) +{ + if (ch >= ARRAY_SIZE(period)) { + return; + } + enable_mask |= 1U<= ARRAY_SIZE(period)) { + return; + } + enable_mask &= ~1U<= ARRAY_SIZE(period)) { + return; + } + period[ch] = period_us; + if (!corked) { + need_write = true; + } +} + +uint16_t RCOutput::read(uint8_t ch) +{ + if (ch >= ARRAY_SIZE(period)) { + return 0; + } + return period[ch]; +} + +void RCOutput::read(uint16_t *period_us, uint8_t len) +{ + for (auto i = 0; i < len; i++) { + period_us[i] = read(i); + } +} + +/* + send a packet with CRC to the ESC + */ +void RCOutput::send_esc_packet(uint8_t type, uint8_t *data, uint16_t size) +{ + uint16_t packet_size = size + 5; + uint8_t out[packet_size]; + + out[0] = ESC_PKT_HEADER; + out[1] = packet_size; + out[2] = type; + + memcpy(&out[3], data, size); + + uint16_t crc = calc_crc_modbus(&out[1], packet_size - 3); + + memcpy(&out[packet_size - 2], &crc, sizeof(uint16_t)); + + sl_client_uart_write(fd, (const char *)out, packet_size); +} + +/* + convert 1000 to 2000 PWM to -800 to 800 for QURT ESCs + */ +static int16_t pwm_to_esc(uint16_t pwm) +{ + const float p = constrain_float((pwm-1000)*0.001, 0, 1); + return int16_t(800*p); +} + +/* + send current commands to ESCs + */ +void RCOutput::send_receive(void) +{ + if (fd == -1) { + return; + } + + AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton(); + uint32_t safety_mask = 0; + + if (boardconfig != nullptr) { + // mask of channels to allow with safety on + safety_mask = boardconfig->get_safety_mask(); + } + + int16_t data[5] {}; + + for (uint8_t i=0; i<4; i++) { + uint16_t v = period[i]; + if (safety_on && (safety_mask & (1U< 5) { + last_fb_req_ms = now_ms; + // request feedback from one ESC + last_fb_idx = (last_fb_idx+1) % 4; + data[last_fb_idx] |= 1; + } + + send_esc_packet(ESC_PACKET_TYPE_PWM_CMD, (uint8_t *)data, sizeof(data)); + + check_response(); +} + +/* + handle a telem feedback packet + */ +void RCOutput::handle_esc_feedback(const struct esc_response_v2 &pkt) +{ + const uint8_t idx = pkt.id_state>>4; + if (idx >= ARRAY_SIZE(period)) { + return; + } + update_rpm(idx, pkt.rpm); + + AP_ESC_Telem_Backend::TelemetryData tdata {}; + tdata.voltage = pkt.voltage*0.001; + tdata.current = pkt.current*0.008; + tdata.temperature_cdeg = pkt.temperature; + + update_telem_data(idx, tdata, + AP_ESC_Telem_Backend::TelemetryType::CURRENT | + AP_ESC_Telem_Backend::TelemetryType::VOLTAGE | + AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE); +} + +/* + handle a power status packet, making it available to AnalogIn + */ +void RCOutput::handle_power_status(const struct esc_power_status &pkt) +{ + esc_voltage = pkt.voltage * 0.001; + esc_current = pkt.current * 0.008; +} + +// check for responses +void RCOutput::check_response(void) +{ + uint8_t buf[256]; + struct PACKED esc_packet { + uint8_t header; + uint8_t length; + uint8_t type; + union { + struct esc_response_v2 resp_v2; + struct esc_power_status power_status; + } u; + }; + auto n = sl_client_uart_read(fd, (char *)buf, sizeof(buf)); + while (n >= 3) { + const auto *pkt = (struct esc_packet *)buf; + if (pkt->header != ESC_PKT_HEADER || pkt->length > n) { + return; + } + const uint16_t crc = calc_crc_modbus(&pkt->length, pkt->length-3); + const uint16_t crc2 = buf[pkt->length-2] | buf[pkt->length-1]<<8; + if (crc != crc2) { + return; + } + switch (pkt->type) { + case ESC_PACKET_TYPE_FB_RESPONSE: + handle_esc_feedback(pkt->u.resp_v2); + break; + case ESC_PACKET_TYPE_FB_POWER_STATUS: + handle_power_status(pkt->u.power_status); + break; + default: + HAP_PRINTF("Unknown pkt %u", pkt->type); + break; + } + if (n == pkt->length) { + break; + } + memmove(&buf[0], &buf[pkt->length], n - pkt->length); + n -= pkt->length; + } +} + +void RCOutput::cork(void) +{ + corked = true; +} + +void RCOutput::push(void) +{ + if (corked) { + corked = false; + need_write = true; + send_receive(); + } +} diff --git a/libraries/AP_HAL_QURT/RCOutput.h b/libraries/AP_HAL_QURT/RCOutput.h new file mode 100644 index 00000000000000..ee3f95aac2f27e --- /dev/null +++ b/libraries/AP_HAL_QURT/RCOutput.h @@ -0,0 +1,85 @@ +#pragma once + +#include +#include "AP_HAL_QURT.h" +#include + +class QURT::RCOutput : public AP_HAL::RCOutput, AP_ESC_Telem_Backend +{ +public: + friend class QURT::Util; + + void init() override; + void set_freq(uint32_t chmask, uint16_t freq_hz) override; + uint16_t get_freq(uint8_t ch) override; + void enable_ch(uint8_t ch) override; + void disable_ch(uint8_t ch) override; + void write(uint8_t ch, uint16_t period_us) override; + uint16_t read(uint8_t ch) override; + void read(uint16_t *period_us, uint8_t len) override; + void cork(void) override; + void push(void) override; + + float get_voltage(void) const + { + return esc_voltage; + } + float get_current(void) const + { + return esc_current; + } + + /* + force the safety switch on, disabling output from the ESCs/servos + */ + bool force_safety_on(void) override { safety_on = true; return true; } + + /* + force the safety switch off, enabling output from the ESCs/servos + */ + void force_safety_off(void) override { safety_on = false; } + +private: + const uint32_t baudrate = 2000000; + + void send_receive(void); + void check_response(void); + void send_esc_packet(uint8_t type, uint8_t *data, uint16_t size); + + struct PACKED esc_response_v2 { + uint8_t id_state; // bits 0:3 = state, bits 4:7 = ID + + uint16_t rpm; // Current RPM of the motor + uint8_t cmd_counter; // Number of commands received by the ESC + uint8_t power; // Applied power [0..100] + + uint16_t voltage; // Voltage measured by the ESC in mV + int16_t current; // Current measured by the ESC in 8mA resolution + int16_t temperature; // Temperature measured by the ESC in 0.01 degC resolution + }; + + struct PACKED esc_power_status { + uint8_t id; //ESC Id (could be used as system ID elsewhere) + uint16_t voltage; //Input voltage (Millivolts) + int16_t current; //Total Current (8mA resolution) + }; + + void handle_esc_feedback(const struct esc_response_v2 &pkt); + void handle_power_status(const struct esc_power_status &pkt); + + int fd = -1; + uint16_t enable_mask; + static const uint8_t channel_count = 4; + uint16_t period[channel_count]; + volatile bool need_write; + bool corked; + HAL_Semaphore mutex; + uint8_t last_fb_idx; + uint32_t last_fb_req_ms; + + float esc_voltage; + float esc_current; + + // start with safety on, gets disabled by AP_BoardConfig + bool safety_on = true; +}; diff --git a/libraries/AP_HAL_QURT/SPIDevice.cpp b/libraries/AP_HAL_QURT/SPIDevice.cpp new file mode 100644 index 00000000000000..a4fcdc6660202c --- /dev/null +++ b/libraries/AP_HAL_QURT/SPIDevice.cpp @@ -0,0 +1,134 @@ +/* + * 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 . + */ + +#include "SPIDevice.h" + +#include +#include +#include +#include "Scheduler.h" +#include "Semaphores.h" +#include "interface.h" +#include + +using namespace QURT; + +#define MHZ (1000U*1000U) +#define KHZ (1000U) + +const char *device_names[] = {"INV1", "INV2", "INV3"}; + +static SPIBus *spi_bus; + +SPIBus::SPIBus(void): + DeviceBus(Scheduler::PRIORITY_SPI) +{ + fd = sl_client_config_spi_bus(); + HAP_PRINTF("Created SPI bus -> %d", fd); +} + +SPIDevice::SPIDevice(const char *name, SPIBus &_bus) + : bus(_bus) +{ + set_device_bus(0); + set_device_address(1); + set_speed(AP_HAL::Device::SPEED_LOW); + + pname = name; +} + +SPIDevice::~SPIDevice() +{ +} + +bool SPIDevice::set_speed(AP_HAL::Device::Speed _speed) +{ + return true; +} + +bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len, + uint8_t *recv, uint32_t recv_len) +{ + // If there is no receive buffer then this is a write transaction + // and the data to write is in the send buffer + if (!recv) { + return transfer_fullduplex(send, (uint8_t*) send, send_len); + } + + // Special case handling. This can happen when a send buffer is specified + // even though we are doing only a read. + if (send == recv && send_len == recv_len) { + return transfer_fullduplex(send, recv, send_len); + } + + // This is a read transaction + uint8_t buf[send_len+recv_len]; + if (send_len > 0) { + memcpy(buf, send, send_len); + } + if (recv_len > 0) { + memset(&buf[send_len], 0, recv_len); + } + transfer_fullduplex(buf, buf, send_len+recv_len); + if (recv_len > 0) { + memcpy(recv, &buf[send_len], recv_len); + } + return true; +} + +bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) +{ + return (sl_client_spi_transfer(bus.fd, send, recv, len) == 0); +} + +void SPIDevice::acquire_bus(bool accuire) +{ +} + +AP_HAL::Semaphore *SPIDevice::get_semaphore() +{ + return &bus.semaphore; +} + +AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) +{ + return bus.register_periodic_callback(period_usec, cb, this); +} + +bool SPIDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) +{ + return bus.adjust_timer(h, period_usec); +} + +AP_HAL::OwnPtr +SPIDeviceManager::get_device(const char *name) +{ + uint8_t i; + for (i = 0; i(nullptr); + } + + if (spi_bus == nullptr) { + spi_bus = new SPIBus(); + } + + return AP_HAL::OwnPtr(new SPIDevice(name, *spi_bus)); +} + diff --git a/libraries/AP_HAL_QURT/SPIDevice.h b/libraries/AP_HAL_QURT/SPIDevice.h new file mode 100644 index 00000000000000..65a55858204e01 --- /dev/null +++ b/libraries/AP_HAL_QURT/SPIDevice.h @@ -0,0 +1,65 @@ +/* + * 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 +#include +#include "AP_HAL_QURT.h" + +#include "Semaphores.h" +#include "Scheduler.h" +#include "DeviceBus.h" + +namespace QURT +{ + +class SPIBus : public DeviceBus +{ +public: + SPIBus(); + int fd = -1; +}; + +class SPIDevice : public AP_HAL::SPIDevice +{ +public: + SPIDevice(const char *name, SPIBus &bus); + virtual ~SPIDevice(); + + bool set_speed(AP_HAL::Device::Speed speed) override; + bool transfer(const uint8_t *send, uint32_t send_len, + uint8_t *recv, uint32_t recv_len) override; + bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override; + AP_HAL::Semaphore *get_semaphore() override; + AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override; + bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override; + +private: + SPIBus &bus; + const char *pname; + void acquire_bus(bool accuire); +}; + +class SPIDeviceManager : public AP_HAL::SPIDeviceManager +{ +public: + friend class SPIDevice; + + AP_HAL::OwnPtr get_device(const char *name) override; +}; +} + diff --git a/libraries/AP_HAL_QURT/Scheduler.cpp b/libraries/AP_HAL_QURT/Scheduler.cpp new file mode 100644 index 00000000000000..2930861a273254 --- /dev/null +++ b/libraries/AP_HAL_QURT/Scheduler.cpp @@ -0,0 +1,352 @@ +#include + +#include "AP_HAL_QURT.h" +#include "Scheduler.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "UARTDriver.h" +#include "Storage.h" +#include "RCOutput.h" +#include "RCInput.h" +#include +#include "Thread.h" + +using namespace QURT; + +extern const AP_HAL::HAL& hal; + +Scheduler::Scheduler() +{ +} + +void Scheduler::init() +{ + _main_thread_ctx = pthread_self(); + + // setup the timer thread - this will call tasks at 1kHz + pthread_attr_t thread_attr; + struct sched_param param; + + pthread_attr_init(&thread_attr); + pthread_attr_setstacksize(&thread_attr, 16000); + + param.sched_priority = APM_TIMER_PRIORITY; + (void)pthread_attr_setschedparam(&thread_attr, ¶m); + + pthread_create(&_timer_thread_ctx, &thread_attr, &Scheduler::_timer_thread, this); + + // the UART thread runs at a medium priority + pthread_attr_init(&thread_attr); + pthread_attr_setstacksize(&thread_attr, 16000); + + param.sched_priority = APM_UART_PRIORITY; + (void)pthread_attr_setschedparam(&thread_attr, ¶m); + + pthread_create(&_uart_thread_ctx, &thread_attr, &Scheduler::_uart_thread, this); + + // the IO thread runs at lower priority + pthread_attr_init(&thread_attr); + pthread_attr_setstacksize(&thread_attr, 16000); + + param.sched_priority = APM_IO_PRIORITY; + (void)pthread_attr_setschedparam(&thread_attr, ¶m); + + pthread_create(&_io_thread_ctx, &thread_attr, &Scheduler::_io_thread, this); +} + +#define APM_QURT_MAX_PRIORITY (200 + 20) +#define APM_QURT_TIMER_PRIORITY (200 + 15) +#define APM_QURT_UART_PRIORITY (200 + 14) +#define APM_QURT_NET_PRIORITY (200 + 14) +#define APM_QURT_RCIN_PRIORITY (200 + 13) +#define APM_QURT_MAIN_PRIORITY (200 + 12) +#define APM_QURT_IO_PRIORITY (200 + 10) +#define APM_QURT_SCRIPTING_PRIORITY (200 + 1) +#define AP_QURT_SENSORS_SCHED_PRIO (200 + 12) + +uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority) const +{ + uint8_t thread_priority = APM_QURT_IO_PRIORITY; + static const struct { + priority_base base; + uint8_t p; + } priority_map[] = { + { PRIORITY_BOOST, APM_QURT_MAIN_PRIORITY}, + { PRIORITY_MAIN, APM_QURT_MAIN_PRIORITY}, + { PRIORITY_SPI, AP_QURT_SENSORS_SCHED_PRIO+1}, + { PRIORITY_I2C, AP_QURT_SENSORS_SCHED_PRIO}, + { PRIORITY_CAN, APM_QURT_TIMER_PRIORITY}, + { PRIORITY_TIMER, APM_QURT_TIMER_PRIORITY}, + { PRIORITY_RCIN, APM_QURT_RCIN_PRIORITY}, + { PRIORITY_IO, APM_QURT_IO_PRIORITY}, + { PRIORITY_UART, APM_QURT_UART_PRIORITY}, + { PRIORITY_STORAGE, APM_QURT_IO_PRIORITY}, + { PRIORITY_SCRIPTING, APM_QURT_SCRIPTING_PRIORITY}, + { PRIORITY_NET, APM_QURT_NET_PRIORITY}, + }; + for (const auto &m : priority_map) { + if (m.base == base) { + thread_priority = constrain_int16(m.p + priority, 1, APM_QURT_MAX_PRIORITY); + break; + } + } + + return thread_priority; +} + +/* + create a new thread +*/ +bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) +{ + Thread *thread = new Thread{(Thread::task_t)proc}; + if (thread == nullptr) { + return false; + } + + const uint8_t thread_priority = calculate_thread_priority(base, priority); + + stack_size = MAX(stack_size, 8192U); + + // Setting the stack size too large can cause odd behavior!!! + thread->set_stack_size(stack_size); + + /* + * We should probably store the thread handlers and join() when exiting, + * but let's the thread manage itself for now. + */ + thread->set_auto_free(true); + + DEV_PRINTF("Starting thread %s: Priority %u", name, thread_priority); + + if (!thread->start(name, SCHED_FIFO, thread_priority)) { + delete thread; + return false; + } + + return true; +} + +void Scheduler::delay_microseconds(uint16_t usec) +{ + qurt_timer_sleep(usec); +} + +void Scheduler::delay(uint16_t ms) +{ + uint64_t start = AP_HAL::micros64(); + + while ((AP_HAL::micros64() - start)/1000 < ms) { + delay_microseconds(1000); + if (_min_delay_cb_ms <= ms) { + if (in_main_thread()) { + const auto old_task = hal.util->persistent_data.scheduler_task; + hal.util->persistent_data.scheduler_task = -4; + call_delay_cb(); + hal.util->persistent_data.scheduler_task = old_task; + } + } + } +} + +void Scheduler::register_timer_process(AP_HAL::MemberProc proc) +{ + for (uint8_t i = 0; i < _num_timer_procs; i++) { + if (_timer_proc[i] == proc) { + return; + } + } + + if (_num_timer_procs < QURT_SCHEDULER_MAX_TIMER_PROCS) { + _timer_proc[_num_timer_procs] = proc; + _num_timer_procs++; + } else { + hal.console->printf("Out of timer processes\n"); + } +} + +void Scheduler::register_io_process(AP_HAL::MemberProc proc) +{ + for (uint8_t i = 0; i < _num_io_procs; i++) { + if (_io_proc[i] == proc) { + return; + } + } + + if (_num_io_procs < QURT_SCHEDULER_MAX_TIMER_PROCS) { + _io_proc[_num_io_procs] = proc; + _num_io_procs++; + } else { + hal.console->printf("Out of IO processes\n"); + } +} + +void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) +{ + _failsafe = failsafe; +} + +void Scheduler::suspend_timer_procs() +{ + _timer_suspended = true; +} + +void Scheduler::resume_timer_procs() +{ + _timer_suspended = false; + if (_timer_event_missed == true) { + _run_timers(false); + _timer_event_missed = false; + } +} + +void Scheduler::reboot(bool hold_in_bootloader) +{ + HAP_PRINTF("**** REBOOT REQUESTED ****"); + // delay for printf to appear on USB monitor + qurt_timer_sleep(10000); + + // tell host we want to reboot + struct qurt_rpc_msg msg {}; + msg.msg_id = QURT_MSG_ID_REBOOT; + qurt_rpc_send(msg); + + // wait for RPC to get through + qurt_timer_sleep(10000); + exit(1); +} + +void Scheduler::_run_timers(bool called_from_timer_thread) +{ + if (_in_timer_proc) { + return; + } + _in_timer_proc = true; + + if (!_timer_suspended) { + // now call the timer based drivers + for (int i = 0; i < _num_timer_procs; i++) { + if (_timer_proc[i]) { + _timer_proc[i](); + } + } + } else if (called_from_timer_thread) { + _timer_event_missed = true; + } + + // and the failsafe, if one is setup + if (_failsafe != nullptr) { + _failsafe(); + } + + _in_timer_proc = false; +} + +extern bool qurt_ran_overtime; + +void *Scheduler::_timer_thread(void *arg) +{ + Scheduler *sched = (Scheduler *)arg; + + while (!sched->_hal_initialized) { + sched->delay_microseconds(1000); + } + while (true) { + sched->delay_microseconds(1000); + + // run registered timers + sched->_run_timers(true); + } + return nullptr; +} + +void Scheduler::_run_io(void) +{ + if (_in_io_proc) { + return; + } + _in_io_proc = true; + + if (!_timer_suspended) { + // now call the IO based drivers + for (int i = 0; i < _num_io_procs; i++) { + if (_io_proc[i]) { + _io_proc[i](); + } + } + } + + _in_io_proc = false; +} + +void *Scheduler::_uart_thread(void *arg) +{ + Scheduler *sched = (Scheduler *)arg; + + while (!sched->_hal_initialized) { + sched->delay_microseconds(1000); + } + while (true) { + sched->delay_microseconds(200); + + // process any pending serial bytes + for (uint8_t i = 0; i < hal.num_serial; i++) { + auto *p = hal.serial(i); + if (p != nullptr) { + p->_timer_tick(); + } + } + } + return nullptr; +} + +void *Scheduler::_io_thread(void *arg) +{ + Scheduler *sched = (Scheduler *)arg; + + while (!sched->_hal_initialized) { + sched->delay_microseconds(1000); + } + while (true) { + sched->delay_microseconds(1000); + + // run registered IO processes + sched->_run_io(); + + // update storage + hal.storage->_timer_tick(); + + // update RC input + ((QURT::RCInput *)hal.rcin)->_timer_tick(); + } + return nullptr; +} + +bool Scheduler::in_main_thread() const +{ + return pthread_equal(pthread_self(), _main_thread_ctx); +} + +void Scheduler::set_system_initialized() +{ + _main_thread_ctx = pthread_self(); + if (_initialized) { + AP_HAL::panic("PANIC: scheduler::system_initialized called" + "more than once"); + } + _initialized = true; +} + +void Scheduler::hal_initialized(void) +{ + HAP_PRINTF("HAL is initialised"); + _hal_initialized = true; +} diff --git a/libraries/AP_HAL_QURT/Scheduler.h b/libraries/AP_HAL_QURT/Scheduler.h new file mode 100644 index 00000000000000..8c4fd863a96df1 --- /dev/null +++ b/libraries/AP_HAL_QURT/Scheduler.h @@ -0,0 +1,84 @@ +#pragma once + +#include +#if CONFIG_HAL_BOARD == HAL_BOARD_QURT +#include "AP_HAL_QURT_Namespace.h" +#include +#include +#include + +#define QURT_SCHEDULER_MAX_TIMER_PROCS 8 + +#define APM_MAIN_PRIORITY 180 +#define APM_TIMER_PRIORITY 181 +#define APM_UART_PRIORITY 60 +#define APM_IO_PRIORITY 58 + +/* Scheduler implementation: */ +class QURT::Scheduler : public AP_HAL::Scheduler +{ +public: + Scheduler(); + /* AP_HAL::Scheduler methods */ + + 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 suspend_timer_procs(); + void resume_timer_procs(); + void reboot(bool hold_in_bootloader) override; + + bool in_main_thread() const override; + void hal_initialized(); + + void set_system_initialized() override; + bool is_system_initialized() override + { + return _initialized; + } + + bool thread_create(AP_HAL::MemberProc proc, const char *name, + uint32_t stack_size, priority_base base, int8_t priority) override; + +private: + bool _initialized; + volatile bool _hal_initialized; + AP_HAL::Proc _delay_cb; + uint16_t _min_delay_cb_ms; + AP_HAL::Proc _failsafe; + + volatile bool _timer_suspended; + + AP_HAL::MemberProc _timer_proc[QURT_SCHEDULER_MAX_TIMER_PROCS]; + uint8_t _num_timer_procs; + volatile bool _in_timer_proc; + + AP_HAL::MemberProc _io_proc[QURT_SCHEDULER_MAX_TIMER_PROCS]; + uint8_t _num_io_procs; + volatile bool _in_io_proc; + + volatile bool _timer_event_missed; + + pthread_t _main_thread_ctx; + pthread_t _timer_thread_ctx; + pthread_t _io_thread_ctx; + pthread_t _storage_thread_ctx; + pthread_t _uart_thread_ctx; + + uint8_t calculate_thread_priority(priority_base base, int8_t priority) const; + + static void *_timer_thread(void *arg); + static void *_io_thread(void *arg); + static void *_storage_thread(void *arg); + static void *_uart_thread(void *arg); + + void _run_timers(bool called_from_timer_thread); + void _run_io(void); +}; +#endif + + + diff --git a/libraries/AP_HAL_QURT/Semaphores.cpp b/libraries/AP_HAL_QURT/Semaphores.cpp new file mode 100644 index 00000000000000..1c7c280e0a0bbe --- /dev/null +++ b/libraries/AP_HAL_QURT/Semaphores.cpp @@ -0,0 +1,111 @@ +#include + +#include "Semaphores.h" + +extern const AP_HAL::HAL& hal; + +using namespace QURT; + +// construct a semaphore +Semaphore::Semaphore() +{ + pthread_mutexattr_t attr; + pthread_mutexattr_init(&attr); + pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE); + pthread_mutex_init(&_lock, &attr); +} + +bool Semaphore::give() +{ + return pthread_mutex_unlock(&_lock) == 0; +} + +bool Semaphore::check_owner() +{ + return owner == pthread_self(); +} + +bool Semaphore::take(uint32_t timeout_ms) +{ + if (timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER) { + auto ok = pthread_mutex_lock(&_lock) == 0; + if (ok) { + owner = pthread_self(); + } + return ok; + } + if (take_nonblocking()) { + return true; + } + uint64_t start = AP_HAL::micros64(); + do { + hal.scheduler->delay_microseconds(200); + if (take_nonblocking()) { + return true; + } + } while ((AP_HAL::micros64() - start) < timeout_ms*1000); + return false; +} + +bool Semaphore::take_nonblocking() +{ + const auto ok = pthread_mutex_trylock(&_lock) == 0; + if (ok) { + owner = pthread_self(); + } + return ok; +} + +/* + binary semaphore using condition variables + */ + +BinarySemaphore::BinarySemaphore(bool initial_state) : + AP_HAL::BinarySemaphore(initial_state) +{ + pthread_cond_init(&cond, NULL); + pending = initial_state; +} + +bool BinarySemaphore::wait(uint32_t timeout_us) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + struct timespec ts; + if (clock_gettime(CLOCK_REALTIME, &ts) != 0) { + return false; + } + ts.tv_sec += timeout_us/1000000UL; + ts.tv_nsec += (timeout_us % 1000000U) * 1000UL; + if (ts.tv_nsec >= 1000000000L) { + ts.tv_sec++; + ts.tv_nsec -= 1000000000L; + } + if (pthread_cond_timedwait(&cond, &mtx._lock, &ts) != 0) { + return false; + } + } + pending = false; + return true; +} + +bool BinarySemaphore::wait_blocking(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + if (pthread_cond_wait(&cond, &mtx._lock) != 0) { + return false; + } + } + pending = false; + return true; +} + +void BinarySemaphore::signal(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + pending = true; + pthread_cond_signal(&cond); + } +} diff --git a/libraries/AP_HAL_QURT/Semaphores.h b/libraries/AP_HAL_QURT/Semaphores.h new file mode 100644 index 00000000000000..61a36795e01aac --- /dev/null +++ b/libraries/AP_HAL_QURT/Semaphores.h @@ -0,0 +1,42 @@ +#pragma once + +#include +#include +#include +#include + +namespace QURT +{ + +class Semaphore : public AP_HAL::Semaphore +{ +public: + friend class BinarySemaphore; + Semaphore(); + bool give() override; + bool take(uint32_t timeout_ms) override; + bool take_nonblocking() override; + bool check_owner(void); +protected: + // qurt_mutex_t _lock; + pthread_mutex_t _lock; + pthread_t owner; +}; + + +class BinarySemaphore : public AP_HAL::BinarySemaphore +{ +public: + BinarySemaphore(bool initial_state=false); + + bool wait(uint32_t timeout_us) override; + bool wait_blocking(void) override; + void signal(void) override; + +protected: + Semaphore mtx; + pthread_cond_t cond; + bool pending; +}; + +} diff --git a/libraries/AP_HAL_QURT/Storage.cpp b/libraries/AP_HAL_QURT/Storage.cpp new file mode 100644 index 00000000000000..a4bf15acd1b96d --- /dev/null +++ b/libraries/AP_HAL_QURT/Storage.cpp @@ -0,0 +1,195 @@ +#include "Storage.h" + +#include +#include +#include +#include +#include + +#include + +using namespace QURT; + +#define QURT_STORAGE_MAX_WRITE 512 +#define QURT_STORAGE_LINE_SHIFT 9 +#define QURT_STORAGE_LINE_SIZE (1<>QURT_STORAGE_LINE_SHIFT; + line <= end>>QURT_STORAGE_LINE_SHIFT; + line++) { + _dirty_mask |= 1U << line; + } +} + +void Storage::read_block(void *dst, uint16_t loc, size_t n) +{ + if (loc >= sizeof(_buffer)-(n-1)) { + return; + } + init(); + memcpy(dst, &_buffer[loc], n); +} + +void Storage::write_block(uint16_t loc, const void *src, size_t n) +{ + if (loc >= sizeof(_buffer)-(n-1)) { + return; + } + if (memcmp(src, &_buffer[loc], n) != 0) { + init(); + memcpy(&_buffer[loc], src, n); + _mark_dirty(loc, n); + } +} + +void Storage::_timer_tick(void) +{ + if (!_initialised || _dirty_mask == 0 || _fd == -1) { + return; + } + + // write out the first dirty set of lines. We don't write more + // than one to keep the latency of this call to a minimum + uint8_t i, n; + for (i=0; i>QURT_STORAGE_LINE_SHIFT); n++) { + if (!(_dirty_mask & (1<<(n+i)))) { + break; + } + // mark that line clean + write_mask |= (1<<(n+i)); + } + + /* + write the lines. This also updates _dirty_mask. Note that + because this is a SCHED_FIFO thread it will not be preempted + by the main task except during blocking calls. This means we + don't need a semaphore around the _dirty_mask updates. + */ + if (lseek(_fd, i< + +#define QURT_STORAGE_SIZE HAL_STORAGE_SIZE + +namespace QURT +{ + +class Storage : public AP_HAL::Storage +{ +public: + static Storage *from(AP_HAL::Storage *storage) + { + return static_cast(storage); + } + + + void init() override; + + uint8_t read_byte(uint16_t loc); + uint16_t read_word(uint16_t loc); + uint32_t read_dword(uint16_t loc); + void read_block(void *dst, uint16_t src, size_t n) override; + + void write_byte(uint16_t loc, uint8_t value); + void write_word(uint16_t loc, uint16_t value); + void write_dword(uint16_t loc, uint32_t value); + void write_block(uint16_t dst, const void* src, size_t n) override; + + bool get_storage_ptr(void *&ptr, size_t &size) override; + + virtual void _timer_tick(void) override; + +protected: + void _mark_dirty(uint16_t loc, uint16_t length); + bool _storage_create(void); + + int _fd = -1; + volatile bool _initialised; + volatile uint32_t _dirty_mask; + uint8_t _buffer[QURT_STORAGE_SIZE]; +}; + +} diff --git a/libraries/AP_HAL_QURT/Thread.cpp b/libraries/AP_HAL_QURT/Thread.cpp new file mode 100644 index 00000000000000..246e7bc9036b88 --- /dev/null +++ b/libraries/AP_HAL_QURT/Thread.cpp @@ -0,0 +1,182 @@ +/* + * Copyright (C) 2016 Intel Corporation. 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 . + */ +#include "Thread.h" + +#include +#include +#include +#include +#include + +#include +#include +#include "Scheduler.h" + +extern const AP_HAL::HAL &hal; + +namespace QURT +{ + + +void *Thread::_run_trampoline(void *arg) +{ + Thread *thread = static_cast(arg); + thread->_run(); + + if (thread->_auto_free) { + delete thread; + } + + return nullptr; +} + +bool Thread::_run() +{ + if (!_task) { + return false; + } + + _task(); + + return true; +} + +size_t Thread::get_stack_usage() +{ + return 0; +} + +bool Thread::start(const char *name, int policy, int prio) +{ + if (_started) { + return false; + } + + struct sched_param param = { .sched_priority = prio }; + pthread_attr_t attr; + int r; + + pthread_attr_init(&attr); + + if ((r = pthread_attr_setschedparam(&attr, ¶m)) != 0) { + AP_HAL::panic("Failed to set attributes for thread '%s': %s", + name, strerror(r)); + } + + const uint32_t stack_alignment = 2048U; + _stack_size = (_stack_size+stack_alignment) & ~stack_alignment; + if (_stack_size) { + if (pthread_attr_setstacksize(&attr, _stack_size) != 0) { + return false; + } + } + + r = pthread_create(&_ctx, &attr, &Thread::_run_trampoline, this); + if (r != 0) { + AP_HAL::panic("Failed to create thread '%s': %s", + name, strerror(r)); + } + pthread_attr_destroy(&attr); + + _started = true; + + return true; +} + +bool Thread::is_current_thread() +{ + return pthread_equal(pthread_self(), _ctx); +} + +bool Thread::join() +{ + void *ret; + + if (_ctx == 0) { + return false; + } + + if (pthread_join(_ctx, &ret) != 0 || + (intptr_t)ret != 0) { + return false; + } + + return true; +} + + +bool PeriodicThread::set_rate(uint32_t rate_hz) +{ + if (_started || rate_hz == 0) { + return false; + } + + _period_usec = hz_to_usec(rate_hz); + + return true; +} + +bool Thread::set_stack_size(size_t stack_size) +{ + if (_started) { + return false; + } + + _stack_size = MAX(stack_size, (size_t) PTHREAD_STACK_MIN); + + return true; +} + +bool PeriodicThread::_run() +{ + if (_period_usec == 0) { + return false; + } + + uint64_t next_run_usec = AP_HAL::micros64() + _period_usec; + + while (!_should_exit) { + uint64_t dt = next_run_usec - AP_HAL::micros64(); + if (dt > _period_usec) { + // we've lost sync - restart + next_run_usec = AP_HAL::micros64(); + } else { + qurt_timer_sleep(dt); + } + next_run_usec += _period_usec; + + _task(); + } + + _started = false; + _should_exit = false; + + return true; +} + +bool PeriodicThread::stop() +{ + if (!is_started()) { + return false; + } + + _should_exit = true; + + return true; +} + +} diff --git a/libraries/AP_HAL_QURT/Thread.h b/libraries/AP_HAL_QURT/Thread.h new file mode 100644 index 00000000000000..69985a04d18589 --- /dev/null +++ b/libraries/AP_HAL_QURT/Thread.h @@ -0,0 +1,108 @@ +/* + * Copyright (C) 2016 Intel Corporation. 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 . + */ +#pragma once + +#include +#include +#include + +#include + +namespace QURT +{ + +/* + * Interface abstracting threads + */ +class Thread +{ +public: + FUNCTOR_TYPEDEF(task_t, void); + + Thread(task_t t) : _task(t) { } + + virtual ~Thread() { } + + bool start(const char *name, int policy, int prio); + + bool is_current_thread(); + + bool is_started() const + { + return _started; + } + + size_t get_stack_usage(); + + bool set_stack_size(size_t stack_size); + + void set_auto_free(bool auto_free) + { + _auto_free = auto_free; + } + + virtual bool stop() + { + return false; + } + + bool join(); + +protected: + static void *_run_trampoline(void *arg); + + /* + * Run the task assigned in the constructor. May be overriden in case it's + * preferred to use Thread as an interface or when user wants to aggregate + * some initialization or teardown for the thread. + */ + virtual bool _run(); + + void _poison_stack(); + + task_t _task; + bool _started = false; + bool _should_exit = false; + bool _auto_free = false; + pthread_t _ctx = 0; + + struct stack_debug { + uint32_t *start; + uint32_t *end; + } _stack_debug; + + size_t _stack_size = 0; +}; + +class PeriodicThread : public Thread +{ +public: + PeriodicThread(Thread::task_t t) + : Thread(t) + { } + + bool set_rate(uint32_t rate_hz); + + bool stop() override; + +protected: + bool _run() override; + + uint64_t _period_usec = 0; +}; + +} diff --git a/libraries/AP_HAL_QURT/UARTDriver.cpp b/libraries/AP_HAL_QURT/UARTDriver.cpp new file mode 100644 index 00000000000000..db91beb6025d95 --- /dev/null +++ b/libraries/AP_HAL_QURT/UARTDriver.cpp @@ -0,0 +1,287 @@ + +#include "interface.h" +#include "UARTDriver.h" +#include + +#if HAL_GCS_ENABLED +#include +#endif + +extern const AP_HAL::HAL& hal; +using namespace QURT; + +/* QURT implementations of virtual methods */ +void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) +{ + if (_initialised) { + return; + } + + /* we have enough memory to have a larger transmit buffer for + * all ports. This means we don't get delays while waiting to + * write GPS config packets + */ + if (rxS < 4096) { + rxS = 4096; + } + if (txS < 4096) { + txS = 4096; + } + + WITH_SEMAPHORE(_write_mutex); + + if (_writebuf.set_size(txS) && _readbuf.set_size(rxS)) { + _initialised = true; + } +} + +void UARTDriver::_end() +{ +} + +void UARTDriver::_flush() +{ +} + +bool UARTDriver::is_initialized() +{ + return _initialised; +} + +bool UARTDriver::tx_pending() +{ + return (_writebuf.available() > 0); +} + +uint32_t UARTDriver::_available() +{ + if (!_initialised) { + return 0; + } + + WITH_SEMAPHORE(_read_mutex); + + return _readbuf.available(); +} + +uint32_t UARTDriver::txspace() +{ + if (!_initialised) { + return 0; + } + return _writebuf.space(); +} + +bool UARTDriver::_discard_input() +{ + if (!_initialised) { + return false; + } + + WITH_SEMAPHORE(_read_mutex); + + _readbuf.clear(); + return true; +} + +size_t UARTDriver::_write(const uint8_t *buffer, size_t size) +{ + if (!_initialised) { + return 0; + } + WITH_SEMAPHORE(_write_mutex); + + return _writebuf.write(buffer, size); +} + +ssize_t UARTDriver::_read(uint8_t *buffer, uint16_t size) +{ + if (!_initialised) { + return 0; + } + + WITH_SEMAPHORE(_read_mutex); + + return _readbuf.read(buffer, size); +} + +/* + push any pending bytes to/from the serial port. This is called at + 1kHz in the timer thread. Doing it this way reduces the system call + overhead in the main task enormously. + */ +void UARTDriver::_timer_tick(void) +{ + if (!_initialised) { + return; + } + + for (auto i=0; i<10; i++) { + if (!_write_pending_bytes()) { + break; + } + } + + _fill_read_buffer(); +} + +/* + methods for UARTDriver_Console + */ +void UARTDriver_Console::printf(const char *fmt, ...) +{ + va_list ap; + char buf[300]; + va_start(ap, fmt); + vsnprintf(buf, sizeof(buf), fmt, ap); + va_end(ap); + HAP_PRINTF(buf); +} + + +/* + methods for UARTDriver_MAVLinkUDP + */ +typedef void (*mavlink_data_callback_t)(const struct qurt_rpc_msg *msg, void* p); +extern void register_mavlink_data_callback(uint8_t instance, mavlink_data_callback_t func, void *p); + +UARTDriver_MAVLinkUDP::UARTDriver_MAVLinkUDP(uint8_t instance) : inst(instance) +{ + register_mavlink_data_callback(instance, _mavlink_data_cb, (void *) this); +} + +void UARTDriver_MAVLinkUDP::check_rx_seq(uint32_t seq) +{ + if (seq != rx_seq) + { + HAP_PRINTF("Sequence mismatch for instance %u. Expected %u, got %u", inst, rx_seq, seq); + } + rx_seq++; +} + +void UARTDriver_MAVLinkUDP::_mavlink_data_cb(const struct qurt_rpc_msg *msg, void *p) +{ + auto *driver = (UARTDriver_MAVLinkUDP *)p; + driver->check_rx_seq(msg->seq); + driver->_readbuf.write(msg->data, msg->data_length); +} + +/* + try to push out one lump of pending bytes + return true if progress is made + */ +bool UARTDriver_MAVLinkUDP::_write_pending_bytes(void) +{ + WITH_SEMAPHORE(_write_mutex); + + // write any pending bytes + const uint32_t available_bytes = _writebuf.available(); + uint16_t n = available_bytes; + + if (n > 0) { + // send on MAVLink packet boundaries if possible + n = mavlink_packetise(_writebuf, n); + } + + if (n <= 0) { + return false; + } + + struct qurt_rpc_msg msg; + if (n > sizeof(msg.data)) { + return false; + } + msg.msg_id = QURT_MSG_ID_MAVLINK_MSG; + msg.inst = inst; + msg.seq = tx_seq++; + msg.data_length = _writebuf.read(msg.data, n); + + return qurt_rpc_send(msg); +} + +/* + setup baudrate for this local UART + */ +void UARTDriver_Local::_begin(uint32_t b, uint16_t rxS, uint16_t txS) +{ + if (b == 0) { + // re-open not needed + return; + } + + // QURT wants 420000 for CRSF, ArduPilot driver wants 416666 + if (b == 416666) { + b = 420000; + } + + UARTDriver::_begin(b, rxS, txS); + + if (baudrate != b || fd == -1) { + int fd2 = sl_client_config_uart(port_id, b); + if (fd2 == -1 && fd != -1) { + // baudrate rejected, revert to last baudrate + sl_client_config_uart(port_id, baudrate); + } + if (fd2 != -1) { + baudrate = b; + fd = fd2; + } + } +} + +/* + push out pending bytes + */ +bool UARTDriver_Local::_write_pending_bytes(void) +{ + WITH_SEMAPHORE(_write_mutex); + if (fd == -1) { + return false; + } + uint32_t available; + const uint8_t *ptr = _writebuf.readptr(available); + if (ptr != nullptr) { + auto n = sl_client_uart_write(fd, (const char *)ptr, available); + if (n > 0) { + _writebuf.advance(n); + return true; + } + } + return false; +} + +/* + read from the UART into _readbuf + */ +void UARTDriver_Local::_fill_read_buffer(void) +{ + WITH_SEMAPHORE(_read_mutex); + if (fd == -1) { + return; + } + uint32_t n = _readbuf.space(); + if (n > 512) { + n = 512; + } + char buf[n]; + auto nread = sl_client_uart_read(fd, buf, sizeof(buf)); + if (nread > 0) { + _readbuf.write((const uint8_t *)buf, nread); + receive_timestamp_us = AP_HAL::micros64(); + } +} + +/* + return timestamp estimate in microseconds for when the start of a + nbytes packet arrived on the uart. +*/ +uint64_t UARTDriver_Local::receive_time_constraint_us(uint16_t nbytes) +{ + uint64_t last_receive_us = receive_timestamp_us; + if (baudrate > 0) { + // assume 10 bits per byte + uint32_t transport_time_us = (1000000UL * 10UL / baudrate) * (nbytes + available()); + last_receive_us -= transport_time_us; + } + return last_receive_us; +} diff --git a/libraries/AP_HAL_QURT/UARTDriver.h b/libraries/AP_HAL_QURT/UARTDriver.h new file mode 100644 index 00000000000000..575e27707ba63a --- /dev/null +++ b/libraries/AP_HAL_QURT/UARTDriver.h @@ -0,0 +1,137 @@ +/* + 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_HAL_QURT.h" +#include "Semaphores.h" +#include +#include "ap_host/src/protocol.h" + +class QURT::UARTDriver : public AP_HAL::UARTDriver +{ +public: + bool is_initialized() override; + bool tx_pending() override; + + /* Empty implementations of Stream virtual methods */ + uint32_t txspace() override; + + virtual bool _write_pending_bytes(void) + { + return false; + } + virtual void _timer_tick(void) override; + virtual void _fill_read_buffer(void) {} + + virtual uint32_t bw_in_bytes_per_second() const override + { + return 5760; + } + virtual enum AP_HAL::UARTDriver::flow_control get_flow_control(void) override + { + return AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE; + } + +protected: + virtual void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + size_t _write(const uint8_t *buffer, size_t size) override; + ssize_t _read(uint8_t *buffer, uint16_t size) override WARN_IF_UNUSED; + void _end() override; + void _flush() override; + uint32_t _available() override; + bool _discard_input() override; + volatile bool _initialised; + + ByteBuffer _readbuf{0}; + ByteBuffer _writebuf{0}; + + QURT::Semaphore _read_mutex; + QURT::Semaphore _write_mutex; +}; + +/* + subclass for console output, maps to HAP_PRINTF +*/ +class QURT::UARTDriver_Console : public QURT::UARTDriver +{ +public: + using UARTDriver::UARTDriver; + virtual void printf(const char *fmt, ...) override; +}; + +/* + subclass for MAVLink UDP communications +*/ + +class QURT::UARTDriver_MAVLinkUDP : public QURT::UARTDriver +{ +public: + UARTDriver_MAVLinkUDP(uint8_t instance); + + bool _write_pending_bytes(void) override; + + void check_rx_seq(uint32_t seq); + + uint32_t bw_in_bytes_per_second() const override + { + return 250000 * 3; + } + enum AP_HAL::UARTDriver::flow_control get_flow_control(void) override + { + return AP_HAL::UARTDriver::FLOW_CONTROL_ENABLE; + } + +private: + static void _mavlink_data_cb(const struct qurt_rpc_msg *msg, void *p); + uint8_t inst; + uint32_t tx_seq; + uint32_t rx_seq; +}; + +/* + subclass for local UART communications +*/ +class QURT::UARTDriver_Local : public QURT::UARTDriver +{ +public: + UARTDriver_Local(uint8_t _port_id) : port_id(_port_id) {} + + uint32_t bw_in_bytes_per_second() const override + { + return baudrate?baudrate/10:5760; + } + + bool _write_pending_bytes(void) override; + void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + void _fill_read_buffer(void) override; + + uint32_t get_baud_rate() const override + { + return baudrate; + } + + /* + return timestamp estimate in microseconds for when the start of + a nbytes packet arrived on the uart. + */ + uint64_t receive_time_constraint_us(uint16_t nbytes) override; + +private: + const uint8_t port_id; + int fd = -1; + uint32_t baudrate; + uint64_t receive_timestamp_us; +}; diff --git a/libraries/AP_HAL_QURT/Util.cpp b/libraries/AP_HAL_QURT/Util.cpp new file mode 100644 index 00000000000000..23444db8c9d25d --- /dev/null +++ b/libraries/AP_HAL_QURT/Util.cpp @@ -0,0 +1,34 @@ +#include +#include "Semaphores.h" +#include + +extern const AP_HAL::HAL& hal; + +#include "Util.h" +#include "RCOutput.h" + +using namespace QURT; + +extern "C" { + void *fc_heap_alloc(size_t size); + void fc_heap_free(void* ptr); + size_t fc_heap_size(void); + size_t fc_heap_usage(void); +} + +uint32_t Util::available_memory(void) +{ + return fc_heap_size() - fc_heap_usage(); +} + +/* + return state of safety switch, if applicable +*/ +Util::safety_state Util::safety_switch_state(void) +{ + const auto *rcout = (QURT::RCOutput *)hal.rcout; + if (rcout != nullptr && rcout->safety_on) { + return SAFETY_DISARMED; + } + return SAFETY_ARMED; +} diff --git a/libraries/AP_HAL_QURT/Util.h b/libraries/AP_HAL_QURT/Util.h new file mode 100644 index 00000000000000..4fb0618beb40df --- /dev/null +++ b/libraries/AP_HAL_QURT/Util.h @@ -0,0 +1,28 @@ +#pragma once + +#include +#include "AP_HAL_QURT_Namespace.h" + +class QURT::Util : public AP_HAL::Util +{ +public: + /* + set HW RTC in UTC microseconds + */ + void set_hw_rtc(uint64_t time_utc_usec) override {} + + /* + get system clock in UTC microseconds + */ + uint64_t get_hw_rtc() const override + { + return 0; + } + + uint32_t available_memory(void) override; + + /* + return state of safety switch, if applicable + */ + enum safety_state safety_switch_state(void) override; +}; diff --git a/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/inc/slpi_link.h b/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/inc/slpi_link.h new file mode 100644 index 00000000000000..863ad969de1caa --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/inc/slpi_link.h @@ -0,0 +1,22 @@ +#ifndef SLPI_LINK_H +#define SLPI_LINK_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +typedef void (*slpi_link_cb)(const uint8_t *data, uint32_t length_in_bytes); + +int slpi_link_init(bool enable_debug_messages, slpi_link_cb callback, const char *library_name); +int slpi_link_get_time_offset(void); +int slpi_link_send(const uint8_t *data, uint32_t length_in_bytes); +void slpi_link_reset(void); + +#ifdef __cplusplus +} +#endif + +#endif // SLPI_LINK_H diff --git a/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/src/slpi_link_stub.c b/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/src/slpi_link_stub.c new file mode 100644 index 00000000000000..e82fe7a190c219 --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/libslpi-link-api/src/slpi_link_stub.c @@ -0,0 +1,23 @@ + +#include "../inc/slpi_link.h" + +int slpi_link_init(bool enable_debug_messages, slpi_link_cb callback, const char *library_name) +{ + return 0; +} + +int slpi_link_get_time_offset(void) +{ + return 0; +} + +int slpi_link_send(const uint8_t *data, uint32_t length_in_bytes) +{ + return 0; +} + +void slpi_link_reset(void) +{ + return; +} + diff --git a/libraries/AP_HAL_QURT/ap_host/service/README.md b/libraries/AP_HAL_QURT/ap_host/service/README.md new file mode 100644 index 00000000000000..63c9d4f83d1148 --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/service/README.md @@ -0,0 +1,25 @@ +# ArduPilot on Voxl-2 + +This directory provides a systemd service file for ArduPilot on Voxl2 +by ModalAI + +To build use: + + - ./waf configure --board QURT + - ./waf copter + +To install copy files as follows: + + - voxl-ardupilot.service to /etc/systemd/system/ + - voxl-ardupilot to /usr/bin/ + - build/QURT/ardupilot to /usr/bin/ + - build/QURT/bin/arducopter to /usr/lib/rfsa/adsp/ArduPilot.so + - copy the right parameter file from Tools/Frame_params/ModalAI/ to /data/APM/defaults.parm + +You can then use: + + - systemctl enable voxl-ardupilot.service + - systemctl start voxl-ardupilot + + + diff --git a/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot b/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot new file mode 100755 index 00000000000000..441a53a413062f --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot @@ -0,0 +1,8 @@ +#!/bin/bash + +print_usage() { + echo -e "\nUsage: voxl-ardupilot" + exit 1 +} + +/usr/bin/ardupilot diff --git a/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot.service b/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot.service new file mode 100644 index 00000000000000..c1326183ac785d --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/service/voxl-ardupilot.service @@ -0,0 +1,13 @@ +[Unit] +Description=ArduPilot +After=sscrpcd.service +Requires=sscrpcd.service + +[Service] +Restart=always +RestartSec=1s +ExecStartPre=/bin/sleep 1 +ExecStart=/usr/bin/voxl-ardupilot + +[Install] +WantedBy=multi-user.target diff --git a/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.cpp b/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.cpp new file mode 100644 index 00000000000000..54ba54e184e5af --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.cpp @@ -0,0 +1,188 @@ +/* + get system network addresses + + based on code from Samba + + Copyright (C) Andrew Tridgell 1998 + Copyright (C) Jeremy Allison 2007 + Copyright (C) Jelmer Vernooij 2007 + + 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 +#include +#include +#include +#include +#include +#include +#include + +void freeifaddrs(struct ifaddrs *ifp) +{ + if (ifp != nullptr) { + free(ifp->ifa_name); + free(ifp->ifa_addr); + free(ifp->ifa_netmask); + free(ifp->ifa_dstaddr); + freeifaddrs(ifp->ifa_next); + free(ifp); + } +} + +static struct sockaddr *sockaddr_dup(struct sockaddr *sa) +{ + struct sockaddr *ret; + socklen_t socklen; + socklen = sizeof(struct sockaddr_storage); + ret = (struct sockaddr *)calloc(1, socklen); + if (ret == nullptr) { + return nullptr; + } + memcpy(ret, sa, socklen); + return ret; +} + +/* this works for Linux 2.2, Solaris 2.5, SunOS4, HPUX 10.20, OSF1 + V4.0, Ultrix 4.4, SCO Unix 3.2, IRIX 6.4 and FreeBSD 3.2. + + It probably also works on any BSD style system. */ + +int getifaddrs(struct ifaddrs **ifap) +{ + struct ifconf ifc; + char buff[8192]; + int fd, i, n; + struct ifreq *ifr=nullptr; + struct ifaddrs *curif; + struct ifaddrs *lastif = nullptr; + + *ifap = nullptr; + + if ((fd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) { + return -1; + } + + ifc.ifc_len = sizeof(buff); + ifc.ifc_buf = buff; + + if (ioctl(fd, SIOCGIFCONF, &ifc) != 0) { + close(fd); + return -1; + } + + ifr = ifc.ifc_req; + + n = ifc.ifc_len / sizeof(struct ifreq); + + /* Loop through interfaces, looking for ones that are broadcast capable */ + for (i=n-1; i>=0; i--) { + if (ioctl(fd, SIOCGIFFLAGS, &ifr[i]) == -1) { + freeifaddrs(*ifap); + close(fd); + return -1; + } + + curif = (struct ifaddrs *)calloc(1, sizeof(struct ifaddrs)); + if (curif == nullptr) { + freeifaddrs(*ifap); + close(fd); + return -1; + } + curif->ifa_name = strdup(ifr[i].ifr_name); + if (curif->ifa_name == nullptr) { + free(curif); + freeifaddrs(*ifap); + close(fd); + return -1; + } + curif->ifa_flags = ifr[i].ifr_flags; + curif->ifa_dstaddr = nullptr; + curif->ifa_data = nullptr; + curif->ifa_next = nullptr; + + curif->ifa_addr = nullptr; + if (ioctl(fd, SIOCGIFADDR, &ifr[i]) != -1) { + curif->ifa_addr = sockaddr_dup(&ifr[i].ifr_addr); + if (curif->ifa_addr == nullptr) { + free(curif->ifa_name); + free(curif); + freeifaddrs(*ifap); + close(fd); + return -1; + } + } + + curif->ifa_netmask = nullptr; + if (ioctl(fd, SIOCGIFNETMASK, &ifr[i]) != -1) { + curif->ifa_netmask = sockaddr_dup(&ifr[i].ifr_addr); + if (curif->ifa_netmask == nullptr) { + if (curif->ifa_addr != nullptr) { + free(curif->ifa_addr); + } + free(curif->ifa_name); + free(curif); + freeifaddrs(*ifap); + close(fd); + return -1; + } + } + + if (lastif == nullptr) { + *ifap = curif; + } else { + lastif->ifa_next = curif; + } + lastif = curif; + } + + close(fd); + + return 0; +} + +const char *get_ipv4_broadcast(void) +{ + struct ifaddrs *ifap = nullptr; + if (getifaddrs(&ifap) != 0) { + return nullptr; + } + struct ifaddrs *ia; + for (ia=ifap; ia; ia=ia->ifa_next) { + struct sockaddr_in *sin = (struct sockaddr_in *)ia->ifa_addr; + struct sockaddr_in *nmask = (struct sockaddr_in *)ia->ifa_netmask; + struct in_addr bcast; + if (strcmp(ia->ifa_name, "lo") == 0) { + continue; + } + bcast.s_addr = sin->sin_addr.s_addr | ~nmask->sin_addr.s_addr; + const char *ret = inet_ntoa(bcast); + freeifaddrs(ifap); + return ret; + } + freeifaddrs(ifap); + return nullptr; +} + +#ifdef MAIN_PROGRAM +int main(void) +{ + printf("%s\n", get_ipv4_broadcast()); + return 0; +} +#endif diff --git a/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.h b/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.h new file mode 100644 index 00000000000000..6fe41051956079 --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/src/getifaddrs.h @@ -0,0 +1,2 @@ +const char *get_ipv4_broadcast(void); + diff --git a/libraries/AP_HAL_QURT/ap_host/src/main.cpp b/libraries/AP_HAL_QURT/ap_host/src/main.cpp new file mode 100644 index 00000000000000..135c281195e7f8 --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/src/main.cpp @@ -0,0 +1,336 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "slpi_link.h" +#include "protocol.h" +#include "getifaddrs.h" + +volatile bool _running = false; +static bool enable_debug = false; +static bool enable_remote_debug = false; + +static int gcs_socket_fd; +static int obd_socket_fd; +static bool gcs_connected; +static bool obd_connected; +static struct sockaddr_in gcs_addr; +static struct sockaddr_in obd_addr; + +#define SO_NAME "ArduPilot.so" + +// setup for mavlink to localhost +#define MAVLINK_UDP_LOCALHOST 1 + +// Ports for onboard stream +#define MAVLINK_OBD_UDP_PORT_LOCAL 14556 +#define MAVLINK_OBD_UDP_PORT_REMOTE 14557 + +// Ports for external GCS stream +#define MAVLINK_GCS_UDP_PORT_LOCAL 14558 +#define MAVLINK_GCS_UDP_PORT_REMOTE 14559 + + +// directory for logs, parameters, terrain etc +#define DATA_DIRECTORY "/data/APM" + +static void shutdown_signal_handler(int signo) +{ + switch (signo) { + case SIGINT: // normal ctrl-c shutdown interrupt + _running = false; + fprintf(stderr, "\nreceived SIGINT Ctrl-C\n"); + break; + case SIGTERM: // catchable terminate signal + _running = false; + fprintf(stderr, "\nreceived SIGTERM\n"); + break; + case SIGHUP: + // terminal closed or disconnected, carry on anyway + fprintf(stderr, "\nreceived SIGHUP, continuing anyway\n"); + break; + default: + fprintf(stderr, "\nreceived signal %d\n", signo); + break; + } + return; +} + +static void slpi_init(void); + +static uint32_t num_params = 0; +static uint32_t expected_seq[MAX_MAVLINK_INSTANCES] = {0, 0}; + +static void receive_callback(const uint8_t *data, uint32_t length_in_bytes) +{ + if (enable_debug) { + printf("Got %u bytes in receive callback\n", length_in_bytes); + } + const auto *msg = (const struct qurt_rpc_msg *)data; + if (length_in_bytes < QURT_RPC_MSG_HEADER_LEN) { + printf("Invalid length_in_bytes %d", length_in_bytes); + return; + } + if (msg->data_length + QURT_RPC_MSG_HEADER_LEN != length_in_bytes) { + printf("Invalid lengths %d %d\n", msg->data_length, length_in_bytes); + return; + } + if (msg->inst < MAX_MAVLINK_INSTANCES) { + if (msg->seq != expected_seq[msg->inst]) { + printf("Invalid seq %u %u\n", msg->seq, expected_seq[msg->inst]); + } + } else { + printf("Invalid instance %u\n", msg->inst); + } + expected_seq[msg->inst] = msg->seq + 1; + + switch (msg->msg_id) { + case QURT_MSG_ID_MAVLINK_MSG: { + if (_running) { + if (msg->inst == 0) { + const auto bytes_sent = sendto(gcs_socket_fd, msg->data, msg->data_length, 0, (struct sockaddr *)&gcs_addr, sizeof(gcs_addr)); + if (bytes_sent <= 0) { + fprintf(stderr, "Send to GCS failed\n"); + } + } else if (msg->inst == 1) { + const auto bytes_sent = sendto(obd_socket_fd, msg->data, msg->data_length, 0, (struct sockaddr *)&obd_addr, sizeof(obd_addr)); + if (bytes_sent <= 0) { + fprintf(stderr, "Send to onboard failed\n"); + } + } + } + break; + } + case QURT_MSG_ID_REBOOT: { + printf("Rebooting\n"); + exit(0); + break; + } + default: + fprintf(stderr, "Got unknown message id %d\n", msg->msg_id); + break; + } +} + +static void slpi_init(void) +{ + int r; + while ((r=slpi_link_init(enable_remote_debug, &receive_callback, SO_NAME)) != 0) { + fprintf(stderr, "slpi_link_init error %d %s, retrying\n", r, strerror(errno)); + sleep(1); + } +} + +/* + setup directories for the hexagon code to use + */ +static void setup_directores(void) +{ + struct stat st; + + mkdir(DATA_DIRECTORY, 0777); + chmod(DATA_DIRECTORY, 0777); + if (stat(DATA_DIRECTORY, &st) != 0 || !S_ISDIR(st.st_mode)) { + printf("Unable to create %s", DATA_DIRECTORY); + exit(1); + } +} + +void *obd_recv_thread(void *) +{ + + uint32_t next_seq = 0; + + printf("Waiting for OBD receive\n"); + + while (_running) { + struct qurt_rpc_msg msg {}; + struct sockaddr_in from; + socklen_t fromlen = sizeof(from); + uint32_t bytes_received = recvfrom(obd_socket_fd, msg.data, sizeof(msg.data), 0, + (struct sockaddr*)&from, &fromlen); + if (bytes_received > 0 && !obd_connected) { + obd_addr = from; + obd_connected = true; + printf("Connnected to OBD addr %s\n", inet_ntoa(from.sin_addr)); + } + if (bytes_received < 0) { + fprintf(stderr, "OBD receive failed"); + continue; + } + if (bytes_received > sizeof(msg.data)) { + printf("Invalid bytes_received %d\n", bytes_received); + continue; + } + msg.msg_id = QURT_MSG_ID_MAVLINK_MSG; + msg.inst = 1; + msg.data_length = bytes_received; + msg.seq = next_seq++; + // printf("Message received. %d bytes\n", bytes_received); + if (slpi_link_send((const uint8_t*) &msg, bytes_received + QURT_RPC_MSG_HEADER_LEN)) { + fprintf(stderr, "slpi_link_send_data failed for instance 1\n"); + } + } + + return NULL; +} + +int main() +{ + printf("Starting up\n"); + + setup_directores(); + + // make the sigaction struct for shutdown signals + // sa_handler and sa_sigaction is a union, only set one + struct sigaction action; + action.sa_handler = shutdown_signal_handler; + sigemptyset(&action.sa_mask); + action.sa_flags = 0; + + // set actions + if (sigaction(SIGINT, &action, NULL) < 0) { + fprintf(stderr, "ERROR: failed to set sigaction\n"); + return -1; + } + if (sigaction(SIGTERM, &action, NULL) < 0) { + fprintf(stderr, "ERROR: failed to set sigaction\n"); + return -1; + } + if (sigaction(SIGHUP, &action, NULL) < 0) { + fprintf(stderr, "ERROR: failed to set sigaction\n"); + return -1; + } + + slpi_init(); + + //initialize sockets and structures + gcs_socket_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (gcs_socket_fd == -1) { + fprintf(stderr, "Could not create GCS socket"); + return -1; + } + obd_socket_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (obd_socket_fd == -1) { + fprintf(stderr, "Could not create OBD socket"); + return -1; + } + +#if MAVLINK_UDP_LOCALHOST + // send to mavlink router on localhost for GCS + gcs_addr.sin_addr.s_addr = htonl(INADDR_LOOPBACK); + gcs_addr.sin_family = AF_INET; + gcs_addr.sin_port = htons(MAVLINK_GCS_UDP_PORT_REMOTE); + + struct sockaddr_in gcs_local {}; + gcs_local.sin_addr.s_addr = INADDR_ANY; + gcs_local.sin_family = AF_INET; + gcs_local.sin_port = htons(MAVLINK_GCS_UDP_PORT_LOCAL); + + if (bind(gcs_socket_fd, (struct sockaddr *)&gcs_local, sizeof(gcs_local)) == 0) { + printf("Bind localhost GCS socket OK\n"); + } else { + printf("Bind localhost GCS socket failed: %s", strerror(errno)); + } + + // send to mavlink router on localhost for onboard stream + obd_addr.sin_addr.s_addr = htonl(INADDR_LOOPBACK); + obd_addr.sin_family = AF_INET; + obd_addr.sin_port = htons(MAVLINK_OBD_UDP_PORT_REMOTE); + + struct sockaddr_in obd_local {}; + obd_local.sin_addr.s_addr = INADDR_ANY; + obd_local.sin_family = AF_INET; + obd_local.sin_port = htons(MAVLINK_OBD_UDP_PORT_LOCAL); + + if (bind(obd_socket_fd, (struct sockaddr *)&obd_local, sizeof(obd_local)) == 0) { + printf("Bind localhost OBD socket OK\n"); + } else { + printf("Bind localhost OBD socket failed: %s", strerror(errno)); + } +#else + // broadcast directly to the local network broadcast address + const char *bcast_address = get_ipv4_broadcast(); + printf("Broadcast address=%s\n", bcast_address); + inet_aton(bcast_address, &gcs_addr.sin_addr); + gcs_addr.sin_family = AF_INET; + gcs_addr.sin_port = htons(UDP_OUT_PORT); + + int one = 1; + setsockopt(socket_fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); + + struct sockaddr_in any {}; + any.sin_addr.s_addr = INADDR_ANY; + any.sin_port = htons(15550); + + if (bind(socket_fd, (struct sockaddr *)&any, sizeof(any)) == 0) { + printf("Bind OK\n"); + } else { + printf("Bind failed: %s", strerror(errno)); + } +#endif + + printf("Enter ctrl-c to exit\n"); + _running = true; + + pthread_t obd_recv_thread_id; + pthread_attr_t obd_recv_thread_attr; + pthread_attr_init(&obd_recv_thread_attr); + pthread_create(&obd_recv_thread_id, &obd_recv_thread_attr, obd_recv_thread, NULL); + + uint32_t next_seq = 0; + + printf("Waiting for GCS receive\n"); + + while (_running) { + struct qurt_rpc_msg msg {}; + struct sockaddr_in from; + socklen_t fromlen = sizeof(from); + uint32_t bytes_received = recvfrom(gcs_socket_fd, msg.data, sizeof(msg.data), 0, + (struct sockaddr*)&from, &fromlen); + if (bytes_received > 0 && !gcs_connected) { + gcs_addr = from; + gcs_connected = true; + printf("Connnected to GCS at %s\n", inet_ntoa(from.sin_addr)); + } + if (bytes_received < 0) { + fprintf(stderr, "GCS receive failed"); + continue; + } + if (bytes_received > sizeof(msg.data)) { + printf("Invalid bytes_received %d\n", bytes_received); + continue; + } + msg.msg_id = QURT_MSG_ID_MAVLINK_MSG; + msg.inst = 0; + msg.data_length = bytes_received; + msg.seq = next_seq++; + // printf("Message received. %d bytes\n", bytes_received); + if (slpi_link_send((const uint8_t*) &msg, bytes_received + QURT_RPC_MSG_HEADER_LEN)) { + fprintf(stderr, "slpi_link_send_data failed for instance 0\n"); + } + } + + printf("Reseting SLPI\n"); + // Send reset to SLPI + slpi_link_reset(); + sleep(1); + + printf("Exiting\n"); + + return 0; +} + diff --git a/libraries/AP_HAL_QURT/ap_host/src/protocol.h b/libraries/AP_HAL_QURT/ap_host/src/protocol.h new file mode 100644 index 00000000000000..8e8782e192d717 --- /dev/null +++ b/libraries/AP_HAL_QURT/ap_host/src/protocol.h @@ -0,0 +1,20 @@ + +#include + +#pragma once + +#define QURT_MSG_ID_MAVLINK_MSG 1 +#define QURT_MSG_ID_REBOOT 2 + +#define MAX_MAVLINK_INSTANCES 2 + +struct __attribute__((__packed__)) qurt_rpc_msg { + uint8_t msg_id; + uint8_t inst; + uint16_t data_length; + uint32_t seq; + uint8_t data[300]; +}; + +#define QURT_RPC_MSG_HEADER_LEN 8 + diff --git a/libraries/AP_HAL_QURT/install.sh b/libraries/AP_HAL_QURT/install.sh new file mode 100755 index 00000000000000..b9bcc19bd0201e --- /dev/null +++ b/libraries/AP_HAL_QURT/install.sh @@ -0,0 +1,21 @@ +#!/bin/bash +# script to install ArduPilot on a voxl2 board +# this assumes you have already installed the voxl-ardupilot.service file +# and /usr/bin/voxl-ardupilot script + +[ $# -eq 1 ] || { + echo "install.sh IPADDRESS" + exit 1 +} + +DEST="$1" + +set -e + +echo "Installing ArduPilot on $DEST" + +rsync -a build/QURT/bin/arducopter $DEST:/usr/lib/rfsa/adsp/ArduPilot.so +rsync -a build/QURT/ardupilot $DEST:/usr/bin/ + +echo "Restarting ArduPilot" +ssh $DEST systemctl restart voxl-ardupilot diff --git a/libraries/AP_HAL_QURT/interface.h b/libraries/AP_HAL_QURT/interface.h new file mode 100644 index 00000000000000..fb3019f127a826 --- /dev/null +++ b/libraries/AP_HAL_QURT/interface.h @@ -0,0 +1,49 @@ +#define __EXPORT __attribute__ ((visibility ("default"))) + +#ifndef __cplusplus +#error "C++ should be defined!!!" +#endif + +#include + +// Functions that are called by the SLPI LINK server into AP client +extern "C" { + // Called by the SLPI LINK server to initialize and start AP + int slpi_link_client_init(void) __EXPORT; + + // Called by the SLPI LINK server when there is a new message for AP + int slpi_link_client_receive(const uint8_t *data, int data_len_in_bytes) __EXPORT; +} + +// Functions in SLPI LINK server that are called by AP client into DSP +extern "C" { + // Send a message to the applications processor + int sl_client_send_data(const uint8_t *data, int data_len_in_bytes); + + void sl_client_register_fatal_error_cb(void (*func)(void)); + + // Interrupt callback registration + int sl_client_register_interrupt_callback(int (*func)(int, void*, void*), void* arg); + + // Get DSP CPU utilization (0 - 100) + int sl_client_get_cpu_utilization(void); + + // I2C interface API + int sl_client_config_i2c_bus(uint8_t bus_number, uint8_t address, uint32_t frequency); + void sl_client_set_address_i2c_bus(int fd, uint8_t address); + int sl_client_i2c_transfer(int fd, const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len); + + // SPI interface API + int sl_client_spi_transfer(int fd, const uint8_t *send, uint8_t *recv, const unsigned len); + int sl_client_config_spi_bus(void); + + // UART interface API + int sl_client_config_uart(uint8_t port_number, uint32_t speed); + int sl_client_uart_write(int fd, const char *data, const unsigned data_len); + int sl_client_uart_read(int fd, char *buffer, const unsigned buffer_len); +} + +// IDs for serial ports +#define QURT_UART_GPS 6 +#define QURT_UART_RCIN 7 +#define QURT_UART_ESC 2 diff --git a/libraries/AP_HAL_QURT/malloc.cpp b/libraries/AP_HAL_QURT/malloc.cpp new file mode 100644 index 00000000000000..5a3c40ed2f5896 --- /dev/null +++ b/libraries/AP_HAL_QURT/malloc.cpp @@ -0,0 +1,84 @@ +/* + wrappers around core memory allocation functions from libc +*/ + +#include +#include +#include + +const std::nothrow_t std::nothrow; + +extern "C" { + void *fc_heap_alloc(size_t size); + void fc_heap_free(void* ptr); + + void *__wrap_malloc(size_t size); + void __wrap_free(void *ptr); + void *__wrap_calloc(size_t nmemb, size_t size); + void *__wrap_realloc(void *ptr, size_t size); +} + +#define HEAP_HEADER_MAGIC 0x1763247F + +typedef struct { + size_t size; + uint32_t magic; +} heap_header_t; + +void *__wrap_malloc(size_t size) +{ + // fc_heap_alloc guarantees zero filled memory + auto *ret = (heap_header_t *)fc_heap_alloc(size+sizeof(heap_header_t)); + if (ret == nullptr) { + return nullptr; + } + ret->size = size; + ret->magic = HEAP_HEADER_MAGIC; + return (void*)(ret+1); +} + +void __wrap_free(void *ptr) +{ + if (ptr == nullptr) { + return; + } + auto *h = ((heap_header_t *)ptr)-1; + if (h->magic != HEAP_HEADER_MAGIC) { + AP_HAL::panic("free: bad memory header 0x%x", unsigned(h->magic)); + } + fc_heap_free((void*)h); +} + +void *__wrap_calloc(size_t nmemb, size_t size) +{ + return __wrap_malloc(nmemb*size); +} + +void *__wrap_realloc(void *ptr, size_t size) +{ + if (size == 0) { + // a free + __wrap_free(ptr); + return nullptr; + } + if (ptr == nullptr) { + // new allocation + return __wrap_malloc(size); + } + + auto *h = ((heap_header_t *)ptr)-1; + if (h->magic != HEAP_HEADER_MAGIC) { + AP_HAL::panic("realloc: bad memory header 0x%x", unsigned(h->magic)); + } + + void *ret = __wrap_malloc(size); + if (ret == nullptr) { + return nullptr; + } + const size_t copy_size = size > h->size? h->size : size; + memcpy(ret, ptr, copy_size); + __wrap_free(ptr); + + return ret; +} + diff --git a/libraries/AP_HAL_QURT/packaging/.gitignore b/libraries/AP_HAL_QURT/packaging/.gitignore new file mode 100644 index 00000000000000..eaa90ca25d79ca --- /dev/null +++ b/libraries/AP_HAL_QURT/packaging/.gitignore @@ -0,0 +1,5 @@ +*.deb +pkg/DEB +pkg/data +pkg/control/control + diff --git a/libraries/AP_HAL_QURT/packaging/make_package.sh b/libraries/AP_HAL_QURT/packaging/make_package.sh new file mode 100755 index 00000000000000..241f4e93c2f3ac --- /dev/null +++ b/libraries/AP_HAL_QURT/packaging/make_package.sh @@ -0,0 +1,100 @@ +#!/bin/bash + +set -e # exit on error to prevent bad ipk from being generated + +[ $# -eq 2 ] || { + echo "Usage: make_package.sh VEHICLETYPE VEHICLE_BINARY" + exit 1 +} + +VEHICLETYPE="$1" +VEHICLE_BINARY="$2" + +[ -d $VEHICLETYPE ] || { + echo "Vehicle directory $VEHICLETYPE not found" + exit 1 +} + +# get version numbers +FW_MAJOR=$(grep FW_MAJOR $VEHICLETYPE/version.h | cut -d' ' -f3) +FW_MINOR=$(grep FW_MINOR $VEHICLETYPE/version.h | cut -d' ' -f3) +FW_PATCH=$(grep FW_PATCH $VEHICLETYPE/version.h | cut -d' ' -f3) +GIT_VERSION=$(git rev-parse HEAD | cut -c1-8) + +VERSION="${FW_MAJOR}.${FW_MINOR}.${FW_PATCH}-${GIT_VERSION}" + +cd libraries/AP_HAL_QURT/packaging + +cat pkg/control/control.in | sed "s/FW_VERSION/$VERSION/g" > pkg/control/control + +echo "Package Name: " $PACKAGE +echo "version Number: " $VERSION + +################################################################################ +# variables +################################################################################ +PACKAGE=$(cat pkg/control/control | grep "Package" | cut -d' ' -f 2) + +DATA_DIR=pkg/data +CONTROL_DIR=pkg/control +DEB_DIR=pkg/DEB + +################################################################################ +# start with a little cleanup to remove old files +################################################################################ +# remove data directory where 'make install' installed to +rm -rf $DATA_DIR +mkdir $DATA_DIR + +# remove deb packaging folders +rm -rf $DEB_DIR + +################################################################################ +## install compiled stuff into data directory +################################################################################ + +if [ -f ../../../build/QURT/ardupilot ] && \ + [ -f ../../../build/QURT/bin/$VEHICLE_BINARY ]; then + + # Copy the SLPI DSP AP library + mkdir -p $DATA_DIR/usr/lib/rfsa/adsp + cp ../../../build/QURT/bin/$VEHICLE_BINARY $DATA_DIR/usr/lib/rfsa/adsp/ArduPilot.so + + # Install executables + mkdir -p $DATA_DIR/usr/bin + cp ../../../build/QURT/ardupilot $DATA_DIR/usr/bin + cp ../ap_host/service/voxl-ardupilot $DATA_DIR/usr/bin + chmod a+x $DATA_DIR/usr/bin/ardupilot + chmod a+x $DATA_DIR/usr/bin/voxl-ardupilot + + # Create necessary directories for ArduPilot operation + mkdir -p $DATA_DIR/data/APM + + # Install default parameter files + cp ../../../Tools/Frame_params/ModalAI/*.parm $DATA_DIR/data/APM + + mkdir -p $DATA_DIR/etc/systemd/system/ + cp ../ap_host/service/voxl-ardupilot.service $DATA_DIR/etc/systemd/system/ + +else + echo "Error: Build artifacts not found" + exit 1 +fi + +################################################################################ +# make a DEB package +################################################################################ + +echo "starting building Debian Package" + +## make a folder dedicated to Deb building and copy the requires debian-binary file in +mkdir $DEB_DIR + +## copy the control stuff in +cp -rf $CONTROL_DIR/ $DEB_DIR/DEBIAN +cp -rf $DATA_DIR/* $DEB_DIR + +DEB_NAME="${PACKAGE}_${VEHICLETYPE}_${VERSION}_arm64.deb" +dpkg-deb --root-owner-group --build "${DEB_DIR}" "${DEB_NAME}" + +echo "DONE" diff --git a/libraries/AP_HAL_QURT/packaging/pkg/control/control.in b/libraries/AP_HAL_QURT/packaging/pkg/control/control.in new file mode 100644 index 00000000000000..1ad0196bdf57b2 --- /dev/null +++ b/libraries/AP_HAL_QURT/packaging/pkg/control/control.in @@ -0,0 +1,8 @@ +Package: voxl-ardupilot +Version: FW_VERSION +Section: devel +Priority: optional +Architecture: arm64 +Depends: modalai-slpi(>=1.1.19), libslpi-link +Maintainer: Eric Katzfey +Description: ModalAI ArduPilot flight controller diff --git a/libraries/AP_HAL_QURT/packaging/pkg/control/postinst b/libraries/AP_HAL_QURT/packaging/pkg/control/postinst new file mode 100755 index 00000000000000..04f668085e805a --- /dev/null +++ b/libraries/AP_HAL_QURT/packaging/pkg/control/postinst @@ -0,0 +1,39 @@ +#!/bin/bash + +# Create directory for APM use +cd /data +mkdir -p APM +chown system:system APM + +# Make sure the run scripts are executable +cd /usr/bin +chmod a+x voxl-ardupilot + +# Check to see if a DSP test signature exists +if /bin/ls /usr/lib/rfsa/adsp/testsig-*.so &> /dev/null; then + /bin/echo "Found DSP signature file" +else + /bin/echo "Could not find DSP signature file" + # Look for the DSP signature generation script + if [ -f /share/modalai/qrb5165-slpi-test-sig/generate-test-sig.sh ]; then + /bin/echo "Attempting to generate the DSP signature file" + # Automatically generate the test signature so that px4 can run on SLPI DSP + /share/modalai/qrb5165-slpi-test-sig/generate-test-sig.sh + else + /bin/echo "Could not find the DSP signature file generation script" + fi +fi + +# Always flush all changes to disk +/bin/sync + +cd - + +# try to reload services, but don't fail if it can't +set +e +if [ -f /bin/systemctl ]; then + systemctl daemon-reload +fi + +# exit 0 even if systemctl failed +exit 0 diff --git a/libraries/AP_HAL_QURT/replace.cpp b/libraries/AP_HAL_QURT/replace.cpp new file mode 100644 index 00000000000000..969f697620fb36 --- /dev/null +++ b/libraries/AP_HAL_QURT/replace.cpp @@ -0,0 +1,220 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "replace.h" +#include "interface.h" +#include "ap_host/src/protocol.h" + +extern "C" { + + // this is not declared in qurt headers + void HAP_debug(const char *msg, int level, const char *filename, int line); + + void HAP_printf(const char *file, int line, const char *format, ...) + { + va_list ap; + char buf[300]; + + va_start(ap, format); + vsnprintf(buf, sizeof(buf), format, ap); + va_end(ap); + HAP_debug(buf, 0, file, line); + //usleep(20000); + } + + /** + QURT doesn't have strnlen() + **/ + size_t strnlen(const char *s, size_t max) + { + size_t len; + + for (len = 0; len < max; len++) { + if (s[len] == '\0') { + break; + } + } + return len; + } + + int vasprintf(char **ptr, const char *format, va_list ap) + { + int ret; + va_list ap2; + + va_copy(ap2, ap); + ret = vsnprintf(nullptr, 0, format, ap2); + va_end(ap2); + if (ret < 0) { + return ret; + } + + (*ptr) = (char *)malloc(ret+1); + if (!*ptr) { + return -1; + } + + va_copy(ap2, ap); + ret = vsnprintf(*ptr, ret+1, format, ap2); + va_end(ap2); + + return ret; + } + + int asprintf(char **ptr, const char *format, ...) + { + va_list ap; + int ret; + + *ptr = nullptr; + va_start(ap, format); + ret = vasprintf(ptr, format, ap); + va_end(ap); + + return ret; + } + + void *memmem(const void *haystack, size_t haystacklen, + const void *needle, size_t needlelen) + { + if (needlelen == 0) { + return const_cast(haystack); + } + while (haystacklen >= needlelen) { + char *p = (char *)memchr(haystack, *(const char *)needle, + haystacklen-(needlelen-1)); + if (!p) { + return NULL; + } + if (memcmp(p, needle, needlelen) == 0) { + return p; + } + haystack = p+1; + haystacklen -= (p - (const char *)haystack) + 1; + } + return NULL; + } + + char *strndup(const char *s, size_t n) + { + char *ret; + + n = strnlen(s, n); + ret = (char*)malloc(n+1); + if (!ret) { + return NULL; + } + memcpy(ret, s, n); + ret[n] = 0; + + return ret; + } + + int pthread_cond_init(pthread_cond_t *cond, pthread_condattr_t *attr) + { + return 0; + } + + // INVESTIGATE: What is this needed on QURT? + int apfs_rename(const char *oldpath, const char *newpath) + { + return 0; + } + + // INVESTIGATE: Seems important :-) + int ArduPilot_main(int argc, const char *argv[]) + { + return 0; + } + + char *__wrap_strdup(const char *s); +} + +extern "C" int qurt_ardupilot_main(int argc, char* const argv[]); + +int slpi_link_client_init(void) +{ + HAP_PRINTF("About to call qurt_ardupilot_main %p", &qurt_ardupilot_main); + + qurt_ardupilot_main(0, NULL); + + return 0; +} + +typedef void (*mavlink_data_callback_t)(const struct qurt_rpc_msg *msg, void* p); + +static mavlink_data_callback_t mav_cb[MAX_MAVLINK_INSTANCES]; +static void *mav_cb_ptr[MAX_MAVLINK_INSTANCES]; + +void register_mavlink_data_callback(uint8_t instance, mavlink_data_callback_t func, void *p) +{ + if (instance < MAX_MAVLINK_INSTANCES) { + mav_cb[instance] = func; + mav_cb_ptr[instance] = p; + } else { + HAP_PRINTF("Error: Invalid mavlink instance %u", instance); + } +} + +int slpi_link_client_receive(const uint8_t *data, int data_len_in_bytes) +{ + if (data_len_in_bytes < QURT_RPC_MSG_HEADER_LEN) { + return 0; + } + const auto *msg = (struct qurt_rpc_msg *)data; + if (msg->data_length + QURT_RPC_MSG_HEADER_LEN != data_len_in_bytes) { + return 0; + } + + switch (msg->msg_id) { + case QURT_MSG_ID_MAVLINK_MSG: { + if ((msg->inst < MAX_MAVLINK_INSTANCES) && (mav_cb[msg->inst])) { + mav_cb[msg->inst](msg, mav_cb_ptr[msg->inst]); + } + break; + } + default: + HAP_PRINTF("Got unknown message id %d", msg->msg_id); + break; + } + + return 0; +} + +int __wrap_printf(const char *fmt, ...) +{ + va_list ap; + + char buf[300]; + va_start(ap, fmt); + vsnprintf(buf, sizeof(buf), fmt, ap); + va_end(ap); + HAP_PRINTF(buf); + + return 0; +} + +/* + free() on strdup return on QURT causes a memory fault + */ +char *__wrap_strdup(const char *s) +{ + return strndup(s, strlen(s)); +} + +/* + send a RPC message to the host + */ +bool qurt_rpc_send(struct qurt_rpc_msg &msg) +{ + if (msg.data_length > sizeof(msg.data)) { + return false; + } + return sl_client_send_data((const uint8_t*)&msg, msg.data_length + QURT_RPC_MSG_HEADER_LEN) >= 0; +} diff --git a/libraries/AP_HAL_QURT/replace.h b/libraries/AP_HAL_QURT/replace.h new file mode 100644 index 00000000000000..0fb943e6ee0a7a --- /dev/null +++ b/libraries/AP_HAL_QURT/replace.h @@ -0,0 +1,56 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#include +#include +#include "ap_host/src/protocol.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* + work around broken headers + */ +size_t strnlen(const char *s, size_t maxlen); +char *strndup(const char *s, size_t n); +int asprintf(char **, const char *, ...); +off_t lseek(int, off_t, int); +DIR *opendir (const char *); +int unlink(const char *pathname); +void *memmem(const void *haystack, size_t haystacklen, + const void *needle, size_t needlelen); + +//typedef int32_t pid_t; +pid_t getpid (void); + +void HAP_printf(const char *file, int line, const char *fmt, ...); + +int __wrap_printf(const char *fmt, ...); + +#ifdef __cplusplus +} +#endif + +#define HAP_PRINTF(...) HAP_printf(__FILE__, __LINE__, __VA_ARGS__) + +extern volatile int _last_dsp_line; +extern volatile const char *_last_dsp_file; +extern volatile uint32_t _last_counter; + +#define HAP_LINE() do { _last_dsp_line = __LINE__; _last_dsp_file = __FILE__; _last_counter++; } while (0) + +// missing defines from math.h +#define M_SQRT1_2 0.70710678118654752440 + +#ifdef __cplusplus +// send a message to the host +bool qurt_rpc_send(struct qurt_rpc_msg &msg); +#endif + diff --git a/libraries/AP_HAL_QURT/system.cpp b/libraries/AP_HAL_QURT/system.cpp new file mode 100644 index 00000000000000..f6d8b8fa5dd7a4 --- /dev/null +++ b/libraries/AP_HAL_QURT/system.cpp @@ -0,0 +1,65 @@ +#include +#include +#include +#include + +#include +#include + +#include "replace.h" +#include +#include + +extern const AP_HAL::HAL& hal; + +namespace AP_HAL +{ + +static struct { + uint64_t start_time; +} state; + +void init() +{ + state.start_time = micros64(); + // we don't want exceptions in flight code. That is the job of SITL + feclearexcept(FE_OVERFLOW | FE_DIVBYZERO | FE_INVALID); +} + +void panic(const char *errormsg, ...) +{ + char buf[200]; + va_list ap; + va_start(ap, errormsg); + vsnprintf(buf, sizeof(buf), errormsg, ap); + va_end(ap); + HAP_PRINTF("PANIC: %s", buf); + qurt_timer_sleep(100000); + exit(1); +} + +uint32_t micros() +{ + return micros64() & 0xFFFFFFFF; +} + +uint32_t millis() +{ + return millis64() & 0xFFFFFFFF; +} + +uint64_t micros64() +{ + struct timespec ts; + clock_gettime(CLOCK_MONOTONIC, &ts); + uint64_t ret = ts.tv_sec*1000*1000ULL + uint64_div1000(ts.tv_nsec); + ret -= state.start_time; + return ret; +} + +uint64_t millis64() +{ + return uint64_div1000(micros64()); +} + +} // namespace AP_HAL diff --git a/libraries/AP_HAL_SITL/AnalogIn.cpp b/libraries/AP_HAL_SITL/AnalogIn.cpp index 265092a072caef..6f3d17d9a91fee 100644 --- a/libraries/AP_HAL_SITL/AnalogIn.cpp +++ b/libraries/AP_HAL_SITL/AnalogIn.cpp @@ -62,14 +62,14 @@ float ADCSource::read_latest() { bool ADCSource::set_pin(uint8_t pin) { _pin = pin; - return true; + return pin != ANALOG_INPUT_NONE; } void AnalogIn::init() { } AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) { - return new ADCSource(_sitlState, pin); + return NEW_NOTHROW ADCSource(_sitlState, pin); } #endif diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index af8fc068759256..7011c2206b616b 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -74,9 +74,12 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, const uint64_t tx_deadline tx_item.setup = true; tx_item.index = _tx_frame_counter; tx_item.deadline = tx_deadline; - _tx_queue.emplace(tx_item); - _tx_frame_counter++; - stats.tx_requests++; + if (_tx_queue.push(tx_item)) { + _tx_frame_counter++; + stats.tx_requests++; + } else { + stats.tx_overflow++; + } _pollRead(); // Read poll is necessary because it can release the pending TX flag _pollWrite(); @@ -87,32 +90,32 @@ int16_t CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& out_timestamp_u CANIface::CanIOFlags& out_flags) { WITH_SEMAPHORE(sem); - if (_rx_queue.empty()) { + if (_rx_queue.is_empty()) { _pollRead(); // This allows to use the socket not calling poll() explicitly. - if (_rx_queue.empty()) { + if (_rx_queue.is_empty()) { return 0; } } { - const CanRxItem& rx = _rx_queue.front(); + const CanRxItem &rx = *_rx_queue[0]; out_frame = rx.frame; out_timestamp_us = rx.timestamp_us; out_flags = rx.flags; } - (void)_rx_queue.pop(); + IGNORE_RETURN(_rx_queue.pop()); return AP_HAL::CANIface::receive(out_frame, out_timestamp_us, out_flags); } bool CANIface::_hasReadyTx() { WITH_SEMAPHORE(sem); - return !_tx_queue.empty(); + return !_tx_queue.is_empty(); } bool CANIface::_hasReadyRx() { WITH_SEMAPHORE(sem); - return !_rx_queue.empty(); + return !_rx_queue.is_empty(); } void CANIface::_poll(bool read, bool write) @@ -137,7 +140,7 @@ void CANIface::_pollWrite() } while (_hasReadyTx()) { WITH_SEMAPHORE(sem); - const CanTxItem tx = _tx_queue.top(); + const CanTxItem tx = *_tx_queue[0]; const uint64_t curr_time = AP_HAL::micros64(); if (tx.deadline >= curr_time) { // hal.console->printf("%x TDEAD: %lu CURRT: %lu DEL: %lu\n",tx.frame.id, tx.deadline, curr_time, tx.deadline-curr_time); @@ -153,7 +156,7 @@ void CANIface::_pollWrite() } // Removing the frame from the queue - (void)_tx_queue.pop(); + IGNORE_RETURN(_tx_queue.pop()); } } @@ -180,15 +183,14 @@ void CANIface::flush_tx() WITH_SEMAPHORE(sem); do { _poll(true, true); - } while(!_tx_queue.empty()); + } while(!_tx_queue.is_empty()); } void CANIface::clear_rx() { WITH_SEMAPHORE(sem); // Clean Rx Queue - std::queue empty; - std::swap( _rx_queue, empty ); + _rx_queue.clear(); } void CANIface::_confirmSentFrame() @@ -215,12 +217,16 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) const SITL::SIM::CANTransport can_type = _sitl->can_transport[_self_index]; switch (can_type) { case SITL::SIM::CANTransport::MulticastUDP: - transport = new CAN_Multicast(); + transport = NEW_NOTHROW CAN_Multicast(); break; - case SITL::SIM::CANTransport::SocketCAN: #if HAL_CAN_WITH_SOCKETCAN - transport = new CAN_SocketCAN(); + case SITL::SIM::CANTransport::SocketCAN: + transport = NEW_NOTHROW CAN_SocketCAN(); + break; #endif + case SITL::SIM::CANTransport::None: + default: // if user supplies an invalid value for the parameter + transport = nullptr; break; } if (transport == nullptr) { diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index 5876217ecc4c4b..7e02e61be30eb4 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -20,9 +20,8 @@ #if HAL_NUM_CAN_IFACES #include - +#include #include -#include #include #include #include @@ -127,8 +126,8 @@ class CANIface: public AP_HAL::CANIface { AP_HAL::BinarySemaphore *sem_handle; pollfd _pollfd; - std::priority_queue _tx_queue; - std::queue _rx_queue; + ObjectArray _tx_queue{100}; + ObjectArray _rx_queue{100}; /* bus statistics diff --git a/libraries/AP_HAL_SITL/DSP.cpp b/libraries/AP_HAL_SITL/DSP.cpp index 2bb4d8131ad34a..8227a5d087fb33 100644 --- a/libraries/AP_HAL_SITL/DSP.cpp +++ b/libraries/AP_HAL_SITL/DSP.cpp @@ -39,7 +39,7 @@ extern const AP_HAL::HAL& hal; // initialize the FFT state machine 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, sliding_window_size); + DSP::FFTWindowStateSITL* fft = NEW_NOTHROW 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; @@ -71,7 +71,7 @@ DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sampl return; } - buf = new complexf[window_size]; + buf = NEW_NOTHROW complexf[window_size]; } DSP::FFTWindowStateSITL::~FFTWindowStateSITL() diff --git a/libraries/AP_HAL_SITL/GPIO.cpp b/libraries/AP_HAL_SITL/GPIO.cpp index 3fe8db8cc6a102..4a83c2bf206d0b 100644 --- a/libraries/AP_HAL_SITL/GPIO.cpp +++ b/libraries/AP_HAL_SITL/GPIO.cpp @@ -82,7 +82,7 @@ void GPIO::toggle(uint8_t pin) /* Alternative interface: */ AP_HAL::DigitalSource* GPIO::channel(uint16_t n) { if (n < 16) { // (ie. sizeof(pin_mask)*8) - return new DigitalSource(static_cast(n)); + return NEW_NOTHROW DigitalSource(static_cast(n)); } else { return nullptr; } diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index ab4a67dd83fe26..be72972e269d4e 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -206,6 +206,11 @@ bool HAL_SITL::run_in_maintenance_mode() const } #endif +uint32_t HAL_SITL::get_uart_output_full_queue_count() const +{ + return _sitl_state->_serial_0_outqueue_full_count; +} + 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 4ddc20b2cb6663..495405c62bfa47 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.h +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.h @@ -41,6 +41,8 @@ class HAL_SITL : public AP_HAL::HAL { bool run_in_maintenance_mode() const; #endif + uint32_t get_uart_output_full_queue_count() const; + private: HALSITL::SITL_State *_sitl_state; diff --git a/libraries/AP_HAL_SITL/I2CDevice.cpp b/libraries/AP_HAL_SITL/I2CDevice.cpp index 7b7b2d5914fb85..28c1f11e4073e7 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.cpp +++ b/libraries/AP_HAL_SITL/I2CDevice.cpp @@ -67,7 +67,7 @@ int I2CBus::_ioctl(uint8_t ioctl_number, void *data) AP_HAL::Device::PeriodicHandle I2CBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) { // mostly swiped from ChibiOS: - I2CBus::callback_info *callback = new I2CBus::callback_info; + I2CBus::callback_info *callback = NEW_NOTHROW I2CBus::callback_info; if (callback == nullptr) { return nullptr; } @@ -116,7 +116,7 @@ I2CDeviceManager::get_device(uint8_t bus, if (bus >= ARRAY_SIZE(buses)) { return AP_HAL::OwnPtr(nullptr); } - auto dev = AP_HAL::OwnPtr(new I2CDevice(buses[bus], address)); + auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(buses[bus], address)); return dev; } diff --git a/libraries/AP_HAL_SITL/RCOutput.cpp b/libraries/AP_HAL_SITL/RCOutput.cpp index 423c4ea57e4d77..40677c66ec3161 100644 --- a/libraries/AP_HAL_SITL/RCOutput.cpp +++ b/libraries/AP_HAL_SITL/RCOutput.cpp @@ -101,7 +101,7 @@ void RCOutput::push(void) SITL::SIM *sitl = AP::sitl(); if (sitl && sitl->esc_telem) { if (esc_telem == nullptr) { - esc_telem = new AP_ESC_Telem_SITL; + esc_telem = NEW_NOTHROW AP_ESC_Telem_SITL; } if (esc_telem != nullptr) { esc_telem->update(); diff --git a/libraries/AP_HAL_SITL/RCOutput.h b/libraries/AP_HAL_SITL/RCOutput.h index fe6324d4ba2390..81924047943876 100644 --- a/libraries/AP_HAL_SITL/RCOutput.h +++ b/libraries/AP_HAL_SITL/RCOutput.h @@ -54,7 +54,7 @@ class HALSITL::RCOutput : public AP_HAL::RCOutput { bool _corked; uint16_t _pending[SITL_NUM_CHANNELS]; - AP_HAL::Util::safety_state safety_state; + AP_HAL::Util::safety_state safety_state = AP_HAL::Util::safety_state::SAFETY_DISARMED; }; #endif diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index a65e56310e5b8e..c90b40218b3e30 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -112,7 +112,7 @@ void SITL_State::init(int argc, char * const argv[]) { printf("Running Instance: %d\n", _instance); - sitl_model = new SimMCast(""); + sitl_model = NEW_NOTHROW SimMCast(""); _sitl = AP::sitl(); @@ -124,10 +124,9 @@ void SITL_State::wait_clock(uint64_t wait_time_usec) { while (AP_HAL::micros64() < wait_time_usec) { struct sitl_input input {}; - sitl_model->update(input); + sitl_model->update(input); // delays up to 1 millisecond sim_update(); update_voltage_current(input, 0); - usleep(100); } } @@ -195,7 +194,7 @@ void SimMCast::multicast_read(void) printf("Waiting for multicast state\n"); } struct SITL::sitl_fdm state; - while (sock.recv((void*)&state, sizeof(state), 0) != sizeof(state)) { + while (sock.recv((void*)&state, sizeof(state), 1) != sizeof(state)) { // nop } if (_sitl->state.timestamp_us == 0) { diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 8bf0abf8a57638..4850e40b027a40 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -79,9 +79,11 @@ void SITL_State::_sitl_setup() if (_sitl != nullptr) { // setup some initial values _update_airspeed(0); +#if AP_SIM_SOLOGIMBAL_ENABLED if (enable_gimbal) { - gimbal = new SITL::Gimbal(_sitl->state); + gimbal = NEW_NOTHROW SITL::SoloGimbal(); } +#endif sitl_model->set_buzzer(&_sitl->buzzer_sim); sitl_model->set_sprayer(&_sitl->sprayer_sim); @@ -183,11 +185,14 @@ void SITL_State::wait_clock(uint64_t wait_time_usec) // conditions. if (speedup > 1 && hal.scheduler->in_main_thread()) { while (true) { - const int queue_length = ((HALSITL::UARTDriver*)hal.serial(0))->get_system_outqueue_length(); + HALSITL::UARTDriver *uart = (HALSITL::UARTDriver*)hal.serial(0); + const int queue_length = uart->get_system_outqueue_length(); // ::fprintf(stderr, "queue_length=%d\n", (signed)queue_length); if (queue_length < 1024) { break; } + _serial_0_outqueue_full_count++; + uart->handle_reading_from_device_to_readbuffer(); usleep(1000); } } @@ -327,9 +332,21 @@ void SITL_State::_simulator_servos(struct sitl_input &input) 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); + uint32_t dt_us = now - last_wind_update_us; + if (dt_us > 1000) { + last_wind_update_us = now; + // slew wind based on the configured time constant + const float dt = dt_us * 1.0e-6; + const float tc = MAX(_sitl->wind_change_tc, 0.1); + const float alpha = calc_lowpass_alpha_dt(dt, 1.0/tc); + _sitl->wind_speed_active += (_sitl->wind_speed - _sitl->wind_speed_active) * alpha; + _sitl->wind_direction_active += (wrap_180(_sitl->wind_direction - _sitl->wind_direction_active)) * alpha; + _sitl->wind_dir_z_active += (_sitl->wind_dir_z - _sitl->wind_dir_z_active) * alpha; + _sitl->wind_direction_active = wrap_180(_sitl->wind_direction_active); + } + wind_speed = _sitl->wind_speed_active; + wind_direction = _sitl->wind_direction_active; + wind_dir_z = _sitl->wind_dir_z_active; // pass wind into simulators using different wind types via param SIM_WIND_T*. switch (_sitl->wind_type) { diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 91f0a85739c456..b5452aceda2dfc 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -1,6 +1,7 @@ #pragma once #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -40,7 +41,7 @@ class HALSITL::SITL_State : public SITL_State_Common { "tcp:7", "tcp:8", }; - std::vector cmdline_param; + ObjectArray cmdline_param{100}; /* parse a home location string */ static bool parse_home(const char *home_str, @@ -107,9 +108,7 @@ class HALSITL::SITL_State : public SITL_State_Common { uint32_t time_delta_wind; uint32_t delayed_time_wind; uint32_t wind_start_delay_micros; - - // simulated GPS devices - SITL::GPS *gps[2]; // constrained by # of parameter sets + uint32_t last_wind_update_us; // returns a voltage between 0V to 5V which should appear as the // voltage from the sensor diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index de94ee65900be5..47a625d4d77670 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -25,20 +25,20 @@ extern const AP_HAL::HAL& hal; using namespace HALSITL; #define streq(a, b) (!strcmp(a, b)) -SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg) +SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg, const uint8_t portNumber) { if (streq(name, "benewake_tf02")) { if (benewake_tf02 != nullptr) { AP_HAL::panic("Only one benewake_tf02 at a time"); } - benewake_tf02 = new SITL::RF_Benewake_TF02(); + benewake_tf02 = NEW_NOTHROW SITL::RF_Benewake_TF02(); return benewake_tf02; #if !defined(HAL_BUILD_AP_PERIPH) } else if (streq(name, "vicon")) { if (vicon != nullptr) { AP_HAL::panic("Only one vicon system at a time"); } - vicon = new SITL::Vicon(); + vicon = NEW_NOTHROW SITL::Vicon(); return vicon; #endif #if HAL_SIM_ADSB_ENABLED @@ -47,7 +47,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const // will cope with begin() being called multiple times on a // serial port if (adsb == nullptr) { - adsb = new SITL::ADSB(); + adsb = NEW_NOTHROW SITL::ADSB(); } sitl_model->set_adsb(adsb); return adsb; @@ -56,97 +56,97 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (ainsteinlrd1 != nullptr) { AP_HAL::panic("Only one ainsteinlrd1 at a time"); } - ainsteinlrd1 = new SITL::RF_Ainstein_LR_D1(); + ainsteinlrd1 = NEW_NOTHROW SITL::RF_Ainstein_LR_D1(); return ainsteinlrd1; } else if (streq(name, "benewake_tf03")) { if (benewake_tf03 != nullptr) { AP_HAL::panic("Only one benewake_tf03 at a time"); } - benewake_tf03 = new SITL::RF_Benewake_TF03(); + benewake_tf03 = NEW_NOTHROW SITL::RF_Benewake_TF03(); return benewake_tf03; } else if (streq(name, "benewake_tfmini")) { if (benewake_tfmini != nullptr) { AP_HAL::panic("Only one benewake_tfmini at a time"); } - benewake_tfmini = new SITL::RF_Benewake_TFmini(); + benewake_tfmini = NEW_NOTHROW SITL::RF_Benewake_TFmini(); return benewake_tfmini; } else if (streq(name, "nooploop_tofsense")) { if (nooploop != nullptr) { AP_HAL::panic("Only one nooploop_tofsense at a time"); } - nooploop = new SITL::RF_Nooploop(); + nooploop = NEW_NOTHROW SITL::RF_Nooploop(); return nooploop; } 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(); + teraranger_serial = NEW_NOTHROW SITL::RF_TeraRanger_Serial(); return teraranger_serial; } else if (streq(name, "lightwareserial")) { if (lightwareserial != nullptr) { AP_HAL::panic("Only one lightwareserial at a time"); } - lightwareserial = new SITL::RF_LightWareSerial(); + lightwareserial = NEW_NOTHROW SITL::RF_LightWareSerial(); return lightwareserial; } else if (streq(name, "lightwareserial-binary")) { if (lightwareserial_binary != nullptr) { AP_HAL::panic("Only one lightwareserial-binary at a time"); } - lightwareserial_binary = new SITL::RF_LightWareSerialBinary(); + lightwareserial_binary = NEW_NOTHROW SITL::RF_LightWareSerialBinary(); return lightwareserial_binary; } else if (streq(name, "lanbao")) { if (lanbao != nullptr) { AP_HAL::panic("Only one lanbao at a time"); } - lanbao = new SITL::RF_Lanbao(); + lanbao = NEW_NOTHROW SITL::RF_Lanbao(); return lanbao; } else if (streq(name, "blping")) { if (blping != nullptr) { AP_HAL::panic("Only one blping at a time"); } - blping = new SITL::RF_BLping(); + blping = NEW_NOTHROW SITL::RF_BLping(); return blping; } else if (streq(name, "leddarone")) { if (leddarone != nullptr) { AP_HAL::panic("Only one leddarone at a time"); } - leddarone = new SITL::RF_LeddarOne(); + leddarone = NEW_NOTHROW SITL::RF_LeddarOne(); return leddarone; } else if (streq(name, "rds02uf")) { if (rds02uf != nullptr) { AP_HAL::panic("Only one rds02uf at a time"); } - rds02uf = new SITL::RF_RDS02UF(); + rds02uf = NEW_NOTHROW SITL::RF_RDS02UF(); return rds02uf; } else if (streq(name, "USD1_v0")) { if (USD1_v0 != nullptr) { AP_HAL::panic("Only one USD1_v0 at a time"); } - USD1_v0 = new SITL::RF_USD1_v0(); + USD1_v0 = NEW_NOTHROW SITL::RF_USD1_v0(); return USD1_v0; } else if (streq(name, "USD1_v1")) { if (USD1_v1 != nullptr) { AP_HAL::panic("Only one USD1_v1 at a time"); } - USD1_v1 = new SITL::RF_USD1_v1(); + USD1_v1 = NEW_NOTHROW SITL::RF_USD1_v1(); return USD1_v1; } else if (streq(name, "maxsonarseriallv")) { if (maxsonarseriallv != nullptr) { AP_HAL::panic("Only one maxsonarseriallv at a time"); } - maxsonarseriallv = new SITL::RF_MaxsonarSerialLV(); + maxsonarseriallv = NEW_NOTHROW SITL::RF_MaxsonarSerialLV(); return maxsonarseriallv; } else if (streq(name, "wasp")) { if (wasp != nullptr) { AP_HAL::panic("Only one wasp at a time"); } - wasp = new SITL::RF_Wasp(); + wasp = NEW_NOTHROW SITL::RF_Wasp(); return wasp; } else if (streq(name, "nmea")) { if (nmea != nullptr) { AP_HAL::panic("Only one nmea at a time"); } - nmea = new SITL::RF_NMEA(); + nmea = NEW_NOTHROW SITL::RF_NMEA(); return nmea; #if !defined(HAL_BUILD_AP_PERIPH) @@ -154,34 +154,34 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (rf_mavlink != nullptr) { AP_HAL::panic("Only one rf_mavlink at a time"); } - rf_mavlink = new SITL::RF_MAVLink(); + rf_mavlink = NEW_NOTHROW SITL::RF_MAVLink(); return rf_mavlink; #endif } else if (streq(name, "frsky-d")) { if (frsky_d != nullptr) { AP_HAL::panic("Only one frsky_d at a time"); } - frsky_d = new SITL::Frsky_D(); + frsky_d = NEW_NOTHROW SITL::Frsky_D(); return frsky_d; // } else if (streq(name, "frsky-SPort")) { // if (frsky_sport != nullptr) { // AP_HAL::panic("Only one frsky_sport at a time"); // } - // frsky_sport = new SITL::Frsky_SPort(); + // frsky_sport = NEW_NOTHROW SITL::Frsky_SPort(); // return frsky_sport; // } else if (streq(name, "frsky-SPortPassthrough")) { // if (frsky_sport_passthrough != nullptr) { // AP_HAL::panic("Only one frsky_sport passthrough at a time"); // } - // frsky_sport = new SITL::Frsky_SPortPassthrough(); + // frsky_sport = NEW_NOTHROW SITL::Frsky_SPortPassthrough(); // return frsky_sportpassthrough; #if AP_SIM_CRSF_ENABLED } else if (streq(name, "crsf")) { if (crsf != nullptr) { AP_HAL::panic("Only one crsf at a time"); } - crsf = new SITL::CRSF(); + crsf = NEW_NOTHROW SITL::CRSF(); return crsf; #endif #if HAL_SIM_PS_RPLIDARA2_ENABLED @@ -189,7 +189,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (rplidara2 != nullptr) { AP_HAL::panic("Only one rplidara2 at a time"); } - rplidara2 = new SITL::PS_RPLidarA2(); + rplidara2 = NEW_NOTHROW SITL::PS_RPLidarA2(); return rplidara2; #endif #if HAL_SIM_PS_RPLIDARA1_ENABLED @@ -197,7 +197,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (rplidara1 != nullptr) { AP_HAL::panic("Only one rplidara1 at a time"); } - rplidara1 = new SITL::PS_RPLidarA1(); + rplidara1 = NEW_NOTHROW SITL::PS_RPLidarA1(); return rplidara1; #endif #if HAL_SIM_PS_TERARANGERTOWER_ENABLED @@ -205,7 +205,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (terarangertower != nullptr) { AP_HAL::panic("Only one terarangertower at a time"); } - terarangertower = new SITL::PS_TeraRangerTower(); + terarangertower = NEW_NOTHROW SITL::PS_TeraRangerTower(); return terarangertower; #endif #if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED @@ -213,7 +213,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (sf45b != nullptr) { AP_HAL::panic("Only one sf45b at a time"); } - sf45b = new SITL::PS_LightWare_SF45B(); + sf45b = NEW_NOTHROW SITL::PS_LightWare_SF45B(); return sf45b; #endif #if AP_SIM_ADSB_SAGETECH_MXS_ENABLED @@ -221,9 +221,9 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (sagetech_mxs != nullptr) { AP_HAL::panic("Only one sagetech_mxs at a time"); } - sagetech_mxs = new SITL::ADSB_Sagetech_MXS(); + sagetech_mxs = NEW_NOTHROW SITL::ADSB_Sagetech_MXS(); if (adsb == nullptr) { - adsb = new SITL::ADSB(); + adsb = NEW_NOTHROW SITL::ADSB(); } sitl_model->set_adsb(adsb); return sagetech_mxs; @@ -248,51 +248,51 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (jre != nullptr) { AP_HAL::panic("Only one jre at a time"); } - jre = new SITL::RF_JRE(); + jre = NEW_NOTHROW SITL::RF_JRE(); return jre; } else if (streq(name, "gyus42v2")) { if (gyus42v2 != nullptr) { AP_HAL::panic("Only one gyus42v2 at a time"); } - gyus42v2 = new SITL::RF_GYUS42v2(); + gyus42v2 = NEW_NOTHROW SITL::RF_GYUS42v2(); return gyus42v2; } else if (streq(name, "megasquirt")) { if (efi_ms != nullptr) { AP_HAL::panic("Only one megasquirt at a time"); } - efi_ms = new SITL::EFI_MegaSquirt(); + efi_ms = NEW_NOTHROW SITL::EFI_MegaSquirt(); return efi_ms; } else if (streq(name, "hirth")) { if (efi_hirth != nullptr) { AP_HAL::panic("Only one hirth at a time"); } - efi_hirth = new SITL::EFI_Hirth(); + efi_hirth = NEW_NOTHROW SITL::EFI_Hirth(); return efi_hirth; } else if (streq(name, "VectorNav")) { if (vectornav != nullptr) { AP_HAL::panic("Only one VectorNav at a time"); } - vectornav = new SITL::VectorNav(); + vectornav = NEW_NOTHROW SITL::VectorNav(); return vectornav; } else if (streq(name, "MicroStrain5")) { if (microstrain5 != nullptr) { AP_HAL::panic("Only one MicroStrain5 at a time"); } - microstrain5 = new SITL::MicroStrain5(); + microstrain5 = NEW_NOTHROW SITL::MicroStrain5(); return microstrain5; } else if (streq(name, "MicroStrain7")) { if (microstrain7 != nullptr) { AP_HAL::panic("Only one MicroStrain7 at a time"); } - microstrain7 = new SITL::MicroStrain7(); + microstrain7 = NEW_NOTHROW SITL::MicroStrain7(); return microstrain7; } else if (streq(name, "ILabs")) { if (inertiallabs != nullptr) { AP_HAL::panic("Only one InertialLabs INS at a time"); } - inertiallabs = new SITL::InertialLabs(); + inertiallabs = NEW_NOTHROW SITL::InertialLabs(); return inertiallabs; #if HAL_SIM_AIS_ENABLED @@ -300,20 +300,24 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const if (ais != nullptr) { AP_HAL::panic("Only one AIS at a time"); } - ais = new SITL::AIS(); + ais = NEW_NOTHROW SITL::AIS(); return ais; #endif } else if (strncmp(name, "gps", 3) == 0) { - const char *p = strchr(name, ':'); - if (p == nullptr) { - AP_HAL::panic("Need a GPS number (e.g. sim:gps:1)"); - } - uint8_t x = atoi(p+1); + uint8_t x = atoi(arg); if (x <= 0 || x > ARRAY_SIZE(gps)) { - AP_HAL::panic("Bad GPS number %u", x); + AP_HAL::panic("Bad GPS number %u (%s)", x, arg); } - gps[x-1] = new SITL::GPS(x-1); + gps[x-1] = NEW_NOTHROW SITL::GPS(x-1); return gps[x-1]; + } else if (streq(name, "ELRS")) { + // Only allocate if not done already + // MAVLink serial ports have begin called several times + if (elrs == nullptr) { + elrs = NEW_NOTHROW SITL::ELRS(portNumber, this); + _sitl->set_stop_MAVLink_sim_state(); + } + return elrs; } AP_HAL::panic("unknown simulated device: %s", name); @@ -324,9 +328,9 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const */ void SITL_State_Common::sim_update(void) { -#if HAL_SIM_GIMBAL_ENABLED +#if AP_SIM_SOLOGIMBAL_ENABLED if (gimbal != nullptr) { - gimbal->update(); + gimbal->update(*sitl_model); } #endif #if HAL_SIM_ADSB_ENABLED @@ -481,6 +485,10 @@ void SITL_State_Common::sim_update(void) gps[i]->update(); } } + + if (elrs != nullptr) { + elrs->update(); + } } /* diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 19e7356c3b6055..472f7dfefa6601 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -9,7 +9,7 @@ #define SITL_SERVO_PORT 20722 #include -#include +#include #include #include #include @@ -53,6 +53,8 @@ #include #include +#include + #include "AP_HAL_SITL.h" #include "AP_HAL_SITL_Namespace.h" #include "HAL_SITL_Class.h" @@ -88,7 +90,7 @@ class HALSITL::SITL_State_Common { // create a simulated serial device; type of device is given by // name parameter - SITL::SerialDevice *create_serial_sim(const char *name, const char *arg); + SITL::SerialDevice *create_serial_sim(const char *name, const char *arg, const uint8_t portNumber); // simulated airspeed, sonar and battery monitor float sonar_pin_voltage; // pin 0 @@ -102,11 +104,11 @@ class HALSITL::SITL_State_Common { bool new_rc_input; uint16_t pwm_output[SITL_NUM_CHANNELS]; bool output_ready = false; - -#if HAL_SIM_GIMBAL_ENABLED + +#if AP_SIM_SOLOGIMBAL_ENABLED // simulated gimbal bool enable_gimbal; - SITL::Gimbal *gimbal; + SITL::SoloGimbal *gimbal; #endif #if HAL_SIM_ADSB_ENABLED @@ -229,7 +231,10 @@ class HALSITL::SITL_State_Common { const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; // simulated GPS devices - SITL::GPS *gps[2]; // constrained by # of parameter sets + SITL::GPS *gps[AP_SIM_MAX_GPS_SENSORS]; // constrained by # of parameter sets + + // Simulated ELRS radio + SITL::ELRS *elrs; // returns a voltage between 0V to 5V which should appear as the // voltage from the sensor @@ -242,6 +247,10 @@ class HALSITL::SITL_State_Common { void multicast_state_open(void); void multicast_state_send(void); + // number of times we have paused the simulation for 1ms because + // the TCP queue is full: + uint32_t _serial_0_outqueue_full_count; + protected: enum vehicle_type _vehicle; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 1f8d3935df8d4e..042bb2ce7f2128 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -14,6 +14,7 @@ #include #include #include +#include #include #include #include @@ -38,6 +39,8 @@ #include #include #include +#include + #include #include @@ -93,16 +96,6 @@ void SITL_State::_usage(void) "\t--gimbal enable simulated MAVLink gimbal\n" "\t--autotest-dir DIR set directory for additional files\n" "\t--defaults path set path to defaults file\n" - "\t--uartA device (deprecated) set device string for SERIAL0\n" - "\t--uartC device (deprecated) set device string for SERIAL1\n" // ordering captures the historical use of uartB as SERIAL3 - "\t--uartD device (deprecated) set device string for SERIAL2\n" - "\t--uartB device (deprecated) set device string for SERIAL3\n" - "\t--uartE device (deprecated) set device string for SERIAL4\n" - "\t--uartF device (deprecated) set device string for SERIAL5\n" - "\t--uartG device (deprecated) set device string for SERIAL6\n" - "\t--uartH device (deprecated) set device string for SERIAL7\n" - "\t--uartI device (deprecated) set device string for SERIAL8\n" - "\t--uartJ device (deprecated) set device string for SERIAL9\n" "\t--serial0 device set device string for SERIAL0\n" "\t--serial1 device set device string for SERIAL1\n" "\t--serial2 device set device string for SERIAL2\n" @@ -113,6 +106,7 @@ void SITL_State::_usage(void) "\t--serial7 device set device string for SERIAL7\n" "\t--serial8 device set device string for SERIAL8\n" "\t--serial9 device set device string for SERIAL9\n" + "\t--uartA device alias for --serial0 (do not use)\n" "\t--rtscts enable rtscts on serial ports (default false)\n" "\t--base-port PORT set port num for base port(default 5670) must be before -I option\n" "\t--rc-in-port PORT set port num for rc in\n" @@ -142,6 +136,7 @@ static const struct { { "djix", MultiCopter::create }, { "cwx", MultiCopter::create }, { "hexa", MultiCopter::create }, + { "hexax", MultiCopter::create }, { "hexa-cwx", MultiCopter::create }, { "hexa-dji", MultiCopter::create }, { "octa", MultiCopter::create }, @@ -170,6 +165,7 @@ static const struct { { "last_letter", last_letter::create }, { "tracker", Tracker::create }, { "balloon", Balloon::create }, + { "glider", Glider::create }, { "plane", Plane::create }, { "calibration", Calibration::create }, { "vectored", Submarine::create }, @@ -183,6 +179,9 @@ static const struct { { "JSON", JSON::create }, { "blimp", Blimp::create }, { "novehicle", NoVehicle::create }, +#if AP_SIM_STRATOBLIMP_ENABLED + { "stratoblimp", StratoBlimp::create }, +#endif }; void SITL_State::_set_signal_handlers(void) const @@ -307,7 +306,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"enable-fgview", false, 0, CMDLINE_FGVIEW}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, - {"uartA", true, 0, CMDLINE_UARTA}, + // {"uartA", true, 0, CMDLINE_UARTA}, // alias for serial0 {"uartB", true, 0, CMDLINE_UARTB}, {"uartC", true, 0, CMDLINE_UARTC}, {"uartD", true, 0, CMDLINE_UARTD}, @@ -318,6 +317,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"uartI", true, 0, CMDLINE_UARTI}, {"uartJ", true, 0, CMDLINE_UARTJ}, {"serial0", true, 0, CMDLINE_SERIAL0}, + {"uartA", true, 0, CMDLINE_SERIAL0}, // for MissionPlanner compatibility {"serial1", true, 0, CMDLINE_SERIAL1}, {"serial2", true, 0, CMDLINE_SERIAL2}, {"serial3", true, 0, CMDLINE_SERIAL3}, @@ -384,13 +384,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case 's': speedup = strtof(gopt.optarg, nullptr); temp_cmdline_param = {"SIM_SPEEDUP", speedup}; - cmdline_param.push_back(temp_cmdline_param); + cmdline_param.push(temp_cmdline_param); printf("Setting SIM_SPEEDUP=%f\n", speedup); break; case 'r': sim_rate_hz = strtof(gopt.optarg, nullptr); temp_cmdline_param = {"SIM_RATE_HZ", sim_rate_hz}; - cmdline_param.push_back(temp_cmdline_param); + cmdline_param.push(temp_cmdline_param); printf("Setting SIM_RATE_HZ=%f\n", sim_rate_hz); break; case 'C': @@ -439,9 +439,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case 'v': vehicle_str = gopt.optarg; break; +#if AP_SIM_SOLOGIMBAL_ENABLED case CMDLINE_GIMBAL: enable_gimbal = true; break; +#endif case CMDLINE_FGVIEW: _use_fg_view = true; break; @@ -466,11 +468,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) static const uint8_t mapping[] = { 0, 3, 1, 2, 4, 5, 6, 7, 8, 9 }; int serial_idx = mapping[uart_idx]; char uart_letter = (char)(uart_idx)+'A'; - printf("WARNING: deprecated option --uart%c will be removed in a " - "future release. Use --serial%d instead.\n", - uart_letter, serial_idx); - _serial_path[serial_idx] = gopt.optarg; - break; + printf("ERROR: Removed option --uart%c supplied. " + "Use --serial%d instead.\n", uart_letter, serial_idx); + exit(1); } case CMDLINE_SERIAL0: case CMDLINE_SERIAL1: @@ -515,7 +515,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) exit(1); } temp_cmdline_param = {"SYSID_THISMAV", static_cast(sysid)}; - cmdline_param.push_back(temp_cmdline_param); + cmdline_param.push(temp_cmdline_param); printf("Setting SYSID_THISMAV=%d\n", sysid); break; } diff --git a/libraries/AP_HAL_SITL/SPIDevice.cpp b/libraries/AP_HAL_SITL/SPIDevice.cpp index 2ea7a4e22ae5f3..9e082a53e98359 100644 --- a/libraries/AP_HAL_SITL/SPIDevice.cpp +++ b/libraries/AP_HAL_SITL/SPIDevice.cpp @@ -73,7 +73,7 @@ int SPIBus::_ioctl(uint8_t cs_pin, uint8_t ioctl_number, void *data) AP_HAL::Device::PeriodicHandle SPIBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) { // mostly swiped from ChibiOS: - SPIBus::callback_info *callback = new SPIBus::callback_info; + SPIBus::callback_info *callback = NEW_NOTHROW SPIBus::callback_info; if (callback == nullptr) { return nullptr; } @@ -150,7 +150,7 @@ SPIDeviceManager::get_device(const char *name) } if (busp == nullptr) { // create a new one - busp = new SPIBus(desc.bus); + busp = NEW_NOTHROW SPIBus(desc.bus); if (busp == nullptr) { return nullptr; } @@ -160,7 +160,7 @@ SPIDeviceManager::get_device(const char *name) buses = busp; } - return AP_HAL::OwnPtr(new SPIDevice(*busp, desc)); + return AP_HAL::OwnPtr(NEW_NOTHROW SPIDevice(*busp, desc)); } // void SPIDeviceManager::_timer_tick() diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 0ae924f15ae1aa..ccc40042e8ea99 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -7,7 +7,7 @@ #include #include #include -#if defined (__clang__) || (defined (__APPLE__) && defined (__MACH__)) +#if defined (__clang__) || (defined (__APPLE__) && defined (__MACH__)) || defined (__OpenBSD__) #include #else #include @@ -351,7 +351,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ pthread_t thread {}; const uint32_t alloc_stack = MAX(size_t(PTHREAD_STACK_MIN),stack_size); - struct thread_attr *a = new struct thread_attr; + struct thread_attr *a = NEW_NOTHROW struct thread_attr; if (!a) { return false; } @@ -385,7 +385,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ goto failed; } -#if !defined(__APPLE__) +#if !defined(__APPLE__) && !defined(__OpenBSD__) pthread_setname_np(thread, name); #endif diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index cb645d11f625e1..358fb614824129 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -77,11 +77,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) if (strcmp(path, "GPS1") == 0) { /* gps */ _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("gps:1", ""); + _sim_serial_device = _sitlState->create_serial_sim("gps", "1", _portNumber); } else if (strcmp(path, "GPS2") == 0) { /* 2nd gps */ _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("gps:2", ""); + _sim_serial_device = _sitlState->create_serial_sim("gps", "2", _portNumber); } else { /* parse type:args:flags string for path. For example: @@ -109,7 +109,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) // add sanity check here that we're doing mavlink on this port? ::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber); _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr); + _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr, _portNumber); } else #endif if (strcmp(devtype, "tcp") == 0) { @@ -132,7 +132,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) if (!_connected) { ::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber); _connected = true; - _sim_serial_device = _sitlState->create_serial_sim(args1, args2); + _sim_serial_device = _sitlState->create_serial_sim(args1, args2, _portNumber); } } else if (strcmp(devtype, "udpclient") == 0) { // udp client connection @@ -402,20 +402,18 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) */ void UARTDriver::_tcp_start_client(const char *address, uint16_t port) { - int one=1; - struct sockaddr_in sockaddr; - int ret; if (_connected) { return; } _use_send_recv = true; - + if (_fd != -1) { close(_fd); } + struct sockaddr_in sockaddr; memset(&sockaddr,0,sizeof(sockaddr)); #ifdef HAVE_SOCK_SIN_LEN @@ -425,22 +423,36 @@ void UARTDriver::_tcp_start_client(const char *address, uint16_t port) sockaddr.sin_family = AF_INET; sockaddr.sin_addr.s_addr = inet_addr(address); - _fd = socket(AF_INET, SOCK_STREAM, 0); - if (_fd == -1) { - fprintf(stderr, "socket failed - %s\n", strerror(errno)); - exit(1); - } - ret = fcntl(_fd, F_SETFD, FD_CLOEXEC); - if (ret == -1) { - fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); - exit(1); - } + constexpr auto one=1; + int ret; + for (int attempt = 0; attempt < 3; ++attempt) { + _fd = socket(AF_INET, SOCK_STREAM, 0); + if (_fd == -1) { + fprintf(stderr, "socket failed - %s\n", strerror(errno)); + exit(1); + } + ret = fcntl(_fd, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); + exit(1); + } - /* we want to be able to re-use ports quickly */ - setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + /* we want to be able to re-use ports quickly */ + setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + + ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == 0) { + break; + } + fprintf(stderr, "connect failed on port %u - %s at %d retrying\n", + (unsigned) ntohs(sockaddr.sin_port), strerror(errno), AP_HAL::millis()); + close(_fd); + // If connection failed, wait for a bit before retrying + sleep(1); + } - ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); if (ret == -1) { + close(_fd); fprintf(stderr, "connect failed on port %u - %s\n", (unsigned)ntohs(sockaddr.sin_port), strerror(errno)); @@ -451,6 +463,7 @@ void UARTDriver::_tcp_start_client(const char *address, uint16_t port) setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); fcntl(_fd, F_SETFD, FD_CLOEXEC); _connected = true; + fprintf(stdout, "New remote connection on serial port %u, p %u at %d\n", _portNumber, (unsigned) ntohs(sockaddr.sin_port), AP_HAL::millis()); } @@ -701,6 +714,8 @@ bool UARTDriver::set_unbuffered_writes(bool on) { v &= ~O_NONBLOCK; #if defined(__APPLE__) && defined(__MACH__) fcntl(_fd, F_SETFL | F_NOCACHE, v | O_SYNC); +#elif defined(__OpenBSD__) + fcntl(_fd, F_SETFL, v | O_SYNC); #else fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC); #endif @@ -815,13 +830,11 @@ void UARTDriver::handle_writing_from_writebuffer_to_device() SITL::SIM *_sitl = AP::sitl(); if (_sitl && _sitl->telem_baudlimit_enable) { // limit byte rate to configured baudrate - uint32_t now = AP_HAL::micros(); - float dt = 1.0e-6 * (now - last_write_tick_us); - max_bytes = _uart_baudrate * dt / 10; + // Byte rate is bit rate divided by 10. 8 bits of data + start/stop bits + max_bytes = baud_limits.write.max_bytes(float(_uart_baudrate) * 0.1); if (max_bytes == 0) { return; } - last_write_tick_us = now; } #endif if (_packetise) { @@ -884,13 +897,11 @@ void UARTDriver::handle_reading_from_device_to_readbuffer() SITL::SIM *_sitl = AP::sitl(); if (_sitl && _sitl->telem_baudlimit_enable) { // limit byte rate to configured baudrate - uint32_t now = AP_HAL::micros(); - float dt = 1.0e-6 * (now - last_read_tick_us); - max_bytes = _uart_baudrate * dt / 10; + // Byte rate is bit rate divided by 10. 8 bits of data + start/stop bits + max_bytes = baud_limits.read.max_bytes(float(_uart_baudrate) * 0.1); if (max_bytes == 0) { return; } - last_read_tick_us = now; } #endif diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 88803c9ddbe40f..4fc517d2c5931d 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -9,6 +9,7 @@ #include #include #include +#include #include @@ -113,8 +114,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { uint16_t _mc_myport; // for baud-rate limiting: - uint32_t last_read_tick_us; - uint32_t last_write_tick_us; + struct { + DataRateLimit write; + DataRateLimit read; + } baud_limits; HAL_Semaphore write_mtx; @@ -158,6 +161,7 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { // statistics uint32_t _tx_stats_bytes; uint32_t _rx_stats_bytes; + }; #endif diff --git a/libraries/AP_HAL_SITL/UART_utils.cpp b/libraries/AP_HAL_SITL/UART_utils.cpp index f0a7d06c70873c..ca4628c57baf1e 100644 --- a/libraries/AP_HAL_SITL/UART_utils.cpp +++ b/libraries/AP_HAL_SITL/UART_utils.cpp @@ -19,7 +19,7 @@ #include "UARTDriver.h" -#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(__APPLE__) +#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(__APPLE__) || defined(__OpenBSD__) #define USE_TERMIOS #endif @@ -73,6 +73,7 @@ void HALSITL::UARTDriver::configure_parity(uint8_t v) if (_fd < 0) { return; } + UARTDriver::parity = v; #ifdef USE_TERMIOS struct termios t; diff --git a/libraries/AP_HAL_SITL/Util.cpp b/libraries/AP_HAL_SITL/Util.cpp index f5c6bbeeaaef9a..753e97b8ce4ab4 100644 --- a/libraries/AP_HAL_SITL/Util.cpp +++ b/libraries/AP_HAL_SITL/Util.cpp @@ -85,68 +85,6 @@ bool HALSITL::Util::get_system_id(char buf[50]) return get_system_id_unformatted((uint8_t *)buf, len); } -#ifdef ENABLE_HEAP -void *HALSITL::Util::allocate_heap_memory(size_t size) -{ - struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap)); - if (new_heap != nullptr) { - new_heap->scripting_max_heap_size = size; - new_heap->current_heap_usage = 0; - } - return (void *)new_heap; -} - -void *HALSITL::Util::heap_realloc(void *heap_ptr, void *ptr, size_t old_size, size_t new_size) -{ - if (heap_ptr == nullptr) { - return nullptr; - } - - struct heap *heapp = (struct heap*)heap_ptr; - - // extract appropriate headers - size_t old_size_header = 0; - heap_allocation_header *old_header = nullptr; - if (ptr != nullptr) { - old_header = ((heap_allocation_header *)ptr) - 1; - old_size_header = old_header->allocation_size; -#if !defined(HAL_BUILD_AP_PERIPH) - if (old_size_header != old_size && new_size != 0) { - INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); - } -#endif - } - - if ((heapp->current_heap_usage + new_size - old_size) > heapp->scripting_max_heap_size) { - // fail the allocation as we don't have the memory. Note that we don't simulate fragmentation - return nullptr; - } - - heapp->current_heap_usage -= old_size_header; - if (new_size == 0) { - free(old_header); - return nullptr; - } - - heap_allocation_header *new_header = (heap_allocation_header *)malloc(new_size + sizeof(heap_allocation_header)); - if (new_header == nullptr) { - // total failure to allocate, this is very surprising in SITL - return nullptr; - } - heapp->current_heap_usage += new_size; - new_header->allocation_size = new_size; - void *new_mem = new_header + 1; - - if (ptr == nullptr) { - return new_mem; - } - memcpy(new_mem, ptr, old_size > new_size ? new_size : old_size); - free(old_header); - return new_mem; -} - -#endif // ENABLE_HEAP - #if !defined(HAL_BUILD_AP_PERIPH) enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void) { @@ -160,8 +98,11 @@ enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void) void HALSITL::Util::set_cmdline_parameters() { - for (auto param: sitlState->cmdline_param) { - AP_Param::set_default_by_name(param.name, param.value); + for (uint16_t i=0; icmdline_param.available(); i++) { + const auto param = sitlState->cmdline_param[i]; + if (param != nullptr) { + AP_Param::set_default_by_name(param->name, param->value); + } } } #endif diff --git a/libraries/AP_HAL_SITL/Util.h b/libraries/AP_HAL_SITL/Util.h index 588fc2a25a311c..66cfd2a97737ea 100644 --- a/libraries/AP_HAL_SITL/Util.h +++ b/libraries/AP_HAL_SITL/Util.h @@ -17,16 +17,12 @@ class HALSITL::Util : public AP_HAL::Util { Util(SITL_State *_sitlState) : sitlState(_sitlState) {} - bool run_debug_shell(AP_HAL::BetterStream *stream) override { - return false; - } - /** how much free memory do we have in bytes. */ uint32_t available_memory(void) override { - // SITL is assumed to always have plenty of memory. Return 128k for now - return 0x20000; + // SITL is assumed to always have plenty of memory. Return 512k for now + return 512*1024; } // get path to custom defaults file for AP_Param @@ -47,12 +43,6 @@ class HALSITL::Util : public AP_HAL::Util { bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; void dump_stack_trace(); -#ifdef ENABLE_HEAP - // heap functions, note that a heap once alloc'd cannot be dealloc'd - void *allocate_heap_memory(size_t size) override; - void *heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size) override; -#endif // ENABLE_HEAP - #ifdef WITH_SITL_TONEALARM bool toneAlarm_init(uint8_t types) override { return _toneAlarm.init(); } void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override { @@ -94,17 +84,6 @@ class HALSITL::Util : public AP_HAL::Util { static ToneAlarm_SF _toneAlarm; #endif -#ifdef ENABLE_HEAP - struct heap_allocation_header { - size_t allocation_size; // size of allocated block, not including this header - }; - - struct heap { - size_t scripting_max_heap_size; - size_t current_heap_usage; - }; -#endif // ENABLE_HEAP - int saved_argc; char *const *saved_argv; diff --git a/libraries/AP_HAL_SITL/sitl_airspeed.cpp b/libraries/AP_HAL_SITL/sitl_airspeed.cpp index 2c149c1916a7ba..cf3e666aa16566 100644 --- a/libraries/AP_HAL_SITL/sitl_airspeed.cpp +++ b/libraries/AP_HAL_SITL/sitl_airspeed.cpp @@ -24,27 +24,6 @@ using namespace HALSITL; #define VOLTS_TO_PASCAL 819 #define PASCAL_TO_VOLTS(_p) (_p/VOLTS_TO_PASCAL) -// 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 */ @@ -52,7 +31,7 @@ void SITL_State::_update_airspeed(float true_airspeed) { for (uint8_t i=0; iairspeed[i]; - float airspeed = true_airspeed / get_EAS2TAS(_sitl->state.altitude); + float airspeed = true_airspeed / AP_Baro::get_EAS2TAS_for_alt_amsl(_sitl->state.altitude); const float diff_pressure = sq(airspeed) / arspd.ratio; float airspeed_raw; diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index 81c5b4941b0c07..2bbcbb8e73a6aa 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -65,13 +65,24 @@ 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 struct stat statbuf; + const char *custom_scripts_dir_path = getenv("AP_SCRIPTS_DIR_PATH"); + char *custom_scripts_dir_path_pattern = nullptr; + if (custom_scripts_dir_path != nullptr) { + if (asprintf(&custom_scripts_dir_path_pattern, "%s/%%s", custom_scripts_dir_path) == -1) { + custom_scripts_dir_path_pattern = nullptr; + } + } const char *paths[] { + custom_scripts_dir_path_pattern, "Tools/scripts/%s", "APM/Tools/scripts/%s", // for autotest server "../Tools/scripts/%s", // when run from e.g. ArduCopter subdirectory }; char buffer[60]; for (uint8_t i=0; i #ifndef HAL_HOTT_TELEM_ENABLED -#define HAL_HOTT_TELEM_ENABLED 1 +#define HAL_HOTT_TELEM_ENABLED BOARD_FLASH_SIZE > 2048 #endif #if HAL_HOTT_TELEM_ENABLED diff --git a/libraries/AP_IBus_Telem/AP_IBus_Telem.cpp b/libraries/AP_IBus_Telem/AP_IBus_Telem.cpp new file mode 100644 index 00000000000000..0b0d31a600ce5c --- /dev/null +++ b/libraries/AP_IBus_Telem/AP_IBus_Telem.cpp @@ -0,0 +1,792 @@ +/* + 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 . + + + i-BUS telemetry for FlySky/Turnigy receivers and other peripherals + (eg iA6B, iA10) by Nicole Ashley . + + Originally based on work by Jan Verhulst: + https://github.com/ArduPilot/ardupilot/pull/16545 + + Libraries used for reference and inspiration: + + * iBUStelemetry + https://github.com/Hrastovc/iBUStelemetry + + * IBusBM + https://github.com/bmellink/IBusBM + + * BetaFlight + https://github.com/betaflight/betaflight/blob/master/src/main/telemetry/ibus_shared.c + */ + +#include + +#if AP_IBUS_TELEM_ENABLED + +#include +#include +#include +#include +#include +#include + +// 2-byte values +#define IBUS_SENSOR_TYPE_TEMPERATURE 0x01 // Temperature (in 0.1 degrees, where 0=-40'C) +#define IBUS_SENSOR_TYPE_RPM_FLYSKY 0x02 // FlySky-specific throttle value +#define IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE 0x03 // External voltage (in centivolts, so 1450 is 14.50V) +#define IBUS_SENSOR_TYPE_AVERAGE_CELL_VOLTAGE 0x04 // Avg cell voltage (in centivolts, so 1450 is 14.50V) +#define IBUS_SENSOR_TYPE_BATTERY_CURRENT 0x05 // Battery current (centi-amps) +#define IBUS_SENSOR_TYPE_FUEL 0x06 // Remaining battery percentage +#define IBUS_SENSOR_TYPE_RPM 0x07 // Throttle value (in 0.01, so 1200 is 12.00%) +#define IBUS_SENSOR_TYPE_COMPASS_HEADING 0x08 // Heading (0-360 degrees) +#define IBUS_SENSOR_TYPE_CLIMB_RATE 0x09 // Climb rate (cm/s) +#define IBUS_SENSOR_TYPE_COG 0x0a // Course over ground (centidegrees, so 27015 is 270.15 degrees) +#define IBUS_SENSOR_TYPE_GPS_STATUS 0x0b // GPS status (2 values: fix type, and number of satellites) +#define IBUS_SENSOR_TYPE_ACC_X 0x0c // Acc X (cm/s) +#define IBUS_SENSOR_TYPE_ACC_Y 0x0d // Acc Y (cm/s) +#define IBUS_SENSOR_TYPE_ACC_Z 0x0e // Acc Z (cm/s) +#define IBUS_SENSOR_TYPE_ROLL 0x0f // Roll (centidegrees) +#define IBUS_SENSOR_TYPE_PITCH 0x10 // Pitch (centidegrees) +#define IBUS_SENSOR_TYPE_YAW 0x11 // Yaw (centidegrees) +#define IBUS_SENSOR_TYPE_VERTICAL_SPEED 0x12 // Vertical speed (cm/s) +#define IBUS_SENSOR_TYPE_GROUND_SPEED 0x13 // Speed (cm/s) +#define IBUS_SENSOR_TYPE_GPS_DIST 0x14 // Distance from home (m) +#define IBUS_SENSOR_TYPE_ARMED 0x15 // Armed / unarmed (1 = armed, 0 = unarmed) +#define IBUS_SENSOR_TYPE_FLIGHT_MODE 0x16 // Flight mode +#define IBUS_SENSOR_TYPE_ODO1 0x7c // Odometer1 +#define IBUS_SENSOR_TYPE_ODO2 0x7d // Odometer2 +#define IBUS_SENSOR_TYPE_SPEED 0x7e // Speed km/h +#define IBUS_SENSOR_TYPE_ALT_FLYSKY 0xf9 // FlySky-specific altitude (metres) + +// 4-byte values +#define IBUS_SENSOR_TYPE_TEMPERATURE_PRESSURE 0x41 // Combined temperature & pressure value +#define IBUS_SENSOR_TYPE_GPS_LAT 0x80 // WGS84 in degrees * 1E7 +#define IBUS_SENSOR_TYPE_GPS_LNG 0x81 // WGS84 in degrees * 1E7 +#define IBUS_SENSOR_TYPE_GPS_ALT 0x82 // GPS (cm) +#define IBUS_SENSOR_TYPE_ALT 0x83 // Alt (cm) +#define IBUS_SENSOR_TYPE_ALT_MAX 0x84 // MaxAlt (cm) + +// i-BUS vehicle modes +#define IBUS_VEHICLE_MODE_STAB 0 +#define IBUS_VEHICLE_MODE_ACRO 1 +#define IBUS_VEHICLE_MODE_AHOLD 2 +#define IBUS_VEHICLE_MODE_AUTO 3 +#define IBUS_VEHICLE_MODE_GUIDED 4 +#define IBUS_VEHICLE_MODE_LOITER 5 +#define IBUS_VEHICLE_MODE_RTL 6 +#define IBUS_VEHICLE_MODE_CIRCLE 7 +#define IBUS_VEHICLE_MODE_PHOLD 8 +#define IBUS_VEHICLE_MODE_LAND 9 +#define IBUS_VEHICLE_MODE_UNKNOWN 255 // Must be positive and 0 is already used; out of range blanks the value + +// All the sensors we can accurately provide are listed here. +// i-BUS will generally only query up to 15 sensors, so subjectively +// higher-value sensors are sorted to the top to make the most of a +// small telemetry window. In the future these could be configurable. +static const AP_IBus_Telem::SensorDefinition sensors[] { +#if AP_ARMING_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_ARMED, .sensor_length = 2}, +#endif + {.sensor_type = IBUS_SENSOR_TYPE_FLIGHT_MODE, .sensor_length = 2}, +#if AP_GPS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_GPS_STATUS, .sensor_length = 2}, +#endif +#if AP_BATTERY_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_FUEL, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE, .sensor_length = 2}, +#endif +#if AP_BARO_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_ALT, .sensor_length = 4}, +#endif +#if AP_AHRS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_GPS_DIST, .sensor_length = 2}, +#endif +#if AP_BARO_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_CLIMB_RATE, .sensor_length = 2}, +#endif +#if AP_GPS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_GROUND_SPEED, .sensor_length = 2}, +#endif +#if AP_AHRS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_ROLL, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_PITCH, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_YAW, .sensor_length = 2}, +#endif +#if AP_AIRSPEED_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_SPEED, .sensor_length = 2}, +#endif +#if AP_BARO_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_TEMPERATURE_PRESSURE, .sensor_length = 4}, +#endif +#if AP_RPM_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_RPM, .sensor_length = 2}, +#endif +#if AP_BATTERY_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_BATTERY_CURRENT, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_AVERAGE_CELL_VOLTAGE, .sensor_length = 2}, +#endif +#if AP_AHRS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_COMPASS_HEADING, .sensor_length = 2}, +#endif +#if AP_GPS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_COG, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_GPS_LAT, .sensor_length = 4}, + {.sensor_type = IBUS_SENSOR_TYPE_GPS_LNG, .sensor_length = 4}, + {.sensor_type = IBUS_SENSOR_TYPE_GPS_ALT, .sensor_length = 4}, +#endif +#if AP_AHRS_ENABLED + {.sensor_type = IBUS_SENSOR_TYPE_ACC_X, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_ACC_Y, .sensor_length = 2}, + {.sensor_type = IBUS_SENSOR_TYPE_ACC_Z, .sensor_length = 2}, +#endif +}; + +#if APM_BUILD_TYPE(APM_BUILD_Rover) + +/* Rover modes: + MANUAL = 0 + ACRO = 1 + STEERING = 3 + HOLD = 4 + LOITER = 5 + FOLLOW = 6 + SIMPLE = 7 + DOCK = 8 + CIRCLE = 9 + AUTO = 10 + RTL = 11 + SMART_RTL = 12 + GUIDED = 15 + INITIALISING = 16 +*/ +static const AP_IBus_Telem::ModeMap mode_map[] { + {.ap_mode = 1, .ibus_mode = IBUS_VEHICLE_MODE_ACRO}, + {.ap_mode = 4, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, + {.ap_mode = 5, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 9, .ibus_mode = IBUS_VEHICLE_MODE_CIRCLE}, + {.ap_mode = 10, .ibus_mode = IBUS_VEHICLE_MODE_AUTO}, + {.ap_mode = 11, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 12, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 15, .ibus_mode = IBUS_VEHICLE_MODE_GUIDED}, +}; + +#elif APM_BUILD_COPTER_OR_HELI + +/* Copter modes: + STABILIZE = 0 + ACRO = 1 + ALT_HOLD = 2 + AUTO = 3 + GUIDED = 4 + LOITER = 5 + RTL = 6 + CIRCLE = 7 + LAND = 9 + DRIFT = 11 + SPORT = 13 + FLIP = 14 + AUTOTUNE = 15 + POSHOLD = 16 + BRAKE = 17 + THROW = 18 + AVOID_ADSB = 19 + GUIDED_NOGPS = 20 + SMART_RTL = 21 + FLOWHOLD = 22 + FOLLOW = 23 + ZIGZAG = 24 + SYSTEMID = 25 + AUTOROTATE = 26 + AUTO_RTL = 27 + TURTLE = 28 +*/ +static const AP_IBus_Telem::ModeMap mode_map[] { + {.ap_mode = 0, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 1, .ibus_mode = IBUS_VEHICLE_MODE_ACRO}, + {.ap_mode = 2, .ibus_mode = IBUS_VEHICLE_MODE_AHOLD}, + {.ap_mode = 3, .ibus_mode = IBUS_VEHICLE_MODE_AUTO}, + {.ap_mode = 4, .ibus_mode = IBUS_VEHICLE_MODE_GUIDED}, + {.ap_mode = 5, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 6, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 7, .ibus_mode = IBUS_VEHICLE_MODE_CIRCLE}, + {.ap_mode = 9, .ibus_mode = IBUS_VEHICLE_MODE_LAND}, + {.ap_mode = 16, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, + {.ap_mode = 21, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 22, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, + {.ap_mode = 27, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, +}; + +#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) + +/* Plane modes: + MANUAL = 0 + CIRCLE = 1 + STABILIZE = 2 + TRAINING = 3 + ACRO = 4 + FLY_BY_WIRE_A = 5 + FLY_BY_WIRE_B = 6 + CRUISE = 7 + AUTOTUNE = 8 + AUTO = 10 + RTL = 11 + LOITER = 12 + TAKEOFF = 13 + AVOID_ADSB = 14 + GUIDED = 15 + INITIALISING = 16 + QSTABILIZE = 17 + QHOVER = 18 + QLOITER = 19 + QLAND = 20 + QRTL = 21 + QAUTOTUNE = 22 + QACRO = 23 + THERMAL = 24 + LOITER_ALT_QLAND = 25 +*/ +static const AP_IBus_Telem::ModeMap mode_map[] { + {.ap_mode = 1, .ibus_mode = IBUS_VEHICLE_MODE_CIRCLE}, + {.ap_mode = 2, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 4, .ibus_mode = IBUS_VEHICLE_MODE_ACRO}, + {.ap_mode = 5, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 6, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 7, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 10, .ibus_mode = IBUS_VEHICLE_MODE_AUTO}, + {.ap_mode = 11, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 12, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 13, .ibus_mode = IBUS_VEHICLE_MODE_AUTO}, + {.ap_mode = 15, .ibus_mode = IBUS_VEHICLE_MODE_GUIDED}, + {.ap_mode = 17, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 18, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, + {.ap_mode = 19, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 20, .ibus_mode = IBUS_VEHICLE_MODE_LAND}, + {.ap_mode = 21, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 23, .ibus_mode = IBUS_VEHICLE_MODE_ACRO}, + {.ap_mode = 25, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, +}; + +#elif APM_BUILD_TYPE(APM_BUILD_ArduSub) + +/* Submarine modes: + STABILIZE = 0 + ACRO = 1 + ALT_HOLD = 2 + AUTO = 3 + GUIDED = 4 + CIRCLE = 7 + SURFACE = 9 + POSHOLD = 16 + MANUAL = 19 + MOTOR_DETECT = 20 +*/ +static const AP_IBus_Telem::ModeMap mode_map[] { + {.ap_mode = 0, .ibus_mode = IBUS_VEHICLE_MODE_STAB}, + {.ap_mode = 1, .ibus_mode = IBUS_VEHICLE_MODE_ACRO}, + {.ap_mode = 2, .ibus_mode = IBUS_VEHICLE_MODE_AHOLD}, + {.ap_mode = 3, .ibus_mode = IBUS_VEHICLE_MODE_AUTO}, + {.ap_mode = 4, .ibus_mode = IBUS_VEHICLE_MODE_GUIDED}, + {.ap_mode = 5, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 6, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, + {.ap_mode = 7, .ibus_mode = IBUS_VEHICLE_MODE_CIRCLE}, + {.ap_mode = 8, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, + {.ap_mode = 9, .ibus_mode = IBUS_VEHICLE_MODE_LAND}, + {.ap_mode = 16, .ibus_mode = IBUS_VEHICLE_MODE_PHOLD}, +}; + +#elif APM_BUILD_TYPE(APM_BUILD_Blimp) + +/* Blimp modes: + LAND = 0 + MANUAL = 1 + VELOCITY = 2 + LOITER = 3 + RTL = 4 +*/ +static const AP_IBus_Telem::ModeMap mode_map[] { + {.ap_mode = 0, .ibus_mode = IBUS_VEHICLE_MODE_LAND}, + {.ap_mode = 3, .ibus_mode = IBUS_VEHICLE_MODE_LOITER}, + {.ap_mode = 4, .ibus_mode = IBUS_VEHICLE_MODE_RTL}, +}; + +#else + +static const AP_IBus_Telem::ModeMap mode_map[] {}; + +#endif + +void AP_IBus_Telem::init() +{ + const AP_SerialManager &serial_manager = AP::serialmanager(); + if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_IBUS_Telem, 0))) { + port->set_options(port->OPTION_HDPLEX); + hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_IBus_Telem::tick, void)); + } +} + +void AP_IBus_Telem::tick(void) +{ + if (!initialized) { + port->begin(115200); + initialized = true; + } + + const uint16_t available = MIN(port->available(), 1024U); + if (available == 0) { + return; + } + + const uint32_t now = AP_HAL::millis(); + if ((now - last_received_message_time_ms) < PROTOCOL_TIMEGAP) { + // Any bytes that arrive too soon since the last message should be discarded + port->discard_input(); + return; + } + + union { + CommandPacket incoming_message; + uint8_t buffer[sizeof(CommandPacket)]; + } u; + + if (available < sizeof(u.incoming_message)) { + // We've got here mid-message; come back in the next loop when it might be complete + return; + } + + last_received_message_time_ms = now; + + if (available > sizeof(u.incoming_message)) { + // We've received too many bytes, so probably a malformed message + port->discard_input(); + return; + } + + if (port->read(u.buffer, sizeof(u.buffer)) != sizeof(u.buffer)) { + // Despite all our checks this is still the wrong size; safest to wait until the next message + port->discard_input(); + return; + } + + if (u.incoming_message.message_length != PROTOCOL_INCOMING_MESSAGE_LENGTH) { + // Every message starts with this fixed message length; if not then it's not valid + return; + } + + uint16_t calculated_checksum = 0xFFFF; + for (uint8_t i = 0; i < sizeof(u.buffer) - 2; i++) { + calculated_checksum -= u.buffer[i]; + } + + if (u.incoming_message.checksum != calculated_checksum) { + return; + } + + handle_incoming_message(u.incoming_message); +} + +void AP_IBus_Telem::handle_incoming_message(const CommandPacket &incoming) +{ + // Sensor 0 is reserved for the transmitter, so if for some reason it's requested we should ignore it + if (incoming.sensor_id == 0) { + return; + } + + // If we've reached the end of our sensor list, we shouldn't respond; this tells the receiver that there + // are no more sensors to discover. + if (incoming.sensor_id > ARRAY_SIZE(sensors)) { + return; + } + + const auto &sensor_definition = sensors[incoming.sensor_id - 1]; + + switch (incoming.command << 4) { + case PROTOCOL_COMMAND_DISCOVER: + handle_discover_command(incoming); + break; + + case PROTOCOL_COMMAND_TYPE: + handle_type_command(incoming, sensor_definition); + break; + + case PROTOCOL_COMMAND_VALUE: + handle_value_command(incoming, sensor_definition); + break; + } +} + +/* A discovery query has the following format: + * 0x04: Message length + * 0x81: 0x80 for discovery + 0x01 for sensor ID 1 + * 0x7A: Checksum low byte + * 0xFF: Checksum high byte + Checksums are 0xFFFF minus the sum of the previous bytes + + To acknowledge a discovery query, we echo the command back. + */ +void AP_IBus_Telem::handle_discover_command(const CommandPacket &incoming) +{ + struct protocol_command_discover_response_t { + uint8_t command_length; + uint8_t address; + uint16_t checksum; + } packet { + PROTOCOL_FOUR_LENGTH, + (uint8_t)(PROTOCOL_COMMAND_DISCOVER | incoming.sensor_id) + }; + populate_checksum((uint8_t*)&packet, sizeof(packet)); + port->write((uint8_t*)&packet, sizeof(packet)); +} + +/* A type query has the following format: + * 0x04: Message length + * 0x91: 0x90 for type + 0x01 for sensor ID 1 + * 0x6A: Checksum low byte + * 0xFF: Checksum high byte + Checksums are 0xFFFF minus the sum of the previous bytes + + To respond to a type query, we send: + * 0x06: Message length + * 0x91: 0x90 for type + 0x01 for sensor ID 1 + * 0x03: Sensor type, eg 0x03 for external voltage + * 0x02: Sensor length (2 or 4 bytes) + * 0x63: Checksum low byte + * 0xFF: Checksum high byte + Checksums are 0xFFFF minus the sum of the previous bytes + */ +void AP_IBus_Telem::handle_type_command(const CommandPacket &incoming, const SensorDefinition &sensor) +{ + struct protocol_command_type_response_t { + uint8_t command_length; + uint8_t address; + uint8_t type; + uint8_t length; + uint16_t checksum; + } packet { + PROTOCOL_SIX_LENGTH, + (uint8_t)(PROTOCOL_COMMAND_TYPE | incoming.sensor_id), + sensor.sensor_type, + sensor.sensor_length + }; + populate_checksum((uint8_t*)&packet, sizeof(packet)); + port->write((uint8_t*)&packet, sizeof(packet)); +} + +/* A value query has the following format: + * 0x04: Message length + * 0xA1: 0xA0 for value + 0x01 for sensor ID 1 + * 0x5A: Checksum low byte + * 0xFF: Checksum high byte + Checksums are 0xFFFF minus the sum of the previous bytes + + To respond to a value query, we send: + * 0x06: Message length (or 0x08 for a 4-byte sensor) + * 0xA1: 0xA1 for value + 0x01 for sensor ID 1 + * 0xD4: Value byte (value is 12,500 in this example) + * 0x30: Value byte + * 0x54: Checksum low byte + * 0xFE: Checksum high byte + Checksums are 0xFFFF minus the sum of the previous bytes + */ +void AP_IBus_Telem::handle_value_command(const CommandPacket &incoming, const SensorDefinition &sensor) +{ + const SensorValue value = get_sensor_value(sensor.sensor_type); + if (sensor.sensor_length == 2) { + handle_2_byte_value_command(incoming, value); + } else { + handle_4_byte_value_command(incoming, value); + } +} + +void AP_IBus_Telem::handle_2_byte_value_command(const CommandPacket &incoming, const SensorValue &value) +{ + struct protocol_command_2byte_value_response_t { + uint8_t command_length; + uint8_t address; + uint8_t value[2]; + uint16_t checksum; + } packet { + PROTOCOL_SIX_LENGTH, + (uint8_t)(PROTOCOL_COMMAND_VALUE | incoming.sensor_id), + {value.byte[0], value.byte[1]} + }; + populate_checksum((uint8_t*)&packet, sizeof(packet)); + port->write((uint8_t*)&packet, sizeof(packet)); +} + +void AP_IBus_Telem::handle_4_byte_value_command(const CommandPacket &incoming, const SensorValue &value) +{ + struct protocol_command_4byte_value_response_t { + uint8_t command_length; + uint8_t address; + uint8_t value[4]; + uint16_t checksum; + } packet { + PROTOCOL_EIGHT_LENGTH, + (uint8_t)(PROTOCOL_COMMAND_VALUE | incoming.sensor_id), + {value.byte[0], value.byte[1], value.byte[2], value.byte[3]} + }; + populate_checksum((uint8_t*)&packet, sizeof(packet)); + port->write((uint8_t*)&packet, sizeof(packet)); +} + +AP_IBus_Telem::SensorValue AP_IBus_Telem::get_sensor_value(const uint8_t sensor_type) +{ + SensorValue value; + switch (sensor_type) { +#if AP_BATTERY_ENABLED + case IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE: + value.uint16 = AP::battery().voltage() * 100; + break; + + case IBUS_SENSOR_TYPE_AVERAGE_CELL_VOLTAGE: + value.uint16 = get_average_cell_voltage_cV(); + break; + + case IBUS_SENSOR_TYPE_BATTERY_CURRENT: + value.uint16 = get_current_cAh(); + break; + + case IBUS_SENSOR_TYPE_FUEL: + value.uint16 = get_battery_or_fuel_level_pct(); + break; +#endif // AP_BATTERY_ENABLED + +#if AP_RPM_ENABLED + case IBUS_SENSOR_TYPE_RPM: + case IBUS_SENSOR_TYPE_RPM_FLYSKY: + value.uint16 = get_rpm(); + break; +#endif + +#if AP_AHRS_ENABLED + case IBUS_SENSOR_TYPE_COMPASS_HEADING: + value.uint16 = AP::ahrs().yaw_sensor * 0.01; + break; +#endif + +#if AP_BARO_ENABLED + case IBUS_SENSOR_TYPE_CLIMB_RATE: + case IBUS_SENSOR_TYPE_VERTICAL_SPEED: + value.int16 = AP::baro().get_climb_rate() * 100; + break; +#endif + +#if AP_GPS_ENABLED + case IBUS_SENSOR_TYPE_COG: + value.uint16 = AP::gps().ground_course() * 100; + break; + + case IBUS_SENSOR_TYPE_GPS_STATUS: + value.byte[0] = get_gps_status(); + value.byte[1] = AP::gps().num_sats(); + break; +#endif // AP_GPS_ENABLED + +#if AP_AHRS_ENABLED + case IBUS_SENSOR_TYPE_ACC_X: + value.int16 = (AP::ahrs().get_accel() - AP::ahrs().get_accel_bias()).x * 1000; + break; + + case IBUS_SENSOR_TYPE_ACC_Y: + value.int16 = (AP::ahrs().get_accel() - AP::ahrs().get_accel_bias()).y * 1000; + break; + + case IBUS_SENSOR_TYPE_ACC_Z: + value.int16 = (AP::ahrs().get_accel() - AP::ahrs().get_accel_bias()).z * 1000; + break; + + case IBUS_SENSOR_TYPE_ROLL: + value.int16 = AP::ahrs().roll_sensor; + break; + + case IBUS_SENSOR_TYPE_PITCH: + value.int16 = AP::ahrs().pitch_sensor; + break; + + case IBUS_SENSOR_TYPE_YAW: + value.int16 = AP::ahrs().yaw_sensor; + break; +#endif // AP_AHRS_ENABLED + +#if AP_GPS_ENABLED + case IBUS_SENSOR_TYPE_GROUND_SPEED: + value.uint16 = AP::gps().ground_speed_cm(); + break; +#endif + +#if AP_AHRS_ENABLED + case IBUS_SENSOR_TYPE_GPS_DIST: + value.uint16 = get_distance_from_home_m(); + break; +#endif + +#if AP_ARMING_ENABLED + case IBUS_SENSOR_TYPE_ARMED: + value.uint16 = AP::arming().is_armed(); + break; +#endif + + case IBUS_SENSOR_TYPE_FLIGHT_MODE: + value.uint16 = get_vehicle_mode(); + break; + +#if AP_AIRSPEED_ENABLED + case IBUS_SENSOR_TYPE_SPEED: + value.uint16 = AP::airspeed()->get_airspeed(); + break; +#endif + +#if AP_BARO_ENABLED + case IBUS_SENSOR_TYPE_TEMPERATURE_PRESSURE: { + const uint32_t pressure = AP::baro().get_pressure(); + const uint32_t temperature = (AP::baro().get_temperature() + 40) * 10; + value.uint32 = pressure | (temperature << 19); + break; + } +#endif + +#if AP_GPS_ENABLED + case IBUS_SENSOR_TYPE_GPS_LAT: + value.int32 = AP::gps().location().lat; + break; + + case IBUS_SENSOR_TYPE_GPS_LNG: + value.int32 = AP::gps().location().lng; + break; + + case IBUS_SENSOR_TYPE_GPS_ALT: + value.int32 = AP::gps().location().alt; + break; +#endif // AP_GPS_ENABLED + +#if AP_BARO_ENABLED + case IBUS_SENSOR_TYPE_ALT: + value.int32 = AP::baro().get_altitude() * 100; + break; +#endif + + default: + value.int32 = 0; + } + + return value; +} + +#if AP_BATTERY_ENABLED +uint16_t AP_IBus_Telem::get_average_cell_voltage_cV() +{ + if (!AP::battery().has_cell_voltages()) { + return 0; + } + + const auto &cell_voltages = AP::battery().get_cell_voltages(); + const uint8_t number_of_cells = ARRAY_SIZE(cell_voltages.cells); + if (number_of_cells == 0) { + return 0; + } + + uint32_t voltage_sum = 0; + for (auto i = 0; i < number_of_cells; i++) { + voltage_sum += cell_voltages.cells[i] * 0.001; + } + return voltage_sum / number_of_cells * 100; + +} + +uint16_t AP_IBus_Telem::get_current_cAh() +{ + float current = 0; + IGNORE_RETURN(AP::battery().current_amps(current)); + return current * 100; +} + +uint8_t AP_IBus_Telem::get_battery_or_fuel_level_pct() +{ + uint8_t percentage = 0; + IGNORE_RETURN(AP::battery().capacity_remaining_pct(percentage)); + return percentage; +} +#endif // AP_BATTERY_ENABLED + +#if AP_RPM_ENABLED +uint16_t AP_IBus_Telem::get_rpm() +{ + const AP_RPM *rpm = AP::rpm(); + float rpm_value; + if (rpm && rpm->get_rpm(0, rpm_value)) { + return rpm_value; + } + + return 0; +} +#endif + +#if AP_GPS_ENABLED +uint8_t AP_IBus_Telem::get_gps_status() +{ + if (!AP::gps().is_healthy()) { + return 0; + } + + const AP_GPS::GPS_Status gps_status = AP::gps().status(); + if (gps_status >= AP_GPS::GPS_OK_FIX_3D) { + return 3; + } else if (gps_status >= AP_GPS::GPS_OK_FIX_2D) { + return 2; + } else if (gps_status == AP_GPS::NO_FIX) { + return 1; + } else { + return 0; + } +} +#endif // AP_GPS_ENABLED + +#if AP_AHRS_ENABLED +uint16_t AP_IBus_Telem::get_distance_from_home_m() +{ + Vector2f home; + if (AP::ahrs().get_relative_position_NE_home(home)) { + return home.length(); + } + + return 0; +} +#endif + +uint16_t AP_IBus_Telem::get_vehicle_mode() +{ + const uint8_t vehicle_mode = AP::vehicle()->get_mode(); + for (uint8_t i = 0; i < ARRAY_SIZE(mode_map); i++) { + if (mode_map[i].ap_mode == vehicle_mode) { + return mode_map[i].ibus_mode; + } + } + return IBUS_VEHICLE_MODE_UNKNOWN; +} + +// Populate the last two bytes of packet with the checksum of the preceding bytes +void AP_IBus_Telem::populate_checksum(uint8_t *packet, const uint16_t size) +{ + uint16_t checksum = 0xFFFF; + + for (int i=0; i> 8; +} + +#endif diff --git a/libraries/AP_IBus_Telem/AP_IBus_Telem.h b/libraries/AP_IBus_Telem/AP_IBus_Telem.h new file mode 100644 index 00000000000000..da845715b694ee --- /dev/null +++ b/libraries/AP_IBus_Telem/AP_IBus_Telem.h @@ -0,0 +1,126 @@ +/* + 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 . + + + i-BUS telemetry for FlySky/Turnigy receivers and other peripherals + (eg iA6B, iA10) by Nicole Ashley . + + Originally based on work by Jan Verhulst: + https://github.com/ArduPilot/ardupilot/pull/16545 + + Libraries used for reference and inspiration: + + * iBUStelemetry + https://github.com/Hrastovc/iBUStelemetry + + * IBusBM + https://github.com/bmellink/IBusBM + + * BetaFlight + https://github.com/betaflight/betaflight/blob/master/src/main/telemetry/ibus_shared.c + */ + +#pragma once + +#include + +#ifndef AP_IBUS_TELEM_ENABLED +#define AP_IBUS_TELEM_ENABLED BOARD_FLASH_SIZE > 2048 +#endif + +#if AP_IBUS_TELEM_ENABLED + +#include +#include +#include +#include +#include +#include + +class AP_IBus_Telem +{ +public: + AP_IBus_Telem() {} + + CLASS_NO_COPY(AP_IBus_Telem); + + void init(); + + typedef struct { + uint8_t sensor_type; // Sensor type (IBUS_SENSOR_TYPE_* above) + uint8_t sensor_length; // Data length for defined sensor (can be 2 or 4 bytes) + } SensorDefinition; + + typedef struct { + uint8_t ap_mode; + uint8_t ibus_mode; + } ModeMap; + +private: + + typedef union { + uint16_t uint16; + uint32_t uint32; + int16_t int16; + int32_t int32; + uint8_t byte[4]; + } SensorValue; + + struct PACKED CommandPacket { + uint8_t message_length; + uint8_t sensor_id : 4; + uint8_t command : 4; + uint16_t checksum; + }; + + void tick(); + void handle_incoming_message(const CommandPacket &incoming); + void handle_discover_command(const CommandPacket &incoming); + void handle_type_command(const CommandPacket &incoming, const SensorDefinition &sensor); + void handle_value_command(const CommandPacket &incoming, const SensorDefinition &sensor); + void handle_2_byte_value_command(const CommandPacket &incoming, const SensorValue &value); + void handle_4_byte_value_command(const CommandPacket &incoming, const SensorValue &value); + SensorValue get_sensor_value(uint8_t sensor_id); +#if AP_BATTERY_ENABLED + uint16_t get_average_cell_voltage_cV(); + uint16_t get_current_cAh(); + uint8_t get_battery_or_fuel_level_pct(); +#endif +#if AP_RPM_ENABLED + uint16_t get_rpm(); +#endif +#if AP_GPS_ENABLED + uint8_t get_gps_status(); +#endif +#if AP_AHRS_ENABLED + uint16_t get_distance_from_home_m(); +#endif + uint16_t get_vehicle_mode(); + void populate_checksum(uint8_t *packet, const uint16_t size); + + static const uint8_t PROTOCOL_COMMAND_DISCOVER = 0x80; // Command to discover a sensor (lowest 4 bits are sensor) + static const uint8_t PROTOCOL_COMMAND_TYPE = 0x90; // Command to request a sensor type (lowest 4 bits are sensor) + static const uint8_t PROTOCOL_COMMAND_VALUE = 0xA0; // Command to request a sensor's value (lowest 4 bits are sensor) + static const uint8_t PROTOCOL_TIMEGAP = 3; // Packets are received very ~7ms so use ~half that for the gap + static const uint8_t PROTOCOL_FOUR_LENGTH = 0x04; // indicate that the message has 4 bytes + static const uint8_t PROTOCOL_SIX_LENGTH = 0x06; // indicate that the message has 6 bytes + static const uint8_t PROTOCOL_EIGHT_LENGTH = 0x08; // indicate that the message has 8 bytes + static const uint8_t PROTOCOL_INCOMING_MESSAGE_LENGTH = PROTOCOL_FOUR_LENGTH; // All incoming messages are the same length + + AP_HAL::UARTDriver *port; + bool initialized; + uint32_t last_received_message_time_ms; // When the last message was received +}; + +#endif diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index b5202ea7220cb5..37c04689fcf0ab 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -44,9 +44,11 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: START_CHAN // @DisplayName: Input channel for engine start // @Description: This is an RC input channel for requesting engine start. Engine will try to start when channel is at or above 1700. Engine will stop when channel is at or below 1300. Between 1301 and 1699 the engine will not change state unless a MAVLink command or mission item commands a state change, or the vehicle is disarmed. See ICE_STARTCHN_MIN parameter to change engine stop PWM value and/or to enable debouncing of the START_CH to avoid accidental engine kills due to noise on channel. + // @Legacy: 4.5 param // @User: Standard // @Values: 0:None,1:Chan1,2:Chan2,3:Chan3,4:Chan4,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16 - AP_GROUPINFO("START_CHAN", 1, AP_ICEngine, start_chan, 0), + + // 1 was START_CHAN // @Param: STARTER_TIME // @DisplayName: Time to run starter @@ -76,30 +78,38 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: PWM_IGN_ON // @DisplayName: PWM value for ignition on // @Description: This is the value sent to the ignition channel when on + // @Legacy: 4.5 param // @User: Standard // @Range: 1000 2000 - AP_GROUPINFO("PWM_IGN_ON", 5, AP_ICEngine, pwm_ignition_on, 2000), + + // 5 was PWM_IGN_ON // @Param: PWM_IGN_OFF // @DisplayName: PWM value for ignition off // @Description: This is the value sent to the ignition channel when off + // @Legacy: 4.5 param // @User: Standard // @Range: 1000 2000 - AP_GROUPINFO("PWM_IGN_OFF", 6, AP_ICEngine, pwm_ignition_off, 1000), + + // 6 was PWM_IGN_OFF // @Param: PWM_STRT_ON // @DisplayName: PWM value for starter on // @Description: This is the value sent to the starter channel when on + // @Legacy: 4.5 param // @User: Standard // @Range: 1000 2000 - AP_GROUPINFO("PWM_STRT_ON", 7, AP_ICEngine, pwm_starter_on, 2000), + + // 7 was PWM_STRT_ON // @Param: PWM_STRT_OFF // @DisplayName: PWM value for starter off // @Description: This is the value sent to the starter channel when off + // @Legacy: 4.5 param // @User: Standard // @Range: 1000 2000 - AP_GROUPINFO("PWM_STRT_OFF", 8, AP_ICEngine, pwm_starter_off, 1000), + + // 8 was PWM_STRT_OFF #if AP_RPM_ENABLED // @Param: RPM_CHAN @@ -145,12 +155,12 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: OPTIONS // @DisplayName: ICE options // @Description: Options for ICE control. The Disable ignition in RC failsafe option will cause the ignition to be set off on any R/C failsafe. If Throttle while disarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode. If disable while disarmed is set the engine will not start while the vehicle is disarmed unless overriden by the MAVLink DO_ENGINE_CONTROL command. - // @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle while disarmed,3:Disable while disarmed + // @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle control in MANUAL while disarmed with safety off,3:Disable while disarmed,4:Crank direction Reverse AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0), // @Param: STARTCHN_MIN // @DisplayName: Input channel for engine start minimum PWM - // @Description: This is a minimum PWM value for engine start channel for an engine stop to be commanded. Setting this value will avoid RC input glitches with low PWM values from causing an unwanted engine stop. A value of zero means any PWM below 1300 triggers an engine stop. + // @Description: This is a minimum PWM value for engine start channel for an engine stop to be commanded. Setting this value will avoid RC input glitches with low PWM values from causing an unwanted engine stop. A value of zero means any PWM above 800 and below 1300 triggers an engine stop. To stop the engine start channel must above the larger of this value and 800 and below 1300. // @User: Standard // @Range: 0 1300 AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0), @@ -167,6 +177,16 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // 18 was IGNITION_RLY + // Hidden param used as a flag for param conversion + // This allows one time conversion while allowing user to flash between versions with and without converted params + AP_GROUPINFO_FLAGS("FMT_VER", 19, AP_ICEngine, param_format_version, 0, AP_PARAM_FLAG_HIDDEN), + + // @Param: STRT_MX_RTRY + // @DisplayName: Maximum number of retries + // @Description: If set 0 then there is no limit to retrials. If set to a value greater than 0 then the engine will retry starting the engine this many times before giving up. + // @User: Standard + // @Range: 0 127 + AP_GROUPINFO("STRT_MX_RTRY", 20, AP_ICEngine, max_crank_retry, 0), AP_GROUPEND }; @@ -187,6 +207,81 @@ AP_ICEngine::AP_ICEngine() #endif } +// One time init call +void AP_ICEngine::init() +{ + // Configure starter and ignition outputs as range type + SRV_Channels::set_range(SRV_Channel::k_starter, 1); + SRV_Channels::set_range(SRV_Channel::k_ignition, 1); + + // Set default PWM endpoints to 1000 to 2000 + SRV_Channels::set_output_min_max_defaults(SRV_Channel::k_starter, 1000, 2000); + SRV_Channels::set_output_min_max_defaults(SRV_Channel::k_ignition, 1000, 2000); + + // Convert params + param_conversion(); +} + +// PARAMETER_CONVERSION - Added: Aug 2024 +void AP_ICEngine::param_conversion() +{ + if (!enable || (param_format_version == 1)) { + // not enabled or conversion has already been done + return; + } + + // Set format version so the conversion is not done again + param_format_version.set_and_save(1); + + AP_Param::ConversionInfo info; + if (!AP_Param::find_key_by_pointer(this, info.old_key)) { + return; + } + + // Conversion table giving the old on and off pwm parameter indexes and the function for both starter and ignition + const struct convert_table { + uint32_t element[2]; + SRV_Channel::Aux_servo_function_t fuction; + } conversion_table[] = { + { {450, 514}, SRV_Channel::k_starter }, // PWM_STRT_ON, PWM_STRT_OFF + { {322, 386}, SRV_Channel::k_ignition }, // PWM_IGN_ON, PWM_IGN_OFF + }; + + // All PWM values were int16 + info.type = AP_PARAM_INT16; + + for (const auto & elem : conversion_table) { + // Use the original default values if params are not saved + uint16_t pwm_on = 2000; + uint16_t pwm_off = 1000; + + // Get param values if configured + AP_Int16 param_value; + info.old_group_element = elem.element[0]; + if (AP_Param::find_old_parameter(&info, ¶m_value)) { + pwm_on = param_value; + } + info.old_group_element = elem.element[1]; + if (AP_Param::find_old_parameter(&info, ¶m_value)) { + pwm_off = param_value; + } + + // Save as servo endpoints, note that save_output_min_max will set reversed if needed + SRV_Channels::save_output_min_max(elem.fuction, pwm_off, pwm_on); + } + + // Convert to new RC option + AP_Int8 start_chan; + info.type = AP_PARAM_INT8; + info.old_group_element = 66; + if (AP_Param::find_old_parameter(&info, &start_chan) && (start_chan > 0)) { + RC_Channel *chan = rc().channel(start_chan-1); + if (chan != nullptr) { + chan->option.set_and_save((int16_t)RC_Channel::AUX_FUNC::ICE_START_STOP); + } + } +} + /* update engine state */ @@ -197,7 +292,7 @@ void AP_ICEngine::update(void) } uint16_t cvalue = 1500; - RC_Channel *c = rc().channel(start_chan-1); + RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP); if (c != nullptr && rc().has_valid_input()) { // get starter control channel cvalue = c->get_radio_in(); @@ -276,6 +371,13 @@ void AP_ICEngine::update(void) } #endif + // Stop on emergency stop + if (SRV_Channels::get_emergency_stop()) { + // Throttle is already forced to 0 in this case, ignition should also be stopped. + // Starter should not run. + should_run = false; + } + // switch on current state to work out new state switch (state) { case ICE_DISABLED: @@ -284,6 +386,10 @@ void AP_ICEngine::update(void) if (should_run) { state = ICE_START_DELAY; } + crank_retry_ct = 0; + // clear the last uncommanded stop time, we only care about tracking + // the last one since the engine was started + last_uncommanded_stop_ms = 0; break; case ICE_START_HEIGHT_DELAY: { @@ -307,8 +413,16 @@ void AP_ICEngine::update(void) if (!should_run) { state = ICE_OFF; } else if (now - starter_last_run_ms >= starter_delay*1000) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting engine"); - state = ICE_STARTING; + // check if we should retry starting the engine + if (max_crank_retry <= 0 || crank_retry_ct < max_crank_retry) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting engine"); + state = ICE_STARTING; + crank_retry_ct++; + } else { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Engine max crank attempts reached"); + // Mark the last run now so we don't send this message every loop + starter_last_run_ms = now; + } } break; @@ -334,7 +448,14 @@ void AP_ICEngine::update(void) 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"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Uncommanded engine stop"); + if (last_uncommanded_stop_ms != 0 && + now - last_uncommanded_stop_ms > 3*(starter_time + starter_delay)*1000) { + // if it has been a long enough time since the last uncommanded stop + // (3 times the time between start attempts) then reset the retry count + crank_retry_ct = 0; + } + last_uncommanded_stop_ms = now; } } #endif @@ -349,7 +470,7 @@ void AP_ICEngine::update(void) // reset initial height while disarmed initial_height = -pos.z; } - } else if (idle_percent <= 0 && !option_set(Options::THROTTLE_WHILE_DISARMED)) { + } else if (idle_percent <= 0 && !allow_throttle_while_disarmed()) { // force ignition off when disarmed state = ICE_OFF; } @@ -431,7 +552,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle idle_percent > percentage) { percentage = idle_percent; - if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed()) { + if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed()) { percentage = MAX(percentage, base_throttle); } return true; @@ -472,7 +593,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle #endif // AP_RPM_ENABLED // 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() && + if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed() && base_throttle > percentage) { percentage = base_throttle; return true; @@ -501,7 +622,7 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: already running"); return false; } - RC_Channel *c = rc().channel(start_chan-1); + RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP); if (c != nullptr && rc().has_valid_input()) { // get starter control channel uint16_t cvalue = c->get_radio_in(); @@ -601,7 +722,7 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) */ void AP_ICEngine::set_ignition(bool on) { - SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, on? pwm_ignition_on : pwm_ignition_off); + SRV_Channels::set_output_scaled(SRV_Channel::k_ignition, on ? 1.0 : 0.0); #if AP_RELAY_ENABLED AP_Relay *relay = AP::relay(); @@ -617,10 +738,10 @@ void AP_ICEngine::set_ignition(bool on) */ void AP_ICEngine::set_starter(bool on) { - SRV_Channels::set_output_pwm(SRV_Channel::k_starter, on? pwm_starter_on : pwm_starter_off); + SRV_Channels::set_output_scaled(SRV_Channel::k_starter, on ? 1.0 : 0.0); #if AP_ICENGINE_TCA9554_STARTER_ENABLED - tca9554_starter.set_starter(on); + tca9554_starter.set_starter(on, option_set(Options::CRANK_DIR_REVERSE)); #endif #if AP_RELAY_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 351302e7638f0f..4afc96f2ada6d8 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -39,6 +39,9 @@ class AP_ICEngine { static const struct AP_Param::GroupInfo var_info[]; + // One time init call + void init(); + // update engine state. Should be called at 10Hz or more void update(void); @@ -83,16 +86,13 @@ class AP_ICEngine { #if AP_RPM_ENABLED // filter for RPM value - LowPassFilterFloat _rpm_filter; + LowPassFilterConstDtFloat _rpm_filter; float filtered_rpm_value; #endif // enable library AP_Int8 enable; - // channel for pilot to command engine start, 0 for none - AP_Int8 start_chan; - // min pwm on start channel for engine stop AP_Int16 start_chan_min_pwm; @@ -106,12 +106,10 @@ class AP_ICEngine { // delay between start attempts (seconds) AP_Float starter_delay; - - // pwm values - AP_Int16 pwm_ignition_on; - AP_Int16 pwm_ignition_off; - AP_Int16 pwm_starter_on; - AP_Int16 pwm_starter_off; + + // max crank retry + AP_Int8 max_crank_retry; + int8_t crank_retry_ct; #if AP_RPM_ENABLED // RPM above which engine is considered to be running @@ -124,6 +122,9 @@ class AP_ICEngine { // time when we last ran the starter uint32_t starter_last_run_ms; + // time when we last had an uncommanded engine stop + uint32_t last_uncommanded_stop_ms; + // throttle percentage for engine start AP_Int8 start_percent; @@ -160,6 +161,7 @@ class AP_ICEngine { DISABLE_REDLINE_GOVERNOR = (1U << 1), THROTTLE_WHILE_DISARMED = (1U << 2), NO_RUNNING_WHILE_DISARMED = (1U << 3), + CRANK_DIR_REVERSE = (1U << 4), }; AP_Int16 options; @@ -184,6 +186,10 @@ class AP_ICEngine { float throttle_percentage; } redline; #endif + + // Param conversion function and flag + void param_conversion(); + AP_Int8 param_format_version; }; diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp index fddfa3363fc113..802e1e4cb34d81 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp @@ -82,7 +82,7 @@ void AP_ICEngine_TCA9554::TCA9554_set(TCA9554_state_t value) } } -void AP_ICEngine_TCA9554::set_starter(bool on) +void AP_ICEngine_TCA9554::set_starter(bool on, bool crank_dir_reverse) { if (!initialised) { initialised = TCA9554_init(); @@ -91,7 +91,11 @@ void AP_ICEngine_TCA9554::set_starter(bool on) return; } } - TCA9554_set(on? STARTER_ON : STARTER_OFF); + if (!crank_dir_reverse) { + TCA9554_set(on? STARTER_FORWARD : STARTER_OFF); + } else { + TCA9554_set(on? STARTER_REVERSE : STARTER_OFF); + } } #endif // AP_ICENGINE_TCA9554_STARTER_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h index 005a5ece6cfdff..25185ec3d6861a 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h @@ -9,14 +9,15 @@ class AP_ICEngine_TCA9554 { public: - void set_starter(bool on); + void set_starter(bool on, bool crank_dir_reverse); private: AP_HAL::OwnPtr dev_TCA9554; enum TCA9554_state_t { - STARTER_OFF = 0x30, // output register - 0011 0000 - STARTER_ON = 0x11, // output register - 0001 0001 - Forward direction + STARTER_OFF = 0x30, // output register - 0011 0000 + STARTER_FORWARD = 0x11, // output register - 0001 0001 - Forward direction + STARTER_REVERSE = 0x01, // output register - 0000 0001 - Reverse direction }; TCA9554_state_t last_state; diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index fefa91ebf03775..93f0b7bc1dcb2d 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -43,6 +43,7 @@ enum ioevents { IOEVENT_SET_DSHOT_PERIOD, IOEVENT_SET_CHANNEL_MASK, IOEVENT_DSHOT, + IOEVENT_PROFILED, }; // max number of consecutve protocol failures we accept before raising @@ -89,7 +90,9 @@ void AP_IOMCU::init(void) crc_is_ok = true; } #endif - +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + use_safety_as_led = boardconfig->use_safety_as_led(); +#endif if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU", 1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) { AP_HAL::panic("Unable to allocate IOMCU thread"); @@ -156,10 +159,9 @@ void AP_IOMCU::thread_main(void) DEV_PRINTF("IOMCU: 0x%lx\n", config.mcuid); - // set IO_ARM_OK and FMU_ARMED - if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, 0, + // set IO_ARM_OK and clear FMU_ARMED + if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, P_SETUP_ARMING_FMU_ARMED, P_SETUP_ARMING_IO_ARM_OK | - P_SETUP_ARMING_FMU_ARMED | P_SETUP_ARMING_RC_HANDLING_DISABLED)) { event_failed(mask); continue; @@ -301,6 +303,16 @@ void AP_IOMCU::thread_main(void) } mask &= ~EVENT_MASK(IOEVENT_DSHOT); +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + if (mask & EVENT_MASK(IOEVENT_PROFILED)) { + if (!write_registers(PAGE_PROFILED, 0, sizeof(profiled)/sizeof(uint16_t), (const uint16_t*)&profiled)) { + event_failed(mask); + continue; + } + } + mask &= ~EVENT_MASK(IOEVENT_PROFILED); +#endif + // check for regular timed events uint32_t now = AP_HAL::millis(); if (now - last_rc_read_ms > 20) { @@ -338,7 +350,8 @@ void AP_IOMCU::thread_main(void) last_telem_read_ms = AP_HAL::millis(); } #endif - if (now - last_safety_option_check_ms > 1000) { + // update options at the same rate that the iomcu updates the state + if (now - last_safety_option_check_ms > 100) { update_safety_options(); last_safety_option_check_ms = now; } @@ -346,7 +359,7 @@ void AP_IOMCU::thread_main(void) // update failsafe pwm if (pwm_out.failsafe_pwm_set != pwm_out.failsafe_pwm_sent) { uint8_t set = pwm_out.failsafe_pwm_set; - if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.failsafe_pwm)) { + if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_RC_CHANNELS, pwm_out.failsafe_pwm)) { pwm_out.failsafe_pwm_sent = set; } } @@ -372,7 +385,7 @@ void AP_IOMCU::send_servo_out() if (rate.sbus_rate_hz == 0) { n = MIN(n, 8); } else { - n = MIN(n, IOMCU_MAX_CHANNELS); + n = MIN(n, IOMCU_MAX_RC_CHANNELS); } uint32_t now = AP_HAL::micros(); if (now - last_servo_out_us >= 2000 || AP_BoardConfig::io_dshot()) { @@ -453,7 +466,11 @@ void AP_IOMCU::read_telem() TelemetryData t { .temperature_cdeg = int16_t(telem->temperature_cdeg[i]), .voltage = float(telem->voltage_cvolts[i]) * 0.01, - .current = float(telem->current_camps[i]) * 0.01 + .current = float(telem->current_camps[i]) * 0.01, +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + .edt2_status = telem->edt2_status[i], + .edt2_stress = telem->edt2_stress[i], +#endif }; update_telem_data(esc_group * 4 + i, t, telem->types[i]); } @@ -642,8 +659,8 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 // wait for the expected number of reply bytes or timeout if (!uart.wait_timeout(count*2+4, 10)) { - debug("t=%lu timeout read page=%u offset=%u count=%u\n", - AP_HAL::millis(), page, offset, count); + debug("t=%lu timeout read page=%u offset=%u count=%u avail=%u\n", + AP_HAL::millis(), page, offset, count, uart.available()); protocol_fail_count++; return false; } @@ -791,7 +808,7 @@ bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm) { - if (chan >= IOMCU_MAX_CHANNELS) { + if (chan >= IOMCU_MAX_RC_CHANNELS) { // could be SBUS out return; } if (chan >= pwm_out.num_channels) { @@ -986,12 +1003,29 @@ void AP_IOMCU::set_bidir_dshot_mask(uint16_t mask) trigger_event(IOEVENT_SET_OUTPUT_MODE); } +// set reversible mask +void AP_IOMCU::set_reversible_mask(uint16_t mask) +{ + mode_out.reversible_mask = mask; + trigger_event(IOEVENT_SET_OUTPUT_MODE); +} + AP_HAL::RCOutput::output_mode AP_IOMCU::get_output_mode(uint8_t& mask) const { mask = reg_status.rcout_mask; return AP_HAL::RCOutput::output_mode(reg_status.rcout_mode); } +uint32_t AP_IOMCU::get_disabled_channels(uint32_t digital_mask) const +{ + uint32_t dig_out = reg_status.rcout_mask & (digital_mask & 0xFF); + if (dig_out > 0 + && AP_HAL::RCOutput::is_dshot_protocol(AP_HAL::RCOutput::output_mode(reg_status.rcout_mode))) { + return ~dig_out & 0xFF; + } + return 0; +} + // setup channels void AP_IOMCU::enable_ch(uint8_t ch) { @@ -1018,17 +1052,23 @@ void AP_IOMCU::update_safety_options(void) } uint16_t desired_options = 0; uint16_t options = boardconfig->get_safety_button_options(); + bool armed = hal.util->get_soft_armed(); if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) { desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_OFF; } 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) && AP::arming().is_armed()) { + if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) && armed) { desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF); } + // update armed state + if (armed) { + desired_options |= P_SETUP_ARMING_FMU_ARMED; + } + if (last_safety_options != desired_options) { - uint16_t mask = (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF); + uint16_t mask = (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF | P_SETUP_ARMING_FMU_ARMED); uint32_t bits_to_set = desired_options & mask; uint32_t bits_to_clear = (~desired_options) & mask; if (modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, bits_to_clear, bits_to_set)) { @@ -1112,7 +1152,7 @@ bool AP_IOMCU::check_crc(void) void AP_IOMCU::set_failsafe_pwm(uint16_t chmask, uint16_t period_us) { bool changed = false; - for (uint8_t i=0; iget_function()); MIX_UPDATE(mixing.servo_reversed[i], c->get_reversed()); } - // update RCMap - MIX_UPDATE(mixing.rc_channel[0], rcmap->roll()); - MIX_UPDATE(mixing.rc_channel[1], rcmap->pitch()); - MIX_UPDATE(mixing.rc_channel[2], rcmap->throttle()); - MIX_UPDATE(mixing.rc_channel[3], rcmap->yaw()); + auto &xrc = rc(); + // note that if not all of these channels are specified correctly + // in parameters then these may be a "dummy" RC channel pointer. + // In that case c->ch() will be zero. + const RC_Channel *channels[] { + &xrc.get_roll_channel(), + &xrc.get_pitch_channel(), + &xrc.get_throttle_channel(), + &xrc.get_yaw_channel() + }; for (uint8_t i=0; i<4; i++) { - const RC_Channel *c = RC_Channels::rc_channel(mixing.rc_channel[i]-1); - if (!c) { - continue; - } + const auto *c = channels[i]; + MIX_UPDATE(mixing.rc_channel[i], c->ch()); MIX_UPDATE(mixing.rc_min[i], c->get_radio_min()); MIX_UPDATE(mixing.rc_max[i], c->get_radio_max()); MIX_UPDATE(mixing.rc_trim[i], c->get_radio_trim()); @@ -1365,6 +1408,12 @@ void AP_IOMCU::set_GPIO_mask(uint8_t mask) trigger_event(IOEVENT_GPIO); } +// Get GPIO mask of channels setup for output +uint8_t AP_IOMCU::get_GPIO_mask() const +{ + return GPIO.channel_mask; +} + // write to a output pin void AP_IOMCU::write_GPIO(uint8_t pin, bool value) { @@ -1382,6 +1431,17 @@ void AP_IOMCU::write_GPIO(uint8_t pin, bool value) trigger_event(IOEVENT_GPIO); } +// Read the last output value send to the GPIO pin +// This is not a real read of the actual pin +// This allows callers to check for state change +uint8_t AP_IOMCU::read_virtual_GPIO(uint8_t pin) const +{ + if (!convert_pin_number(pin)) { + return 0; + } + return (GPIO.output_mask & (1U << pin)) != 0; +} + // toggle a output pin void AP_IOMCU::toggle_GPIO(uint8_t pin) { @@ -1392,6 +1452,23 @@ void AP_IOMCU::toggle_GPIO(uint8_t pin) trigger_event(IOEVENT_GPIO); } +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED +// set profiled R G B values +void AP_IOMCU::set_profiled(uint8_t r, uint8_t g, uint8_t b) +{ + if (!use_safety_as_led) { + return; + } + if (r == profiled.red && g == profiled.green && b == profiled.blue) { + return; + } + profiled.magic = PROFILED_ENABLE_MAGIC; + profiled.red = r; + profiled.green = g; + profiled.blue = b; + trigger_event(IOEVENT_PROFILED); +} +#endif namespace AP { AP_IOMCU *iomcu(void) { diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 253b1b9890b457..3b4f315a1406b4 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -11,7 +11,6 @@ #if HAL_WITH_IO_MCU #include "iofirmware/ioprotocol.h" -#include #include #include @@ -110,9 +109,15 @@ class AP_IOMCU // set bi-directional mask void set_bidir_dshot_mask(uint16_t mask); + // set reversible mask + void set_reversible_mask(uint16_t mask); + // get output mode AP_HAL::RCOutput::output_mode get_output_mode(uint8_t& mask) const; + // approximation to disabled channel + uint32_t get_disabled_channels(uint32_t digital_mask) const; + // MCUID uint32_t get_mcu_id() const { return config.mcuid; } @@ -145,7 +150,7 @@ class AP_IOMCU void soft_reboot(); // setup for FMU failsafe mixing - bool setup_mixing(RCMapper *rcmap, int8_t override_chan, + bool setup_mixing(int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask); // Check if pin number is valid and configured for GPIO @@ -157,12 +162,25 @@ class AP_IOMCU // set GPIO mask of channels setup for output void set_GPIO_mask(uint8_t mask); + // Get GPIO mask of channels setup for output + uint8_t get_GPIO_mask() const; + // write to a output pin void write_GPIO(uint8_t pin, bool value); + // Read the last output value send to the GPIO pin + // This is not a real read of the actual pin + // This allows callers to check for state change + uint8_t read_virtual_GPIO(uint8_t pin) const; + // toggle a output pin void toggle_GPIO(uint8_t pin); +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + // set profiled values + void set_profiled(uint8_t r, uint8_t g, uint8_t b); +#endif + // channel group masks const uint8_t ch_masks[3] = { 0x03,0x0C,0xF0 }; @@ -243,9 +261,9 @@ class AP_IOMCU // output pwm values struct { uint8_t num_channels; - uint16_t pwm[IOMCU_MAX_CHANNELS]; + uint16_t pwm[IOMCU_MAX_RC_CHANNELS]; uint16_t safety_mask; - uint16_t failsafe_pwm[IOMCU_MAX_CHANNELS]; + uint16_t failsafe_pwm[IOMCU_MAX_RC_CHANNELS]; uint8_t failsafe_pwm_set; uint8_t failsafe_pwm_sent; uint16_t channel_mask; @@ -253,7 +271,7 @@ class AP_IOMCU // read back pwm values struct { - uint16_t pwm[IOMCU_MAX_CHANNELS]; + uint16_t pwm[IOMCU_MAX_RC_CHANNELS]; } pwm_in; // output rates @@ -284,6 +302,11 @@ class AP_IOMCU // output mode values struct page_mode_out mode_out; +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + // profiled control + struct page_profiled profiled {0, 255, 255, 255}; // by default, white +#endif + // IMU heater duty cycle uint8_t heater_duty_cycle; @@ -297,6 +320,9 @@ class AP_IOMCU bool detected_io_reset; bool initialised; bool is_chibios_backend; +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + bool use_safety_as_led; +#endif uint32_t protocol_fail_count; uint32_t protocol_count; diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 6e97fa4cf2714f..e3277b764e2957 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -91,7 +91,7 @@ static void setup_tx_dma(hal_uart_driver* uart) dmaStreamSetMode(uart->dmatx, uart->dmatxmode | STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); // enable transmission complete interrupt - uart->usart->SR = ~USART_SR_TC; + uart->usart->SR &= ~USART_SR_TC; uart->usart->CR1 |= USART_CR1_TCIE; dmaStreamEnable(uart->dmatx); @@ -303,7 +303,7 @@ void AP_IOMCU_FW::init() thread_ctx = chThdGetSelfX(); #if AP_HAL_SHARED_DMA_ENABLED - tx_dma_handle = new ChibiOS::Shared_DMA(STM32_UART_USART2_TX_DMA_STREAM, SHARED_DMA_NONE, + tx_dma_handle = NEW_NOTHROW ChibiOS::Shared_DMA(STM32_UART_USART2_TX_DMA_STREAM, SHARED_DMA_NONE, FUNCTOR_BIND_MEMBER(&AP_IOMCU_FW::tx_dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&AP_IOMCU_FW::tx_dma_deallocate, void, Shared_DMA *)); tx_dma_handle->lock(); @@ -489,6 +489,10 @@ void AP_IOMCU_FW::update() last_status_ms = now; page_status_update(); } + +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + profiled_update(); +#endif #ifdef HAL_WITH_BIDIR_DSHOT // EDT updates are semt at ~1Hz per ESC, but we want to make sure // that we don't delay updates unduly so sample at 5Hz @@ -635,25 +639,34 @@ void AP_IOMCU_FW::telem_update() uint32_t now_ms = AP_HAL::millis(); for (uint8_t i = 0; i < IOMCU_MAX_TELEM_CHANNELS/4; i++) { + struct page_dshot_telem &dshot_i = dshot_telem[i]; for (uint8_t j = 0; j < 4; j++) { const uint8_t esc_id = (i * 4 + j); if (esc_id >= IOMCU_MAX_TELEM_CHANNELS) { continue; } - dshot_telem[i].error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); + dshot_i.error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); #if HAL_WITH_ESC_TELEM const volatile AP_ESC_Telem_Backend::TelemetryData& telem = esc_telem.get_telem_data(esc_id); // if data is stale then set to zero to avoid phantom data appearing in mavlink if (now_ms - telem.last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS) { - dshot_telem[i].voltage_cvolts[j] = 0; - dshot_telem[i].current_camps[j] = 0; - dshot_telem[i].temperature_cdeg[j] = 0; + dshot_i.voltage_cvolts[j] = 0; + dshot_i.current_camps[j] = 0; + dshot_i.temperature_cdeg[j] = 0; +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + dshot_i.edt2_status[j] = 0; + dshot_i.edt2_stress[j] = 0; +#endif continue; } - dshot_telem[i].voltage_cvolts[j] = uint16_t(roundf(telem.voltage * 100)); - dshot_telem[i].current_camps[j] = uint16_t(roundf(telem.current * 100)); - dshot_telem[i].temperature_cdeg[j] = telem.temperature_cdeg; - dshot_telem[i].types[j] = telem.types; + dshot_i.voltage_cvolts[j] = uint16_t(roundf(telem.voltage * 100)); + dshot_i.current_camps[j] = uint16_t(roundf(telem.current * 100)); + dshot_i.temperature_cdeg[j] = telem.temperature_cdeg; +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + dshot_i.edt2_status[j] = uint8_t(telem.edt2_status); + dshot_i.edt2_stress[j] = uint8_t(telem.edt2_stress); +#endif + dshot_i.types[j] = telem.types; #endif } } @@ -911,6 +924,7 @@ bool AP_IOMCU_FW::handle_code_write() mode_out.mode = rx_io_packet.regs[1]; mode_out.bdmask = rx_io_packet.regs[2]; mode_out.esc_type = rx_io_packet.regs[3]; + mode_out.reversible_mask = rx_io_packet.regs[4]; break; case PAGE_REG_SETUP_HEATER_DUTY_CYCLE: @@ -966,7 +980,7 @@ bool AP_IOMCU_FW::handle_code_write() } /* copy channel data */ uint16_t i = 0, num_values = rx_io_packet.count; - while ((i < IOMCU_MAX_CHANNELS) && (num_values > 0)) { + while ((i < IOMCU_MAX_RC_CHANNELS) && (num_values > 0)) { /* XXX range-check value? */ if (rx_io_packet.regs[i] != PWM_IGNORE_THIS_CHANNEL) { reg_direct_pwm.pwm[i] = rx_io_packet.regs[i]; @@ -1019,6 +1033,20 @@ bool AP_IOMCU_FW::handle_code_write() break; } +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + case PAGE_PROFILED: + if (rx_io_packet.count != 2 || (rx_io_packet.regs[0] & 0xFF) != PROFILED_ENABLE_MAGIC) { + return false; + } + profiled_brg[0] = rx_io_packet.regs[0] >> 8; + profiled_brg[1] = rx_io_packet.regs[1] & 0xFF; + profiled_brg[2] = rx_io_packet.regs[1] >> 8; + // push new led data + profiled_num_led_pushed = 0; + profiled_control_enabled = true; + break; +#endif + default: break; } @@ -1053,6 +1081,48 @@ void AP_IOMCU_FW::calculate_fw_crc(void) reg_setup.crc[1] = sum >> 16; } +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED +// bitbang profiled bitstream, 8-10 chunks at a time +// Max time taken per call is ~7us +void AP_IOMCU_FW::profiled_update(void) +{ + if (profiled_num_led_pushed > PROFILED_LED_LEN) { + profiled_byte_index = 0; + profiled_leading_zeros = PROFILED_LEADING_ZEROS; + return; + } + + // push 10 zero leading bits at a time + if (profiled_leading_zeros != 0) { + for (uint8_t i = 0; i < 10; i++) { + palClearLine(HAL_GPIO_PIN_SAFETY_INPUT); + palSetLine(HAL_GPIO_PIN_SAFETY_INPUT); + profiled_leading_zeros--; + } + return; + } + + if ((profiled_byte_index == 0) || + (profiled_byte_index == PROFILED_OUTPUT_BYTE_LEN)) { + // start bit + palClearLine(HAL_GPIO_PIN_SAFETY_INPUT); + palSetLine(HAL_GPIO_PIN_SAFETY_LED); + palSetLine(HAL_GPIO_PIN_SAFETY_INPUT); + profiled_byte_index = 0; + profiled_num_led_pushed++; + } + + uint8_t byte_val = profiled_brg[profiled_byte_index]; + for (uint8_t i = 0; i < 8; i++) { + palClearLine(HAL_GPIO_PIN_SAFETY_INPUT); + palWriteLine(HAL_GPIO_PIN_SAFETY_LED, byte_val & 1); + byte_val >>= 1; + palSetLine(HAL_GPIO_PIN_SAFETY_INPUT); + } + + profiled_byte_index++; +} +#endif /* update safety state @@ -1066,6 +1136,15 @@ void AP_IOMCU_FW::safety_update(void) } safety_update_ms = now; +#if AP_IOMCU_PROFILED_SUPPORT_ENABLED + if (profiled_control_enabled) { + // set line mode to output for safety input pin + palSetLineMode(HAL_GPIO_PIN_SAFETY_INPUT, PAL_MODE_OUTPUT_PUSHPULL); + palSetLineMode(HAL_GPIO_PIN_SAFETY_LED, PAL_MODE_OUTPUT_PUSHPULL); + return; + } +#endif + bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_INPUT); if (safety_pressed) { if (reg_status.flag_safety_off && (reg_setup.arming & P_SETUP_ARMING_SAFETY_DISABLE_ON)) { @@ -1088,6 +1167,8 @@ void AP_IOMCU_FW::safety_update(void) hal.rcout->force_safety_on(); } } + // update the armed state + hal.util->set_soft_armed((reg_setup.arming & P_SETUP_ARMING_FMU_ARMED) != 0); #if IOMCU_ENABLE_RESET_TEST { @@ -1166,6 +1247,7 @@ void AP_IOMCU_FW::rcout_config_update(void) // see if there is anything to do, we only support setting the mode for a particular channel once if ((last_output_mode_mask & mode_out.mask) == mode_out.mask && (last_output_bdmask & mode_out.bdmask) == mode_out.bdmask + && (last_output_reversible_mask & mode_out.reversible_mask) == mode_out.reversible_mask && last_output_esc_type == mode_out.esc_type) { return; } @@ -1178,13 +1260,15 @@ void AP_IOMCU_FW::rcout_config_update(void) #endif #ifdef HAL_WITH_BIDIR_DSHOT hal.rcout->set_bidir_dshot_mask(mode_out.bdmask); - hal.rcout->set_dshot_esc_type(AP_HAL::RCOutput::DshotEscType(mode_out.esc_type)); #endif + hal.rcout->set_reversible_mask(mode_out.reversible_mask); + hal.rcout->set_dshot_esc_type(AP_HAL::RCOutput::DshotEscType(mode_out.esc_type)); hal.rcout->set_output_mode(mode_out.mask, (AP_HAL::RCOutput::output_mode)mode_out.mode); // enabling dshot changes the memory allocation reg_status.freemem = hal.util->available_memory(); last_output_mode_mask |= mode_out.mask; last_output_bdmask |= mode_out.bdmask; + last_output_reversible_mask |= mode_out.reversible_mask; last_output_esc_type = mode_out.esc_type; break; case AP_HAL::RCOutput::MODE_PWM_ONESHOT: @@ -1216,7 +1300,7 @@ void AP_IOMCU_FW::rcout_config_update(void) */ void AP_IOMCU_FW::fill_failsafe_pwm(void) { - for (uint8_t i=0; i 0 && mixing.rc_channel[i] <= IOMCU_MAX_CHANNELS) { + if (mixing.rc_channel[i] > 0 && mixing.rc_channel[i] <= IOMCU_MAX_RC_CHANNELS) { uint8_t chan = mixing.rc_channel[i]-1; if (i == 2 && !mixing.throttle_is_angle) { rcin[i] = mix_input_range(i, rc_input.pwm[chan]); @@ -141,7 +141,7 @@ void AP_IOMCU_FW::run_mixer(void) } } - for (uint8_t i=0; i -#include #include "AP_InertialNav.h" +#include + /* A wrapper around the AP_InertialNav class which uses the NavEKF filter if available, and falls back to the AP_InertialNav filter diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index 9159a4180917a1..0a50e732df9680 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -5,14 +5,13 @@ */ #pragma once -#include #include // definitions shared by inertial and ekf nav filters class AP_InertialNav { public: // Constructor - AP_InertialNav(AP_AHRS &ahrs) : + AP_InertialNav(class AP_AHRS &ahrs) : _ahrs_ekf(ahrs) {} diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index b2a76a1f266b28..8c6f05fd1e6789 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -721,7 +721,7 @@ AP_InertialSensor::AP_InertialSensor() : AP_InertialSensor *AP_InertialSensor::get_singleton() { if (!_singleton) { - _singleton = new AP_InertialSensor(); + _singleton = NEW_NOTHROW AP_InertialSensor(); } return _singleton; } @@ -736,6 +736,14 @@ bool AP_InertialSensor::register_gyro(uint8_t &instance, uint16_t raw_sample_rat return false; } + // Loop over the existing instances and check if the instance already exists + for (uint8_t instance_to_check = 0; instance_to_check < _gyro_count; instance_to_check++) { + if ((uint32_t)_gyro_id(instance_to_check) == id) { + // if it does, then bail + return false; + } + } + _gyro_raw_sample_rates[_gyro_count] = raw_sample_rate_hz; _gyro_over_sampling[_gyro_count] = 1; _gyro_raw_sampling_multiplier[_gyro_count] = INT16_MAX/radians(2000); @@ -796,6 +804,14 @@ bool AP_InertialSensor::register_accel(uint8_t &instance, uint16_t raw_sample_ra return false; } + // Loop over the existing instances and check if the instance already exists + for (uint8_t instance_to_check = 0; instance_to_check < _accel_count; instance_to_check++) { + if ((uint32_t)_accel_id(instance_to_check) == id) { + // if it does, then bail + return false; + } + } + _accel_raw_sample_rates[_accel_count] = raw_sample_rate_hz; _accel_over_sampling[_accel_count] = 1; _accel_raw_sampling_multiplier[_accel_count] = INT16_MAX/(16*GRAVITY_MSS); @@ -838,9 +854,11 @@ void AP_InertialSensor::_start_backends() _backends[i]->start(); } +#if AP_INERTIALSENSOR_ALLOW_NO_SENSORS if (_gyro_count == 0 || _accel_count == 0) { AP_HAL::panic("INS needs at least 1 gyro and 1 accel"); } +#endif // clear IDs for unused sensor instances for (uint8_t i=get_accel_count(); i 0) { init_gyro(); } @@ -1157,7 +1175,7 @@ AP_InertialSensor::detect_backends(void) // if enabled, make the first IMU the external AHRS const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::IMU); if (serial_port >= 0) { - ADD_BACKEND(new AP_InertialSensor_ExternalAHRS(*this, serial_port)); + ADD_BACKEND(NEW_NOTHROW AP_InertialSensor_ExternalAHRS(*this, serial_port)); } #endif @@ -1308,8 +1326,10 @@ AP_InertialSensor::detect_backends(void) #else DEV_PRINTF("INS: unable to initialise driver\n"); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: unable to initialise driver"); + #if !AP_INERTIALSENSOR_ALLOW_NO_SENSORS AP_BoardConfig::config_error("INS: unable to initialise driver"); #endif + #endif } } @@ -1850,7 +1870,9 @@ void AP_InertialSensor::HarmonicNotch::update_params(uint8_t instance, bool conv last_center_freq_hz[instance] = params.center_freq_hz(); last_bandwidth_hz[instance] = params.bandwidth_hz(); last_attenuation_dB[instance] = params.attenuation_dB(); - } else if (params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) { + } + + if (params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) { if (num_calculated_notch_frequencies > 1) { filter[instance].update(num_calculated_notch_frequencies, calculated_notch_freq_hz); } else { @@ -1931,13 +1953,13 @@ void AP_InertialSensor::update(void) // set primary to first healthy accel and gyro for (uint8_t i=0; i> 2) & 3) { case 0: gyro_scale = radians(125) / 0x4E200000; - dangle_scale = radians(360.0 / 0x7FFFFFFF); + dangle_scale = radians(360.0 / (float)0x7FFFFFFF); break; case 1: gyro_scale = radians(500) / 0x4E200000; - dangle_scale = radians(720.0 / 0x7FFFFFFF); + dangle_scale = radians(720.0 / (float)0x7FFFFFFF); break; case 3: gyro_scale = radians(2000) / 0x4E200000; - dangle_scale = radians(2160.0 / 0x7FFFFFFF); + dangle_scale = radians(2160.0 / (float)0x7FFFFFFF); break; default: return false; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.h b/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.h index 6c2a6d2851ad73..5dc97edb2aac1a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.h @@ -66,8 +66,6 @@ class AP_InertialSensor_ADIS1647x : public AP_InertialSensor_Backend { Delta32 =3 } opmode; - uint8_t accel_instance; - uint8_t gyro_instance; enum Rotation rotation; uint8_t drdy_pin; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp index f916e0e063c208..5886993f628892 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp @@ -85,7 +85,7 @@ AP_InertialSensor_BMI055::probe(AP_InertialSensor &imu, if (!dev_accel || !dev_gyro) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI055(imu, std::move(dev_accel), std::move(dev_gyro), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI055(imu, std::move(dev_accel), std::move(dev_gyro), rotation); if (!sensor) { return nullptr; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.h index 5b5773a3272f06..6622906e2dd49d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.h @@ -62,8 +62,6 @@ class AP_InertialSensor_BMI055 : public AP_InertialSensor_Backend { AP_HAL::OwnPtr dev_accel; AP_HAL::OwnPtr dev_gyro; - uint8_t accel_instance; - uint8_t gyro_instance; enum Rotation rotation; uint8_t temperature_counter; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp index aa839b6b4e6bbc..a0a538704c970b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp @@ -84,7 +84,7 @@ AP_InertialSensor_BMI088::probe(AP_InertialSensor &imu, if (!dev_accel || !dev_gyro) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI088(imu, std::move(dev_accel), std::move(dev_gyro), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI088(imu, std::move(dev_accel), std::move(dev_gyro), rotation); if (!sensor) { return nullptr; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h index d8820529aa88ae..005ddc2615daf4 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h @@ -79,8 +79,6 @@ class AP_InertialSensor_BMI088 : public AP_InertialSensor_Backend { AP_HAL::OwnPtr dev_gyro; AP_HAL::Device::PeriodicHandle gyro_periodic_handle; - uint8_t accel_instance; - uint8_t gyro_instance; enum Rotation rotation; uint8_t temperature_counter; enum DevTypes _accel_devtype; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp index aff58e5b3503e0..777ab3cf0e30d7 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp @@ -135,7 +135,7 @@ AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu, if (!dev) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI160(imu, std::move(dev), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI160(imu, std::move(dev), rotation); if (!sensor) { return nullptr; @@ -157,7 +157,7 @@ AP_InertialSensor_BMI160::probe(AP_InertialSensor &imu, if (!dev) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI160(imu, std::move(dev), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI160(imu, std::move(dev), rotation); if (!sensor) { return nullptr; @@ -201,8 +201,8 @@ void AP_InertialSensor_BMI160::start() _dev->get_semaphore()->give(); - if (!_imu.register_accel(_accel_instance, BMI160_ODR_TO_HZ(BMI160_ODR), _dev->get_bus_id_devtype(DEVTYPE_BMI160)) || - !_imu.register_gyro(_gyro_instance, BMI160_ODR_TO_HZ(BMI160_ODR), _dev->get_bus_id_devtype(DEVTYPE_BMI160))) { + if (!_imu.register_accel(accel_instance, BMI160_ODR_TO_HZ(BMI160_ODR), _dev->get_bus_id_devtype(DEVTYPE_BMI160)) || + !_imu.register_gyro(gyro_instance, BMI160_ODR_TO_HZ(BMI160_ODR), _dev->get_bus_id_devtype(DEVTYPE_BMI160))) { return; } @@ -213,8 +213,8 @@ void AP_InertialSensor_BMI160::start() bool AP_InertialSensor_BMI160::update() { - update_accel(_accel_instance); - update_gyro(_gyro_instance); + update_accel(accel_instance); + update_gyro(gyro_instance); return true; } @@ -420,11 +420,11 @@ void AP_InertialSensor_BMI160::_read_fifo() accel *= _accel_scale; gyro *= _gyro_scale; - _rotate_and_correct_accel(_accel_instance, accel); - _rotate_and_correct_gyro(_gyro_instance, gyro); + _rotate_and_correct_accel(accel_instance, accel); + _rotate_and_correct_gyro(gyro_instance, gyro); - _notify_new_accel_raw_sample(_accel_instance, accel); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _notify_new_accel_raw_sample(accel_instance, accel); + _notify_new_gyro_raw_sample(gyro_instance, gyro); } if (excess) { diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.h index 77aac9eb08f3b1..fe5940015ab3f9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.h @@ -120,10 +120,7 @@ class AP_InertialSensor_BMI160 : public AP_InertialSensor_Backend { AP_HAL::OwnPtr _dev; enum Rotation _rotation; - uint8_t _accel_instance; float _accel_scale; - - uint8_t _gyro_instance; float _gyro_scale; AP_HAL::DigitalSource *_int1_pin; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp index 37bade08b8fd33..41776d0143e9fb 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp @@ -164,7 +164,7 @@ AP_InertialSensor_BMI270::probe(AP_InertialSensor &imu, if (!dev) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI270(imu, std::move(dev), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI270(imu, std::move(dev), rotation); if (!sensor) { return nullptr; @@ -186,7 +186,7 @@ AP_InertialSensor_BMI270::probe(AP_InertialSensor &imu, if (!dev) { return nullptr; } - auto sensor = new AP_InertialSensor_BMI270(imu, std::move(dev), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_BMI270(imu, std::move(dev), rotation); if (!sensor) { return nullptr; @@ -212,14 +212,14 @@ void AP_InertialSensor_BMI270::start() _dev->get_semaphore()->give(); - 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))) { + 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; } // setup sensor rotations from probe() - set_gyro_orientation(_gyro_instance, _rotation); - set_accel_orientation(_accel_instance, _rotation); + set_gyro_orientation(gyro_instance, _rotation); + set_accel_orientation(accel_instance, _rotation); /* Call read_fifo() at 1600Hz */ periodic_handle = _dev->register_periodic_callback(BACKEND_PERIOD_US, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_BMI270::read_fifo, void)); @@ -227,8 +227,8 @@ void AP_InertialSensor_BMI270::start() bool AP_InertialSensor_BMI270::update() { - update_accel(_accel_instance); - update_gyro(_gyro_instance); + update_accel(accel_instance); + update_gyro(gyro_instance); return true; } @@ -364,8 +364,8 @@ 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); + notify_accel_fifo_reset(accel_instance); + notify_gyro_fifo_reset(gyro_instance); } /* @@ -383,8 +383,8 @@ void AP_InertialSensor_BMI270::read_fifo(void) uint8_t len[2]; if (!read_registers(BMI270_REG_FIFO_LENGTH_LSB, len, 2)) { - _inc_accel_error_count(_accel_instance); - _inc_gyro_error_count(_gyro_instance); + _inc_accel_error_count(accel_instance); + _inc_gyro_error_count(gyro_instance); return; } uint16_t fifo_length = len[0] + (len[1]<<8); @@ -403,8 +403,8 @@ void AP_InertialSensor_BMI270::read_fifo(void) uint8_t data[fifo_length]; if (!read_registers(BMI270_REG_FIFO_DATA, data, fifo_length)) { - _inc_accel_error_count(_accel_instance); - _inc_gyro_error_count(_gyro_instance); + _inc_accel_error_count(accel_instance); + _inc_gyro_error_count(gyro_instance); return; } @@ -462,14 +462,14 @@ void AP_InertialSensor_BMI270::read_fifo(void) temperature_counter = 0; uint8_t tbuf[2]; if (!read_registers(BMI270_REG_TEMPERATURE_LSB, tbuf, 2)) { - _inc_accel_error_count(_accel_instance); - _inc_gyro_error_count(_gyro_instance); + _inc_accel_error_count(accel_instance); + _inc_gyro_error_count(gyro_instance); } else { 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); + _publish_temperature(accel_instance, temp_degc); } } } @@ -487,8 +487,8 @@ void AP_InertialSensor_BMI270::parse_accel_frame(const uint8_t* d) accel *= scale; - _rotate_and_correct_accel(_accel_instance, accel); - _notify_new_accel_raw_sample(_accel_instance, accel); + _rotate_and_correct_accel(accel_instance, accel); + _notify_new_accel_raw_sample(accel_instance, accel); } void AP_InertialSensor_BMI270::parse_gyro_frame(const uint8_t* d) @@ -502,8 +502,8 @@ void AP_InertialSensor_BMI270::parse_gyro_frame(const uint8_t* d) Vector3f gyro(xyz[0], xyz[1], xyz[2]); gyro *= scale; - _rotate_and_correct_gyro(_gyro_instance, gyro); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _rotate_and_correct_gyro(gyro_instance, gyro); + _notify_new_gyro_raw_sample(gyro_instance, gyro); } bool AP_InertialSensor_BMI270::hardware_init() diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h index fb21ca0f57de53..0e16d230945c71 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h @@ -115,8 +115,6 @@ class AP_InertialSensor_BMI270 : public AP_InertialSensor_Backend { enum Rotation _rotation; - uint8_t _accel_instance; - uint8_t _gyro_instance; uint8_t temperature_counter; static const uint8_t maximum_fifo_config_file[]; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 79d36134f94964..944b20661a1315 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -164,7 +164,7 @@ void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vecto */ void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &gyro) /* front end */ { - if ((1U<_init()) { delete sensor; return nullptr; @@ -140,7 +140,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensense::probe(AP_InertialSensor dev->set_read_flag(0x80); - sensor = new AP_InertialSensor_Invensense(imu, std::move(dev), rotation); + sensor = NEW_NOTHROW AP_InertialSensor_Invensense(imu, std::move(dev), rotation); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; @@ -202,8 +202,8 @@ void AP_InertialSensor_Invensense::_fifo_reset(bool log_error) _dev->set_speed(AP_HAL::Device::SPEED_HIGH); _last_stat_user_ctrl = user_ctrl | BIT_USER_CTRL_FIFO_EN; - notify_accel_fifo_reset(_accel_instance); - notify_gyro_fifo_reset(_gyro_instance); + notify_accel_fifo_reset(accel_instance); + notify_gyro_fifo_reset(gyro_instance); } void AP_InertialSensor_Invensense::_fast_fifo_reset() @@ -211,8 +211,8 @@ 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); + notify_accel_fifo_reset(accel_instance); + notify_gyro_fifo_reset(gyro_instance); } @@ -224,7 +224,7 @@ bool AP_InertialSensor_Invensense::_has_auxiliary_bus() void AP_InertialSensor_Invensense::start() { // pre-fetch instance numbers for checking fast sampling settings - if (!_imu.get_gyro_instance(_gyro_instance) || !_imu.get_accel_instance(_accel_instance)) { + if (!_imu.get_gyro_instance(gyro_instance) || !_imu.get_accel_instance(accel_instance)) { return; } @@ -320,8 +320,8 @@ void AP_InertialSensor_Invensense::start() break; } - if (!_imu.register_gyro(_gyro_instance, 1000, _dev->get_bus_id_devtype(gdev)) || - !_imu.register_accel(_accel_instance, 1000, _dev->get_bus_id_devtype(adev))) { + if (!_imu.register_gyro(gyro_instance, 1000, _dev->get_bus_id_devtype(gdev)) || + !_imu.register_accel(accel_instance, 1000, _dev->get_bus_id_devtype(adev))) { return; } @@ -329,12 +329,12 @@ void AP_InertialSensor_Invensense::start() _set_filter_register(); // update backend sample rate - _set_accel_raw_sample_rate(_accel_instance, _accel_backend_rate_hz); - _set_gyro_raw_sample_rate(_gyro_instance, _gyro_backend_rate_hz); + _set_accel_raw_sample_rate(accel_instance, _accel_backend_rate_hz); + _set_gyro_raw_sample_rate(gyro_instance, _gyro_backend_rate_hz); // indicate what multiplier is appropriate for the sensors' // readings to fit them into an int16_t: - _set_raw_sample_accel_multiplier(_accel_instance, multiplier_accel); + _set_raw_sample_accel_multiplier(accel_instance, multiplier_accel); // set sample rate to 1000Hz and apply a software filter // In this configuration, the gyro sample rate is 8kHz @@ -426,8 +426,8 @@ void AP_InertialSensor_Invensense::start() _dev->set_speed(AP_HAL::Device::SPEED_HIGH); // setup sensor rotations from probe() - set_gyro_orientation(_gyro_instance, _rotation); - set_accel_orientation(_accel_instance, _rotation); + set_gyro_orientation(gyro_instance, _rotation); + set_accel_orientation(accel_instance, _rotation); // setup scale factors for fifo data after downsampling _fifo_accel_scale = _accel_scale / _accel_fifo_downsample_rate; @@ -447,7 +447,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 * 0.001, _gyro_backend_rate_hz * 0.001); + gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate * 0.001, _gyro_backend_rate_hz * 0.001); return true; } return false; @@ -459,10 +459,10 @@ bool AP_InertialSensor_Invensense::get_output_banner(char* banner, uint8_t banne */ bool AP_InertialSensor_Invensense::update() /* front end */ { - update_accel(_accel_instance); - update_gyro(_gyro_instance); + update_accel(accel_instance); + update_gyro(gyro_instance); - _publish_temperature(_accel_instance, _temp_filtered); + _publish_temperature(accel_instance, _temp_filtered); if (fast_reset_count) { // check if we have reported in the last 1 seconds or @@ -472,13 +472,13 @@ bool AP_InertialSensor_Invensense::update() /* front end */ 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)); + 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); + AP::logger().Write_MessageF("IMU%u fast fifo reset %u", gyro_instance, fast_reset_count); last_fast_reset_count = fast_reset_count; } #endif @@ -502,7 +502,7 @@ AuxiliaryBus *AP_InertialSensor_Invensense::get_auxiliary_bus() } if (_has_auxiliary_bus()) { - _auxiliary_bus = new AP_Invensense_AuxiliaryBus(*this, _dev->get_bus_id()); + _auxiliary_bus = NEW_NOTHROW AP_Invensense_AuxiliaryBus(*this, _dev->get_bus_id()); } return _auxiliary_bus; @@ -602,7 +602,7 @@ bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_sampl return false; } else { if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + debug("temp reset IMU[%u] %d %d", accel_instance, _raw_temp, t2); } _fifo_reset(true); return false; @@ -615,11 +615,11 @@ bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_sampl -int16_val(data, 6)); gyro *= _gyro_scale; - _rotate_and_correct_accel(_accel_instance, accel); - _rotate_and_correct_gyro(_gyro_instance, gyro); + _rotate_and_correct_accel(accel_instance, accel); + _rotate_and_correct_gyro(gyro_instance, gyro); - _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _notify_new_accel_raw_sample(accel_instance, accel, 0, fsync_set); + _notify_new_gyro_raw_sample(gyro_instance, gyro); _temp_filtered = _temp_filter.apply(temp); } @@ -652,7 +652,7 @@ bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *sam ret = false; } else { if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + debug("temp reset IMU[%u] %d %d", accel_instance, _raw_temp, t2); } _fifo_reset(true); ret = false; @@ -674,14 +674,14 @@ bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *sam _accum.accel += _accum.accel_filter.apply(a); Vector3f a2 = a * _accel_scale; - _notify_new_accel_sensor_rate_sample(_accel_instance, a2); + _notify_new_accel_sensor_rate_sample(accel_instance, a2); _accum.accel_count++; if (_accum.accel_count % _accel_fifo_downsample_rate == 0) { _accum.accel *= _fifo_accel_scale; - _rotate_and_correct_accel(_accel_instance, _accum.accel); - _notify_new_accel_raw_sample(_accel_instance, _accum.accel, 0, false); + _rotate_and_correct_accel(accel_instance, _accum.accel); + _notify_new_accel_raw_sample(accel_instance, _accum.accel, 0, false); _accum.accel.zero(); _accum.accel_count = 0; // we assume that the gyro rate is always >= and a multiple of the accel rate @@ -696,20 +696,20 @@ bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *sam -int16_val(data, 6)); Vector3f g2 = g * _gyro_scale; - _notify_new_gyro_sensor_rate_sample(_gyro_instance, g2); + _notify_new_gyro_sensor_rate_sample(gyro_instance, g2); _accum.gyro += g; if (_accum.gyro_count % _gyro_fifo_downsample_rate == 0) { _accum.gyro *= _fifo_gyro_scale; - _rotate_and_correct_gyro(_gyro_instance, _accum.gyro); - _notify_new_gyro_raw_sample(_gyro_instance, _accum.gyro); + _rotate_and_correct_gyro(gyro_instance, _accum.gyro); + _notify_new_gyro_raw_sample(gyro_instance, _accum.gyro); _accum.gyro.zero(); } } if (clipped) { - increment_clip_count(_accel_instance); + increment_clip_count(accel_instance); } if (ret) { @@ -788,7 +788,7 @@ void AP_InertialSensor_Invensense::_read_fifo() if (_fast_sampling) { if (!_accumulate_sensor_rate_sampling(rx, n)) { 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); + debug("IMU[%u] stop at %u of %u", accel_instance, n_samples, bytes_read/MPU_SAMPLE_SIZE); } break; } @@ -831,8 +831,8 @@ void AP_InertialSensor_Invensense::_read_fifo() AP_HAL::Device::checkreg reg; if (!_dev->check_next_register(reg)) { log_register_change(_dev->get_bus_id(), reg); - _inc_gyro_error_count(_gyro_instance); - _inc_accel_error_count(_accel_instance); + _inc_gyro_error_count(gyro_instance); + _inc_accel_error_count(accel_instance); } _dev->set_speed(AP_HAL::Device::SPEED_HIGH); } @@ -890,7 +890,7 @@ void AP_InertialSensor_Invensense::_set_filter_register(void) _gyro_to_accel_sample_ratio = 2; _gyro_backend_rate_hz = _accel_backend_rate_hz = 1000; - if (enable_fast_sampling(_accel_instance)) { + if (enable_fast_sampling(accel_instance)) { _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 @@ -919,11 +919,11 @@ void AP_InertialSensor_Invensense::_set_filter_register(void) } // for logging purposes set the oversamping rate - _set_accel_oversampling(_accel_instance, _accel_fifo_downsample_rate); - _set_gyro_oversampling(_gyro_instance, _gyro_fifo_downsample_rate); + _set_accel_oversampling(accel_instance, _accel_fifo_downsample_rate); + _set_gyro_oversampling(gyro_instance, _gyro_fifo_downsample_rate); - _set_accel_sensor_rate_sampling_enabled(_accel_instance, true); - _set_gyro_sensor_rate_sampling_enabled(_gyro_instance, true); + _set_accel_sensor_rate_sampling_enabled(accel_instance, true); + _set_gyro_sensor_rate_sampling_enabled(gyro_instance, true); /* set divider for internal sample rate to 0x1F when fast sampling enabled. This reduces the impact of the slave @@ -1204,7 +1204,7 @@ AuxiliaryBusSlave *AP_Invensense_AuxiliaryBus::_instantiate_slave(uint8_t addr, _configure_slaves(); } - return new AP_Invensense_AuxiliaryBusSlave(*this, addr, instance); + return NEW_NOTHROW AP_Invensense_AuxiliaryBusSlave(*this, addr, instance); } void AP_Invensense_AuxiliaryBus::_configure_slaves() diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h index 7f77e35e48aaf8..7ba132f3a309a7 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h @@ -115,10 +115,6 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend int16_t _raw_temp; - // instance numbers of accel and gyro data - uint8_t _gyro_instance; - uint8_t _accel_instance; - float temp_sensitivity = 1.0f/340; // degC/LSB float temp_zero = 36.53f; // degC @@ -186,7 +182,7 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend Vector3f gyro; uint8_t accel_count; uint8_t gyro_count; - LowPassFilterVector3f accel_filter{4000, 188}; + LowPassFilterConstDtVector3f accel_filter{4000, 188}; } _accum; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp index 0503fad44b638f..b8279d339fd624 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp @@ -94,7 +94,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSens return nullptr; } AP_InertialSensor_Invensensev2 *sensor = - new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation); + NEW_NOTHROW AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; @@ -116,7 +116,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev2::probe(AP_InertialSens dev->set_read_flag(0x80); - sensor = new AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation); + sensor = NEW_NOTHROW AP_InertialSensor_Invensensev2(imu, std::move(dev), rotation); if (!sensor || !sensor->_init()) { delete sensor; return nullptr; @@ -155,8 +155,8 @@ void AP_InertialSensor_Invensensev2::_fifo_reset() _dev->set_speed(AP_HAL::Device::SPEED_HIGH); _last_stat_user_ctrl = user_ctrl | BIT_USER_CTRL_FIFO_EN; - notify_accel_fifo_reset(_accel_instance); - notify_gyro_fifo_reset(_gyro_instance); + notify_accel_fifo_reset(accel_instance); + notify_gyro_fifo_reset(gyro_instance); } bool AP_InertialSensor_Invensensev2::_has_auxiliary_bus() @@ -167,7 +167,7 @@ bool AP_InertialSensor_Invensensev2::_has_auxiliary_bus() void AP_InertialSensor_Invensensev2::start() { // pre-fetch instance numbers for checking fast sampling settings - if (!_imu.get_gyro_instance(_gyro_instance) || !_imu.get_accel_instance(_accel_instance)) { + if (!_imu.get_gyro_instance(gyro_instance) || !_imu.get_accel_instance(accel_instance)) { return; } @@ -207,8 +207,8 @@ void AP_InertialSensor_Invensensev2::start() break; } - if (!_imu.register_gyro(_gyro_instance, 1125, _dev->get_bus_id_devtype(gdev)) || - !_imu.register_accel(_accel_instance, 1125, _dev->get_bus_id_devtype(adev))) { + if (!_imu.register_gyro(gyro_instance, 1125, _dev->get_bus_id_devtype(gdev)) || + !_imu.register_accel(accel_instance, 1125, _dev->get_bus_id_devtype(adev))) { return; } @@ -219,12 +219,12 @@ void AP_InertialSensor_Invensensev2::start() _register_write(INV2REG_FSYNC_CONFIG, FSYNC_CONFIG_EXT_SYNC_AZ, true); #endif // update backend sample rate - _set_accel_raw_sample_rate(_accel_instance, _accel_backend_rate_hz); - _set_gyro_raw_sample_rate(_gyro_instance, _gyro_backend_rate_hz); + _set_accel_raw_sample_rate(accel_instance, _accel_backend_rate_hz); + _set_gyro_raw_sample_rate(gyro_instance, _gyro_backend_rate_hz); // indicate what multiplier is appropriate for the sensors' // readings to fit them into an int16_t: - _set_raw_sample_accel_multiplier(_accel_instance, multiplier_accel); + _set_raw_sample_accel_multiplier(accel_instance, multiplier_accel); // set sample rate to 1.125KHz _register_write(INV2REG_GYRO_SMPLRT_DIV, 0, true); @@ -238,8 +238,8 @@ void AP_InertialSensor_Invensensev2::start() _dev->set_speed(AP_HAL::Device::SPEED_HIGH); // setup sensor rotations from probe() - set_gyro_orientation(_gyro_instance, _rotation); - set_accel_orientation(_accel_instance, _rotation); + set_gyro_orientation(gyro_instance, _rotation); + set_accel_orientation(accel_instance, _rotation); // setup scale factors for fifo data after downsampling _fifo_accel_scale = _accel_scale / _accel_fifo_downsample_rate; @@ -259,7 +259,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 * 0.001, _gyro_backend_rate_hz * 0.001); + gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate * 0.001, _gyro_backend_rate_hz * 0.001); return true; } return false; @@ -270,10 +270,10 @@ bool AP_InertialSensor_Invensensev2::get_output_banner(char* banner, uint8_t ban */ bool AP_InertialSensor_Invensensev2::update() { - update_accel(_accel_instance); - update_gyro(_gyro_instance); + update_accel(accel_instance); + update_gyro(gyro_instance); - _publish_temperature(_accel_instance, _temp_filtered); + _publish_temperature(accel_instance, _temp_filtered); return true; } @@ -293,7 +293,7 @@ AuxiliaryBus *AP_InertialSensor_Invensensev2::get_auxiliary_bus() } if (_has_auxiliary_bus()) { - _auxiliary_bus = new AP_Invensensev2_AuxiliaryBus(*this, _dev->get_bus_id()); + _auxiliary_bus = NEW_NOTHROW AP_Invensensev2_AuxiliaryBus(*this, _dev->get_bus_id()); } return _auxiliary_bus; @@ -341,7 +341,7 @@ bool AP_InertialSensor_Invensensev2::_accumulate(uint8_t *samples, uint8_t n_sam int16_t t2 = int16_val(data, 6); if (!_check_raw_temp(t2)) { if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + debug("temp reset IMU[%u] %d %d", accel_instance, _raw_temp, t2); } _fifo_reset(); return false; @@ -353,11 +353,11 @@ bool AP_InertialSensor_Invensensev2::_accumulate(uint8_t *samples, uint8_t n_sam -int16_val(data, 5)); gyro *= GYRO_SCALE; - _rotate_and_correct_accel(_accel_instance, accel); - _rotate_and_correct_gyro(_gyro_instance, gyro); + _rotate_and_correct_accel(accel_instance, accel); + _rotate_and_correct_gyro(gyro_instance, gyro); - _notify_new_accel_raw_sample(_accel_instance, accel, 0, fsync_set); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _notify_new_accel_raw_sample(accel_instance, accel, 0, fsync_set); + _notify_new_gyro_raw_sample(gyro_instance, gyro); _temp_filtered = _temp_filter.apply(temp); } @@ -386,7 +386,7 @@ bool AP_InertialSensor_Invensensev2::_accumulate_sensor_rate_sampling(uint8_t *s int16_t t2 = int16_val(data, 6); if (!_check_raw_temp(t2)) { if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + debug("temp reset IMU[%u] %d %d", accel_instance, _raw_temp, t2); } _fifo_reset(); ret = false; @@ -406,14 +406,14 @@ bool AP_InertialSensor_Invensensev2::_accumulate_sensor_rate_sampling(uint8_t *s _accum.accel += _accum.accel_filter.apply(a); Vector3f a2 = a * _accel_scale; - _notify_new_accel_sensor_rate_sample(_accel_instance, a2); + _notify_new_accel_sensor_rate_sample(accel_instance, a2); _accum.accel_count++; if (_accum.accel_count % _accel_fifo_downsample_rate == 0) { _accum.accel *= _fifo_accel_scale; - _rotate_and_correct_accel(_accel_instance, _accum.accel); - _notify_new_accel_raw_sample(_accel_instance, _accum.accel, 0, false); + _rotate_and_correct_accel(accel_instance, _accum.accel); + _notify_new_accel_raw_sample(accel_instance, _accum.accel, 0, false); _accum.accel.zero(); _accum.accel_count = 0; // we assume that the gyro rate is always >= and a multiple of the accel rate @@ -428,20 +428,20 @@ bool AP_InertialSensor_Invensensev2::_accumulate_sensor_rate_sampling(uint8_t *s -int16_val(data, 5)); Vector3f g2 = g * GYRO_SCALE; - _notify_new_gyro_sensor_rate_sample(_gyro_instance, g2); + _notify_new_gyro_sensor_rate_sample(gyro_instance, g2); _accum.gyro += g; if (_accum.gyro_count % _gyro_fifo_downsample_rate == 0) { _accum.gyro *= _fifo_gyro_scale; - _rotate_and_correct_gyro(_gyro_instance, _accum.gyro); - _notify_new_gyro_raw_sample(_gyro_instance, _accum.gyro); + _rotate_and_correct_gyro(gyro_instance, _accum.gyro); + _notify_new_gyro_raw_sample(gyro_instance, _accum.gyro); _accum.gyro.zero(); } } if (clipped) { - increment_clip_count(_accel_instance); + increment_clip_count(accel_instance); } if (ret) { @@ -519,7 +519,7 @@ void AP_InertialSensor_Invensensev2::_read_fifo() if (_fast_sampling) { if (!_accumulate_sensor_rate_sampling(rx, n)) { if (!hal.scheduler->in_expected_delay()) { - debug("IMU[%u] stop at %u of %u", _accel_instance, n_samples, bytes_read/INV2_SAMPLE_SIZE); + debug("IMU[%u] stop at %u of %u", accel_instance, n_samples, bytes_read/INV2_SAMPLE_SIZE); } break; } @@ -542,8 +542,8 @@ void AP_InertialSensor_Invensensev2::_read_fifo() AP_HAL::Device::checkreg reg; if (!_dev->check_next_register(reg)) { log_register_change(_dev->get_bus_id(), reg); - _inc_gyro_error_count(_gyro_instance); - _inc_accel_error_count(_accel_instance); + _inc_gyro_error_count(gyro_instance); + _inc_accel_error_count(accel_instance); } _dev->set_speed(AP_HAL::Device::SPEED_HIGH); } @@ -608,7 +608,7 @@ void AP_InertialSensor_Invensensev2::_set_filter_and_scaling(void) _gyro_fifo_downsample_rate = _accel_fifo_downsample_rate = 1; _gyro_backend_rate_hz = _accel_backend_rate_hz = 1125; - if (enable_fast_sampling(_accel_instance)) { + if (enable_fast_sampling(accel_instance)) { _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 @@ -631,11 +631,11 @@ void AP_InertialSensor_Invensensev2::_set_filter_and_scaling(void) _accel_backend_rate_hz *= MIN(fast_sampling_rate, 4); // for logging purposes set the oversamping rate - _set_accel_oversampling(_accel_instance, _accel_fifo_downsample_rate); - _set_gyro_oversampling(_gyro_instance, _gyro_fifo_downsample_rate); + _set_accel_oversampling(accel_instance, _accel_fifo_downsample_rate); + _set_gyro_oversampling(gyro_instance, _gyro_fifo_downsample_rate); - _set_accel_sensor_rate_sampling_enabled(_accel_instance, true); - _set_gyro_sensor_rate_sampling_enabled(_gyro_instance, true); + _set_accel_sensor_rate_sampling_enabled(accel_instance, true); + _set_gyro_sensor_rate_sampling_enabled(gyro_instance, true); /* set divider for internal sample rate to 0x1F when fast sampling enabled. This reduces the impact of the slave @@ -868,7 +868,7 @@ AuxiliaryBusSlave *AP_Invensensev2_AuxiliaryBus::_instantiate_slave(uint8_t addr _configure_slaves(); } - return new AP_Invensensev2_AuxiliaryBusSlave(*this, addr, instance); + return NEW_NOTHROW AP_Invensensev2_AuxiliaryBusSlave(*this, addr, instance); } void AP_Invensensev2_AuxiliaryBus::_configure_slaves() diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.h index 9becc1d60e6444..1b14062863a29e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.h @@ -103,10 +103,6 @@ class AP_InertialSensor_Invensensev2 : public AP_InertialSensor_Backend int16_t _raw_temp; - // instance numbers of accel and gyro data - uint8_t _gyro_instance; - uint8_t _accel_instance; - float temp_sensitivity = 1.0f/333.87f; // degC/LSB float temp_zero = 21; // degC @@ -156,7 +152,7 @@ class AP_InertialSensor_Invensensev2 : public AP_InertialSensor_Backend Vector3f gyro; uint8_t accel_count; uint8_t gyro_count; - LowPassFilterVector3f accel_filter{4500, 188}; + LowPassFilterConstDtVector3f accel_filter{4500, 188}; } _accum; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp index 110d3586b64f13..d22a7a224f30b1 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp @@ -136,6 +136,7 @@ extern const AP_HAL::HAL& hal; #define INV3_ID_ICM42605 0x42 #define INV3_ID_ICM42688 0x47 #define INV3_ID_IIM42652 0x6f +#define INV3_ID_IIM42653 0x56 #define INV3_ID_ICM42670 0x67 #define INV3_ID_ICM45686 0xE9 @@ -166,8 +167,8 @@ struct PACKED FIFODataHighRes { #define INV3_SAMPLE_SIZE sizeof(FIFOData) #define INV3_HIGHRES_SAMPLE_SIZE sizeof(FIFODataHighRes) -static_assert(sizeof(FIFOData) == 16); -static_assert(sizeof(FIFODataHighRes) == 20); +static_assert(sizeof(FIFOData) == 16, "FIFOData must be 16 bytes"); +static_assert(sizeof(FIFODataHighRes) == 20, "FIFODataHighRes must be 20 bytes"); #define INV3_FIFO_BUFFER_LEN 8 @@ -185,12 +186,12 @@ AP_InertialSensor_Invensensev3::~AP_InertialSensor_Invensensev3() #if HAL_INS_HIGHRES_SAMPLE if (highres_sampling) { if (fifo_buffer != nullptr) { - hal.util->free_type(fifo_buffer, INV3_FIFO_BUFFER_LEN * INV3_HIGHRES_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + hal.util->free_type(fifo_buffer, INV3_FIFO_BUFFER_LEN * INV3_HIGHRES_SAMPLE_SIZE + 1, AP_HAL::Util::MEM_DMA_SAFE); } } else #endif if (fifo_buffer != nullptr) { - hal.util->free_type(fifo_buffer, INV3_FIFO_BUFFER_LEN * INV3_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + hal.util->free_type(fifo_buffer, INV3_FIFO_BUFFER_LEN * INV3_SAMPLE_SIZE + 1, AP_HAL::Util::MEM_DMA_SAFE); } } @@ -207,7 +208,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev3::probe(AP_InertialSens } AP_InertialSensor_Invensensev3 *sensor = - new AP_InertialSensor_Invensensev3(imu, std::move(_dev), _rotation); + NEW_NOTHROW AP_InertialSensor_Invensensev3(imu, std::move(_dev), _rotation); if (!sensor || !sensor->hardware_init()) { delete sensor; return nullptr; @@ -258,6 +259,12 @@ void AP_InertialSensor_Invensensev3::start() devtype = DEVTYPE_INS_IIM42652; temp_sensitivity = 1.0 / 2.07; break; + case Invensensev3_Type::IIM42653: + devtype = DEVTYPE_INS_IIM42653; + temp_sensitivity = 1.0 / 2.07; + gyro_scale = GYRO_SCALE_4000DPS; + accel_scale = ACCEL_SCALE_32G; + break; case Invensensev3_Type::ICM42688: devtype = DEVTYPE_INS_ICM42688; temp_sensitivity = 1.0 / 2.07; @@ -294,13 +301,14 @@ void AP_InertialSensor_Invensensev3::start() switch (inv3_type) { case Invensensev3_Type::ICM42688: // HiRes 19bit case Invensensev3_Type::IIM42652: // HiRes 19bit - case Invensensev3_Type::ICM42670: // HiRes 19bit + case Invensensev3_Type::IIM42653: // HiRes 19bit case Invensensev3_Type::ICM45686: // HiRes 20bit highres_sampling = dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI; break; case Invensensev3_Type::ICM40609: // No HiRes case Invensensev3_Type::ICM42605: case Invensensev3_Type::ICM40605: + case Invensensev3_Type::ICM42670: // HiRes 19bit (not working) break; } } @@ -358,10 +366,10 @@ void AP_InertialSensor_Invensensev3::start() // allocate fifo buffer #if HAL_INS_HIGHRES_SAMPLE if (highres_sampling) { - fifo_buffer = hal.util->malloc_type(INV3_FIFO_BUFFER_LEN * INV3_HIGHRES_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + fifo_buffer = hal.util->malloc_type(INV3_FIFO_BUFFER_LEN * INV3_HIGHRES_SAMPLE_SIZE + 1, AP_HAL::Util::MEM_DMA_SAFE); } else #endif - fifo_buffer = hal.util->malloc_type(INV3_FIFO_BUFFER_LEN * INV3_SAMPLE_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + fifo_buffer = hal.util->malloc_type(INV3_FIFO_BUFFER_LEN * INV3_SAMPLE_SIZE + 1, AP_HAL::Util::MEM_DMA_SAFE); if (fifo_buffer == nullptr) { AP_HAL::panic("Invensensev3: Unable to allocate FIFO buffer"); @@ -468,6 +476,9 @@ static inline float uint20_to_float(uint8_t msb, uint8_t bits, uint8_t lsb) bool AP_InertialSensor_Invensensev3::accumulate_highres_samples(const FIFODataHighRes *data, uint8_t n_samples) { +#if INV3_ENABLE_FIFO_LOGGING + const uint64_t tstart = AP_HAL::micros64(); +#endif for (uint8_t i = 0; i < n_samples; i++) { const FIFODataHighRes &d = data[i]; @@ -488,6 +499,9 @@ bool AP_InertialSensor_Invensensev3::accumulate_highres_samples(const FIFODataHi accel *= accel_scale; gyro *= gyro_scale; +#if INV3_ENABLE_FIFO_LOGGING + Write_GYR(gyro_instance, tstart+(i*backend_period_us), gyro, true); +#endif const float temp = d.temperature * temp_sensitivity + temp_zero; // these four calls are about 40us @@ -513,6 +527,8 @@ void AP_InertialSensor_Invensensev3::read_fifo() uint8_t reg_counth; uint8_t reg_data; + uint8_t* samples = nullptr; + uint8_t* tfr_buffer = (uint8_t*)fifo_buffer; switch (inv3_type) { case Invensensev3_Type::ICM45686: @@ -549,18 +565,28 @@ void AP_InertialSensor_Invensensev3::read_fifo() while (n_samples > 0) { uint8_t n = MIN(n_samples, INV3_FIFO_BUFFER_LEN); - if (!block_read(reg_data, (uint8_t*)fifo_buffer, n * fifo_sample_size)) { + + // we don't use read_registers() here to ensure that the fifo buffer that we have allocated + // gets passed all the way down to the SPI DMA handling. This involves one transfer to send + // the register read and then another using the same buffer and length which is handled specially + // for the read + tfr_buffer[0] = reg_data | BIT_READ_FLAG; + // transfer will also be sending data, make sure that data is zero + memset(tfr_buffer + 1, 0, n * fifo_sample_size); + if (!dev->transfer(tfr_buffer, n * fifo_sample_size + 1, tfr_buffer, n * fifo_sample_size + 1)) { goto check_registers; } + samples = tfr_buffer + 1; + #if HAL_INS_HIGHRES_SAMPLE if (highres_sampling) { - if (!accumulate_highres_samples((FIFODataHighRes*)fifo_buffer, n)) { + if (!accumulate_highres_samples((FIFODataHighRes*)samples, n)) { need_reset = true; break; } } else #endif - if (!accumulate_samples((FIFOData*)fifo_buffer, n)) { + if (!accumulate_samples((FIFOData*)samples, n)) { need_reset = true; break; } @@ -806,6 +832,7 @@ void AP_InertialSensor_Invensensev3::set_filter_and_scaling(void) case Invensensev3_Type::ICM42688: case Invensensev3_Type::ICM42605: case Invensensev3_Type::IIM42652: + case Invensensev3_Type::IIM42653: case Invensensev3_Type::ICM42670: { /* fix for the "stuck gyro" issue, which affects all IxM42xxx @@ -949,6 +976,9 @@ bool AP_InertialSensor_Invensensev3::check_whoami(void) case INV3_ID_IIM42652: inv3_type = Invensensev3_Type::IIM42652; return true; + case INV3_ID_IIM42653: + inv3_type = Invensensev3_Type::IIM42653; + return true; case INV3_ID_ICM42670: inv3_type = Invensensev3_Type::ICM42670; return true; @@ -1024,6 +1054,7 @@ bool AP_InertialSensor_Invensensev3::hardware_init(void) switch (inv3_type) { case Invensensev3_Type::ICM45686: case Invensensev3_Type::ICM40609: + case Invensensev3_Type::IIM42653: _clip_limit = 29.5f * GRAVITY_MSS; break; case Invensensev3_Type::ICM42688: @@ -1031,7 +1062,7 @@ bool AP_InertialSensor_Invensensev3::hardware_init(void) case Invensensev3_Type::ICM42605: case Invensensev3_Type::ICM40605: case Invensensev3_Type::ICM42670: - _clip_limit = 15.5f * GRAVITY_MSS; + _clip_limit = (16.0f - 0.5f) * GRAVITY_MSS; break; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h index aa9971db0d48ec..6b4fc49a8c5c49 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h @@ -37,6 +37,7 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend ICM42605, // No HiRes ICM40605, // No HiRes IIM42652, // HiRes 19bit + IIM42653, // HiRes 19bit ICM42670, // HiRes 19bit ICM45686 // HiRes 20bit }; @@ -74,10 +75,6 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend bool accumulate_samples(const struct FIFOData *data, uint8_t n_samples); bool accumulate_highres_samples(const struct FIFODataHighRes *data, uint8_t n_samples); - // instance numbers of accel and gyro data - uint8_t gyro_instance; - uint8_t accel_instance; - // reset FIFO configure1 register uint8_t fifo_config1; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp index 1bc80404759c19..82a19e2261656f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp @@ -146,7 +146,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_L3G4200D::probe(AP_InertialSensor & return nullptr; } AP_InertialSensor_L3G4200D *sensor - = new AP_InertialSensor_L3G4200D(imu, std::move(dev_gyro), std::move(dev_accel)); + = NEW_NOTHROW AP_InertialSensor_L3G4200D(imu, std::move(dev_gyro), std::move(dev_accel)); if (!sensor || !sensor->_init_sensor()) { delete sensor; return nullptr; @@ -250,8 +250,8 @@ bool AP_InertialSensor_L3G4200D::_init_sensor(void) */ void AP_InertialSensor_L3G4200D::start(void) { - if (!_imu.register_gyro(_gyro_instance, 800, _dev_gyro->get_bus_id_devtype(DEVTYPE_L3G4200D)) || - !_imu.register_accel(_accel_instance, 800, _dev_accel->get_bus_id_devtype(DEVTYPE_L3G4200D))) { + if (!_imu.register_gyro(gyro_instance, 800, _dev_gyro->get_bus_id_devtype(DEVTYPE_L3G4200D)) || + !_imu.register_accel(accel_instance, 800, _dev_accel->get_bus_id_devtype(DEVTYPE_L3G4200D))) { return; } @@ -276,8 +276,8 @@ void AP_InertialSensor_L3G4200D::_set_filter_frequency(uint8_t filter_hz) */ bool AP_InertialSensor_L3G4200D::update(void) { - update_gyro(_gyro_instance); - update_accel(_accel_instance); + update_gyro(gyro_instance); + update_accel(accel_instance); return true; } @@ -313,8 +313,8 @@ void AP_InertialSensor_L3G4200D::_accumulate_gyro (void) // Adjust for chip scaling to get radians/sec //hal.console->printf("gyro %f \r\n",gyro.x); gyro *= L3G4200D_GYRO_SCALE_R_S; - _rotate_and_correct_gyro(_gyro_instance, gyro); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _rotate_and_correct_gyro(gyro_instance, gyro); + _notify_new_gyro_raw_sample(gyro_instance, gyro); } } } @@ -341,8 +341,8 @@ void AP_InertialSensor_L3G4200D::_accumulate_accel (void) Vector3f accel = Vector3f(buffer[i][0], -buffer[i][1], -buffer[i][2]); // Adjust for chip scaling to get m/s/s accel *= ADXL345_ACCELEROMETER_SCALE_M_S; - _rotate_and_correct_accel(_accel_instance, accel); - _notify_new_accel_raw_sample(_accel_instance, accel); + _rotate_and_correct_accel(accel_instance, accel); + _notify_new_accel_raw_sample(accel_instance, accel); } } } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h index 535613571d49ed..b97b430f6df167 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h @@ -52,9 +52,5 @@ class AP_InertialSensor_L3G4200D : public AP_InertialSensor_Backend LowPassFilter2pVector3f _gyro_filter; enum Rotation _rotation; - - // gyro and accel instances - uint8_t _gyro_instance; - uint8_t _accel_instance; }; #endif // __AP_INERTIAL_SENSOR_L3G4200D2_H__ \ No newline at end of file diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp index a872ddc7b5ae48..a62fd1eb2fc1a6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp @@ -384,10 +384,10 @@ AP_InertialSensor_LSM9DS0::AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu, , _dev_accel(std::move(dev_accel)) , _drdy_pin_num_a(drdy_pin_num_a) , _drdy_pin_num_g(drdy_pin_num_g) + , _temp_filter(400, 1) , _rotation_a(rotation_a) , _rotation_g(rotation_g) , _rotation_gH(rotation_gH) - , _temp_filter(400, 1) { } @@ -402,7 +402,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS0::probe(AP_InertialSensor &_ return nullptr; } AP_InertialSensor_LSM9DS0 *sensor = - new AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel), + NEW_NOTHROW AP_InertialSensor_LSM9DS0(_imu, std::move(dev_gyro), std::move(dev_accel), LSM9DS0_DRY_X_PIN, LSM9DS0_DRY_G_PIN, rotation_a, rotation_g, rotation_gH); if (!sensor || !sensor->_init_sensor()) { @@ -512,19 +512,19 @@ bool AP_InertialSensor_LSM9DS0::_hardware_init() */ void AP_InertialSensor_LSM9DS0::start(void) { - if (!_imu.register_gyro(_gyro_instance, 760, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_L3GD20)) || - !_imu.register_accel(_accel_instance, 1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_LSM303D))) { + if (!_imu.register_gyro(gyro_instance, 760, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_L3GD20)) || + !_imu.register_accel(accel_instance, 1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_LSM303D))) { return; } if (whoami_g == LSM9DS0_G_WHOAMI_H) { - set_gyro_orientation(_gyro_instance, _rotation_gH); + set_gyro_orientation(gyro_instance, _rotation_gH); } else { - set_gyro_orientation(_gyro_instance, _rotation_g); + set_gyro_orientation(gyro_instance, _rotation_g); } - set_accel_orientation(_accel_instance, _rotation_a); + set_accel_orientation(accel_instance, _rotation_a); - _set_accel_max_abs_offset(_accel_instance, 5.0f); + _set_accel_max_abs_offset(accel_instance, 5.0f); /* start the timer process to read samples */ _dev_gyro->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_LSM9DS0::_poll_data, void)); @@ -700,11 +700,11 @@ void AP_InertialSensor_LSM9DS0::_poll_data() AP_HAL::Device::checkreg reg; if (!_dev_gyro->check_next_register(reg)) { log_register_change(_dev_gyro->get_bus_id(), reg); - _inc_gyro_error_count(_gyro_instance); + _inc_gyro_error_count(gyro_instance); } if (!_dev_accel->check_next_register(reg)) { log_register_change(_dev_accel->get_bus_id(), reg); - _inc_accel_error_count(_accel_instance); + _inc_accel_error_count(accel_instance); } } @@ -740,8 +740,8 @@ void AP_InertialSensor_LSM9DS0::_read_data_transaction_a() Vector3f accel_data(raw_data.x, -raw_data.y, -raw_data.z); accel_data *= _accel_scale; - _rotate_and_correct_accel(_accel_instance, accel_data); - _notify_new_accel_raw_sample(_accel_instance, accel_data, AP_HAL::micros64()); + _rotate_and_correct_accel(accel_instance, accel_data); + _notify_new_accel_raw_sample(accel_instance, accel_data, AP_HAL::micros64()); // read temperature every 10th sample if (_temp_counter++ >= 10) { @@ -770,15 +770,15 @@ void AP_InertialSensor_LSM9DS0::_read_data_transaction_g() gyro_data *= _gyro_scale; - _rotate_and_correct_gyro(_gyro_instance, gyro_data); - _notify_new_gyro_raw_sample(_gyro_instance, gyro_data, AP_HAL::micros64()); + _rotate_and_correct_gyro(gyro_instance, gyro_data); + _notify_new_gyro_raw_sample(gyro_instance, gyro_data, AP_HAL::micros64()); } bool AP_InertialSensor_LSM9DS0::update() { - update_gyro(_gyro_instance); - update_accel(_accel_instance); - _publish_temperature(_accel_instance, _temperature); + update_gyro(gyro_instance); + update_accel(accel_instance); + _publish_temperature(accel_instance, _temperature); return true; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h index 29fff902705412..18244897a24ee6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h @@ -97,8 +97,6 @@ class AP_InertialSensor_LSM9DS0 : public AP_InertialSensor_Backend float _accel_scale; int _drdy_pin_num_a; int _drdy_pin_num_g; - uint8_t _gyro_instance; - uint8_t _accel_instance; float _temperature; uint8_t _temp_counter; LowPassFilter2pFloat _temp_filter; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp index 295f1ebccadbc8..d95cfce0f0fcce 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp @@ -214,9 +214,9 @@ AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS1::probe(AP_InertialSensor &_ } AP_InertialSensor_LSM9DS1 *sensor = - new AP_InertialSensor_LSM9DS1(_imu,std::move(dev), - LSM9DS1_DRY_XG_PIN, - rotation); + NEW_NOTHROW AP_InertialSensor_LSM9DS1(_imu,std::move(dev), + LSM9DS1_DRY_XG_PIN, + rotation); if (!sensor || !sensor->_init_sensor()) { delete sensor; return nullptr; @@ -321,8 +321,8 @@ void AP_InertialSensor_LSM9DS1::_fifo_reset() _dev->set_speed(AP_HAL::Device::SPEED_HIGH); - notify_accel_fifo_reset(_accel_instance); - notify_gyro_fifo_reset(_gyro_instance); + notify_accel_fifo_reset(accel_instance); + notify_gyro_fifo_reset(gyro_instance); } /* @@ -330,15 +330,15 @@ void AP_InertialSensor_LSM9DS1::_fifo_reset() */ void AP_InertialSensor_LSM9DS1::start(void) { - if (!_imu.register_gyro(_gyro_instance, 952, _dev->get_bus_id_devtype(DEVTYPE_GYR_LSM9DS1)) || - !_imu.register_accel(_accel_instance, 952, _dev->get_bus_id_devtype(DEVTYPE_ACC_LSM9DS1))) { + if (!_imu.register_gyro(gyro_instance, 952, _dev->get_bus_id_devtype(DEVTYPE_GYR_LSM9DS1)) || + !_imu.register_accel(accel_instance, 952, _dev->get_bus_id_devtype(DEVTYPE_ACC_LSM9DS1))) { return; } - set_accel_orientation(_accel_instance, _rotation); - set_gyro_orientation(_gyro_instance, _rotation); + set_accel_orientation(accel_instance, _rotation); + set_gyro_orientation(gyro_instance, _rotation); - _set_accel_max_abs_offset(_accel_instance, 5.0f); + _set_accel_max_abs_offset(accel_instance, 5.0f); /* start the timer process to read samples */ _dev->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_LSM9DS1::_poll_data, void)); @@ -431,7 +431,7 @@ void AP_InertialSensor_LSM9DS1::_poll_data() AP_HAL::Device::checkreg reg; if (!_dev->check_next_register(reg)) { log_register_change(_dev->get_bus_id(), reg); - _inc_accel_error_count(_accel_instance); + _inc_accel_error_count(accel_instance); } } @@ -465,8 +465,8 @@ void AP_InertialSensor_LSM9DS1::_read_data_transaction_x(uint16_t samples) Vector3f accel_data(raw_data.x, raw_data.y, -raw_data.z); accel_data *= _accel_scale; - _rotate_and_correct_accel(_accel_instance, accel_data); - _notify_new_accel_raw_sample(_accel_instance, accel_data); + _rotate_and_correct_accel(accel_instance, accel_data); + _notify_new_accel_raw_sample(accel_instance, accel_data); } /* @@ -501,14 +501,14 @@ void AP_InertialSensor_LSM9DS1::_read_data_transaction_g(uint16_t samples) Vector3f gyro_data(raw_data.x, raw_data.y, -raw_data.z); gyro_data *= _gyro_scale; - _rotate_and_correct_gyro(_gyro_instance, gyro_data); - _notify_new_gyro_raw_sample(_gyro_instance, gyro_data); + _rotate_and_correct_gyro(gyro_instance, gyro_data); + _notify_new_gyro_raw_sample(gyro_instance, gyro_data); } bool AP_InertialSensor_LSM9DS1::update() { - update_gyro(_gyro_instance); - update_accel(_accel_instance); + update_gyro(gyro_instance); + update_accel(accel_instance); return true; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.h b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.h index f52859c1bbd963..7997476abac397 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.h @@ -68,7 +68,5 @@ class AP_InertialSensor_LSM9DS1 : public AP_InertialSensor_Backend float _gyro_scale; float _accel_scale; int _drdy_pin_num_xg; - uint8_t _gyro_instance; - uint8_t _accel_instance; enum Rotation _rotation; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp index 4fa6c6ba641183..fa71deadd954c3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp @@ -5,6 +5,7 @@ #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" +#include #include // Write ACC data packet: raw accel data diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp index 1d4ff5f19887bc..2a8aa0621b9069 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp @@ -26,7 +26,7 @@ AP_InertialSensor_NONE::AP_InertialSensor_NONE(AP_InertialSensor &imu, const uin */ AP_InertialSensor_Backend *AP_InertialSensor_NONE::detect(AP_InertialSensor &_imu, const uint16_t sample_rates[]) { - AP_InertialSensor_NONE *sensor = new AP_InertialSensor_NONE(_imu, sample_rates); + AP_InertialSensor_NONE *sensor = NEW_NOTHROW AP_InertialSensor_NONE(_imu, sample_rates); if (sensor == nullptr) { return nullptr; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp index 761e2e9100b301..fa061c40781255 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp @@ -206,7 +206,7 @@ AP_InertialSensor_Backend *AP_InertialSensor_RST::probe(AP_InertialSensor &imu, return nullptr; } AP_InertialSensor_RST *sensor - = new AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a); + = NEW_NOTHROW AP_InertialSensor_RST(imu, std::move(dev_gyro), std::move(dev_accel), rotation_g, rotation_a); if (!sensor || !sensor->_init_sensor()) { delete sensor; return nullptr; @@ -336,13 +336,13 @@ bool AP_InertialSensor_RST::_init_sensor(void) */ void AP_InertialSensor_RST::start(void) { - if (!_imu.register_gyro(_gyro_instance, 800, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_I3G4250D)) || - !_imu.register_accel(_accel_instance, 1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_IIS328DQ))) { + if (!_imu.register_gyro(gyro_instance, 800, _dev_gyro->get_bus_id_devtype(DEVTYPE_GYR_I3G4250D)) || + !_imu.register_accel(accel_instance, 1000, _dev_accel->get_bus_id_devtype(DEVTYPE_ACC_IIS328DQ))) { return; } - set_gyro_orientation(_gyro_instance, _rotation_g); - set_accel_orientation(_accel_instance, _rotation_a); + set_gyro_orientation(gyro_instance, _rotation_g); + set_accel_orientation(accel_instance, _rotation_a); // start the timer process to read samples _dev_gyro->register_periodic_callback(1150, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_RST::gyro_measure, void)); @@ -354,8 +354,8 @@ void AP_InertialSensor_RST::start(void) */ bool AP_InertialSensor_RST::update(void) { - update_gyro(_gyro_instance); - update_accel(_accel_instance); + update_gyro(gyro_instance); + update_accel(accel_instance); return true; } @@ -376,8 +376,8 @@ void AP_InertialSensor_RST::gyro_measure(void) if (_dev_gyro->read_registers(GYRO_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) { gyro = Vector3f(raw_data[0], raw_data[1], raw_data[2]); gyro *= _gyro_scale; - _rotate_and_correct_gyro(_gyro_instance, gyro); - _notify_new_gyro_raw_sample(_gyro_instance, gyro); + _rotate_and_correct_gyro(gyro_instance, gyro); + _notify_new_gyro_raw_sample(gyro_instance, gyro); } } @@ -397,8 +397,8 @@ void AP_InertialSensor_RST::accel_measure(void) if (_dev_accel->read_registers(ACCEL_OUT_X_L | ADDR_INCREMENT, (uint8_t *)raw_data, sizeof(raw_data))) { accel = Vector3f(raw_data[0], raw_data[1], raw_data[2]); accel *= _accel_scale; - _rotate_and_correct_accel(_accel_instance, accel); - _notify_new_accel_raw_sample(_accel_instance, accel); + _rotate_and_correct_accel(accel_instance, accel); + _notify_new_accel_raw_sample(accel_instance, accel); } } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_RST.h b/libraries/AP_InertialSensor/AP_InertialSensor_RST.h index 90d76d3e393767..0efaa6cbbef862 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_RST.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_RST.h @@ -47,9 +47,6 @@ class AP_InertialSensor_RST : public AP_InertialSensor_Backend float _gyro_scale; float _accel_scale; - // gyro and accel instances - uint8_t _gyro_instance; - uint8_t _accel_instance; enum Rotation _rotation_g; enum Rotation _rotation_a; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp index 652dd100ad5b87..53b1bd901a0629 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp @@ -63,7 +63,7 @@ AP_InertialSensor_Backend* AP_InertialSensor_SCHA63T::probe(AP_InertialSensor &i if (!dev_uno || !dev_due) { return nullptr; } - auto sensor = new AP_InertialSensor_SCHA63T(imu, std::move(dev_uno), std::move(dev_due), rotation); + auto sensor = NEW_NOTHROW AP_InertialSensor_SCHA63T(imu, std::move(dev_uno), std::move(dev_due), rotation); if (!sensor) { return nullptr; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h index 3ffc203a26ecec..64110a12604049 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.h @@ -84,7 +84,5 @@ class AP_InertialSensor_SCHA63T : public AP_InertialSensor_Backend AP_HAL::OwnPtr dev_uno; AP_HAL::OwnPtr dev_due; - uint8_t accel_instance; - uint8_t gyro_instance; enum Rotation rotation; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index c6b994413a8bb9..d9e91a0df429cf 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -20,7 +20,7 @@ AP_InertialSensor_SITL::AP_InertialSensor_SITL(AP_InertialSensor &imu, const uin */ AP_InertialSensor_Backend *AP_InertialSensor_SITL::detect(AP_InertialSensor &_imu, const uint16_t sample_rates[]) { - AP_InertialSensor_SITL *sensor = new AP_InertialSensor_SITL(_imu, sample_rates); + AP_InertialSensor_SITL *sensor = NEW_NOTHROW AP_InertialSensor_SITL(_imu, sample_rates); if (sensor == nullptr) { return nullptr; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h index ac95bac811e25a..856f40ab003a70 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h @@ -45,8 +45,6 @@ class AP_InertialSensor_SITL : public AP_InertialSensor_Backend const uint16_t gyro_sample_hz; const uint16_t accel_sample_hz; - uint8_t gyro_instance; - uint8_t accel_instance; uint64_t next_gyro_sample; uint64_t next_accel_sample; float gyro_time; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_config.h b/libraries/AP_InertialSensor/AP_InertialSensor_config.h index d4775b7219133a..5ad27d03003346 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_config.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_config.h @@ -51,6 +51,10 @@ #define AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED AP_INERTIALSENSOR_ENABLED #endif +#ifndef AP_INERTIALSENSOR_ALLOW_NO_SENSORS +#define AP_INERTIALSENSOR_ALLOW_NO_SENSORS 0 +#endif + #if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED #ifndef HAL_INS_NUM_HARMONIC_NOTCH_FILTERS #define HAL_INS_NUM_HARMONIC_NOTCH_FILTERS 2 diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index 22b4aa454148c0..bb71172dc9b009 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -349,7 +349,7 @@ void AP_InertialSensor_TCal::update_accel_learning(const Vector3f &accel, float return; } if (learn == nullptr && hal.scheduler->is_system_initialized()) { - learn = new Learn(*this, temperature); + learn = NEW_NOTHROW Learn(*this, temperature); if (learn) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TCAL[%u]: started calibration t=%.1fC tmax=%.1fC", instance()+1, @@ -526,6 +526,7 @@ void AP_InertialSensor::get_persistent_params(ExpandingString &str) const str.printf("INS%u_ACCOFFS_Z=%f\n", imu, aoff.z); str.printf("INS%u_ACCSCAL_X=%f\n", imu, ascl.x); str.printf("INS%u_ACCSCAL_Y=%f\n", imu, ascl.y); + str.printf("INS%u_ACCSCAL_Z=%f\n", imu, ascl.z); str.printf("INS%u_ACC_CALTEMP=%.2f\n", imu, params[i].caltemp_accel.get()); } #endif diff --git a/libraries/AP_InertialSensor/BatchSampler.cpp b/libraries/AP_InertialSensor/BatchSampler.cpp index e86a3f559c0e7a..a7d7403e360ec6 100644 --- a/libraries/AP_InertialSensor/BatchSampler.cpp +++ b/libraries/AP_InertialSensor/BatchSampler.cpp @@ -87,7 +87,9 @@ void AP_InertialSensor::BatchSampler::periodic() if (_sensor_mask == 0) { return; } +#if HAL_LOGGING_ENABLED push_data_to_log(); +#endif } void AP_InertialSensor::BatchSampler::update_doing_sensor_rate_logging() @@ -175,6 +177,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor() update_doing_sensor_rate_logging(); } +#if HAL_LOGGING_ENABLED void AP_InertialSensor::BatchSampler::push_data_to_log() { if (!initialised) { @@ -266,6 +269,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T } return true; } +#endif // HAL_LOGGING_ENABLED void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample) { diff --git a/libraries/AP_InternalError/AP_InternalError.cpp b/libraries/AP_InternalError/AP_InternalError.cpp index bc505804a8179c..0f23b2d1d42771 100644 --- a/libraries/AP_InternalError/AP_InternalError.cpp +++ b/libraries/AP_InternalError/AP_InternalError.cpp @@ -85,22 +85,19 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con { buffer[0] = 0; uint32_t buffer_used = 0; + const char *format = "%s"; // no comma before the first item for (uint8_t i=0; i= len) { break; } if (internal_errors & (1U<snprintf((char*)&buffer[buffer_used], + const int written = hal.util->snprintf((char*)&buffer[buffer_used], len-buffer_used, format, error_bit_descriptions[i]); - if (written <= 0) { + format = ",%s"; // once we write something, need commas thereafter + + if (written < 0) { break; } buffer_used += written; diff --git a/libraries/AP_JSON/AP_JSON.cpp b/libraries/AP_JSON/AP_JSON.cpp index 823de3512538aa..33bf30657bea0a 100644 --- a/libraries/AP_JSON/AP_JSON.cpp +++ b/libraries/AP_JSON/AP_JSON.cpp @@ -56,7 +56,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename) ::printf("failed to open json %s\n", filename); return nullptr; } - char *buf = new char[st.st_size+1]; + char *buf = NEW_NOTHROW char[st.st_size+1]; if (buf == nullptr) { AP::FS().close(fd); ::printf("failed to allocate json %s\n", filename); @@ -72,7 +72,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename) char *start = strchr(buf, '{'); if (!start) { - ::printf("Invalid json %s", filename); + ::printf("Invalid json %s\n", filename); delete[] buf; return nullptr; } @@ -87,15 +87,15 @@ AP_JSON::value *AP_JSON::load_json(const char *filename) } while (*p != '\n' && *p != '\r' && *p); } - AP_JSON::value *obj = new AP_JSON::value; + AP_JSON::value *obj = NEW_NOTHROW AP_JSON::value; if (obj == nullptr) { - ::printf("Invalid allocate json for %s", filename); + ::printf("Invalid allocate json for %s\n", filename); delete[] buf; return nullptr; } std::string err = AP_JSON::parse(*obj, start); if (!err.empty()) { - ::printf("parse failed for json %s", filename); + ::printf("parse failed for json %s\n", filename); delete obj; delete[] buf; return nullptr; @@ -133,9 +133,9 @@ AP_JSON::value::value(int type, bool) : type_(type), u_() break INIT(boolean_, false); INIT(number_, 0.0); - INIT(string_, new std::string()); - INIT(array_, new array()); - INIT(object_, new object()); + INIT(string_, NEW_NOTHROW std::string()); + INIT(array_, NEW_NOTHROW array()); + INIT(object_, NEW_NOTHROW object()); #undef INIT default: break; @@ -154,42 +154,42 @@ AP_JSON::value::value(double n) : type_(number_type), u_() AP_JSON::value::value(const std::string &s) : type_(string_type), u_() { - u_.string_ = new std::string(s); + u_.string_ = NEW_NOTHROW std::string(s); } AP_JSON::value::value(const array &a) : type_(array_type), u_() { - u_.array_ = new array(a); + u_.array_ = NEW_NOTHROW array(a); } AP_JSON::value::value(const object &o) : type_(object_type), u_() { - u_.object_ = new object(o); + u_.object_ = NEW_NOTHROW object(o); } AP_JSON::value::value(std::string &&s) : type_(string_type), u_() { - u_.string_ = new std::string(std::move(s)); + u_.string_ = NEW_NOTHROW std::string(std::move(s)); } AP_JSON::value::value(array &&a) : type_(array_type), u_() { - u_.array_ = new array(std::move(a)); + u_.array_ = NEW_NOTHROW array(std::move(a)); } AP_JSON::value::value(object &&o) : type_(object_type), u_() { - u_.object_ = new object(std::move(o)); + u_.object_ = NEW_NOTHROW object(std::move(o)); } AP_JSON::value::value(const char *s) : type_(string_type), u_() { - u_.string_ = new std::string(s); + u_.string_ = NEW_NOTHROW std::string(s); } AP_JSON::value::value(const char *s, size_t len) : type_(string_type), u_() { - u_.string_ = new std::string(s, len); + u_.string_ = NEW_NOTHROW std::string(s, len); } void AP_JSON::value::clear() @@ -220,9 +220,9 @@ AP_JSON::value::value(const value &x) : type_(x.type_), u_() case p##type: \ u_.p = v; \ break - INIT(string_, new std::string(*x.u_.string_)); - INIT(array_, new array(*x.u_.array_)); - INIT(object_, new object(*x.u_.object_)); + INIT(string_, NEW_NOTHROW std::string(*x.u_.string_)); + INIT(array_, NEW_NOTHROW array(*x.u_.array_)); + INIT(object_, NEW_NOTHROW object(*x.u_.object_)); #undef INIT default: u_ = x.u_; @@ -291,9 +291,9 @@ GET(double, u_.number_) setter \ } SET(bool, boolean, u_.boolean_ = _val;) -SET(std::string, string, u_.string_ = new std::string(_val);) -SET(array, array, u_.array_ = new array(_val);) -SET(object, object, u_.object_ = new object(_val);) +SET(std::string, string, u_.string_ = NEW_NOTHROW std::string(_val);) +SET(array, array, u_.array_ = NEW_NOTHROW array(_val);) +SET(object, object, u_.object_ = NEW_NOTHROW object(_val);) SET(double, number, u_.number_ = _val;) #undef SET @@ -303,9 +303,9 @@ SET(double, number, u_.number_ = _val;) type_ = jtype##_type; \ setter \ } -MOVESET(std::string, string, u_.string_ = new std::string(std::move(_val));) -MOVESET(array, array, u_.array_ = new array(std::move(_val));) -MOVESET(object, object, u_.object_ = new object(std::move(_val));) +MOVESET(std::string, string, u_.string_ = NEW_NOTHROW std::string(std::move(_val));) +MOVESET(array, array, u_.array_ = NEW_NOTHROW array(std::move(_val));) +MOVESET(object, object, u_.object_ = NEW_NOTHROW object(std::move(_val));) #undef MOVESET bool AP_JSON::value::evaluate_as_boolean() const diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index db0afdf4aba7eb..521489abbf4edd 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -63,7 +63,7 @@ void AP_KDECAN::init() for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { if (CANSensor::get_driver_type(i) == AP_CAN::Protocol::KDECAN) { - _driver = new AP_KDECAN_Driver(); + _driver = NEW_NOTHROW AP_KDECAN_Driver(); return; } } @@ -235,14 +235,14 @@ void AP_KDECAN_Driver::loop() for (uint8_t i=0; i= TELEMETRY_INTERVAL_MS) { - if (send_packet(TELEMETRY_OBJ_ADDR, BROADCAST_NODE_ID, 10)) { + if (send_packet(TELEMETRY_OBJ_ADDR, BROADCAST_NODE_ID, 10000)) { _telemetry.timer_ms = now_ms; } } @@ -256,7 +256,7 @@ void AP_KDECAN_Driver::loop() broadcast_esc_info_next_interval_ms = 1000; } - if (send_packet(ESC_INFO_OBJ_ADDR, BROADCAST_NODE_ID, 100)) { + if (send_packet(ESC_INFO_OBJ_ADDR, BROADCAST_NODE_ID, 100000)) { _init.detected_bitmask_ms = now_ms; } } @@ -264,13 +264,13 @@ void AP_KDECAN_Driver::loop() } // while true } -bool AP_KDECAN_Driver::send_packet_uint16(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_ms, const uint16_t data) +bool AP_KDECAN_Driver::send_packet_uint16(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_us, const uint16_t data) { const uint16_t data_be16 = htobe16(data); - return send_packet(address, dest_id, timeout_ms, (uint8_t*)&data_be16, 2); + return send_packet(address, dest_id, timeout_us, (uint8_t*)&data_be16, 2); } -bool AP_KDECAN_Driver::send_packet(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_ms, const uint8_t *data, const uint8_t data_len) +bool AP_KDECAN_Driver::send_packet(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_us, const uint8_t *data, const uint8_t data_len) { // broadcast telemetry request frame const frame_id_t id { @@ -285,7 +285,6 @@ bool AP_KDECAN_Driver::send_packet(const uint8_t address, const uint8_t dest_id, AP_HAL::CANFrame frame = AP_HAL::CANFrame((id.value | AP_HAL::CANFrame::FlagEFF), data, data_len, false); - const uint64_t timeout_us = uint64_t(timeout_ms) * 1000UL; return write_frame(frame, timeout_us); } diff --git a/libraries/AP_KDECAN/AP_KDECAN.h b/libraries/AP_KDECAN/AP_KDECAN.h index 635b100bbd990e..70ba23d984a274 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.h +++ b/libraries/AP_KDECAN/AP_KDECAN.h @@ -56,8 +56,8 @@ class AP_KDECAN_Driver : public CANSensor // handler for incoming frames void handle_frame(AP_HAL::CANFrame &frame) override; - bool send_packet_uint16(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_ms, const uint16_t data); - bool send_packet(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_ms, const uint8_t *data = nullptr, const uint8_t data_len = 0); + bool send_packet_uint16(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_us, const uint16_t data); + bool send_packet(const uint8_t address, const uint8_t dest_id, const uint32_t timeout_us, const uint8_t *data = nullptr, const uint8_t data_len = 0); void loop(); diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 2750c232298d0d..ca6cc75b88bb9a 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -339,6 +339,7 @@ void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &nex // Waypoint capture status is always false during waypoint following _WPcircle = false; + _last_loiter.reached_loiter_target_ms = 0; _bearing_error = Nu; // bearing error angle (radians), +ve to left of track @@ -348,6 +349,8 @@ void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &nex // update L1 control for loitering void AP_L1_Control::update_loiter(const Location ¢er_WP, float radius, int8_t loiter_direction) { + const float radius_unscaled = radius; + Location _current_loc; // scale loiter radius with square of EAS2TAS to allow us to stay @@ -442,18 +445,43 @@ void AP_L1_Control::update_loiter(const Location ¢er_WP, float radius, int8_ // Perform switchover between 'capture' and 'circle' modes at the // point where the commands cross over to achieve a seamless transfer // Only fly 'capture' mode if outside the circle + const uint32_t now_ms = AP_HAL::millis(); if (xtrackErrCirc > 0.0f && loiter_direction * latAccDemCap < loiter_direction * latAccDemCirc) { _latAccDem = latAccDemCap; - _WPcircle = false; + + /* + if we were previously on the circle and the target has not + changed then keep _WPcircle true. This prevents + reached_loiter_target() from going false due to a gust of + wind or an unachievable loiter radius + */ + if (_WPcircle && + _last_loiter.reached_loiter_target_ms != 0 && + now_ms - _last_loiter.reached_loiter_target_ms < 200U && + loiter_direction == _last_loiter.direction && + is_equal(radius_unscaled, _last_loiter.radius) && + center_WP.same_loc_as(_last_loiter.center_WP)) { + // same location, within 200ms, keep the _WPcircle status as true + _last_loiter.reached_loiter_target_ms = now_ms; + } else { + _WPcircle = false; + _last_loiter.reached_loiter_target_ms = 0; + } + _bearing_error = Nu; // angle between demanded and achieved velocity vector, +ve to left of track _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians) from AC to L1 point } else { _latAccDem = latAccDemCirc; _WPcircle = true; + _last_loiter.reached_loiter_target_ms = now_ms; _bearing_error = 0.0f; // bearing error (radians), +ve to left of track _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians)from AC to L1 point } + _last_loiter.radius = radius_unscaled; + _last_loiter.direction = loiter_direction; + _last_loiter.center_WP = center_WP; + _data_is_stale = false; // status are correctly updated with current waypoint data } @@ -487,6 +515,7 @@ void AP_L1_Control::update_heading_hold(int32_t navigation_heading_cd) // Waypoint capture status is always false during heading hold _WPcircle = false; + _last_loiter.reached_loiter_target_ms = 0; _crosstrack_error = 0; @@ -510,6 +539,7 @@ void AP_L1_Control::update_level_flight(void) // Waypoint capture status is always false during heading hold _WPcircle = false; + _last_loiter.reached_loiter_target_ms = 0; _latAccDem = 0; diff --git a/libraries/AP_L1_Control/AP_L1_Control.h b/libraries/AP_L1_Control/AP_L1_Control.h index b775e5800a5a8a..20eb6e577713cd 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.h +++ b/libraries/AP_L1_Control/AP_L1_Control.h @@ -14,7 +14,6 @@ */ #include -#include #include #include #include @@ -125,6 +124,14 @@ class AP_L1_Control : public AP_Navigation { AP_Float _loiter_bank_limit; + // remember reached_loiter_target decision + struct { + uint32_t reached_loiter_target_ms; + float radius; + int8_t direction; + Location center_WP; + } _last_loiter; + bool _reverse = false; float get_yaw() const; int32_t get_yaw_sensor() const; diff --git a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp index 5d3bdc2f41558a..ebc44a3937d554 100644 --- a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp +++ b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp @@ -142,10 +142,12 @@ void AP_LTM_Telem::send_Sframe(void) const uint8_t flightmode = AP_Notify::flags.flight_mode; // flight mode uint8_t rssi = 0; // radio RSSI (%a) +#if AP_RSSI_ENABLED AP_RSSI *ap_rssi = AP_RSSI::get_singleton(); if (ap_rssi) { rssi = ap_rssi->read_receiver_rssi_uint8(); } +#endif const uint8_t armstat = AP_Notify::flags.armed; // 0: disarmed, 1: armed const uint8_t failsafe = AP_Notify::flags.failsafe_radio; // 0: normal, 1: failsafe diff --git a/libraries/AP_LTM_Telem/AP_LTM_Telem.h b/libraries/AP_LTM_Telem/AP_LTM_Telem.h index f0315f7f975c86..245baf758e9794 100644 --- a/libraries/AP_LTM_Telem/AP_LTM_Telem.h +++ b/libraries/AP_LTM_Telem/AP_LTM_Telem.h @@ -17,7 +17,7 @@ #include #ifndef AP_LTM_TELEM_ENABLED -#define AP_LTM_TELEM_ENABLED 1 +#define AP_LTM_TELEM_ENABLED BOARD_FLASH_SIZE > 2048 #endif #if AP_LTM_TELEM_ENABLED diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 7ac89719947864..ed2591cd3bb1a2 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -168,7 +168,7 @@ void AP_LandingGear::deploy() // send message only if output has been configured if (!_deployed && SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) { - gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "LandingGear: DEPLOY"); } // set deployed flag @@ -194,7 +194,7 @@ void AP_LandingGear::retract() // send message only if output has been configured if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) { - gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: RETRACT"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "LandingGear: RETRACT"); } } diff --git a/libraries/AP_LeakDetector/AP_LeakDetector.cpp b/libraries/AP_LeakDetector/AP_LeakDetector.cpp index c4973b3a1ebaa5..3b39a9a07fde79 100644 --- a/libraries/AP_LeakDetector/AP_LeakDetector.cpp +++ b/libraries/AP_LeakDetector/AP_LeakDetector.cpp @@ -112,11 +112,11 @@ void AP_LeakDetector::init() switch(_type[i]) { case ANALOG: _state[i].instance = i; - _drivers[i] = new AP_LeakDetector_Analog(*this, _state[i]); + _drivers[i] = NEW_NOTHROW AP_LeakDetector_Analog(*this, _state[i]); break; case DIGITAL: _state[i].instance = i; - _drivers[i] = new AP_LeakDetector_Digital(*this, _state[i]); + _drivers[i] = NEW_NOTHROW AP_LeakDetector_Digital(*this, _state[i]); break; } } diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 5ea3d7b595be76..60d4e4a1b2dd04 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -6,7 +6,7 @@ #include "AP_Logger_File.h" #include "AP_Logger_Flash_JEDEC.h" -#include "AP_Logger_W25N01GV.h" +#include "AP_Logger_W25NXX.h" #include "AP_Logger_MAVLink.h" #include @@ -247,7 +247,7 @@ void AP_Logger::init(const AP_Int32 &log_bitmask, const struct LogStructure *str return; } LoggerMessageWriter_DFLogStart *message_writer = - new LoggerMessageWriter_DFLogStart(); + NEW_NOTHROW LoggerMessageWriter_DFLogStart(); if (message_writer == nullptr) { AP_BoardConfig::allocation_error("message writer"); } @@ -489,7 +489,7 @@ bool AP_Logger::validate_structure(const struct LogStructure *logstructure, cons if (false && passed) { for (uint8_t j=0; jmultipliers); j++) { const char fmt = logstructure->format[j]; - if (fmt != 'f') { + if (fmt != 'f' && fmt != 'd' && fmt != 'g') { continue; } const char logmultiplier = logstructure->multipliers[j]; @@ -614,16 +614,6 @@ void AP_Logger::Write_MessageF(const char *fmt, ...) void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend) { _log_start_count++; - - for (uint8_t i=0; i<_next_backend; i++) { - if (backends[i] == backend) { // pointer comparison! - // reset sent masks - for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) { - f->sent_mask &= ~(1<msg_type = fmt->type; f->msg_len = fmt->length; f->name = strndup(fmt->name, sizeof(fmt->name)); @@ -843,7 +833,7 @@ uint16_t AP_Logger::get_max_num_logs() { } /* we're started if any of the backends are started */ -bool AP_Logger::logging_started(void) { +bool AP_Logger::logging_started(void) const { for (uint8_t i=0; i< _next_backend; i++) { if (backends[i]->logging_started()) { return true; @@ -906,9 +896,10 @@ void AP_Logger::Write_Parameter(const char *name, float value) } void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission, - const AP_Mission::Mission_Command &cmd) + const AP_Mission::Mission_Command &cmd, + LogMessages id) { - FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd)); + FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd, id)); } #if HAL_RALLY_ENABLED @@ -950,12 +941,7 @@ void AP_Logger::Write_NamedValueFloat(const char *name, float value) void AP_Logger::Safe_Write_Emit_FMT(log_write_fmt *f) { for (uint8_t i=0; i<_next_backend; i++) { - if (!(f->sent_mask & (1U<Write_Emit_FMT(f->msg_type)) { - continue; - } - f->sent_mask |= (1U<Safe_Write_Emit_FMT(f->msg_type); } } @@ -1041,12 +1027,6 @@ void AP_Logger::WriteV(const char *name, const char *labels, const char *units, } for (uint8_t i=0; i<_next_backend; i++) { - if (!(f->sent_mask & (1U<Write_Emit_FMT(f->msg_type)) { - continue; - } - f->sent_mask |= (1U<Write(f->msg_type, arg_copy, is_critical, is_streaming); @@ -1313,8 +1293,15 @@ int16_t AP_Logger::find_free_msg_type() const * It is assumed that logstruct's char* variables are valid strings of * maximum lengths for those fields (given in LogStructure.h e.g. LS_NAME_SIZE) */ -bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const +bool AP_Logger::fill_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const { + // check the static lists first... + const LogStructure *found = structure_for_msg_type(msg_type); + if (found != nullptr) { + logstruct = *found; + return true; + } + // find log structure information corresponding to msg_type: struct log_write_fmt *f; for (f = log_write_fmts; f; f=f->next) { @@ -1368,6 +1355,7 @@ int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const case 'd' : len += sizeof(double); break; case 'e' : len += sizeof(int32_t); break; case 'f' : len += sizeof(float); break; + case 'g' : len += sizeof(float16_s); break; case 'h' : len += sizeof(int16_t); break; case 'i' : len += sizeof(int32_t); break; case 'n' : len += sizeof(char[4]); break; @@ -1639,13 +1627,13 @@ void AP_Logger::log_file_content(const char *filename) void AP_Logger::log_file_content(FileContent &file_content, const char *filename) { WITH_SEMAPHORE(file_content.sem); - auto *file = new file_list; + auto *file = NEW_NOTHROW file_list; if (file == nullptr) { return; } // make copy to allow original to go out of scope const size_t len = strlen(filename)+1; - char * tmp_filename = new char[len]; + char * tmp_filename = NEW_NOTHROW char[len]; if (tmp_filename == nullptr) { delete file; return; diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index d3cb4b0d687db4..9fe2c07f26a14a 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -28,13 +28,13 @@ enum class LogEvent : uint8_t { AUTO_ARMED = 15, LAND_COMPLETE_MAYBE = 17, LAND_COMPLETE = 18, - NOT_LANDED = 28, LOST_GPS = 19, FLIP_START = 21, FLIP_END = 22, SET_HOME = 25, SET_SIMPLE_ON = 26, SET_SIMPLE_OFF = 27, + NOT_LANDED = 28, SET_SUPERSIMPLE_ON = 29, AUTOTUNE_INITIALISED = 30, AUTOTUNE_OFF = 31, @@ -79,8 +79,15 @@ enum class LogEvent : uint8_t { STANDBY_ENABLE = 74, STANDBY_DISABLE = 75, - FENCE_FLOOR_ENABLE = 80, - FENCE_FLOOR_DISABLE = 81, + // Fence events + FENCE_ALT_MAX_ENABLE = 76, + FENCE_ALT_MAX_DISABLE = 77, + FENCE_CIRCLE_ENABLE = 78, + FENCE_CIRCLE_DISABLE = 79, + FENCE_ALT_MIN_ENABLE = 80, + FENCE_ALT_MIN_DISABLE = 81, + FENCE_POLYGON_ENABLE = 82, + FENCE_POLYGON_DISABLE = 83, // if the EKF's source input set is changed (e.g. via a switch or // a script), we log an event: @@ -266,8 +273,15 @@ class AP_Logger uint8_t source_component, MAV_RESULT result, bool was_command_long=false); + void Write_MISE(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) { + Write_Mission_Cmd(mission, cmd, LOG_MISE_MSG); + } + void Write_CMD(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) { + Write_Mission_Cmd(mission, cmd, LOG_CMD_MSG); + } void Write_Mission_Cmd(const AP_Mission &mission, - const AP_Mission::Mission_Command &cmd); + const AP_Mission::Mission_Command &cmd, + LogMessages id); void Write_RallyPoint(uint8_t total, uint8_t sequence, const class RallyLocation &rally_point); @@ -287,7 +301,7 @@ class AP_Logger // returns true if logging of a message should be attempted bool should_log(uint32_t mask) const; - bool logging_started(void); + bool logging_started(void) const; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX // currently only AP_Logger_File support this: @@ -365,7 +379,7 @@ class AP_Logger void handle_log_send(); bool in_log_download() const; - float quiet_nanf() const { return nanf("0x4152"); } // "AR" + float quiet_nanf() const { return NaNf; } // "AR" double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI" // returns true if msg_type is associated with a message @@ -382,7 +396,6 @@ class AP_Logger struct log_write_fmt *next; uint8_t msg_type; uint8_t msg_len; - uint8_t sent_mask; // bitmask of backends sent to const char *name; const char *fmt; const char *labels; @@ -452,7 +465,7 @@ class AP_Logger int16_t find_free_msg_type() const; // fill LogStructure with information about msg_type - bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const; + bool fill_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const; bool _armed; @@ -585,6 +598,7 @@ class AP_Logger void handle_log_request_data(class GCS_MAVLINK &, const mavlink_message_t &msg); void handle_log_request_erase(class GCS_MAVLINK &, const mavlink_message_t &msg); void handle_log_request_end(class GCS_MAVLINK &, const mavlink_message_t &msg); + void end_log_transfer(); void handle_log_send_listing(); // handle LISTING state void handle_log_sending(); // handle SENDING state bool handle_log_send_data(); // send data chunk to client diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index e0b0ecfb6c9f50..6d9db1a43b9a77 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -100,7 +100,7 @@ void AP_Logger_Backend::start_new_log_reset_variables() _dropped = 0; _startup_messagewriter->reset(); _front.backend_starting_new_log(this); - _log_file_size_bytes = 0; + _formats_written.clearall(); } // We may need to make sure data is loggable before starting the @@ -124,42 +124,6 @@ void AP_Logger_Backend::push_log_blocks() { WriteMoreStartupMessages(); } -// returns true if all format messages have been written, and thus it is OK -// for other messages to go out to the log -bool AP_Logger_Backend::WriteBlockCheckStartupMessages() -{ -#if APM_BUILD_TYPE(APM_BUILD_Replay) - return true; -#endif - - if (_startup_messagewriter->fmt_done()) { - return true; - } - - if (_writing_startup_messages) { - // we have been called by a messagewriter, so writing is OK - return true; - } - - if (!_startup_messagewriter->finished() && - !hal.scheduler->in_main_thread()) { - // only the main thread may write startup messages out - return false; - } - - // we're not writing startup messages, so this must be some random - // caller hoping to write blocks out. Push out log blocks - we - // might end up clearing the buffer..... - push_log_blocks(); - - // even if we did finish writing startup messages, we can't - // permit any message to go in as its timestamp will be before - // any we wrote in. Time going backwards annoys log readers. - - // sorry! currently busy writing out startup messages... - return false; -} - // source more messages from the startup message writer: void AP_Logger_Backend::WriteMoreStartupMessages() { @@ -181,6 +145,15 @@ void AP_Logger_Backend::WriteMoreStartupMessages() */ +// output a FMT message if not already done so +void AP_Logger_Backend::Safe_Write_Emit_FMT(uint8_t msg_type) +{ + if (have_emitted_format_for_type(LogMessages(msg_type))) { + return; + } + Write_Emit_FMT(msg_type); +} + bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type) { #if APM_BUILD_TYPE(APM_BUILD_Replay) @@ -202,7 +175,7 @@ bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type) ls.units, ls.multipliers }; - if (!_front.fill_log_write_logstructure(logstruct, msg_type)) { + if (!_front.fill_logstructure(logstruct, msg_type)) { // this is a bug; we've been asked to write out the FMT // message for a msg_type, but the frontend can't supply the // required information @@ -284,6 +257,13 @@ bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_ offset += sizeof(float); break; } + case 'g': { + Float16_t tmp; + tmp.set(va_arg(arg_list, double));; + memcpy(&buffer[offset], &tmp, sizeof(tmp)); + offset += sizeof(tmp); + break; + } case 'n': charlen = 4; break; @@ -363,6 +343,23 @@ bool AP_Logger_Backend::StartNewLogOK() const return true; } +// validate that pBuffer looks like a message, extract message type. +// Returns false if this doesn't look like a valid message. +bool AP_Logger_Backend::message_type_from_block(const void *pBuffer, uint16_t size, LogMessages &type) const +{ + if (size < 3) { + return false; + } + if (((uint8_t*)pBuffer)[0] != HEAD_BYTE1 || + ((uint8_t*)pBuffer)[1] != HEAD_BYTE2) { + // Not passed a message + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return false; + } + type = LogMessages(((uint8_t*)pBuffer)[2]); + return true; +} + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size) @@ -381,11 +378,10 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, if (size < 3) { AP_HAL::panic("Short prioritised block"); } - if (((uint8_t*)pBuffer)[0] != HEAD_BYTE1 || - ((uint8_t*)pBuffer)[1] != HEAD_BYTE2) { + LogMessages type; + if (!message_type_from_block(pBuffer, size, type)) { AP_HAL::panic("Not passed a message"); } - const uint8_t type = ((uint8_t*)pBuffer)[2]; uint8_t type_len; const char *name_src; const struct LogStructure *s = _front.structure_for_msg_type(type); @@ -413,6 +409,35 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, } #endif +bool AP_Logger_Backend::ensure_format_emitted(const void *pBuffer, uint16_t size) +{ +#if APM_BUILD_TYPE(APM_BUILD_Replay) + // we trust that Replay will correctly emit formats as required + return true; +#endif + + // extract the ID: + LogMessages type; + if (!message_type_from_block(pBuffer, size, type)) { + return false; + } + if (have_emitted_format_for_type(type)) { + return true; + } + + // make sure the FMT message has gone out! + if (type == LOG_FORMAT_MSG) { + // kind of? Our caller is just about to emit this.... + return true; + } + if (!have_emitted_format_for_type(LOG_FORMAT_MSG) && + !Write_Emit_FMT(LOG_FORMAT_MSG)) { + return false; + } + + return Write_Emit_FMT(type); +} + bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical, bool writev_streaming) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !APM_BUILD_TYPE(APM_BUILD_Replay) @@ -435,6 +460,10 @@ bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size } } + if (!ensure_format_emitted(pBuffer, size)) { + return false; + } + return _WritePrioritisedBlock(pBuffer, size, is_critical); } @@ -673,7 +702,6 @@ void AP_Logger_Backend::df_stats_gather(const uint16_t bytes_written, uint32_t s } stats.buf_space_sigma += space_remaining; stats.bytes += bytes_written; - _log_file_size_bytes += bytes_written; stats.blocks++; } diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 616ce36b667e1e..dd661d2a7e7c5d 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -9,6 +9,7 @@ #include #include #include +#include "LogStructure.h" class LoggerMessageWriter_DFLogStart; @@ -75,6 +76,7 @@ class AP_Logger_Backend virtual void get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page) = 0; virtual void get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc) = 0; virtual int16_t get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0; + virtual void end_log_transfer() = 0; virtual uint16_t get_num_logs() = 0; virtual uint16_t find_oldest_log(); @@ -132,10 +134,14 @@ class AP_Logger_Backend bool Write_Fence(); #endif bool Write_Format(const struct LogStructure *structure); + bool have_emitted_format_for_type(LogMessages a_type) const { + return _formats_written.get(uint8_t(a_type)); + } 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); + const AP_Mission::Mission_Command &cmd, + LogMessages id); bool Write_Mode(uint8_t mode, const ModeReason reason); bool Write_Parameter(const char *name, float value, float default_val); bool Write_Parameter(const AP_Param *ap, @@ -155,6 +161,9 @@ class AP_Logger_Backend // Returns true if the FMT message has ever been written. bool Write_Emit_FMT(uint8_t msg_type); + // output a FMT message if not already done so + void Safe_Write_Emit_FMT(uint8_t msg_type); + // write a log message out to the log of msg_type type, with // values contained in arg_list: bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false, bool is_streaming=false); @@ -195,7 +204,6 @@ class AP_Logger_Backend /* read a block */ - virtual bool WriteBlockCheckStartupMessages(); virtual void WriteMoreStartupMessages(); virtual void push_log_blocks(); @@ -205,7 +213,6 @@ class AP_Logger_Backend uint16_t _cached_oldest_log; uint32_t _dropped; - uint32_t _log_file_size_bytes; // should we rotate when we next stop logging bool _rotate_pending; @@ -262,6 +269,12 @@ class AP_Logger_Backend void Write_AP_Logger_Stats_File(const struct df_stats &_stats); void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size); + + bool message_type_from_block(const void *pBuffer, uint16_t size, LogMessages &type) const; + bool ensure_format_emitted(const void *pBuffer, uint16_t size); + bool emit_format_for_type(LogMessages a_type); + Bitmask<256> _formats_written; + }; #endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index c0966f7ec6ef3c..7ebf38c8c025ab 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -132,15 +132,7 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, return false; } - if (!WriteBlockCheckStartupMessages()) { - _dropped++; - return false; - } - - if (!write_sem.take(1)) { - _dropped++; - return false; - } + WITH_SEMAPHORE(write_sem); const uint32_t space = writebuf.space(); @@ -155,7 +147,6 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, if (!must_dribble && space < non_messagewriter_message_reserved_space(writebuf.get_size())) { // this message isn't dropped, it will be sent again... - write_sem.give(); return false; } last_messagewrite_message_sent = now; @@ -163,7 +154,6 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, // we reserve some amount of space for critical messages: if (!is_critical && space < critical_message_reserved_space(writebuf.get_size())) { _dropped++; - write_sem.give(); return false; } } @@ -171,13 +161,11 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, // if no room for entire message - drop it: if (space < size) { _dropped++; - write_sem.give(); return false; } writebuf.write((uint8_t*)pBuffer, size); df_stats_gather(size, writebuf.space()); - write_sem.give(); return true; } @@ -212,7 +200,7 @@ uint16_t AP_Logger_Block::ReadHeaders() // we are at the start of a file, read the file header if (df_FilePage == 1) { struct FileHeader fh; - BlockRead(0, &fh, sizeof(fh)); + BlockRead(sizeof(ph), &fh, sizeof(fh)); df_FileTime = fh.utc_secs; df_Read_BufferIdx += sizeof(fh); } @@ -314,7 +302,7 @@ void AP_Logger_Block::periodic_1Hz() _front._params.disarm_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, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.blk_ratemax, _front._params.disarm_ratemax); } if (!io_thread_alive()) { @@ -553,7 +541,7 @@ void AP_Logger_Block::stop_logging_async(void) void AP_Logger_Block::start_new_log(void) { if (erase_started) { - // already erasing + // currently erasing return; } diff --git a/libraries/AP_Logger/AP_Logger_Block.h b/libraries/AP_Logger/AP_Logger_Block.h index 8061137a5794d9..7f53e9550db5d6 100644 --- a/libraries/AP_Logger/AP_Logger_Block.h +++ b/libraries/AP_Logger/AP_Logger_Block.h @@ -24,6 +24,7 @@ class AP_Logger_Block : public AP_Logger_Backend { void get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page) override; void get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc) override; int16_t get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override WARN_IF_UNUSED; + void end_log_transfer() override { } uint16_t get_num_logs() override; void start_new_log(void) override; uint32_t bufferspace_available() override; diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 3208f8cf6e2549..4be657072997db 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -173,7 +173,7 @@ void AP_Logger_File::periodic_1Hz() _front._params.disarm_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, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.file_ratemax, _front._params.disarm_ratemax); } } @@ -366,26 +366,12 @@ void AP_Logger_File::Prep_MinSpace() } while (log_to_remove != first_log_to_remove); } -/* - construct a log file name given a log number. - The number in the log filename will *not* be zero-padded. - Note: Caller must free. - */ -char *AP_Logger_File::_log_file_name_short(const uint16_t log_num) const -{ - char *buf = nullptr; - if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == -1) { - return nullptr; - } - return buf; -} - /* construct a log file name given a log number. The number in the log filename will be zero-padded. Note: Caller must free. */ -char *AP_Logger_File::_log_file_name_long(const uint16_t log_num) const +char *AP_Logger_File::_log_file_name(const uint16_t log_num) const { char *buf = nullptr; if (asprintf(&buf, "%s/%08u.BIN", _log_directory, (unsigned)log_num) == -1) { @@ -394,25 +380,6 @@ char *AP_Logger_File::_log_file_name_long(const uint16_t log_num) const return buf; } -/* - return a log filename appropriate for the supplied log_num if a - filename exists with the short (not-zero-padded name) then it is the - appropirate name, otherwise the long (zero-padded) version is. - Note: Caller must free. - */ -char *AP_Logger_File::_log_file_name(const uint16_t log_num) const -{ - char *filename = _log_file_name_short(log_num); - if (filename == nullptr) { - return nullptr; - } - if (file_exists(filename)) { - return filename; - } - free(filename); - return _log_file_name_long(log_num); -} - /* return path name of the lastlog.txt marker file Note: Caller must free. @@ -461,7 +428,7 @@ bool AP_Logger_File::StartNewLogOK() const if (recent_open_error()) { return false; } -#if !APM_BUILD_TYPE(APM_BUILD_Replay) +#if !APM_BUILD_TYPE(APM_BUILD_Replay) && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) if (hal.scheduler->in_main_thread()) { return false; } @@ -474,11 +441,6 @@ bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, { WITH_SEMAPHORE(semaphore); - if (! WriteBlockCheckStartupMessages()) { - _dropped++; - return false; - } - #if APM_BUILD_TYPE(APM_BUILD_Replay) if (AP::FS().write(_write_fd, pBuffer, size) != size) { AP_HAL::panic("Short write"); @@ -680,6 +642,14 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p return ret; } +void AP_Logger_File::end_log_transfer() +{ + if (_read_fd != -1) { + AP::FS().close(_read_fd); + _read_fd = -1; + } +} + /* find size and date of a log */ @@ -802,7 +772,7 @@ void AP_Logger_File::start_new_log(void) // set _open_error here to avoid infinite recursion. Simply // writing a prioritised block may try to open a log - which means - // if anything in the start_new_log path does a gcs().send_text() + // if anything in the start_new_log path does a GCS_SEND_TEXT() // (for example), you will end up recursing if we don't take // precautions. We will reset _open_error if we actually manage // to open the log... @@ -907,7 +877,7 @@ bool AP_Logger_File::write_lastlog_file(uint16_t log_num) #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX void AP_Logger_File::flush(void) -#if APM_BUILD_TYPE(APM_BUILD_Replay) +#if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) { uint32_t tnow = AP_HAL::millis(); while (_write_fd != -1 && _initialised && !recent_open_error() && _writebuf.available()) { diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 038324e92e2274..3cfa02b132edf1 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -26,7 +26,7 @@ class AP_Logger_File : public AP_Logger_Backend static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_File(front, ls); + return NEW_NOTHROW AP_Logger_File(front, ls); } // initialisation @@ -45,6 +45,7 @@ class AP_Logger_File : public AP_Logger_Backend void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override; void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override; int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override; + void end_log_transfer() override; uint16_t get_num_logs() override; void start_new_log(void) override; uint16_t find_oldest_log() override; @@ -111,8 +112,6 @@ class AP_Logger_File : public AP_Logger_Backend /* construct a file name given a log number. Caller must free. */ char *_log_file_name(const uint16_t log_num) const; - char *_log_file_name_long(const uint16_t log_num) const; - char *_log_file_name_short(const uint16_t log_num) const; char *_lastlog_file_name() const; uint32_t _get_log_size(const uint16_t log_num); uint32_t _get_log_time(const uint16_t log_num); diff --git a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.cpp b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.cpp index e40eab78820796..025c53e3093ca1 100644 --- a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.cpp +++ b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.cpp @@ -4,7 +4,7 @@ #include "AP_Logger_config.h" -#if HAL_LOGGING_DATAFLASH_ENABLED +#if HAL_LOGGING_FLASH_JEDEC_ENABLED #include @@ -323,4 +323,4 @@ void AP_Logger_Flash_JEDEC::WriteEnable(void) dev->transfer(&b, 1, nullptr, 0); } -#endif // HAL_LOGGING_DATAFLASH_ENABLED +#endif // HAL_LOGGING_FLASH_JEDEC_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h index 43c0b37665d73d..1a85e51575e4e5 100644 --- a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h +++ b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h @@ -7,7 +7,7 @@ #include "AP_Logger_Block.h" -#if HAL_LOGGING_DATAFLASH_ENABLED +#if HAL_LOGGING_FLASH_JEDEC_ENABLED class AP_Logger_Flash_JEDEC : public AP_Logger_Block { public: @@ -15,7 +15,7 @@ class AP_Logger_Flash_JEDEC : public AP_Logger_Block { AP_Logger_Block(front, writer) {} static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_Flash_JEDEC(front, ls); + return NEW_NOTHROW AP_Logger_Flash_JEDEC(front, ls); } void Init(void) override; bool CardInserted() const override { return !flash_died && df_NumPages > 0; } @@ -46,4 +46,4 @@ class AP_Logger_Flash_JEDEC : public AP_Logger_Block { bool read_cache_valid; }; -#endif // HAL_LOGGING_DATAFLASH_ENABLED +#endif // HAL_LOGGING_FLASH_JEDEC_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.cpp b/libraries/AP_Logger/AP_Logger_MAVLink.cpp index 7d48b4afcaac33..6309abee28e3a8 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLink.cpp @@ -136,11 +136,6 @@ bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz return false; } - if (! WriteBlockCheckStartupMessages()) { - semaphore.give(); - return false; - } - if (bufferspace_available() < size) { if (_startup_messagewriter->finished()) { // do not count the startup packets as being dropped... @@ -545,7 +540,7 @@ void AP_Logger_MAVLink::periodic_1Hz() _front._params.disarm_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, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.mav_ratemax, _front._params.disarm_ratemax); } if (_sending_to_client && diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.h b/libraries/AP_Logger/AP_Logger_MAVLink.h index 4ae7202ff4f5d7..7dd85d30d8eb4b 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.h +++ b/libraries/AP_Logger/AP_Logger_MAVLink.h @@ -21,7 +21,7 @@ class AP_Logger_MAVLink : public AP_Logger_Backend static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_MAVLink(front, ls); + return NEW_NOTHROW AP_Logger_MAVLink(front, ls); } // initialisation @@ -50,6 +50,7 @@ class AP_Logger_MAVLink : public AP_Logger_Backend void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override {} void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override {} int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override { return 0; } + void end_log_transfer() override { }; uint16_t get_num_logs(void) override { return 0; } void remote_log_block_status_msg(const GCS_MAVLINK &link, const mavlink_message_t& msg) override; diff --git a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp index 08486b60e9b19e..841bf1beea5fbf 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp @@ -128,7 +128,7 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message uint16_t num_logs = get_num_logs(); if (packet.id > num_logs || packet.id < 1) { // request for an invalid log; cancel any current download - transfer_activity = TransferActivity::IDLE; + end_log_transfer(); return; } @@ -174,11 +174,16 @@ void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, const mavlink_messag void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, const mavlink_message_t &msg) { WITH_SEMAPHORE(_log_send_sem); - mavlink_log_request_end_t packet; - mavlink_msg_log_request_end_decode(&msg, &packet); + // mavlink_log_request_end_t packet; + // mavlink_msg_log_request_end_decode(&msg, &packet); + end_log_transfer(); +} +void AP_Logger::end_log_transfer() +{ transfer_activity = TransferActivity::IDLE; _log_sending_link = nullptr; + backends[0]->end_log_transfer(); } /** @@ -323,8 +328,7 @@ bool AP_Logger::handle_log_send_data() _log_data_offset += nbytes; _log_data_remaining -= nbytes; if (nbytes < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) { - transfer_activity = TransferActivity::IDLE; - _log_sending_link = nullptr; + end_log_transfer(); } return true; } diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp b/libraries/AP_Logger/AP_Logger_W25NXX.cpp similarity index 67% rename from libraries/AP_Logger/AP_Logger_W25N01GV.cpp rename to libraries/AP_Logger/AP_Logger_W25NXX.cpp index 86ce642c991d59..df3e8bcea2d894 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp +++ b/libraries/AP_Logger/AP_Logger_W25NXX.cpp @@ -5,9 +5,9 @@ #include -#include "AP_Logger_W25N01GV.h" +#include "AP_Logger_W25NXX.h" -#if HAL_LOGGING_DATAFLASH_ENABLED +#if HAL_LOGGING_FLASH_W25NXX_ENABLED #include @@ -30,37 +30,40 @@ extern const AP_HAL::HAL& hal; #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 W25NXX_STATUS_REG 0xC0 +#define W25NXX_PROT_REG 0xA0 +#define W25NXX_CONF_REG 0xB0 +#define W25NXX_STATUS_EFAIL 0x04 +#define W25NXX_STATUS_PFAIL 0x08 + +#define W25NXX_PROT_SRP1_ENABLE (1 << 0) +#define W25NXX_PROT_WP_E_ENABLE (1 << 1) +#define W25NXX_PROT_TB_ENABLE (1 << 2) +#define W25NXX_PROT_PB0_ENABLE (1 << 3) +#define W25NXX_PROT_PB1_ENABLE (1 << 4) +#define W25NXX_PROT_PB2_ENABLE (1 << 5) +#define W25NXX_PROT_PB3_ENABLE (1 << 6) +#define W25NXX_PROT_SRP2_ENABLE (1 << 7) + +#define W25NXX_CONFIG_ECC_ENABLE (1 << 4) +#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3) + +#define W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled) +#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us +#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms +#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms + #define W25N01G_NUM_BLOCKS 1024 +#define W25N02K_NUM_BLOCKS 2048 #define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 +#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22 -void AP_Logger_W25N01GV::Init() +void AP_Logger_W25NXX::Init() { dev = hal.spi->get_device("dataflash"); if (!dev) { - AP_HAL::panic("PANIC: AP_Logger W25N01GV device not found"); + AP_HAL::panic("PANIC: AP_Logger W25NXX device not found"); return; } @@ -80,17 +83,17 @@ void AP_Logger_W25N01GV::Init() uint8_t b = JEDEC_DEVICE_RESET; dev->transfer(&b, 1, nullptr, 0); } - hal.scheduler->delay(W25N01G_TIMEOUT_RESET_MS); + hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS); // disable write protection - WriteStatusReg(W25N01G_PROT_REG, 0); + WriteStatusReg(W25NXX_PROT_REG, 0); // enable ECC and buffer mode - WriteStatusReg(W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE); + WriteStatusReg(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE|W25NXX_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)); + printf("W25NXX status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n", + ReadStatusRegBits(W25NXX_PROT_REG), + ReadStatusRegBits(W25NXX_CONF_REG), + ReadStatusRegBits(W25NXX_STATUS_REG)); AP_Logger_Block::Init(); } @@ -98,7 +101,7 @@ void AP_Logger_W25N01GV::Init() /* wait for busy flag to be cleared */ -void AP_Logger_W25N01GV::WaitReady() +void AP_Logger_W25NXX::WaitReady() { if (flash_died) { return; @@ -115,7 +118,7 @@ void AP_Logger_W25N01GV::WaitReady() } } -bool AP_Logger_W25N01GV::getSectorCount(void) +bool AP_Logger_W25NXX::getSectorCount(void) { WaitReady(); @@ -133,6 +136,13 @@ bool AP_Logger_W25N01GV::getSectorCount(void) df_PageSize = 2048; df_PagePerBlock = 64; df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N01G_NUM_BLOCKS; + break; + case JEDEC_ID_WINBOND_W25N02KV: + df_PageSize = 2048; + df_PagePerBlock = 64; + df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N02K_NUM_BLOCKS; break; default: @@ -141,14 +151,14 @@ bool AP_Logger_W25N01GV::getSectorCount(void) return false; } - df_NumPages = W25N01G_NUM_BLOCKS * df_PagePerBlock; + df_NumPages = flash_blockNum * 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) +uint8_t AP_Logger_W25NXX::ReadStatusRegBits(uint8_t bits) { WITH_SEMAPHORE(dev_sem); uint8_t cmd[2] { JEDEC_READ_STATUS, bits }; @@ -157,7 +167,7 @@ uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits) return status; } -void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits) +void AP_Logger_W25NXX::WriteStatusReg(uint8_t reg, uint8_t bits) { WaitReady(); WITH_SEMAPHORE(dev_sem); @@ -165,14 +175,14 @@ void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits) dev->transfer(cmd, 3, nullptr, 0); } -bool AP_Logger_W25N01GV::Busy() +bool AP_Logger_W25NXX::Busy() { - uint8_t status = ReadStatusRegBits(W25N01G_STATUS_REG); + uint8_t status = ReadStatusRegBits(W25NXX_STATUS_REG); - if ((status & W25N01G_STATUS_PFAIL) != 0) { + if ((status & W25NXX_STATUS_PFAIL) != 0) { printf("Program failure!\n"); } - if ((status & W25N01G_STATUS_EFAIL) != 0) { + if ((status & W25NXX_STATUS_EFAIL) != 0) { printf("Erase failure!\n"); } @@ -182,18 +192,18 @@ bool AP_Logger_W25N01GV::Busy() /* send a command with an address */ -void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr) +void AP_Logger_W25NXX::send_command_addr(uint8_t command, uint32_t PageAdr) { uint8_t cmd[4]; cmd[0] = command; - cmd[1] = 0; // dummy + cmd[1] = (PageAdr >> 16) & 0xff; cmd[2] = (PageAdr >> 8) & 0xff; cmd[3] = (PageAdr >> 0) & 0xff; dev->transfer(cmd, 4, nullptr, 0); } -void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum) +void AP_Logger_W25NXX::PageToBuffer(uint32_t pageNum) { if (pageNum == 0 || pageNum > df_NumPages+1) { printf("Invalid page read %u\n", pageNum); @@ -237,7 +247,7 @@ void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum) } } -void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum) +void AP_Logger_W25NXX::BufferToPage(uint32_t pageNum) { if (pageNum == 0 || pageNum > df_NumPages+1) { printf("Invalid page write %u\n", pageNum); @@ -278,7 +288,7 @@ void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum) /* erase one sector (sizes varies with hw) */ -void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum) +void AP_Logger_W25NXX::SectorErase(uint32_t blockNum) { WriteEnable(); WITH_SEMAPHORE(dev_sem); @@ -290,12 +300,12 @@ void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum) /* erase one 4k sector */ -void AP_Logger_W25N01GV::Sector4kErase(uint32_t sectorNum) +void AP_Logger_W25NXX::Sector4kErase(uint32_t sectorNum) { SectorErase(sectorNum); } -void AP_Logger_W25N01GV::StartErase() +void AP_Logger_W25NXX::StartErase() { WriteEnable(); @@ -309,10 +319,10 @@ void AP_Logger_W25N01GV::StartErase() printf("Dataflash: erase started\n"); } -bool AP_Logger_W25N01GV::InErase() +bool AP_Logger_W25NXX::InErase() { if (erase_start_ms && !Busy()) { - if (erase_block < W25N01G_NUM_BLOCKS) { + if (erase_block < flash_blockNum) { SectorErase(erase_block++); } else { printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms); @@ -323,7 +333,7 @@ bool AP_Logger_W25N01GV::InErase() return erase_start_ms != 0; } -void AP_Logger_W25N01GV::WriteEnable(void) +void AP_Logger_W25NXX::WriteEnable(void) { WaitReady(); WITH_SEMAPHORE(dev_sem); @@ -331,4 +341,4 @@ void AP_Logger_W25N01GV::WriteEnable(void) dev->transfer(&b, 1, nullptr, 0); } -#endif // HAL_LOGGING_DATAFLASH_ENABLED +#endif // HAL_LOGGING_FLASH_W25NXX_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.h b/libraries/AP_Logger/AP_Logger_W25NXX.h similarity index 80% rename from libraries/AP_Logger/AP_Logger_W25N01GV.h rename to libraries/AP_Logger/AP_Logger_W25NXX.h index 556603eaffd22b..c384fa97db3e4c 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.h +++ b/libraries/AP_Logger/AP_Logger_W25NXX.h @@ -3,19 +3,21 @@ */ #pragma once +#include "AP_Logger_config.h" + +#if HAL_LOGGING_FLASH_W25NXX_ENABLED + #include #include "AP_Logger_Block.h" -#if HAL_LOGGING_DATAFLASH_ENABLED - -class AP_Logger_W25N01GV : public AP_Logger_Block { +class AP_Logger_W25NXX : public AP_Logger_Block { public: - AP_Logger_W25N01GV(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_W25NXX(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); + return NEW_NOTHROW AP_Logger_W25NXX(front, ls); } void Init(void) override; bool CardInserted() const override { return !flash_died && df_NumPages > 0; } @@ -39,10 +41,12 @@ class AP_Logger_W25N01GV : public AP_Logger_Block { AP_HAL::OwnPtr dev; AP_HAL::Semaphore *dev_sem; + uint32_t flash_blockNum; + bool flash_died; uint32_t erase_start_ms; uint16_t erase_block; bool read_cache_valid; }; -#endif // HAL_LOGGING_DATAFLASH_ENABLED +#endif // HAL_LOGGING_FLASH_W25NXX_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_config.h b/libraries/AP_Logger/AP_Logger_config.h index 8627867a380478..a5a3508043c340 100644 --- a/libraries/AP_Logger/AP_Logger_config.h +++ b/libraries/AP_Logger/AP_Logger_config.h @@ -26,11 +26,19 @@ #endif #if HAL_LOGGING_DATAFLASH_ENABLED - #define HAL_LOGGING_BLOCK_ENABLED 1 + #define HAL_LOGGING_BLOCK_ENABLED HAL_LOGGING_ENABLED #else #define HAL_LOGGING_BLOCK_ENABLED 0 #endif +#ifndef HAL_LOGGING_FLASH_W25NXX_ENABLED +#define HAL_LOGGING_FLASH_W25NXX_ENABLED HAL_LOGGING_BLOCK_ENABLED +#endif + +#ifndef HAL_LOGGING_FLASH_JEDEC_ENABLED +#define HAL_LOGGING_FLASH_JEDEC_ENABLED HAL_LOGGING_BLOCK_ENABLED +#endif + #if HAL_LOGGING_FILESYSTEM_ENABLED #if !defined (HAL_BOARD_LOG_DIRECTORY) diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 405f41ac2cbd02..4765af723cdfb1 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -60,7 +60,11 @@ bool AP_Logger_Backend::Write_Format(const struct LogStructure *s) { struct log_Format pkt; Fill_Format(s, pkt); - return WriteCriticalBlock(&pkt, sizeof(pkt)); + if (!WriteCriticalBlock(&pkt, sizeof(pkt))) { + return false; + } + _formats_written.set(s->msg_type); + return true; } /* @@ -296,12 +300,13 @@ void AP_Logger::Write_Command(const mavlink_command_int_t &packet, } bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission, - const AP_Mission::Mission_Command &cmd) + const AP_Mission::Mission_Command &cmd, + LogMessages msgid) { mavlink_mission_item_int_t mav_cmd = {}; AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd); - const struct log_Cmd pkt{ - LOG_PACKET_HEADER_INIT(LOG_CMD_MSG), + const struct log_CMD pkt{ + LOG_PACKET_HEADER_INIT(msgid), time_us : AP_HAL::micros64(), command_total : mission.num_commands(), sequence : mav_cmd.seq, diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 261f6e17e56e0b..d2c014eb3341c5 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -146,6 +146,7 @@ const struct MultiplierStructure log_Multipliers[] = { #include #include #include +#include // structure used to define logging format // It is packed on ChibiOS to save flash space; however, this causes problems @@ -350,22 +351,6 @@ struct PACKED log_MCU { float MCU_voltage_max; }; -struct PACKED log_Cmd { - LOG_PACKET_HEADER; - uint64_t time_us; - uint16_t command_total; - uint16_t sequence; - uint16_t command; - float param1; - float param2; - float param3; - float param4; - int32_t latitude; - int32_t longitude; - float altitude; - uint8_t frame; -}; - struct PACKED log_MAVLink_Command { LOG_PACKET_HEADER; uint64_t time_us; @@ -571,6 +556,7 @@ struct PACKED log_Performance { uint32_t i2c_count; uint32_t i2c_isr_count; uint32_t extra_loop_us; + uint64_t rtc; }; struct PACKED log_SRTL { @@ -712,21 +698,6 @@ struct PACKED log_VER { // @Field: TR: innovation test ratio // @Field: Pri: True if sensor is the primary sensor -// @LoggerMessage: CMD -// @Description: Executed mission command information -// @Field: TimeUS: Time since system startup -// @Field: CTot: Total number of mission commands -// @Field: CNum: This command's offset in mission -// @Field: CId: Command type -// @Field: Prm1: Parameter 1 -// @Field: Prm2: Parameter 2 -// @Field: Prm3: Parameter 3 -// @Field: Prm4: Parameter 4 -// @Field: Lat: Command latitude -// @Field: Lng: Command longitude -// @Field: Alt: Command altitude -// @Field: Frame: Frame used for position - // @LoggerMessage: CSRV // @Description: Servo feedback data // @Field: TimeUS: Time since system startup @@ -829,7 +800,7 @@ struct PACKED log_VER { // @Field: txp: transmitted packet count // @Field: rxp: received packet count // @Field: rxdp: perceived number of packets we never received -// @Field: flags: compact representation of some stage of the channel +// @Field: flags: compact representation of some state of the channel // @FieldBitmaskEnum: flags: GCS_MAVLINK::Flags // @Field: ss: stream slowdown is the number of ms being added to each message to fit within bandwidth // @Field: tf: times buffer was full when a message was going to be sent @@ -925,14 +896,15 @@ struct PACKED log_VER { // @Field: MaxT: Maximum loop time // @Field: Mem: Free memory available // @Field: Load: System processor load -// @Field: IntE: Internal error mask; which internal errors have been detected -// @FieldBitmaskEnum: IntE: AP_InternalError::error_t +// @Field: InE: Internal error mask; which internal errors have been detected +// @FieldBitmaskEnum: InE: AP_InternalError::error_t // @Field: ErrL: Internal error line number; last line number on which a internal error was detected -// @Field: ErrC: Internal error count; how many internal errors have been detected +// @Field: ErC: Internal error count; how many internal errors have been detected // @Field: SPIC: Number of SPI transactions processed // @Field: I2CC: Number of i2c transactions processed // @Field: I2CI: Number of i2c interrupts serviced // @Field: Ex: number of microseconds being added to each loop to address scheduler overruns +// @Field: R: RTC time, time since Unix epoch // @LoggerMessage: POWR // @Description: System power information @@ -1082,7 +1054,7 @@ struct PACKED log_VER { // @Field: NumPts: number of points currently in use // @Field: MaxPts: maximum number of points that could be used // @Field: Action: most recent internal action taken by SRTL library -// @FieldValueEnum: Action: AP_SmartRTL::SRTL_Actions +// @FieldValueEnum: Action: AP_SmartRTL::Action // @Field: N: point associated with most recent action (North component) // @Field: E: point associated with most recent action (East component) // @Field: D: point associated with most recent action (Down component) @@ -1164,7 +1136,9 @@ struct PACKED log_VER { // @Description: Ardupilot version // @Field: TimeUS: Time since system startup // @Field: BT: Board type +// @FieldValueEnum: BT: HAL_BOARD // @Field: BST: Board subtype +// @FieldValueEnum: BST: HAL_BOARD_SUBTYPE // @Field: Maj: Major version number // @Field: Min: Minor version number // @Field: Pat: Patch number @@ -1173,6 +1147,7 @@ struct PACKED log_VER { // @Field: FWS: Firmware version string // @Field: APJ: Board ID // @Field: BU: Build vehicle type +// @FieldValueEnum: BU: APM_BUILD // @Field: FV: Filter version // @LoggerMessage: MOTB @@ -1218,8 +1193,7 @@ LOG_STRUCTURE_FROM_PRECLAND \ "POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---", true }, \ { LOG_MCU_MSG, sizeof(log_MCU), \ "MCU","Qffff","TimeUS,MTemp,MVolt,MVmin,MVmax", "sOvvv", "F0000", true }, \ - { LOG_CMD_MSG, sizeof(log_Cmd), \ - "CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \ +LOG_STRUCTURE_FROM_MISSION \ { LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \ "MAVC", "QBBBBBHffffiifBB","TimeUS,TS,TC,SS,SC,Fr,Cmd,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \ { LOG_RADIO_MSG, sizeof(log_Radio), \ @@ -1239,7 +1213,7 @@ LOG_STRUCTURE_FROM_MOUNT \ LOG_STRUCTURE_FROM_BEACON \ LOG_STRUCTURE_FROM_PROXIMITY \ { LOG_PERFORMANCE_MSG, sizeof(log_Performance), \ - "PM", "QHHHIIHHIIIIII", "TimeUS,LR,NLon,NL,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "sz---b%------s", "F----0A------F" }, \ + "PM", "QHHHIIHHIIIIIIQ", "TimeUS,LR,NLon,NL,MaxT,Mem,Load,ErrL,InE,ErC,SPIC,I2CC,I2CI,Ex,R", "sz---b%------ss", "F----0A------FF" }, \ { LOG_SRTL_MSG, sizeof(log_SRTL), \ "SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \ LOG_STRUCTURE_FROM_AVOIDANCE \ @@ -1249,7 +1223,7 @@ LOG_STRUCTURE_FROM_AVOIDANCE \ "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","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", true }, \ + "CSRV","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", false }, \ { LOG_PIDR_MSG, sizeof(log_PID), \ "PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS, true }, \ { LOG_PIDP_MSG, sizeof(log_PID), \ @@ -1283,7 +1257,7 @@ LOG_STRUCTURE_FROM_FENCE \ "MAV", "QBHHHBHH", "TimeUS,chan,txp,rxp,rxdp,flags,ss,tf", "s#----s-", "F-000-C-" }, \ LOG_STRUCTURE_FROM_VISUALODOM \ { LOG_OPTFLOW_MSG, sizeof(log_Optflow), \ - "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" , true }, \ + "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" , true }, \ { LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \ "WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" , true }, \ { LOG_ADSB_MSG, sizeof(log_ADSB), \ @@ -1309,7 +1283,7 @@ LOG_STRUCTURE_FROM_AIS \ { LOG_MOTBATT_MSG, sizeof(log_MotBatt), \ "MOTB", "QfffffB", "TimeUS,LiftMax,BatVolt,ThLimit,ThrAvMx,ThrOut,FailFlags", "s------", "F------" , true } -// message types 0 to 63 reserved for vehicle specific use +// message types 0 to 31 reserved for vehicle-specific use // message types for common messages enum LogMessages : uint8_t { @@ -1326,7 +1300,6 @@ enum LogMessages : uint8_t { LOG_MCU_MSG, LOG_IDS_FROM_AHRS, LOG_SIMSTATE_MSG, - LOG_CMD_MSG, LOG_MAVLINK_COMMAND_MSG, LOG_RADIO_MSG, LOG_ATRP_MSG, @@ -1337,6 +1310,7 @@ enum LogMessages : uint8_t { LOG_IDS_FROM_ESC_TELEM, LOG_IDS_FROM_BATTMONITOR, LOG_IDS_FROM_HAL_CHIBIOS, + LOG_IDS_FROM_MISSION, LOG_IDS_FROM_GPS, diff --git a/libraries/AP_Logger/LoggerMessageWriter.cpp b/libraries/AP_Logger/LoggerMessageWriter.cpp index 3918fc6226c6b3..0aaa3671aa5266 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.cpp +++ b/libraries/AP_Logger/LoggerMessageWriter.cpp @@ -109,7 +109,12 @@ void LoggerMessageWriter_DFLogStart::process() case Stage::FORMATS: // write log formats so the log is self-describing while (next_format_to_send < _logger_backend->num_types()) { - if (!_logger_backend->Write_Format(_logger_backend->structure(next_format_to_send))) { + const auto &s { _logger_backend->structure(next_format_to_send) }; + if (_logger_backend->have_emitted_format_for_type((LogMessages)s->msg_type)) { + next_format_to_send++; + continue; + } + if (!_logger_backend->Write_Format(s)) { return; // call me again! } next_format_to_send++; @@ -177,40 +182,30 @@ void LoggerMessageWriter_DFLogStart::process() stage = Stage::RUNNING_SUBWRITERS; FALLTHROUGH; - case Stage::RUNNING_SUBWRITERS: - if (!_writesysinfo.finished()) { - _writesysinfo.process(); - if (!_writesysinfo.finished()) { - return; - } - } + case Stage::RUNNING_SUBWRITERS: { + LoggerMessageWriter *subwriters[] { + &_writesysinfo, #if AP_MISSION_ENABLED - if (!_writeentiremission.finished()) { - _writeentiremission.process(); - if (!_writeentiremission.finished()) { - return; - } - } + &_writeentiremission, #endif #if HAL_LOGGER_RALLY_ENABLED - if (!_writeallrallypoints.finished()) { - _writeallrallypoints.process(); - if (!_writeallrallypoints.finished()) { - return; - } - } + &_writeallrallypoints, #endif #if HAL_LOGGER_FENCE_ENABLED - if (!_writeallpolyfence.finished()) { - _writeallpolyfence.process(); - if (!_writeallpolyfence.finished()) { - return; + &_writeallpolyfence, +#endif + }; + for (auto *sw : subwriters) { + if (!sw->finished()) { + sw->process(); + if (!sw->finished()) { + return; + } } } -#endif stage = Stage::VEHICLE_MESSAGES; FALLTHROUGH; - + } case Stage::VEHICLE_MESSAGES: // we guarantee 200 bytes of space for the vehicle startup // messages. This allows them to be simple functions rather @@ -442,7 +437,7 @@ void LoggerMessageWriter_WriteEntireMission::process() { // upon failure to write the mission we will re-read from // storage; this could be improved. if (_mission->read_cmd_from_storage(_mission_number_to_send,cmd)) { - if (!_logger_backend->Write_Mission_Cmd(*_mission, cmd)) { + if (!_logger_backend->Write_Mission_Cmd(*_mission, cmd, LOG_CMD_MSG)) { return; // call me again } } diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index 2e28503676faf5..ad109f815537fc 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -8,7 +8,7 @@ class LoggerMessageWriter { virtual void reset() = 0; virtual void process() = 0; - virtual bool finished() { return _finished; } + bool finished() const { return _finished; } virtual void set_logger_backend(class AP_Logger_Backend *backend) { _logger_backend = backend; diff --git a/libraries/AP_Logger/README.md b/libraries/AP_Logger/README.md index d049c16f654c9b..52b99ff583ee2b 100644 --- a/libraries/AP_Logger/README.md +++ b/libraries/AP_Logger/README.md @@ -23,6 +23,7 @@ and how the content should be interpreted. |M | uint8_t flight mode| |q | int64_t| |Q | uint64_t| +|g | float16_t| Legacy field types - do not use. These have been replaced by using the base C type and an appropriate multiplier column entry. 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 76e8aac2b696c3..740c0ed0d70c47 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 @@ -40,6 +40,7 @@ struct PACKED log_TYP2 { uint8_t M; // flight mode int64_t q; uint64_t Q; + Float16_t g; }; @@ -74,10 +75,10 @@ static const struct LogStructure log_structure[] = { { LOG_TYP2_MSG, sizeof(log_TYP2), "TYP2", - "QcCeELMqQ", - "TimeUS,c,C,e,E,L,M,q,Q", - "s--------", - "F--------" + "QcCeELMqQg", + "TimeUS,c,C,e,E,L,M,q,Q,g", + "s---------", + "F---------" }, { LOG_MESSAGE_MSG, sizeof(log_Message), @@ -93,8 +94,8 @@ static const struct LogStructure log_structure[] = { // structure and that in LogStructure.h #define TYP1_FMT "QabBhHiIfdnNZ" #define TYP1_LBL "TimeUS,b,B,h,H,i,I,f,d,n,N,Z" -#define TYP2_FMT "QcCeELMqQ" -#define TYP2_LBL "TimeUS,c,C,e,E,L,M,q,Q" +#define TYP2_FMT "QcCeELMqQg" +#define TYP2_LBL "TimeUS,c,C,e,E,L,M,q,Q,g" static uint16_t log_num; @@ -158,8 +159,12 @@ void AP_LoggerTest_AllTypes::Log_Write_TypeMessages() 'A','B','C','D','E','F','G','H','I','J','K','L','M','N','O','P', 'A','B','C','D','E','F','G','H','I','J','K','L','M','N','O','P' } }; - logger.WriteBlock(&typ1, sizeof(typ1)); + if (!logger.WriteBlock_first_succeed(&typ1, sizeof(typ1))) { + abort(); + } + Float16_t f16; + f16.set(13.54f); struct log_TYP2 typ2 = { LOG_PACKET_HEADER_INIT(LOG_TYP2_MSG), time_us : AP_HAL::micros64(), @@ -170,7 +175,8 @@ void AP_LoggerTest_AllTypes::Log_Write_TypeMessages() L : -3576543, // uint32_t latitude/longitude; M : 5, // uint8_t; // flight mode; q : -98239832498328, // int64_t - Q : 3432345232233432 // uint64_t + Q : 3432345232233432, // uint64_t + g : f16 // float16_t }; logger.WriteBlock(&typ2, sizeof(typ2)); @@ -232,7 +238,8 @@ void AP_LoggerTest_AllTypes::Log_Write_TypeMessages_Log_Write() -3576543, // uint32_t latitude/longitude; 5, // uint8_t; // flight mode; -98239832498328, // int64_t - 3432345232233432 // uint64_t + 3432345232233432, // uint64_t + 13.54 // float16_t ); // emit a message which contains NaNs: diff --git a/libraries/AP_Logger/examples/AP_Logger_AllTypes/output.BIN b/libraries/AP_Logger/examples/AP_Logger_AllTypes/output.BIN index 2976c66e9d7456..f4bd3d14466bb4 100644 Binary files a/libraries/AP_Logger/examples/AP_Logger_AllTypes/output.BIN and b/libraries/AP_Logger/examples/AP_Logger_AllTypes/output.BIN differ diff --git a/libraries/AP_MSP/AP_MSP.cpp b/libraries/AP_MSP/AP_MSP.cpp index 9f41ed928afbbe..9006bbf8907e7d 100644 --- a/libraries/AP_MSP/AP_MSP.cpp +++ b/libraries/AP_MSP/AP_MSP.cpp @@ -63,12 +63,12 @@ AP_MSP::AP_MSP() bool AP_MSP::init_backend(uint8_t backend_idx, AP_HAL::UARTDriver *uart, AP_SerialManager::SerialProtocol protocol) { if (protocol == AP_SerialManager::SerialProtocol_MSP) { - _backends[backend_idx] = new AP_MSP_Telem_Generic(uart); + _backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_Generic(uart); } else if (protocol == AP_SerialManager::SerialProtocol_DJI_FPV) { - _backends[backend_idx] = new AP_MSP_Telem_DJI(uart); + _backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_DJI(uart); #if HAL_WITH_MSP_DISPLAYPORT } else if (protocol == AP_SerialManager::SerialProtocol_MSP_DisplayPort) { - _backends[backend_idx] = new AP_MSP_Telem_DisplayPort(uart); + _backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_DisplayPort(uart); #endif } else { return false; diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index 2ee0a6a43cb442..816d876c97d915 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -25,7 +25,6 @@ #include #include #include -#include #include #include #include @@ -218,7 +217,7 @@ void AP_MSP_Telem_Backend::update_gps_state(gps_state_t &gps_state) gps_state.lon = loc.lng; gps_state.alt_m = loc.alt/100; // 1m resolution gps_state.speed_cms = gps.ground_speed() * 100; - gps_state.ground_course_cd = gps.ground_course_cd(); + gps_state.ground_course_dd = gps.ground_course_cd() / 10; } } #endif @@ -503,93 +502,105 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m MSP_UNUSED(src); switch (cmd_msp) { +#if HAL_MSP_RANGEFINDER_ENABLED case MSP2_SENSOR_RANGEFINDER: { const MSP::msp_rangefinder_data_message_t *pkt = (const MSP::msp_rangefinder_data_message_t *)src->ptr; msp_handle_rangefinder(*pkt); } break; +#endif +#if HAL_MSP_OPTICALFLOW_ENABLED case MSP2_SENSOR_OPTIC_FLOW: { const MSP::msp_opflow_data_message_t *pkt = (const MSP::msp_opflow_data_message_t *)src->ptr; msp_handle_opflow(*pkt); } break; +#endif +#if HAL_MSP_GPS_ENABLED case MSP2_SENSOR_GPS: { const MSP::msp_gps_data_message_t *pkt = (const MSP::msp_gps_data_message_t *)src->ptr; msp_handle_gps(*pkt); } break; +#endif +#if AP_COMPASS_MSP_ENABLED case MSP2_SENSOR_COMPASS: { const MSP::msp_compass_data_message_t *pkt = (const MSP::msp_compass_data_message_t *)src->ptr; msp_handle_compass(*pkt); } break; +#endif +#if AP_BARO_MSP_ENABLED case MSP2_SENSOR_BAROMETER: { const MSP::msp_baro_data_message_t *pkt = (const MSP::msp_baro_data_message_t *)src->ptr; msp_handle_baro(*pkt); } break; +#endif +#if AP_AIRSPEED_MSP_ENABLED && AP_AIRSPEED_ENABLED case MSP2_SENSOR_AIRSPEED: { const MSP::msp_airspeed_data_message_t *pkt = (const MSP::msp_airspeed_data_message_t *)src->ptr; msp_handle_airspeed(*pkt); } break; +#endif } return MSP_RESULT_NO_REPLY; } +#if HAL_MSP_OPTICALFLOW_ENABLED void AP_MSP_Telem_Backend::msp_handle_opflow(const MSP::msp_opflow_data_message_t &pkt) { -#if HAL_MSP_OPTICALFLOW_ENABLED AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { return; } optflow->handle_msp(pkt); -#endif } +#endif +#if HAL_MSP_RANGEFINDER_ENABLED void AP_MSP_Telem_Backend::msp_handle_rangefinder(const MSP::msp_rangefinder_data_message_t &pkt) { -#if HAL_MSP_RANGEFINDER_ENABLED RangeFinder *rangefinder = AP::rangefinder(); if (rangefinder == nullptr) { return; } rangefinder->handle_msp(pkt); -#endif } +#endif +#if HAL_MSP_GPS_ENABLED void AP_MSP_Telem_Backend::msp_handle_gps(const MSP::msp_gps_data_message_t &pkt) { -#if HAL_MSP_GPS_ENABLED AP::gps().handle_msp(pkt); -#endif } +#endif +#if AP_COMPASS_MSP_ENABLED void AP_MSP_Telem_Backend::msp_handle_compass(const MSP::msp_compass_data_message_t &pkt) { -#if AP_COMPASS_MSP_ENABLED AP::compass().handle_msp(pkt); -#endif } +#endif +#if AP_BARO_MSP_ENABLED void AP_MSP_Telem_Backend::msp_handle_baro(const MSP::msp_baro_data_message_t &pkt) { -#if AP_BARO_MSP_ENABLED AP::baro().handle_msp(pkt); -#endif } +#endif +#if AP_AIRSPEED_MSP_ENABLED && AP_AIRSPEED_ENABLED void AP_MSP_Telem_Backend::msp_handle_airspeed(const MSP::msp_airspeed_data_message_t &pkt) { -#if AP_AIRSPEED_MSP_ENABLED && AP_AIRSPEED_ENABLED auto *airspeed = AP::airspeed(); if (airspeed) { airspeed->handle_msp(pkt); } -#endif } +#endif uint32_t AP_MSP_Telem_Backend::get_osd_flight_mode_bitmask(void) { @@ -1056,17 +1067,10 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rtc(sbuf_t *dst) #if AP_RC_CHANNEL_ENABLED MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rc(sbuf_t *dst) { -#if AP_RCMAPPER_ENABLED - const RCMapper* rcmap = AP::rcmap(); - if (rcmap == nullptr) { - return MSP_RESULT_ERROR; - } - - // note: rcmap channels start at 1 - float roll = rc().rc_channel(rcmap->roll()-1)->norm_input_dz(); - float pitch = -rc().rc_channel(rcmap->pitch()-1)->norm_input_dz(); - float yaw = rc().rc_channel(rcmap->yaw()-1)->norm_input_dz(); - float throttle = rc().rc_channel(rcmap->throttle()-1)->norm_input_dz(); + float roll = rc().get_roll_channel().norm_input_dz(); + float pitch = -rc().get_pitch_channel().norm_input_dz(); + float yaw = rc().get_yaw_channel().norm_input_dz(); + float throttle = rc().get_throttle_channel().norm_input_dz(); const struct PACKED { uint16_t a; @@ -1083,9 +1087,6 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rc(sbuf_t *dst) sbuf_write_data(dst, &rc, sizeof(rc)); return MSP_RESULT_ACK; -#else - return MSP_RESULT_ERROR; -#endif } #endif // AP_RC_CHANNEL_ENABLED diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.h b/libraries/AP_MSP/AP_MSP_Telem_Backend.h index fccdf487740b0a..96aa176e422d99 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.h +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.h @@ -57,7 +57,7 @@ friend AP_MSP; int32_t lon; uint16_t alt_m; uint16_t speed_cms; - int16_t ground_course_cd; + uint16_t ground_course_dd; } gps_state_t; typedef struct airspeed_state_s { diff --git a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp index bafa921bd0263c..f01bf7b0be40d6 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp @@ -91,7 +91,7 @@ MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_esc_sensor_data(sbuf_t *dst) int16_t highest_temperature = 0; AP_ESC_Telem& telem = AP::esc_telem(); if (!displaying_stats_screen()) { - telem.get_highest_motor_temperature(highest_temperature); + telem.get_highest_temperature(highest_temperature); } else { #if OSD_ENABLED AP_OSD *osd = AP::osd(); diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 2e4d6ba9b5b404..e553ade4d941ab 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -339,14 +339,13 @@ uint16_t get_random16(void) } -#if AP_SIM_ENABLED -// generate a random float between -1 and 1, for use in SITL +// generate a random float between -1 and 1 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; + return (get_random16() / 65535.0) * 2 - 1; #endif } @@ -359,7 +358,6 @@ Vector3f rand_vec3f(void) rand_float() }; } -#endif /* return true if two rotations are equivalent diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index f513565eed6f96..87e2914831f56c 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -20,6 +20,8 @@ #include "location.h" #include "control.h" +static const float NaNf = nanf("0x4152"); + #if HAL_WITH_EKF_DOUBLE typedef Vector2 Vector2F; typedef Vector3 Vector3F; diff --git a/libraries/AP_Math/control.h b/libraries/AP_Math/control.h index 142791c46b9e24..7567decf6b33ed 100644 --- a/libraries/AP_Math/control.h +++ b/libraries/AP_Math/control.h @@ -4,10 +4,6 @@ #include "vector2.h" #include "vector3.h" -#ifndef HAL_WITH_POSTYPE_DOUBLE -#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024 -#endif - #if HAL_WITH_POSTYPE_DOUBLE typedef double postype_t; typedef Vector2d Vector2p; diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index 7317a19906e0b4..c0280b54b9a23b 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -42,6 +42,7 @@ static const double RAD_TO_DEG_DOUBLE = 1 / DEG_TO_RAD_DOUBLE; #endif #define RadiansToCentiDegrees(x) (static_cast(x) * RAD_TO_DEG * static_cast(100)) +#define CentiDegreesToRadians(x) (static_cast(x) * DEG_TO_RAD * 0.01f) // acceleration due to gravity in m/s/s #define GRAVITY_MSS 9.80665f diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index bd64d62a02c8be..ccfcb7bc01d13d 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -21,7 +21,7 @@ #include "AP_Math.h" // create a rotation matrix given some euler angles -// this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf +// this is based on https://github.com/ArduPilot/Datasheets/blob/main/References/EulerAngles.pdf template void Matrix3::from_euler(T roll, T pitch, T yaw) { @@ -44,7 +44,7 @@ void Matrix3::from_euler(T roll, T pitch, T yaw) } // calculate euler angles from a rotation matrix -// this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf +// this is based on https://github.com/ArduPilot/Datasheets/blob/main/References/EulerAngles.pdf template void Matrix3::to_euler(T *roll, T *pitch, T *yaw) const { @@ -227,14 +227,6 @@ bool Matrix3::invert() return success; } -template -void Matrix3::zero(void) -{ - a.x = a.y = a.z = 0; - b.x = b.y = b.z = 0; - c.x = c.y = c.z = 0; -} - // create rotation matrix for rotation about the vector v by angle theta // See: http://www.euclideanspace.com/maths/geometry/rotations/conversions/angleToMatrix/ template diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index 3b2d8ed8c99452..77ed088b8c9758 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -55,18 +55,18 @@ class Matrix3 { // trivial ctor // note that the Vector3 ctor will zero the vector elements - constexpr Matrix3() {} + constexpr Matrix3() {} // setting ctor - constexpr Matrix3(const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) + constexpr Matrix3(const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) : a(a0) , b(b0) , c(c0) {} // setting ctor - constexpr Matrix3(const T ax, const T ay, const T az, - const T bx, const T by, const T bz, - const T cx, const T cy, const T cz) + constexpr Matrix3(const T ax, const T ay, const T az, + const T bx, const T by, const T bz, + const T cx, const T cy, const T cz) : a(ax,ay,az) , b(bx,by,bz) , c(cx,cy,cz) {} @@ -219,14 +219,14 @@ class Matrix3 { bool invert() WARN_IF_UNUSED; // zero the matrix - void zero(void); + void zero(void) { + memset((void*)this, 0, sizeof(*this)); + } // setup the identity matrix void identity(void) { + zero(); a.x = b.y = c.z = 1; - a.y = a.z = 0; - b.x = b.z = 0; - c.x = c.y = 0; } // check if any elements are NAN @@ -235,13 +235,17 @@ class Matrix3 { return a.is_nan() || b.is_nan() || c.is_nan(); } - // create a rotation matrix from Euler angles + /* + create a rotation matrix from Euler angles in 321 euler ordering + */ void from_euler(T roll, T pitch, T yaw); - // create eulers from a rotation matrix. - // roll is from -Pi to Pi - // pitch is from -Pi/2 to Pi/2 - // yaw is from -Pi to Pi + /* create eulers from a rotation matrix. + roll is from -Pi to Pi + pitch is from -Pi/2 to Pi/2 + yaw is from -Pi to Pi + euler order is 321 + */ void to_euler(T *roll, T *pitch, T *yaw) const; // create matrix from rotation enum diff --git a/libraries/AP_Math/matrix_alg.cpp b/libraries/AP_Math/matrix_alg.cpp index cda345b21b8bf0..9b5f76ec08d106 100644 --- a/libraries/AP_Math/matrix_alg.cpp +++ b/libraries/AP_Math/matrix_alg.cpp @@ -35,7 +35,7 @@ template static T* matrix_multiply(const T *A, const T *B, uint16_t n) { - T* ret = new T[n*n]; + T* ret = NEW_NOTHROW T[n*n]; memset(ret,0.0f,n*n*sizeof(T)); for(uint16_t i = 0; i < n; i++) { @@ -194,13 +194,13 @@ static bool mat_inverseN(const T* A, T* inv, uint16_t n) { T *L, *U, *P; bool ret = true; - L = new T[n*n]; - U = new T[n*n]; - P = new T[n*n]; + L = NEW_NOTHROW T[n*n]; + U = NEW_NOTHROW T[n*n]; + P = NEW_NOTHROW T[n*n]; mat_LU_decompose(A,L,U,P,n); - T *L_inv = new T[n*n]; - T *U_inv = new T[n*n]; + T *L_inv = NEW_NOTHROW T[n*n]; + T *U_inv = NEW_NOTHROW T[n*n]; memset(L_inv,0,n*n*sizeof(T)); mat_forward_sub(L,L_inv,n); diff --git a/libraries/AP_Math/polyfit.cpp b/libraries/AP_Math/polyfit.cpp index 3a702671850ff6..88a925070f1b1a 100644 --- a/libraries/AP_Math/polyfit.cpp +++ b/libraries/AP_Math/polyfit.cpp @@ -31,7 +31,7 @@ template bool PolyFit::get_polynomial(vtype res[order]) const { // we dynamically allocate the inverse matrix to keep stack usage low - xtype *inv_mat = new xtype[order*order]; + xtype *inv_mat = NEW_NOTHROW xtype[order*order]; if (inv_mat == nullptr) { return false; } diff --git a/libraries/AP_Math/quaternion.h b/libraries/AP_Math/quaternion.h index 1c47540c678ae8..45b0f612df5747 100644 --- a/libraries/AP_Math/quaternion.h +++ b/libraries/AP_Math/quaternion.h @@ -50,15 +50,6 @@ class QuaternionT { { } - // function call operator - void operator()(const T _q1, const T _q2, const T _q3, const T _q4) - { - q1 = _q1; - q2 = _q2; - q3 = _q3; - q4 = _q4; - } - // check if any elements are NAN bool is_nan(void) const WARN_IF_UNUSED { @@ -81,11 +72,11 @@ class QuaternionT { // convert a vector from earth to body frame void earth_to_body(Vector3 &v) const; - // create a quaternion from Euler angles + // create a quaternion from Euler angles using 321 euler ordering void from_euler(T roll, T pitch, T yaw); void from_euler(const Vector3 &v); - // create a quaternion from Euler angles applied in yaw, roll, pitch order + // create a quaternion from Euler angles applied in yaw, roll, pitch order (312) // instead of the normal yaw, pitch, roll order void from_vector312(T roll, T pitch, T yaw); @@ -129,7 +120,7 @@ class QuaternionT { // get euler yaw angle in radians T get_euler_yaw() const; - // create eulers (in radians) from a quaternion + // create eulers (in radians) from a quaternion, using 321 ordering void to_euler(float &roll, float &pitch, float &yaw) const; void to_euler(Vector3f &rpy) const { to_euler(rpy.x, rpy.y, rpy.z); @@ -139,7 +130,7 @@ class QuaternionT { to_euler(rpy.x, rpy.y, rpy.z); } - // create eulers from a quaternion + // create eulers from a quaternion with 312 ordering Vector3 to_vector312(void) const; T length_squared(void) const; diff --git a/libraries/AP_Math/tests/test_math.cpp b/libraries/AP_Math/tests/test_math.cpp index afd8a164c829f3..de3f3a53a6171b 100644 --- a/libraries/AP_Math/tests/test_math.cpp +++ b/libraries/AP_Math/tests/test_math.cpp @@ -654,6 +654,23 @@ TEST(MathTest, RANDOM16) EXPECT_NE(random_value, get_random16()); } +TEST(MathTest, RAND_FLOAT) +{ + // bodgy range checks + float lowest_value = 0; + float highest_value = 0; + for (auto i=0; i<1000; i++) { + const auto value = rand_float(); + lowest_value = MIN(lowest_value, value); + highest_value = MAX(highest_value, value); + } + EXPECT_NEAR(-0.95, lowest_value, 0.05); + EXPECT_NEAR(0.95, highest_value, 0.05); + EXPECT_GE(lowest_value, -1.0); + EXPECT_LE(highest_value, 1.0); + +} + TEST(MathTest, VELCORRECTION) { static constexpr Vector3F pos{1.0f, 1.0f, 0.0f}; diff --git a/libraries/AP_Math/tests/test_rotations.cpp b/libraries/AP_Math/tests/test_rotations.cpp index 15fdfa6238055a..d9de8f82e59dfe 100644 --- a/libraries/AP_Math/tests/test_rotations.cpp +++ b/libraries/AP_Math/tests/test_rotations.cpp @@ -189,5 +189,83 @@ TEST(RotationsTest, TestFailedGetLinux) } }*/ +/* + rotate a matrix using a give order, specified as a string + for example "321" + */ +static void rotate_ordered(Matrix3f &m, const char *order, + const float roll_deg, + const float pitch_deg, + const float yaw_deg) +{ + while (*order) { + Matrix3f m2; + switch (*order) { + case '1': + m2.from_euler(radians(roll_deg), 0, 0); + break; + case '2': + m2.from_euler(0, radians(pitch_deg), 0); + break; + case '3': + m2.from_euler(0, 0, radians(yaw_deg)); + break; + } + m *= m2; + order++; + } +} + +/* + test the two euler orders we use in ArduPilot + */ +TEST(RotationsTest, TestEulerOrder) +{ + const float roll_deg = 20; + const float pitch_deg = 31; + const float yaw_deg = 72; + float r, p, y; + Vector3f v; + + Matrix3f m; + + // apply in 321 ordering + m.identity(); + rotate_ordered(m, "321", roll_deg, pitch_deg, yaw_deg); + + // get using to_euler + m.to_euler(&r, &p, &y); + + EXPECT_FLOAT_EQ(degrees(r), roll_deg); + EXPECT_FLOAT_EQ(degrees(p), pitch_deg); + EXPECT_FLOAT_EQ(degrees(y), yaw_deg); + + // get using to_euler312, should not match + v = m.to_euler312(); + + EXPECT_GE(fabsf(degrees(v.x)-roll_deg), 1); + EXPECT_GE(fabsf(degrees(v.y)-pitch_deg), 1); + EXPECT_GE(fabsf(degrees(v.z)-yaw_deg), 1); + + // apply in 312 ordering + m.identity(); + rotate_ordered(m, "312", roll_deg, pitch_deg, yaw_deg); + + // get using to_euler312 + v = m.to_euler312(); + + EXPECT_FLOAT_EQ(degrees(v.x), roll_deg); + EXPECT_FLOAT_EQ(degrees(v.y), pitch_deg); + EXPECT_FLOAT_EQ(degrees(v.z), yaw_deg); + + // get using to_euler, should not match + m.to_euler(&r, &p, &y); + + EXPECT_GE(fabsf(degrees(r)-roll_deg), 1); + EXPECT_GE(fabsf(degrees(p)-pitch_deg), 1); + EXPECT_GE(fabsf(degrees(y)-yaw_deg), 1); +} + + AP_GTEST_PANIC() AP_GTEST_MAIN() diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index 0204e8d3af9d18..149bcd08e04752 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -241,7 +241,7 @@ bool Vector2::circle_segment_intersection(const Vector2& seg_start, const // -> o o -> | -> | // FallShort (t1>1,t2>1), Past (t1<0,t2<0), CompletelyInside(t1<0, t2>1) - // intersection = new Vector3(E.x + t1 * d.x, secondPoint.y, E.y + t1 * d.y); + // intersection = NEW_NOTHROW Vector3(E.x + t1 * d.x, secondPoint.y, E.y + t1 * d.y); // intersection.x = seg_start.x + t1 * seg_end_minus_start.x; // intersection.y = seg_start.y + t1 * seg_end_minus_start.y; diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index ae43ee847ae746..8c74b61a5faad4 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -47,12 +47,12 @@ struct Vector2 T x, y; // trivial ctor - constexpr Vector2() + constexpr Vector2() : x(0) , y(0) {} // setting ctor - constexpr Vector2(const T x0, const T y0) + constexpr Vector2(const T x0, const T y0) : x(x0) , y(y0) {} diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index 021b737a013158..3c763008eeec2a 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -429,7 +429,7 @@ T Vector3::angle(const Vector3 &v2) const return 0.0f; } const T cosv = ((*this)*v2) / len; - if (fabsF(cosv) >= 1) { + if (cosv >= 1 || cosv <= -1) { return 0.0f; } return acosF(cosv); diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index d4d3a1baa63cb2..6a9b0bc23b5b89 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -76,19 +76,19 @@ class Vector3 T x, y, z; // trivial ctor - constexpr Vector3() + constexpr Vector3() : x(0) , y(0) , z(0) {} // setting ctor - constexpr Vector3(const T x0, const T y0, const T z0) + constexpr Vector3(const T x0, const T y0, const T z0) : x(x0) , y(y0) , z(z0) {} //Create a Vector3 from a Vector2 with z - constexpr Vector3(const Vector2 &v0, const T z0) + constexpr Vector3(const Vector2 &v0, const T z0) : x(v0.x) , y(v0.y) , z(z0) {} diff --git a/libraries/AP_Math/vectorN.h b/libraries/AP_Math/vectorN.h index 1a78e7f36a2598..56a0da07f082c2 100644 --- a/libraries/AP_Math/vectorN.h +++ b/libraries/AP_Math/vectorN.h @@ -35,14 +35,14 @@ class VectorN { public: // trivial ctor - inline VectorN() { + inline VectorN() { for (auto i = 0; i < N; i++) { _v[i] = T{}; } } // vector ctor - inline VectorN(const T *v) { + inline VectorN(const T *v) { memcpy(_v, v, sizeof(T)*N); } diff --git a/libraries/AP_Menu/AP_Menu.cpp b/libraries/AP_Menu/AP_Menu.cpp index 647b4eea60d7ee..5ce3dac8250e31 100644 --- a/libraries/AP_Menu/AP_Menu.cpp +++ b/libraries/AP_Menu/AP_Menu.cpp @@ -261,11 +261,11 @@ Menu::_allocate_buffers(void) { /* only allocate if the buffers are nullptr */ if (_inbuf == nullptr) { - _inbuf = new char[_commandline_max]; + _inbuf = NEW_NOTHROW char[_commandline_max]; memset(_inbuf, 0, _commandline_max); } if (_argv == nullptr) { - _argv = new arg[_args_max+1]; + _argv = NEW_NOTHROW arg[_args_max+1]; memset(_argv, 0, (_args_max+1) * sizeof(_argv[0])); } } diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 4f9f07ad1c239c..d27beca79e9ca2 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -16,6 +16,8 @@ #include #include #include +#include +#include const AP_Param::GroupInfo AP_Mission::var_info[] = { @@ -94,7 +96,7 @@ void AP_Mission::init() 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) { + if (option_is_set(Option::CLEAR_ON_BOOT)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Clearing Mission"); clear(); } @@ -261,6 +263,7 @@ void AP_Mission::reset() _flags.do_cmd_loaded = false; _flags.do_cmd_all_done = false; _flags.in_landing_sequence = false; + _flags.in_return_path = false; _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE; _do_cmd.index = AP_MISSION_CMD_INDEX_NONE; _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE; @@ -398,17 +401,40 @@ bool AP_Mission::verify_command(const Mission_Command& cmd) bool AP_Mission::start_command(const Mission_Command& cmd) { - // check for landing related commands and set in_landing_sequence flag +#if HAL_LOGGING_ENABLED + if (log_start_mission_item_bit != (uint32_t)-1) { + auto &logger = AP::logger(); + if (logger.should_log(log_start_mission_item_bit)) { + logger.Write_MISE(*this, cmd); + } + } +#endif + + // check for landing related commands and set flags if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) { - set_in_landing_sequence_flag(true); + _flags.in_landing_sequence = true; + + } else if (cmd.id == MAV_CMD_DO_RETURN_PATH_START) { + _flags.in_return_path = true; + } else if (is_takeoff_type_cmd(cmd.id)) { - set_in_landing_sequence_flag(false); + // Clear landing and return path flags on takeoff + _flags.in_landing_sequence = false; + _flags.in_return_path = false; + } - if (cmd.id == MAV_CMD_DO_JUMP || cmd.id == MAV_CMD_JUMP_TAG || cmd.id == MAV_CMD_DO_JUMP_TAG) { + switch (cmd.id) { + case MAV_CMD_DO_JUMP: + case MAV_CMD_JUMP_TAG: + case MAV_CMD_DO_JUMP_TAG: GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u %s %u", cmd.index, cmd.type(), (unsigned)cmd.p1); - } else { + break; + + default: GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type()); + break; + } switch (cmd.id) { @@ -439,6 +465,10 @@ bool AP_Mission::start_command(const Mission_Command& cmd) case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE: return start_command_camera(cmd); +#endif +#if AP_FENCE_ENABLED + case MAV_CMD_DO_FENCE_ENABLE: + return start_command_fence(cmd); #endif case MAV_CMD_DO_PARACHUTE: return start_command_parachute(cmd); @@ -537,23 +567,44 @@ int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle) return default_angle; } // special handling for nav commands with no target location - if (cmd.id == MAV_CMD_NAV_GUIDED_ENABLE || - cmd.id == MAV_CMD_NAV_DELAY) { + switch (cmd.id) { + case MAV_CMD_NAV_GUIDED_ENABLE: + case MAV_CMD_NAV_DELAY: return default_angle; - } - if (cmd.id == MAV_CMD_NAV_SET_YAW_SPEED) { + + case MAV_CMD_NAV_SET_YAW_SPEED: return (_nav_cmd.content.set_yaw_speed.angle_deg * 100); + + default: + break; } + return _nav_cmd.content.location.get_bearing_to(cmd.content.location); } // set_current_cmd - jumps to command specified by index bool AP_Mission::set_current_cmd(uint16_t index) { - // read command to check for DO_LAND_START + // Clear flags + _flags.in_landing_sequence = false; + _flags.in_return_path = false; + + // read command to check for DO_LAND_START and DO_RETURN_PATH_START Mission_Command cmd; - if (!read_cmd_from_storage(index, cmd) || (cmd.id != MAV_CMD_DO_LAND_START)) { - _flags.in_landing_sequence = false; + if (read_cmd_from_storage(index, cmd)) { + switch (cmd.id) { + case MAV_CMD_DO_LAND_START: + _flags.in_landing_sequence = true; + break; + + case MAV_CMD_DO_RETURN_PATH_START: + _flags.in_return_path = true; + break; + + default: + break; + + } } // mission command has been set, don't track history. @@ -678,46 +729,42 @@ bool AP_Mission::set_item(uint16_t index, mavlink_mission_item_int_t& src_packet bool AP_Mission::get_item(uint16_t index, mavlink_mission_item_int_t& ret_packet) const { - // setting ret_packet.command = -1 and/or returning false - // means it contains invalid data after it leaves here. - - // this is the on-storage format - AP_Mission::Mission_Command cmd {}; + mavlink_mission_item_int_t tmp; // can't handle request for anything bigger than the mission size... if (index >= num_commands()) { - ret_packet.command = -1; return false; } // minimal placeholder values during read-from-storage - ret_packet.target_system = 1; // unused sysid - ret_packet.target_component = 1; // unused compid + tmp.target_system = 1; // unused sysid + tmp.target_component = 1; // unused compid // 0=home, higher number/s = mission item number. - ret_packet.seq = index; + tmp.seq = index; // retrieve mission from eeprom - if (!read_cmd_from_storage(ret_packet.seq, cmd)) { - ret_packet.command = -1; + AP_Mission::Mission_Command cmd {}; + if (!read_cmd_from_storage(tmp.seq, cmd)) { return false; } // convert into mavlink-ish format for lua and friends. - if (!mission_cmd_to_mavlink_int(cmd, ret_packet)) { - ret_packet.command = -1; + if (!mission_cmd_to_mavlink_int(cmd, tmp)) { return false; } // set packet's current field to 1 if this is the command being executed if (cmd.id == (uint16_t)get_current_nav_cmd().index) { - ret_packet.current = 1; + tmp.current = 1; } else { - ret_packet.current = 0; + tmp.current = 0; } // set auto continue to 1, becasue that's what's done elsewhere. - ret_packet.autocontinue = 1; // 1 (true), 0 (false) - ret_packet.command = cmd.id; + tmp.autocontinue = 1; // 1 (true), 0 (false) + tmp.command = cmd.id; + + ret_packet = tmp; return true; } @@ -853,6 +900,7 @@ bool AP_Mission::stored_in_location(uint16_t id) case MAV_CMD_NAV_SPLINE_WAYPOINT: case MAV_CMD_NAV_GUIDED_ENABLE: case MAV_CMD_DO_SET_HOME: + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: case MAV_CMD_DO_GO_AROUND: case MAV_CMD_DO_SET_ROI: @@ -945,6 +993,9 @@ MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_in case MAV_CMD_NAV_WAYPOINT: nan_mask = ~(1 << 3); // param 4 can be nan break; + case MAV_CMD_NAV_LOITER_UNLIM: + nan_mask = ~(1 << 3); // param 4 can be nan + break; case MAV_CMD_NAV_LAND: nan_mask = ~(1 << 3); // param 4 can be nan break; @@ -1169,6 +1220,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ cmd.content.repeat_servo.cycle_time = packet.param4; // time in seconds break; + case MAV_CMD_DO_RETURN_PATH_START: // MAV ID: 188 case MAV_CMD_DO_LAND_START: // MAV ID: 189 break; @@ -1199,6 +1251,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ break; case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205 + // TODO: this is only valid if packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING cmd.content.mount_control.pitch = packet.param1; cmd.content.mount_control.roll = packet.param2; cmd.content.mount_control.yaw = packet.param3; @@ -1210,7 +1263,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ break; case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207 - cmd.p1 = packet.param1; // action 0=disable, 1=enable + cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=disable floor break; case MAV_CMD_DO_AUX_FUNCTION: @@ -1681,6 +1734,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param4 = cmd.content.repeat_servo.cycle_time; // time in milliseconds converted to seconds break; + case MAV_CMD_DO_RETURN_PATH_START: // MAV ID: 188 case MAV_CMD_DO_LAND_START: // MAV ID: 189 break; @@ -1714,6 +1768,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param1 = cmd.content.mount_control.pitch; packet.param2 = cmd.content.mount_control.roll; packet.param3 = cmd.content.mount_control.yaw; + packet.z = MAV_MOUNT_MODE_MAVLINK_TARGETING; break; case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206 @@ -1722,7 +1777,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c break; case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207 - packet.param1 = cmd.p1; // action 0=disable, 1=enable + packet.param1 = cmd.p1; // action 0=disable, 1=enable, 2=disable floor, 3=enable except floor break; case MAV_CMD_DO_PARACHUTE: // MAV ID: 208 @@ -1792,7 +1847,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c #if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED case MAV_CMD_NAV_PAYLOAD_PLACE: - packet.param1 = cmd.p1/100.0f; // copy max-descend parameter (cm->m) + packet.param1 = cmd.p1*0.01f; // copy max-descend parameter (cm->m) break; #endif @@ -1940,6 +1995,7 @@ void AP_Mission::complete() // flag mission as complete _flags.state = MISSION_COMPLETE; _flags.in_landing_sequence = false; + _flags.in_return_path = false; // callback to main program's mission complete function _mission_complete_fn(); @@ -2131,24 +2187,18 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i jump_index = cmd_index; } - // check if jump command is 'repeat forever' - if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) { + // get number of times jump command has already been run + if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER || + get_jump_times_run(temp_cmd) < temp_cmd.content.jump.num_times) { + // update the record of the number of times run + if (increment_jump_num_times_if_found && !_flags.resuming_mission) { + increment_jump_times_run(temp_cmd, send_gcs_msg); + } // continue searching from jump target cmd_index = temp_cmd.content.jump.target; } else { - // get number of times jump command has already been run - int16_t jump_times_run = get_jump_times_run(temp_cmd); - if (jump_times_run < temp_cmd.content.jump.num_times) { - // update the record of the number of times run - if (increment_jump_num_times_if_found && !_flags.resuming_mission) { - increment_jump_times_run(temp_cmd, send_gcs_msg); - } - // continue searching from jump target - cmd_index = temp_cmd.content.jump.target; - } else { - // jump has been run specified number of times so move search to next command in mission - cmd_index++; - } + // jump has been run specified number of times so move search to next command in mission + cmd_index++; } } else { // this is a non-jump command so return it @@ -2284,7 +2334,11 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd, bool send_gcs_ms if (_jump_tracking[i].index == cmd.index) { _jump_tracking[i].num_times_run++; if (send_gcs_msg) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times); + if (cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/unlimited", _jump_tracking[i].index, _jump_tracking[i].num_times_run); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times); + } } return; } else if (_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) { @@ -2319,7 +2373,6 @@ void AP_Mission::check_eeprom_version() // be found. uint16_t AP_Mission::get_landing_sequence_start(const Location ¤t_loc) { - const Location::AltFrame current_loc_alt_frame = current_loc.get_alt_frame(); uint16_t landing_start_index = 0; float min_distance = -1; @@ -2339,15 +2392,7 @@ uint16_t AP_Mission::get_landing_sequence_start(const Location ¤t_loc) continue; } - float tmp_distance; - if (current_loc_alt_frame == tmp.content.location.get_alt_frame() || tmp.content.location.change_alt_frame(current_loc_alt_frame)) { - // 3D distance - altitudes are able to be compared in the same frame - tmp_distance = tmp.content.location.get_distance_NED(current_loc).length(); - } else { - // 2D distance - no altitude - tmp_distance = tmp.content.location.get_distance(current_loc); - } - + const float tmp_distance = tmp.content.location.get_distance_NED_alt_frame(current_loc).length(); if (min_distance < 0 || tmp_distance < min_distance) { min_distance = tmp_distance; landing_start_index = i; @@ -2374,7 +2419,6 @@ bool AP_Mission::jump_to_landing_sequence(const Location ¤t_loc) } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing sequence start"); - _flags.in_landing_sequence = true; return true; } @@ -2382,6 +2426,61 @@ bool AP_Mission::jump_to_landing_sequence(const Location ¤t_loc) return false; } +/* + find the closest point on the mission after a DO_RETURN_PATH_START and before DO_LAND_START or landing + */ +bool AP_Mission::jump_to_closest_mission_leg(const Location ¤t_loc) +{ + if (_flags.state == MISSION_RUNNING) { + // if mission is already running don't switch away from a active landing or return path + if (_flags.in_landing_sequence) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing sequence active"); + return true; + + } else if (_flags.in_return_path) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Return path active"); + return true; + } + } + + uint16_t landing_start_index = 0; + float min_distance = -1; + + // This defines the maximum number of waypoints that will be searched, this limits the worst case runtime + uint16_t search_remaining = 1000; + + // Go through mission and check each DO_RETURN_PATH_START + for (uint16_t i = 1; i < num_commands(); i++) { + if (get_command_id(i) == uint16_t(MAV_CMD_DO_RETURN_PATH_START)) { + uint16_t tmp_index; + float tmp_distance; + if (distance_to_mission_leg(i, search_remaining, tmp_distance, tmp_index, current_loc) && (min_distance < 0 || tmp_distance <= min_distance)){ + min_distance = tmp_distance; + landing_start_index = tmp_index; + } + if (search_remaining == 0) { + // Run out of time to search, stop and return the best so far + break; + } + } + } + + if (landing_start_index != 0 && set_current_cmd(landing_start_index)) { + + // if the mission has ended it has to be restarted + if (state() == AP_Mission::MISSION_STOPPED) { + resume(); + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Return path started"); + _flags.in_return_path = true; + return true; + } + + // Failed to find do land start + return false; +} + // jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort bool AP_Mission::jump_to_abort_landing_sequence(const Location ¤t_loc) { @@ -2413,8 +2512,6 @@ bool AP_Mission::jump_to_abort_landing_sequence(const Location ¤t_loc) resume(); } - _flags.in_landing_sequence = false; - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing abort sequence start"); return true; } @@ -2437,7 +2534,7 @@ bool AP_Mission::is_best_land_sequence(const Location ¤t_loc) } // check if MIS_OPTIONS bit set to allow distance calculation to be done - if (!(_options & AP_MISSION_MASK_DIST_TO_LAND_CALC)) { + if (!option_is_set(Option::FAILSAFE_TO_BEST_LANDING)) { return false; } @@ -2492,7 +2589,7 @@ bool AP_Mission::distance_to_landing(uint16_t index, float &tot_distance, Locati } // run through remainder of mission to approximate a distance to landing - for (uint8_t i=0; i<255; i++) { + for (uint8_t i=0; i 0; search_remaining--) { + // search until the end of the mission command list + for (uint16_t cmd_index = index; cmd_index <= (unsigned)_cmd_total; cmd_index++) { + if (get_next_cmd(cmd_index, temp_cmd, true, false)) { + break; + } else { + // got to the end of the mission + goto reset_do_jump_tracking; + } + } + index = temp_cmd.index + 1; + + if (stored_in_location(temp_cmd.id) && temp_cmd.content.location.initialised()) { + if (prev_loc.lat == 0 && prev_loc.lng == 0) { + // Need a valid previous location to do distance to leg calculation + prev_loc = temp_cmd.content.location; + + // single point dist calc + rejoin_distance = prev_loc.get_distance_NED_alt_frame(current_loc).length(); + rejoin_index = temp_cmd.index; + ret = true; + + } else { + // Calculate the distance to rejoin + const Vector3f mission_vector = prev_loc.get_distance_NED_alt_frame(temp_cmd.content.location); + if (!mission_vector.is_zero()) { + Vector3f pos = prev_loc.get_distance_NED_alt_frame(current_loc); + + // project pos vector on to mission vector + Vector3f p = pos.projected(mission_vector); + + // constrain to mission line + p.x = constrain_float(p.x, MIN(0,mission_vector.x), MAX(0,mission_vector.x)); + p.y = constrain_float(p.y, MIN(0,mission_vector.y), MAX(0,mission_vector.y)); + p.z = constrain_float(p.z, MIN(0,mission_vector.z), MAX(0,mission_vector.z)); + + const float disttemp = (p - pos).length(); + + // store wp location as previous + prev_loc = temp_cmd.content.location; + + if (disttemp < rejoin_distance || is_negative(rejoin_distance)) { + rejoin_distance = disttemp; + rejoin_index = temp_cmd.index; + } + ret = true; + } + } + } + + if (is_landing_type_cmd(temp_cmd.id) || (temp_cmd.id == MAV_CMD_DO_LAND_START)) { + // reached a landing! + goto reset_do_jump_tracking; + } + } + // reached end of loop without getting to a landing or DO_LAND_START + ret = false; + +reset_do_jump_tracking: + for (uint8_t i=0; i #include #include +#include #if AP_RC_CHANNEL_ENABLED bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command& cmd) @@ -329,8 +330,8 @@ bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Miss } // 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); + const bool pitch_angle_valid = abs(cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg) <= 90; + const bool yaw_angle_valid = abs(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; @@ -347,4 +348,30 @@ bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Miss return false; } +bool AP_Mission::start_command_fence(const AP_Mission::Mission_Command& cmd) +{ +#if AP_FENCE_ENABLED + AC_Fence* fence = AP::fence(); + + if (fence == nullptr) { + return false; + } + + if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::DISABLE_FENCE)) { // disable fence + uint8_t fences = fence->enable_configured(false); + fence->print_fence_message("disabled", fences); + return true; + } else if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::ENABLE_FENCE)) { // enable fence + uint8_t fences = fence->enable_configured(true); + fence->print_fence_message("enabled", fences); + return true; + } else if (cmd.p1 == uint8_t(AC_Fence::MavlinkFenceActions::DISABLE_ALT_MIN_FENCE)) { // disable fence floor only + fence->disable_floor(); + fence->print_fence_message("disabled", AC_FENCE_TYPE_ALT_MIN); + return true; + } +#endif // AP_FENCE_ENABLED + return false; +} + #endif // AP_MISSION_ENABLED diff --git a/libraries/AP_Mission/LogStructure.h b/libraries/AP_Mission/LogStructure.h new file mode 100644 index 00000000000000..98b0f942fac33f --- /dev/null +++ b/libraries/AP_Mission/LogStructure.h @@ -0,0 +1,59 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_MISSION \ + LOG_MISE_MSG, \ + LOG_CMD_MSG + +// @LoggerMessage: CMD +// @Description: Uploaded mission command information +// @Field: TimeUS: Time since system startup +// @Field: CTot: Total number of mission commands +// @Field: CNum: This command's offset in mission +// @Field: CId: Command type +// @Field: Prm1: Parameter 1 +// @Field: Prm2: Parameter 2 +// @Field: Prm3: Parameter 3 +// @Field: Prm4: Parameter 4 +// @Field: Lat: Command latitude +// @Field: Lng: Command longitude +// @Field: Alt: Command altitude +// @Field: Frame: Frame used for position +struct PACKED log_CMD { + LOG_PACKET_HEADER; + uint64_t time_us; + uint16_t command_total; + uint16_t sequence; + uint16_t command; + float param1; + float param2; + float param3; + float param4; + int32_t latitude; + int32_t longitude; + float altitude; + uint8_t frame; +}; + +// @LoggerMessage: MISE +// @Description: Executed mission command information; emitted when we start to run an item +// @Field: TimeUS: Time since system startup +// @Field: CTot: Total number of mission commands +// @Field: CNum: This command's offset in mission +// @Field: CId: Command type +// @Field: Prm1: Parameter 1 +// @Field: Prm2: Parameter 2 +// @Field: Prm3: Parameter 3 +// @Field: Prm4: Parameter 4 +// @Field: Lat: Command latitude +// @Field: Lng: Command longitude +// @Field: Alt: Command altitude +// @Field: Frame: Frame used for position + +// note we currently reuse the same structure for CMD and MISE. +#define LOG_STRUCTURE_FROM_MISSION \ + { LOG_CMD_MSG, sizeof(log_CMD), \ + "CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \ + { LOG_MISE_MSG, sizeof(log_CMD), \ + "MISE", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, diff --git a/libraries/AP_Module/AP_Module.cpp b/libraries/AP_Module/AP_Module.cpp index 3bad1d59ef852c..7e6c5ce6a236d5 100644 --- a/libraries/AP_Module/AP_Module.cpp +++ b/libraries/AP_Module/AP_Module.cpp @@ -17,6 +17,8 @@ #if AP_MODULE_SUPPORTED +#include + /* support for external modules */ @@ -55,7 +57,7 @@ void AP_Module::module_scan(const char *path) void *s = dlsym(m, hook_names[i]); if (s != nullptr) { // found a hook in this module, add it to the list - struct hook_list *h = new hook_list; + struct hook_list *h = NEW_NOTHROW hook_list; if (h == nullptr) { AP_HAL::panic("Failed to allocate hook for %s", hook_names[i]); } diff --git a/libraries/AP_Module/AP_Module.h b/libraries/AP_Module/AP_Module.h index 768413f4c5620b..e80d8ccacaac21 100644 --- a/libraries/AP_Module/AP_Module.h +++ b/libraries/AP_Module/AP_Module.h @@ -29,7 +29,7 @@ #if AP_MODULE_SUPPORTED -#include +#include #ifndef AP_MODULE_DEFAULT_DIRECTORY #define AP_MODULE_DEFAULT_DIRECTORY "/usr/lib/ardupilot/modules" @@ -48,7 +48,7 @@ class AP_Module { static void call_hook_setup_complete(void); // call any AHRS_update hooks - static void call_hook_AHRS_update(const AP_AHRS &ahrs); + static void call_hook_AHRS_update(const class AP_AHRS &ahrs); // call any gyro_sample hooks static void call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f &gyro); diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 3d22635b8a1a71..cdb9685dc466fb 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -224,27 +224,17 @@ void AP_MotorsCoax::_output_test_seq(uint8_t motor_seq, int16_t pwm) switch (motor_seq) { case 1: // flap servo 1 - rc_write(AP_MOTORS_MOT_1, pwm); - break; case 2: // flap servo 2 - rc_write(AP_MOTORS_MOT_2, pwm); - break; case 3: // flap servo 3 - rc_write(AP_MOTORS_MOT_3, pwm); - break; case 4: // flap servo 4 - rc_write(AP_MOTORS_MOT_4, pwm); - break; case 5: // motor 1 - rc_write(AP_MOTORS_MOT_5, pwm); - break; case 6: // motor 2 - rc_write(AP_MOTORS_MOT_6, pwm); + rc_write(motor_seq - 1u, pwm); break; default: // do nothing diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index bc9d5c05ae00b1..506e4af32073bc 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -18,6 +18,7 @@ #include "AP_MotorsHeli.h" #include #include +#include extern const AP_HAL::HAL& hal; @@ -147,6 +148,10 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = { // @User: Standard AP_GROUPINFO("COL_LAND_MIN", 32, AP_MotorsHeli, _collective_land_min_deg, AP_MOTORS_HELI_COLLECTIVE_LAND_MIN), + // @Group: RSC_AROT_ + // @Path: ../AC_Autorotation/RSC_Autorotation.cpp + AP_SUBGROUPINFO(_main_rotor.autorotation, "RSC_AROT_", 33, AP_MotorsHeli, RSC_Autorotation), + AP_GROUPEND }; @@ -554,6 +559,10 @@ bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const return false; } + if (!_main_rotor.autorotation.arming_checks(buflen, buffer)) { + return false; + } + return true; } @@ -606,9 +615,36 @@ void AP_MotorsHeli::set_rotor_runup_complete(bool new_value) #if HAL_LOGGING_ENABLED if (!_heliflags.rotor_runup_complete && new_value) { LOGGER_WRITE_EVENT(LogEvent::ROTOR_RUNUP_COMPLETE); - } else if (_heliflags.rotor_runup_complete && !new_value && !_heliflags.in_autorotation) { + } else if (_heliflags.rotor_runup_complete && !new_value && !_main_rotor.in_autorotation()) { LOGGER_WRITE_EVENT(LogEvent::ROTOR_SPEED_BELOW_CRITICAL); } #endif _heliflags.rotor_runup_complete = new_value; } + +#if HAL_LOGGING_ENABLED +// Returns the scaling value required to convert the collective angle parameters into the cyclic-output-to-angle conversion +float AP_MotorsHeli::get_cyclic_angle_scaler(void) const { + // We want to use the collective min-max to angle relationship to calculate the cyclic input to angle relationship + // First we scale the collective angle range by it's min-max output. Recall that we assume that the maximum possible + // collective range is 1000, hence the *1e-3. + // The factor 2.0 accounts for the fact that we scale the servo outputs from 0 ~ 1 to -1 ~ 1 + return ((float)(_collective_max-_collective_min))*1e-3 * (_collective_max_deg.get() - _collective_min_deg.get()) * 2.0; +} +#endif + +// Helper function for param conversions to be done in motors class +void AP_MotorsHeli::heli_motors_param_conversions(void) +{ + // PARAMETER_CONVERSION - Added: Sep-2024 + // move autorotation related parameters within the RSC into their own class + const AP_Param::ConversionInfo rsc_arot_conversion_info[] = { + { 90, 108096, AP_PARAM_INT8, "H_RSC_AROT_ENBL" }, + { 90, 104000, AP_PARAM_INT8, "H_RSC_AROT_RAMP" }, + { 90, 112192, AP_PARAM_INT16, "H_RSC_AROT_IDLE" }, + }; + uint8_t table_size = ARRAY_SIZE(rsc_arot_conversion_info); + for (uint8_t i=0; i #include "AP_MotorsHeli_RSC.h" #include +#include + +// default main rotor speed (ch8 out) as a number from 0 ~ 100 +#define AP_MOTORS_HELI_RSC_SETPOINT 70 + +// default main rotor critical speed +#define AP_MOTORS_HELI_RSC_CRITICAL 50 + +// RSC output defaults +#define AP_MOTORS_HELI_RSC_IDLE_DEFAULT 0 + +// default main rotor ramp up time in seconds +#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to setpoint +#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed + +// Throttle Curve Defaults +#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25 +#define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT 32 +#define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT 38 +#define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT 50 +#define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT 100 + +// RSC governor defaults +#define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100 + extern const AP_HAL::HAL& hal; @@ -193,30 +218,11 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = { // @User: Standard AP_GROUPINFO("GOV_TORQUE", 24, AP_MotorsHeli_RSC, _governor_torque, 30), - // @Param: AROT_ENG_T - // @DisplayName: Time for in-flight power re-engagement - // @Description: amount of seconds to move throttle output from idle to throttle curve position during manual autorotations - // @Range: 0 10 - // @Units: % - // @Increment: 0.5 - // @User: Standard - AP_GROUPINFO("AROT_ENG_T", 25, AP_MotorsHeli_RSC, _rsc_arot_engage_time, AP_MOTORS_HELI_RSC_AROT_ENGAGE_TIME), + // 25 was AROT_ENG_T, has been moved to AROT_RAMP in RSC autorotation sub group - // @Param: AROT_MN_EN - // @DisplayName: Enable Manual Autorotations - // @Description: Allows you to enable (1) or disable (0) the manual autorotation capability. - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("AROT_MN_EN", 26, AP_MotorsHeli_RSC, _rsc_arot_man_enable, 0), + // 26 was AROT_MN_EN, moved to H_RSC_AROT_ENBL in RSC autorotation sub group - // @Param: AROT_IDLE - // @DisplayName: Idle Throttle Percentage during Autorotation - // @Description: Idle throttle used for all RSC modes. For external governors, this would be set to signal it to enable fast spool-up, when bailing out of an autorotation. Set 0 to disable. If also using a tail rotor of type DDVP with external governor then this value must lie within the autorotation window of both governors. - // @Range: 0 40 - // @Units: % - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("AROT_IDLE", 27, AP_MotorsHeli_RSC, _arot_idle_output, AP_MOTORS_HELI_RSC_AROT_IDLE), + // 27 was AROT_IDLE, moved to RSC autorotation sub group AP_GROUPEND }; @@ -246,6 +252,8 @@ void AP_MotorsHeli_RSC::set_throttle_curve() // output - update value to send to ESC/Servo void AP_MotorsHeli_RSC::output(RotorControlState state) { + // Store rsc state for logging + _rsc_state = state; // _rotor_RPM available to the RSC output #if AP_RPM_ENABLED const AP_RPM *rpm = AP_RPM::get_singleton(); @@ -288,12 +296,16 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) _governor_fault = false; //turbine start flag on _starting = true; - _autorotating = false; - _bailing_out = false; - _gov_bailing_out = false; + + // ensure we always deactivate the autorotation state if we disarm + autorotation.set_active(false, true); // ensure _idle_throttle not set to invalid value _idle_throttle = get_idle_output(); + + // reset fast idle timer + _fast_idle_timer = 0.0; + break; case RotorControlState::IDLE: @@ -304,47 +316,36 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) governor_reset(); _autothrottle = false; _governor_fault = false; - if (_in_autorotation) { - // if in autorotation, set the output to idle for autorotation. This will tell an external governor to use fast ramp for spool up. - // if autorotation idle is set to zero then default to the RSC idle value. - if (_arot_idle_output == 0) { + + // turbine start sequence + if (_turbine_start && _starting == true ) { + _idle_throttle += 0.001f; + if (_control_output >= 1.0f) { _idle_throttle = get_idle_output(); - } else { - _idle_throttle = constrain_float( get_arot_idle_output(), 0.0f, 0.4f); - } - if (!_autorotating) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation"); - _autorotating =true; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Turbine startup"); + _starting = false; } - } else { - if (_autorotating) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation Stopped"); - _autorotating =false; - } - // set rotor control speed to idle speed parameter, this happens instantly and ignores ramping - if (_turbine_start && _starting == true ) { - _idle_throttle += 0.001f; - if (_control_output >= 1.0f) { - _idle_throttle = get_idle_output(); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Turbine startup"); - _starting = false; - } - } else { - if (_cooldown_time > 0) { - _idle_throttle = get_idle_output() * 1.5f; - _fast_idle_timer += dt; - if (_fast_idle_timer > (float)_cooldown_time) { - _fast_idle_timer = 0.0f; - } - } else { - _idle_throttle = get_idle_output(); - } - } - // this resets the bailout feature if the aircraft has landed. - _use_bailout_ramp = false; - _bailing_out = false; - _gov_bailing_out = false; + _control_output = _idle_throttle; + break; } + + // all other idle throttle functions below this require idle throttle to be reset to H_RSC_IDLE on each call + _idle_throttle = get_idle_output(); + + // check if we need to use autorotation idle throttle + if (autorotation.get_idle_throttle(_idle_throttle)) { + // if we are here then we are autorotating + _control_output = _idle_throttle; + break; + } + + // check if we need to use engine cooldown + if (_fast_idle_timer > 0.0) { + // running at fast idle for engine cool down + _idle_throttle *= 1.5; + _fast_idle_timer -= dt; + } + _control_output = _idle_throttle; break; @@ -352,13 +353,17 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) // set main rotor ramp to increase to full speed update_rotor_ramp(1.0f, dt); + // set fast idle timer so next time RSC goes to idle, the cooldown timer starts + if (_cooldown_time.get() > 0) { + _fast_idle_timer = _cooldown_time.get(); + } + // ensure _idle_throttle not set to invalid value due to premature switch out of turbine start if (_starting) { _idle_throttle = get_idle_output(); } // if turbine engine started without using start sequence, set starting flag just to be sure it can't be triggered when back in idle _starting = false; - _autorotating = false; if ((_control_mode == ROTOR_CONTROL_MODE_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SETPOINT)) { // set control rotor speed to ramp slewed value between idle and desired speed @@ -389,38 +394,20 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt) { - int8_t ramp_time; - int8_t bailout_time; - // sanity check ramp time and enable bailout if set - if (_ramp_time <= 0) { - ramp_time = 1; - } else { - ramp_time = _ramp_time; - } + float ramp_time = MAX(float(_ramp_time.get()), 1.0); - if (_rsc_arot_engage_time <= 0) { - bailout_time = 1; - } else { - bailout_time = _rsc_arot_engage_time; + // check if we need to use the bailout ramp up rate for the autorotation case + if (autorotation.bailing_out()) { + ramp_time = autorotation.get_bailout_ramp(); } // ramp output upwards towards target if (_rotor_ramp_output < rotor_ramp_input) { - if (_use_bailout_ramp) { - if (!_bailing_out) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "bailing_out"); - _bailing_out = true; - if (_control_mode == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {_gov_bailing_out = true;} - } - _rotor_ramp_output += (dt / bailout_time); - } else { - _rotor_ramp_output += (dt / ramp_time); - } - if (_rotor_ramp_output > rotor_ramp_input) { - _rotor_ramp_output = rotor_ramp_input; - _bailing_out = false; - _use_bailout_ramp = false; - } + _rotor_ramp_output += (dt / ramp_time); + + // Do not allow output to exceed requested input + _rotor_ramp_output = MIN(_rotor_ramp_output, rotor_ramp_input); + } else { // ramping down happens instantly _rotor_ramp_output = rotor_ramp_input; @@ -430,14 +417,13 @@ void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt) // update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut void AP_MotorsHeli_RSC::update_rotor_runup(float dt) { - int8_t runup_time = _runup_time; + float runup_time = _runup_time; // sanity check runup time runup_time = MAX(_ramp_time+1,runup_time); - // adjust rotor runup when bailing out - if (_use_bailout_ramp) { - // maintain same delta as set in parameters - runup_time = _runup_time-_ramp_time+1; + // adjust rotor runup when in autorotation or bailing out + if (in_autorotation()) { + runup_time = autorotation.get_runup_time(); } // protect against divide by zero @@ -458,7 +444,7 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt) } // if in autorotation, don't let rotor_runup_output go less than critical speed to keep // runup complete flag from being set to false - if (_autorotating && !rotor_speed_above_critical()) { + if (in_autorotation() && !rotor_speed_above_critical()) { _rotor_runup_output = get_critical_speed(); } @@ -480,20 +466,13 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt) _runup_complete = false; } // if rotor estimated speed is zero, then spooldown has been completed - if (get_rotor_speed() <= 0.0f) { + if (_rotor_runup_output <= 0.0f) { _spooldown_complete = true; } else { _spooldown_complete = false; } } -// get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value -float AP_MotorsHeli_RSC::get_rotor_speed() const -{ - // if no actual measured rotor speed is available, estimate speed based on rotor runup scalar. - return _rotor_runup_output; -} - // write_rsc - outputs pwm onto output rsc channel // servo_out parameter is of the range 0 ~ 1 void AP_MotorsHeli_RSC::write_rsc(float servo_out) @@ -574,7 +553,7 @@ void AP_MotorsHeli_RSC::autothrottle_run() } else if (!_governor_engage && !_governor_fault) { // if governor is not engaged and rotor is overspeeding by more than governor range due to // misconfigured throttle curve or stuck throttle, set a fault and governor will not operate - if (_rotor_rpm > (_governor_rpm + _governor_range) && !_gov_bailing_out) { + if (_rotor_rpm > (_governor_rpm + _governor_range) && !autorotation.bailing_out()) { _governor_fault = true; governor_reset(); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed"); @@ -582,7 +561,7 @@ void AP_MotorsHeli_RSC::autothrottle_run() // when performing power recovery from autorotation, this waits for user to load rotor in order to // engage the governor - } else if (_rotor_rpm > _governor_rpm && _gov_bailing_out) { + } else if (_rotor_rpm > _governor_rpm && autorotation.bailing_out()) { _governor_output = 0.0f; // torque rise limiter accelerates rotor to the reference speed @@ -593,7 +572,6 @@ void AP_MotorsHeli_RSC::autothrottle_run() if (_rotor_rpm >= ((float)_governor_rpm - torque_ref_error_rpm)) { _governor_engage = true; _autothrottle = true; - _gov_bailing_out = false; GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Governor Engaged"); } } else { @@ -616,3 +594,42 @@ void AP_MotorsHeli_RSC::governor_reset() _governor_engage = false; _governor_fault_count = 0; // reset fault count when governor reset } + +#if HAL_LOGGING_ENABLED +// Write a helicopter motors packet +void AP_MotorsHeli_RSC::write_log(void) const +{ + // @LoggerMessage: HRSC + // @Description: Helicopter related messages + // @Field: I: Instance, 0=Main, 1=Tail + // @Field: TimeUS: Time since system startup + // @Field: DRRPM: Desired rotor speed + // @Field: ERRPM: Estimated rotor speed + // @Field: Gov: Governor Output + // @Field: Throt: Throttle output + // @Field: Ramp: throttle ramp up + // @Field: Stat: RSC state + + // Write to data flash log + AP::logger().WriteStreaming("HRSC", + "TimeUS,I,DRRPM,ERRPM,Gov,Throt,Ramp,Stat", + "s#------", + "F-------", + "QBfffffB", + AP_HAL::micros64(), + _instance, + get_desired_speed(), + _rotor_runup_output, + _governor_output, + get_control_output(), + _rotor_ramp_output, + uint8_t(_rsc_state)); +} +#endif + + +// considered to be "in an autorotation" if active or bailing out +bool AP_MotorsHeli_RSC::in_autorotation(void) const +{ + return autorotation.active() || autorotation.bailing_out(); +} diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 276728ca4d1dc3..47fa68f8ad180b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -4,31 +4,8 @@ #include // ArduPilot Mega Vector/Matrix math Library #include #include - -// default main rotor speed (ch8 out) as a number from 0 ~ 100 -#define AP_MOTORS_HELI_RSC_SETPOINT 70 - -// default main rotor critical speed -#define AP_MOTORS_HELI_RSC_CRITICAL 50 - -// RSC output defaults -#define AP_MOTORS_HELI_RSC_IDLE_DEFAULT 0 - -// default main rotor ramp up time in seconds -#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to setpoint -#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed -#define AP_MOTORS_HELI_RSC_AROT_ENGAGE_TIME 1 // time in seconds to ramp motors when bailing out of autorotation -#define AP_MOTORS_HELI_RSC_AROT_IDLE 0 - -// Throttle Curve Defaults -#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25 -#define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT 32 -#define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT 38 -#define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT 50 -#define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT 100 - -// RSC governor defaults -#define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100 +#include +#include // rotor control modes enum RotorControlMode { @@ -46,7 +23,9 @@ class AP_MotorsHeli_RSC { friend class AP_MotorsHeli_Quad; AP_MotorsHeli_RSC(SRV_Channel::Aux_servo_function_t aux_fn, - uint8_t default_channel) : + uint8_t default_channel, + uint8_t inst) : + _instance(inst), _aux_fn(aux_fn), _default_channel(default_channel) { @@ -81,12 +60,8 @@ class AP_MotorsHeli_RSC { // set_desired_speed - this requires input to be 0-1 void set_desired_speed(float desired_speed) { _desired_speed = desired_speed; } - // get_rotor_speed - estimated rotor speed when no governor or rpm sensor is used - float get_rotor_speed() const; - // functions for autothrottle, throttle curve, governor, idle speed, output to servo void set_governor_output(float governor_output) {_governor_output = governor_output; } - 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.set(idle_output); } @@ -104,20 +79,8 @@ class AP_MotorsHeli_RSC { // set_collective. collective for throttle curve calculation void set_collective(float collective) { _collective_in = collective; } - // use bailout ramp time - void use_bailout_ramp_time(bool enable) { _use_bailout_ramp = enable; } - - // use external governor autorotation window - void set_autorotation_flag(bool flag) { _in_autorotation = flag; } - - // set the throttle percentage to be used during autorotation for this instance of Heli_RSC - void set_arot_idle_output(int16_t idle) { _arot_idle_output.set(idle); } - - // set the manual autorotation option for this instance of Heli_RSC - void set_rsc_arot_man_enable(int8_t enable) { _rsc_arot_man_enable.set(enable); } - - // set the autorotation power recovery time for this instance of Heli_RSC - void set_rsc_arot_engage_time(int8_t eng_time) { _rsc_arot_engage_time.set(eng_time); } + // true if we are considered to be autorotating or bailing out of an autorotation + bool in_autorotation(void) const; // turbine start initialize sequence void set_turbine_start(bool turbine_start) {_turbine_start = turbine_start; } @@ -129,7 +92,14 @@ class AP_MotorsHeli_RSC { uint32_t get_output_mask() const; // rotor_speed_above_critical - return true if rotor speed is above that critical for flight - bool rotor_speed_above_critical(void) const { return get_rotor_speed() > get_critical_speed(); } + bool rotor_speed_above_critical(void) const { return _rotor_runup_output >= get_critical_speed(); } + +#if HAL_LOGGING_ENABLED + // RSC logging + void write_log(void) const; +#endif + + RSC_Autorotation autorotation; // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; @@ -141,16 +111,14 @@ class AP_MotorsHeli_RSC { AP_Int8 _runup_time; // Time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time AP_Int16 _critical_speed; // Rotor speed below which flight is not possible AP_Int16 _idle_output; // Rotor control output while at idle - AP_Int16 _arot_idle_output; // Percent value used when in autorotation - AP_Int8 _rsc_arot_engage_time; // time in seconds for in-flight power re-engagement - AP_Int8 _rsc_arot_man_enable; // enables manual autorotation private: uint64_t _last_update_us; + const uint8_t _instance; // channel setup for aux function - SRV_Channel::Aux_servo_function_t _aux_fn; - uint8_t _default_channel; + const SRV_Channel::Aux_servo_function_t _aux_fn; + const uint8_t _default_channel; // internal variables RotorControlMode _control_mode = ROTOR_CONTROL_MODE_DISABLED; // motor control mode, Passthrough or Setpoint @@ -168,16 +136,13 @@ class AP_MotorsHeli_RSC { bool _governor_engage; // RSC governor status flag bool _autothrottle; // autothrottle status flag bool _governor_fault; // governor fault status flag - bool _use_bailout_ramp; // true if allowing RSC to quickly ramp up engine - bool _in_autorotation; // true if vehicle is currently in an autorotation bool _spooldown_complete; // flag for determining if spooldown is complete float _fast_idle_timer; // cooldown timer variable uint8_t _governor_fault_count; // variable for tracking governor speed sensor faults float _governor_torque_reference; // governor reference for load calculations - bool _autorotating; // flag that holds the status of autorotation - bool _bailing_out; // flag that holds the status of bail out(power engagement) float _idle_throttle; // current idle throttle setting - bool _gov_bailing_out; // flag that holds the status of governor bail out + + RotorControlState _rsc_state; // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output void update_rotor_ramp(float rotor_ramp_input, float dt); @@ -207,5 +172,5 @@ class AP_MotorsHeli_RSC { float get_idle_output() const { return _idle_output * 0.01; } float get_governor_torque() const { return _governor_torque * 0.01; } float get_governor_compensator() const { return _governor_compensator * 0.000001; } - float get_arot_idle_output() const { return _arot_idle_output * 0.01; } + }; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index a996fb7d04cf0d..6372363e37a43b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -220,6 +220,8 @@ void AP_MotorsHeli_Single::init_outputs() case TAIL_TYPE::DIRECTDRIVE_VARPITCH: case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV: _tail_rotor.init_servo(); + // yaw servo is an angle from -4500 to 4500 + SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); break; case TAIL_TYPE::SERVO_EXTGYRO: @@ -268,22 +270,6 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() _main_rotor._rsc_mode.save(); _heliflags.save_rsc_mode = false; } - - // allow use of external governor autorotation bailout - if (_heliflags.in_autorotation) { - _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); - // set bailout ramp time - _main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); - if (use_tail_RSC()) { - _tail_rotor.set_autorotation_flag(_heliflags.in_autorotation); - _tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); - } - } else { - _main_rotor.set_autorotation_flag(false); - if (use_tail_RSC()) { - _tail_rotor.set_autorotation_flag(false); - } - } } // calculate_scalars - recalculates various scalers used. @@ -324,18 +310,12 @@ void AP_MotorsHeli_Single::calculate_scalars() _tail_rotor.set_runup_time(_main_rotor._runup_time.get()); _tail_rotor.set_critical_speed(_main_rotor._critical_speed.get()); _tail_rotor.set_idle_output(_main_rotor._idle_output.get()); - _tail_rotor.set_arot_idle_output(_main_rotor._arot_idle_output.get()); - _tail_rotor.set_rsc_arot_man_enable(_main_rotor._rsc_arot_man_enable.get()); - _tail_rotor.set_rsc_arot_engage_time(_main_rotor._rsc_arot_engage_time.get()); } else { _tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_DISABLED); _tail_rotor.set_ramp_time(0); _tail_rotor.set_runup_time(0); _tail_rotor.set_critical_speed(0); _tail_rotor.set_idle_output(0); - _tail_rotor.set_arot_idle_output(0); - _tail_rotor.set_rsc_arot_man_enable(0); - _tail_rotor.set_rsc_arot_engage_time(0); } } @@ -408,10 +388,9 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float } // ensure not below landed/landing collective - if (_heliflags.landing_collective && collective_out < _collective_land_min_pct && !_heliflags.in_autorotation) { + if (_heliflags.landing_collective && collective_out < _collective_land_min_pct && !_main_rotor.in_autorotation()) { collective_out = _collective_land_min_pct; limit.throttle_lower = true; - } // updates below land min collective flag @@ -467,7 +446,7 @@ float AP_MotorsHeli_Single::get_yaw_offset(float collective) return 0.0; } - if (_heliflags.in_autorotation || (get_control_output() <= _main_rotor.get_idle_output())) { + if (_main_rotor.autorotation.active() || (_main_rotor.get_control_output() <= _main_rotor.get_idle_output())) { // Motor is stopped or at idle, and thus not creating torque return 0.0; } @@ -654,6 +633,9 @@ bool AP_MotorsHeli_Single::arming_checks(size_t buflen, char *buffer) const // Called from system.cpp void AP_MotorsHeli_Single::heli_motors_param_conversions(void) { + // Run common conversions from base class + AP_MotorsHeli::heli_motors_param_conversions(); + // PARAMETER_CONVERSION - Added: Nov-2023 // Convert trim for DDFP tails // Previous DDFP configs used servo trim for setting the yaw trim, which no longer works with thrust linearisation. Convert servo trim @@ -691,3 +673,19 @@ bool AP_MotorsHeli_Single::use_tail_RSC() const return (type == TAIL_TYPE::DIRECTDRIVE_VARPITCH) || (type == TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV); } + +#if HAL_LOGGING_ENABLED +void AP_MotorsHeli_Single::Log_Write(void) +{ + // Write swash plate logging + // For single heli we have to apply an additional cyclic scaler of sqrt(2.0) because the + // definition of when we achieve _cyclic_max is different to dual heli. In single, _cyclic_max + // is limited at sqrt(2.0), in dual it is limited at 1.0 + float cyclic_angle_scaler = get_cyclic_angle_scaler() * sqrtf(2.0); + _swashplate.write_log(cyclic_angle_scaler, _collective_min_deg.get(), _collective_max_deg.get(), _collective_min.get(), _collective_max.get()); + + // Write RSC logging + _main_rotor.write_log(); + _tail_rotor.write_log(); +} +#endif diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 61e6588a5ab9fb..5b55ffad0990c2 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -32,8 +32,8 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // constructor 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(AP_MOTORS_MOT_1, AP_MOTORS_MOT_2, AP_MOTORS_MOT_3, AP_MOTORS_MOT_5) + _tail_rotor(SRV_Channel::k_heli_tail_rsc, AP_MOTORS_HELI_SINGLE_TAILRSC, 1U), + _swashplate(AP_MOTORS_MOT_1, AP_MOTORS_MOT_2, AP_MOTORS_MOT_3, AP_MOTORS_MOT_5, 1U) { AP_Param::setup_object_defaults(this, var_info); }; @@ -77,6 +77,11 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // Thrust Linearization handling Thrust_Linearization thr_lin {*this}; +#if HAL_LOGGING_ENABLED + // Blade angle logging - called at 10 Hz + void Log_Write(void) override; +#endif + // var_info static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp index 3471edc168cc90..49eff5b895f5c9 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp @@ -16,6 +16,7 @@ #include #include #include +#include #include "AP_MotorsHeli_Swash.h" @@ -87,13 +88,10 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = { AP_GROUPEND }; -AP_MotorsHeli_Swash::AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3) +AP_MotorsHeli_Swash::AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t instance) : + _motor_num{mot_0, mot_1, mot_2, mot_3}, + _instance(instance) { - _motor_num[0] = mot_0; - _motor_num[1] = mot_1; - _motor_num[2] = mot_2; - _motor_num[3] = mot_3; - AP_Param::setup_object_defaults(this, var_info); } @@ -214,8 +212,14 @@ void AP_MotorsHeli_Swash::add_servo_raw(uint8_t num, float roll, float pitch, fl // calculates servo output void AP_MotorsHeli_Swash::calculate(float roll, float pitch, float collective) { + + // Store inputs for logging, store col before col reversal to ensure logging comes out with the correct sign (+/-) + _roll_input = roll; + _pitch_input = pitch; + _collective_input_scaled = collective; + // Collective control direction. Swash moves up for negative collective pitch, down for positive collective pitch - if (_collective_direction == COLLECTIVE_DIRECTION_REVERSED){ + if (_collective_direction == COLLECTIVE_DIRECTION_REVERSED) { collective = 1 - collective; } @@ -283,3 +287,37 @@ uint32_t AP_MotorsHeli_Swash::get_output_mask() const } return mask; } + +#if HAL_LOGGING_ENABLED +// Write SWSH log for this instance of swashplate +void AP_MotorsHeli_Swash::write_log(float cyclic_scaler, float col_ang_min, float col_ang_max, int16_t col_min, int16_t col_max) const +{ + // Calculate the collective contribution to blade pitch angle + // Swashplate receives the scaled collective value based on the col_min and col_max params. We have to reverse the scaling here to do the angle calculation. + float collective_scalar = ((float)(col_max-col_min))*1e-3; + collective_scalar = MAX(collective_scalar, 1e-3); + float _collective_input = (_collective_input_scaled - (float)(col_min - 1000)*1e-3) / collective_scalar; + float col = (col_ang_max - col_ang_min) * _collective_input + col_ang_min; + + // Calculate the cyclic contribution to blade pitch angle + float tcyc = norm(_roll_input, _pitch_input) * cyclic_scaler; + float pcyc = _pitch_input * cyclic_scaler; + float rcyc = _roll_input * cyclic_scaler; + + // @LoggerMessage: SWSH + // @Description: Helicopter swashplate logging + // @Field: TimeUS: Time since system startup + // @Field: I: Swashplate instance + // @Field: Col: Blade pitch angle contribution from collective + // @Field: TCyc: Total blade pitch angle contribution from cyclic + // @Field: PCyc: Blade pitch angle contribution from pitch cyclic + // @Field: RCyc: Blade pitch angle contribution from roll cyclic + AP::logger().WriteStreaming("SWSH", "TimeUS,I,Col,TCyc,PCyc,RCyc", "s#dddd", "F-0000", "QBffff", + AP_HAL::micros64(), + _instance, + col, + tcyc, + pcyc, + rcyc); +} +#endif diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.h b/libraries/AP_Motors/AP_MotorsHeli_Swash.h index 927777e98372eb..4f12ba2f198bfd 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.h @@ -5,6 +5,7 @@ #include #include // ArduPilot Mega Vector/Matrix math Library #include +#include // swashplate types enum SwashPlateType { @@ -19,7 +20,7 @@ enum SwashPlateType { class AP_MotorsHeli_Swash { public: - AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3); + AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t instance); // configure - configure the swashplate settings for any updated parameters void configure(); @@ -39,6 +40,11 @@ class AP_MotorsHeli_Swash { // Get function output mask uint32_t get_output_mask() const; +#if HAL_LOGGING_ENABLED + // Write SWSH log for this instance of swashplate + void write_log(float cyclic_scaler, float col_ang_min, float col_ang_max, int16_t col_min, int16_t col_max) const; +#endif + // var_info static const struct AP_Param::GroupInfo var_info[]; @@ -75,7 +81,13 @@ class AP_MotorsHeli_Swash { float _pitchFactor[_max_num_servos]; // Pitch axis scaling of servo output based on servo position float _collectiveFactor[_max_num_servos]; // Collective axis scaling of servo output based on servo position float _output[_max_num_servos]; // Servo output value - uint8_t _motor_num[_max_num_servos]; // Motor function to use for output + const uint8_t _motor_num[_max_num_servos]; // Motor function to use for output + const uint8_t _instance; // Swashplate instance. Used for logging. + + // Variables stored for logging + float _roll_input; + float _pitch_input; + float _collective_input_scaled; // parameters AP_Int8 _swashplate_type; // Swash Type Setting diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 70e07103be6ff8..9ad6a92299e0b5 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -686,7 +686,7 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type) break; } case MOTOR_FRAME_TYPE_H: { - // H frame set-up - same as X but motors spin in opposite directiSons + // 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 }, diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 5d315b91769087..e8a099998a9b73 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -86,11 +86,11 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Param: PWM_TYPE // @DisplayName: Output PWM type - // @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output + // @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output.PWMRange and PWMAngle are PWM special/rare cases for ESCs that dont calibrate normally (some Sub motors) or where each ESC must have its PWM range set individually using the Servo params instead of PWM_MIN/MAX parameters. // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange,9:PWMAngle // @User: Advanced // @RebootRequired: True - AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL), + AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, float(PWMType::NORMAL)), // @Param: PWM_MIN // @DisplayName: PWM output minimum @@ -457,6 +457,21 @@ float AP_MotorsMulticopter::actuator_spin_up_to_ground_idle() const return constrain_float(_spin_up_ratio, 0.0f, 1.0f) * thr_lin.get_spin_min(); } +// return throttle out for motor motor_num, returns true if value is valid false otherwise +bool AP_MotorsMulticopter::get_thrust(uint8_t motor_num, float& thr_out) const +{ + if (motor_num >= AP_MOTORS_MAX_NUM_MOTORS || !motor_enabled[motor_num]) { + return false; + } + + // Constrain to linearization range. + const float actuator = constrain_float(_actuator[motor_num], thr_lin.get_spin_min(), thr_lin.get_spin_max()); + + // Remove linearization and compensation gain + thr_out = thr_lin.actuator_to_thrust(actuator) / thr_lin.get_compensation_gain(); + return true; +} + // parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid bool AP_MotorsMulticopter::check_mot_pwm_params() const { @@ -474,7 +489,7 @@ 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_type == PWM_TYPE_PWM_ANGLE)) { + if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWMType::PWM_RANGE) || (_pwm_type == PWMType::PWM_ANGLE)) { _pwm_min.set_and_default(1000); _pwm_max.set_and_default(2000); } diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index d6fdf6a3092b55..7e8491c8497c07 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -89,6 +89,9 @@ class AP_MotorsMulticopter : public AP_Motors { // convert values to PWM min and max if not configured void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max); + // return thrust for motor motor_num, returns true if value is valid false otherwise + bool get_thrust(uint8_t motor_num, float& thr_out) const override; + #if HAL_LOGGING_ENABLED // 10hz logging of voltage scaling and max trust void Log_Write() override; diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index ab566944aeb967..e387694c2010cf 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -48,9 +48,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100); // check for reverse tricopter - if (frame_type == MOTOR_FRAME_TYPE_PLUSREV) { - _pitch_reversed = true; - } + _pitch_reversed = frame_type == MOTOR_FRAME_TYPE_PLUSREV; _mav_type = MAV_TYPE_TRICOPTER; @@ -62,11 +60,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty void AP_MotorsTri::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) { // check for reverse tricopter - if (frame_type == MOTOR_FRAME_TYPE_PLUSREV) { - _pitch_reversed = true; - } else { - _pitch_reversed = false; - } + _pitch_reversed = frame_type == MOTOR_FRAME_TYPE_PLUSREV; set_initialised_ok((frame_class == MOTOR_FRAME_TRI) && SRV_Channels::function_assigned(SRV_Channel::k_motor7)); } @@ -286,7 +280,8 @@ void AP_MotorsTri::output_armed_stabilizing() void AP_MotorsTri::_output_test_seq(uint8_t motor_seq, int16_t pwm) { // output to motors and servos - switch (motor_seq) { + if (!_pitch_reversed) { + switch (motor_seq) { case 1: // front right motor rc_write(AP_MOTORS_MOT_1, pwm); @@ -306,6 +301,29 @@ void AP_MotorsTri::_output_test_seq(uint8_t motor_seq, int16_t pwm) default: // do nothing break; + } + } else { + switch (motor_seq) { + case 1: + // front motor + rc_write(AP_MOTORS_MOT_4, pwm); + break; + case 2: + // front servo + rc_write(AP_MOTORS_CH_TRI_YAW, pwm); + break; + case 3: + // back right motor + rc_write(AP_MOTORS_MOT_1, pwm); + break; + case 4: + // back left motor + rc_write(AP_MOTORS_MOT_2, pwm); + break; + default: + // do nothing + break; + } } } @@ -360,6 +378,30 @@ float AP_MotorsTri::get_roll_factor(uint8_t i) return ret; } +// This function is currently only used by AP_Motors_test +#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +float AP_MotorsTri::get_pitch_factor_json(uint8_t i) +{ + float ret = 0.0f; + + switch (i) { + case AP_MOTORS_MOT_1: // front motors + case AP_MOTORS_MOT_2: + ret = 0.5f; + break; + case AP_MOTORS_MOT_4: // rear motor + ret = -1.0f; + break; + } + + if (_pitch_reversed) { + ret *= -1.0f; + } + + return ret; +} +#endif // APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + // Run arming checks bool AP_MotorsTri::arming_checks(size_t buflen, char *buffer) const { @@ -374,3 +416,38 @@ bool AP_MotorsTri::arming_checks(size_t buflen, char *buffer) const // run base class checks return AP_MotorsMulticopter::arming_checks(buflen, buffer); } + +// This function is currently only used by AP_Motors_test +#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +// Get the testing order for the motors +uint8_t AP_MotorsTri::get_motor_test_order(uint8_t i) +{ + if (!_pitch_reversed) { + switch (i) { + case AP_MOTORS_MOT_1: // front right motor + return 1; + case AP_MOTORS_MOT_4: // back motor + return 2; + case AP_MOTORS_CH_TRI_YAW: // back servo + return 3; + case AP_MOTORS_MOT_2: // front left motor + return 4; + default: + return 0; + } + } else { + switch (i) { + case AP_MOTORS_MOT_4: // front motor + return 1; + case AP_MOTORS_CH_TRI_YAW: // front servo + return 2; + case AP_MOTORS_MOT_1: // back right motor + return 3; + case AP_MOTORS_MOT_2: // back left motor + return 4; + default: + return 0; + } + } +} +#endif // APM_BUILD_TYPE(APM_BUILD_UNKNOWN) diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 430e5c9b706a22..3c034ccc1ceeb7 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -48,9 +48,15 @@ class AP_MotorsTri : public AP_MotorsMulticopter { // using copter motors for forward flight float get_roll_factor(uint8_t i) override; + // return the pitch factor of any motor, this is used for AP_Motors_test + float get_pitch_factor_json(uint8_t i); + // Run arming checks bool arming_checks(size_t buflen, char *buffer) const override; + // Get the testing order for the motors, this is used for AP_Motors_test + uint8_t get_motor_test_order(uint8_t i); + protected: // output - sends commands to the motors void output_armed_stabilizing() override; @@ -59,6 +65,7 @@ class AP_MotorsTri : public AP_MotorsMulticopter { void thrust_compensation(void) override; const char* _get_frame_string() const override { return "TRI"; } + const char* get_type_string() const override { return _pitch_reversed ? "pitch-reversed" : ""; } // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index b5d81c13b7d044..42d7deebda5a4d 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -135,35 +135,35 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) hal.rcout->set_freq(mask, freq_hz); hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); - const pwm_type type = (pwm_type)_pwm_type.get(); + const PWMType type = _pwm_type; switch (type) { - case PWM_TYPE_ONESHOT: + case PWMType::ONESHOT: if (freq_hz > 50 && mask != 0) { hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); } break; - case PWM_TYPE_ONESHOT125: + case PWMType::ONESHOT125: if (freq_hz > 50 && mask != 0) { hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125); } break; - case PWM_TYPE_BRUSHED: + case PWMType::BRUSHED: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED); break; - case PWM_TYPE_DSHOT150: + case PWMType::DSHOT150: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150); break; - case PWM_TYPE_DSHOT300: + case PWMType::DSHOT300: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300); break; - case PWM_TYPE_DSHOT600: + case PWMType::DSHOT600: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600); break; - case PWM_TYPE_DSHOT1200: + case PWMType::DSHOT1200: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200); break; - case PWM_TYPE_PWM_RANGE: - case PWM_TYPE_PWM_ANGLE: + case PWMType::PWM_RANGE: + case PWMType::PWM_ANGLE: /* this is a motor output type for multirotors which honours the SERVOn_MIN/MAX (and TRIM for angle) values per channel @@ -173,20 +173,20 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) Angle type offsets by 1500 to get -500 to 500. */ - if (type == PWM_TYPE_PWM_RANGE) { + if (type == PWMType::PWM_RANGE) { _motor_pwm_scaled.offset = 1000.0; } else { - // PWM_TYPE_PWM_ANGLE + // PWMType::PWM_ANGLE _motor_pwm_scaled.offset = 1500.0; } _motor_pwm_scaled.mask |= motor_mask; for (uint8_t i=0; i<16; i++) { if ((1U< _pwm_type; // PWM output type // motor failure handling bool _thrust_boost; // true if thrust boost is enabled to handle motor failure @@ -361,19 +375,6 @@ class AP_Motors { MAV_TYPE _mav_type; // MAV_TYPE_GENERIC = 0; - enum pwm_type { - PWM_TYPE_NORMAL = 0, - PWM_TYPE_ONESHOT = 1, - PWM_TYPE_ONESHOT125 = 2, - PWM_TYPE_BRUSHED = 3, - PWM_TYPE_DSHOT150 = 4, - PWM_TYPE_DSHOT300 = 5, - PWM_TYPE_DSHOT600 = 6, - PWM_TYPE_DSHOT1200 = 7, - PWM_TYPE_PWM_RANGE = 8, - PWM_TYPE_PWM_ANGLE = 9 - }; - // return string corresponding to frame_class virtual const char* _get_frame_string() const = 0; diff --git a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp index ff2114864a4556..4dd5a952423869 100644 --- a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp +++ b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp @@ -3,6 +3,7 @@ #include "AP_Motors_Class.h" #include #include +#include #include #define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5 // battery voltage filtered at 0.5hz @@ -84,8 +85,8 @@ const AP_Param::GroupInfo Thrust_Linearization::var_info[] = { }; Thrust_Linearization::Thrust_Linearization(AP_Motors& _motors) : - motors(_motors), - lift_max(1.0) + lift_max(1.0), + motors(_motors) { // setup battery voltage filtering batt_voltage_filt.set_cutoff_frequency(AP_MOTORS_BATT_VOLT_FILT_HZ); @@ -193,7 +194,7 @@ float Thrust_Linearization::get_compensation_gain() const #if AP_MOTORS_DENSITY_COMP == 1 // air density ratio is increasing in density / decreasing in altitude - const float air_density_ratio = AP::baro().get_air_density_ratio(); + const float air_density_ratio = AP::ahrs().get_air_density_ratio(); if (air_density_ratio > 0.3 && air_density_ratio < 1.5) { ret *= 1.0 / constrain_float(air_density_ratio, 0.5, 1.25); } diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 491bb0fc60bff6..336eea61e3d809 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -25,14 +25,16 @@ void loop(); void motor_order_test(); void stability_test(); void update_motors(); -void print_all_motor_matrix(); +void print_all_motors(); +void print_motor_matrix(uint8_t frame_class, uint8_t frame_type); +void print_motor_tri(uint8_t frame_class, uint8_t frame_type); // Instantiate a few classes that will be needed so that the singletons can be called from the motors lib #if HAL_WITH_ESC_TELEM AP_ESC_Telem esc_telem; #endif -#define VERSION "AP_Motors library test ver 1.1" +#define VERSION "AP_Motors library test ver 1.2" SRV_Channels srvs; AP_BattMonitor _battmonitor{0, nullptr, nullptr}; @@ -40,6 +42,7 @@ AP_BattMonitor _battmonitor{0, nullptr, nullptr}; AP_Motors *motors; AP_MotorsHeli *motors_heli; AP_MotorsMatrix *motors_matrix; +AP_MotorsTri *motors_tri; bool thrust_boost = false; @@ -240,7 +243,7 @@ void setup() ::printf("autorotation only supported by heli frame types, got %i\n", frame_class); exit(1); } - motors_heli->set_in_autorotation(!is_zero(value)); + motors_heli->set_autorotation_active(!is_zero(value)); } else { ::printf("Expected \"frame_class\", \"yaw_headroom\" or \"throttle_avg_max\"\n"); @@ -271,9 +274,12 @@ void setup() } else if (strcmp(argv[1],"p") == 0) { if (motors_matrix == nullptr) { - ::printf("Print only supports motors matrix\n"); + motors_matrix = new AP_MotorsMatrix(400); } - print_all_motor_matrix(); + if (motors_tri == nullptr) { + motors_tri = new AP_MotorsTri(400); + } + print_all_motors(); } else { ::printf("Expected first argument: 't', 's' or 'p'\n"); @@ -336,81 +342,142 @@ void loop() } } +bool first_layout = true; + // print motor layout for all frame types in json format -void print_all_motor_matrix() +void print_all_motors() { hal.console->printf("{\n"); hal.console->printf("\t\"Version\": \"%s\",\n", VERSION); hal.console->printf("\t\"layouts\": [\n"); - bool first_layout = true; - char frame_and_type_string[30]; + first_layout = true; for (uint8_t frame_class=0; frame_class <= AP_Motors::MOTOR_FRAME_DECA; frame_class++) { for (uint8_t frame_type=0; frame_type < AP_Motors::MOTOR_FRAME_TYPE_Y4; frame_type++) { - if (frame_type == AP_Motors::MOTOR_FRAME_TYPE_VTAIL || - frame_type == AP_Motors::MOTOR_FRAME_TYPE_ATAIL) { - // Skip the none planar motors types - continue; + if (frame_class == AP_Motors::MOTOR_FRAME_TRI) { + print_motor_tri(frame_class, frame_type); + } else { + print_motor_matrix(frame_class, frame_type); } - motors_matrix->init((AP_Motors::motor_frame_class)frame_class, (AP_Motors::motor_frame_type)frame_type); - if (motors_matrix->initialised_ok()) { - if (!first_layout) { + } + } + + hal.console->printf("\n"); + hal.console->printf("\t]\n"); + hal.console->printf("}\n"); +} + +void print_motor_tri(uint8_t frame_class, uint8_t frame_type) +{ + char frame_and_type_string[30]; + motors_tri->init((AP_Motors::motor_frame_class)frame_class, (AP_Motors::motor_frame_type)frame_type); + if (motors_tri->initialised_ok()) { + if (!first_layout) { + hal.console->printf(",\n"); + } + first_layout = false; + + // Grab full frame string and strip "Frame: " and split + // This is the long way round, motors does have direct getters, but there protected + motors_tri->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string)); + char *frame_string = strchr(frame_and_type_string, ':'); + char *type_string = strchr(frame_and_type_string, '/'); + if (type_string != nullptr) { + *type_string = 0; + } + + hal.console->printf("\t\t{\n"); + hal.console->printf("\t\t\t\"Class\": %i,\n", frame_class); + hal.console->printf("\t\t\t\"ClassName\": \"%s\",\n", frame_string+2); + hal.console->printf("\t\t\t\"Type\": %i,\n", frame_type); + hal.console->printf("\t\t\t\"TypeName\": \"%s\",\n", (type_string != nullptr) ? type_string + 1 : "default"); + hal.console->printf("\t\t\t\"motors\": [\n"); + bool first_motor = true; + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + float roll, pitch; + uint8_t testing_order; + roll = motors_tri->get_roll_factor(i); + pitch = motors_tri->get_pitch_factor_json(i); + testing_order = motors_tri->get_motor_test_order(i); + if (testing_order) { + if (!first_motor) { hal.console->printf(",\n"); } - first_layout = false; - - // Grab full frame string and strip "Frame: " and split - // This is the long way round, motors does have direct getters, but there protected - motors_matrix->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string)); - char *frame_string = strchr(frame_and_type_string, ':'); - char *type_string = strchr(frame_and_type_string, '/'); - if (type_string != nullptr) { - *type_string = 0; - } + first_motor = false; + hal.console->printf("\t\t\t\t{\n"); + hal.console->printf("\t\t\t\t\t\"Number\": %i,\n", i+1); + hal.console->printf("\t\t\t\t\t\"TestOrder\": %i,\n", testing_order); + hal.console->printf("\t\t\t\t\t\"Rotation\": \"?\",\n"); + hal.console->printf("\t\t\t\t\t\"Roll\": %0.4f,\n", roll); + hal.console->printf("\t\t\t\t\t\"Pitch\": %0.4f\n", pitch); + hal.console->printf("\t\t\t\t}"); + while (hal.console->tx_pending()) { ; } + } + } + hal.console->printf("\n"); + hal.console->printf("\t\t\t]\n"); + hal.console->printf("\t\t}"); - hal.console->printf("\t\t{\n"); - hal.console->printf("\t\t\t\"Class\": %i,\n", frame_class); - hal.console->printf("\t\t\t\"ClassName\": \"%s\",\n", frame_string+2); - hal.console->printf("\t\t\t\"Type\": %i,\n", frame_type); - hal.console->printf("\t\t\t\"TypeName\": \"%s\",\n", (type_string != nullptr) ? type_string + 1 : "?"); - hal.console->printf("\t\t\t\"motors\": [\n"); - bool first_motor = true; - for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { - float roll, pitch, yaw, throttle; - uint8_t testing_order; - if (motors_matrix->get_factors(i, roll, pitch, yaw, throttle, testing_order)) { - if (!first_motor) { - hal.console->printf(",\n"); - } - first_motor = false; - hal.console->printf("\t\t\t\t{\n"); - hal.console->printf("\t\t\t\t\t\"Number\": %i,\n", i+1); - hal.console->printf("\t\t\t\t\t\"TestOrder\": %i,\n", testing_order); - hal.console->printf("\t\t\t\t\t\"Rotation\": "); - if (is_positive(yaw)) { - hal.console->printf("\"CCW\",\n"); - } else if (is_negative(yaw)) { - hal.console->printf("\"CW\",\n"); - } else { - hal.console->printf("\"?\",\n"); - } - hal.console->printf("\t\t\t\t\t\"Roll\": %0.4f,\n", roll); - hal.console->printf("\t\t\t\t\t\"Pitch\": %0.4f\n", pitch); - hal.console->printf("\t\t\t\t}"); - } - } - hal.console->printf("\n"); - hal.console->printf("\t\t\t]\n"); - hal.console->printf("\t\t}"); + } +} + +void print_motor_matrix(uint8_t frame_class, uint8_t frame_type) +{ + char frame_and_type_string[30]; + motors_matrix->init((AP_Motors::motor_frame_class)frame_class, (AP_Motors::motor_frame_type)frame_type); + if (motors_matrix->initialised_ok()) { + if (!first_layout) { + hal.console->printf(",\n"); + } + first_layout = false; + + // Grab full frame string and strip "Frame: " and split + // This is the long way round, motors does have direct getters, but there protected + motors_matrix->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string)); + char *frame_string = strchr(frame_and_type_string, ':'); + char *type_string = strchr(frame_and_type_string, '/'); + if (type_string != nullptr) { + *type_string = 0; + } + hal.console->printf("\t\t{\n"); + hal.console->printf("\t\t\t\"Class\": %i,\n", frame_class); + hal.console->printf("\t\t\t\"ClassName\": \"%s\",\n", frame_string+2); + hal.console->printf("\t\t\t\"Type\": %i,\n", frame_type); + hal.console->printf("\t\t\t\"TypeName\": \"%s\",\n", (type_string != nullptr) ? type_string + 1 : "?"); + hal.console->printf("\t\t\t\"motors\": [\n"); + bool first_motor = true; + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + float roll, pitch, yaw, throttle; + uint8_t testing_order; + if (motors_matrix->get_factors(i, roll, pitch, yaw, throttle, testing_order)) { + if (!first_motor) { + hal.console->printf(",\n"); + } + first_motor = false; + hal.console->printf("\t\t\t\t{\n"); + hal.console->printf("\t\t\t\t\t\"Number\": %i,\n", i+1); + hal.console->printf("\t\t\t\t\t\"TestOrder\": %i,\n", testing_order); + hal.console->printf("\t\t\t\t\t\"Rotation\": "); + if (is_positive(yaw)) { + hal.console->printf("\"CCW\",\n"); + } else if (is_negative(yaw)) { + hal.console->printf("\"CW\",\n"); + } else { + hal.console->printf("\"?\",\n"); + } + hal.console->printf("\t\t\t\t\t\"Roll\": %0.4f,\n", roll); + hal.console->printf("\t\t\t\t\t\"Pitch\": %0.4f\n", pitch); + hal.console->printf("\t\t\t\t}"); + while (hal.console->tx_pending()) { ; } } } - } + hal.console->printf("\n"); + hal.console->printf("\t\t\t]\n"); + hal.console->printf("\t\t}"); - hal.console->printf("\n"); - hal.console->printf("\t]\n"); - hal.console->printf("}\n"); + } } // stability_test @@ -451,7 +518,7 @@ void stability_test() // arm motors motors->armed(true); motors->set_interlock(true); - SRV_Channels::enable_aux_servos(); + AP::srv().enable_aux_servos(); hal.console->printf("Roll,Pitch,Yaw,Thr,"); for (uint8_t i=0; i #include #include "AP_Mount.h" -#if HAL_MOUNT_ENABLED - #include "AP_Mount_Backend.h" #include "AP_Mount_Servo.h" #include "AP_Mount_SoloGimbal.h" @@ -15,6 +17,7 @@ #include "AP_Mount_Scripting.h" #include "AP_Mount_Xacti.h" #include "AP_Mount_Viewpro.h" +#include "AP_Mount_Topotek.h" #include #include #include @@ -45,7 +48,7 @@ AP_Mount::AP_Mount() } _singleton = this; - AP_Param::setup_object_defaults(this, var_info); + AP_Param::setup_object_defaults(this, var_info); } // init - detect and initialise all mounts @@ -62,6 +65,9 @@ void AP_Mount::init() // primary is reset to the first instantiated mount bool primary_set = false; + // keep track of number of serial instances for initialisation + uint8_t serial_instance = 0; + // create each instance for (uint8_t instance=0; instancesend_camera_capture_status(chan); } +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Mount::send_camera_thermal_range(uint8_t instance, mavlink_channel_t chan) const +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + backend->send_camera_thermal_range(chan); +} +#endif + +// change camera settings not normally used by autopilot +// setting values from AP_Camera::Setting enum +bool AP_Mount::change_setting(uint8_t instance, CameraSetting setting, float value) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->change_setting(setting, value); +} + // get rangefinder distance. Returns true on success bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const { @@ -1014,7 +1058,10 @@ void AP_Mount::convert_params() // 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) { + if (mnt_type == 0) { + // if the mount was not previously set, no need to perform the upgrade logic + return; + } else 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)); @@ -1024,8 +1071,9 @@ void AP_Mount::convert_params() // conversion is still done even if HAL_MOUNT_SERVO_ENABLED is false mnt_type = 7; // (int8_t)Type::BrushlessPWM; } + // if the mount was previously set, then we need to save the upgraded mount type + _params[0].type.set_and_save(mnt_type); } - _params[0].type.set_and_save(mnt_type); // convert MNT_JSTICK_SPD to MNT1_RC_RATE int8_t jstick_spd = 0; diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index d67526302a643e..54762e915307fc 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -47,6 +47,7 @@ class AP_Mount_Siyi; class AP_Mount_Scripting; class AP_Mount_Xacti; class AP_Mount_Viewpro; +class AP_Mount_Topotek; /* This is a workaround to allow the MAVLink backend access to the @@ -67,6 +68,7 @@ class AP_Mount friend class AP_Mount_Scripting; friend class AP_Mount_Xacti; friend class AP_Mount_Viewpro; + friend class AP_Mount_Topotek; public: AP_Mount(); @@ -114,6 +116,9 @@ class AP_Mount #endif #if HAL_MOUNT_VIEWPRO_ENABLED Viewpro = 11, /// Viewpro gimbal using a custom serial protocol +#endif +#if HAL_MOUNT_TOPOTEK_ENABLED + Topotek = 12, /// Topotek gimbal using a custom serial protocol #endif }; @@ -157,6 +162,7 @@ class AP_Mount void set_yaw_lock(uint8_t instance, bool yaw_lock); // set angle target in degrees + // roll and pitch are in earth-frame // 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); @@ -265,6 +271,15 @@ class AP_Mount // send camera capture status message to GCS void send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const; +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(uint8_t instance, mavlink_channel_t chan) const; +#endif + + // change camera settings not normally used by autopilot + // setting values from AP_Camera::Setting enum + bool change_setting(uint8_t instance, CameraSetting setting, float value); + // // rangefinder // diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index a08eccf34fd8ae..79a8a5eaf0586c 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -1,8 +1,62 @@ -#include "AP_Mount_Alexmos.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_ALEXMOS_ENABLED + +#include "AP_Mount_Alexmos.h" + #include +//definition of the commands id for the Alexmos Serial Protocol +#define CMD_READ_PARAMS 'R' +#define CMD_WRITE_PARAMS 'W' +#define CMD_REALTIME_DATA 'D' +#define CMD_BOARD_INFO 'V' +#define CMD_CALIB_ACC 'A' +#define CMD_CALIB_GYRO 'g' +#define CMD_CALIB_EXT_GAIN 'G' +#define CMD_USE_DEFAULTS 'F' +#define CMD_CALIB_POLES 'P' +#define CMD_RESET 'r' +#define CMD_HELPER_DATA 'H' +#define CMD_CALIB_OFFSET 'O' +#define CMD_CALIB_BAT 'B' +#define CMD_MOTORS_ON 'M' +#define CMD_MOTORS_OFF 'm' +#define CMD_CONTROL 'C' +#define CMD_TRIGGER_PIN 'T' +#define CMD_EXECUTE_MENU 'E' +#define CMD_GET_ANGLES 'I' +#define CMD_CONFIRM 'C' +// Board v3.x only +#define CMD_BOARD_INFO_3 20 +#define CMD_READ_PARAMS_3 21 +#define CMD_WRITE_PARAMS_3 22 +#define CMD_REALTIME_DATA_3 23 +#define CMD_SELECT_IMU_3 24 +#define CMD_READ_PROFILE_NAMES 28 +#define CMD_WRITE_PROFILE_NAMES 29 +#define CMD_QUEUE_PARAMS_INFO_3 30 +#define CMD_SET_PARAMS_3 31 +#define CMD_SAVE_PARAMS_3 32 +#define CMD_READ_PARAMS_EXT 33 +#define CMD_WRITE_PARAMS_EXT 34 +#define CMD_AUTO_PID 35 +#define CMD_SERVO_OUT 36 +#define CMD_ERROR 255 + +#define AP_MOUNT_ALEXMOS_MODE_NO_CONTROL 0 +#define AP_MOUNT_ALEXMOS_MODE_SPEED 1 +#define AP_MOUNT_ALEXMOS_MODE_ANGLE 2 +#define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3 +#define AP_MOUNT_ALEXMOS_MODE_RC 4 + +#define AP_MOUNT_ALEXMOS_SPEED 30 // deg/s + +#define INT14_DEGREES (360.0f / float(0x3FFF)) // 1 full rotation in degrees over 14 bit range +#define VALUE_TO_DEGREE(d) (float(d)*INT14_DEGREES) +#define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/INT14_DEGREES))) +#define DEGREE_PER_SEC_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.1220740379f))) + void AP_Mount_Alexmos::init() { const AP_SerialManager& serial_manager = AP::serialmanager(); @@ -49,20 +103,9 @@ void AP_Mount_Alexmos::update() 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 6485073dd4f5cb..10225afa7255d1 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -3,63 +3,16 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_ALEXMOS_ENABLED + +#include "AP_Mount_Backend.h" + #include #include #include -//definition of the commands id for the Alexmos Serial Protocol -#define CMD_READ_PARAMS 'R' -#define CMD_WRITE_PARAMS 'W' -#define CMD_REALTIME_DATA 'D' -#define CMD_BOARD_INFO 'V' -#define CMD_CALIB_ACC 'A' -#define CMD_CALIB_GYRO 'g' -#define CMD_CALIB_EXT_GAIN 'G' -#define CMD_USE_DEFAULTS 'F' -#define CMD_CALIB_POLES 'P' -#define CMD_RESET 'r' -#define CMD_HELPER_DATA 'H' -#define CMD_CALIB_OFFSET 'O' -#define CMD_CALIB_BAT 'B' -#define CMD_MOTORS_ON 'M' -#define CMD_MOTORS_OFF 'm' -#define CMD_CONTROL 'C' -#define CMD_TRIGGER_PIN 'T' -#define CMD_EXECUTE_MENU 'E' -#define CMD_GET_ANGLES 'I' -#define CMD_CONFIRM 'C' -// Board v3.x only -#define CMD_BOARD_INFO_3 20 -#define CMD_READ_PARAMS_3 21 -#define CMD_WRITE_PARAMS_3 22 -#define CMD_REALTIME_DATA_3 23 -#define CMD_SELECT_IMU_3 24 -#define CMD_READ_PROFILE_NAMES 28 -#define CMD_WRITE_PROFILE_NAMES 29 -#define CMD_QUEUE_PARAMS_INFO_3 30 -#define CMD_SET_PARAMS_3 31 -#define CMD_SAVE_PARAMS_3 32 -#define CMD_READ_PARAMS_EXT 33 -#define CMD_WRITE_PARAMS_EXT 34 -#define CMD_AUTO_PID 35 -#define CMD_SERVO_OUT 36 -#define CMD_ERROR 255 - -#define AP_MOUNT_ALEXMOS_MODE_NO_CONTROL 0 -#define AP_MOUNT_ALEXMOS_MODE_SPEED 1 -#define AP_MOUNT_ALEXMOS_MODE_ANGLE 2 -#define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3 -#define AP_MOUNT_ALEXMOS_MODE_RC 4 - -#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))) -#define DEGREE_PER_SEC_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.1220740379f))) - class AP_Mount_Alexmos : public AP_Mount_Backend { public: diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 5fc2a3cff03391..531d01c30a6e36 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -1,5 +1,9 @@ -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" + #if HAL_MOUNT_ENABLED + +#include "AP_Mount_Backend.h" + #include #include #include @@ -66,7 +70,31 @@ bool AP_Mount_Backend::set_mode(MAV_MOUNT_MODE mode) return true; } +// called when mount mode is RC-targetting, updates the mnt_target object from RC inputs: +void AP_Mount_Backend::update_mnt_target_from_rc_target() +{ + if (rc().in_rc_failsafe()) { + if (option_set(Options::NEUTRAL_ON_RC_FS)) { + mnt_target.angle_rad.set(_params.neutral_angles.get() * DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; + return; + } + } + + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; + } +} + // set angle target in degrees +// roll and pitch are in earth-frame // 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) { @@ -277,8 +305,8 @@ void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packe { switch (get_mode()) { case MAV_MOUNT_MODE_MAVLINK_TARGETING: - // input_a : Pitch in centi-degrees - // input_b : Roll in centi-degrees + // input_a : Pitch in centi-degrees (earth-frame) + // input_b : Roll in centi-degrees (earth-frame) // 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; @@ -325,10 +353,10 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_comma return MAV_RESULT_ACCEPTED; 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 + // set target angles (in degrees) from mavlink message + const float pitch_deg = packet.param1; // param1: pitch (earth-frame, degrees) + const float roll_deg = packet.param2; // param2: roll (earth-frame, degrees) + const float yaw_deg = packet.param3; // param3: yaw (body-frame, degrees) // 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)) { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 56706d7463c98e..67b673d656ebeb 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -84,6 +84,7 @@ class AP_Mount_Backend void set_yaw_lock(bool yaw_lock) { _yaw_lock = yaw_lock; } // set angle target in degrees + // roll and pitch are in earth-frame // 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); @@ -197,6 +198,14 @@ class AP_Mount_Backend // send camera capture status message to GCS virtual void send_camera_capture_status(mavlink_channel_t chan) const {} +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // send camera thermal status message to GCS + virtual void send_camera_thermal_range(mavlink_channel_t chan) const {} +#endif + + // change camera settings not normally used by autopilot + virtual bool change_setting(CameraSetting setting, float value) { return false; } + #if AP_MOUNT_POI_TO_LATLONALT_ENABLED // get poi information. Returns true on success and fills in gimbal attitude, location and poi location bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc); @@ -240,9 +249,21 @@ class AP_Mount_Backend // options parameter bitmask handling enum class Options : uint8_t { RCTARGETING_LOCK_FROM_PREVMODE = (1U << 0), // RC_TARGETING mode's lock/follow state maintained from previous mode + NEUTRAL_ON_RC_FS = (1U << 1), // move mount to netral position on RC failsafe }; bool option_set(Options opt) const { return (_params.options.get() & (uint8_t)opt) != 0; } + // called when mount mode is RC-targetting, updates the mnt_target object from RC inputs: + void update_mnt_target_from_rc_target(); + + // returns true if user has configured a valid roll angle range + // allows user to disable roll even on 3-axis gimbal + bool roll_range_valid() const { return (_params.roll_angle_min < _params.roll_angle_max); } + + // returns true if user has configured a valid pitch angle range + // allows user to disable pitch even on 3-axis gimbal + bool pitch_range_valid() const { return (_params.pitch_angle_min < _params.pitch_angle_max); } + // 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); } diff --git a/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp b/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp new file mode 100644 index 00000000000000..35fe60265b6a72 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp @@ -0,0 +1,27 @@ +#include "AP_Mount_config.h" + +#if HAL_MOUNT_ENABLED + +#include "AP_Mount_Backend_Serial.h" + +#include + +// Default init function for every mount +void AP_Mount_Backend_Serial::init() +{ + const AP_SerialManager& serial_manager = AP::serialmanager(); + + // search for serial port. hild classes should check that uart is not nullptr + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, _serial_instance); + if (_uart == nullptr) { + return; + } + + // initialised successfully if uart is found + _initialised = true; + + // call the parent class init + AP_Mount_Backend::init(); +} + +#endif // HAL_MOUNT_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Backend_Serial.h b/libraries/AP_Mount/AP_Mount_Backend_Serial.h new file mode 100644 index 00000000000000..49fd2a50bdeb75 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Backend_Serial.h @@ -0,0 +1,48 @@ +/* + 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 . + */ + +/* + Mount driver backend class for serial drivers + Mounts using custom serial protocols should be derived from this class + */ +#pragma once + +#include "AP_Mount_config.h" + +#if HAL_MOUNT_ENABLED + +#include "AP_Mount_Backend.h" + +class AP_Mount_Backend_Serial : public AP_Mount_Backend +{ +public: + // Constructor + AP_Mount_Backend_Serial(class AP_Mount &frontend, class AP_Mount_Params ¶ms, uint8_t instance, uint8_t serial_instance) : + AP_Mount_Backend(frontend, params, instance), + _serial_instance(serial_instance) + {} + + // perform any required initialisation for this instance + void init() override; + +protected: + + // internal variables + AP_HAL::UARTDriver *_uart; // uart connected to gimbal + uint8_t _serial_instance; // this instance's serial instance number + bool _initialised; // true if uart has been initialised +}; + +#endif // HAL_MOUNT_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp index 6efe6b7ec4b39e..9e88a32417a7ef 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.cpp +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -1,7 +1,9 @@ -#include "AP_Mount_Gremsy.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_GREMSY_ENABLED +#include "AP_Mount_Gremsy.h" + #include #include @@ -48,20 +50,9 @@ void AP_Mount_Gremsy::update() } // 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -202,7 +193,7 @@ void AP_Mount_Gremsy::handle_gimbal_device_information(const mavlink_message_t & 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", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: %s %s fw:%u.%u.%u.%u", info.vendor_name, info.model_name, (unsigned)fw_ver_major, diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.h b/libraries/AP_Mount/AP_Mount_Gremsy.h index 79bd42af77670a..581eda36908ab9 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.h +++ b/libraries/AP_Mount/AP_Mount_Gremsy.h @@ -3,10 +3,12 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_GREMSY_ENABLED +#include "AP_Mount_Backend.h" + #include #include #include diff --git a/libraries/AP_Mount/AP_Mount_Params.cpp b/libraries/AP_Mount/AP_Mount_Params.cpp index 57257eb5e4e2be..d077c603ec9767 100644 --- a/libraries/AP_Mount/AP_Mount_Params.cpp +++ b/libraries/AP_Mount/AP_Mount_Params.cpp @@ -9,7 +9,7 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = { // @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, 9:Scripting, 10:Xacti, 11:Viewpro + // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial, 6:Gremsy, 7:BrushlessPWM, 8:Siyi, 9:Scripting, 10:Xacti, 11:Viewpro, 12:Topotek // @RebootRequired: True // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Mount_Params, type, 0, AP_PARAM_FLAG_ENABLE), @@ -168,7 +168,7 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = { // @Param: _OPTIONS // @DisplayName: Mount options // @Description: Mount options bitmask - // @Bitmask: 0:RC lock state from previous mode + // @Bitmask: 0:RC lock state from previous mode, 1:Return to neutral angles on RC failsafe // @User: Standard AP_GROUPINFO("_OPTIONS", 16, AP_Mount_Params, options, 0), diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index 333bac05775059..71875ad1592dca 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -1,6 +1,9 @@ -#include "AP_Mount_SToRM32.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_STORM32MAVLINK_ENABLED + +#include "AP_Mount_SToRM32.h" + #include #include @@ -52,21 +55,10 @@ void AP_Mount_SToRM32::update() 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); resend_now = true; break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -128,7 +120,7 @@ void AP_Mount_SToRM32::find_gimbal() if (GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_GIMBAL, compid, _sysid, _chan)) { _compid = compid; _initialised = true; - gcs().send_text(MAV_SEVERITY_INFO, "Mount: SToRM32"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: SToRM32"); } } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index 33aef375c410f4..6ff1a1ad1abaf2 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -3,10 +3,12 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_STORM32MAVLINK_ENABLED +#include "AP_Mount_Backend.h" + #include #include diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 928a40a297496b..ace890366352df 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -1,23 +1,12 @@ -#include "AP_Mount_SToRM32_serial.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_STORM32SERIAL_ENABLED + +#include "AP_Mount_SToRM32_serial.h" + #include #include #include -#include - -// init - performs any required initialisation for this instance -void AP_Mount_SToRM32_serial::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_port) { - _initialised = true; - } - AP_Mount_Backend::init(); - -} // update mount position - should be called periodically void AP_Mount_SToRM32_serial::update() @@ -63,21 +52,10 @@ void AP_Mount_SToRM32_serial::update() 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); resend_now = true; break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -142,7 +120,7 @@ bool AP_Mount_SToRM32_serial::can_send(bool with_control) { if (with_control) { required_tx += sizeof(AP_Mount_SToRM32_serial::cmd_set_angles_struct); } - return (_reply_type == ReplyType_UNKNOWN) && (_port->txspace() >= required_tx); + return (_reply_type == ReplyType_UNKNOWN) && (_uart->txspace() >= required_tx); } @@ -167,7 +145,7 @@ void AP_Mount_SToRM32_serial::send_target_angles(const MountTarget& angle_target return; } - if ((size_t)_port->txspace() < sizeof(cmd_set_angles_data)) { + if ((size_t)_uart->txspace() < sizeof(cmd_set_angles_data)) { return; } @@ -181,7 +159,7 @@ void AP_Mount_SToRM32_serial::send_target_angles(const MountTarget& angle_target cmd_set_angles_data.crc = crc_calculate(&buf[1], sizeof(cmd_set_angles_data)-3); for (uint8_t i = 0; i != sizeof(cmd_set_angles_data) ; i++) { - _port->write(buf[i]); + _uart->write(buf[i]); } // store time of send @@ -194,11 +172,11 @@ void AP_Mount_SToRM32_serial::get_angles() { return; } - if (_port->txspace() < 1) { + if (_uart->txspace() < 1) { return; } - _port->write('d'); + _uart->write('d'); }; @@ -220,14 +198,14 @@ void AP_Mount_SToRM32_serial::read_incoming() { uint8_t data; int16_t numc; - numc = _port->available(); + numc = _uart->available(); if (numc < 0 ) { return; } for (int16_t i = 0; i < numc; i++) { // Process bytes received - data = _port->read(); + data = _uart->read(); if (_reply_type == ReplyType_UNKNOWN) { continue; } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index e6632ca10eb8bc..07b3d3d165de8b 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -3,25 +3,24 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_STORM32SERIAL_ENABLED +#include "AP_Mount_Backend_Serial.h" + #include #include #include #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second -class AP_Mount_SToRM32_serial : public AP_Mount_Backend +class AP_Mount_SToRM32_serial : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; - - // init - performs any required initialisation for this instance - void init() override; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; // update mount position - should be called periodically void update() override; @@ -127,11 +126,7 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend // internal variables - AP_HAL::UARTDriver *_port; - - bool _initialised; // true once the driver has been initialised uint32_t _last_send; // system time of last do_mount_control sent to gimbal - uint8_t _reply_length; uint8_t _reply_counter; ReplyType _reply_type = ReplyType_UNKNOWN; diff --git a/libraries/AP_Mount/AP_Mount_Scripting.cpp b/libraries/AP_Mount/AP_Mount_Scripting.cpp index c2b93304e67ee5..165d0d1a58a072 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.cpp +++ b/libraries/AP_Mount/AP_Mount_Scripting.cpp @@ -1,6 +1,9 @@ -#include "AP_Mount_Scripting.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_SCRIPTING_ENABLED + +#include "AP_Mount_Scripting.h" + #include #include #include @@ -45,21 +48,10 @@ void AP_Mount_Scripting::update() 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); target_loc_valid = false; break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: diff --git a/libraries/AP_Mount/AP_Mount_Scripting.h b/libraries/AP_Mount/AP_Mount_Scripting.h index ecf1f7cbd89c72..52537f171dd1f0 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.h +++ b/libraries/AP_Mount/AP_Mount_Scripting.h @@ -4,10 +4,12 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_SCRIPTING_ENABLED +#include "AP_Mount_Backend.h" + #include #include #include @@ -50,4 +52,4 @@ class AP_Mount_Scripting : public AP_Mount_Backend bool target_loc_valid; // true if target_loc holds a valid target location }; -#endif // HAL_MOUNT_SIYISERIAL_ENABLED +#endif // HAL_MOUNT_SCRIPTING_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 2f926c7d848a38..f2446c2af7a5f6 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -1,6 +1,9 @@ -#include "AP_Mount_Servo.h" +#include "AP_Mount_config.h" + #if HAL_MOUNT_SERVO_ENABLED +#include "AP_Mount_Servo.h" + #include #include @@ -55,20 +58,9 @@ void AP_Mount_Servo::update() } // 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -119,6 +111,18 @@ void AP_Mount_Servo::update() move_servo(_pan_idx, degrees(_angle_bf_output_rad.z)*10, _params.yaw_angle_min*10, _params.yaw_angle_max*10); } +// returns true if this mount can control its roll +bool AP_Mount_Servo::has_roll_control() const +{ + return SRV_Channels::function_assigned(_roll_idx) && roll_range_valid(); +} + +// returns true if this mount can control its tilt +bool AP_Mount_Servo::has_pitch_control() const +{ + return SRV_Channels::function_assigned(_tilt_idx) && pitch_range_valid(); +} + // returns true if this mount can control its pan (required for multicopters) bool AP_Mount_Servo::has_pan_control() const { @@ -128,14 +132,23 @@ bool AP_Mount_Servo::has_pan_control() const // get attitude as a quaternion. returns true on success bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat) { - // no feedback from gimbal so simply report targets - // mnt_target.angle_rad always holds latest angle targets - - // ensure yaw target is in body-frame with limits applied - const float yaw_bf = constrain_float(mnt_target.angle_rad.get_bf_yaw(), radians(_params.yaw_angle_min), radians(_params.yaw_angle_max)); + // No feedback from gimbal so simply report demanded servo angles (which is + // not the same as target angles). + float roll_rad = 0.0f; + float pitch_rad = 0.0f; + float yaw_rad = 0.0f; + if (has_roll_control()) { + roll_rad = constrain_float(_angle_bf_output_rad.x, radians(_params.roll_angle_min), radians(_params.roll_angle_max)); + } + if (has_pitch_control()) { + pitch_rad = constrain_float(_angle_bf_output_rad.y, radians(_params.pitch_angle_min), radians(_params.pitch_angle_max)); + } + if (has_pan_control()) { + yaw_rad = constrain_float(_angle_bf_output_rad.z, radians(_params.yaw_angle_min), radians(_params.yaw_angle_max)); + } // convert to quaternion - att_quat.from_euler(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, yaw_bf}); + att_quat.from_euler(roll_rad, pitch_rad, yaw_rad); return true; } diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index 529a97bd7341c1..a1da63210bc5c3 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -3,10 +3,12 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_SERVO_ENABLED +#include "AP_Mount_Backend.h" + #include #include #include @@ -31,6 +33,12 @@ class AP_Mount_Servo : public AP_Mount_Backend // update mount position - should be called periodically void update() override; + // returns true if this mount can control its roll + bool has_roll_control() const override; + + // returns true if this mount can control its tilt + bool has_pitch_control() const override; + // returns true if this mount can control its pan (required for multicopters) bool has_pan_control() const override; diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 3f00d1caa03e3a..e16a29586de5f5 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -1,11 +1,13 @@ -#include "AP_Mount_Siyi.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_SIYI_ENABLED + +#include "AP_Mount_Siyi.h" + #include #include #include #include -#include #include extern const AP_HAL::HAL& hal; @@ -18,6 +20,7 @@ extern const AP_HAL::HAL& hal; #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_TIMEOUT_MS 1000 // timeout for health and rangefinder readings +#define AP_MOUNT_SIYI_THERM_TIMEOUT_MS 3000// timeout for temp min/max readings #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) @@ -29,23 +32,10 @@ const AP_Mount_Siyi::HWInfo AP_Mount_Siyi::hardware_lookup_table[] { {{'7','3'}, "A8"}, {{'6','B'}, "ZR10"}, {{'7','8'}, "ZR30"}, + {{'8','3'}, "ZT6"}, {{'7','A'}, "ZT30"}, }; -// 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_Gimbal, 0); - if (_uart == nullptr) { - return; - } - - _initialised = true; - AP_Mount_Backend::init(); -} - // update mount position - should be called periodically void AP_Mount_Siyi::update() { @@ -96,10 +86,15 @@ void AP_Mount_Siyi::update() _last_rangefinder_req_ms = now_ms; } +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // request thermal min/max from ZT30 or ZT6 + request_thermal_minmax(); +#endif + // send attitude to gimbal at 10Hz if (now_ms - _last_attitude_send_ms > 100) { _last_attitude_send_ms = now_ms; - send_attitude(); + send_attitude_position(); } // run zoom control @@ -129,20 +124,9 @@ void AP_Mount_Siyi::update() break; } - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's RC inputs - MountTarget rc_target; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -558,6 +542,25 @@ void AP_Mount_Siyi::process_packet() break; } +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + case SiyiCommandId::GET_TEMP_FULL_IMAGE: { + if (_parsed_msg.data_bytes_received != 12) { +#if AP_MOUNT_SIYI_DEBUG + unexpected_len = true; +#endif + break; + } + _thermal.last_update_ms = AP_HAL::millis(); + _thermal.max_C = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]) * 0.01; + _thermal.min_C = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+3], _msg_buff[_msg_buff_data_start+2]) * 0.01; + _thermal.max_pos.x = UINT16_VALUE(_msg_buff[_msg_buff_data_start+5], _msg_buff[_msg_buff_data_start+4]); + _thermal.max_pos.y = UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]); + _thermal.min_pos.x = UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]); + _thermal.min_pos.y = UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]); + break; + } +#endif + case SiyiCommandId::READ_RANGEFINDER: { _rangefinder_dist_m = UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]); _last_rangefinder_dist_ms = AP_HAL::millis(); @@ -827,7 +830,8 @@ float AP_Mount_Siyi::get_zoom_mult_max() const return 0; case HardwareModel::A2: case HardwareModel::A8: - // a8 has 6x digital zoom + case HardwareModel::ZT6: + // a8, zt6 have 6x digital zoom return 6; case HardwareModel::ZR10: case HardwareModel::ZR30: @@ -923,45 +927,55 @@ SetFocusResult AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value) // set camera lens as a value from 0 to 8 bool AP_Mount_Siyi::set_lens(uint8_t lens) { - // only supported on ZT30. sanity check lens values - if ((_hardware_model != HardwareModel::ZT30) || (lens > 8)) { - return false; + CameraImageType selected_lens; + + switch (_hardware_model) { + + case HardwareModel::ZT30: { + // maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful + static const CameraImageType cam_image_type_table[] { + CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3 + CameraImageType::MAIN_WIDEANGLE_SUB_THERMAL, // 5 + CameraImageType::MAIN_THERMAL_SUB_ZOOM, // 7 + CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE, // 0 + CameraImageType::MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM, // 1 + CameraImageType::MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL, // 2 + CameraImageType::MAIN_ZOOM_SUB_WIDEANGLE, // 4 + CameraImageType::MAIN_WIDEANGLE_SUB_ZOOM, // 6 + CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE, // 8 + }; + + // sanity check lens values + if (lens >= ARRAY_SIZE(cam_image_type_table)) { + return false; + } + selected_lens = cam_image_type_table[lens]; + break; } - // maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful - CameraImageType cam_image_type = CameraImageType::MAIN_ZOOM_SUB_THERMAL; - switch (lens) { - case 0: - cam_image_type = CameraImageType::MAIN_ZOOM_SUB_THERMAL; // 3 - break; - case 1: - cam_image_type = CameraImageType::MAIN_WIDEANGLE_SUB_THERMAL; // 5 - break; - case 2: - cam_image_type = CameraImageType::MAIN_THERMAL_SUB_ZOOM; // 7 - break; - case 3: - cam_image_type = CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE; // 0 - break; - case 4: - cam_image_type = CameraImageType::MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM; // 1 - break; - case 5: - cam_image_type = CameraImageType::MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL; // 2 - break; - case 6: - cam_image_type = CameraImageType::MAIN_ZOOM_SUB_WIDEANGLE; // 4 - break; - case 7: - cam_image_type = CameraImageType::MAIN_WIDEANGLE_SUB_ZOOM; // 6 - break; - case 8: - cam_image_type = CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE; // 8 - break; + case HardwareModel::ZT6: { + // maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful + static const CameraImageType cam_image_type_table[] { + CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3 + CameraImageType::MAIN_THERMAL_SUB_ZOOM, // 7 + CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE, // 0 + }; + + // sanity check lens values + if (lens >= ARRAY_SIZE(cam_image_type_table)) { + return false; + } + selected_lens = cam_image_type_table[lens]; + break; + } + + default: + // set lens not supported on this camera + return false; } // send desired image type to camera - return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type); + return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)selected_lens); } // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type @@ -1045,6 +1059,7 @@ void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const case HardwareModel::UNKNOWN: case HardwareModel::A2: case HardwareModel::A8: + case HardwareModel::ZT6: focal_length_mm = 21; break; case HardwareModel::ZR10: @@ -1069,8 +1084,8 @@ void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const model_name, // model_name uint8_t[32] fw_version, // firmware version uint32_t focal_length_mm, // focal_length float (mm) - 0, // sensor_size_h float (mm) - 0, // sensor_size_v float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix) 0, // lens_id uint8_t @@ -1084,7 +1099,6 @@ void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const void AP_Mount_Siyi::send_camera_settings(mavlink_channel_t chan) const { const uint8_t mode_id = (_config_info.record_status == RecordingStatus::ON) ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE; - const float NaN = nanf("0x4152"); const float zoom_mult_max = get_zoom_mult_max(); float zoom_pct = 0.0; if (is_positive(zoom_mult_max)) { @@ -1097,7 +1111,48 @@ void AP_Mount_Siyi::send_camera_settings(mavlink_channel_t chan) const AP_HAL::millis(), // time_boot_ms mode_id, // camera mode (0:image, 1:video, 2:image survey) zoom_pct, // zoomLevel float, percentage from 0 to 100, NaN if unknown - NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown + NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown +} + +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +// send camera thermal range message to GCS +void AP_Mount_Siyi::send_camera_thermal_range(mavlink_channel_t chan) const +{ + const uint32_t now_ms = AP_HAL::millis(); + bool timeout = now_ms - _thermal.last_update_ms > AP_MOUNT_SIYI_THERM_TIMEOUT_MS; + + // send CAMERA_THERMAL_RANGE message + mavlink_msg_camera_thermal_range_send( + chan, + now_ms, // time_boot_ms + _instance + 1, // video stream id (assume one-to-one mapping with camera id) + _instance + 1, // camera device id + timeout ? NaNf : _thermal.max_C, // max in degC + timeout ? NaNf : _thermal.max_pos.x, // max x position + timeout ? NaNf : _thermal.max_pos.y, // max y position + timeout ? NaNf : _thermal.min_C, // min in degC + timeout ? NaNf : _thermal.min_pos.x, // min x position + timeout ? NaNf : _thermal.min_pos.y);// min y position +} +#endif + +// change camera settings not normally used by autopilot +// THERMAL_PALETTE: 0:WhiteHot, 2:Sepia, 3:IronBow, 4:Rainbow, 5:Night, 6:Aurora, 7:RedHot, 8:Jungle, 9:Medical, 10:BlackHot, 11:GloryHot +// THERMAL_GAIN: 0:Low gain (50C ~ 550C), 1:High gain (-20C ~ 150C) +// THERMAL_RAW_DATA: 0:Disable Raw Data (30fps), 1:Enable Raw Data (25fps) +bool AP_Mount_Siyi::change_setting(CameraSetting setting, float value) +{ + switch (setting) { + case CameraSetting::THERMAL_PALETTE: + return send_1byte_packet(SiyiCommandId::SET_THERMAL_PALETTE, (uint8_t)value); + case CameraSetting::THERMAL_GAIN: + return send_1byte_packet(SiyiCommandId::SET_THERMAL_GAIN, (uint8_t)value); + case CameraSetting::THERMAL_RAW_DATA: + return send_1byte_packet(SiyiCommandId::SET_THERMAL_RAW_DATA, (uint8_t)value); + } + + // invalid setting so return false + return false; } // get model name string. returns "Unknown" if hardware model is not yet known @@ -1152,6 +1207,7 @@ void AP_Mount_Siyi::check_firmware_version() const case HardwareModel::A2: case HardwareModel::ZR10: case HardwareModel::ZR30: + case HardwareModel::ZT6: case HardwareModel::ZT30: // TBD break; @@ -1175,10 +1231,31 @@ void AP_Mount_Siyi::check_firmware_version() const } } +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +// get thermal min/max if available at 5hz +void AP_Mount_Siyi::request_thermal_minmax() +{ + // only supported on ZT6 and ZT30 + if (_hardware_model != HardwareModel::ZT6 && + _hardware_model != HardwareModel::ZT30) { + return; + } + + // check for timeout + uint32_t now_ms = AP_HAL::millis(); + if ((now_ms - _thermal.last_update_ms > AP_MOUNT_SIYI_THERM_TIMEOUT_MS) && + (now_ms - _thermal.last_req_ms > AP_MOUNT_SIYI_THERM_TIMEOUT_MS)) { + // request thermal min/max at 5hz + send_1byte_packet(SiyiCommandId::GET_TEMP_FULL_IMAGE, 2); + _thermal.last_req_ms = now_ms; + } +} +#endif + /* - send ArduPilot attitude to gimbal + send ArduPilot attitude and position to gimbal */ -void AP_Mount_Siyi::send_attitude(void) +void AP_Mount_Siyi::send_attitude_position(void) { const auto &ahrs = AP::ahrs(); struct { @@ -1200,6 +1277,35 @@ void AP_Mount_Siyi::send_attitude(void) attitude.yawspeed = gyro.z; send_packet(SiyiCommandId::EXTERNAL_ATTITUDE, (const uint8_t *)&attitude, sizeof(attitude)); + + // send location and velocity + struct { + uint32_t time_boot_ms; + int32_t lat, lon; + int32_t alt_msl, alt_ellipsoid; + Vector3l velocity_ned_int32; + } position; + Location loc; + Vector3f velocity_ned; + float undulation = 0; + if (!ahrs.get_location(loc) || + !ahrs.get_velocity_NED(velocity_ned)) { + return; + } + AP::gps().get_undulation(undulation); + + position.time_boot_ms = now_ms; + position.lat = loc.lat; + position.lon = loc.lng; + position.alt_msl = loc.alt; + position.alt_ellipsoid = position.alt_msl - undulation*100; + + // convert velocity to int32 and scale to mm/s + position.velocity_ned_int32.x = velocity_ned.x * 1000; + position.velocity_ned_int32.y = velocity_ned.y * 1000; + position.velocity_ned_int32.z = velocity_ned.z * 1000; + + send_packet(SiyiCommandId::POSITION_DATA, (const uint8_t *)&position, sizeof(position)); } #endif // HAL_MOUNT_SIYI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 75a03efda3271d..7f7f280b224aa1 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -19,29 +19,28 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_SIYI_ENABLED +#include "AP_Mount_Backend_Serial.h" + #include #include #include -#define AP_MOUNT_SIYI_PACKETLEN_MAX 38 // maximum number of bytes in a packet sent to or received from the gimbal +#define AP_MOUNT_SIYI_PACKETLEN_MAX 42 // maximum number of bytes in a packet sent to or received from the gimbal -class AP_Mount_Siyi : public AP_Mount_Backend +class AP_Mount_Siyi : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; /* 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; @@ -85,6 +84,17 @@ class AP_Mount_Siyi : public AP_Mount_Backend // send camera settings message to GCS void send_camera_settings(mavlink_channel_t chan) const override; +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // send camera thermal range message to GCS + void send_camera_thermal_range(mavlink_channel_t chan) const override; +#endif + + // change camera settings not normally used by autopilot + // THERMAL_PALETTE: 0:WhiteHot, 2:Sepia, 3:IronBow, 4:Rainbow, 5:Night, 6:Aurora, 7:RedHot, 8:Jungle, 9:Medical, 10:BlackHot, 11:GloryHot + // THERMAL_GAIN: 0:Low gain (50C ~ 550C), 1:High gain (-20C ~ 150C) + // THERMAL_RAW_DATA: 0:Disable Raw Data (30fps), 1:Enable Raw Data (25fps) + bool change_setting(CameraSetting setting, float value) override; + // // rangefinder // @@ -120,9 +130,14 @@ class AP_Mount_Siyi : public AP_Mount_Backend ACQUIRE_GIMBAL_ATTITUDE = 0x0D, ABSOLUTE_ZOOM = 0x0F, SET_CAMERA_IMAGE_TYPE = 0x11, + GET_TEMP_FULL_IMAGE = 0x14, READ_RANGEFINDER = 0x15, + SET_THERMAL_PALETTE = 0x1B, EXTERNAL_ATTITUDE = 0x22, SET_TIME = 0x30, + SET_THERMAL_RAW_DATA = 0x34, + SET_THERMAL_GAIN = 0x38, + POSITION_DATA = 0x3e, }; // Function Feedback Info packet info_type values @@ -166,6 +181,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend A8, ZR10, ZR30, + ZT6, ZT30 } _hardware_model; @@ -292,9 +308,12 @@ class AP_Mount_Siyi : public AP_Mount_Backend // Checks that the firmware version on the Gimbal meets the minimum supported version. void check_firmware_version() const; +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // get thermal min/max if available at 5hz + void request_thermal_minmax(); +#endif + // internal variables - AP_HAL::UARTDriver *_uart; // uart connected to gimbal - bool _initialised; // true once the driver has been initialised bool _got_hardware_id; // true once hardware id ha been received FirmwareVersion _fw_version; // firmware version (for reporting for GCS) @@ -337,9 +356,9 @@ class AP_Mount_Siyi : public AP_Mount_Backend uint32_t _last_rangefinder_dist_ms; // system time of last successful read of rangefinder distance float _rangefinder_dist_m; // distance received from rangefinder - // sending of attitude to gimbal + // sending of attitude and position to gimbal uint32_t _last_attitude_send_ms; - void send_attitude(void); + void send_attitude_position(void); // hardware lookup table indexed by HardwareModel enum values (see above) struct HWInfo { @@ -348,8 +367,20 @@ class AP_Mount_Siyi : public AP_Mount_Backend }; static const HWInfo hardware_lookup_table[]; +#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED + // thermal variables + struct { + uint32_t last_req_ms; // system time of last request for thermal min/max temperatures + uint32_t last_update_ms; // system time of last update of thermal min/max temperatures + float max_C; // thermal max temp in C + float min_C; // thermal min temp in C + Vector2ui max_pos; // thermal max temp position on image in pixels. x=0 is left, y=0 is top + Vector2ui min_pos; // thermal min temp position on image in pixels. x=0 is left, y=0 is top + } _thermal; +#endif + // count of SET_TIME packets, we send 5 times to cope with packet loss uint8_t sent_time_count; }; -#endif // HAL_MOUNT_SIYISERIAL_ENABLED +#endif // HAL_MOUNT_SIYI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index b188f945a2f23f..251c859693b2d3 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -1,6 +1,9 @@ -#include "AP_Mount_SoloGimbal.h" +#include "AP_Mount_config.h" + #if HAL_SOLO_GIMBAL_ENABLED +#include "AP_Mount_SoloGimbal.h" + #include "SoloGimbal.h" #include #include @@ -62,20 +65,10 @@ void AP_Mount_SoloGimbal::update() 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); - MountTarget rc_target; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 4e64233284a9fd..ed32e6697bef67 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -3,18 +3,16 @@ */ #pragma once +#include "AP_Mount_config.h" -#include +#if HAL_SOLO_GIMBAL_ENABLED #include "AP_Mount_Backend.h" -#if HAL_SOLO_GIMBAL_ENABLED #include #include #include -#include #include "SoloGimbal.h" - class AP_Mount_SoloGimbal : public AP_Mount_Backend { diff --git a/libraries/AP_Mount/AP_Mount_Topotek.cpp b/libraries/AP_Mount/AP_Mount_Topotek.cpp new file mode 100755 index 00000000000000..4e468a7ae51733 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Topotek.cpp @@ -0,0 +1,1226 @@ +#include "AP_Mount_config.h" + +#if HAL_MOUNT_TOPOTEK_ENABLED + +#include "AP_Mount_Topotek.h" + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define ANGULAR_VELOCITY_CONVERSION 1.220740379 // gimbal angular velocity conversion ratio +#define TRACK_TOTAL_WIDTH 1920 // track the maximum width of the image range +#define TRACK_TOTAL_HEIGHT 1080 // track the maximum height of the image range +#define TRACK_RANGE 60 // the size of the image at point tracking +#define AP_MOUNT_TOPOTEK_UPDATE_INTERVAL_MS 100 // resend angle or rate targets to gimbal at this interval +#define AP_MOUNT_TOPOTEK_HEALTH_TIMEOUT_MS 1000 // timeout for health and rangefinder readings +#define AP_MOUNT_TOPOTEK_PACKETLEN_MIN 12 // packet length not including the data segment +#define AP_MOUNT_TOPOTEK_DATALEN_MAX (AP_MOUNT_TOPOTEK_PACKETLEN_MAX - AP_MOUNT_TOPOTEK_PACKETLEN_MIN) // data segment lens can be no more tha this + +// 3 character identifiers +# define AP_MOUNT_TOPOTEK_ID3CHAR_CAPTURE "CAP" // take picture, data bytes: 01:RGB + thermal, 02:RGB, 03:thermal, 05:RGB + thermal (with temp measurement) +# define AP_MOUNT_TOPOTEK_ID3CHAR_RECORD_VIDEO "REC" // record video, data bytes: 00:stop, 01:start, 0A:toggle start/stop +# define AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_ZOOM "ZMC" // control zoom, data bytes: 00:stop, 01:zoom out, 02:zoom in +# define AP_MOUNT_TOPOTEK_ID3CHAR_GET_ZOOM "ZOM" // get zoom, no data bytes +# define AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_FOCUS "FCC" // control focus, data bytes: 00:stop, 01:focus+, 02:focus-, 0x10:auto focus, 0x11:manual focus, 0x12:manu focus (save), 0x13:auto focus (save) +# define AP_MOUNT_TOPOTEK_ID3CHAR_GET_FOCUS "FOC" // get focus, no data bytes +# define AP_MOUNT_TOPOTEK_ID3CHAR_SET_ZOOM_AND_FOCU "ZFP" // set zoom and focus +# define AP_MOUNT_TOPOTEK_ID3CHAR_DAY_NIGHT_SWITCHING "IRC" // set day/night setting, data bytes: 00:day, 01:night, 0A:toggle state +# define AP_MOUNT_TOPOTEK_ID3CHAR_TRACKING "TRC" // get/set image tracking, data bytes: 00:get status (use with "r"), 01:stop (use with "w") +# define AP_MOUNT_TOPOTEK_ID3CHAR_START_TRACKING "LOC" // start image tracking +# define AP_MOUNT_TOPOTEK_ID3CHAR_LRF "LRF" // laser rangefinder control, data bytes: 00:ranging stop, 01:ranging start, 02:single measurement, 03:continuous measurement +# define AP_MOUNT_TOPOTEK_ID3CHAR_PIP "PIP" // set picture-in-picture setting, data bytes: // 00:main only, 01:main+sub, 02:sub+main, 03:sub only, 0A:next +# define AP_MOUNT_TOPOTEK_ID3CHAR_GIMBAL_ATT "GIA" // get gimbal attitude, data bytes: 00:stop, 01:start +# define AP_MOUNT_TOPOTEK_ID3CHAR_SD_CARD "SDC" // get SD card state, data bytes: 00:get remaining capacity, 01:get total capacity +# define AP_MOUNT_TOPOTEK_ID3CHAR_TIME "UTC" // set time and date, data bytes: HHMMSSDDMMYY +# define AP_MOUNT_TOPOTEK_ID3CHAR_GET_VERSION "VSN" // get firmware version, data bytes always 00 +# define AP_MOUNT_TOPOTEK_ID3CHAR_GET_MODEL_NAME "PA2" // get model name, data bytes always 00 +# define AP_MOUNT_TOPOTEK_ID3CHAR_GIMBAL_MODE "PTZ" // set gimbal mode, data bytes: 00:stop, 01:up, 02:down, 03:left, 04:right, 05:home position, 06:lock, 07:follow, 08:lock/follow toggle, 09:calibration, 0A:one button down +# define AP_MOUNT_TOPOTEK_ID3CHAR_YPR_RATE "YPR" // set the rate yaw, pitch and roll targets of the gimbal yaw in range -99 ~ +99 +# define AP_MOUNT_TOPOTEK_ID3CHAR_YAW_ANGLE "GIY" // set the yaw angle target in the range -150 ~ 150, speed 0 ~ 99 (0.1deg/sec) +# define AP_MOUNT_TOPOTEK_ID3CHAR_YAW_ANGLE_BF "GAY" // set the yaw angle target in body-frame in the range -150 ~ 150, speed 0 ~ 99 (0.1deg/sec) +# define AP_MOUNT_TOPOTEK_ID3CHAR_PITCH_ANGLE "GIP" // set the pitch angle target in the range -90 ~ 90, speed 0 ~ 99 (0.1deg/sec) +# define AP_MOUNT_TOPOTEK_ID3CHAR_ROLL_ANGLE "GIR" // set the roll angle target in the range -90 ~ 90, speed 0 ~ 99 (0.1deg/sec) +# define AP_MOUNT_TOPOTEK_ID3CHAR_SET_LAT "LAT" // set the gimbal's latitude +# define AP_MOUNT_TOPOTEK_ID3CHAR_SET_LON "LON" // set the gimbal's longitude +# define AP_MOUNT_TOPOTEK_ID3CHAR_SET_ALT "ALT" // set the gimbal's altitude +# define AP_MOUNT_TOPOTEK_ID3CHAR_SET_AZIMUTH "AZI" // set the gimbal's yaw (aka azimuth) + +#define AP_MOUNT_TOPOTEK_DEBUG 0 +#define debug(fmt, args ...) do { if (AP_MOUNT_TOPOTEK_DEBUG) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Topotek: " fmt, ## args); } } while (0) + +const char* AP_Mount_Topotek::send_message_prefix = "Mount: Topotek"; + +// update mount position - should be called periodically +void AP_Mount_Topotek::update() +{ + // exit immediately if not initialised + if (!_initialised) { + return; + } + + // reading incoming packets from gimbal + read_incoming_packets(); + + // everything below updates at 10hz + uint32_t now_ms = AP_HAL::millis(); + if ((now_ms - _last_req_current_info_ms) < 100) { + return; + } + _last_req_current_info_ms = now_ms; + + // re-send the stop zoom command a second time to prevent data transmission errors. + if (_last_zoom_stop) { + _last_zoom_stop = false; + send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_ZOOM, true, 0); + } + + // re-send the stop focus command a second time to prevent data transmission errors. + if (_last_focus_stop) { + _last_focus_stop = false; + send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_FOCUS, true, 0); + } + + // send GPS-related information to the gimbal + send_location_info(); + + // calls below here called at 1hz + _last_req_step++; + if (_last_req_step >= 10) { + _last_req_step = 0; + } + switch (_last_req_step) { + case 0: + // get gimbal version + if (!_got_gimbal_version) { + request_gimbal_version(); + } + break; + case 2: + // request gimbal attitude at 1hz + // gimbal will continue to send attitude information during the next period + request_gimbal_attitude(); + break; + case 4: + // request memory card information + request_gimbal_sdcard_info(); + break; + case 6: + // request tracking info + request_track_status(); + break; + case 8: + // get gimbal model name + if (!_got_gimbal_model_name) { + request_gimbal_model_name(); + } + break; + } + + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + + // handle tracking state + if (_is_tracking) { + // cancel tracking if mode has changed + if (_last_mode != _mode) { + _last_mode = _mode; + cancel_tracking(); + } + return; + } + _last_mode = _mode; + + // 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(); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, 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(); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); + break; + } + + // point to the angles given by a mavlink message + case MAV_MOUNT_MODE_MAVLINK_TARGETING: + // mavlink targets are stored while handling the incoming message + break; + + // RC radio manual angle control, but with stabilization from the AHRS + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); + break; + + // point mount to a GPS point given by the mission planner + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } + break; + + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } + break; + + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } + break; + + default: + // we do not know this mode so raise internal error + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + break; + } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_angle_target(mnt_target.angle_rad); + break; + case MountTargetType::RATE: + send_rate_target(mnt_target.rate_rads); + break; + } +} + +// return true if healthy +bool AP_Mount_Topotek::healthy() const +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // unhealthy if attitude information not received recently + const uint32_t last_current_angle_ms = _last_current_angle_ms; + return (AP_HAL::millis() - last_current_angle_ms < AP_MOUNT_TOPOTEK_HEALTH_TIMEOUT_MS); +} + +// take a picture. returns true on success +bool AP_Mount_Topotek::take_picture() +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // exit immediately if the memory card is abnormal + if (!_sdcard_status) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s SD card error", send_message_prefix); + return false; + } + + // sample command: #TPUD2wCAP01 + return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_CAPTURE, true, 1); +} + +// start or stop video recording. returns true on success +// set start_recording = true to start record, false to stop recording +bool AP_Mount_Topotek::record_video(bool start_recording) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // exit immediately if the memory card is abnormal + if (!_sdcard_status) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s SD card error", send_message_prefix); + return false; + } + + // sample command: #TPUD2wREC01 + return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_RECORD_VIDEO, true, start_recording ? 1 : 0); +} + +// set zoom specified as a rate +bool AP_Mount_Topotek::set_zoom(ZoomType zoom_type, float zoom_value) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // zoom rate + if (zoom_type == ZoomType::RATE) { + uint8_t zoom_cmd; + if (is_zero(zoom_value)) { + // stop zoom + zoom_cmd = 0; + _last_zoom_stop = true; + } else if (zoom_value < 0) { + // zoom out + zoom_cmd = 1; + } else { + // zoom in + zoom_cmd = 2; + } + // sample command: #TPUM2wZMC00 + return send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_ZOOM, true, zoom_cmd); + } + + // unsupported zoom type + return false; +} + +// set focus specified as rate, percentage or auto +// focus in = -1, focus hold = 0, focus out = 1 +SetFocusResult AP_Mount_Topotek::set_focus(FocusType focus_type, float focus_value) +{ + // exit immediately if not initialised + if (!_initialised) { + return SetFocusResult::FAILED; + } + + switch (focus_type) { + case FocusType::RATE: { + // focus stop + uint8_t focus_cmd; + if (is_zero(focus_value)) { + focus_cmd = 0; + _last_focus_stop = true; + } else if (focus_value < 0) { + // focus- + focus_cmd = 2; + } else { + // focus+ + focus_cmd = 1; + } + // send focus command and switch to manual focus + // sample command: #TPUM2wFCC00 + if (send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_FOCUS, true, focus_cmd) && + send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_FOCUS, true, 0x11)) { + return SetFocusResult::ACCEPTED; + } + return SetFocusResult::FAILED; + } + case FocusType::PCT: + // not supported + return SetFocusResult::INVALID_PARAMETERS; + case FocusType::AUTO: + // auto focus + if (send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_CONTROL_FOCUS, true, 0x10)) { + return SetFocusResult::ACCEPTED; + } + return SetFocusResult::FAILED; + } + + // unsupported focus type + return SetFocusResult::INVALID_PARAMETERS; +} + +// set tracking to none, point or rectangle (see TrackingType enum) +// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right +// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom +bool AP_Mount_Topotek::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // local variables holding tracker center and width + int16_t track_center_x, track_center_y, track_width, track_height; + bool send_tracking_cmd = false; + + switch (tracking_type) { + + case TrackingType::TRK_NONE: + return cancel_tracking(); + + case TrackingType::TRK_POINT: { + // calculate tracking center, width and height + track_center_x = (int16_t)((p1.x*TRACK_TOTAL_WIDTH - 960) / 0.96); + track_center_y = (int16_t)((p1.y*TRACK_TOTAL_HEIGHT - 540) / 0.54); + track_width = (int16_t)(TRACK_RANGE / 0.96); + track_height = (int16_t)(TRACK_RANGE / 0.54); + send_tracking_cmd = true; + break; + } + + case TrackingType::TRK_RECTANGLE: + // calculate upper left and bottom right points + // handle case where p1 and p2 are in an unexpected order + int16_t upper_leftx = (int16_t)(MIN(p1.x, p2.x)*TRACK_TOTAL_WIDTH); + int16_t upper_lefty = (int16_t)(MIN(p1.y, p2.y)*TRACK_TOTAL_HEIGHT); + int16_t bottom_rightx = (int16_t)(MAX(p1.x, p2.x)*TRACK_TOTAL_WIDTH); + int16_t bottom_righty = (int16_t)(MAX(p1.y, p2.y)*TRACK_TOTAL_HEIGHT); + + // calculated width and height and sanity check + const int16_t frame_selection_width = bottom_rightx - upper_leftx; + const int16_t frame_selection_height = bottom_righty - upper_lefty; + if (frame_selection_width <= 0 || frame_selection_height <= 0) { + return false; + } + + // calculate tracking center + track_center_x = (int16_t)((((upper_leftx + bottom_rightx) * 0.5) - 960) / 0.96); + track_center_y = (int16_t)((((upper_lefty + bottom_righty) * 0.5) - 540) / 0.54); + + // tracking range after conversion + track_width = (int16_t)(frame_selection_width / 0.96); + track_height = (int16_t)(frame_selection_height / 0.54); + + send_tracking_cmd = true; + break; + } + + if (send_tracking_cmd) { + // set the gimbal to the ready-to-track state when the gimbal tracking status is stopped + if (_last_tracking_state == TrackingStatus::STOPPED_TRACKING) { + send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_TRACKING, true, 2); + } + + // prepare data bytes + uint8_t databuff[10]; + databuff[0] = HIGHBYTE(track_center_x); + databuff[1] = LOWBYTE(track_center_x); + databuff[2] = HIGHBYTE(track_center_y); + databuff[3] = LOWBYTE(track_center_y); + databuff[4] = HIGHBYTE(track_width); + databuff[5] = LOWBYTE(track_width); + databuff[6] = HIGHBYTE(track_height); + databuff[7] = LOWBYTE(track_height); + databuff[8] = 0; + databuff[9] = (tracking_type == TrackingType::TRK_POINT) ? 9 : 1; // when tracking point, enable fuzzy click function + + // send tracking command + bool res = send_variablelen_packet(HeaderType::VARIABLE_LEN, + AddressByte::SYSTEM_AND_IMAGE, + AP_MOUNT_TOPOTEK_ID3CHAR_START_TRACKING, + true, + (uint8_t*)databuff, ARRAY_SIZE(databuff)); + + // display error message on failure + if (!res) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s tracking failed", send_message_prefix); + } + + return res; + } + + // should never reach here + return false; +} + +// send command to gimbal to cancel tracking (if necessary) +// returns true on success, false on failure to send message +bool AP_Mount_Topotek::cancel_tracking() +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // if gimbal is tracking-in-progress change to waiting state, otherwise stop + const uint8_t track_set = _last_tracking_state == TrackingStatus::TRACKING_IN_PROGRESS ? 1 : 0; + + // send tracking command + return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_TRACKING, true, track_set); +} + +// set camera picture-in-picture mode +bool AP_Mount_Topotek::set_lens(uint8_t lens) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // sanity check lens number + // 00:main only, 01:main+sub, 02:sub+main, 03:sub only, 0A:next + // sample command: #TPUD2wPIP0A + if (lens > 3) { + return false; + } + + // send pip command + return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, lens); +} + +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t +bool AP_Mount_Topotek::set_camera_source(uint8_t primary_source, uint8_t secondary_source) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // maps primary and secondary source to pip setting + // pip settings 00:main only, 01:main+sub, 02:sub+main, 03:sub only, 0A:next + // sample command: #TPUD2wPIP0A + uint8_t pip_setting = 0; + switch (primary_source) { + case 0: // Default (RGB) + FALLTHROUGH; + case 1: // RGB + switch (secondary_source) { + case 0: // RGB + Default (None) + pip_setting = 0; // main only + break; + case 2: // PIP RGB+IR + pip_setting = 1; // main+sub + break; + default: + return false; + } + break; + case 2: // IR + switch (secondary_source) { + case 0: // IR + Default (None) + pip_setting = 3; // sub only + break; + case 1: // IR+RGB + pip_setting = 2; // sub+main + break; + default: + return false; + } + break; + default: + return false; + } + + // send pip command + return send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_PIP, true, pip_setting); +} +#endif // HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED + +// send camera information message to GCS +void AP_Mount_Topotek::send_camera_information(mavlink_channel_t chan) const +{ + // exit immediately if not initialised + if (!_initialised) { + return; + } + + static const uint8_t vendor_name[32] = "Topotek"; + static uint8_t model_name[32] {}; + const char cam_definition_uri[140] {}; + + // copy model name if available + if (_got_gimbal_model_name) { + strncpy((char*)model_name, (const char*)_model_name, ARRAY_SIZE(model_name)); + } + + // capability flags + const uint32_t flags = CAMERA_CAP_FLAGS_CAPTURE_VIDEO | + CAMERA_CAP_FLAGS_CAPTURE_IMAGE | + CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM | + CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS | + CAMERA_CAP_FLAGS_HAS_TRACKING_POINT | + CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE; + + // send CAMERA_INFORMATION message + mavlink_msg_camera_information_send( + chan, + AP_HAL::millis(), // time_boot_ms + vendor_name, // vendor_name uint8_t[32] + model_name, // model_name uint8_t[32] + _firmware_ver, // firmware version uint32_t + 0, // focal_length float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) + 0, // resolution_h uint16_t (pix) + 0, // resolution_v uint16_t (pix) + 0, // lens_id uint8_t + flags, // flags uint32_t (CAMERA_CAP_FLAGS) + 0, // cam_definition_version uint16_t + cam_definition_uri, // cam_definition_uri char[140] + _instance + 1); // gimbal_device_id uint8_t +} + +// send camera settings message to GCS +void AP_Mount_Topotek::send_camera_settings(mavlink_channel_t chan) const +{ + // exit immediately if not initialised + if (!_initialised) { + return; + } + + // send CAMERA_SETTINGS message + mavlink_msg_camera_settings_send( + chan, + AP_HAL::millis(), // time_boot_ms + _recording ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) + NaNf, // zoomLevel float, percentage from 0 to 100, NaN if unknown + NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown +} + +// get rangefinder distance. Returns true on success +bool AP_Mount_Topotek::get_rangefinder_distance(float& distance_m) const +{ + // if not healthy or negative distance return false + // healthy() checks attitude timeout which is in same message as rangefinder distance + if (!healthy() || (_measure_dist_m < 0)) { + return false; + } + + distance_m = _measure_dist_m; + return true; +} + +// enable/disable rangefinder. Returns true on success +bool AP_Mount_Topotek::set_rangefinder_enable(bool enable) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // 00:ranging stop, 01:ranging start, 02:single measurement, 03:continuous measurement + // sample command: #TPUM2wLRF00 + return send_fixedlen_packet(AddressByte::LENS, AP_MOUNT_TOPOTEK_ID3CHAR_LRF, true, enable ? 3 : 0); +} + +// get attitude as a quaternion. returns true on success +bool AP_Mount_Topotek::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 +void AP_Mount_Topotek::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++) { + uint8_t b; + if (!_uart->read(b)) { + continue; + } + + // add latest byte to buffer + _msg_buff[_msg_buff_len++] = b; + + // protect against overly long messages + if (_msg_buff_len >= AP_MOUNT_TOPOTEK_PACKETLEN_MAX) { + reset_parser = true; + } + + // process byte depending upon current state + switch (_parser.state) { + + case ParseState::WAITING_FOR_HEADER1: + if (b == '#') { + _parser.state = ParseState::WAITING_FOR_HEADER2; + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_HEADER2: + if (b == 't' || b == 'T') { + _parser.state = ParseState::WAITING_FOR_HEADER3; + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_HEADER3: + if (b == 'p' || b == 'P') { + _parser.state = ParseState::WAITING_FOR_ADDR1; + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_ADDR1: + case ParseState::WAITING_FOR_ADDR2: + if (b == 'U' || b =='M' || b == 'D' || b =='E' || b =='P' || b =='G') { + // advance to next state + _parser.state = (ParseState)((uint8_t)_parser.state+1); + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_DATALEN: + // sanity check data length + _parser.data_len = (uint8_t)char_to_hex(b); + if (_parser.data_len <= AP_MOUNT_TOPOTEK_DATALEN_MAX) { + _parser.state = ParseState::WAITING_FOR_CONTROL; + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_CONTROL: + // r or w + if (b == 'r' || b == 'w') { + _parser.state = ParseState::WAITING_FOR_ID1; + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_ID1: + case ParseState::WAITING_FOR_ID2: + case ParseState::WAITING_FOR_ID3: + // check all uppercase letters and numbers. eg 'GAC' + if ((b >= 'A' && b <= 'Z') || (b >= '0' && b <= '9')) { + // advance to next state + _parser.state = (ParseState)((uint8_t)_parser.state+1); + break; + } + reset_parser = true; + break; + + case ParseState::WAITING_FOR_DATA: { + // normally hex numbers in char form (e.g. '0A') + const uint8_t data_bytes_received = _msg_buff_len - (AP_MOUNT_TOPOTEK_PACKETLEN_MIN - 2); + + // sanity check to protect against programming errors + if (data_bytes_received > AP_MOUNT_TOPOTEK_DATALEN_MAX) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + reset_parser = true; + break; + } + + // advance parser state once expected number of bytes have been received + if (data_bytes_received == _parser.data_len) { + _parser.state = ParseState::WAITING_FOR_CRC_LOW; + } + break; + } + + case ParseState::WAITING_FOR_CRC_LOW: + _parser.state = ParseState::WAITING_FOR_CRC_HIGH; + break; + + case ParseState::WAITING_FOR_CRC_HIGH: + // this is the last byte in the message so reset the parser + reset_parser = true; + + // sanity check to protect against programming errors + if (_msg_buff_len < AP_MOUNT_TOPOTEK_PACKETLEN_MIN) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + break; + } + + // calculate and check CRC + const uint8_t crc_value = calculate_crc(_msg_buff, _msg_buff_len - 2); + const char crc_char1 = hex2char((crc_value >> 4) & 0x0f); + const char crc_char2 = hex2char((crc_value) & 0x0f); + if (crc_char1 != _msg_buff[_msg_buff_len - 2] || crc_char2 != _msg_buff[_msg_buff_len-1]) { + debug("CRC expected:%x got:%c%c", (int)crc_value, crc_char1, crc_char2); + break; + } + + // CRC is OK, call function to process the message + for (uint8_t count = 0; count < AP_MOUNT_RECV_GIMBAL_CMD_CATEGORIES_NUM; count++) { + if (strncmp((const char*)_msg_buff + 7, (const char*)(uart_recv_cmd_compare_list[count].uart_cmd_key), 3) == 0) { + (this->*(uart_recv_cmd_compare_list[count].func))(); + break; + } + } + } + + // handle reset of parser + if (reset_parser) { + _parser.state = ParseState::WAITING_FOR_HEADER1; + _msg_buff_len = 0; + reset_parser = false; + } + } +} + +// request gimbal attitude +void AP_Mount_Topotek::request_gimbal_attitude() +{ + // sample command: #TPUG2wGIA01 + send_fixedlen_packet(AddressByte::GIMBAL, AP_MOUNT_TOPOTEK_ID3CHAR_GIMBAL_ATT, true, 1); +} + +// request gimbal memory card information +void AP_Mount_Topotek::request_gimbal_sdcard_info() +{ + // request remaining capacity + // sample command including CRC: #TPUD2rSDC003E + // 00:get remaining capacity, 01:get total capacity + send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_SD_CARD, false, 0); +} + +// request gimbal tracking status +void AP_Mount_Topotek::request_track_status() +{ + // 00:get status (use with "r"), 01:stop (use with "w") + // sample command: #TPUD2rTRC00 + send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_TRACKING, false, 0); +} + +// request gimbal version +void AP_Mount_Topotek::request_gimbal_version() +{ + // sample command: #TPUD2rVSN00 + send_fixedlen_packet(AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_GET_VERSION, false, 0); +} + +// request gimbal model name +void AP_Mount_Topotek::request_gimbal_model_name() +{ + // sample command: #TPUG2rPA200 + send_fixedlen_packet(AddressByte::GIMBAL, AP_MOUNT_TOPOTEK_ID3CHAR_GET_MODEL_NAME, false, 0); +} + +// send angle target in radians to gimbal +void AP_Mount_Topotek::send_angle_target(const MountTarget& angle_rad) +{ + // gimbal's earth-frame angle control drifts so always use body frame + // set gimbal's lock state if it has changed + if (!set_gimbal_lock(false)) { + return; + } + + // calculate and send yaw target + // sample command #tpUG6wGIY + const char* format_str = "%04X%02X"; + const uint8_t speed = 99; + const uint16_t yaw_angle_cd = (uint16_t)constrain_int16(degrees(angle_rad.get_bf_yaw()) * 100, MAX(-18000, _params.yaw_angle_min * 100), MIN(18000, _params.yaw_angle_max * 100)); + + uint8_t databuff[7]; + hal.util->snprintf((char *)databuff, ARRAY_SIZE(databuff), format_str, yaw_angle_cd, speed); + send_variablelen_packet(HeaderType::VARIABLE_LEN, + AddressByte::GIMBAL, + AP_MOUNT_TOPOTEK_ID3CHAR_YAW_ANGLE_BF, + true, + (uint8_t*)databuff, ARRAY_SIZE(databuff)-1); + + // send pitch target + // sample command: #tpUG6wGIP + const uint16_t pitch_angle_cd = (uint16_t)constrain_int16(-degrees(angle_rad.pitch) * 100, -9000, 9000); + hal.util->snprintf((char *)databuff, ARRAY_SIZE(databuff), format_str, pitch_angle_cd, speed); + send_variablelen_packet(HeaderType::VARIABLE_LEN, + AddressByte::GIMBAL, + AP_MOUNT_TOPOTEK_ID3CHAR_PITCH_ANGLE, + true, + (uint8_t*)databuff, ARRAY_SIZE(databuff)-1); + + // send roll target + // sample command: #tpUG6wGIR + const uint16_t roll_angle_cd = (uint16_t)constrain_int16(degrees(angle_rad.roll) * 100, -18000, 18000); + hal.util->snprintf((char *)databuff, ARRAY_SIZE(databuff), format_str, roll_angle_cd, speed); + send_variablelen_packet(HeaderType::VARIABLE_LEN, + AddressByte::GIMBAL, + AP_MOUNT_TOPOTEK_ID3CHAR_ROLL_ANGLE, + true, + (uint8_t*)databuff, ARRAY_SIZE(databuff)-1); +} + +// send rate target in rad/s to gimbal +void AP_Mount_Topotek::send_rate_target(const MountTarget& rate_rads) +{ + // set gimbal's lock state if it has changed + if (!set_gimbal_lock(rate_rads.yaw_is_ef)) { + return; + } + + // convert and constrain rates + const uint8_t roll_angle_speed = constrain_int16(degrees(rate_rads.roll) * ANGULAR_VELOCITY_CONVERSION, -99, 99); + const uint8_t pitch_angle_speed = constrain_int16(degrees(rate_rads.pitch) * ANGULAR_VELOCITY_CONVERSION, -99, 99); + const uint8_t yaw_angle_speed = constrain_int16(degrees(rate_rads.yaw) * ANGULAR_VELOCITY_CONVERSION, -99, 99); + + // send stop rotation command three times if target roll, pitch and yaw are zero + if (roll_angle_speed == 0 && pitch_angle_speed == 0 && yaw_angle_speed == 0) { + if (_stop_order_count < 3) { + // sample command: #TPUG2wPTZ00 + if (send_fixedlen_packet(AddressByte::GIMBAL, AP_MOUNT_TOPOTEK_ID3CHAR_GIMBAL_MODE, true, 0)) { + _stop_order_count++; + } + } + return; + } + _stop_order_count = 0; + + // prepare and send command + // sample command: #tpUG6wYPR + uint8_t databuff[7]; + hal.util->snprintf((char *)databuff, ARRAY_SIZE(databuff), "%02X%02X%02X", yaw_angle_speed, pitch_angle_speed, roll_angle_speed); + send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::GIMBAL, AP_MOUNT_TOPOTEK_ID3CHAR_YPR_RATE, true, databuff, ARRAY_SIZE(databuff)-1); +} + +// send time and date to gimbal +bool AP_Mount_Topotek::send_time_to_gimbal() +{ +#if AP_RTC_ENABLED + // get date and time + // year is the regular Gregorian year, month is 0~11, day is 1~31, hour is 0~23, minute is 0~59, second is 0~60 (1 leap second), ms is 0~999 + uint16_t year, ms; + uint8_t month, day, hour, min, sec; + if (!AP::rtc().get_date_and_time_utc(year, month, day, hour, min, sec, ms)) { + return false; + } + + // sample command: #tpUDCwUTCHHMMSSDDMMYY + uint8_t databuff[13]; + hal.util->snprintf((char*)databuff, ARRAY_SIZE(databuff), "%02d%02d%02d%02d%02d%02d", hour, min, sec, day, month + 1, year - 2000); + return send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_TIME, true, (uint8_t*)databuff, ARRAY_SIZE(databuff)-1); +#else + return false; +#endif +} + +// send GPS-related information to the gimbal +bool AP_Mount_Topotek::send_location_info() +{ + // get current location + Location loc; + int32_t alt_amsl_cm = 0; + if (!AP::ahrs().get_location(loc) || !loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_amsl_cm)) { + return false; + } + + // convert latitude and longitude to positive angles in degrees + const double latitude = labs(loc.lat) * 1e-7; + const double longitude = labs(loc.lng) * 1e-7; + + // get the degree part + const int16_t lat_deg = (int16_t)latitude; + const int16_t lng_deg = (int16_t)longitude; + + // get the minute part + const double lat_min = (latitude - lat_deg) * 60.0; + const double lng_min = (longitude - lng_deg) * 60.0; + + // prepare and send latitude + // first byte is N or S, followed by GPS coordinates in degree division format, in the format of ddmm.mmmm + // first byte is zero and will also be transmitted. same as the data format in $GPGGA + // sample command: #tpUDAwLATNddmm.mmmm + uint8_t databuff_lat[11]; + hal.util->snprintf((char*)databuff_lat, ARRAY_SIZE(databuff_lat), "%c%02d%07.4f", loc.lat > 0 ? 'N':'S', lat_deg, lat_min); + if (!send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_SET_LAT, true, (uint8_t*)databuff_lat, ARRAY_SIZE(databuff_lat)-1)) { + return false; + } + + // prepare and send longitude + // sample command: #tpUDBwLONEdddmm.mmmm + uint8_t databuff_lon[12]; + hal.util->snprintf((char*)databuff_lon, ARRAY_SIZE(databuff_lon), "%c%03d%07.4f", loc.lng > 0 ? 'E':'W', lng_deg, lng_min); + if (!send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_SET_LON, true, (uint8_t*)databuff_lon, ARRAY_SIZE(databuff_lon)-1)) { + return false; + } + + // get the height in meters + float alt_amsl_m = alt_amsl_cm * 0.01; + + // prepare and send vehicle altitude + // sample command: #tpUD8wALT000000.0, similar format to $GPGGA + uint8_t databuff_alt[9]; + hal.util->snprintf((char*)databuff_alt, ARRAY_SIZE(databuff_alt), "%08.1f", alt_amsl_m); + if (!send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_SET_ALT, true, (uint8_t*)databuff_alt, ARRAY_SIZE(databuff_alt)-1)) { + return false; + } + + // prepare and send vehicle yaw + // sample command: #tpUD5wAZI359.9, similar format to $GPRMC + const float veh_yaw_deg = wrap_360(degrees(AP::ahrs().get_yaw())); + uint8_t databuff_azimuth[6]; + hal.util->snprintf((char*)databuff_azimuth, ARRAY_SIZE(databuff_azimuth), "%05.1f", veh_yaw_deg); + if (!send_variablelen_packet(HeaderType::VARIABLE_LEN, AddressByte::SYSTEM_AND_IMAGE, AP_MOUNT_TOPOTEK_ID3CHAR_SET_AZIMUTH, true, (uint8_t*)databuff_azimuth, ARRAY_SIZE(databuff_azimuth)-1)) { + return false; + } + + return true; +} + +// attitude information analysis of gimbal +void AP_Mount_Topotek::gimbal_angle_analyse() +{ + // consume current angles + int16_t yaw_angle_cd = wrap_180_cd(hexchar4_to_int16(_msg_buff[10], _msg_buff[11], _msg_buff[12], _msg_buff[13])); + int16_t pitch_angle_cd = -hexchar4_to_int16(_msg_buff[14], _msg_buff[15], _msg_buff[16], _msg_buff[17]); + int16_t roll_angle_cd = hexchar4_to_int16(_msg_buff[18], _msg_buff[19], _msg_buff[20], _msg_buff[21]); + + // convert cd to radians + _current_angle_rad.x = radians(roll_angle_cd * 0.01); + _current_angle_rad.y = radians(pitch_angle_cd * 0.01); + _current_angle_rad.z = radians(yaw_angle_cd * 0.01); + _last_current_angle_ms = AP_HAL::millis(); + + return; +} + +// gimbal video information analysis +void AP_Mount_Topotek::gimbal_record_analyse() +{ + _recording = (_msg_buff[10] == '1' || _msg_buff[11] == '1'); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s recording %s", send_message_prefix, _recording ? "ON" : "OFF"); +} + +// information analysis of gimbal storage card +void AP_Mount_Topotek::gimbal_sdcard_analyse() +{ + if (('N' == _msg_buff[10]) && ('N' == _msg_buff[11]) && ('N' == _msg_buff[12]) && ('N' == _msg_buff[13])) { + // memory card exception + _sdcard_status = false; + return; + } + _sdcard_status = true; + + // send UTC time to the camera + if (_sent_time_count < 7) { + if (send_time_to_gimbal()) { + _sent_time_count++; + } + } + + return; +} + +// gimbal tracking information analysis +void AP_Mount_Topotek::gimbal_track_analyse() +{ + // ignore tracking state if unchanged + TrackingStatus tracking_state = (TrackingStatus)_msg_buff[11]; + if (tracking_state == _last_tracking_state) { + return; + } + _last_tracking_state = tracking_state; + + // inform user + const char* tracking_str = "tracking"; + switch (tracking_state) { + case TrackingStatus::STOPPED_TRACKING: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s stopped", send_message_prefix, tracking_str); + _is_tracking = false; + break; + case TrackingStatus::WAITING_FOR_TRACKING: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s waiting", send_message_prefix, tracking_str); + _is_tracking = false; + break; + case TrackingStatus::TRACKING_IN_PROGRESS: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s started", send_message_prefix, tracking_str); + _is_tracking = true; + break; + } +} + +// gimbal distance information analysis +void AP_Mount_Topotek::gimbal_dist_info_analyse() +{ + if ('E' == _msg_buff[10] && 'R' == _msg_buff[11] && 'R' ==_msg_buff[12]) { + _measure_dist_m = -1.0f; + return; + } + + // distance is in meters in the format, "12345.6" where each digit is in decimal + _measure_dist_m = char_to_hex(_msg_buff[10]) * 10000.0 + + char_to_hex(_msg_buff[11]) * 1000.0 + + char_to_hex(_msg_buff[12]) * 100.0 + + char_to_hex(_msg_buff[13]) * 10.0 + + char_to_hex(_msg_buff[14]) + + char_to_hex(_msg_buff[16]) * 0.1; +} + +// gimbal basic information analysis +void AP_Mount_Topotek::gimbal_version_analyse() +{ + // version array with index 0=major, 1=minor, 2=patch + uint8_t version[3] {}; + + // extract firmware version + // the version can be in the format "1.2.3" or "123" + const uint8_t data_buf_len = char_to_hex(_msg_buff[5]); + + // check for "." + bool contains_period = false; + for (uint8_t i = 0; i < data_buf_len; i++) { + contains_period |= _msg_buff[10 + i] == '.'; + } + + // if contains period, extract version number + uint32_t ver_num = 0; + uint8_t ver_count = 0; + if (contains_period) { + for (uint8_t i = 0; i < data_buf_len; i++) { + if (_msg_buff[10 + i] != '.') { + ver_num = ver_num * 10 + char_to_hex(_msg_buff[10 + i]); + } else { + version[ver_count++] = ver_num; + ver_num = 0; + } + if (ver_count >= ARRAY_SIZE(version)) { + break; + } + } + } else { + if (data_buf_len >= 1) { + version[0] = char_to_hex(_msg_buff[10]); + } + if (data_buf_len >= 2) { + version[1] = char_to_hex(_msg_buff[11]); + } + if (data_buf_len >= 3) { + version[2] = char_to_hex(_msg_buff[12]); + } + } + _firmware_ver = (version[2] << 16) | (version[1] << 8) | (version[0]); + + // display gimbal model and firmware version to user + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s v%u.%u.%u", + send_message_prefix, + version[0], // major version + version[1], // minor version + version[2]); // patch version + + _got_gimbal_version = true; +} + +// gimbal model name message analysis +void AP_Mount_Topotek::gimbal_model_name_analyse() +{ + strncpy((char *)_model_name, (const char *)_msg_buff + 10, char_to_hex(_msg_buff[5])); + + // display gimbal model name to user + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s", send_message_prefix, _model_name); + + _got_gimbal_model_name = true; +} + +// calculate checksum +uint8_t AP_Mount_Topotek::calculate_crc(const uint8_t *cmd, uint8_t len) const +{ + uint8_t crc = 0; + for (uint16_t i = 0; i= data)) { + return (data + '0'); + } else { + return (data - 10 + 'A'); + } +} + +// convert a 4 character hex number to an integer +// the characters are in the format "1234" where the most significant digit is first +int16_t AP_Mount_Topotek::hexchar4_to_int16(char high, char mid_high, char mid_low, char low) const +{ + const int16_t value = (char_to_hex(high) << 12) | + (char_to_hex(mid_high) << 8) | + (char_to_hex(mid_low) << 4) | + (char_to_hex(low)); + + return value; +} + +// send a fixed length packet +bool AP_Mount_Topotek::send_fixedlen_packet(AddressByte address, const Identifier id, bool write, uint8_t value) +{ + uint8_t databuff[3]; + hal.util->snprintf((char *)databuff, ARRAY_SIZE(databuff), "%02X", value); + return send_variablelen_packet(HeaderType::FIXED_LEN, address, id, write, databuff, ARRAY_SIZE(databuff)-1); +} + +// send variable length packet +bool AP_Mount_Topotek::send_variablelen_packet(HeaderType header, AddressByte address, const Identifier id, bool write, const uint8_t* databuff, uint8_t databuff_len) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // calculate and sanity check packet size + const uint16_t packet_size = AP_MOUNT_TOPOTEK_PACKETLEN_MIN + databuff_len; + if (packet_size > AP_MOUNT_TOPOTEK_PACKETLEN_MAX) { + debug("send_packet data buff too large"); + return false; + } + + // check for sufficient space in outgoing buffer + if (_uart->txspace() < packet_size) { + debug("tx buffer full"); + return false; + } + + // create buffer for holding outgoing packet + uint8_t send_buff[packet_size]; + uint8_t send_buff_ofs = 0; + + // packet header (bytes 0 ~ 2) + send_buff[send_buff_ofs++] = '#'; + send_buff[send_buff_ofs++] = (header == HeaderType::FIXED_LEN) ? 'T' : 't'; + send_buff[send_buff_ofs++] = (header == HeaderType::FIXED_LEN) ? 'P' : 'p'; + + // address (bytes 3, 4) + send_buff[send_buff_ofs++] = (uint8_t)AddressByte::UART; + send_buff[send_buff_ofs++] = (uint8_t)address; + + // data length (byte 5) + send_buff[send_buff_ofs++] = hex2char(databuff_len); + + // control byte (byte 6) + send_buff[send_buff_ofs++] = write ? (uint8_t)ControlByte::WRITE : (uint8_t)ControlByte::READ; + + // identified (bytes 7 ~ 9) + send_buff[send_buff_ofs++] = id[0]; + send_buff[send_buff_ofs++] = id[1]; + send_buff[send_buff_ofs++] = id[2]; + + // data + if (databuff_len != 0) { + memcpy(&send_buff[send_buff_ofs], databuff, databuff_len); + send_buff_ofs += databuff_len; + } + + // crc + uint8_t crc = calculate_crc(send_buff, send_buff_ofs); + send_buff[send_buff_ofs++] = hex2char((crc >> 4) & 0x0f); + send_buff[send_buff_ofs++] = hex2char(crc & 0x0f); + + // send packet + _uart->write(send_buff, send_buff_ofs); + return true; +} + +// 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 +bool AP_Mount_Topotek::set_gimbal_lock(bool lock) +{ + if (_last_lock == lock) { + return true; + } + + // send message and update lock state + if (send_fixedlen_packet(AddressByte::GIMBAL, AP_MOUNT_TOPOTEK_ID3CHAR_GIMBAL_MODE, true, lock ? 6 : 7)) { + _last_lock = lock; + return true; + } + return false; +} + +#endif // HAL_MOUNT_TOPOTEK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Topotek.h b/libraries/AP_Mount/AP_Mount_Topotek.h new file mode 100755 index 00000000000000..9c8882936c758d --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Topotek.h @@ -0,0 +1,285 @@ +/* + Topotek gimbal driver using custom serial protocol + + Packet format (courtesy of Topotek's SDK document) + + ------------------------------------------------------------------------------------------- + Field Index Bytes Description + ------------------------------------------------------------------------------------------- + Frame Header 0 3 type of command + Address Bit 3 2 the source address comes first, and the destination address comes last + Data_Len 5 1 data length + Control Bit 6 1 r -> query w -> setup and control + Identification Bit 7 3 identification function + Data 10 Data_Len + Check Bit 2 the frame header is converted to HEX before reaching the check bit, + the sum is done, and the result is converted to ASC-II. Two bytes, the high one first + */ + +#pragma once + +#include "AP_Mount_config.h" + +#if HAL_MOUNT_TOPOTEK_ENABLED + +#include "AP_Mount_Backend_Serial.h" +#include +#include +#include + +#define AP_MOUNT_TOPOTEK_PACKETLEN_MAX 36 // maximum number of bytes in a packet sent to or received from the gimbal +#define AP_MOUNT_RECV_GIMBAL_CMD_CATEGORIES_NUM 7 // parse the number of gimbal command types + +class AP_Mount_Topotek : public AP_Mount_Backend_Serial +{ + +public: + // Constructor + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; + + // Do not allow copies + CLASS_NO_COPY(AP_Mount_Topotek); + + // 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 for gimbals + // + + // 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 zoom specified as a rate + bool set_zoom(ZoomType zoom_type, float zoom_value) override; + + // set focus specified as rate or auto + // focus in = -1, focus hold = 0, focus out = 1 + SetFocusResult set_focus(FocusType focus_type, float focus_value) override; + + // set tracking to none, point or rectangle (see TrackingType enum) + // if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right + // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom + bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) override; + + // send command to gimbal to cancel tracking (if necessary) + // returns true on success, false on failure to send message + bool cancel_tracking(); + + // set camera picture-in-picture mode + bool set_lens(uint8_t lens) override; + +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override; +#endif + + // send camera information message to GCS + void send_camera_information(mavlink_channel_t chan) const override; + + // send camera settings message to GCS + void send_camera_settings(mavlink_channel_t chan) const override; + + // + // rangefinder + // + + // get rangefinder distance. Returns true on success + bool get_rangefinder_distance(float& distance_m) const override; + + // enable/disable rangefinder. Returns true on success + bool set_rangefinder_enable(bool enable) override; + +protected: + + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; + +private: + + // header type (fixed or variable length) + // first three bytes of packet determined by this value + enum class HeaderType : uint8_t { + FIXED_LEN = 0x00, // #TP will be sent + VARIABLE_LEN = 0x01, // #tp will be sent + }; + + // address (2nd and 3rd bytes of packet) + // first byte is always U followed by one of the other options + enum class AddressByte : uint8_t { + SYSTEM_AND_IMAGE = 68, // 'D' + AUXILIARY_EQUIPMENT = 69, // 'E' + GIMBAL = 71, // 'G' + LENS = 77, // 'M' + NETWORK = 80, // 'P' + UART = 85, // 'U' + }; + + // control byte (read or write) + // sent as 7th byte of packet + enum class ControlByte : uint8_t { + READ = 114, // 'r' + WRITE = 119, // 'w' + }; + + // parsing state + enum class ParseState : uint8_t { + WAITING_FOR_HEADER1 = 0,// # + WAITING_FOR_HEADER2, // T or t + WAITING_FOR_HEADER3, // P or p + WAITING_FOR_ADDR1, // normally U + WAITING_FOR_ADDR2, // M, D, E, P, G + WAITING_FOR_DATALEN, + WAITING_FOR_CONTROL, // r or w + WAITING_FOR_ID1, // e.g. 'G' + WAITING_FOR_ID2, // e.g. 'A' + WAITING_FOR_ID3, // e.g. 'C' + WAITING_FOR_DATA, // normally hex numbers in char form (e.g. '0A') + WAITING_FOR_CRC_LOW, + WAITING_FOR_CRC_HIGH, + }; + + // tracking status + enum class TrackingStatus : uint8_t { + STOPPED_TRACKING = 0x30, // not tracking + WAITING_FOR_TRACKING = 0x31, // wait to track command status + TRACKING_IN_PROGRESS = 0x32 // the status is being tracked. + }; + + // identifier bytes + typedef char Identifier[3]; + + // send text prefix string + static const char* send_message_prefix; + + // reading incoming packets from gimbal and confirm they are of the correct format + void read_incoming_packets(); + + // request gimbal attitude + void request_gimbal_attitude(); + + // request gimbal memory card information + void request_gimbal_sdcard_info(); + + // request gimbal tracking status + void request_track_status(); + + // request gimbal version + void request_gimbal_version(); + + // request gimbal model name + void request_gimbal_model_name(); + + // send angle target in radians to gimbal + void send_angle_target(const MountTarget& angle_rad); + + // send rate target in rad/s to gimbal + void send_rate_target(const MountTarget& rate_rads); + + // send time and date to gimbal + bool send_time_to_gimbal(); + + // send GPS-related information to the gimbal + bool send_location_info(); + + // attitude information analysis of gimbal + void gimbal_angle_analyse(); + + // gimbal video information analysis + void gimbal_record_analyse(); + + // information analysis of gimbal storage card + void gimbal_sdcard_analyse(); + + // gimbal tracking information analysis + void gimbal_track_analyse(); + + // gimbal basic information analysis + void gimbal_version_analyse(); + + // gimbal model name message analysis + void gimbal_model_name_analyse(); + + // gimbal distance information analysis + void gimbal_dist_info_analyse(); + + // calculate checksum + uint8_t calculate_crc(const uint8_t *cmd, uint8_t len) const; + + // hexadecimal to character conversion + uint8_t hex2char(uint8_t data) const; + + // convert a 4 character hex number to an integer + // the characters are in the format "1234" where the most significant digit is first + int16_t hexchar4_to_int16(char high, char mid_high, char mid_low, char low) const; + + // send a fixed length packet to gimbal + // returns true on success, false if serial port initialization failed + bool send_fixedlen_packet(AddressByte address, const Identifier id, bool write, uint8_t value); + + // send a variable length packet to gimbal + // returns true on success, false if serial port initialization failed + bool send_variablelen_packet(HeaderType header, AddressByte address, const Identifier id, bool write, const uint8_t* databuff, uint8_t databuff_len); + + // 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 + bool set_gimbal_lock(bool lock); + + // members + bool _recording; // recording status (received from gimbal) + bool _is_tracking; // whether to enable the tracking state + TrackingStatus _last_tracking_state = TrackingStatus::STOPPED_TRACKING; // last tracking state received from gimbal + uint8_t _last_mode; // mode during latest update, used to detect mode changes and cancel tracking + bool _sdcard_status; // memory card status (received from gimbal) + bool _last_lock; // last lock mode sent to gimbal + bool _got_gimbal_version; // true if gimbal's version has been received + bool _got_gimbal_model_name; // true if gimbal's model name has been received + bool _last_zoom_stop; // true if zoom has been stopped (used to re-send in order to handle lost packets) + bool _last_focus_stop; // true if focus has been stopped (used to re-sent in order to handle lost packets) + uint8_t _model_name[16]; // gimbal model name + uint8_t _sent_time_count; // count of current time messages sent to gimbal + uint32_t _firmware_ver; // firmware version + Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw) + uint32_t _last_current_angle_ms; // system time (in milliseconds) that angle information received from the gimbal + uint32_t _last_req_current_info_ms; // system time that this driver last requested current gimbal infomation + uint8_t _last_req_step; // 10hz request loop step (different requests are sent at various steps) + uint8_t _stop_order_count; // number of stop commands sent since target rates became zero + float _measure_dist_m = -1.0f; // latest rangefinder distance (in meters) + uint8_t _msg_buff[AP_MOUNT_TOPOTEK_PACKETLEN_MAX]; // buffer holding bytes from latest packet received. only used to calculate crc + uint8_t _msg_buff_len; // number of bytes in the msg buffer + struct { + ParseState state; // parser state + uint8_t data_len; // expected number of data bytes + } _parser; + + // mapping from received message key to member function pointer to consume the message + typedef struct { + uint8_t uart_cmd_key[4]; // gimbal message key; + void (AP_Mount_Topotek::*func)(void); // member function to consume messager + } UartCmdFunctionHandler; + + // stores command ID and corresponding member functions that are compared with the command received by the gimbal + UartCmdFunctionHandler uart_recv_cmd_compare_list[AP_MOUNT_RECV_GIMBAL_CMD_CATEGORIES_NUM] = { + {{"GIA"}, &AP_Mount_Topotek::gimbal_angle_analyse}, + {{"REC"}, &AP_Mount_Topotek::gimbal_record_analyse}, + {{"SDC"}, &AP_Mount_Topotek::gimbal_sdcard_analyse}, + {{"LRF"}, &AP_Mount_Topotek::gimbal_dist_info_analyse}, + {{"TRC"}, &AP_Mount_Topotek::gimbal_track_analyse}, + {{"VSN"}, &AP_Mount_Topotek::gimbal_version_analyse}, + {{"PA2"}, &AP_Mount_Topotek::gimbal_model_name_analyse} + }; +}; + +#endif // HAL_MOUNT_TOPOTEK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 409d9cc27b4e8a..aa443483e82b28 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -1,13 +1,15 @@ -#include "AP_Mount_Viewpro.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_VIEWPRO_ENABLED + +#include "AP_Mount_Viewpro.h" + #include #include #include #include #include #include -#include extern const AP_HAL::HAL& hal; @@ -28,20 +30,6 @@ extern const AP_HAL::HAL& hal; const char* AP_Mount_Viewpro::send_text_prefix = "Viewpro:"; -// init - performs any required initialisation for this instance -void AP_Mount_Viewpro::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_uart == nullptr) { - return; - } - - _initialised = true; - AP_Mount_Backend::init(); -} - // update mount position - should be called periodically void AP_Mount_Viewpro::update() { @@ -109,20 +97,9 @@ void AP_Mount_Viewpro::update() 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; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -935,8 +912,8 @@ void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const vendor_name, // vendor_name uint8_t[32] _model_name, // model_name uint8_t[32] _firmware_version, // firmware version uint32_t - 0, // focal_length float (mm) - 0, // sensor_size_h float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix) @@ -955,8 +932,6 @@ void AP_Mount_Viewpro::send_camera_settings(mavlink_channel_t chan) const return; } - const float NaN = nanf("0x4152"); - // convert zoom times (e.g. 1x ~ 20x) to target zoom level (e.g. 0 to 100) const float zoom_level = linear_interpolate(0, 100, _zoom_times, 1, AP_MOUNT_VIEWPRO_ZOOM_MAX); @@ -966,7 +941,7 @@ void AP_Mount_Viewpro::send_camera_settings(mavlink_channel_t chan) const AP_HAL::millis(), // time_boot_ms _recording ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) zoom_level, // zoomLevel float, percentage from 0 to 100, NaN if unknown - NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown + NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown } // get rangefinder distance. Returns true on success diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.h b/libraries/AP_Mount/AP_Mount_Viewpro.h index 1ddaa283212be4..1100586cd1ce16 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.h +++ b/libraries/AP_Mount/AP_Mount_Viewpro.h @@ -16,10 +16,12 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_VIEWPRO_ENABLED +#include "AP_Mount_Backend_Serial.h" + #include #include #include @@ -27,19 +29,16 @@ #define AP_MOUNT_VIEWPRO_PACKETLEN_MAX 63 // maximum number of bytes in a packet sent to or received from the gimbal -class AP_Mount_Viewpro : public AP_Mount_Backend +class AP_Mount_Viewpro : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; /* Do not allow copies */ CLASS_NO_COPY(AP_Mount_Viewpro); - // init - performs any required initialisation for this instance - void init() override; - // update mount position - should be called periodically void update() override; @@ -378,8 +377,6 @@ class AP_Mount_Viewpro : public AP_Mount_Backend bool send_m_ahrs(); // internal variables - AP_HAL::UARTDriver *_uart; // uart connected to gimbal - bool _initialised; // true once the driver has been initialised uint8_t _msg_buff[AP_MOUNT_VIEWPRO_PACKETLEN_MAX]; // buffer holding latest bytes from gimbal uint8_t _msg_buff_len; // number of bytes held in msg buff const uint8_t _msg_buff_data_start = 2; // data starts at this byte of _msg_buff diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index 3d551885ce35dc..410de2660ce690 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -1,6 +1,9 @@ -#include "AP_Mount_Xacti.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_XACTI_ENABLED + +#include "AP_Mount_Xacti.h" + #include #include #include @@ -21,7 +24,6 @@ extern const AP_HAL::HAL& hal; #define AP_MOUNT_XACTI_DEBUG 0 #define debug(fmt, args ...) do { if (AP_MOUNT_XACTI_DEBUG) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Xacti: " fmt, ## args); } } while (0) -bool AP_Mount_Xacti::_subscribed = false; AP_Mount_Xacti::DetectedModules AP_Mount_Xacti::_detected_modules[]; HAL_Semaphore AP_Mount_Xacti::_sem_registry; const char* AP_Mount_Xacti::send_text_prefix = "Xacti:"; @@ -49,7 +51,7 @@ AP_Mount_Xacti::AP_Mount_Xacti(class AP_Mount &frontend, class AP_Mount_Params & void AP_Mount_Xacti::init() { // instantiate parameter queue, return on failure so init fails - _set_param_int32_queue = new ObjectArray(XACTI_SET_PARAM_QUEUE_SIZE); + _set_param_int32_queue = NEW_NOTHROW ObjectArray(XACTI_SET_PARAM_QUEUE_SIZE); if (_set_param_int32_queue == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s init failed", send_text_prefix); return; @@ -135,20 +137,9 @@ void AP_Mount_Xacti::update() break; } - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's RC inputs - MountTarget rc_target; - get_rc_target(mnt_target.target_type, rc_target); - switch (mnt_target.target_type) { - case MountTargetType::ANGLE: - mnt_target.angle_rad = rc_target; - break; - case MountTargetType::RATE: - mnt_target.rate_rads = rc_target; - break; - } + case MAV_MOUNT_MODE_RC_TARGETING: + update_mnt_target_from_rc_target(); break; - } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: @@ -361,7 +352,6 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const static const uint8_t vendor_name[32] = "Xacti"; static uint8_t model_name[32] = "CX-GB100"; const char cam_definition_uri[140] {}; - const float NaN = nanf("0x4152"); // capability flags const uint32_t flags = CAMERA_CAP_FLAGS_CAPTURE_VIDEO | @@ -375,9 +365,9 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const vendor_name, // vendor_name uint8_t[32] model_name, // model_name uint8_t[32] _firmware_version.received ? _firmware_version.mav_ver : 0, // firmware version uint32_t - NaN, // focal_length float (mm) - NaN, // sensor_size_h float (mm) - NaN, // sensor_size_v float (mm) + NaNf, // focal_length float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix) 0, // lens_id uint8_t @@ -390,15 +380,13 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const // send camera settings message to GCS void AP_Mount_Xacti::send_camera_settings(mavlink_channel_t chan) const { - const float NaN = nanf("0x4152"); - // send CAMERA_SETTINGS message mavlink_msg_camera_settings_send( chan, AP_HAL::millis(), // time_boot_ms _recording_video ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) 0, // zoomLevel float, percentage from 0 to 100, NaN if unknown - NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown + NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown } // get attitude as a quaternion. returns true on success @@ -428,25 +416,13 @@ void AP_Mount_Xacti::send_target_angles(float pitch_rad, float yaw_rad, bool yaw } // subscribe to Xacti DroneCAN messages -void AP_Mount_Xacti::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Mount_Xacti::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - // return immediately if DroneCAN is unavailable - if (ap_dronecan == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s DroneCAN subscribe failed", send_text_prefix); - return; - } - - _subscribed = true; + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_gimbal_attitude_status, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("gimbal_attitude_status_sub"); - _subscribed = false; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_gnss_status_req, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("gnss_status_req_sub"); - _subscribed = false; - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_gimbal_attitude_status, driver_index) != nullptr) + && (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_gnss_status_req, driver_index) != nullptr) + ; } // register backend in detected modules array used to map DroneCAN port and node id to backend diff --git a/libraries/AP_Mount/AP_Mount_Xacti.h b/libraries/AP_Mount/AP_Mount_Xacti.h index 31a66840235617..14643a7acc49ec 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.h +++ b/libraries/AP_Mount/AP_Mount_Xacti.h @@ -8,10 +8,12 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_config.h" #if HAL_MOUNT_XACTI_ENABLED +#include "AP_Mount_Backend.h" + #include #include #include @@ -73,7 +75,7 @@ class AP_Mount_Xacti : public AP_Mount_Backend void send_camera_settings(mavlink_channel_t chan) const override; // subscribe to Xacti DroneCAN messages - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); // xacti specific message handlers static void handle_gimbal_attitude_status(AP_DroneCAN* ap_dronecan, const CanardRxTransfer& transfer, const com_xacti_GimbalAttitudeStatus &msg); @@ -265,7 +267,6 @@ class AP_Mount_Xacti : public AP_Mount_Backend bool _camera_error; // true if status reports camera error // DroneCAN related variables - static bool _subscribed; // true once subscribed to receive DroneCAN messages static struct DetectedModules { AP_Mount_Xacti *driver; // pointer to Xacti backends AP_DroneCAN* ap_dronecan; // DroneCAN interface used by this backend diff --git a/libraries/AP_Mount/AP_Mount_config.h b/libraries/AP_Mount/AP_Mount_config.h index 0a6d38671cb037..c6e0791c2a6b03 100644 --- a/libraries/AP_Mount/AP_Mount_config.h +++ b/libraries/AP_Mount/AP_Mount_config.h @@ -1,13 +1,17 @@ #pragma once #include -#include +#include +#include +#include #ifndef HAL_MOUNT_ENABLED #define HAL_MOUNT_ENABLED 1 #endif +#ifndef AP_MOUNT_BACKEND_DEFAULT_ENABLED #define AP_MOUNT_BACKEND_DEFAULT_ENABLED HAL_MOUNT_ENABLED +#endif #ifndef HAL_MOUNT_ALEXMOS_ENABLED #define HAL_MOUNT_ALEXMOS_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED @@ -54,7 +58,16 @@ #define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024 #endif +#ifndef HAL_MOUNT_TOPOTEK_ENABLED +#define HAL_MOUNT_TOPOTEK_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED +#endif + // set camera source is supported on gimbals that may have more than one lens #ifndef HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED #define HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SIYI_ENABLED || HAL_MOUNT_XACTI_ENABLED || HAL_MOUNT_VIEWPRO_ENABLED #endif + +// send thermal range is only support on Siyi cameras +#ifndef AP_MOUNT_SEND_THERMAL_RANGE_ENABLED +#define AP_MOUNT_SEND_THERMAL_RANGE_ENABLED HAL_MOUNT_SIYI_ENABLED +#endif diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 4503c02cec3f5c..6e270de10251a5 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -1,9 +1,11 @@ +#include "AP_Mount_config.h" + +#if HAL_SOLO_GIMBAL_ENABLED + #include #include #include "SoloGimbal.h" -#if HAL_SOLO_GIMBAL_ENABLED - #include #include #include @@ -245,7 +247,7 @@ void SoloGimbal::update_fast() { // single gyro mode - one of the first two gyros are unhealthy or don't exist // just read primary gyro Vector3f dAng; - readVehicleDeltaAngle(ins.get_primary_gyro(), dAng); + readVehicleDeltaAngle(ins.get_first_usable_gyro(), dAng); _vehicle_delta_angles += dAng; } } diff --git a/libraries/AP_Mount/SoloGimbalEKF.cpp b/libraries/AP_Mount/SoloGimbalEKF.cpp index b599b4c2516b85..b514706f159a94 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.cpp +++ b/libraries/AP_Mount/SoloGimbalEKF.cpp @@ -1,3 +1,7 @@ +#include "AP_Mount_config.h" + +#if HAL_SOLO_GIMBAL_ENABLED + #include // uncomment this to force the optimisation of this code, note that @@ -9,7 +13,6 @@ #endif #include "SoloGimbalEKF.h" -#if HAL_SOLO_GIMBAL_ENABLED #include #include #include diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index 60bf156acb3ba2..ff76f0583dfed0 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -1,5 +1,8 @@ -#include "SoloGimbal_Parameters.h" +#include "AP_Mount_config.h" + #if HAL_SOLO_GIMBAL_ENABLED + +#include "SoloGimbal_Parameters.h" #include #include #include diff --git a/libraries/AP_MultiHeap/AP_MultiHeap.cpp b/libraries/AP_MultiHeap/AP_MultiHeap.cpp new file mode 100644 index 00000000000000..ff81139cc839bc --- /dev/null +++ b/libraries/AP_MultiHeap/AP_MultiHeap.cpp @@ -0,0 +1,206 @@ +/* + multiple heap interface, allowing for an allocator that uses + multiple underlying heaps to cope with multiple memory regions on + STM32 boards + */ + +#include "AP_MultiHeap.h" + +#if ENABLE_HEAP +#include +#include + +/* + allow up to 10 heaps + */ +#ifndef MAX_HEAPS +#define MAX_HEAPS 10 +#endif + +extern const AP_HAL::HAL &hal; + +/* + create heaps with a total memory size, splitting over at most + max_heaps + */ +bool MultiHeap::create(uint32_t total_size, uint8_t max_heaps, bool _allow_expansion, uint32_t _reserve_size) +{ + max_heaps = MIN(MAX_HEAPS, max_heaps); + if (heaps != nullptr) { + // don't allow double allocation + return false; + } + heaps = NEW_NOTHROW Heap[max_heaps]; + if (heaps == nullptr) { + return false; + } + num_heaps = max_heaps; + for (uint8_t i=0; i 0) { + heaps[i].hp = heap_create(alloc_size); + if (heaps[i].hp != nullptr) { + total_size -= alloc_size; + sum_size += alloc_size; + break; + } + alloc_size *= 0.9; + } + if (total_size == 0) { + break; + } + } + if (total_size != 0) { + destroy(); + return false; + } + + allow_expansion = _allow_expansion; + reserve_size = _reserve_size; + + return true; +} + +// destroy heap +void MultiHeap::destroy(void) +{ + if (!available()) { + return; + } + for (uint8_t i=0; iget_soft_armed()) { + // only expand the available heaps when armed. When disarmed + // user should fix their SCR_HEAP_SIZE parameter + last_failed = true; + return nullptr; + } + + /* + vehicle is armed and MultiHeap (for scripting) is out of + memory. We will see if we can add a new heap from available + memory if we have at least reserve_size bytes free + */ + const uint32_t available = hal.util->available_memory(); + const uint32_t heap_overhead = 128; // conservative value, varies with HAL + const uint32_t min_size = size + heap_overhead; + if (available < reserve_size+min_size) { + last_failed = true; + return nullptr; + } + + // round up to a minimum of 30k to allocate, and allow for heap overhead + const uint32_t round_to = 30*1024U; + const uint32_t alloc_size = MIN(available - reserve_size, MAX(size+heap_overhead, round_to)); + if (alloc_size < min_size) { + last_failed = true; + return nullptr; + } + for (uint8_t i=0; i= new_size) { + // Lua assumes that the allocator never fails when osize >= nsize + // the best we can do is return the old pointer + return ptr; + } + return nullptr; + } + memcpy(newp, ptr, MIN(old_size, new_size)); + deallocate(ptr); + return newp; +} + +#endif // ENABLE_HEAP diff --git a/libraries/AP_MultiHeap/AP_MultiHeap.h b/libraries/AP_MultiHeap/AP_MultiHeap.h new file mode 100644 index 00000000000000..3b67f11739e93d --- /dev/null +++ b/libraries/AP_MultiHeap/AP_MultiHeap.h @@ -0,0 +1,83 @@ +/* + multiple heap interface, allowing for an allocator that uses + multiple underlying heaps to cope with multiple memory regions on + STM32 boards + */ + +#pragma once + +#include +#include + +#if ENABLE_HEAP + +#include +#include + +class MultiHeap { +public: + /* + allocate/deallocate heaps + */ + bool create(uint32_t total_size, uint8_t max_heaps, bool allow_expansion, uint32_t reserve_size); + void destroy(void); + + // return true if the heap is available for operations + bool available(void) const; + + // allocate memory within heaps + void *allocate(uint32_t size); + void deallocate(void *ptr); + + // change allocated size of a pointer - this operates in a similar + // fashion to realloc, but requires an (accurate!) old_size value + // when ptr is not NULL. This is guaranteed by the lua scripting + // allocation API + void *change_size(void *ptr, uint32_t old_size, uint32_t new_size); + + /* + get the size that we have expanded to. Used by error reporting in scripting + */ + uint32_t get_expansion_size(void) const { + return expanded_to; + } + +private: + struct Heap { + void *hp; + }; + struct Heap *heaps; + + uint8_t num_heaps; + bool allow_expansion; + uint32_t reserve_size; + uint32_t sum_size; + uint32_t expanded_to; + + // we only do heap expansion if the last allocation failed this + // encourages the lua scripting engine to garbage collect to + // re-use memory when possible + bool last_failed; + + + /* + low level allocation functions + */ + /* + heap functions used by lua scripting + */ + // allocate a new heap + void *heap_create(uint32_t size); + + // destroy a heap + void heap_destroy(void *ptr); + + // allocate some memory on a specific heap + void *heap_allocate(void *heap, uint32_t size); + + // free some memory that was allocated by heap_allocate. The implementation must + // be able to determine which heap the allocation was from using the pointer + void heap_free(void *ptr); +}; + +#endif // ENABLE_HEAP diff --git a/libraries/AP_MultiHeap/MultiHeap_chibios.cpp b/libraries/AP_MultiHeap/MultiHeap_chibios.cpp new file mode 100644 index 00000000000000..d3225cd3b7b388 --- /dev/null +++ b/libraries/AP_MultiHeap/MultiHeap_chibios.cpp @@ -0,0 +1,47 @@ +/* + allocation backend functions using native ChibiOS chHeap API + */ + +#include "AP_MultiHeap.h" +#include + +#if ENABLE_HEAP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + +#include +#include + +/* + heap functions used by lua scripting + */ +void *MultiHeap::heap_create(uint32_t size) +{ + memory_heap_t *heap = (memory_heap_t *)malloc(size + sizeof(memory_heap_t)); + if (heap == nullptr) { + return nullptr; + } + chHeapObjectInit(heap, heap + 1U, size); + return heap; +} + +void MultiHeap::heap_destroy(void *ptr) +{ + free(ptr); +} + +void *MultiHeap::heap_allocate(void *heap, uint32_t size) +{ + if (heap == nullptr) { + return nullptr; + } + if (size == 0) { + return nullptr; + } + return chHeapAlloc((memory_heap_t *)heap, size); +} + +void MultiHeap::heap_free(void *ptr) +{ + return chHeapFree(ptr); +} + +#endif // ENABLE_HEAP && CONFIG_HAL_BOARD diff --git a/libraries/AP_MultiHeap/MultiHeap_malloc.cpp b/libraries/AP_MultiHeap/MultiHeap_malloc.cpp new file mode 100644 index 00000000000000..857d01e76bfc82 --- /dev/null +++ b/libraries/AP_MultiHeap/MultiHeap_malloc.cpp @@ -0,0 +1,119 @@ +#include "AP_MultiHeap.h" +#include + +#if ENABLE_HEAP && CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS + +/* + on systems other than chibios we map the allocation to the system + malloc/free functions + */ + +#include +#include + +/* + low level allocator interface using system malloc + */ +/* + default functions for heap management for lua scripting for systems + that don't have the ability to create separable heaps + */ + +struct heap_allocation_header { + struct heap *hp; + uint32_t allocation_size; // size of allocated block, not including this header +}; + +#define HEAP_MAGIC 0x5681ef9f + +struct heap { + uint32_t magic; + uint32_t max_heap_size; + uint32_t current_heap_usage; +}; + +void *MultiHeap::heap_create(uint32_t size) +{ + struct heap *new_heap = (struct heap*)malloc(sizeof(struct heap)); + if (new_heap != nullptr) { + new_heap->max_heap_size = size; + } + new_heap->magic = HEAP_MAGIC; + return (void *)new_heap; +} + +void MultiHeap::heap_destroy(void *heap_ptr) +{ + struct heap *heapp = (struct heap*)heap_ptr; + if (heapp->magic != HEAP_MAGIC) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (heapp->current_heap_usage != 0) { + // lua should guarantee that there is no memory still + // allocated when we destroy the heap. Throw an error in SITL + // if this proves not to be true + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } +#endif + + // free the heap structure + free(heapp); +} + +/* + allocate memory on a specific heap + */ +void *MultiHeap::heap_allocate(void *heap_ptr, uint32_t size) +{ + if (heap_ptr == nullptr || size == 0) { + return nullptr; + } + struct heap *heapp = (struct heap*)heap_ptr; + if (heapp->magic != HEAP_MAGIC) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return nullptr; + } + + if (heapp->current_heap_usage + size > heapp->max_heap_size) { + // fail the allocation as we don't have the memory. Note that + // we don't simulate the fragmentation that we would get with + // HAL_ChibiOS + return nullptr; + } + + auto *header = (heap_allocation_header *)malloc(size + sizeof(heap_allocation_header)); + if (header == nullptr) { + // can't allocate the new memory + return nullptr; + } + header->hp = heapp; + header->allocation_size = size; + + heapp->current_heap_usage += size; + + return header + 1; +} + +/* + free memory from a previous heap_allocate call + */ +void MultiHeap::heap_free(void *ptr) +{ + // extract header + auto *header = ((struct heap_allocation_header *)ptr)-1; + auto *heapp = header->hp; + if (heapp->magic != HEAP_MAGIC) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } + const uint32_t size = header->allocation_size; + heapp->current_heap_usage -= size; + + // free the memory + free(header); +} + +#endif // ENABLE_HEAP && CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS diff --git a/libraries/AP_MultiHeap/tests/test_multiheap.cpp b/libraries/AP_MultiHeap/tests/test_multiheap.cpp new file mode 100644 index 00000000000000..168ed933cf0b3b --- /dev/null +++ b/libraries/AP_MultiHeap/tests/test_multiheap.cpp @@ -0,0 +1,57 @@ +#include +#include +#include +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +TEST(MultiHeap, Tests) +{ + static MultiHeap h; + + EXPECT_TRUE(h.create(150000, 10, true, 10000)); + EXPECT_TRUE(h.available()); + + const uint32_t max_allocs = 1000; + struct alloc { + void *ptr; + uint32_t size; + }; + auto *allocs = new alloc[max_allocs]; + allocs[0].size = 640; + allocs[0].ptr = h.allocate(allocs[0].size); + for (uint32_t i=1; i<2; i++) { + auto &a = allocs[i]; + a.size = 30; + a.ptr = h.allocate(a.size); + } + allocs[0].ptr = h.change_size(allocs[0].ptr, allocs[0].size, 50); + allocs[0].size = 50; + + for (uint32_t i=0; i<5000; i++) { + uint16_t idx = get_random16() % max_allocs; + auto &a = allocs[idx]; + if (a.ptr == nullptr) { + const uint16_t size = get_random16() % 150; + a.ptr = h.allocate(size); + //printf("a.ptr=%p %u -> %u\n", a.ptr, a.size, size); + EXPECT_TRUE(size==0?a.ptr == nullptr : a.ptr != nullptr); + a.size = size; + } else { + const uint16_t size = get_random16() % 150; + a.ptr = h.change_size(a.ptr, a.size, size); + //printf("a.ptr=%p %u -> %u\n", a.ptr, a.size, size); + EXPECT_TRUE(size==0?a.ptr == nullptr : a.ptr != nullptr); + a.size = size; + } + } + for (uint32_t i=0; ihas_orientation(ROTATION_PITCH_270))) { - hal.util->snprintf(failure_msg, failure_msg_len, ekf_requires_msg, "RangeFinder"); - return false; + if (rangefinder_required) { +#if AP_RANGEFINDER_ENABLED + const bool have_rangefinder = (dal.rangefinder() != nullptr && dal.rangefinder()->has_orientation(ROTATION_PITCH_270)); +#else + const bool have_rangefinder = false; +#endif + if (!have_rangefinder) { + hal.util->snprintf(failure_msg, failure_msg_len, ekf_requires_msg, "RangeFinder"); + return false; + } } if (visualodom_required) { diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.h b/libraries/AP_NavEKF/AP_NavEKF_Source.h index b8bfa67d18a8d5..8ceb8d1ab4fbca 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.h +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.h @@ -47,7 +47,14 @@ class AP_NavEKF_Source // enum for OPTIONS parameter enum class SourceOptions { - FUSE_ALL_VELOCITIES = (1 << 0) // fuse all velocities configured in source sets + FUSE_ALL_VELOCITIES = (1 << 0), // fuse all velocities configured in source sets + ALIGN_EXTNAV_POS_WHEN_USING_OPTFLOW = (1 << 1) // align position of inactive sources to ahrs when using optical flow + }; + + enum class SourceSetSelection : uint8_t { + PRIMARY = 0, + SECONDARY = 1, + TERTIARY = 2, }; // initialisation @@ -58,7 +65,7 @@ class AP_NavEKF_Source SourceZ getPosZSource() const; // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary - void setPosVelYawSourceSet(uint8_t source_set_idx); + void setPosVelYawSourceSet(SourceSetSelection source_set_idx); uint8_t getPosVelYawSourceSet() const { return active_source_set; } // get/set velocity source @@ -118,6 +125,9 @@ class AP_NavEKF_Source AP_Enum yaw; // yaw source } _source_set[AP_NAKEKF_SOURCE_SET_MAX]; + // helper to check if an option parameter bit has been set + bool option_is_set(SourceOptions option) const { return (_options.get() & int16_t(option)) != 0; } + AP_Int16 _options; // source options bitmask uint8_t active_source_set; // index of active source set diff --git a/libraries/AP_NavEKF/AP_Nav_Common.h b/libraries/AP_NavEKF/AP_Nav_Common.h index 10037c4e1578db..a24f96e86e1431 100644 --- a/libraries/AP_NavEKF/AP_Nav_Common.h +++ b/libraries/AP_NavEKF/AP_Nav_Common.h @@ -19,6 +19,30 @@ #include #include +// enumeration corresponding to buts within nav_filter_status union. +// Only used for documentation purposes. +enum class NavFilterStatusBit { + ATTITUDE = 1, // attitude estimate valid + HORIZ_VEL = 2, // horizontal velocity estimate valid + VERT_VEL = 4, // vertical velocity estimate valid + HORIZ_POS_REL = 8, // relative horizontal position estimate valid + HORIZ_POS_ABS = 16, // absolute horizontal position estimate valid + VERT_POS = 32, // vertical position estimate valid + TERRAIN_ALT = 64, // terrain height estimate valid + CONST_POS_MODE = 128, // in constant position mode + PRED_HORIZ_POS_REL = 256, // expected good relative horizontal position estimate - used before takeoff + PRED_HORIZ_POS_ABS = 512, // expected good absolute horizontal position estimate - used before takeoff + TAKEOFF_DETECTED = 1024, // optical flow takeoff has been detected + TAKEOFF_EXPECTED = 2048, // compensating for baro errors during takeoff + TOUCHDOWN_EXPECTED = 4096, // compensating for baro errors during touchdown + USING_GPS = 8192, // using GPS position + GPS_GLITCHING = 16384, // GPS glitching is affecting navigation accuracy + GPS_QUALITY_GOOD = 32768, // can use GPS for navigation + INITALIZED = 65536, // has ever been healthy + REJECTING_AIRSPEED = 131072, // rejecting airspeed data + DEAD_RECKONING = 262144, // dead reckoning (e.g. no position or velocity source) +}; + union nav_filter_status { struct { bool attitude : 1; // 0 - true if attitude estimate is valid diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.cpp b/libraries/AP_NavEKF/EKFGSF_yaw.cpp index 7d9e453c7548cb..5a9a963f6cf466 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.cpp +++ b/libraries/AP_NavEKF/EKFGSF_yaw.cpp @@ -103,7 +103,7 @@ void EKFGSF_yaw::update(const Vector3F &delAng, // Calculate a composite yaw as a weighted average of the states for each model. // 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 = {}; + Vector2F yaw_vector; 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]); @@ -196,15 +196,15 @@ void EKFGSF_yaw::predictAHRS(const uint8_t mdl_idx) // Generate attitude solution using simple complementary filter for the selected model // Calculate 'k' unit vector of earth frame rotated into body frame - const Vector3F k(AHRS[mdl_idx].R[2][0], AHRS[mdl_idx].R[2][1], AHRS[mdl_idx].R[2][2]); + const Vector3F k{AHRS[mdl_idx].R[2][0], AHRS[mdl_idx].R[2][1], AHRS[mdl_idx].R[2][2]}; // Calculate angular rate vector in rad/sec averaged across last sample interval - Vector3F ang_rate_delayed_raw = delta_angle / angle_dt; + const Vector3F ang_rate_delayed_raw { delta_angle / angle_dt }; // Perform angular rate correction using accel data and reduce correction as accel magnitude moves away from 1 g (reduces drift when vehicle picked up and moved). // During fixed wing flight, compensate for centripetal acceleration assuming coordinated turns and X axis forward - Vector3F tilt_error_gyro_correction = {}; // (rad/sec) + Vector3F tilt_error_gyro_correction; // (rad/sec) if (accel_gain > 0.0f) { @@ -213,8 +213,11 @@ void EKFGSF_yaw::predictAHRS(const uint8_t mdl_idx) if (is_positive(true_airspeed)) { // Calculate centripetal acceleration in body frame from cross product of body rate and body frame airspeed vector // NOTE: this assumes X axis is aligned with airspeed vector - Vector3F centripetal_accel_vec_bf = Vector3F(0.0f, ang_rate_delayed_raw[2] * true_airspeed, - ang_rate_delayed_raw[1] * true_airspeed); - + const Vector3F centripetal_accel_vec_bf { + 0.0f, + ang_rate_delayed_raw[2] * true_airspeed, + - ang_rate_delayed_raw[1] * true_airspeed + }; // Correct measured accel for centripetal acceleration accel -= centripetal_accel_vec_bf; } diff --git a/libraries/AP_NavEKF/EKF_Buffer.cpp b/libraries/AP_NavEKF/EKF_Buffer.cpp index b557b4e88dd3cd..b27dd084baca8e 100644 --- a/libraries/AP_NavEKF/EKF_Buffer.cpp +++ b/libraries/AP_NavEKF/EKF_Buffer.cpp @@ -53,12 +53,13 @@ uint32_t ekf_ring_buffer::time_ms(uint8_t idx) const bool ekf_ring_buffer::recall(void *element, const uint32_t sample_time_ms) { bool ret = false; + uint8_t best_index = 0; // only valid when ret becomes true 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); + best_index = oldest; ret = true; } if (dt < 0) { @@ -70,6 +71,11 @@ bool ekf_ring_buffer::recall(void *element, const uint32_t sample_time_ms) count--; oldest = (oldest+1) % size; } + + if (ret) { + memcpy(element, get_offset(best_index), elsize); + } + return ret; } diff --git a/libraries/AP_NavEKF/tests/test_ring_buffer.cpp b/libraries/AP_NavEKF/tests/test_ring_buffer.cpp index e61840469d9217..515715462502b6 100644 --- a/libraries/AP_NavEKF/tests/test_ring_buffer.cpp +++ b/libraries/AP_NavEKF/tests/test_ring_buffer.cpp @@ -128,7 +128,7 @@ TEST(ekf_imu_buffer, one_element_case) struct element { uint8_t value; }; - ekf_imu_buffer *b = new ekf_imu_buffer(sizeof(element)); + ekf_imu_buffer *b = NEW_NOTHROW ekf_imu_buffer(sizeof(element)); b->init(1); // 1 element EXPECT_EQ(b->is_filled(), false); EXPECT_EQ(b->get_oldest_index(), b->get_youngest_index()); @@ -157,7 +157,7 @@ TEST(ekf_imu_buffer, is_filled) struct element { uint8_t value; }; - ekf_imu_buffer *b = new ekf_imu_buffer(sizeof(element)); + ekf_imu_buffer *b = NEW_NOTHROW ekf_imu_buffer(sizeof(element)); b->init(4); // 4 elements const element e { 34 }; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index bc958e012aef6b..98c8e58a6ca758 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1,6 +1,9 @@ -#include +#include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" + +#include +#include #include #include #include @@ -598,6 +601,13 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @User: Advanced // @RebootRequired: True AP_GROUPINFO("GSF_RST_MAX", 57, NavEKF2, _gsfResetMaxCount, 2), + + // @Param: OPTIONS + // @DisplayName: Optional EKF behaviour + // @Description: optional EKF2 behaviour. Disabling external navigation prevents use of external vision data in the EKF2 solution + // @Bitmask: 0:DisableExternalNavigation + // @User: Advanced + AP_GROUPINFO("OPTIONS", 58, NavEKF2, _options, 0), AP_GROUPEND }; @@ -668,7 +678,7 @@ bool NavEKF2::InitialiseFilter(void) } // try to allocate from CCM RAM, fallback to Normal RAM if not available or full - core = (NavEKF2_core*)AP::dal().malloc_type(sizeof(NavEKF2_core)*num_cores, AP_DAL::MEM_FAST); + core = (NavEKF2_core*)AP::dal().malloc_type(sizeof(NavEKF2_core)*num_cores, AP_DAL::MemoryType::FAST); if (core == nullptr) { initFailure = InitFailures::NO_MEM; core_malloc_failed = true; @@ -688,7 +698,7 @@ bool NavEKF2::InitialiseFilter(void) if (_imuMask & (1U<free_type(core, sizeof(NavEKF2_core)*num_cores, AP_HAL::Util::MEM_FAST); + AP::dal().free_type(core, sizeof(NavEKF2_core)*num_cores, AP_DAL::MemoryType::FAST); core = nullptr; initFailure = InitFailures::NO_SETUP; GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "NavEKF2: core %d setup failed", num_cores); @@ -1089,6 +1099,10 @@ bool NavEKF2::getOriginLLH(Location &loc) const if (!core) { return false; } + if (common_origin_valid) { + loc = common_EKF_origin; + return true; + } return core[primary].getOriginLLH(loc); } @@ -1103,11 +1117,9 @@ bool NavEKF2::setOriginLLH(const Location &loc) if (!core) { return false; } - if (_fusionModeGPS != 3 || common_origin_valid) { - // we don't allow setting of the EKF origin if using GPS - // or if the EKF origin has already been set. - // This is to prevent accidental setting of EKF origin with an - // invalid position or height or causing upsets from a shifting origin. + if (common_origin_valid) { + // we don't allow setting of the EKF origin if the EKF origin + // has already been set. GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF2 refusing set origin"); return false; } @@ -1514,8 +1526,7 @@ void NavEKF2::updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_ void NavEKF2::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms) { AP::dal().writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms); - - if (core) { + if (!option_is_set(Option::DisableExternalNav) && core) { for (uint8_t i=0; i - -#include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" -extern const AP_HAL::HAL& hal; +#include + +#include "AP_NavEKF2.h" /******************************************************** * RESET FUNCTIONS * diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index 459d3de3983a31..ed19bd078ffba3 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -1,11 +1,9 @@ -#include - -#include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" -#include -extern const AP_HAL::HAL& hal; +#include +#include +#include "AP_NavEKF2.h" // Control filter mode transitions void NavEKF2_core::controlFilterModes() diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 33f822b71798d5..cdd25bc13383cf 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -1,11 +1,12 @@ -#include - #include "AP_NavEKF2_core.h" + +#include "AP_NavEKF2.h" + #include #include #include -extern const AP_HAL::HAL& hal; +#if AP_RANGEFINDER_ENABLED /******************************************************** @@ -110,6 +111,7 @@ void NavEKF2_core::readRangeFinder(void) } } } +#endif // write the raw optical flow measurements // this needs to be called externally. @@ -335,13 +337,13 @@ void NavEKF2_core::readIMUData() if (ins.use_accel(imu_index)) { accel_active = imu_index; } else { - accel_active = ins.get_primary_accel(); + accel_active = ins.get_first_usable_accel(); } if (ins.use_gyro(imu_index)) { gyro_active = imu_index; } else { - gyro_active = ins.get_primary_gyro(); + gyro_active = ins.get_first_usable_gyro(); } if (gyro_active != gyro_index_active) { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index 32820bd9ddd712..6d5937dd2247b7 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -60,12 +60,16 @@ bool NavEKF2_core::getHeightControlLimit(float &height) const // only ask for limiting if we are doing optical flow only navigation if (frontend->_fusionModeGPS == 3 && (PV_AidingMode == AID_RELATIVE) && flowDataValid) { // If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors +#if AP_RANGEFINDER_ENABLED const auto *_rng = dal.rangefinder(); if (_rng == nullptr) { // we really, really shouldn't be here. return false; } height = MAX(float(_rng->max_distance_cm_orient(ROTATION_PITCH_270)) * 0.007f - 1.0f, 1.0f); +#else + return false; +#endif // If we are are not using the range finder as the height reference, then compensate for the difference between terrain and EKF origin if (frontend->_altSource != 1) { height -= terrainState; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp index 3e7b99ee346937..debcaaf2c29e8d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp @@ -942,6 +942,7 @@ void NavEKF2_core::FuseVelPosNED() // select the height measurement to be fused from the available baro, range finder and GPS sources void NavEKF2_core::selectHeightForFusion() { +#if AP_RANGEFINDER_ENABLED // Read range finder data and check for new data in the buffer // This data is used by both height and optical flow fusion processing readRangeFinder(); @@ -961,6 +962,7 @@ void NavEKF2_core::selectHeightForFusion() } } } +#endif // read baro height data from the sensor and check for new data in the buffer readBaroData(); @@ -971,6 +973,7 @@ void NavEKF2_core::selectHeightForFusion() if (extNavUsedForPos) { // always use external navigation as the height source if using for position. activeHgtSource = HGT_SOURCE_EXTNAV; +#if AP_RANGEFINDER_ENABLED } else if ((frontend->_altSource == 1) && _rng && rangeFinderDataIsFresh) { // user has specified the range finder as a primary height source activeHgtSource = HGT_SOURCE_RNG; @@ -1004,6 +1007,7 @@ void NavEKF2_core::selectHeightForFusion() // reliable terrain and range finder so start using range finder height activeHgtSource = HGT_SOURCE_RNG; } +#endif // AP_RANGEFINDER_ENABLED } else if (frontend->_altSource == 0) { activeHgtSource = HGT_SOURCE_BARO; } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp index 2336c522db9d25..859930bdd01ded 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp @@ -1,9 +1,8 @@ -#include - #include "AP_NavEKF2_core.h" -extern const AP_HAL::HAL& hal; +#include "AP_NavEKF2.h" +#include /* Monitor GPS data to see if quality is good enough to initialise the EKF Monitor magnetometer innovations to see if the heading is good enough to use GPS diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index abc916f3332393..7b394a083ba6df 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -1,8 +1,10 @@ +#include "AP_NavEKF2_core.h" + #include +#include +#include #include "AP_NavEKF2.h" -#include "AP_NavEKF2_core.h" -#include extern const AP_HAL::HAL& hal; @@ -30,8 +32,8 @@ extern const AP_HAL::HAL& hal; // constructor NavEKF2_core::NavEKF2_core(NavEKF2 *_frontend) : - frontend(_frontend), - dal(AP::dal()) + dal(AP::dal()), + frontend(_frontend) { } @@ -99,7 +101,7 @@ bool NavEKF2_core::setup_core(uint8_t _imu_index, uint8_t _core_index) } // try to instantiate - yawEstimator = new EKFGSF_yaw(); + yawEstimator = NEW_NOTHROW EKFGSF_yaw(); if (yawEstimator == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF2 IMU%uGSF: allocation failed",(unsigned)imu_index); return false; @@ -243,9 +245,11 @@ void NavEKF2_core::InitialiseVariables() delAngBiasLearned = false; memset(&filterStatus, 0, sizeof(filterStatus)); activeHgtSource = 0; +#if AP_RANGEFINDER_ENABLED memset(&rngMeasIndex, 0, sizeof(rngMeasIndex)); memset(&storedRngMeasTime_ms, 0, sizeof(storedRngMeasTime_ms)); memset(&storedRngMeas, 0, sizeof(storedRngMeas)); +#endif terrainHgtStable = true; ekfOriginHgtVar = 0.0f; ekfGpsRefHgt = 0.0; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index d9f0adb2ce58a2..0dc9c6881908f8 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -29,7 +29,8 @@ #include #include #include -#include +#include +#include #include "AP_NavEKF/EKFGSF_yaw.h" @@ -70,12 +71,14 @@ #endif // maximum number of downward facing rangefinder instances available +#if AP_RANGEFINDER_ENABLED #if RANGEFINDER_MAX_INSTANCES > 1 #define DOWNWARD_RANGEFINDER_MAX_INSTANCES 2 #else #define DOWNWARD_RANGEFINDER_MAX_INSTANCES 1 #endif - +#endif + class AP_AHRS; class NavEKF2_core : public NavEKF_core_common @@ -339,7 +342,7 @@ class NavEKF2_core : public NavEKF_core_common private: EKFGSF_yaw *yawEstimator; - AP_DAL &dal; + class AP_DAL &dal; // Reference to the global EKF frontend for parameters class NavEKF2 *frontend; @@ -700,9 +703,11 @@ class NavEKF2_core : public NavEKF_core_common // update inflight calculaton that determines if GPS data is good enough for reliable navigation void calcGpsGoodForFlight(void); +#if AP_RANGEFINDER_ENABLED // Read the range finder and take new measurements if available // Apply a median filter to range finder data void readRangeFinder(); +#endif // check if the vehicle has taken off during optical flow navigation by looking at inertial and range finder data void detectOptFlowTakeoff(void); @@ -1014,9 +1019,11 @@ class NavEKF2_core : public NavEKF_core_common ftype rngOnGnd; // Expected range finder reading in metres when vehicle is on ground uint32_t lastRngMeasTime_ms; // Timestamp of last range measurement bool terrainHgtStable; // true when the terrain height is stable enough to be used as a height reference +#if AP_RANGEFINDER_ENABLED ftype storedRngMeas[DOWNWARD_RANGEFINDER_MAX_INSTANCES][3]; // Ringbuffer of stored range measurements for dual range sensors uint32_t storedRngMeasTime_ms[DOWNWARD_RANGEFINDER_MAX_INSTANCES][3]; // Ringbuffers of stored range measurement times for dual range sensors uint8_t rngMeasIndex[DOWNWARD_RANGEFINDER_MAX_INSTANCES]; // Current range measurement ringbuffer index for dual range sensors +#endif // Range Beacon Sensor Fusion EKF_obs_buffer_t storedRangeBeacon; // Beacon range buffer diff --git a/libraries/AP_NavEKF2/LogStructure.h b/libraries/AP_NavEKF2/LogStructure.h index 753d9ceb0f4b33..8d61f208c7a09f 100644 --- a/libraries/AP_NavEKF2/LogStructure.h +++ b/libraries/AP_NavEKF2/LogStructure.h @@ -1,7 +1,7 @@ #pragma once #include -#include +#include #define LOG_IDS_FROM_NAVEKF2 \ LOG_NKF0_MSG, \ @@ -100,8 +100,8 @@ struct PACKED log_NKF1 { // @Field: GSX: Gyro Scale Factor (X-axis) // @Field: GSY: Gyro Scale Factor (Y-axis) // @Field: GSZ: Gyro Scale Factor (Z-axis) -// @Field: VWN: Estimated wind velocity (North component) -// @Field: VWE: Estimated wind velocity (East component) +// @Field: VWN: Estimated wind velocity (moving-to-North component) +// @Field: VWE: Estimated wind velocity (moving-to-East component) // @Field: MN: Magnetic field strength (North component) // @Field: ME: Magnetic field strength (East component) // @Field: MD: Magnetic field strength (Down component) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 26bbeffc23d5e8..7e8dfadb0e5c5c 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1,3 +1,5 @@ +#include "AP_NavEKF3.h" + #include #include "AP_NavEKF3_core.h" @@ -734,10 +736,18 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Units: m AP_GROUPINFO("GPS_VACC_MAX", 10, NavEKF3, _gpsVAccThreshold, 0.0f), + // @Param: OPTIONS + // @DisplayName: Optional EKF behaviour + // @Description: This controls optional EKF behaviour. Setting JammingExpected will change the EKF nehaviour such that if dead reckoning navigation is possible it will require the preflight alignment GPS quality checks controlled by EK3_GPS_CHECK and EK3_CHECK_SCALE to pass before resuming GPS use if GPS lock is lost for more than 2 seconds to prevent bad + // @Bitmask: 0:JammingExpected + // @User: Advanced + AP_GROUPINFO("OPTIONS", 11, NavEKF3, _options, 0), + AP_GROUPEND }; -NavEKF3::NavEKF3() +NavEKF3::NavEKF3() : + dal{AP::dal()} { AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info2); @@ -750,11 +760,11 @@ bool NavEKF3::InitialiseFilter(void) if (_enable == 0 || _imuMask == 0) { return false; } - const auto &ins = AP::dal().ins(); + const auto &ins = dal.ins(); - AP::dal().start_frame(AP_DAL::FrameType::InitialiseFilterEKF3); + dal.start_frame(AP_DAL::FrameType::InitialiseFilterEKF3); - imuSampleTime_us = AP::dal().micros64(); + imuSampleTime_us = dal.micros64(); // remember expected frame time const float loop_rate = ins.get_loop_rate_hz(); @@ -800,7 +810,7 @@ bool NavEKF3::InitialiseFilter(void) } // check if there is enough memory to create the EKF cores - if (AP::dal().available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) { + if (dal.available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 not enough memory"); _enable.set(0); num_cores = 0; @@ -808,7 +818,7 @@ bool NavEKF3::InitialiseFilter(void) } //try to allocate from CCM RAM, fallback to Normal RAM if not available or full - core = (NavEKF3_core*)AP::dal().malloc_type(sizeof(NavEKF3_core)*num_cores, AP::dal().MEM_FAST); + core = (NavEKF3_core*)dal.malloc_type(sizeof(NavEKF3_core)*num_cores, AP_DAL::MemoryType::FAST); if (core == nullptr) { _enable.set(0); num_cores = 0; @@ -818,7 +828,7 @@ bool NavEKF3::InitialiseFilter(void) // Call constructors on all cores for (uint8_t i = 0; i < num_cores; i++) { - new (&core[i]) NavEKF3_core(this); + new (&core[i]) NavEKF3_core(this, dal); } } @@ -898,13 +908,13 @@ bool NavEKF3::coreBetterScore(uint8_t new_core, uint8_t current_core) const */ void NavEKF3::UpdateFilter(void) { - AP::dal().start_frame(AP_DAL::FrameType::UpdateFilterEKF3); + dal.start_frame(AP_DAL::FrameType::UpdateFilterEKF3); if (!core) { return; } - imuSampleTime_us = AP::dal().micros64(); + imuSampleTime_us = dal.micros64(); for (uint8_t i=0; i 1E7; } - const bool armed = AP::dal().get_armed(); + const bool armed = dal.get_armed(); // core selection is only available after the vehicle is armed, else forced to lane 0 if its healthy if (runCoreSelection && armed) { @@ -983,7 +993,7 @@ void NavEKF3::UpdateFilter(void) resetCoreErrors(); coreLastTimePrimary_us[primary] = imuSampleTime_us; primary = newPrimaryIndex; - lastLaneSwitch_ms = AP::dal().millis(); + lastLaneSwitch_ms = dal.millis(); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 lane switch %u", primary); } } @@ -1013,9 +1023,9 @@ void NavEKF3::UpdateFilter(void) */ void NavEKF3::checkLaneSwitch(void) { - AP::dal().log_event3(AP_DAL::Event::checkLaneSwitch); + dal.log_event3(AP_DAL::Event::checkLaneSwitch); - uint32_t now = AP::dal().millis(); + uint32_t now = dal.millis(); if (lastLaneSwitch_ms != 0 && now - lastLaneSwitch_ms < 5000) { // don't switch twice in 5 seconds return; @@ -1050,7 +1060,7 @@ void NavEKF3::checkLaneSwitch(void) void NavEKF3::requestYawReset(void) { - AP::dal().log_event3(AP_DAL::Event::requestYawReset); + dal.log_event3(AP_DAL::Event::requestYawReset); for (uint8_t i = 0; i < num_cores; i++) { core[i].EKFGSF_requestYawReset(); @@ -1100,9 +1110,9 @@ void NavEKF3::resetCoreErrors(void) 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)); + dal.log_event3(AP_DAL::Event(uint8_t(AP_DAL::Event::setSourceSet0)+source_set_idx)); } - sources.setPosVelYawSourceSet(source_set_idx); + sources.setPosVelYawSourceSet((AP_NavEKF_Source::SourceSetSelection)source_set_idx); } // Check basic filter health metrics and return a consolidated health status @@ -1128,21 +1138,21 @@ bool NavEKF3::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f const AP_NavEKF_Source::SourceYaw yaw_source = sources.getYawSource(); if (((magCalParamVal == 5) || (magCalParamVal == 6)) && (yaw_source != AP_NavEKF_Source::SourceYaw::GPS)) { // yaw source is configured to use compass but MAG_CAL valid is deprecated - AP::dal().snprintf(failure_msg, failure_msg_len, "EK3_MAG_CAL and EK3_SRC1_YAW inconsistent"); + dal.snprintf(failure_msg, failure_msg_len, "EK3_MAG_CAL and EK3_SRC1_YAW inconsistent"); return false; } if (!core) { - AP::dal().snprintf(failure_msg, failure_msg_len, "no EKF3 cores"); + dal.snprintf(failure_msg, failure_msg_len, "no EKF3 cores"); return false; } for (uint8_t i = 0; i < num_cores; i++) { if (!core[i].healthy()) { const char *failure = core[i].prearm_failure_reason(); if (failure != nullptr) { - AP::dal().snprintf(failure_msg, failure_msg_len, failure); + dal.snprintf(failure_msg, failure_msg_len, failure); } else { - AP::dal().snprintf(failure_msg, failure_msg_len, "EKF3 core %d unhealthy", (int)i); + dal.snprintf(failure_msg, failure_msg_len, "EKF3 core %d unhealthy", (int)i); } return false; } @@ -1256,7 +1266,7 @@ uint8_t NavEKF3::get_active_source_set() const // reset body axis gyro bias estimates void NavEKF3::resetGyroBias(void) { - AP::dal().log_event3(AP_DAL::Event::resetGyroBias); + dal.log_event3(AP_DAL::Event::resetGyroBias); if (core) { for (uint8_t i=0; i _log_level; // log verbosity level AP_Float _gpsVAccThreshold; // vertical accuracy threshold to use GPS as an altitude source + AP_Int32 _options; // bit mask of processing options + + // enum for processing options + enum class Option { + JammingExpected = (1<<0), + }; + bool option_is_enabled(Option option) const { + return (_options & (uint32_t)option) != 0; + } // Possible values for _flowUse #define FLOW_USE_NONE 0 @@ -487,6 +498,7 @@ class NavEKF3 { 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 before dead reckoning is declared (msec) + const uint16_t gpsNoFixTimeout_ms = 2000; // Time without a fix required to reset GPS alignment checks when EK3_OPTIONS bit 0 is set (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 38508e44a9a15c..c188681f0e6144 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp @@ -20,25 +20,19 @@ void NavEKF3_core::FuseAirspeed() { // declarations - ftype vn; - ftype ve; - ftype vd; - ftype vwn; - ftype vwe; ftype SH_TAS[3]; ftype SK_TAS[2]; Vector24 H_TAS = {}; - ftype VtasPred; // copy required states to local variable names - vn = stateStruct.velocity.x; - ve = stateStruct.velocity.y; - vd = stateStruct.velocity.z; - vwn = stateStruct.wind_vel.x; - vwe = stateStruct.wind_vel.y; + const ftype vn = stateStruct.velocity.x; + const ftype ve = stateStruct.velocity.y; + const ftype vd = stateStruct.velocity.z; + const ftype vwn = stateStruct.wind_vel.x; + const ftype vwe = stateStruct.wind_vel.y; // calculate the predicted airspeed - VtasPred = norm((ve - vwe) , (vn - vwn) , vd); + const ftype VtasPred = norm((ve - vwe) , (vn - vwn) , vd); // perform fusion of True Airspeed measurement if (VtasPred > 1.0f) { @@ -120,7 +114,7 @@ void NavEKF3_core::FuseAirspeed() zero_range(&Kfusion[0], 16, 21); } - if (tasDataDelayed.allowFusion && !inhibitWindStates) { + if (tasDataDelayed.allowFusion && !inhibitWindStates && !treatWindStatesAsTruth) { 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 { @@ -212,8 +206,10 @@ void NavEKF3_core::SelectTasFusion() readAirSpdData(); // if the filter is initialised, wind states are not inhibited and we have data to fuse, then perform TAS fusion + if (tasDataToFuse && statesInitialised && !inhibitWindStates) { FuseAirspeed(); + tasDataToFuse = false; prevTasStep_ms = imuSampleTime_ms; } } @@ -239,7 +235,8 @@ void NavEKF3_core::SelectBetaDragFusion() bool f_timeTrigger = ((imuSampleTime_ms - prevBetaDragStep_ms) >= frontend->betaAvg_ms); // use of air data to constrain drift is necessary if we have limited sensor data or are doing inertial dead reckoning - bool is_dead_reckoning = ((imuSampleTime_ms - lastPosPassTime_ms) > frontend->deadReckonDeclare_ms) && ((imuSampleTime_ms - lastVelPassTime_ms) > frontend->deadReckonDeclare_ms); + bool is_dead_reckoning = ((imuSampleTime_ms - lastGpsPosPassTime_ms) > frontend->deadReckonDeclare_ms) && + ((imuSampleTime_ms - lastVelPassTime_ms) > frontend->deadReckonDeclare_ms); const bool noYawSensor = !use_compass() && !using_noncompass_for_yaw(); const bool f_required = (noYawSensor && (frontend->_betaMask & (1<<1))) || is_dead_reckoning; @@ -256,10 +253,6 @@ void NavEKF3_core::SelectBetaDragFusion() // we are required to correct only wind states airDataFusionWindOnly = true; } - // Fuse estimated airspeed to aid wind estimation - if (usingDefaultAirspeed) { - FuseAirspeed(); - } FuseSideslip(); prevBetaDragStep_ms = imuSampleTime_ms; } @@ -281,15 +274,6 @@ void NavEKF3_core::SelectBetaDragFusion() void NavEKF3_core::FuseSideslip() { // declarations - ftype q0; - ftype q1; - ftype q2; - ftype q3; - ftype vn; - ftype ve; - ftype vd; - ftype vwn; - ftype vwe; const ftype R_BETA = 0.03f; // assume a sideslip angle RMS of ~10 deg Vector13 SH_BETA; Vector8 SK_BETA; @@ -297,15 +281,15 @@ void NavEKF3_core::FuseSideslip() Vector24 H_BETA; // copy required states to local variable names - q0 = stateStruct.quat[0]; - q1 = stateStruct.quat[1]; - q2 = stateStruct.quat[2]; - q3 = stateStruct.quat[3]; - vn = stateStruct.velocity.x; - ve = stateStruct.velocity.y; - vd = stateStruct.velocity.z; - vwn = stateStruct.wind_vel.x; - vwe = stateStruct.wind_vel.y; + const ftype q0 = stateStruct.quat[0]; + const ftype q1 = stateStruct.quat[1]; + const ftype q2 = stateStruct.quat[2]; + const ftype q3 = stateStruct.quat[3]; + const ftype vn = stateStruct.velocity.x; + const ftype ve = stateStruct.velocity.y; + const ftype vd = stateStruct.velocity.z; + const ftype vwn = stateStruct.wind_vel.x; + const ftype vwe = stateStruct.wind_vel.y; // calculate predicted wind relative velocity in NED vel_rel_wind.x = vn - vwn; @@ -424,7 +408,7 @@ void NavEKF3_core::FuseSideslip() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = SK_BETA[0]*(P[22][0]*SK_BETA[5] + P[22][1]*SK_BETA[4] - P[22][4]*SK_BETA[1] + P[22][5]*SK_BETA[2] + P[22][2]*SK_BETA[6] + P[22][6]*SK_BETA[3] - P[22][3]*SK_BETA[7] + P[22][22]*SK_BETA[1] - P[22][23]*SK_BETA[2]); Kfusion[23] = SK_BETA[0]*(P[23][0]*SK_BETA[5] + P[23][1]*SK_BETA[4] - P[23][4]*SK_BETA[1] + P[23][5]*SK_BETA[2] + P[23][2]*SK_BETA[6] + P[23][6]*SK_BETA[3] - P[23][3]*SK_BETA[7] + P[23][22]*SK_BETA[1] - P[23][23]*SK_BETA[2]); } else { @@ -485,8 +469,8 @@ void NavEKF3_core::FuseSideslip() #if EK3_FEATURE_DRAG_FUSION /* * Fuse X and Y body axis specific forces using explicit algebraic equations generated with SymPy. - * See AP_NavEKF3/derivation/main.py for derivation - * Output for change reference: AP_NavEKF3/derivation/generated/acc_bf_generated.cpp + * See derivation/generate_2.py for derivation + * Output for change reference: derivation/generated/acc_bf_generated.cpp */ void NavEKF3_core::FuseDragForces() { @@ -539,20 +523,20 @@ void NavEKF3_core::FuseDragForces() if (axis_index == 0) { // 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 + ftype Kaccx; // Derivative of specific force wrt airspeed if (using_mcoef && using_bcoef_x) { // mixed bluff body and propeller momentum drag const ftype airSpd = (bcoef_x / rho) * (- mcoef + sqrtF(sq(mcoef) + 2.0f * (rho / bcoef_x) * fabsF(mea_acc))); - Kacc = fmaxF(1e-1f, (rho / bcoef_x) * airSpd + mcoef * density_ratio); + Kaccx = fmaxF(1e-1f, (rho / bcoef_x) * airSpd + mcoef * density_ratio); predAccel = (0.5f / bcoef_x) * rho * sq(rel_wind_body[0]) * dragForceSign - rel_wind_body[0] * mcoef * density_ratio; } else if (using_mcoef) { // propeller momentum drag only - Kacc = fmaxF(1e-1f, mcoef * density_ratio); + Kaccx = fmaxF(1e-1f, mcoef * density_ratio); predAccel = - rel_wind_body[0] * mcoef * density_ratio; } else if (using_bcoef_x) { // bluff body drag only const ftype airSpd = sqrtF((2.0f * bcoef_x * fabsF(mea_acc)) / rho); - Kacc = fmaxF(1e-1f, (rho / bcoef_x) * airSpd); + Kaccx = fmaxF(1e-1f, (rho / bcoef_x) * airSpd); predAccel = (0.5f / bcoef_x) * rho * sq(rel_wind_body[0]) * dragForceSign; } else { // skip this axis @@ -563,12 +547,12 @@ void NavEKF3_core::FuseDragForces() const ftype HK0 = vn - vwn; const ftype HK1 = ve - vwe; const ftype HK2 = HK0*q0 + HK1*q3 - q2*vd; - const ftype HK3 = 2*Kacc; + const ftype HK3 = 2*Kaccx; const ftype HK4 = HK0*q1 + HK1*q2 + q3*vd; const ftype HK5 = HK0*q2 - HK1*q1 + q0*vd; const ftype HK6 = -HK0*q3 + HK1*q0 + q1*vd; const ftype HK7 = sq(q0) + sq(q1) - sq(q2) - sq(q3); - const ftype HK8 = HK7*Kacc; + const ftype HK8 = HK7*Kaccx; const ftype HK9 = q0*q3 + q1*q2; const ftype HK10 = HK3*HK9; const ftype HK11 = q0*q2 - q1*q3; @@ -581,7 +565,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK18 = -HK12*P[0][23] + HK12*P[0][5] - HK13*P[0][6] + HK14*P[0][1] + HK15*P[0][0] - HK16*P[0][2] + HK17*P[0][3] - HK7*P[0][22] + HK7*P[0][4]; const ftype HK19 = HK12*P[5][23]; const ftype HK20 = -HK12*P[23][23] - HK13*P[6][23] + HK14*P[1][23] + HK15*P[0][23] - HK16*P[2][23] + HK17*P[3][23] + HK19 - HK7*P[22][23] + HK7*P[4][23]; - const ftype HK21 = sq(Kacc); + const ftype HK21 = sq(Kaccx); const ftype HK22 = HK12*HK21; const ftype HK23 = HK12*P[5][5] - HK13*P[5][6] + HK14*P[1][5] + HK15*P[0][5] - HK16*P[2][5] + HK17*P[3][5] - HK19 + HK7*P[4][5] - HK7*P[5][22]; const ftype HK24 = HK12*P[5][6] - HK12*P[6][23] - HK13*P[6][6] + HK14*P[1][6] + HK15*P[0][6] - HK16*P[2][6] + HK17*P[3][6] + HK7*P[4][6] - HK7*P[6][22]; @@ -592,14 +576,14 @@ void NavEKF3_core::FuseDragForces() const ftype HK29 = -HK12*P[1][23] + HK12*P[1][5] - HK13*P[1][6] + HK14*P[1][1] + HK15*P[0][1] - HK16*P[1][2] + HK17*P[1][3] - HK7*P[1][22] + HK7*P[1][4]; const ftype HK30 = -HK12*P[2][23] + HK12*P[2][5] - HK13*P[2][6] + HK14*P[1][2] + HK15*P[0][2] - HK16*P[2][2] + HK17*P[2][3] - HK7*P[2][22] + HK7*P[2][4]; const ftype HK31 = -HK12*P[3][23] + HK12*P[3][5] - HK13*P[3][6] + HK14*P[1][3] + HK15*P[0][3] - HK16*P[2][3] + HK17*P[3][3] - HK7*P[3][22] + HK7*P[3][4]; - // const ftype HK32 = Kacc/(-HK13*HK21*HK24 + HK14*HK21*HK29 + HK15*HK18*HK21 - HK16*HK21*HK30 + HK17*HK21*HK31 - HK20*HK22 + HK22*HK23 + HK26*HK27 - HK27*HK28 + R_ACC); + // const ftype HK32 = Kaccx/(-HK13*HK21*HK24 + HK14*HK21*HK29 + HK15*HK18*HK21 - HK16*HK21*HK30 + HK17*HK21*HK31 - HK20*HK22 + HK22*HK23 + HK26*HK27 - HK27*HK28 + R_ACC); // calculate innovation variance and exit if badly conditioned innovDragVar.x = (-HK13*HK21*HK24 + HK14*HK21*HK29 + HK15*HK18*HK21 - HK16*HK21*HK30 + HK17*HK21*HK31 - HK20*HK22 + HK22*HK23 + HK26*HK27 - HK27*HK28 + R_ACC); if (innovDragVar.x < R_ACC) { return; } - const ftype HK32 = Kacc / innovDragVar.x; + const ftype HK32 = Kaccx / innovDragVar.x; // Observation Jacobians Hfusion[0] = -HK2*HK3; @@ -614,7 +598,7 @@ void NavEKF3_core::FuseDragForces() // Kalman gains // Don't allow modification of any states other than wind velocity - we only need a wind estimate. - // See AP_NavEKF3/derivation/generated/acc_bf_generated.cpp for un-implemented Kalman gain equations. + // See derivation/generated/acc_bf_generated.cpp for un-implemented Kalman gain equations. Kfusion[22] = -HK28*HK32; Kfusion[23] = -HK20*HK32; @@ -622,20 +606,20 @@ void NavEKF3_core::FuseDragForces() } else if (axis_index == 1) { // 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 + ftype Kaccy; // Derivative of specific force wrt airspeed if (using_mcoef && using_bcoef_y) { // mixed bluff body and propeller momentum drag const ftype airSpd = (bcoef_y / rho) * (- mcoef + sqrtF(sq(mcoef) + 2.0f * (rho / bcoef_y) * fabsF(mea_acc))); - Kacc = fmaxF(1e-1f, (rho / bcoef_y) * airSpd + mcoef * density_ratio); + Kaccy = fmaxF(1e-1f, (rho / bcoef_y) * airSpd + mcoef * density_ratio); predAccel = (0.5f / bcoef_y) * rho * sq(rel_wind_body[1]) * dragForceSign - rel_wind_body[1] * mcoef * density_ratio; } else if (using_mcoef) { // propeller momentum drag only - Kacc = fmaxF(1e-1f, mcoef * density_ratio); + Kaccy = fmaxF(1e-1f, mcoef * density_ratio); predAccel = - rel_wind_body[1] * mcoef * density_ratio; } else if (using_bcoef_y) { // bluff body drag only const ftype airSpd = sqrtF((2.0f * bcoef_y * fabsF(mea_acc)) / rho); - Kacc = fmaxF(1e-1f, (rho / bcoef_y) * airSpd); + Kaccy = fmaxF(1e-1f, (rho / bcoef_y) * airSpd); predAccel = (0.5f / bcoef_y) * rho * sq(rel_wind_body[1]) * dragForceSign; } else { // nothing more to do @@ -646,14 +630,14 @@ void NavEKF3_core::FuseDragForces() const ftype HK0 = ve - vwe; const ftype HK1 = vn - vwn; const ftype HK2 = HK0*q0 - HK1*q3 + q1*vd; - const ftype HK3 = 2*Kacc; + const ftype HK3 = 2*Kaccy; const ftype HK4 = -HK0*q1 + HK1*q2 + q0*vd; const ftype HK5 = HK0*q2 + HK1*q1 + q3*vd; const ftype HK6 = HK0*q3 + HK1*q0 - q2*vd; const ftype HK7 = q0*q3 - q1*q2; const ftype HK8 = HK3*HK7; const ftype HK9 = sq(q0) - sq(q1) + sq(q2) - sq(q3); - const ftype HK10 = HK9*Kacc; + const ftype HK10 = HK9*Kaccy; const ftype HK11 = q0*q1 + q2*q3; const ftype HK12 = 2*HK11; const ftype HK13 = 2*HK7; @@ -662,7 +646,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK16 = 2*HK4; const ftype HK17 = 2*HK6; const ftype HK18 = HK12*P[0][6] + HK13*P[0][22] - HK13*P[0][4] + HK14*P[0][2] + HK15*P[0][0] + HK16*P[0][1] - HK17*P[0][3] - HK9*P[0][23] + HK9*P[0][5]; - const ftype HK19 = sq(Kacc); + const ftype HK19 = sq(Kaccy); const ftype HK20 = HK12*P[6][6] - HK13*P[4][6] + HK13*P[6][22] + HK14*P[2][6] + HK15*P[0][6] + HK16*P[1][6] - HK17*P[3][6] + HK9*P[5][6] - HK9*P[6][23]; const ftype HK21 = HK13*P[4][22]; const ftype HK22 = HK12*P[6][22] + HK13*P[22][22] + HK14*P[2][22] + HK15*P[0][22] + HK16*P[1][22] - HK17*P[3][22] - HK21 - HK9*P[22][23] + HK9*P[5][22]; @@ -682,7 +666,7 @@ void NavEKF3_core::FuseDragForces() // calculation is badly conditioned return; } - const ftype HK32 = Kacc / innovDragVar.y; + const ftype HK32 = Kaccy / innovDragVar.y; // Observation Jacobians Hfusion[0] = -HK2*HK3; @@ -697,7 +681,7 @@ void NavEKF3_core::FuseDragForces() // Kalman gains // Don't allow modification of any states other than wind velocity at this stage of development - we only need a wind estimate. - // See AP_NavEKF3/derivation/generated/acc_bf_generated.cpp for un-implemented Kalman gain equations. + // See derivation/generated/acc_bf_generated.cpp for un-implemented Kalman gain equations. Kfusion[22] = -HK22*HK32; Kfusion[23] = -HK28*HK32; } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp index d2179f348cbeda..3eea5d16d20592 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp @@ -64,6 +64,7 @@ void NavEKF3_core::setWindMagStateLearningMode() PV_AidingMode != AID_NONE; if (!inhibitWindStates && !canEstimateWind) { inhibitWindStates = true; + lastAspdEstIsValid = false; updateStateIndexLim(); } else if (inhibitWindStates && canEstimateWind && (sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y) > sq(5.0f) || dragFusionEnabled)) { @@ -77,7 +78,7 @@ void NavEKF3_core::setWindMagStateLearningMode() Vector3F tempEuler; stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z); ftype trueAirspeedVariance; - const bool haveAirspeedMeasurement = usingDefaultAirspeed || (tasDataDelayed.allowFusion && (imuDataDelayed.time_ms - tasDataDelayed.time_ms < 500) && useAirspeed()); + const bool haveAirspeedMeasurement = (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; @@ -209,6 +210,24 @@ void NavEKF3_core::updateStateIndexLim() } } +// set the default yaw source +void NavEKF3_core::setYawSource() +{ + AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); + if (wasLearningCompass_ms > 0) { + // can't use compass while it is being calibrated + if (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS) { + yaw_source = AP_NavEKF_Source::SourceYaw::NONE; + } else if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + yaw_source = AP_NavEKF_Source::SourceYaw::GPS; + } + } + if (yaw_source != yaw_source_last) { + yaw_source_last = yaw_source; + yaw_source_reset = true; + } +} + // Set inertial navigation aiding mode void NavEKF3_core::setAidingMode() { @@ -218,6 +237,8 @@ void NavEKF3_core::setAidingMode() // Save the previous status so we can detect when it has changed PV_AidingModePrev = PV_AidingMode; + setYawSource(); + // Check that the gyro bias variance has converged checkGyroCalStatus(); @@ -268,7 +289,11 @@ void NavEKF3_core::setAidingMode() // GPS aiding is the preferred option unless excluded by the user if (readyToUseGPS() || readyToUseRangeBeacon() || readyToUseExtNav()) { PV_AidingMode = AID_ABSOLUTE; - } else if (readyToUseOptFlow() || readyToUseBodyOdm()) { + } else if ( +#if EK3_FEATURE_OPTFLOW_FUSION + readyToUseOptFlow() || +#endif + readyToUseBodyOdm()) { PV_AidingMode = AID_RELATIVE; } break; @@ -311,14 +336,23 @@ void NavEKF3_core::setAidingMode() #endif // Check if GPS or external nav is being used - bool posUsed = (imuSampleTime_ms - lastPosPassTime_ms <= minTestTime_ms); + bool posUsed = (imuSampleTime_ms - lastGpsPosPassTime_ms <= minTestTime_ms); 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 || dragUsed || rngBcnUsed || bodyOdmUsed; - // check if velocity drift has been constrained by a measurement source - bool velAiding = gpsVelUsed || airSpdUsed || dragUsed || optFlowUsed || bodyOdmUsed; + // Check if velocity drift has been constrained by a measurement source + // Currently these are all the same source as will stabilise attitude because we do not currently have + // a sensor that only observes attitude + velAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || dragUsed || rngBcnUsed || bodyOdmUsed; + + // Store the last valid airspeed estimate + windStateIsObservable = !inhibitWindStates && (posUsed || gpsVelUsed || optFlowUsed || rngBcnUsed || bodyOdmUsed); + if (windStateIsObservable) { + lastAirspeedEstimate = (stateStruct.velocity - Vector3F(stateStruct.wind_vel.x, stateStruct.wind_vel.y, 0.0F)).length(); + lastAspdEstIsValid = true; + } // check if position drift has been constrained by a measurement source bool posAiding = posUsed || rngBcnUsed; @@ -331,7 +365,7 @@ void NavEKF3_core::setAidingMode() #if EK3_FEATURE_BEACON_FUSION (imuSampleTime_ms - rngBcn.lastPassTime_ms > frontend->tiltDriftTimeMax_ms) && #endif - (imuSampleTime_ms - lastPosPassTime_ms > frontend->tiltDriftTimeMax_ms) && + (imuSampleTime_ms - lastGpsPosPassTime_ms > frontend->tiltDriftTimeMax_ms) && (imuSampleTime_ms - lastVelPassTime_ms > frontend->tiltDriftTimeMax_ms); } @@ -348,7 +382,7 @@ void NavEKF3_core::setAidingMode() #if EK3_FEATURE_BEACON_FUSION (imuSampleTime_ms - rngBcn.lastPassTime_ms > maxLossTime_ms) && #endif - (imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms); + (imuSampleTime_ms - lastGpsPosPassTime_ms > maxLossTime_ms); } if (attAidLossCritical) { @@ -402,11 +436,14 @@ void NavEKF3_core::setAidingMode() case AID_RELATIVE: // We are doing relative position navigation where velocity errors are constrained, but position drift will occur GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u started relative aiding",(unsigned)imu_index); +#if EK3_FEATURE_OPTFLOW_FUSION if (readyToUseOptFlow()) { // Reset time stamps flowValidMeaTime_ms = imuSampleTime_ms; prevFlowFuseTime_ms = imuSampleTime_ms; - } else if (readyToUseBodyOdm()) { + } else +#endif + if (readyToUseBodyOdm()) { // Reset time stamps lastbodyVelPassTime_ms = imuSampleTime_ms; prevBodyVelFuseTime_ms = imuSampleTime_ms; @@ -451,7 +488,7 @@ void NavEKF3_core::setAidingMode() velTimeout = false; // reset the last fusion accepted times to prevent unwanted activation of timeout logic - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; lastVelPassTime_ms = imuSampleTime_ms; #if EK3_FEATURE_BEACON_FUSION rngBcn.lastPassTime_ms = imuSampleTime_ms; @@ -500,6 +537,7 @@ bool NavEKF3_core::useRngFinder(void) const return true; } +#if EK3_FEATURE_OPTFLOW_FUSION // return true if the filter is ready to start using optical flow measurements bool NavEKF3_core::readyToUseOptFlow(void) const { @@ -515,6 +553,7 @@ bool NavEKF3_core::readyToUseOptFlow(void) const // We need stable roll/pitch angles and gyro bias estimates but do not need the yaw angle aligned to use optical flow return (imuSampleTime_ms - flowMeaTime_ms < 200) && tiltAlignComplete && delAngBiasLearned; } +#endif // EK3_FEATURE_OPTFLOW_FUSION // return true if the filter is ready to start using body frame odometry measurements bool NavEKF3_core::readyToUseBodyOdm(void) const @@ -583,9 +622,8 @@ bool NavEKF3_core::readyToUseExtNav(void) const // return true if we should use the compass bool NavEKF3_core::use_compass(void) const { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if ((yaw_source != AP_NavEKF_Source::SourceYaw::COMPASS) && - (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { + if ((yaw_source_last != AP_NavEKF_Source::SourceYaw::COMPASS) && + (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { // not using compass as a yaw source return false; } @@ -598,14 +636,13 @@ bool NavEKF3_core::use_compass(void) const // are we using (aka fusing) a non-compass yaw? bool NavEKF3_core::using_noncompass_for_yaw(void) const { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); #if EK3_FEATURE_EXTERNAL_NAV - if (yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { return ((imuSampleTime_ms - last_extnav_yaw_fusion_ms < 5000) || (imuSampleTime_ms - lastSynthYawTime_ms < 5000)); } #endif - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || - yaw_source == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || + yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()) { return imuSampleTime_ms - last_gps_yaw_ms < 5000 || imuSampleTime_ms - lastSynthYawTime_ms < 5000; } return false; @@ -615,7 +652,7 @@ bool NavEKF3_core::using_noncompass_for_yaw(void) const bool NavEKF3_core::using_extnav_for_yaw() const { #if EK3_FEATURE_EXTERNAL_NAV - if (frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { return ((imuSampleTime_ms - last_extnav_yaw_fusion_ms < 5000) || (imuSampleTime_ms - lastSynthYawTime_ms < 5000)); } #endif @@ -634,17 +671,26 @@ bool NavEKF3_core::assume_zero_sideslip(void) const } // sets the local NED origin using a LLH location (latitude, longitude, height) -// returns false if absolute aiding and GPS is being used or if the origin is already set +// returns false if the origin is already set bool NavEKF3_core::setOriginLLH(const Location &loc) { - if ((PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS)) { - // reject attempts to set the origin if GPS is being used or if the origin is already set - return false; - } - return setOrigin(loc); } +// populates the Earth magnetic field table using the given location +void NavEKF3_core::setEarthFieldFromLocation(const Location &loc) +{ + const auto &compass = dal.compass(); + if (compass.have_scale_factor(magSelectIndex) && + compass.auto_declination_enabled()) { + getEarthFieldTable(loc); + if (frontend->_mag_ef_limit > 0) { + // initialise earth field from tables + stateStruct.earth_magfield = table_earth_field_ga; + } + } +} + // sets the local NED origin using a LLH location (latitude, longitude, height) // returns false is the origin has already been set bool NavEKF3_core::setOrigin(const Location &loc) @@ -659,6 +705,13 @@ bool NavEKF3_core::setOrigin(const Location &loc) // define Earth rotation vector in the NED navigation frame at the origin calcEarthRateNED(earthRateNED, EKF_origin.lat); validOrigin = true; + + // but we do want to populate the WMM table even if we don't have a GPS at all + if (!stateStruct.quat.is_zero()) { + alignMagStateDeclination(); + setEarthFieldFromLocation(EKF_origin); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u origin set",(unsigned)imu_index); if (!frontend->common_origin_valid) { @@ -671,9 +724,11 @@ bool NavEKF3_core::setOrigin(const Location &loc) return true; } -// record a yaw reset event -void NavEKF3_core::recordYawReset() +// record all requested yaw resets completed +void NavEKF3_core::recordYawResetsCompleted() { + gpsYawResetRequest = false; + magYawResetRequest = false; yawAlignComplete = true; if (inFlight) { finalInflightYawInit = true; @@ -685,9 +740,8 @@ void NavEKF3_core::checkGyroCalStatus(void) { // check delta angle bias variances const ftype delAngBiasVarMax = sq(radians(0.15 * dtEkfAvg)); - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if (!use_compass() && (yaw_source != AP_NavEKF_Source::SourceYaw::GPS) && (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) && - (yaw_source != AP_NavEKF_Source::SourceYaw::EXTNAV)) { + if (!use_compass() && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS) && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) && + (yaw_source_last != AP_NavEKF_Source::SourceYaw::EXTNAV)) { // rotate the variances into earth frame and evaluate horizontal terms only as yaw component is poorly observable without a yaw reference // which can make this check fail const Vector3F delAngBiasVarVec { P[10][10], P[11][11], P[12][12] }; @@ -732,7 +786,7 @@ void NavEKF3_core::updateFilterStatus(void) 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.using_gps = ((imuSampleTime_ms - lastGpsPosPassTime_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 diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp index 93e3db98d5b905..50fa12558d2969 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp @@ -100,7 +100,10 @@ void NavEKF3_core::Log_Write_XKFS(uint64_t time_us) const baro_index : selected_baro, gps_index : selected_gps, airspeed_index : getActiveAirspeed(), - source_set : frontend->sources.getPosVelYawSourceSet() + source_set : frontend->sources.getPosVelYawSourceSet(), + gps_good_to_align : gpsGoodToAlign, + wait_for_gps_checks : waitingForGpsChecks, + mag_fusion: (uint8_t) magFusionSel }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } @@ -199,7 +202,11 @@ void NavEKF3_core::Log_Write_XKF5(uint64_t time_us) const 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 +#if EK3_FEATURE_OPTFLOW_FUSION errHAGL : (uint16_t)(100*sqrtF(Popt)), // note Popt is constrained to be non-negative in EstimateTerrainOffset() +#else + errHAGL : 0, // note Popt is constrained to be non-negative in EstimateTerrainOffset() +#endif angErr : (float)outputTrackError.x, // output predictor angle error velErr : (float)outputTrackError.y, // output predictor velocity error posErr : (float)outputTrackError.z // output predictor position tracking error diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp index 7d02dcec6f5bd2..a82a6e2e641546 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp @@ -62,9 +62,15 @@ void NavEKF3_core::controlMagYawReset() bool finalResetRequest = false; bool interimResetRequest = false; if (flightResetAllowed && !assume_zero_sideslip()) { +#if APM_BUILD_TYPE(APM_BUILD_ArduSub) + // for sub, we'd like to be far enough away from metal structures like docks and vessels + // diving 0.5m is reasonable for both open water and pools + finalResetRequest = (stateStruct.position.z - posDownAtTakeoff) > EKF3_MAG_FINAL_RESET_ALT_SUB; +#else // check that we have reached a height where ground magnetic interference effects are insignificant // and can perform a final reset of the yaw and field states finalResetRequest = (stateStruct.position.z - posDownAtTakeoff) < -EKF3_MAG_FINAL_RESET_ALT; +#endif // check for increasing height bool hgtIncreasing = (posDownAtLastMagReset-stateStruct.position.z) > 0.5f; @@ -154,25 +160,24 @@ void NavEKF3_core::realignYawGPS(bool emergency_reset) // If the angles disagree by more than 45 degrees and GPS innovations are large or no previous yaw alignment, we declare the magnetic yaw as bad bool badMagYaw = ((yawErr > 0.7854f) && (velTestRatio > 1.0f) && (PV_AidingMode == AID_ABSOLUTE)) || !yawAlignComplete; + // get yaw variance from GPS speed uncertainty + const ftype gpsVelAcc = fmaxF(gpsSpdAccuracy, ftype(frontend->_gpsHorizVelNoise)); + const ftype gps_yaw_variance = sq(asinF(constrain_float(gpsVelAcc/gpsDataDelayed.vel.xy().length(), -1.0F, 1.0F))); + if (gps_yaw_variance < sq(radians(GPS_VEL_YAW_ALIGN_MAX_ANG_ERR))) { + yawAlignGpsValidCount++; + } else { + yawAlignGpsValidCount = 0; + } + // correct yaw angle using GPS ground course if compass yaw bad if (badMagYaw) { // attempt to use EKF-GSF estimate if available as it is more robust to GPS glitches // by default fly forward vehicles use ground course for initial yaw unless the GSF is explicitly selected as the yaw source - const bool useGSF = !assume_zero_sideslip() || (frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::GSF); + const bool useGSF = !assume_zero_sideslip() || (yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF); if (useGSF && EKFGSF_resetMainFilterYaw(emergency_reset)) { return; } - // get yaw variance from GPS speed uncertainty - const ftype gpsVelAcc = fmaxF(gpsSpdAccuracy, ftype(frontend->_gpsHorizVelNoise)); - const ftype gps_yaw_variance = sq(asinF(constrain_float(gpsVelAcc/gpsDataDelayed.vel.xy().length(), -1.0F, 1.0F))); - - if (gps_yaw_variance < sq(radians(GPS_VEL_YAW_ALIGN_MAX_ANG_ERR))) { - yawAlignGpsValidCount++; - } else { - yawAlignGpsValidCount = 0; - } - if (yawAlignGpsValidCount >= GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD) { yawAlignGpsValidCount = 0; // keep roll and pitch and reset yaw @@ -194,6 +199,10 @@ void NavEKF3_core::realignYawGPS(bool emergency_reset) allMagSensorsFailed = false; } } + } else if (yawAlignGpsValidCount >= GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD) { + // There is no need to do a yaw reset + yawAlignGpsValidCount = 0; + recordYawResetsCompleted(); } } else { yawAlignGpsValidCount = 0; @@ -221,13 +230,6 @@ void NavEKF3_core::SelectMagFusion() // used for load levelling magFusePerformed = false; - // get default yaw source - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if (yaw_source != yaw_source_last) { - yaw_source_last = yaw_source; - yaw_source_reset = true; - } - // Store yaw angle when moving for use as a static reference when not moving if (!onGroundNotMoving) { if (fabsF(prevTnb[0][2]) < fabsF(prevTnb[1][2])) { @@ -245,13 +247,13 @@ void NavEKF3_core::SelectMagFusion() // Handle case where we are not using a yaw sensor of any type and attempt to reset the yaw in // flight using the output from the GSF yaw estimator or GPS ground course. - if ((yaw_source == AP_NavEKF_Source::SourceYaw::GSF) || + if ((yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) || (!use_compass() && - yaw_source != AP_NavEKF_Source::SourceYaw::GPS && - yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK && - yaw_source != AP_NavEKF_Source::SourceYaw::EXTNAV)) { + yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS && + yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK && + yaw_source_last != AP_NavEKF_Source::SourceYaw::EXTNAV)) { - if ((!yawAlignComplete || yaw_source_reset) && ((yaw_source != AP_NavEKF_Source::SourceYaw::GSF) || (EKFGSF_yaw_valid_count >= GSF_YAW_VALID_HISTORY_THRESHOLD))) { + if ((!yawAlignComplete || yaw_source_reset) && ((yaw_source_last != AP_NavEKF_Source::SourceYaw::GSF) || (EKFGSF_yaw_valid_count >= GSF_YAW_VALID_HISTORY_THRESHOLD))) { realignYawGPS(false); yaw_source_reset = false; } else { @@ -262,7 +264,7 @@ void NavEKF3_core::SelectMagFusion() // use the EKF-GSF yaw estimator output as this is more robust than the EKF can achieve without a yaw measurement // for non fixed wing platform types ftype gsfYaw, gsfYawVariance; - const bool didUseEKFGSF = yawAlignComplete && (yaw_source == AP_NavEKF_Source::SourceYaw::GSF) && EKFGSF_getYaw(gsfYaw, gsfYawVariance) && !assume_zero_sideslip() && fuseEulerYaw(yawFusionMethod::GSF); + const bool didUseEKFGSF = yawAlignComplete && (yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) && EKFGSF_getYaw(gsfYaw, gsfYawVariance) && !assume_zero_sideslip() && fuseEulerYaw(yawFusionMethod::GSF); // fallback methods if (!didUseEKFGSF) { @@ -283,7 +285,7 @@ void NavEKF3_core::SelectMagFusion() } // Handle case where we are using GPS yaw sensor instead of a magnetomer - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { bool have_fused_gps_yaw = false; if (storedYawAng.recall(yawAngDataDelayed,imuDataDelayed.time_ms)) { if (tiltAlignComplete && (!yawAlignComplete || yaw_source_reset)) { @@ -292,6 +294,7 @@ void NavEKF3_core::SelectMagFusion() have_fused_gps_yaw = true; lastSynthYawTime_ms = imuSampleTime_ms; last_gps_yaw_fuse_ms = imuSampleTime_ms; + recordYawResetsCompleted(); } else if (tiltAlignComplete && yawAlignComplete) { have_fused_gps_yaw = fuseEulerYaw(yawFusionMethod::GPS); if (have_fused_gps_yaw) { @@ -319,7 +322,7 @@ void NavEKF3_core::SelectMagFusion() yaw_source_reset = true; } - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS) { // no fallback return; } @@ -362,7 +365,7 @@ void NavEKF3_core::SelectMagFusion() #if EK3_FEATURE_EXTERNAL_NAV // Handle case where we are using an external nav for yaw const bool extNavYawDataToFuse = storedExtNavYawAng.recall(extNavYawAngDataDelayed, imuDataDelayed.time_ms); - if (yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { if (extNavYawDataToFuse) { if (tiltAlignComplete && (!yawAlignComplete || yaw_source_reset)) { alignYawAngle(extNavYawAngDataDelayed); @@ -397,7 +400,7 @@ void NavEKF3_core::SelectMagFusion() magTimeout = true; } - if (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + if (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { // check for and read new magnetometer measurements. We don't // read for GPS_COMPASS_FALLBACK as it has already been read // above @@ -409,8 +412,8 @@ void NavEKF3_core::SelectMagFusion() // Control reset of yaw and magnetic field states if we are using compass data if (magDataToFuse) { - if (yaw_source_reset && (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS || - yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { + if (yaw_source_reset && (yaw_source_last == AP_NavEKF_Source::SourceYaw::COMPASS || + yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { magYawResetRequest = true; yaw_source_reset = false; } @@ -423,12 +426,14 @@ void NavEKF3_core::SelectMagFusion() if (dataReady) { // use the simple method of declination to maintain heading if we cannot use the magnetic field states if(inhibitMagStates || magStateResetRequest || !magStateInitComplete) { + magFusionSel = MagFuseSel::FUSE_YAW; fuseEulerYaw(yawFusionMethod::MAGNETOMETER); // zero the test ratio output from the inactive 3-axis magnetometer fusion magTestRatio.zero(); } else { + magFusionSel = MagFuseSel::FUSE_MAG; // if we are not doing aiding with earth relative observations (eg GPS) then the declination is // maintained by fusing declination as a synthesised observation // We also fuse declination if we are using the WMM tables @@ -649,7 +654,7 @@ void NavEKF3_core::FuseMagnetometer() } // zero Kalman gains to inhibit wind state estimation - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] - P[22][2]*SH_MAG[1] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[4] - P[22][18]*SK_MX[3]); Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][1]*SH_MAG[0] - P[23][2]*SH_MAG[1] + P[23][3]*SH_MAG[2] + P[23][0]*SK_MX[2] - P[23][16]*SK_MX[1] + P[23][17]*SK_MX[4] - P[23][18]*SK_MX[3]); } else { @@ -732,7 +737,7 @@ void NavEKF3_core::FuseMagnetometer() } // zero Kalman gains to inhibit wind state estimation - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][0]*SH_MAG[2] + P[23][1]*SH_MAG[1] + P[23][2]*SH_MAG[0] - P[23][3]*SK_MY[2] - P[23][17]*SK_MY[1] - P[23][16]*SK_MY[3] + P[23][18]*SK_MY[4]); } else { @@ -816,7 +821,7 @@ void NavEKF3_core::FuseMagnetometer() } // zero Kalman gains to inhibit wind state estimation - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] - P[22][1]*SH_MAG[2] + P[22][3]*SH_MAG[0] + P[22][2]*SK_MZ[2] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[4] - P[22][17]*SK_MZ[3]); Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][0]*SH_MAG[1] - P[23][1]*SH_MAG[2] + P[23][3]*SH_MAG[0] + P[23][2]*SK_MZ[2] + P[23][18]*SK_MZ[1] + P[23][16]*SK_MZ[4] - P[23][17]*SK_MZ[3]); } else { @@ -909,7 +914,7 @@ void NavEKF3_core::FuseMagnetometer() /* * Fuse direct yaw measurements using explicit algebraic equations auto-generated from - * /AP_NavEKF3/derivation/main.py with output recorded in /AP_NavEKF3/derivation/generated/yaw_generated.cpp + * derivation/generate_2.py with output recorded in derivation/generated/yaw_generated.cpp * Returns true if the fusion was successful */ bool NavEKF3_core::fuseEulerYaw(yawFusionMethod method) @@ -1013,7 +1018,7 @@ bool NavEKF3_core::fuseEulerYaw(yawFusionMethod method) if (canUseA && (!canUseB || fabsF(SA5_inv) >= fabsF(SB5_inv))) { const ftype SA5 = 1.0F/SA5_inv; - const ftype SA6 = 1.0F/SA3; + const ftype SA6 = 1.0F/(SA3); const ftype SA7 = SA2*SA4; const ftype SA8 = 2*SA7; const ftype SA9 = 2*SA6; @@ -1024,7 +1029,7 @@ bool NavEKF3_core::fuseEulerYaw(yawFusionMethod method) H_YAW[3] = SA5*(SA0*SA7 + SA9*q0); } else if (canUseB && (!canUseA || fabsF(SB5_inv) > fabsF(SA5_inv))) { const ftype SB5 = 1.0F/SB5_inv; - const ftype SB6 = 1.0F/SB2; + const ftype SB6 = 1.0F/(SB2); const ftype SB7 = SB3*SB4; const ftype SB8 = 2*SB7; const ftype SB9 = 2*SB6; @@ -1073,7 +1078,7 @@ bool NavEKF3_core::fuseEulerYaw(yawFusionMethod method) if (canUseA && (!canUseB || fabsF(SA5_inv) >= fabsF(SB5_inv))) { const ftype SA5 = 1.0F/SA5_inv; - const ftype SA6 = 1.0F/SA3; + const ftype SA6 = 1.0F/(SA3); const ftype SA7 = SA2*SA4; const ftype SA8 = 2*SA7; const ftype SA9 = 2*SA6; @@ -1084,7 +1089,7 @@ bool NavEKF3_core::fuseEulerYaw(yawFusionMethod method) H_YAW[3] = SA5*(SA0*SA7 + SA9*q0); } else if (canUseB && (!canUseA || fabsF(SB5_inv) > fabsF(SA5_inv))) { const ftype SB5 = 1.0F/SB5_inv; - const ftype SB6 = 1.0F/SB2; + const ftype SB6 = 1.0F/(SB2); const ftype SB7 = SB3*SB4; const ftype SB8 = 2*SB7; const ftype SB9 = 2*SB6; @@ -1352,7 +1357,7 @@ void NavEKF3_core::FuseDeclination(ftype declErr) zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = -t4*t13*(P[22][16]*magE-P[22][17]*magN); Kfusion[23] = -t4*t13*(P[23][16]*magE-P[23][17]*magN); } else { @@ -1573,7 +1578,7 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw(bool emergency_reset) EKFGSF_yaw_reset_ms = imuSampleTime_ms; EKFGSF_yaw_reset_count++; - if ((frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::GSF) || + if ((yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) || !use_compass() || (dal.compass().get_num_enabled() == 0)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned using GPS",(unsigned)imu_index); } else { @@ -1586,7 +1591,7 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw(bool emergency_reset) } // record the yaw reset event - recordYawReset(); + recordYawResetsCompleted(); // reset velocity and position states to GPS - if yaw is fixed then the filter should start to operate correctly ResetVelocity(resetDataSource::DEFAULT); @@ -1662,10 +1667,5 @@ void NavEKF3_core::resetQuatStateYawOnly(ftype yaw, ftype yawVariance, rotationO lastYawReset_ms = imuSampleTime_ms; // record the yaw reset event - recordYawReset(); - - // clear all pending yaw reset requests - gpsYawResetRequest = false; - magYawResetRequest = false; - + recordYawResetsCompleted(); } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 9ebe777515a84e..a7146dd06e71bf 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -1,11 +1,13 @@ -#include - #include "AP_NavEKF3_core.h" + +#include "AP_NavEKF3.h" + #include #include #include #include +#if AP_RANGEFINDER_ENABLED /******************************************************** * OPT FLOW AND RANGE FINDER * ********************************************************/ @@ -105,6 +107,7 @@ void NavEKF3_core::readRangeFinder(void) } } } +#endif // AP_RANGEFINDER_ENABLED void NavEKF3_core::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset) { @@ -165,6 +168,7 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam #endif // EK3_FEATURE_BODY_ODOM } +#if EK3_FEATURE_OPTFLOW_FUSION // write the raw optical flow measurements // this needs to be called externally. void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, float heightOverride) @@ -233,6 +237,7 @@ void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f storedOF.push(ofDataNew); } } +#endif // EK3_FEATURE_OPTFLOW_FUSION /******************************************************** @@ -295,16 +300,10 @@ void NavEKF3_core::readMagData() } if (compass.learn_offsets_enabled()) { - // while learning offsets keep all mag states reset - InitialiseVariablesMag(); wasLearningCompass_ms = imuSampleTime_ms; } else if (wasLearningCompass_ms != 0 && imuSampleTime_ms - wasLearningCompass_ms > 1000) { + // allow time for old data to clear the buffer before signalling other code that compass data can be used wasLearningCompass_ms = 0; - // force a new yaw alignment 1s after learning completes. The - // delay is to ensure any buffered mag samples are discarded - yawAlignComplete = false; - yawAlignGpsValidCount = 0; - InitialiseVariablesMag(); } // If the magnetometer has timed out (been rejected for too long), we find another magnetometer to use if available @@ -378,7 +377,7 @@ void NavEKF3_core::readMagData() * Downsampling is done using a method that does not introduce coning or sculling * errors. */ -void NavEKF3_core::readIMUData() +void NavEKF3_core::readIMUData(bool startPredictEnabled) { const auto &ins = dal.ins(); @@ -393,13 +392,13 @@ void NavEKF3_core::readIMUData() if (ins.use_accel(imu_index)) { accel_active = imu_index; } else { - accel_active = ins.get_primary_accel(); + accel_active = ins.get_first_usable_accel(); } if (ins.use_gyro(imu_index)) { gyro_active = imu_index; } else { - gyro_active = ins.get_primary_gyro(); + gyro_active = ins.get_first_usable_gyro(); } if (gyro_active != gyro_index_active) { @@ -639,6 +638,27 @@ void NavEKF3_core::readGpsData() useGpsVertVel = false; } + if (frontend->option_is_enabled(NavEKF3::Option::JammingExpected) && + (lastTimeGpsReceived_ms - secondLastGpsTime_ms) > frontend->gpsNoFixTimeout_ms) { + const bool doingBodyVelNav = (imuSampleTime_ms - prevBodyVelFuseTime_ms < 1000); + const bool doingFlowNav = (imuSampleTime_ms - prevFlowFuseTime_ms < 1000);; + const bool canDoWindRelNav = assume_zero_sideslip(); + const bool canDeadReckon = ((doingFlowNav && gndOffsetValid) || canDoWindRelNav || doingBodyVelNav); + if (canDeadReckon) { + // If we can do dead reckoning with a data source other than GPS there is time to wait + // for GPS alignment checks to pass before using GPS inside the EKF. + // this gets set back to false in calcGpsGoodToAlign() when GPS checks pass + waitingForGpsChecks = true; + // force GPS checks to restart + lastPreAlignGpsCheckTime_ms = 0; + lastGpsVelFail_ms = imuSampleTime_ms; + lastGpsVelPass_ms = 0; + gpsGoodToAlign = false; + } else { + waitingForGpsChecks = false; + } + } + // Monitor quality of the GPS velocity data before and after alignment calcGpsGoodToAlign(); @@ -675,24 +695,19 @@ void NavEKF3_core::readGpsData() } if (gpsGoodToAlign && !have_table_earth_field) { - const auto &compass = dal.compass(); - if (compass.have_scale_factor(magSelectIndex) && - compass.auto_declination_enabled()) { - getEarthFieldTable(gpsloc); - if (frontend->_mag_ef_limit > 0) { - // initialise earth field from tables - stateStruct.earth_magfield = table_earth_field_ga; - } - } + setEarthFieldFromLocation(gpsloc); } // convert GPS measurements to local NED and save to buffer to be fused later if we have a valid origin - if (validOrigin) { + // and are not waiting for GPs checks to pass + if (validOrigin && !waitingForGpsChecks) { gpsDataNew.lat = gpsloc.lat; gpsDataNew.lng = gpsloc.lng; if ((frontend->_originHgtMode & (1<<2)) == 0) { + // the height adjustment to match GPS is being achieved by adjusting the origin height gpsDataNew.hgt = (ftype)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt); } else { + // the height adjustment to match GPS is being achieved by adjusting the measurements gpsDataNew.hgt = 0.01 * (gpsloc.alt - EKF_origin.alt); } storedGPS.push(gpsDataNew); @@ -832,37 +847,52 @@ void NavEKF3_core::readAirSpdData() // we take a new reading, convert from EAS to TAS and set the flag letting other functions // know a new measurement is available - const auto *airspeed = dal.airspeed(); - if (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; - - // Save data into the buffer to be fused when the fusion time horizon catches up with it - storedTAS.push(tasDataNew); - } - - // Check the buffer for measurements that have been overtaken by the fusion time horizon and need to be fused - tasDataToFuse = storedTAS.recall(tasDataDelayed,imuDataDelayed.time_ms); - - float easErrVar = sq(MAX(frontend->_easNoise, 0.5f)); - // Allow use of a default value if enabled - if (!useAirspeed() && - imuDataDelayed.time_ms - tasDataDelayed.time_ms > 200 && - is_positive(defaultAirSpeed)) { - tasDataDelayed.tas = defaultAirSpeed * EAS2TAS; - tasDataDelayed.tasVariance = sq(MAX(defaultAirSpeedVariance, easErrVar)); - tasDataDelayed.allowFusion = true; - tasDataDelayed.time_ms = 0; - usingDefaultAirspeed = true; + if (useAirspeed()) { + const auto *airspeed = dal.airspeed(); + if (airspeed && + (airspeed->last_update_ms(selected_airspeed) - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) { + tasDataNew.allowFusion = airspeed->healthy(selected_airspeed) && airspeed->use(selected_airspeed); + if (tasDataNew.allowFusion) { + 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)); + // Correct for the average intersampling delay due to the filter update rate + tasDataNew.time_ms -= localFilterTimeStep_ms/2; + // Save data into the buffer to be fused when the fusion time horizon catches up with it + storedTAS.push(tasDataNew); + } + } + // Check the buffer for measurements that have been overtaken by the fusion time horizon and need to be fused + tasDataToFuse = storedTAS.recall(tasDataDelayed,imuDataDelayed.time_ms); } else { - usingDefaultAirspeed = false; + if (is_positive(defaultAirSpeed)) { + // this is the preferred method with the autopilot providing a model based airspeed estimate + if (imuDataDelayed.time_ms - prevTasStep_ms > 200 ) { + tasDataDelayed.tas = defaultAirSpeed * EAS2TAS; + tasDataDelayed.tasVariance = MAX(defaultAirSpeedVariance, sq(MAX(frontend->_easNoise, 0.5f))); + tasDataToFuse = true; + tasDataDelayed.allowFusion = true; + tasDataDelayed.time_ms = imuDataDelayed.time_ms; + } else { + tasDataToFuse = false; + tasDataDelayed.allowFusion = false; + } + } else if (lastAspdEstIsValid && !windStateIsObservable) { + // this uses the last airspeed estimated before dead reckoning started and + // wind states became unobservable + if (lastAspdEstIsValid && imuDataDelayed.time_ms - prevTasStep_ms > 200) { + tasDataDelayed.tas = lastAirspeedEstimate; + // this airspeed estimate has a lot of uncertainty + tasDataDelayed.tasVariance = sq(MAX(MAX(frontend->_easNoise, 0.5f), 0.5f * lastAirspeedEstimate)); + tasDataToFuse = true; + tasDataDelayed.allowFusion = true; + tasDataDelayed.time_ms = imuDataDelayed.time_ms; + } else { + tasDataToFuse = false; + tasDataDelayed.allowFusion = false; + } + } } } @@ -1329,9 +1359,8 @@ ftype NavEKF3_core::MagDeclination(void) const */ void NavEKF3_core::updateMovementCheck(void) { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - const bool runCheck = onGround && (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || - yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV || yaw_source == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()); + const bool runCheck = onGround && (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || + yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV || yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()); if (!runCheck) { onGroundNotMoving = false; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp index e457bf7a03e524..d9fed204e34259 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp @@ -1,8 +1,13 @@ #include #include "AP_NavEKF3.h" + #include "AP_NavEKF3_core.h" + +#if EK3_FEATURE_OPTFLOW_FUSION + #include +#include /******************************************************** * RESET FUNCTIONS * @@ -491,7 +496,7 @@ void NavEKF3_core::FuseOptFlow(const of_elements &ofDataDelayed, bool really_fus zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = t78*(P[22][0]*t2*t5-P[22][4]*t2*t7+P[22][1]*t2*t15+P[22][6]*t2*t10+P[22][2]*t2*t19-P[22][3]*t2*t22+P[22][5]*t2*t27); Kfusion[23] = t78*(P[23][0]*t2*t5-P[23][4]*t2*t7+P[23][1]*t2*t15+P[23][6]*t2*t10+P[23][2]*t2*t19-P[23][3]*t2*t22+P[23][5]*t2*t27); } else { @@ -668,7 +673,7 @@ void NavEKF3_core::FuseOptFlow(const of_elements &ofDataDelayed, bool really_fus zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = -t78*(P[22][0]*t2*t5+P[22][5]*t2*t8-P[22][6]*t2*t10+P[22][1]*t2*t16-P[22][2]*t2*t19+P[22][3]*t2*t22+P[22][4]*t2*t27); Kfusion[23] = -t78*(P[23][0]*t2*t5+P[23][5]*t2*t8-P[23][6]*t2*t10+P[23][1]*t2*t16-P[23][2]*t2*t19+P[23][3]*t2*t22+P[23][4]*t2*t27); } else { @@ -779,3 +784,4 @@ bool NavEKF3_core::getOptFlowSample(uint32_t& timestamp_ms, Vector2f& flowRate, * MISC FUNCTIONS * ********************************************************/ +#endif // EK3_FEATURE_OPTFLOW_FUSION diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 04bf81ec208299..8fc369c392f7d8 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -68,12 +68,16 @@ bool NavEKF3_core::getHeightControlLimit(float &height) const // only ask for limiting if we are doing optical flow navigation if (frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::OPTFLOW) && (PV_AidingMode == AID_RELATIVE) && flowDataValid) { // If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors +#if AP_RANGEFINDER_ENABLED const auto *_rng = dal.rangefinder(); if (_rng == nullptr) { // we really, really shouldn't be here. return false; } height = MAX(float(_rng->max_distance_cm_orient(ROTATION_PITCH_270)) * 0.007f - 1.0f, 1.0f); +#else + return false; +#endif // If we are are not using the range finder as the height reference, then compensate for the difference between terrain and EKF origin if (frontend->sources.getPosZSource() != AP_NavEKF_Source::SourceZ::RANGEFINDER) { height -= terrainState; @@ -260,17 +264,7 @@ bool NavEKF3_core::getPosNE(Vector2f &posNE) const // Return true if the estimate is valid 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) - // Also correct for changes to the origin height - if ((frontend->_originHgtMode & (1<<2)) == 0) { - // Any sensor height drift corrections relative to the WGS-84 reference are applied to the origin. - posD = outputDataNew.position.z + posOffsetNED.z; - } else { - // The origin height is static and corrections are applied to the local vertical position - // so that height returned by getLLH() = height returned by getOriginLLH - posD - posD = outputDataNew.position.z + posOffsetNED.z + 0.01f * (float)EKF_origin.alt - (float)ekfGpsRefHgt; - } + posD = outputDataNew.position.z + posOffsetNED.z; // Return the current height solution status return filterStatus.flags.vert_pos; @@ -493,7 +487,7 @@ bool NavEKF3_core::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::Sour switch (source) { case AP_NavEKF_Source::SourceXY::GPS: // check for timeouts - if (dal.millis() - gpsVelInnovTime_ms > 500) { + if (dal.millis() - gpsRetrieveTime_ms > 500) { return false; } innovations = gpsVelInnov.tofloat(); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index 3810c672b6cdae..98aaf8cd27fbf7 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -13,6 +13,26 @@ // Do not reset vertical velocity using GPS as there is baro alt available to constrain drift void NavEKF3_core::ResetVelocity(resetDataSource velResetSource) { + // if reset source is not specified then use user defined velocity source + if (velResetSource == resetDataSource::DEFAULT) { + switch (frontend->sources.getVelXYSource()) { + case AP_NavEKF_Source::SourceXY::GPS: + velResetSource = resetDataSource::GPS; + break; + case AP_NavEKF_Source::SourceXY::BEACON: + velResetSource = resetDataSource::RNGBCN; + break; + case AP_NavEKF_Source::SourceXY::EXTNAV: + velResetSource = resetDataSource::EXTNAV; + break; + case AP_NavEKF_Source::SourceXY::NONE: + case AP_NavEKF_Source::SourceXY::OPTFLOW: + case AP_NavEKF_Source::SourceXY::WHEEL_ENCODER: + // unhandled sources so stick with the default + break; + } + } + // Store the velocity before the reset so that we can record the reset delta velResetNE.x = stateStruct.velocity.x; velResetNE.y = stateStruct.velocity.y; @@ -73,6 +93,26 @@ void NavEKF3_core::ResetVelocity(resetDataSource velResetSource) // resets position states to last GPS measurement or to zero if in constant position mode void NavEKF3_core::ResetPosition(resetDataSource posResetSource) { + // if reset source is not specified thenn use the user defined position source + if (posResetSource == resetDataSource::DEFAULT) { + switch (frontend->sources.getPosXYSource()) { + case AP_NavEKF_Source::SourceXY::GPS: + posResetSource = resetDataSource::GPS; + break; + case AP_NavEKF_Source::SourceXY::BEACON: + posResetSource = resetDataSource::RNGBCN; + break; + case AP_NavEKF_Source::SourceXY::EXTNAV: + posResetSource = resetDataSource::EXTNAV; + break; + case AP_NavEKF_Source::SourceXY::NONE: + case AP_NavEKF_Source::SourceXY::OPTFLOW: + case AP_NavEKF_Source::SourceXY::WHEEL_ENCODER: + // invalid sources so stick with the default + break; + } + } + // Store the position before the reset so that we can record the reset delta posResetNE.x = stateStruct.position.x; posResetNE.y = stateStruct.position.y; @@ -141,7 +181,7 @@ void NavEKF3_core::ResetPosition(resetDataSource posResetSource) // clear the timeout flags and counters posTimeout = false; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; } #if EK3_FEATURE_POSITION_RESET @@ -150,7 +190,7 @@ void NavEKF3_core::ResetPosition(resetDataSource posResetSource) // Returns true if the set was successful bool NavEKF3_core::setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms) { - if ((imuSampleTime_ms - lastPosPassTime_ms) < frontend->deadReckonDeclare_ms || + if ((imuSampleTime_ms - lastGpsPosPassTime_ms) < frontend->deadReckonDeclare_ms || (PV_AidingMode == AID_NONE) || !validOrigin) { return false; @@ -494,13 +534,14 @@ void NavEKF3_core::SelectVelPosFusion() readGpsYawData(); // get data that has now fallen behind the fusion time horizon - gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms); + gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms) && !waitingForGpsChecks; + if (gpsDataToFuse) { CorrectGPSForAntennaOffset(gpsDataDelayed); // 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 = dal.millis(); + // record time GPS data was retrieved from the buffer (for timeout checks) + gpsRetrieveTime_ms = dal.millis(); } // detect position source changes. Trigger position reset if position source is valid @@ -774,17 +815,17 @@ void NavEKF3_core::FuseVelPosNED() posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2; if (posTestRatio < 1.0f || (PV_AidingMode == AID_NONE)) { posCheckPassed = true; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; } else if ((frontend->_gpsGlitchRadiusMax <= 0) && (PV_AidingMode != AID_NONE)) { // Handle the special case where the glitch radius parameter has been set to a non-positive number. // The innovation variance is increased to limit the state update to an amount corresponding // to a test ratio of 1. posCheckPassed = true; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; varInnovVelPos[3] *= posTestRatio; varInnovVelPos[4] *= posTestRatio; posCheckPassed = true; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; } // Use position data if healthy or timed out or bad IMU data @@ -794,7 +835,7 @@ void NavEKF3_core::FuseVelPosNED() // if timed out or outside the specified uncertainty radius, reset to the external sensor // if velocity drift is being constrained, dont reset until gps passes quality checks const bool posVarianceIsTooLarge = (frontend->_gpsGlitchRadiusMax > 0) && (P[8][8] + P[7][7]) > sq(ftype(frontend->_gpsGlitchRadiusMax)); - if (posTimeout || posVarianceIsTooLarge) { + if ((posTimeout || posVarianceIsTooLarge) && (!velAiding || gpsGoodToAlign)) { // reset the position to the current external sensor position ResetPosition(resetDataSource::DEFAULT); @@ -855,7 +896,7 @@ void NavEKF3_core::FuseVelPosNED() // The innovation variance is increased to limit the state update to an amount corresponding // to a test ratio of 1. posCheckPassed = true; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; for (uint8_t i = 0; i<=imax; i++) { varInnovVelPos[i] *= velTestRatio; } @@ -903,7 +944,7 @@ void NavEKF3_core::FuseVelPosNED() // The innovation variance is increased to limit the state update to an amount corresponding // to a test ratio of 1. posCheckPassed = true; - lastPosPassTime_ms = imuSampleTime_ms; + lastGpsPosPassTime_ms = imuSampleTime_ms; varInnovVelPos[5] *= hgtTestRatio; hgtCheckPassed = true; lastHgtPassTime_ms = imuSampleTime_ms; @@ -1045,7 +1086,7 @@ void NavEKF3_core::FuseVelPosNED() } // inhibit wind state estimation by setting Kalman gains to zero - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = P[22][stateIndex]*SK; Kfusion[23] = P[23][stateIndex]*SK; } else { @@ -1127,6 +1168,7 @@ void NavEKF3_core::FuseVelPosNED() // select the height measurement to be fused from the available baro, range finder and GPS sources void NavEKF3_core::selectHeightForFusion() { +#if AP_RANGEFINDER_ENABLED // Read range finder data and check for new data in the buffer // This data is used by both height and optical flow fusion processing readRangeFinder(); @@ -1146,6 +1188,7 @@ void NavEKF3_core::selectHeightForFusion() } } } +#endif // AP_RANGEFINDER_ENABLED // read baro height data from the sensor and check for new data in the buffer readBaroData(); @@ -1159,6 +1202,7 @@ void NavEKF3_core::selectHeightForFusion() if ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::NONE)) { // user has specified no height sensor activeHgtSource = AP_NavEKF_Source::SourceZ::NONE; +#if AP_RANGEFINDER_ENABLED } else if ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::RANGEFINDER) && _rng && rangeFinderDataIsFresh) { // user has specified the range finder as a primary height source activeHgtSource = AP_NavEKF_Source::SourceZ::RANGEFINDER; @@ -1200,6 +1244,7 @@ void NavEKF3_core::selectHeightForFusion() // reliable terrain and range finder so start using range finder height activeHgtSource = AP_NavEKF_Source::SourceZ::RANGEFINDER; } +#endif } else if (frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::BARO) { activeHgtSource = AP_NavEKF_Source::SourceZ::BARO; } else if ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) { @@ -1278,6 +1323,11 @@ void NavEKF3_core::selectHeightForFusion() hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd); // correct for terrain position relative to datum hgtMea -= terrainState; + // correct sensor so that local position height adjusts to match GPS + if (frontend->_originHgtMode & (1 << 1) && frontend->_originHgtMode & (1 << 2)) { + // offset has to be applied to the measurement, not the NED origin + hgtMea += (float)(ekfGpsRefHgt - 0.01 * (double)EKF_origin.alt); + } velPosObs[5] = -hgtMea; // enable fusion fuseHgtData = true; @@ -1304,6 +1354,10 @@ void NavEKF3_core::selectHeightForFusion() } else if (baroDataToFuse && (activeHgtSource == AP_NavEKF_Source::SourceZ::BARO)) { // using Baro data hgtMea = baroDataDelayed.hgt - baroHgtOffset; + // correct sensor so that local position height adjusts to match GPS + if (frontend->_originHgtMode & (1 << 0) && frontend->_originHgtMode & (1 << 2)) { + hgtMea += (float)(ekfGpsRefHgt - 0.01 * (double)EKF_origin.alt); + } // enable fusion fuseHgtData = true; // set the observation noise @@ -1553,7 +1607,7 @@ void NavEKF3_core::FuseBodyVel() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = t77*(P[22][5]*t4+P[22][4]*t9+P[22][0]*t14-P[22][6]*t11+P[22][1]*t18-P[22][2]*t21+P[22][3]*t24); Kfusion[23] = t77*(P[23][5]*t4+P[23][4]*t9+P[23][0]*t14-P[23][6]*t11+P[23][1]*t18-P[23][2]*t21+P[23][3]*t24); } else { @@ -1730,7 +1784,7 @@ void NavEKF3_core::FuseBodyVel() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = t77*(-P[22][4]*t3+P[22][5]*t8+P[22][0]*t15+P[22][6]*t12+P[22][1]*t18+P[22][2]*t22-P[22][3]*t25); Kfusion[23] = t77*(-P[23][4]*t3+P[23][5]*t8+P[23][0]*t15+P[23][6]*t12+P[23][1]*t18+P[23][2]*t22-P[23][3]*t25); } else { @@ -1908,7 +1962,7 @@ void NavEKF3_core::FuseBodyVel() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = t77*(P[22][4]*t4+P[22][0]*t14+P[22][6]*t9-P[22][5]*t11-P[22][1]*t17+P[22][2]*t20+P[22][3]*t24); Kfusion[23] = t77*(P[23][4]*t4+P[23][0]*t14+P[23][6]*t9-P[23][5]*t11-P[23][1]*t17+P[23][2]*t20+P[23][3]*t24); } else { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp index 6fc98f08148297..0d3125d8dd7c90 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp @@ -3,6 +3,8 @@ #if EK3_FEATURE_BEACON_FUSION +#include + // initialise state: void NavEKF3_core::BeaconFusion::InitialiseVariables() { @@ -40,10 +42,10 @@ void NavEKF3_core::BeaconFusion::InitialiseVariables() delete[] fusionReport; fusionReport = nullptr; numFusionReports = 0; - auto *beacon = AP::dal().beacon(); + auto *beacon = dal.beacon(); if (beacon != nullptr) { const uint8_t count = beacon->count(); - fusionReport = new BeaconFusion::FusionReport[count]; + fusionReport = NEW_NOTHROW BeaconFusion::FusionReport[count]; if (fusionReport != nullptr) { numFusionReports = count; } @@ -234,7 +236,7 @@ void NavEKF3_core::FuseRngBcn() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (!inhibitWindStates && !treatWindStatesAsTruth) { Kfusion[22] = -t26*(P[22][7]*t4*t9+P[22][8]*t3*t9+P[22][9]*t2*t9); Kfusion[23] = -t26*(P[23][7]*t4*t9+P[23][8]*t3*t9+P[23][9]*t2*t9); } else { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp index 47e42773613fff..3fd1c80e2bf5c1 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp @@ -1,6 +1,7 @@ -#include - #include "AP_NavEKF3_core.h" + +#include "AP_NavEKF3.h" + #include /* Monitor GPS data to see if quality is good enough to initialise the EKF @@ -12,7 +13,7 @@ */ void NavEKF3_core::calcGpsGoodToAlign(void) { - if (inFlight && assume_zero_sideslip() && !use_compass()) { + if (inFlight && !finalInflightYawInit && assume_zero_sideslip() && !use_compass()) { // this is a special case where a plane has launched without magnetometer // is now in the air and needs to align yaw to the GPS and start navigating as soon as possible gpsGoodToAlign = true; @@ -230,6 +231,10 @@ void NavEKF3_core::calcGpsGoodToAlign(void) } else if (gpsGoodToAlign && imuSampleTime_ms - lastGpsVelPass_ms > 5000) { gpsGoodToAlign = false; } + + if (gpsGoodToAlign && waitingForGpsChecks) { + waitingForGpsChecks = false; + } } // update inflight calculaton that determines if GPS data is good enough for reliable navigation @@ -379,6 +384,17 @@ void NavEKF3_core::detectFlight() } if (!onGround) { +#if APM_BUILD_TYPE(APM_BUILD_ArduSub) + // If depth has increased since arming, then we definitely are diving + if ((stateStruct.position.z - posDownAtTakeoff) > 1.5f) { + inFlight = true; + } + + // If rangefinder has decreased since arming, then we definitely are diving + if ((rangeDataNew.rng - rngAtStartOfFlight) < -0.5f) { + inFlight = true; + } +#else // If height has increased since exiting on-ground, then we definitely are flying if ((stateStruct.position.z - posDownAtTakeoff) < -1.5f) { inFlight = true; @@ -388,6 +404,7 @@ void NavEKF3_core::detectFlight() if ((rangeDataNew.rng - rngAtStartOfFlight) > 0.5f) { inFlight = true; } +#endif // If more than 5 seconds since likely_flying was set // true, then set inFlight true @@ -444,6 +461,7 @@ void NavEKF3_core::setTerrainHgtStable(bool val) terrainHgtStable = val; } +#if EK3_FEATURE_OPTFLOW_FUSION // Detect takeoff for optical flow navigation void NavEKF3_core::detectOptFlowTakeoff(void) { @@ -461,4 +479,4 @@ void NavEKF3_core::detectOptFlowTakeoff(void) takeOffDetected = false; } } - +#endif // EK3_FEATURE_OPTFLOW_FUSION diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index d689ab85919d7c..2fb368c60236b4 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -8,9 +8,9 @@ #include // constructor -NavEKF3_core::NavEKF3_core(NavEKF3 *_frontend) : +NavEKF3_core::NavEKF3_core(NavEKF3 *_frontend, AP_DAL &_dal) : + dal(_dal), frontend(_frontend), - dal(AP::dal()), public_origin(frontend->common_EKF_origin) { firstInitTime_ms = 0; @@ -131,10 +131,12 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index) if(frontend->sources.gps_yaw_enabled() && !storedYawAng.init(obs_buffer_length)) { return false; } +#if AP_RANGEFINDER_ENABLED // Note: the use of dual range finders potentially doubles the amount of data to be stored if(dal.rangefinder() && !storedRange.init(MIN(2*obs_buffer_length , imu_buffer_length))) { return false; } +#endif // Note: range beacon data is read one beacon at a time and can arrive at a high rate #if EK3_FEATURE_BEACON_FUSION if(dal.beacon() && !rngBcn.storedRange.init(imu_buffer_length+1)) { @@ -172,7 +174,7 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index) } // try to instantiate - yawEstimator = new EKFGSF_yaw(); + yawEstimator = NEW_NOTHROW EKFGSF_yaw(); if (yawEstimator == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 IMU%uGSF: allocation failed",(unsigned)imu_index); return false; @@ -201,7 +203,7 @@ void NavEKF3_core::InitialiseVariables() prevBetaDragStep_ms = imuSampleTime_ms; lastBaroReceived_ms = imuSampleTime_ms; lastVelPassTime_ms = 0; - lastPosPassTime_ms = 0; + lastGpsPosPassTime_ms = 0; lastHgtPassTime_ms = 0; lastTasPassTime_ms = 0; lastSynthYawTime_ms = 0; @@ -247,7 +249,9 @@ void NavEKF3_core::InitialiseVariables() memset(&nextP[0][0], 0, sizeof(nextP)); flowDataValid = false; rangeDataToFuse = false; +#if EK3_FEATURE_OPTFLOW_FUSION Popt = 0.0f; +#endif terrainState = 0.0f; prevPosN = stateStruct.position.x; prevPosE = stateStruct.position.y; @@ -258,6 +262,8 @@ void NavEKF3_core::InitialiseVariables() PV_AidingModePrev = AID_NONE; posTimeout = true; velTimeout = true; + velAiding = false; + waitingForGpsChecks = false; memset(&faultStatus, 0, sizeof(faultStatus)); hgtRate = 0.0f; onGround = true; @@ -266,6 +272,9 @@ void NavEKF3_core::InitialiseVariables() prevInFlight = false; manoeuvring = false; inhibitWindStates = true; + windStateIsObservable = false; + treatWindStatesAsTruth = false; + lastAspdEstIsValid = false; windStatesAligned = false; inhibitDelVelBiasStates = true; inhibitDelAngBiasStates = true; @@ -311,7 +320,9 @@ void NavEKF3_core::InitialiseVariables() ZERO_FARRAY(statesArray); memset(&vertCompFiltState, 0, sizeof(vertCompFiltState)); posVelFusionDelayed = false; +#if EK3_FEATURE_OPTFLOW_FUSION optFlowFusionDelayed = false; +#endif flowFusionActive = false; airSpdFusionDelayed = false; sideSlipFusionDelayed = false; @@ -333,9 +344,11 @@ void NavEKF3_core::InitialiseVariables() memset(&filterStatus, 0, sizeof(filterStatus)); activeHgtSource = AP_NavEKF_Source::SourceZ::BARO; prevHgtSource = activeHgtSource; +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS memset(&rngMeasIndex, 0, sizeof(rngMeasIndex)); memset(&storedRngMeasTime_ms, 0, sizeof(storedRngMeasTime_ms)); memset(&storedRngMeas, 0, sizeof(storedRngMeas)); +#endif terrainHgtStable = true; ekfOriginHgtVar = 0.0f; ekfGpsRefHgt = 0.0; @@ -385,7 +398,9 @@ void NavEKF3_core::InitialiseVariables() storedGPS.reset(); storedBaro.reset(); storedTAS.reset(); +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS storedRange.reset(); +#endif storedOutput.reset(); #if EK3_FEATURE_BEACON_FUSION rngBcn.storedRange.reset(); @@ -441,6 +456,7 @@ void NavEKF3_core::InitialiseVariablesMag() #endif needMagBodyVarReset = false; needEarthBodyVarReset = false; + magFusionSel = MagFuseSel::NOT_FUSING; } /* @@ -466,7 +482,7 @@ bool NavEKF3_core::InitialiseFilterBootstrap(void) } // read all the sensors required to start the EKF the states - readIMUData(); + readIMUData(false); // don't allow prediction readMagData(); readGpsData(); readGpsYawData(); @@ -597,8 +613,10 @@ void NavEKF3_core::CovarianceInit() P[23][23] = P[22][22]; +#if EK3_FEATURE_OPTFLOW_FUSION // optical flow ground height covariance Popt = 0.25f; +#endif } @@ -608,9 +626,6 @@ void NavEKF3_core::CovarianceInit() // Update Filter States - this should be called whenever new IMU data is available void NavEKF3_core::UpdateFilter(bool predict) { - // Set the flag to indicate to the filter that the front-end has given permission for a new state prediction cycle to be started - startPredictEnabled = predict; - // don't run filter updates if states have not been initialised if (!statesInitialised) { return; @@ -627,7 +642,7 @@ void NavEKF3_core::UpdateFilter(bool predict) controlFilterModes(); // read IMU data as delta angles and velocities - readIMUData(); + readIMUData(predict); // Run the EKF equations to estimate at the fusion time horizon if new IMU data is available in the buffer if (runUpdates) { @@ -658,8 +673,10 @@ void NavEKF3_core::UpdateFilter(bool predict) SelectRngBcnFusion(); #endif +#if EK3_FEATURE_OPTFLOW_FUSION // Update states using optical flow data SelectFlowFusion(); +#endif #if EK3_FEATURE_BODY_ODOM // Update states using body frame odometry data @@ -863,7 +880,7 @@ void NavEKF3_core::calcOutputStates() if (!accelPosOffset.is_zero()) { // calculate the average angular rate across the last IMU update // note delAngDT is prevented from being zero in readIMUData() - Vector3F angRate = imuDataNew.delAng * (1.0f/imuDataNew.delAngDT); + Vector3F angRate = dal.ins().get_gyro(gyro_index_active).toftype(); // Calculate the velocity of the body frame origin relative to the IMU in body frame // and rotate into earth frame. Note % operator has been overloaded to perform a cross product @@ -985,8 +1002,8 @@ void NavEKF3_core::calcOutputStates() /* * Calculate the predicted state covariance matrix using algebraic equations generated using SymPy - * See AP_NavEKF3/derivation/main.py for derivation - * Output for change reference: AP_NavEKF3/derivation/generated/covariance_generated.cpp + * See derivation/generate_1.py for derivation + * Output for change reference: derivation/generated/covariance_generated.cpp * Argument rotVarVecPtr is pointer to a vector defining the earth frame uncertainty variance of the quaternion states * used to perform a reset of the quaternion state covariances only. Set to null for normal operation. */ @@ -1080,10 +1097,18 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) if (!inhibitWindStates) { const bool isDragFusionDeadReckoning = filterStatus.flags.dead_reckoning && !dragTimeout; - if (isDragFusionDeadReckoning) { - // when dead reckoning using drag fusion stop learning wind states to provide a more stable velocity estimate + const bool newTreatWindStatesAsTruth = isDragFusionDeadReckoning || !windStateIsObservable; + if (newTreatWindStatesAsTruth) { + treatWindStatesAsTruth = true; P[23][23] = P[22][22] = 0.0f; } else { + if (treatWindStatesAsTruth) { + treatWindStatesAsTruth = false; + if (windStateIsObservable) { + // allow EKF to relearn wind states rapidly + P[23][23] = P[22][22] = sq(WIND_VEL_VARIANCE_MAX); + } + } 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 @@ -1941,7 +1966,11 @@ void NavEKF3_core::ConstrainVariances() } if (!inhibitWindStates) { - for (uint8_t i=22; i<=23; i++) P[i][i] = constrain_ftype(P[i][i],0.0f,WIND_VEL_VARIANCE_MAX); + if (treatWindStatesAsTruth) { + P[23][23] = P[22][22] = 0.0f; + } else { + for (uint8_t i=22; i<=23; i++) P[i][i] = constrain_ftype(P[i][i],0.0f,WIND_VEL_VARIANCE_MAX); + } } else { zeroCols(P,22,23); zeroRows(P,22,23); @@ -2093,7 +2122,7 @@ void NavEKF3_core::calcTiltErrorVariance() const ftype &q2 = stateStruct.quat[2]; const ftype &q3 = stateStruct.quat[3]; - // equations generated by quaternion_error_propagation(): in AP_NavEKF3/derivation/main.py + // equations generated by quaternion_error_propagation(): in derivation/generate_2.py // only diagonals have been used // dq0 ... dq3 terms have been zeroed const ftype PS1 = q0*q1 + q2*q3; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index e1903a7faf724c..ee4d17a6f5c514 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -32,7 +32,7 @@ #include #include #include -#include +#include #include "AP_NavEKF/EKFGSF_yaw.h" @@ -60,6 +60,7 @@ // mag fusion final reset altitude (using NED frame so altitude is negative) #define EKF3_MAG_FINAL_RESET_ALT 2.5f +#define EKF3_MAG_FINAL_RESET_ALT_SUB 0.5f // learning rate for mag biases when using GPS yaw #define EK3_GPS_MAG_LEARN_RATE 0.005f @@ -109,11 +110,13 @@ #define WIND_VEL_VARIANCE_MIN 0.25f // maximum number of downward facing rangefinder instances available +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS #if RANGEFINDER_MAX_INSTANCES > 1 #define DOWNWARD_RANGEFINDER_MAX_INSTANCES 2 #else #define DOWNWARD_RANGEFINDER_MAX_INSTANCES 1 #endif +#endif // number of continuous valid GPS velocity samples required to reset yaw #define GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD 5 @@ -125,7 +128,7 @@ class NavEKF3_core : public NavEKF_core_common { public: // Constructor - NavEKF3_core(class NavEKF3 *_frontend); + NavEKF3_core(class NavEKF3 *_frontend, class AP_DAL &dal); // setup this core backend bool setup_core(uint8_t _imu_index, uint8_t _core_index); @@ -224,7 +227,7 @@ class NavEKF3_core : public NavEKF_core_common // 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 - // returns false if Absolute aiding and GPS is being used or if the origin is already set + // returns false if the origin has already been set bool setOriginLLH(const Location &loc); // Set the EKF's NE horizontal position states and their corresponding variances from a supplied WGS-84 location and uncertainty @@ -232,6 +235,9 @@ class NavEKF3_core : public NavEKF_core_common // Returns true if the set was successful bool setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms); + // Popoluates the WMM data structure with the field at the given location + void setEarthFieldFromLocation(const Location &loc); + // return estimated height above ground level // return false if ground height is not being estimated. bool getHAGL(float &HAGL) const; @@ -421,6 +427,13 @@ class NavEKF3_core : public NavEKF_core_common // 6 was EXTERNAL_YAW_FALLBACK (do not use) }; + // magnetometer fusion selections + enum class MagFuseSel { + NOT_FUSING = 0, + FUSE_YAW = 1, + FUSE_MAG = 2 + }; + // are we using (aka fusing) a non-compass yaw? bool using_noncompass_for_yaw(void) const; @@ -760,7 +773,7 @@ class NavEKF3_core : public NavEKF_core_common void correctDeltaVelocity(Vector3F &delVel, ftype delVelDT, uint8_t accel_index); // update IMU delta angle and delta velocity measurements - void readIMUData(); + void readIMUData(bool startPredictEnabled); // update estimate of inactive bias states void learnInactiveBiases(); @@ -855,8 +868,10 @@ class NavEKF3_core : public NavEKF_core_common // Calculate weighting that is applied to IMU1 accel data to blend data from IMU's 1 and 2 void calcIMU_Weighting(ftype K1, ftype K2); +#if EK3_FEATURE_OPTFLOW_FUSION // return true if the filter is ready to start using optical flow measurements for position and velocity estimation bool readyToUseOptFlow(void) const; +#endif // return true if the filter is ready to start using body frame odometry measurements bool readyToUseBodyOdm(void) const; @@ -867,8 +882,10 @@ class NavEKF3_core : public NavEKF_core_common // return true if we should use the range finder sensor bool useRngFinder(void) const; +#if EK3_FEATURE_OPTFLOW_FUSION // determine when to perform fusion of optical flow measurements void SelectFlowFusion(); +#endif // determine when to perform fusion of body frame odometry measurements void SelectBodyOdomFusion(); @@ -876,9 +893,11 @@ class NavEKF3_core : public NavEKF_core_common // Estimate terrain offset using a single state EKF void EstimateTerrainOffset(const of_elements &ofDataDelayed); +#if EK3_FEATURE_OPTFLOW_FUSION // fuse optical flow measurements into the main filter // really_fuse should be true to actually fuse into the main filter, false to only calculate variances void FuseOptFlow(const of_elements &ofDataDelayed, bool really_fuse); +#endif // Control filter mode changes void controlFilterModes(); @@ -886,6 +905,9 @@ class NavEKF3_core : public NavEKF_core_common // Determine if we are flying or on the ground void detectFlight(); + // set the default yaw source + void setYawSource(); + // Set inertial navigation aiding mode void setAidingMode(); @@ -918,8 +940,10 @@ class NavEKF3_core : public NavEKF_core_common // Apply a median filter to range finder data void readRangeFinder(); +#if EK3_FEATURE_OPTFLOW_FUSION // check if the vehicle has taken off during optical flow navigation by looking at inertial and range finder data void detectOptFlowTakeoff(void); +#endif // align the NE earth magnetic field states with the published declination void alignMagStateDeclination(); @@ -954,8 +978,8 @@ class NavEKF3_core : public NavEKF_core_common // zero attitude state covariances, but preserve variances void zeroAttCovOnly(); - // record a yaw reset event - void recordYawReset(); + // record all requested yaw resets completed + void recordYawResetsCompleted(); // record a magnetic field state reset event void recordMagReset(); @@ -1034,6 +1058,8 @@ class NavEKF3_core : public NavEKF_core_common 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 + bool velAiding; // boolean true if the velocity drift is constrained by observations + bool waitingForGpsChecks; // boolean true if the EKF should write GPS data to the buffer until quality checks have passed uint32_t badIMUdata_ms; // time stamp bad IMU data was last detected uint32_t goodIMUdata_ms; // time stamp good IMU data was last detected uint32_t vertVelVarClipCounter; // counter used to control reset of vertical velocity variance following collapse against the lower limit @@ -1045,7 +1071,9 @@ class NavEKF3_core : public NavEKF_core_common EKF_obs_buffer_t storedMag; // Magnetometer data buffer EKF_obs_buffer_t storedBaro; // Baro data buffer EKF_obs_buffer_t storedTAS; // TAS data buffer +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS EKF_obs_buffer_t storedRange; // Range finder data buffer +#endif EKF_IMU_buffer_t storedOutput;// output state buffer Matrix3F prevTnb; // previous nav to body transformation used for INS earth rotation compensation ftype accNavMag; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2) @@ -1086,7 +1114,7 @@ class NavEKF3_core : public NavEKF_core_common uint32_t lastBaroReceived_ms; // time last time we received baro height data uint16_t hgtRetryTime_ms; // time allowed without use of height measurements before a height timeout is declared uint32_t lastVelPassTime_ms; // time stamp when GPS velocity measurement last passed innovation consistency check (msec) - uint32_t lastPosPassTime_ms; // time stamp when GPS position measurement last passed innovation consistency check (msec) + uint32_t lastGpsPosPassTime_ms; // time stamp when GPS position measurement last passed innovation consistency check (msec) uint32_t lastHgtPassTime_ms; // time stamp when height measurement last passed innovation consistency check (msec) uint32_t lastTasPassTime_ms; // time stamp when airspeed measurement last passed innovation consistency check (msec) uint32_t lastTasFailTime_ms; // time stamp when airspeed measurement last failed innovation consistency check (msec) @@ -1104,7 +1132,11 @@ class NavEKF3_core : public NavEKF_core_common ftype hgtTestRatio; // sum of squares of baro height innovation divided by fail threshold Vector3F magTestRatio; // sum of squares of magnetometer innovations divided by fail threshold ftype tasTestRatio; // sum of squares of true airspeed innovation divided by fail threshold - bool inhibitWindStates; // true when wind states and covariances are to remain constant + bool inhibitWindStates; // true when wind states and covariances should not be used + ftype lastAirspeedEstimate; // last true airspeed estimate (m/s) + bool lastAspdEstIsValid; // true when the last true airspeed estimate is valid (m/s) + bool windStateIsObservable; // true when wind states are observable from measurements. + bool treatWindStatesAsTruth; // true when wind states should be used as a truth reference bool windStatesAligned; // true when wind states have been aligned bool inhibitMagStates; // true when magnetic field states are inactive bool lastInhibitMagStates; // previous inhibitMagStates @@ -1140,7 +1172,6 @@ class NavEKF3_core : public NavEKF_core_common range_elements rangeDataDelayed;// Range finder data at the fusion time horizon tas_elements tasDataNew; // TAS data at the current time horizon tas_elements tasDataDelayed; // TAS data at the fusion time horizon - bool usingDefaultAirspeed; // true when a default airspeed is being used instead of a measured value mag_elements magDataDelayed; // Magnetometer data at the fusion time horizon gps_elements gpsDataNew; // GPS data at the current time horizon gps_elements gpsDataDelayed; // GPS data at the fusion time horizon @@ -1159,7 +1190,9 @@ class NavEKF3_core : public NavEKF_core_common bool motorsArmed; // true when the motors have been armed bool prevMotorsArmed; // value of motorsArmed from previous frame bool posVelFusionDelayed; // true when the position and velocity fusion has been delayed +#if EK3_FEATURE_OPTFLOW_FUSION bool optFlowFusionDelayed; // true when the optical flow fusion has been delayed +#endif bool airSpdFusionDelayed; // true when the air speed fusion has been delayed bool sideSlipFusionDelayed; // true when the sideslip fusion has been delayed bool airDataFusionWindOnly; // true when sideslip and airspeed fusion is only allowed to modify the wind states @@ -1177,7 +1210,6 @@ class NavEKF3_core : public NavEKF_core_common uint8_t magSelectIndex; // Index of the magnetometer that is being used by the EKF bool runUpdates; // boolean true when the EKF updates can be run uint32_t framesSincePredict; // number of frames lapsed since EKF instance did a state prediction - bool startPredictEnabled; // boolean true when the frontend has given permission to start a new state prediciton cycle uint8_t localFilterTimeStep_ms; // average number of msec between filter updates ftype posDownObsNoise; // observation noise variance on the vertical position used by the state and covariance update step (m^2) Vector3F delAngCorrected; // corrected IMU delta angle vector at the EKF time horizon (rad) @@ -1227,7 +1259,7 @@ class NavEKF3_core : public NavEKF_core_common 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) + uint32_t gpsRetrieveTime_ms; // system time that GPS data was retrieved from the buffer (to detect timeouts) // variables added for optical flow fusion EKF_obs_buffer_t storedOF; // OF data buffer @@ -1240,7 +1272,9 @@ class NavEKF3_core : public NavEKF_core_common Vector2 flowVarInnov; // optical flow innovations variances (rad/sec)^2 Vector2 flowInnov; // optical flow LOS innovations (rad/sec) uint32_t flowInnovTime_ms; // system time that optical flow innovations and variances were recorded (to detect timeouts) +#if EK3_FEATURE_OPTFLOW_FUSION ftype Popt; // Optical flow terrain height state covariance (m^2) +#endif ftype terrainState; // terrain position state (m) ftype prevPosN; // north position at last measurement ftype prevPosE; // east position at last measurement @@ -1284,9 +1318,11 @@ class NavEKF3_core : public NavEKF_core_common ftype rngOnGnd; // Expected range finder reading in metres when vehicle is on ground uint32_t lastRngMeasTime_ms; // Timestamp of last range measurement bool terrainHgtStable; // true when the terrain height is stable enough to be used as a height reference +#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS ftype storedRngMeas[DOWNWARD_RANGEFINDER_MAX_INSTANCES][3]; // Ringbuffer of stored range measurements for dual range sensors uint32_t storedRngMeasTime_ms[DOWNWARD_RANGEFINDER_MAX_INSTANCES][3]; // Ringbuffers of stored range measurement times for dual range sensors uint8_t rngMeasIndex[DOWNWARD_RANGEFINDER_MAX_INSTANCES]; // Current range measurement ringbuffer index for dual range sensors +#endif // body frame odometry fusion #if EK3_FEATURE_BODY_ODOM @@ -1320,6 +1356,10 @@ class NavEKF3_core : public NavEKF_core_common #if EK3_FEATURE_BEACON_FUSION class BeaconFusion { public: + BeaconFusion(AP_DAL &_dal) : + dal{_dal} + {} + void InitialiseVariables(); EKF_obs_buffer_t storedRange; // Beacon range buffer @@ -1370,7 +1410,9 @@ class NavEKF3_core : public NavEKF_core_common Vector3F beaconPosNED; // beacon NED position } *fusionReport; uint8_t numFusionReports; - } rngBcn; + + AP_DAL &dal; + } rngBcn{dal}; #endif // if EK3_FEATURE_BEACON_FUSION #if EK3_FEATURE_DRAG_FUSION @@ -1409,6 +1451,7 @@ class NavEKF3_core : public NavEKF_core_common ftype posDownAtLastMagReset; // vertical position last time the mag states were reset (m) ftype yawInnovAtLastMagReset; // magnetic yaw innovation last time the yaw and mag field states were reset (rad) QuaternionF quatAtLastMagReset; // quaternion states last time the mag states were reset + MagFuseSel magFusionSel; // magnetometer fusion selection // Used by on ground movement check required when operating on ground without a yaw reference ftype gyro_diff; // filtered gyro difference (rad/s) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_feature.h b/libraries/AP_NavEKF3/AP_NavEKF3_feature.h index 3cd2bc3866d0d7..18a3c4ae61f120 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_feature.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_feature.h @@ -8,6 +8,7 @@ #include #include #include +#include // define for when to include all features #define EK3_FEATURE_ALL APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) || APM_BUILD_TYPE(APM_BUILD_Replay) @@ -35,3 +36,13 @@ #ifndef EK3_FEATURE_POSITION_RESET #define EK3_FEATURE_POSITION_RESET EK3_FEATURE_ALL || AP_AHRS_POSITION_RESET_ENABLED #endif + +// rangefinder measurements if available +#ifndef EK3_FEATURE_RANGEFINDER_MEASUREMENTS +#define EK3_FEATURE_RANGEFINDER_MEASUREMENTS AP_RANGEFINDER_ENABLED +#endif + +// Flow Fusion if Flow data available +#ifndef EK3_FEATURE_OPTFLOW_FUSION +#define EK3_FEATURE_OPTFLOW_FUSION HAL_NAVEKF3_AVAILABLE && AP_OPTICALFLOW_ENABLED +#endif diff --git a/libraries/AP_NavEKF3/LogStructure.h b/libraries/AP_NavEKF3/LogStructure.h index 8e124462fcf0db..246fc18915d17e 100644 --- a/libraries/AP_NavEKF3/LogStructure.h +++ b/libraries/AP_NavEKF3/LogStructure.h @@ -1,6 +1,7 @@ #pragma once #include +#include #define LOG_IDS_FROM_NAVEKF3 \ LOG_XKF0_MSG, \ @@ -103,8 +104,8 @@ struct PACKED log_XKF1 { // @Field: AX: Estimated accelerometer X bias // @Field: AY: Estimated accelerometer Y bias // @Field: AZ: Estimated accelerometer Z bias -// @Field: VWN: Estimated wind velocity (North component) -// @Field: VWE: Estimated wind velocity (East component) +// @Field: VWN: Estimated wind velocity (moving-to-North component) +// @Field: VWE: Estimated wind velocity (moving-to-East component) // @Field: MN: Magnetic field strength (North component) // @Field: ME: Magnetic field strength (East component) // @Field: MD: Magnetic field strength (Down component) @@ -187,6 +188,7 @@ struct PACKED log_XKF3 { // @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, 5:drag measurement) // @Field: SS: Filter solution status +// @FieldBitmaskEnum: SS: NavFilterStatusBit // @Field: GPS: Filter GPS status // @Field: PI: Primary core index struct PACKED log_XKF4 { @@ -344,6 +346,9 @@ struct PACKED log_XKQ { // @Field: GI: GPS selection index // @Field: AI: airspeed selection index // @Field: SS: Source Set (primary=0/secondary=1/tertiary=2) +// @Field: GPS_GTA: GPS good to align +// @Field: GPS_CHK_WAIT: Waiting for GPS checks to pass +// @Field: MAG_FUSION: Magnetometer fusion (0=not fusing/1=fuse yaw/2=fuse mag) struct PACKED log_XKFS { LOG_PACKET_HEADER; uint64_t time_us; @@ -353,6 +358,9 @@ struct PACKED log_XKFS { uint8_t gps_index; uint8_t airspeed_index; uint8_t source_set; + uint8_t gps_good_to_align; + uint8_t wait_for_gps_checks; + uint8_t mag_fusion; }; // @LoggerMessage: XKTV @@ -439,8 +447,8 @@ struct PACKED log_XKV { { LOG_XKFM_MSG, sizeof(log_XKFM), \ "XKFM", "QBBffff", "TimeUS,C,OGNM,GLR,ALR,GDR,ADR", "s#-----", "F------", true }, \ { LOG_XKFS_MSG, sizeof(log_XKFS), \ - "XKFS","QBBBBBB","TimeUS,C,MI,BI,GI,AI,SS", "s#-----", "F------" , true }, \ - { LOG_XKQ_MSG, sizeof(log_XKQ), "XKQ", "QBffff", "TimeUS,C,Q1,Q2,Q3,Q4", "s#----", "F-0000" , true }, \ + "XKFS","QBBBBBBBBB","TimeUS,C,MI,BI,GI,AI,SS,GPS_GTA,GPS_CHK_WAIT,MAG_FUSION", "s#--------", "F---------" , true }, \ + { LOG_XKQ_MSG, sizeof(log_XKQ), "XKQ", "QBffff", "TimeUS,C,Q1,Q2,Q3,Q4", "s#????", "F-????" , true }, \ { LOG_XKT_MSG, sizeof(log_XKT), \ "XKT", "QBIffffffff", "TimeUS,C,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax", "s#sssssssss", "F-000000000", true }, \ { LOG_XKTV_MSG, sizeof(log_XKTV), \ diff --git a/libraries/AP_NavEKF3/derivation/.gitignore b/libraries/AP_NavEKF3/derivation/.gitignore new file mode 100644 index 00000000000000..e83c02b2eadd30 --- /dev/null +++ b/libraries/AP_NavEKF3/derivation/.gitignore @@ -0,0 +1 @@ +generated/*.cpp diff --git a/libraries/AP_NavEKF3/derivation/code_gen.py b/libraries/AP_NavEKF3/derivation/code_gen.py index 8aa14500b07153..b17d359df9a3d6 100644 --- a/libraries/AP_NavEKF3/derivation/code_gen.py +++ b/libraries/AP_NavEKF3/derivation/code_gen.py @@ -9,11 +9,22 @@ def __init__(self, file_name): self.file_name = file_name self.file = open(self.file_name, 'w') + # custom SymPy -> C function mappings. note that at least one entry must + # match, the last entry will always be used if none match! + self._custom_funcs = { + "Pow": [ + (lambda b, e: e == 2, lambda b, e: f"sq({b})"), # use square function for b**2 + (lambda b, e: e == -1, lambda b, e: f"1.0F/({b})"), # inverse + (lambda b, e: e == -2, lambda b, e: f"1.0F/sq({b})"), # inverse square + (lambda b, e: True, "powf"), # otherwise use default powf + ], + } + def print_string(self, string): self.file.write("// " + string + "\n") def get_ccode(self, expression): - return ccode(expression, type_aliases={real:float32}) + return ccode(expression, type_aliases={real:float32}, user_functions=self._custom_funcs) def write_subexpressions(self,subexpressions): write_string = "" diff --git a/libraries/AP_NavEKF3/derivation/generate.sh b/libraries/AP_NavEKF3/derivation/generate.sh new file mode 100755 index 00000000000000..584829a80f55e5 --- /dev/null +++ b/libraries/AP_NavEKF3/derivation/generate.sh @@ -0,0 +1,8 @@ +#!/usr/bin/env bash + +cd "$(dirname "$0")" +rm -rf generated # ensure generated directory exists and is empty +mkdir -p generated + +./generate_1.py +./generate_2.py diff --git a/libraries/AP_NavEKF3/derivation/main.py b/libraries/AP_NavEKF3/derivation/generate_1.py similarity index 94% rename from libraries/AP_NavEKF3/derivation/main.py rename to libraries/AP_NavEKF3/derivation/generate_1.py index 4d541056042a99..8f738925c8e0e8 100755 --- a/libraries/AP_NavEKF3/derivation/main.py +++ b/libraries/AP_NavEKF3/derivation/generate_1.py @@ -1,10 +1,16 @@ #!/usr/bin/env python3 # Copied from https://github.com/PX4/ecl/commit/264c8c4e8681704e4719d0a03b848df8617c0863 # and modified for ArduPilot +from sympy import __version__ as __sympy__version__ from sympy import * from code_gen import * import numpy as np +# version required to generate the exact code currently present in ArduPilot. +# sympy version upgrades must ensure generated code doesn't pose any problems +# and must not have any other changes to the generator. +assert __sympy__version__ == "1.9", "expected sympy version 1.9, not "+__sympy__version__ + # q: quaternion describing rotation from frame 1 to frame 2 # returns a rotation matrix derived form q which describes the same # rotation @@ -672,29 +678,29 @@ def generate_code(): # derive autocode for other methods - print('Computing tilt error covariance matrix ...') - quaternion_error_propagation() - print('Generating heading observation code ...') - yaw_observation(P,state,R_to_earth) - print('Generating gps heading observation code ...') - gps_yaw_observation(P,state,R_to_body) - print('Generating mag observation code ...') - mag_observation_variance(P,state,R_to_body,i,ib) - mag_observation(P,state,R_to_body,i,ib) - print('Generating declination observation code ...') - declination_observation(P,state,ix,iy) - print('Generating airspeed observation code ...') - tas_observation(P,state,vx,vy,vz,wx,wy) - print('Generating sideslip observation code ...') - beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy) - print('Generating optical flow observation code ...') - optical_flow_observation(P,state,R_to_body,vx,vy,vz) - print('Generating body frame velocity observation code ...') - body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz) - print('Generating body frame acceleration observation code ...') - body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy) - print('Generating yaw estimator code ...') - yaw_estimator() + # print('Computing tilt error covariance matrix ...') + # quaternion_error_propagation() + # print('Generating heading observation code ...') + # yaw_observation(P,state,R_to_earth) + # print('Generating gps heading observation code ...') + # gps_yaw_observation(P,state,R_to_body) + # print('Generating mag observation code ...') + # mag_observation_variance(P,state,R_to_body,i,ib) + # mag_observation(P,state,R_to_body,i,ib) + # print('Generating declination observation code ...') + # declination_observation(P,state,ix,iy) + # print('Generating airspeed observation code ...') + # tas_observation(P,state,vx,vy,vz,wx,wy) + # print('Generating sideslip observation code ...') + # beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy) + # print('Generating optical flow observation code ...') + # optical_flow_observation(P,state,R_to_body,vx,vy,vz) + # print('Generating body frame velocity observation code ...') + # body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz) + # print('Generating body frame acceleration observation code ...') + # body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy) + # print('Generating yaw estimator code ...') + # yaw_estimator() print('Code generation finished!') diff --git a/libraries/AP_NavEKF3/derivation/generate_2.py b/libraries/AP_NavEKF3/derivation/generate_2.py new file mode 100755 index 00000000000000..d7f053d5c4b06f --- /dev/null +++ b/libraries/AP_NavEKF3/derivation/generate_2.py @@ -0,0 +1,695 @@ +#!/usr/bin/env python3 +# Copied from https://github.com/PX4/ecl/commit/264c8c4e8681704e4719d0a03b848df8617c0863 +# and modified for ArduPilot +# this file was originally from ArduPilot commit f81abd73d6bf73dd1cd1d009f355f6f8c025325b +from sympy import __version__ as __sympy__version__ +from sympy import * +from code_gen import * +import numpy as np + +# version required to generate the exact code currently present in ArduPilot. +# sympy version upgrades must ensure generated code doesn't pose any problems +# and must not have any other changes to the generator. +assert __sympy__version__ == "1.9", "expected sympy version 1.9, not "+__sympy__version__ + +# q: quaternion describing rotation from frame 1 to frame 2 +# returns a rotation matrix derived form q which describes the same +# rotation +def quat2Rot(q): + q0 = q[0] + q1 = q[1] + q2 = q[2] + q3 = q[3] + + Rot = Matrix([[q0**2 + q1**2 - q2**2 - q3**2, 2*(q1*q2 - q0*q3), 2*(q1*q3 + q0*q2)], + [2*(q1*q2 + q0*q3), q0**2 - q1**2 + q2**2 - q3**2, 2*(q2*q3 - q0*q1)], + [2*(q1*q3-q0*q2), 2*(q2*q3 + q0*q1), q0**2 - q1**2 - q2**2 + q3**2]]) + + return Rot + +def create_cov_matrix(i, j): + if j >= i: + # return Symbol("P(" + str(i) + "," + str(j) + ")", real=True) + # legacy array format + return Symbol("P[" + str(i) + "][" + str(j) + "]", real=True) + else: + return 0 + +def create_yaw_estimator_cov_matrix(): + # define a symbolic covariance matrix + P = Matrix(3,3,create_cov_matrix) + + for index in range(3): + for j in range(3): + if index > j: + P[index,j] = P[j,index] + + return P + +def create_Tbs_matrix(i, j): + # return Symbol("Tbs(" + str(i) + "," + str(j) + ")", real=True) + # legacy array format + return Symbol("Tbs[" + str(i) + "][" + str(j) + "]", real=True) + +def quat_mult(p,q): + r = Matrix([p[0] * q[0] - p[1] * q[1] - p[2] * q[2] - p[3] * q[3], + p[0] * q[1] + p[1] * q[0] + p[2] * q[3] - p[3] * q[2], + p[0] * q[2] - p[1] * q[3] + p[2] * q[0] + p[3] * q[1], + p[0] * q[3] + p[1] * q[2] - p[2] * q[1] + p[3] * q[0]]) + + return r + +def create_symmetric_cov_matrix(n): + # define a symbolic covariance matrix + P = Matrix(n,n,create_cov_matrix) + + for index in range(n): + for j in range(n): + if index > j: + P[index,j] = P[j,index] + + return P + +# generate equations for observation vector innovation variances +def generate_observation_vector_innovation_variances(P,state,observation,variance,n_obs): + H = observation.jacobian(state) + innovation_variance = zeros(n_obs,1) + for index in range(n_obs): + H[index,:] = Matrix([observation[index]]).jacobian(state) + innovation_variance[index] = H[index,:] * P * H[index,:].T + Matrix([variance]) + + IV_simple = cse(innovation_variance, symbols("IV0:1000"), optimizations='basic') + + return IV_simple + +# generate equations for observation Jacobian and Kalman gain +def generate_observation_equations(P,state,observation,variance,varname="HK"): + H = Matrix([observation]).jacobian(state) + innov_var = H * P * H.T + Matrix([variance]) + assert(innov_var.shape[0] == 1) + assert(innov_var.shape[1] == 1) + K = P * H.T / innov_var[0,0] + extension="0:1000" + var_string = varname+extension + HK_simple = cse(Matrix([H.transpose(), K]), symbols(var_string), optimizations='basic') + + return HK_simple + +# generate equations for observation vector Jacobian and Kalman gain +# n_obs is the vector dimension and must be >= 2 +def generate_observation_vector_equations(P,state,observation,variance,n_obs): + K = zeros(24,n_obs) + H = observation.jacobian(state) + HK = zeros(n_obs*48,1) + for index in range(n_obs): + H[index,:] = Matrix([observation[index]]).jacobian(state) + innov_var = H[index,:] * P * H[index,:].T + Matrix([variance]) + assert(innov_var.shape[0] == 1) + assert(innov_var.shape[1] == 1) + K[:,index] = P * H[index,:].T / innov_var[0,0] + HK[index*48:(index+1)*48,0] = Matrix([H[index,:].transpose(), K[:,index]]) + + HK_simple = cse(HK, symbols("HK0:1000"), optimizations='basic') + + return HK_simple + +# write single observation equations to file +def write_equations_to_file(equations,code_generator_id,n_obs): + if (n_obs < 1): + return + + if (n_obs == 1): + code_generator_id.print_string("Sub Expressions") + code_generator_id.write_subexpressions(equations[0]) + code_generator_id.print_string("Observation Jacobians") + code_generator_id.write_matrix(Matrix(equations[1][0][0:24]), "Hfusion", False) + code_generator_id.print_string("Kalman gains") + code_generator_id.write_matrix(Matrix(equations[1][0][24:]), "Kfusion", False) + else: + code_generator_id.print_string("Sub Expressions") + code_generator_id.write_subexpressions(equations[0]) + for axis_index in range(n_obs): + start_index = axis_index*48 + code_generator_id.print_string("Observation Jacobians - axis %i" % axis_index) + code_generator_id.write_matrix(Matrix(equations[1][0][start_index:start_index+24]), "Hfusion", False) + code_generator_id.print_string("Kalman gains - axis %i" % axis_index) + code_generator_id.write_matrix(Matrix(equations[1][0][start_index+24:start_index+48]), "Kfusion", False) + + return + +# derive equations for sequential fusion of optical flow measurements +def optical_flow_observation(P,state,R_to_body,vx,vy,vz): + flow_code_generator = CodeGenerator("./generated/flow_generated.cpp") + range = symbols("range", real=True) # range from camera focal point to ground along sensor Z axis + obs_var = symbols("R_LOS", real=True) # optical flow line of sight rate measurement noise variance + + # Define rotation matrix from body to sensor frame + Tbs = Matrix(3,3,create_Tbs_matrix) + + # Calculate earth relative velocity in a non-rotating sensor frame + relVelSensor = Tbs * R_to_body * Matrix([vx,vy,vz]) + + # Divide by range to get predicted angular LOS rates relative to X and Y + # axes. Note these are rates in a non-rotating sensor frame + losRateSensorX = +relVelSensor[1]/range + losRateSensorY = -relVelSensor[0]/range + + # calculate the observation Jacobian and Kalman gains for the X axis + equations = generate_observation_equations(P,state,losRateSensorX,obs_var) + + flow_code_generator.print_string("X Axis Equations") + write_equations_to_file(equations,flow_code_generator,1) + + # calculate the observation Jacobian and Kalman gains for the Y axis + equations = generate_observation_equations(P,state,losRateSensorY,obs_var) + + flow_code_generator.print_string("Y Axis Equations") + write_equations_to_file(equations,flow_code_generator,1) + + flow_code_generator.close() + + # calculate a combined result for a possible reduction in operations, but will use more stack + observation = Matrix([relVelSensor[1]/range,-relVelSensor[0]/range]) + equations = generate_observation_vector_equations(P,state,observation,obs_var,2) + flow_code_generator_alt = CodeGenerator("./generated/flow_generated_alt.cpp") + write_equations_to_file(equations,flow_code_generator_alt,2) + flow_code_generator_alt.close() + + return + +# Derive equations for sequential fusion of body frame velocity measurements +def body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz): + obs_var = symbols("R_VEL", real=True) # measurement noise variance + + # Calculate earth relative velocity in a non-rotating sensor frame + vel_bf = R_to_body * Matrix([vx,vy,vz]) + + vel_bf_code_generator = CodeGenerator("./generated/vel_bf_generated.cpp") + axes = [0,1,2] + H_obs = vel_bf.jacobian(state) # observation Jacobians + K_gain = zeros(24,3) + for index in axes: + equations = generate_observation_equations(P,state,vel_bf[index],obs_var) + + vel_bf_code_generator.print_string("axis %i" % index) + vel_bf_code_generator.write_subexpressions(equations[0]) + vel_bf_code_generator.write_matrix(Matrix(equations[1][0][0:24]), "H_VEL", False) + vel_bf_code_generator.write_matrix(Matrix(equations[1][0][24:]), "Kfusion", False) + + vel_bf_code_generator.close() + + # calculate a combined result for a possible reduction in operations, but will use more stack + equations = generate_observation_vector_equations(P,state,vel_bf,obs_var,3) + + vel_bf_code_generator_alt = CodeGenerator("./generated/vel_bf_generated_alt.cpp") + write_equations_to_file(equations,vel_bf_code_generator_alt,3) + vel_bf_code_generator_alt.close() + +# derive equations for fusion of dual antenna yaw measurement +def gps_yaw_observation(P,state,R_to_body): + obs_var = symbols("R_YAW", real=True) # measurement noise variance + ant_yaw = symbols("ant_yaw", real=True) # yaw angle of antenna array axis wrt X body axis + + # define antenna vector in body frame + ant_vec_bf = Matrix([cos(ant_yaw),sin(ant_yaw),0]) + + # rotate into earth frame + ant_vec_ef = R_to_body.T * ant_vec_bf + + # Calculate the yaw angle from the projection + observation = atan(ant_vec_ef[1]/ant_vec_ef[0]) + + equations = generate_observation_equations(P,state,observation,obs_var) + + gps_yaw_code_generator = CodeGenerator("./generated/gps_yaw_generated.cpp") + write_equations_to_file(equations,gps_yaw_code_generator,1) + gps_yaw_code_generator.close() + + return + +# derive equations for fusion of declination +def declination_observation(P,state,ix,iy): + obs_var = symbols("R_DECL", real=True) # measurement noise variance + + # the predicted measurement is the angle wrt magnetic north of the horizontal + # component of the measured field + observation = atan(iy/ix) + + equations = generate_observation_equations(P,state,observation,obs_var) + + mag_decl_code_generator = CodeGenerator("./generated/mag_decl_generated.cpp") + write_equations_to_file(equations,mag_decl_code_generator,1) + mag_decl_code_generator.close() + + return + +# derive equations for fusion of lateral body acceleration (multirotors only) +def body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy): + obs_var = symbols("R_ACC", real=True) # measurement noise variance + Kaccx = symbols("Kaccx", real=True) # measurement noise variance + Kaccy = symbols("Kaccy", real=True) # measurement noise variance + + # use relationship between airspeed along the X and Y body axis and the + # drag to predict the lateral acceleration for a multirotor vehicle type + # where propulsion forces are generated primarily along the Z body axis + + vrel = R_to_body*Matrix([vx-wx,vy-wy,vz]) # predicted wind relative velocity + + # Use this nonlinear model for the prediction in the implementation only + # It uses a ballistic coefficient for each axis + # accXpred = -0.5*rho*vrel[0]*vrel[0]*BCXinv # predicted acceleration measured along X body axis + # 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 + # 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]]) + + acc_bf_code_generator = CodeGenerator("./generated/acc_bf_generated.cpp") + H = observation.jacobian(state) + K = zeros(24,2) + axes = [0,1] + for index in axes: + equations = generate_observation_equations(P,state,observation[index],obs_var) + acc_bf_code_generator.print_string("Axis %i equations" % index) + write_equations_to_file(equations,acc_bf_code_generator,1) + + acc_bf_code_generator.close() + + # # calculate a combined result for a possible reduction in operations, but will use more stack + # equations = generate_observation_vector_equations(P,state,observation,obs_var,2) + + # acc_bf_code_generator_alt = CodeGenerator("./generated/acc_bf_generated_alt.cpp") + # write_equations_to_file(equations,acc_bf_code_generator_alt,3) + # acc_bf_code_generator_alt.close() + + return + +# yaw fusion +def yaw_observation(P,state,R_to_earth): + yaw_code_generator = CodeGenerator("./generated/yaw_generated.cpp") + + # Derive observation Jacobian for fusion of 321 sequence yaw measurement + # Calculate the yaw (first rotation) angle from the 321 rotation sequence + # Provide alternative angle that avoids singularity at +-pi/2 yaw + angMeasA = atan(R_to_earth[1,0]/R_to_earth[0,0]) + H_YAW321_A = Matrix([angMeasA]).jacobian(state) + H_YAW321_A_simple = cse(H_YAW321_A, symbols('SA0:200')) + + angMeasB = pi/2 - atan(R_to_earth[0,0]/R_to_earth[1,0]) + H_YAW321_B = Matrix([angMeasB]).jacobian(state) + H_YAW321_B_simple = cse(H_YAW321_B, symbols('SB0:200')) + + yaw_code_generator.print_string("calculate 321 yaw observation matrix - option A") + yaw_code_generator.write_subexpressions(H_YAW321_A_simple[0]) + yaw_code_generator.write_matrix(Matrix(H_YAW321_A_simple[1]).T, "H_YAW", False) + + yaw_code_generator.print_string("calculate 321 yaw observation matrix - option B") + yaw_code_generator.write_subexpressions(H_YAW321_B_simple[0]) + yaw_code_generator.write_matrix(Matrix(H_YAW321_B_simple[1]).T, "H_YAW", False) + + # Derive observation Jacobian for fusion of 312 sequence yaw measurement + # Calculate the yaw (first rotation) angle from an Euler 312 sequence + # Provide alternative angle that avoids singularity at +-pi/2 yaw + angMeasA = atan(-R_to_earth[0,1]/R_to_earth[1,1]) + H_YAW312_A = Matrix([angMeasA]).jacobian(state) + H_YAW312_A_simple = cse(H_YAW312_A, symbols('SA0:200')) + + angMeasB = pi/2 - atan(-R_to_earth[1,1]/R_to_earth[0,1]) + H_YAW312_B = Matrix([angMeasB]).jacobian(state) + H_YAW312_B_simple = cse(H_YAW312_B, symbols('SB0:200')) + + yaw_code_generator.print_string("calculate 312 yaw observation matrix - option A") + yaw_code_generator.write_subexpressions(H_YAW312_A_simple[0]) + yaw_code_generator.write_matrix(Matrix(H_YAW312_A_simple[1]).T, "H_YAW", False) + + yaw_code_generator.print_string("calculate 312 yaw observation matrix - option B") + yaw_code_generator.write_subexpressions(H_YAW312_B_simple[0]) + yaw_code_generator.write_matrix(Matrix(H_YAW312_B_simple[1]).T, "H_YAW", False) + + yaw_code_generator.close() + + return + +# 3D magnetometer fusion +def mag_observation_variance(P,state,R_to_body,i,ib): + obs_var = symbols("R_MAG", real=True) # magnetometer measurement noise variance + + m_mag = R_to_body * i + ib + + # separate calculation of innovation variance equations for the y and z axes + m_mag[0]=0 + innov_var_equations = generate_observation_vector_innovation_variances(P,state,m_mag,obs_var,3) + mag_innov_var_code_generator = CodeGenerator("./generated/3Dmag_innov_var_generated.cpp") + write_equations_to_file(innov_var_equations,mag_innov_var_code_generator,3) + mag_innov_var_code_generator.close() + + return + +# 3D magnetometer fusion +def mag_observation(P,state,R_to_body,i,ib): + obs_var = symbols("R_MAG", real=True) # magnetometer measurement noise variance + + m_mag = R_to_body * i + ib + + # calculate a separate set of equations for each axis + mag_code_generator = CodeGenerator("./generated/3Dmag_generated.cpp") + + axes = [0,1,2] + label="HK" + for index in axes: + if (index==0): + label="HKX" + elif (index==1): + label="HKY" + elif (index==2): + label="HKZ" + else: + return + equations = generate_observation_equations(P,state,m_mag[index],obs_var,varname=label) + mag_code_generator.print_string("Axis %i equations" % index) + write_equations_to_file(equations,mag_code_generator,1) + + mag_code_generator.close() + + # calculate a combined set of equations for a possible reduction in operations, but will use slighlty more stack + equations = generate_observation_vector_equations(P,state,m_mag,obs_var,3) + + mag_code_generator_alt = CodeGenerator("./generated/3Dmag_generated_alt.cpp") + write_equations_to_file(equations,mag_code_generator_alt,3) + mag_code_generator_alt.close() + + return + +# airspeed fusion +def tas_observation(P,state,vx,vy,vz,wx,wy): + obs_var = symbols("R_TAS", real=True) # true airspeed measurement noise variance + + observation = sqrt((vx-wx)*(vx-wx)+(vy-wy)*(vy-wy)+vz*vz) + + equations = generate_observation_equations(P,state,observation,obs_var) + + tas_code_generator = CodeGenerator("./generated/tas_generated.cpp") + write_equations_to_file(equations,tas_code_generator,1) + tas_code_generator.close() + + return + +# sideslip fusion +def beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy): + obs_var = symbols("R_BETA", real=True) # sideslip measurement noise variance + + v_rel_ef = Matrix([vx-wx,vy-wy,vz]) + v_rel_bf = R_to_body * v_rel_ef + observation = v_rel_bf[1]/v_rel_bf[0] + + equations = generate_observation_equations(P,state,observation,obs_var) + + beta_code_generator = CodeGenerator("./generated/beta_generated.cpp") + write_equations_to_file(equations,beta_code_generator,1) + beta_code_generator.close() + + return + +# yaw estimator prediction and observation code +def yaw_estimator(): + dt = symbols("dt", real=True) # dt (sec) + psi = symbols("psi", real=True) # yaw angle of body frame wrt earth frame + vn, ve = symbols("vn ve", real=True) # velocity in world frame (north/east) - m/sec + daz = symbols("daz", real=True) # IMU z axis delta angle measurement in body axes - rad + dazVar = symbols("dazVar", real=True) # IMU Z axis delta angle measurement variance (rad^2) + dvx, dvy = symbols("dvx dvy", real=True) # IMU x and y axis delta velocity measurement in body axes - m/sec + dvxVar, dvyVar = symbols("dvxVar dvyVar", real=True) # IMU x and y axis delta velocity measurement variance (m/s)^2 + + # derive the body to nav direction transformation matrix + Tbn = Matrix([[cos(psi) , -sin(psi)], + [sin(psi) , cos(psi)]]) + + # attitude update equation + psiNew = psi + daz + + # velocity update equations + velNew = Matrix([vn,ve]) + Tbn*Matrix([dvx,dvy]) + + # Define the state vectors + stateVector = Matrix([vn,ve,psi]) + + # Define vector of process equations + newStateVector = Matrix([velNew,psiNew]) + + # Calculate state transition matrix + F = newStateVector.jacobian(stateVector) + + # Derive the covariance prediction equations + # Error growth in the inertial solution is assumed to be driven by 'noise' in the delta angles and + # velocities, after bias effects have been removed. + + # derive the control(disturbance) influence matrix from IMU noise to state noise + G = newStateVector.jacobian(Matrix([dvx,dvy,daz])) + + # derive the state error matrix + distMatrix = Matrix([[dvxVar , 0 , 0], + [0 , dvyVar , 0], + [0 , 0 , dazVar]]) + + Q = G * distMatrix * G.T + + # propagate covariance matrix + P = create_yaw_estimator_cov_matrix() + + P_new = F * P * F.T + Q + + P_new_simple = cse(P_new, symbols("S0:1000"), optimizations='basic') + + yaw_estimator_covariance_generator = CodeGenerator("./generated/yaw_estimator_covariance_prediction_generated.cpp") + yaw_estimator_covariance_generator.print_string("Equations for covariance matrix prediction") + yaw_estimator_covariance_generator.write_subexpressions(P_new_simple[0]) + yaw_estimator_covariance_generator.write_matrix(Matrix(P_new_simple[1]), "_ekf_gsf[model_index].P", True) + yaw_estimator_covariance_generator.close() + + # derive the covariance update equation for a NE velocity observation + velObsVar = symbols("velObsVar", real=True) # velocity observation variance (m/s)^2 + H = Matrix([[1,0,0], + [0,1,0]]) + + R = Matrix([[velObsVar , 0], + [0 , velObsVar]]) + + S = H * P * H.T + R + S_det_inv = 1 / S.det() + S_inv = S.inv() + K = (P * H.T) * S_inv + P_new = P - K * S * K.T + + # optimize code + t, [S_det_inv_s, S_inv_s, K_s, P_new_s] = cse([S_det_inv, S_inv, K, P_new], symbols("t0:1000"), optimizations='basic') + + yaw_estimator_observation_generator = CodeGenerator("./generated/yaw_estimator_measurement_update_generated.cpp") + yaw_estimator_observation_generator.print_string("Intermediate variables") + yaw_estimator_observation_generator.write_subexpressions(t) + yaw_estimator_observation_generator.print_string("Equations for NE velocity innovation variance's determinante inverse") + yaw_estimator_observation_generator.write_matrix(Matrix([[S_det_inv_s]]), "_ekf_gsf[model_index].S_det_inverse", False) + yaw_estimator_observation_generator.print_string("Equations for NE velocity innovation variance inverse") + yaw_estimator_observation_generator.write_matrix(Matrix(S_inv_s), "_ekf_gsf[model_index].S_inverse", True) + yaw_estimator_observation_generator.print_string("Equations for NE velocity Kalman gain") + yaw_estimator_observation_generator.write_matrix(Matrix(K_s), "K", False) + yaw_estimator_observation_generator.print_string("Equations for covariance matrix update") + yaw_estimator_observation_generator.write_matrix(Matrix(P_new_s), "_ekf_gsf[model_index].P", True) + yaw_estimator_observation_generator.close() + +def quaternion_error_propagation(): + # define quaternion state vector + q0, q1, q2, q3 = symbols("q0 q1 q2 q3", real=True) + q = Matrix([q0, q1, q2, q3]) + + # define truth gravity unit vector in body frame + R_to_earth = quat2Rot(q) + R_to_body = R_to_earth.T + gravity_ef = Matrix([0,0,1]) + gravity_bf = R_to_body * gravity_ef + + # define perturbations to quaternion state vector q + dq0, dq1, dq2, dq3 = symbols("dq0 dq1 dq2 dq3", real=True) + q_delta = Matrix([dq0, dq1, dq2, dq3]) + + # apply perturbations + q_perturbed = q + q_delta + + # gravity unit vector in body frame after quaternion perturbation + R_to_earth_perturbed = quat2Rot(q_perturbed) + R_to_body_perturbed = R_to_earth_perturbed.T + gravity_bf_perturbed = R_to_body_perturbed * gravity_ef + + # calculate the angular difference between the perturbed and unperturbed body frame gravity unit vectors + # assuming small angles + tilt_error_bf = gravity_bf.cross(gravity_bf_perturbed) + + # calculate the derivative of the perturbation rotation vector wrt the quaternion perturbations + J = tilt_error_bf.jacobian(q_delta) + + # remove second order terms + # we don't want the error deltas to appear in the final result + J.subs(dq0,0) + J.subs(dq1,0) + J.subs(dq2,0) + J.subs(dq3,0) + + # define covaraince matrix for quaternion states + P = create_symmetric_cov_matrix(4) + + # discard off diagonals + P_diag = diag(P[0,0],P[1,1],P[2,2],P[3,3]) + + # rotate quaternion covariances into rotation vector state space + P_rot_vec = J * P_diag * J.transpose() + P_rot_vec_simple = cse(P_rot_vec, symbols("PS0:400"), optimizations='basic') + + quat_code_generator = CodeGenerator("./generated/tilt_error_cov_mat_generated.cpp") + quat_code_generator.write_subexpressions(P_rot_vec_simple[0]) + quat_code_generator.write_matrix(Matrix(P_rot_vec_simple[1]), "tiltErrCovMat", False, "[", "]") + quat_code_generator.close() + +def generate_code(): + print('Starting code generation:') + print('Creating symbolic variables ...') + + dt = symbols("dt", real=True) # dt + g = symbols("g", real=True) # gravity constant + + r_hor_vel = symbols("R_hor_vel", real=True) # horizontal velocity noise variance + r_ver_vel = symbols("R_vert_vel", real=True) # vertical velocity noise variance + r_hor_pos = symbols("R_hor_pos", real=True) # horizontal position noise variance + + # inputs, integrated gyro measurements + # delta angle x y z + d_ang_x, d_ang_y, d_ang_z = symbols("dax day daz", real=True) # delta angle x + d_ang = Matrix([d_ang_x, d_ang_y, d_ang_z]) + + # inputs, integrated accelerometer measurements + # delta velocity x y z + d_v_x, d_v_y, d_v_z = symbols("dvx dvy dvz", real=True) + d_v = Matrix([d_v_x, d_v_y,d_v_z]) + + u = Matrix([d_ang, d_v]) + + # input noise + d_ang_x_var, d_ang_y_var, d_ang_z_var = symbols("daxVar dayVar dazVar", real=True) + + d_v_x_var, d_v_y_var, d_v_z_var = symbols("dvxVar dvyVar dvzVar", real=True) + + var_u = Matrix.diag(d_ang_x_var, d_ang_y_var, d_ang_z_var, d_v_x_var, d_v_y_var, d_v_z_var) + + # define state vector + + # attitude quaternion + qw, qx, qy, qz = symbols("q0 q1 q2 q3", real=True) + q = Matrix([qw,qx,qy,qz]) + R_to_earth = quat2Rot(q) + R_to_body = R_to_earth.T + + # velocity in NED local frame (north, east, down) + vx, vy, vz = symbols("vn ve vd", real=True) + v = Matrix([vx,vy,vz]) + + # position in NED local frame (north, east, down) + px, py, pz = symbols("pn pe pd", real=True) + p = Matrix([px,py,pz]) + + # delta angle bias x y z + d_ang_bx, d_ang_by, d_ang_bz = symbols("dax_b day_b daz_b", real=True) + d_ang_b = Matrix([d_ang_bx, d_ang_by, d_ang_bz]) + d_ang_true = d_ang - d_ang_b + + # delta velocity bias x y z + d_vel_bx, d_vel_by, d_vel_bz = symbols("dvx_b dvy_b dvz_b", real=True) + d_vel_b = Matrix([d_vel_bx, d_vel_by, d_vel_bz]) + d_vel_true = d_v - d_vel_b + + # earth magnetic field vector x y z + ix, iy, iz = symbols("magN magE magD", real=True) + i = Matrix([ix,iy,iz]) + + # earth magnetic field bias in body frame + ibx, iby, ibz = symbols("ibx iby ibz", real=True) + + ib = Matrix([ibx,iby,ibz]) + + # wind in local NE frame (north, east) + wx, wy = symbols("vwn, vwe", real=True) + w = Matrix([wx,wy]) + + # state vector at arbitrary time t + state = Matrix([q, v, p, d_ang_b, d_vel_b, i, ib, w]) + + print('Defining state propagation ...') + # kinematic processes driven by IMU 'control inputs' + q_new = quat_mult(q, Matrix([1, 0.5 * d_ang_true[0], 0.5 * d_ang_true[1], 0.5 * d_ang_true[2]])) + v_new = v + R_to_earth * d_vel_true + Matrix([0,0,g]) * dt + p_new = p + v * dt + + # static processes + d_ang_b_new = d_ang_b + d_vel_b_new = d_vel_b + i_new = i + ib_new = ib + w_new = w + + # predicted state vector at time t + dt + state_new = Matrix([q_new, v_new, p_new, d_ang_b_new, d_vel_b_new, i_new, ib_new, w_new]) + + print('Computing state propagation jacobian ...') + A = state_new.jacobian(state) + G = state_new.jacobian(u) + + P = create_symmetric_cov_matrix(24) + + print('Computing covariance propagation ...') + P_new = A * P * A.T + G * var_u * G.T + + for index in range(24): + for j in range(24): + if index > j: + P_new[index,j] = 0 + + print('Simplifying covariance propagation ...') + P_new_simple = cse(P_new, symbols("PS0:400"), optimizations='basic') + + # print('Writing covariance propagation to file ...') + # cov_code_generator = CodeGenerator("./generated/covariance_generated.cpp") + # cov_code_generator.print_string("Equations for covariance matrix prediction, without process noise!") + # cov_code_generator.write_subexpressions(P_new_simple[0]) + # cov_code_generator.write_matrix(Matrix(P_new_simple[1]), "nextP", True, "[", "]") + + # cov_code_generator.close() + + + # derive autocode for other methods + print('Computing tilt error covariance matrix ...') + quaternion_error_propagation() + print('Generating heading observation code ...') + yaw_observation(P,state,R_to_earth) + # print('Generating gps heading observation code ...') + # gps_yaw_observation(P,state,R_to_body) + # print('Generating mag observation code ...') + # mag_observation_variance(P,state,R_to_body,i,ib) + # mag_observation(P,state,R_to_body,i,ib) + # print('Generating declination observation code ...') + # declination_observation(P,state,ix,iy) + # print('Generating airspeed observation code ...') + # tas_observation(P,state,vx,vy,vz,wx,wy) + # print('Generating sideslip observation code ...') + # beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy) + # print('Generating optical flow observation code ...') + # optical_flow_observation(P,state,R_to_body,vx,vy,vz) + # print('Generating body frame velocity observation code ...') + # body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz) + print('Generating body frame acceleration observation code ...') + body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy) + # print('Generating yaw estimator code ...') + # yaw_estimator() + print('Code generation finished!') + + +if __name__ == "__main__": + generate_code() diff --git a/libraries/AP_NavEKF3/derivation/generate_nix b/libraries/AP_NavEKF3/derivation/generate_nix new file mode 100755 index 00000000000000..545582a36d3459 --- /dev/null +++ b/libraries/AP_NavEKF3/derivation/generate_nix @@ -0,0 +1,14 @@ +#!/usr/bin/env nix-shell +#! nix-shell --pure -i bash -p "python3.withPackages (p: [ p.numpy p.sympy ])" +#! nix-shell -I nixpkgs=https://github.com/NixOS/nixpkgs/archive/eabc38219184cc3e04a974fe31857d8e0eac098d.tar.gz + +# above pins Python 3.9.13, Numpy 1.21.2, and Sympy 1.9 (and deps) +# using the last nixos-21.11 branch commit + +cd "$(dirname "$0")" +rm -rf generated # ensure generated directory exists and is empty +mkdir -p generated + +# explicitly invoke python3 to use interpreter from nix-shell +python3 ./generate_1.py +python3 ./generate_2.py diff --git a/libraries/AP_NavEKF3/derivation/generated/acc_bf_generated.cpp b/libraries/AP_NavEKF3/derivation/generated/acc_bf_generated.cpp deleted file mode 100644 index 21b18f298ce7f2..00000000000000 --- a/libraries/AP_NavEKF3/derivation/generated/acc_bf_generated.cpp +++ /dev/null @@ -1,182 +0,0 @@ -// Axis 0 equations -// Sub Expressions -const ftype HK0 = vn - vwn; -const ftype HK1 = ve - vwe; -const ftype HK2 = HK0*q0 + HK1*q3 - q2*vd; -const ftype HK3 = 2*Kaccx; -const ftype HK4 = HK0*q1 + HK1*q2 + q3*vd; -const ftype HK5 = HK0*q2 - HK1*q1 + q0*vd; -const ftype HK6 = -HK0*q3 + HK1*q0 + q1*vd; -const ftype HK7 = sq(q0) + sq(q1) - sq(q2) - sq(q3); -const ftype HK8 = HK7*Kaccx; -const ftype HK9 = q0*q3 + q1*q2; -const ftype HK10 = HK3*HK9; -const ftype HK11 = q0*q2 - q1*q3; -const ftype HK12 = 2*HK9; -const ftype HK13 = 2*HK11; -const ftype HK14 = 2*HK4; -const ftype HK15 = 2*HK2; -const ftype HK16 = 2*HK5; -const ftype HK17 = 2*HK6; -const ftype HK18 = -HK12*P[0][23] + HK12*P[0][5] - HK13*P[0][6] + HK14*P[0][1] + HK15*P[0][0] - HK16*P[0][2] + HK17*P[0][3] - HK7*P[0][22] + HK7*P[0][4]; -const ftype HK19 = HK12*P[5][23]; -const ftype HK20 = -HK12*P[23][23] - HK13*P[6][23] + HK14*P[1][23] + HK15*P[0][23] - HK16*P[2][23] + HK17*P[3][23] + HK19 - HK7*P[22][23] + HK7*P[4][23]; -const ftype HK21 = sq(Kaccx); -const ftype HK22 = HK12*HK21; -const ftype HK23 = HK12*P[5][5] - HK13*P[5][6] + HK14*P[1][5] + HK15*P[0][5] - HK16*P[2][5] + HK17*P[3][5] - HK19 + HK7*P[4][5] - HK7*P[5][22]; -const ftype HK24 = HK12*P[5][6] - HK12*P[6][23] - HK13*P[6][6] + HK14*P[1][6] + HK15*P[0][6] - HK16*P[2][6] + HK17*P[3][6] + HK7*P[4][6] - HK7*P[6][22]; -const ftype HK25 = HK7*P[4][22]; -const ftype HK26 = -HK12*P[4][23] + HK12*P[4][5] - HK13*P[4][6] + HK14*P[1][4] + HK15*P[0][4] - HK16*P[2][4] + HK17*P[3][4] - HK25 + HK7*P[4][4]; -const ftype HK27 = HK21*HK7; -const ftype HK28 = -HK12*P[22][23] + HK12*P[5][22] - HK13*P[6][22] + HK14*P[1][22] + HK15*P[0][22] - HK16*P[2][22] + HK17*P[3][22] + HK25 - HK7*P[22][22]; -const ftype HK29 = -HK12*P[1][23] + HK12*P[1][5] - HK13*P[1][6] + HK14*P[1][1] + HK15*P[0][1] - HK16*P[1][2] + HK17*P[1][3] - HK7*P[1][22] + HK7*P[1][4]; -const ftype HK30 = -HK12*P[2][23] + HK12*P[2][5] - HK13*P[2][6] + HK14*P[1][2] + HK15*P[0][2] - HK16*P[2][2] + HK17*P[2][3] - HK7*P[2][22] + HK7*P[2][4]; -const ftype HK31 = -HK12*P[3][23] + HK12*P[3][5] - HK13*P[3][6] + HK14*P[1][3] + HK15*P[0][3] - HK16*P[2][3] + HK17*P[3][3] - HK7*P[3][22] + HK7*P[3][4]; -const ftype HK32 = Kaccx/(-HK13*HK21*HK24 + HK14*HK21*HK29 + HK15*HK18*HK21 - HK16*HK21*HK30 + HK17*HK21*HK31 - HK20*HK22 + HK22*HK23 + HK26*HK27 - HK27*HK28 + R_ACC); - - -// Observation Jacobians -Hfusion[0] = -HK2*HK3; -Hfusion[1] = -HK3*HK4; -Hfusion[2] = HK3*HK5; -Hfusion[3] = -HK3*HK6; -Hfusion[4] = -HK8; -Hfusion[5] = -HK10; -Hfusion[6] = HK11*HK3; -Hfusion[7] = 0; -Hfusion[8] = 0; -Hfusion[9] = 0; -Hfusion[10] = 0; -Hfusion[11] = 0; -Hfusion[12] = 0; -Hfusion[13] = 0; -Hfusion[14] = 0; -Hfusion[15] = 0; -Hfusion[16] = 0; -Hfusion[17] = 0; -Hfusion[18] = 0; -Hfusion[19] = 0; -Hfusion[20] = 0; -Hfusion[21] = 0; -Hfusion[22] = HK8; -Hfusion[23] = HK10; - - -// Kalman gains -Kfusion[0] = -HK18*HK32; -Kfusion[1] = -HK29*HK32; -Kfusion[2] = -HK30*HK32; -Kfusion[3] = -HK31*HK32; -Kfusion[4] = -HK26*HK32; -Kfusion[5] = -HK23*HK32; -Kfusion[6] = -HK24*HK32; -Kfusion[7] = -HK32*(HK12*P[5][7] - HK12*P[7][23] - HK13*P[6][7] + HK14*P[1][7] + HK15*P[0][7] - HK16*P[2][7] + HK17*P[3][7] + HK7*P[4][7] - HK7*P[7][22]); -Kfusion[8] = -HK32*(HK12*P[5][8] - HK12*P[8][23] - HK13*P[6][8] + HK14*P[1][8] + HK15*P[0][8] - HK16*P[2][8] + HK17*P[3][8] + HK7*P[4][8] - HK7*P[8][22]); -Kfusion[9] = -HK32*(HK12*P[5][9] - HK12*P[9][23] - HK13*P[6][9] + HK14*P[1][9] + HK15*P[0][9] - HK16*P[2][9] + HK17*P[3][9] + HK7*P[4][9] - HK7*P[9][22]); -Kfusion[10] = -HK32*(-HK12*P[10][23] + HK12*P[5][10] - HK13*P[6][10] + HK14*P[1][10] + HK15*P[0][10] - HK16*P[2][10] + HK17*P[3][10] - HK7*P[10][22] + HK7*P[4][10]); -Kfusion[11] = -HK32*(-HK12*P[11][23] + HK12*P[5][11] - HK13*P[6][11] + HK14*P[1][11] + HK15*P[0][11] - HK16*P[2][11] + HK17*P[3][11] - HK7*P[11][22] + HK7*P[4][11]); -Kfusion[12] = -HK32*(-HK12*P[12][23] + HK12*P[5][12] - HK13*P[6][12] + HK14*P[1][12] + HK15*P[0][12] - HK16*P[2][12] + HK17*P[3][12] - HK7*P[12][22] + HK7*P[4][12]); -Kfusion[13] = -HK32*(-HK12*P[13][23] + HK12*P[5][13] - HK13*P[6][13] + HK14*P[1][13] + HK15*P[0][13] - HK16*P[2][13] + HK17*P[3][13] - HK7*P[13][22] + HK7*P[4][13]); -Kfusion[14] = -HK32*(-HK12*P[14][23] + HK12*P[5][14] - HK13*P[6][14] + HK14*P[1][14] + HK15*P[0][14] - HK16*P[2][14] + HK17*P[3][14] - HK7*P[14][22] + HK7*P[4][14]); -Kfusion[15] = -HK32*(-HK12*P[15][23] + HK12*P[5][15] - HK13*P[6][15] + HK14*P[1][15] + HK15*P[0][15] - HK16*P[2][15] + HK17*P[3][15] - HK7*P[15][22] + HK7*P[4][15]); -Kfusion[16] = -HK32*(-HK12*P[16][23] + HK12*P[5][16] - HK13*P[6][16] + HK14*P[1][16] + HK15*P[0][16] - HK16*P[2][16] + HK17*P[3][16] - HK7*P[16][22] + HK7*P[4][16]); -Kfusion[17] = -HK32*(-HK12*P[17][23] + HK12*P[5][17] - HK13*P[6][17] + HK14*P[1][17] + HK15*P[0][17] - HK16*P[2][17] + HK17*P[3][17] - HK7*P[17][22] + HK7*P[4][17]); -Kfusion[18] = -HK32*(-HK12*P[18][23] + HK12*P[5][18] - HK13*P[6][18] + HK14*P[1][18] + HK15*P[0][18] - HK16*P[2][18] + HK17*P[3][18] - HK7*P[18][22] + HK7*P[4][18]); -Kfusion[19] = -HK32*(-HK12*P[19][23] + HK12*P[5][19] - HK13*P[6][19] + HK14*P[1][19] + HK15*P[0][19] - HK16*P[2][19] + HK17*P[3][19] - HK7*P[19][22] + HK7*P[4][19]); -Kfusion[20] = -HK32*(-HK12*P[20][23] + HK12*P[5][20] - HK13*P[6][20] + HK14*P[1][20] + HK15*P[0][20] - HK16*P[2][20] + HK17*P[3][20] - HK7*P[20][22] + HK7*P[4][20]); -Kfusion[21] = -HK32*(-HK12*P[21][23] + HK12*P[5][21] - HK13*P[6][21] + HK14*P[1][21] + HK15*P[0][21] - HK16*P[2][21] + HK17*P[3][21] - HK7*P[21][22] + HK7*P[4][21]); -Kfusion[22] = -HK28*HK32; -Kfusion[23] = -HK20*HK32; - - -// Axis 1 equations -// Sub Expressions -const ftype HK0 = ve - vwe; -const ftype HK1 = vn - vwn; -const ftype HK2 = HK0*q0 - HK1*q3 + q1*vd; -const ftype HK3 = 2*Kaccy; -const ftype HK4 = -HK0*q1 + HK1*q2 + q0*vd; -const ftype HK5 = HK0*q2 + HK1*q1 + q3*vd; -const ftype HK6 = HK0*q3 + HK1*q0 - q2*vd; -const ftype HK7 = q0*q3 - q1*q2; -const ftype HK8 = HK3*HK7; -const ftype HK9 = sq(q0) - sq(q1) + sq(q2) - sq(q3); -const ftype HK10 = HK9*Kaccy; -const ftype HK11 = q0*q1 + q2*q3; -const ftype HK12 = 2*HK11; -const ftype HK13 = 2*HK7; -const ftype HK14 = 2*HK5; -const ftype HK15 = 2*HK2; -const ftype HK16 = 2*HK4; -const ftype HK17 = 2*HK6; -const ftype HK18 = HK12*P[0][6] + HK13*P[0][22] - HK13*P[0][4] + HK14*P[0][2] + HK15*P[0][0] + HK16*P[0][1] - HK17*P[0][3] - HK9*P[0][23] + HK9*P[0][5]; -const ftype HK19 = sq(Kaccy); -const ftype HK20 = HK12*P[6][6] - HK13*P[4][6] + HK13*P[6][22] + HK14*P[2][6] + HK15*P[0][6] + HK16*P[1][6] - HK17*P[3][6] + HK9*P[5][6] - HK9*P[6][23]; -const ftype HK21 = HK13*P[4][22]; -const ftype HK22 = HK12*P[6][22] + HK13*P[22][22] + HK14*P[2][22] + HK15*P[0][22] + HK16*P[1][22] - HK17*P[3][22] - HK21 - HK9*P[22][23] + HK9*P[5][22]; -const ftype HK23 = HK13*HK19; -const ftype HK24 = HK12*P[4][6] - HK13*P[4][4] + HK14*P[2][4] + HK15*P[0][4] + HK16*P[1][4] - HK17*P[3][4] + HK21 - HK9*P[4][23] + HK9*P[4][5]; -const ftype HK25 = HK9*P[5][23]; -const ftype HK26 = HK12*P[5][6] - HK13*P[4][5] + HK13*P[5][22] + HK14*P[2][5] + HK15*P[0][5] + HK16*P[1][5] - HK17*P[3][5] - HK25 + HK9*P[5][5]; -const ftype HK27 = HK19*HK9; -const ftype HK28 = HK12*P[6][23] + HK13*P[22][23] - HK13*P[4][23] + HK14*P[2][23] + HK15*P[0][23] + HK16*P[1][23] - HK17*P[3][23] + HK25 - HK9*P[23][23]; -const ftype HK29 = HK12*P[2][6] + HK13*P[2][22] - HK13*P[2][4] + HK14*P[2][2] + HK15*P[0][2] + HK16*P[1][2] - HK17*P[2][3] - HK9*P[2][23] + HK9*P[2][5]; -const ftype HK30 = HK12*P[1][6] + HK13*P[1][22] - HK13*P[1][4] + HK14*P[1][2] + HK15*P[0][1] + HK16*P[1][1] - HK17*P[1][3] - HK9*P[1][23] + HK9*P[1][5]; -const ftype HK31 = HK12*P[3][6] + HK13*P[3][22] - HK13*P[3][4] + HK14*P[2][3] + HK15*P[0][3] + HK16*P[1][3] - HK17*P[3][3] - HK9*P[3][23] + HK9*P[3][5]; -const ftype HK32 = Kaccy/(HK12*HK19*HK20 + HK14*HK19*HK29 + HK15*HK18*HK19 + HK16*HK19*HK30 - HK17*HK19*HK31 + HK22*HK23 - HK23*HK24 + HK26*HK27 - HK27*HK28 + R_ACC); - - -// Observation Jacobians -Hfusion[0] = -HK2*HK3; -Hfusion[1] = -HK3*HK4; -Hfusion[2] = -HK3*HK5; -Hfusion[3] = HK3*HK6; -Hfusion[4] = HK8; -Hfusion[5] = -HK10; -Hfusion[6] = -HK11*HK3; -Hfusion[7] = 0; -Hfusion[8] = 0; -Hfusion[9] = 0; -Hfusion[10] = 0; -Hfusion[11] = 0; -Hfusion[12] = 0; -Hfusion[13] = 0; -Hfusion[14] = 0; -Hfusion[15] = 0; -Hfusion[16] = 0; -Hfusion[17] = 0; -Hfusion[18] = 0; -Hfusion[19] = 0; -Hfusion[20] = 0; -Hfusion[21] = 0; -Hfusion[22] = -HK8; -Hfusion[23] = HK10; - - -// Kalman gains -Kfusion[0] = -HK18*HK32; -Kfusion[1] = -HK30*HK32; -Kfusion[2] = -HK29*HK32; -Kfusion[3] = -HK31*HK32; -Kfusion[4] = -HK24*HK32; -Kfusion[5] = -HK26*HK32; -Kfusion[6] = -HK20*HK32; -Kfusion[7] = -HK32*(HK12*P[6][7] - HK13*P[4][7] + HK13*P[7][22] + HK14*P[2][7] + HK15*P[0][7] + HK16*P[1][7] - HK17*P[3][7] + HK9*P[5][7] - HK9*P[7][23]); -Kfusion[8] = -HK32*(HK12*P[6][8] - HK13*P[4][8] + HK13*P[8][22] + HK14*P[2][8] + HK15*P[0][8] + HK16*P[1][8] - HK17*P[3][8] + HK9*P[5][8] - HK9*P[8][23]); -Kfusion[9] = -HK32*(HK12*P[6][9] - HK13*P[4][9] + HK13*P[9][22] + HK14*P[2][9] + HK15*P[0][9] + HK16*P[1][9] - HK17*P[3][9] + HK9*P[5][9] - HK9*P[9][23]); -Kfusion[10] = -HK32*(HK12*P[6][10] + HK13*P[10][22] - HK13*P[4][10] + HK14*P[2][10] + HK15*P[0][10] + HK16*P[1][10] - HK17*P[3][10] - HK9*P[10][23] + HK9*P[5][10]); -Kfusion[11] = -HK32*(HK12*P[6][11] + HK13*P[11][22] - HK13*P[4][11] + HK14*P[2][11] + HK15*P[0][11] + HK16*P[1][11] - HK17*P[3][11] - HK9*P[11][23] + HK9*P[5][11]); -Kfusion[12] = -HK32*(HK12*P[6][12] + HK13*P[12][22] - HK13*P[4][12] + HK14*P[2][12] + HK15*P[0][12] + HK16*P[1][12] - HK17*P[3][12] - HK9*P[12][23] + HK9*P[5][12]); -Kfusion[13] = -HK32*(HK12*P[6][13] + HK13*P[13][22] - HK13*P[4][13] + HK14*P[2][13] + HK15*P[0][13] + HK16*P[1][13] - HK17*P[3][13] - HK9*P[13][23] + HK9*P[5][13]); -Kfusion[14] = -HK32*(HK12*P[6][14] + HK13*P[14][22] - HK13*P[4][14] + HK14*P[2][14] + HK15*P[0][14] + HK16*P[1][14] - HK17*P[3][14] - HK9*P[14][23] + HK9*P[5][14]); -Kfusion[15] = -HK32*(HK12*P[6][15] + HK13*P[15][22] - HK13*P[4][15] + HK14*P[2][15] + HK15*P[0][15] + HK16*P[1][15] - HK17*P[3][15] - HK9*P[15][23] + HK9*P[5][15]); -Kfusion[16] = -HK32*(HK12*P[6][16] + HK13*P[16][22] - HK13*P[4][16] + HK14*P[2][16] + HK15*P[0][16] + HK16*P[1][16] - HK17*P[3][16] - HK9*P[16][23] + HK9*P[5][16]); -Kfusion[17] = -HK32*(HK12*P[6][17] + HK13*P[17][22] - HK13*P[4][17] + HK14*P[2][17] + HK15*P[0][17] + HK16*P[1][17] - HK17*P[3][17] - HK9*P[17][23] + HK9*P[5][17]); -Kfusion[18] = -HK32*(HK12*P[6][18] + HK13*P[18][22] - HK13*P[4][18] + HK14*P[2][18] + HK15*P[0][18] + HK16*P[1][18] - HK17*P[3][18] - HK9*P[18][23] + HK9*P[5][18]); -Kfusion[19] = -HK32*(HK12*P[6][19] + HK13*P[19][22] - HK13*P[4][19] + HK14*P[2][19] + HK15*P[0][19] + HK16*P[1][19] - HK17*P[3][19] - HK9*P[19][23] + HK9*P[5][19]); -Kfusion[20] = -HK32*(HK12*P[6][20] + HK13*P[20][22] - HK13*P[4][20] + HK14*P[2][20] + HK15*P[0][20] + HK16*P[1][20] - HK17*P[3][20] - HK9*P[20][23] + HK9*P[5][20]); -Kfusion[21] = -HK32*(HK12*P[6][21] + HK13*P[21][22] - HK13*P[4][21] + HK14*P[2][21] + HK15*P[0][21] + HK16*P[1][21] - HK17*P[3][21] - HK9*P[21][23] + HK9*P[5][21]); -Kfusion[22] = -HK22*HK32; -Kfusion[23] = -HK28*HK32; - - diff --git a/libraries/AP_NavEKF3/derivation/generated/covariance_generated.cpp b/libraries/AP_NavEKF3/derivation/generated/covariance_generated.cpp deleted file mode 100644 index 9f42b505384f87..00000000000000 --- a/libraries/AP_NavEKF3/derivation/generated/covariance_generated.cpp +++ /dev/null @@ -1,492 +0,0 @@ -// Equations for covariance matrix prediction, without process noise! -const ftype PS0 = sq(q1); -const ftype PS1 = 0.25F*daxVar; -const ftype PS2 = sq(q2); -const ftype PS3 = 0.25F*dayVar; -const ftype PS4 = sq(q3); -const ftype PS5 = 0.25F*dazVar; -const ftype PS6 = 0.5F*q1; -const ftype PS7 = 0.5F*q2; -const ftype PS8 = PS7*P[10][11]; -const ftype PS9 = 0.5F*q3; -const ftype PS10 = PS9*P[10][12]; -const ftype PS11 = 0.5F*dax - 0.5F*dax_b; -const ftype PS12 = 0.5F*day - 0.5F*day_b; -const ftype PS13 = 0.5F*daz - 0.5F*daz_b; -const ftype PS14 = PS10 - PS11*P[1][10] - PS12*P[2][10] - PS13*P[3][10] + PS6*P[10][10] + PS8 + P[0][10]; -const ftype PS15 = PS6*P[10][11]; -const ftype PS16 = PS9*P[11][12]; -const ftype PS17 = -PS11*P[1][11] - PS12*P[2][11] - PS13*P[3][11] + PS15 + PS16 + PS7*P[11][11] + P[0][11]; -const ftype PS18 = PS6*P[10][12]; -const ftype PS19 = PS7*P[11][12]; -const ftype PS20 = -PS11*P[1][12] - PS12*P[2][12] - PS13*P[3][12] + PS18 + PS19 + PS9*P[12][12] + P[0][12]; -const ftype PS21 = PS12*P[1][2]; -const ftype PS22 = -PS13*P[1][3]; -const ftype PS23 = -PS11*P[1][1] - PS21 + PS22 + PS6*P[1][10] + PS7*P[1][11] + PS9*P[1][12] + P[0][1]; -const ftype PS24 = -PS11*P[1][2]; -const ftype PS25 = PS13*P[2][3]; -const ftype PS26 = -PS12*P[2][2] + PS24 - PS25 + PS6*P[2][10] + PS7*P[2][11] + PS9*P[2][12] + P[0][2]; -const ftype PS27 = PS11*P[1][3]; -const ftype PS28 = -PS12*P[2][3]; -const ftype PS29 = -PS13*P[3][3] - PS27 + PS28 + PS6*P[3][10] + PS7*P[3][11] + PS9*P[3][12] + P[0][3]; -const ftype PS30 = PS11*P[0][1]; -const ftype PS31 = PS12*P[0][2]; -const ftype PS32 = PS13*P[0][3]; -const ftype PS33 = -PS30 - PS31 - PS32 + PS6*P[0][10] + PS7*P[0][11] + PS9*P[0][12] + P[0][0]; -const ftype PS34 = 0.5F*q0; -const ftype PS35 = q2*q3; -const ftype PS36 = q0*q1; -const ftype PS37 = q1*q3; -const ftype PS38 = q0*q2; -const ftype PS39 = q1*q2; -const ftype PS40 = q0*q3; -const ftype PS41 = -PS2; -const ftype PS42 = sq(q0); -const ftype PS43 = -PS4 + PS42; -const ftype PS44 = PS0 + PS41 + PS43; -const ftype PS45 = -PS11*P[1][13] - PS12*P[2][13] - PS13*P[3][13] + PS6*P[10][13] + PS7*P[11][13] + PS9*P[12][13] + P[0][13]; -const ftype PS46 = PS37 + PS38; -const ftype PS47 = -PS11*P[1][15] - PS12*P[2][15] - PS13*P[3][15] + PS6*P[10][15] + PS7*P[11][15] + PS9*P[12][15] + P[0][15]; -const ftype PS48 = 2*PS47; -const ftype PS49 = dvy - dvy_b; -const ftype PS50 = dvx - dvx_b; -const ftype PS51 = dvz - dvz_b; -const ftype PS52 = PS49*q0 + PS50*q3 - PS51*q1; -const ftype PS53 = 2*PS29; -const ftype PS54 = -PS39 + PS40; -const ftype PS55 = -PS11*P[1][14] - PS12*P[2][14] - PS13*P[3][14] + PS6*P[10][14] + PS7*P[11][14] + PS9*P[12][14] + P[0][14]; -const ftype PS56 = 2*PS55; -const ftype PS57 = -PS49*q3 + PS50*q0 + PS51*q2; -const ftype PS58 = 2*PS33; -const ftype PS59 = PS49*q1 - PS50*q2 + PS51*q0; -const ftype PS60 = 2*PS59; -const ftype PS61 = PS49*q2 + PS50*q1 + PS51*q3; -const ftype PS62 = 2*PS61; -const ftype PS63 = -PS11*P[1][4] - PS12*P[2][4] - PS13*P[3][4] + PS6*P[4][10] + PS7*P[4][11] + PS9*P[4][12] + P[0][4]; -const ftype PS64 = -PS0; -const ftype PS65 = PS2 + PS43 + PS64; -const ftype PS66 = PS39 + PS40; -const ftype PS67 = 2*PS45; -const ftype PS68 = -PS35 + PS36; -const ftype PS69 = -PS11*P[1][5] - PS12*P[2][5] - PS13*P[3][5] + PS6*P[5][10] + PS7*P[5][11] + PS9*P[5][12] + P[0][5]; -const ftype PS70 = PS4 + PS41 + PS42 + PS64; -const ftype PS71 = PS35 + PS36; -const ftype PS72 = 2*PS57; -const ftype PS73 = -PS37 + PS38; -const ftype PS74 = 2*PS52; -const ftype PS75 = -PS11*P[1][6] - PS12*P[2][6] - PS13*P[3][6] + PS6*P[6][10] + PS7*P[6][11] + PS9*P[6][12] + P[0][6]; -const ftype PS76 = -PS34*P[10][11]; -const ftype PS77 = PS11*P[0][11] - PS12*P[3][11] + PS13*P[2][11] - PS19 + PS76 + PS9*P[11][11] + P[1][11]; -const ftype PS78 = PS13*P[0][2]; -const ftype PS79 = PS12*P[0][3]; -const ftype PS80 = PS11*P[0][0] - PS34*P[0][10] - PS7*P[0][12] + PS78 - PS79 + PS9*P[0][11] + P[0][1]; -const ftype PS81 = PS11*P[0][2]; -const ftype PS82 = PS13*P[2][2] + PS28 - PS34*P[2][10] - PS7*P[2][12] + PS81 + PS9*P[2][11] + P[1][2]; -const ftype PS83 = PS9*P[10][11]; -const ftype PS84 = PS7*P[10][12]; -const ftype PS85 = PS11*P[0][10] - PS12*P[3][10] + PS13*P[2][10] - PS34*P[10][10] + PS83 - PS84 + P[1][10]; -const ftype PS86 = -PS34*P[10][12]; -const ftype PS87 = PS11*P[0][12] - PS12*P[3][12] + PS13*P[2][12] + PS16 - PS7*P[12][12] + PS86 + P[1][12]; -const ftype PS88 = PS11*P[0][3]; -const ftype PS89 = -PS12*P[3][3] + PS25 - PS34*P[3][10] - PS7*P[3][12] + PS88 + PS9*P[3][11] + P[1][3]; -const ftype PS90 = PS13*P[1][2]; -const ftype PS91 = PS12*P[1][3]; -const ftype PS92 = PS30 - PS34*P[1][10] - PS7*P[1][12] + PS9*P[1][11] + PS90 - PS91 + P[1][1]; -const ftype PS93 = PS11*P[0][13] - PS12*P[3][13] + PS13*P[2][13] - PS34*P[10][13] - PS7*P[12][13] + PS9*P[11][13] + P[1][13]; -const ftype PS94 = PS11*P[0][15] - PS12*P[3][15] + PS13*P[2][15] - PS34*P[10][15] - PS7*P[12][15] + PS9*P[11][15] + P[1][15]; -const ftype PS95 = 2*PS94; -const ftype PS96 = PS11*P[0][14] - PS12*P[3][14] + PS13*P[2][14] - PS34*P[10][14] - PS7*P[12][14] + PS9*P[11][14] + P[1][14]; -const ftype PS97 = 2*PS96; -const ftype PS98 = PS11*P[0][4] - PS12*P[3][4] + PS13*P[2][4] - PS34*P[4][10] - PS7*P[4][12] + PS9*P[4][11] + P[1][4]; -const ftype PS99 = 2*PS93; -const ftype PS100 = PS11*P[0][5] - PS12*P[3][5] + PS13*P[2][5] - PS34*P[5][10] - PS7*P[5][12] + PS9*P[5][11] + P[1][5]; -const ftype PS101 = PS11*P[0][6] - PS12*P[3][6] + PS13*P[2][6] - PS34*P[6][10] - PS7*P[6][12] + PS9*P[6][11] + P[1][6]; -const ftype PS102 = -PS34*P[11][12]; -const ftype PS103 = -PS10 + PS102 + PS11*P[3][12] + PS12*P[0][12] - PS13*P[1][12] + PS6*P[12][12] + P[2][12]; -const ftype PS104 = PS11*P[3][3] + PS22 - PS34*P[3][11] + PS6*P[3][12] + PS79 - PS9*P[3][10] + P[2][3]; -const ftype PS105 = PS13*P[0][1]; -const ftype PS106 = -PS105 + PS12*P[0][0] - PS34*P[0][11] + PS6*P[0][12] + PS88 - PS9*P[0][10] + P[0][2]; -const ftype PS107 = PS6*P[11][12]; -const ftype PS108 = PS107 + PS11*P[3][11] + PS12*P[0][11] - PS13*P[1][11] - PS34*P[11][11] - PS83 + P[2][11]; -const ftype PS109 = PS11*P[3][10] + PS12*P[0][10] - PS13*P[1][10] + PS18 + PS76 - PS9*P[10][10] + P[2][10]; -const ftype PS110 = PS12*P[0][1]; -const ftype PS111 = PS110 - PS13*P[1][1] + PS27 - PS34*P[1][11] + PS6*P[1][12] - PS9*P[1][10] + P[1][2]; -const ftype PS112 = PS11*P[2][3]; -const ftype PS113 = PS112 + PS31 - PS34*P[2][11] + PS6*P[2][12] - PS9*P[2][10] - PS90 + P[2][2]; -const ftype PS114 = PS11*P[3][13] + PS12*P[0][13] - PS13*P[1][13] - PS34*P[11][13] + PS6*P[12][13] - PS9*P[10][13] + P[2][13]; -const ftype PS115 = PS11*P[3][15] + PS12*P[0][15] - PS13*P[1][15] - PS34*P[11][15] + PS6*P[12][15] - PS9*P[10][15] + P[2][15]; -const ftype PS116 = 2*PS115; -const ftype PS117 = PS11*P[3][14] + PS12*P[0][14] - PS13*P[1][14] - PS34*P[11][14] + PS6*P[12][14] - PS9*P[10][14] + P[2][14]; -const ftype PS118 = 2*PS117; -const ftype PS119 = PS11*P[3][4] + PS12*P[0][4] - PS13*P[1][4] - PS34*P[4][11] + PS6*P[4][12] - PS9*P[4][10] + P[2][4]; -const ftype PS120 = 2*PS114; -const ftype PS121 = PS11*P[3][5] + PS12*P[0][5] - PS13*P[1][5] - PS34*P[5][11] + PS6*P[5][12] - PS9*P[5][10] + P[2][5]; -const ftype PS122 = PS11*P[3][6] + PS12*P[0][6] - PS13*P[1][6] - PS34*P[6][11] + PS6*P[6][12] - PS9*P[6][10] + P[2][6]; -const ftype PS123 = -PS11*P[2][10] + PS12*P[1][10] + PS13*P[0][10] - PS15 + PS7*P[10][10] + PS86 + P[3][10]; -const ftype PS124 = PS105 + PS12*P[1][1] + PS24 - PS34*P[1][12] - PS6*P[1][11] + PS7*P[1][10] + P[1][3]; -const ftype PS125 = PS110 + PS13*P[0][0] - PS34*P[0][12] - PS6*P[0][11] + PS7*P[0][10] - PS81 + P[0][3]; -const ftype PS126 = -PS107 - PS11*P[2][12] + PS12*P[1][12] + PS13*P[0][12] - PS34*P[12][12] + PS84 + P[3][12]; -const ftype PS127 = PS102 - PS11*P[2][11] + PS12*P[1][11] + PS13*P[0][11] - PS6*P[11][11] + PS8 + P[3][11]; -const ftype PS128 = -PS11*P[2][2] + PS21 - PS34*P[2][12] - PS6*P[2][11] + PS7*P[2][10] + PS78 + P[2][3]; -const ftype PS129 = -PS112 + PS32 - PS34*P[3][12] - PS6*P[3][11] + PS7*P[3][10] + PS91 + P[3][3]; -const ftype PS130 = -PS11*P[2][13] + PS12*P[1][13] + PS13*P[0][13] - PS34*P[12][13] - PS6*P[11][13] + PS7*P[10][13] + P[3][13]; -const ftype PS131 = -PS11*P[2][15] + PS12*P[1][15] + PS13*P[0][15] - PS34*P[12][15] - PS6*P[11][15] + PS7*P[10][15] + P[3][15]; -const ftype PS132 = 2*PS131; -const ftype PS133 = -PS11*P[2][14] + PS12*P[1][14] + PS13*P[0][14] - PS34*P[12][14] - PS6*P[11][14] + PS7*P[10][14] + P[3][14]; -const ftype PS134 = 2*PS133; -const ftype PS135 = -PS11*P[2][4] + PS12*P[1][4] + PS13*P[0][4] - PS34*P[4][12] - PS6*P[4][11] + PS7*P[4][10] + P[3][4]; -const ftype PS136 = 2*PS130; -const ftype PS137 = -PS11*P[2][5] + PS12*P[1][5] + PS13*P[0][5] - PS34*P[5][12] - PS6*P[5][11] + PS7*P[5][10] + P[3][5]; -const ftype PS138 = -PS11*P[2][6] + PS12*P[1][6] + PS13*P[0][6] - PS34*P[6][12] - PS6*P[6][11] + PS7*P[6][10] + P[3][6]; -const ftype PS139 = 2*PS46; -const ftype PS140 = 2*PS54; -const ftype PS141 = -PS139*P[13][15] + PS140*P[13][14] - PS44*P[13][13] + PS60*P[2][13] + PS62*P[1][13] + PS72*P[0][13] - PS74*P[3][13] + P[4][13]; -const ftype PS142 = -PS139*P[15][15] + PS140*P[14][15] - PS44*P[13][15] + PS60*P[2][15] + PS62*P[1][15] + PS72*P[0][15] - PS74*P[3][15] + P[4][15]; -const ftype PS143 = PS62*P[1][3]; -const ftype PS144 = PS72*P[0][3]; -const ftype PS145 = -PS139*P[3][15] + PS140*P[3][14] + PS143 + PS144 - PS44*P[3][13] + PS60*P[2][3] - PS74*P[3][3] + P[3][4]; -const ftype PS146 = -PS139*P[14][15] + PS140*P[14][14] - PS44*P[13][14] + PS60*P[2][14] + PS62*P[1][14] + PS72*P[0][14] - PS74*P[3][14] + P[4][14]; -const ftype PS147 = PS60*P[0][2]; -const ftype PS148 = PS74*P[0][3]; -const ftype PS149 = -PS139*P[0][15] + PS140*P[0][14] + PS147 - PS148 - PS44*P[0][13] + PS62*P[0][1] + PS72*P[0][0] + P[0][4]; -const ftype PS150 = PS62*P[1][2]; -const ftype PS151 = PS72*P[0][2]; -const ftype PS152 = -PS139*P[2][15] + PS140*P[2][14] + PS150 + PS151 - PS44*P[2][13] + PS60*P[2][2] - PS74*P[2][3] + P[2][4]; -const ftype PS153 = PS60*P[1][2]; -const ftype PS154 = PS74*P[1][3]; -const ftype PS155 = -PS139*P[1][15] + PS140*P[1][14] + PS153 - PS154 - PS44*P[1][13] + PS62*P[1][1] + PS72*P[0][1] + P[1][4]; -const ftype PS156 = 4*dvyVar; -const ftype PS157 = 4*dvzVar; -const ftype PS158 = -PS139*P[4][15] + PS140*P[4][14] - PS44*P[4][13] + PS60*P[2][4] + PS62*P[1][4] + PS72*P[0][4] - PS74*P[3][4] + P[4][4]; -const ftype PS159 = 2*PS141; -const ftype PS160 = 2*PS68; -const ftype PS161 = PS65*dvyVar; -const ftype PS162 = 2*PS66; -const ftype PS163 = PS44*dvxVar; -const ftype PS164 = -PS139*P[5][15] + PS140*P[5][14] - PS44*P[5][13] + PS60*P[2][5] + PS62*P[1][5] + PS72*P[0][5] - PS74*P[3][5] + P[4][5]; -const ftype PS165 = 2*PS71; -const ftype PS166 = 2*PS73; -const ftype PS167 = PS70*dvzVar; -const ftype PS168 = -PS139*P[6][15] + PS140*P[6][14] - PS44*P[6][13] + PS60*P[2][6] + PS62*P[1][6] + PS72*P[0][6] - PS74*P[3][6] + P[4][6]; -const ftype PS169 = PS160*P[14][15] - PS162*P[13][14] - PS60*P[1][14] + PS62*P[2][14] - PS65*P[14][14] + PS72*P[3][14] + PS74*P[0][14] + P[5][14]; -const ftype PS170 = PS160*P[13][15] - PS162*P[13][13] - PS60*P[1][13] + PS62*P[2][13] - PS65*P[13][14] + PS72*P[3][13] + PS74*P[0][13] + P[5][13]; -const ftype PS171 = PS74*P[0][1]; -const ftype PS172 = PS150 + PS160*P[1][15] - PS162*P[1][13] + PS171 - PS60*P[1][1] - PS65*P[1][14] + PS72*P[1][3] + P[1][5]; -const ftype PS173 = PS160*P[15][15] - PS162*P[13][15] - PS60*P[1][15] + PS62*P[2][15] - PS65*P[14][15] + PS72*P[3][15] + PS74*P[0][15] + P[5][15]; -const ftype PS174 = PS62*P[2][3]; -const ftype PS175 = PS148 + PS160*P[3][15] - PS162*P[3][13] + PS174 - PS60*P[1][3] - PS65*P[3][14] + PS72*P[3][3] + P[3][5]; -const ftype PS176 = PS60*P[0][1]; -const ftype PS177 = PS144 + PS160*P[0][15] - PS162*P[0][13] - PS176 + PS62*P[0][2] - PS65*P[0][14] + PS74*P[0][0] + P[0][5]; -const ftype PS178 = PS72*P[2][3]; -const ftype PS179 = -PS153 + PS160*P[2][15] - PS162*P[2][13] + PS178 + PS62*P[2][2] - PS65*P[2][14] + PS74*P[0][2] + P[2][5]; -const ftype PS180 = 4*dvxVar; -const ftype PS181 = PS160*P[5][15] - PS162*P[5][13] - PS60*P[1][5] + PS62*P[2][5] - PS65*P[5][14] + PS72*P[3][5] + PS74*P[0][5] + P[5][5]; -const ftype PS182 = PS160*P[6][15] - PS162*P[6][13] - PS60*P[1][6] + PS62*P[2][6] - PS65*P[6][14] + PS72*P[3][6] + PS74*P[0][6] + P[5][6]; -const ftype PS183 = -PS165*P[14][15] + PS166*P[13][15] + PS60*P[0][15] + PS62*P[3][15] - PS70*P[15][15] - PS72*P[2][15] + PS74*P[1][15] + P[6][15]; -const ftype PS184 = -PS165*P[14][14] + PS166*P[13][14] + PS60*P[0][14] + PS62*P[3][14] - PS70*P[14][15] - PS72*P[2][14] + PS74*P[1][14] + P[6][14]; -const ftype PS185 = -PS165*P[13][14] + PS166*P[13][13] + PS60*P[0][13] + PS62*P[3][13] - PS70*P[13][15] - PS72*P[2][13] + PS74*P[1][13] + P[6][13]; -const ftype PS186 = -PS165*P[6][14] + PS166*P[6][13] + PS60*P[0][6] + PS62*P[3][6] - PS70*P[6][15] - PS72*P[2][6] + PS74*P[1][6] + P[6][6]; - - -nextP[0][0] = PS0*PS1 - PS11*PS23 - PS12*PS26 - PS13*PS29 + PS14*PS6 + PS17*PS7 + PS2*PS3 + PS20*PS9 + PS33 + PS4*PS5; -nextP[0][1] = -PS1*PS36 + PS11*PS33 - PS12*PS29 + PS13*PS26 - PS14*PS34 + PS17*PS9 - PS20*PS7 + PS23 + PS3*PS35 - PS35*PS5; -nextP[1][1] = PS1*PS95 + PS100*PS11 + PS102*PS13 - PS105*PS34 - PS107*PS7 - PS109*PS12 + PS112 + PS2*PS5 + PS3*PS4 + PS9*PS97; -nextP[0][2] = -PS1*PS37 + PS11*PS29 + PS12*PS33 - PS13*PS23 - PS14*PS9 - PS17*PS34 + PS20*PS6 + PS26 - PS3*PS38 + PS37*PS5; -nextP[1][2] = PS1*PS40 + PS100*PS12 + PS102 - PS105*PS9 + PS107*PS6 + PS109*PS11 - PS112*PS13 - PS3*PS40 - PS34*PS97 - PS39*PS5; -nextP[2][2] = PS0*PS5 + PS1*PS4 + PS11*PS128 + PS12*PS130 + PS127*PS6 - PS13*PS135 - PS132*PS34 - PS133*PS9 + PS137 + PS3*PS95; -nextP[0][3] = PS1*PS39 - PS11*PS26 + PS12*PS23 + PS13*PS33 + PS14*PS7 - PS17*PS6 - PS20*PS34 + PS29 - PS3*PS39 - PS40*PS5; -nextP[1][3] = -PS1*PS38 - PS11*PS82 + PS12*PS92 + PS13*PS80 - PS3*PS37 - PS34*PS87 + PS38*PS5 - PS6*PS77 + PS7*PS85 + PS89; -nextP[2][3] = -PS1*PS35 - PS103*PS34 + PS104 + PS106*PS13 - PS108*PS6 + PS109*PS7 - PS11*PS113 + PS111*PS12 + PS3*PS36 - PS36*PS5; -nextP[3][3] = PS0*PS3 + PS1*PS2 - PS11*PS128 + PS12*PS124 + PS123*PS7 + PS125*PS13 - PS126*PS34 - PS127*PS6 + PS129 + PS42*PS5; -nextP[0][4] = PS23*PS62 + PS26*PS60 - PS44*PS45 - PS46*PS48 - PS52*PS53 + PS54*PS56 + PS57*PS58 + PS63; -nextP[1][4] = -PS44*PS93 - PS46*PS95 + PS54*PS97 + PS60*PS82 + PS62*PS92 + PS72*PS80 - PS74*PS89 + PS98; -nextP[2][4] = -PS104*PS74 + PS106*PS72 + PS111*PS62 + PS113*PS60 - PS114*PS44 - PS116*PS46 + PS118*PS54 + PS119; -nextP[3][4] = PS124*PS62 + PS125*PS72 + PS128*PS60 - PS129*PS74 - PS130*PS44 - PS132*PS46 + PS134*PS54 + PS135; -nextP[4][4] = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*sq(PS54) + PS157*sq(PS46) + PS158 + sq(PS44)*dvxVar; -nextP[0][5] = -PS23*PS60 + PS26*PS62 + PS48*PS68 + PS52*PS58 + PS53*PS57 - PS55*PS65 - PS66*PS67 + PS69; -nextP[1][5] = PS100 - PS60*PS92 + PS62*PS82 - PS65*PS96 - PS66*PS99 + PS68*PS95 + PS72*PS89 + PS74*PS80; -nextP[2][5] = PS104*PS72 + PS106*PS74 - PS111*PS60 + PS113*PS62 + PS116*PS68 - PS117*PS65 - PS120*PS66 + PS121; -nextP[3][5] = -PS124*PS60 + PS125*PS74 + PS128*PS62 + PS129*PS72 + PS132*PS68 - PS133*PS65 - PS136*PS66 + PS137; -nextP[4][5] = -PS140*PS161 + PS142*PS160 + PS145*PS72 - PS146*PS65 + PS149*PS74 + PS152*PS62 - PS155*PS60 - PS157*PS46*PS68 - PS159*PS66 + PS162*PS163 + PS164; -nextP[5][5] = PS157*sq(PS68) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*sq(PS66) + PS181 + sq(PS65)*dvyVar; -nextP[0][6] = PS23*PS74 - PS26*PS72 - PS47*PS70 + PS53*PS61 - PS56*PS71 + PS58*PS59 + PS67*PS73 + PS75; -nextP[1][6] = PS101 + PS60*PS80 + PS62*PS89 - PS70*PS94 - PS71*PS97 - PS72*PS82 + PS73*PS99 + PS74*PS92; -nextP[2][6] = PS104*PS62 + PS106*PS60 + PS111*PS74 - PS113*PS72 - PS115*PS70 - PS118*PS71 + PS120*PS73 + PS122; -nextP[3][6] = PS124*PS74 + PS125*PS60 - PS128*PS72 + PS129*PS62 - PS131*PS70 - PS134*PS71 + PS136*PS73 + PS138; -nextP[4][6] = PS139*PS167 - PS142*PS70 + PS145*PS62 - PS146*PS165 + PS149*PS60 - PS152*PS72 + PS155*PS74 - PS156*PS54*PS71 + PS159*PS73 - PS163*PS166 + PS168; -nextP[5][6] = -PS160*PS167 + PS161*PS165 - PS165*PS169 + PS166*PS170 + PS172*PS74 - PS173*PS70 + PS175*PS62 + PS177*PS60 - PS179*PS72 - PS180*PS66*PS73 + PS182; -nextP[6][6] = PS156*sq(PS71) - PS165*PS184 + PS166*PS185 + PS180*sq(PS73) - PS183*PS70 + PS186 + PS60*(-PS151 - PS165*P[0][14] + PS166*P[0][13] + PS171 + PS60*P[0][0] + PS62*P[0][3] - PS70*P[0][15] + P[0][6]) + PS62*(PS154 - PS165*P[3][14] + PS166*P[3][13] - PS178 + PS60*P[0][3] + PS62*P[3][3] - PS70*P[3][15] + P[3][6]) + sq(PS70)*dvzVar - PS72*(PS147 - PS165*P[2][14] + PS166*P[2][13] + PS174 - PS70*P[2][15] - PS72*P[2][2] + PS74*P[1][2] + P[2][6]) + PS74*(PS143 - PS165*P[1][14] + PS166*P[1][13] + PS176 - PS70*P[1][15] - PS72*P[1][2] + PS74*P[1][1] + P[1][6]); -nextP[0][7] = -PS11*P[1][7] - PS12*P[2][7] - PS13*P[3][7] + PS6*P[7][10] + PS63*dt + PS7*P[7][11] + PS9*P[7][12] + P[0][7]; -nextP[1][7] = PS11*P[0][7] - PS12*P[3][7] + PS13*P[2][7] - PS34*P[7][10] - PS7*P[7][12] + PS9*P[7][11] + PS98*dt + P[1][7]; -nextP[2][7] = PS11*P[3][7] + PS119*dt + PS12*P[0][7] - PS13*P[1][7] - PS34*P[7][11] + PS6*P[7][12] - PS9*P[7][10] + P[2][7]; -nextP[3][7] = -PS11*P[2][7] + PS12*P[1][7] + PS13*P[0][7] + PS135*dt - PS34*P[7][12] - PS6*P[7][11] + PS7*P[7][10] + P[3][7]; -nextP[4][7] = -PS139*P[7][15] + PS140*P[7][14] + PS158*dt - PS44*P[7][13] + PS60*P[2][7] + PS62*P[1][7] + PS72*P[0][7] - PS74*P[3][7] + P[4][7]; -nextP[5][7] = PS160*P[7][15] - PS162*P[7][13] - PS60*P[1][7] + PS62*P[2][7] - PS65*P[7][14] + PS72*P[3][7] + PS74*P[0][7] + P[5][7] + dt*(PS160*P[4][15] - PS162*P[4][13] - PS60*P[1][4] + PS62*P[2][4] - PS65*P[4][14] + PS72*P[3][4] + PS74*P[0][4] + P[4][5]); -nextP[6][7] = -PS165*P[7][14] + PS166*P[7][13] + PS60*P[0][7] + PS62*P[3][7] - PS70*P[7][15] - PS72*P[2][7] + PS74*P[1][7] + P[6][7] + dt*(-PS165*P[4][14] + PS166*P[4][13] + PS60*P[0][4] + PS62*P[3][4] - PS70*P[4][15] - PS72*P[2][4] + PS74*P[1][4] + P[4][6]); -nextP[7][7] = P[4][7]*dt + P[7][7] + dt*(P[4][4]*dt + P[4][7]); -nextP[0][8] = -PS11*P[1][8] - PS12*P[2][8] - PS13*P[3][8] + PS6*P[8][10] + PS7*P[8][11] + PS86*dt + PS9*P[8][12] + P[0][8]; -nextP[1][8] = PS11*P[0][8] - PS12*P[3][8] + PS124*dt + PS13*P[2][8] - PS34*P[8][10] - PS7*P[8][12] + PS9*P[8][11] + P[1][8]; -nextP[2][8] = PS11*P[3][8] + PS12*P[0][8] - PS13*P[1][8] + PS149*dt - PS34*P[8][11] + PS6*P[8][12] - PS9*P[8][10] + P[2][8]; -nextP[3][8] = -PS11*P[2][8] + PS12*P[1][8] + PS13*P[0][8] + PS169*dt - PS34*P[8][12] - PS6*P[8][11] + PS7*P[8][10] + P[3][8]; -nextP[4][8] = -PS171*P[8][15] + PS172*P[8][14] + PS173*P[1][8] + PS174*P[0][8] + PS175*P[2][8] - PS176*P[3][8] + PS196*dt + PS43*P[8][13] + P[4][8]; -nextP[5][8] = PS190*P[8][15] - PS193*P[8][13] + PS201*P[2][8] - PS202*P[0][8] + PS203*P[3][8] - PS204*P[1][8] + PS213*dt + PS75*P[8][14] + P[5][8]; -nextP[6][8] = -PS197*P[8][14] + PS199*P[8][13] - PS214*P[2][8] + PS215*P[3][8] + PS216*P[0][8] + PS217*P[1][8] + PS87*P[8][15] + P[6][8] + dt*(-PS197*P[5][14] + PS199*P[5][13] - PS214*P[2][5] + PS215*P[3][5] + PS216*P[0][5] + PS217*P[1][5] + PS87*P[5][15] + P[5][6]); -nextP[7][8] = P[4][8]*dt + P[7][8] + dt*(P[4][5]*dt + P[5][7]); -nextP[8][8] = P[5][8]*dt + P[8][8] + dt*(P[5][5]*dt + P[5][8]); -nextP[0][9] = -PS11*P[1][9] - PS12*P[2][9] - PS13*P[3][9] + PS6*P[9][10] + PS7*P[9][11] + PS9*P[9][12] + PS94*dt + P[0][9]; -nextP[1][9] = PS11*P[0][9] - PS12*P[3][9] + PS125*dt + PS13*P[2][9] - PS34*P[9][10] - PS7*P[9][12] + PS9*P[9][11] + P[1][9]; -nextP[2][9] = PS11*P[3][9] + PS12*P[0][9] - PS13*P[1][9] + PS150*dt - PS34*P[9][11] + PS6*P[9][12] - PS9*P[9][10] + P[2][9]; -nextP[3][9] = -PS11*P[2][9] + PS12*P[1][9] + PS13*P[0][9] + PS170*dt - PS34*P[9][12] - PS6*P[9][11] + PS7*P[9][10] + P[3][9]; -nextP[4][9] = -PS171*P[9][15] + PS172*P[9][14] + PS173*P[1][9] + PS174*P[0][9] + PS175*P[2][9] - PS176*P[3][9] + PS200*dt + PS43*P[9][13] + P[4][9]; -nextP[5][9] = PS190*P[9][15] - PS193*P[9][13] + PS201*P[2][9] - PS202*P[0][9] + PS203*P[3][9] - PS204*P[1][9] + PS218*dt + PS75*P[9][14] + P[5][9]; -nextP[6][9] = -PS197*P[9][14] + PS199*P[9][13] - PS214*P[2][9] + PS215*P[3][9] + PS216*P[0][9] + PS217*P[1][9] + PS222*dt + PS87*P[9][15] + P[6][9]; -nextP[7][9] = P[4][9]*dt + P[7][9] + dt*(P[4][6]*dt + P[6][7]); -nextP[8][9] = P[5][9]*dt + P[8][9] + dt*(P[5][6]*dt + P[6][8]); -nextP[9][9] = P[6][9]*dt + P[9][9] + dt*(P[6][6]*dt + P[6][9]); -nextP[0][10] = PS14; -nextP[1][10] = PS105; -nextP[2][10] = PS133; -nextP[3][10] = PS151; -nextP[4][10] = -PS171*P[10][15] + PS172*P[10][14] + PS173*P[1][10] + PS174*P[0][10] + PS175*P[2][10] - PS176*P[3][10] + PS43*P[10][13] + P[4][10]; -nextP[5][10] = PS190*P[10][15] - PS193*P[10][13] + PS201*P[2][10] - PS202*P[0][10] + PS203*P[3][10] - PS204*P[1][10] + PS75*P[10][14] + P[5][10]; -nextP[6][10] = -PS197*P[10][14] + PS199*P[10][13] - PS214*P[2][10] + PS215*P[3][10] + PS216*P[0][10] + PS217*P[1][10] + PS87*P[10][15] + P[6][10]; -nextP[7][10] = P[4][10]*dt + P[7][10]; -nextP[8][10] = P[5][10]*dt + P[8][10]; -nextP[9][10] = P[6][10]*dt + P[9][10]; -nextP[10][10] = P[10][10]; -nextP[0][11] = PS17; -nextP[1][11] = PS97; -nextP[2][11] = PS132; -nextP[3][11] = PS155; -nextP[4][11] = -PS171*P[11][15] + PS172*P[11][14] + PS173*P[1][11] + PS174*P[0][11] + PS175*P[2][11] - PS176*P[3][11] + PS43*P[11][13] + P[4][11]; -nextP[5][11] = PS190*P[11][15] - PS193*P[11][13] + PS201*P[2][11] - PS202*P[0][11] + PS203*P[3][11] - PS204*P[1][11] + PS75*P[11][14] + P[5][11]; -nextP[6][11] = -PS197*P[11][14] + PS199*P[11][13] - PS214*P[2][11] + PS215*P[3][11] + PS216*P[0][11] + PS217*P[1][11] + PS87*P[11][15] + P[6][11]; -nextP[7][11] = P[4][11]*dt + P[7][11]; -nextP[8][11] = P[5][11]*dt + P[8][11]; -nextP[9][11] = P[6][11]*dt + P[9][11]; -nextP[10][11] = P[10][11]; -nextP[11][11] = P[11][11]; -nextP[0][12] = PS20; -nextP[1][12] = PS107; -nextP[2][12] = PS127; -nextP[3][12] = PS154; -nextP[4][12] = -PS171*P[12][15] + PS172*P[12][14] + PS173*P[1][12] + PS174*P[0][12] + PS175*P[2][12] - PS176*P[3][12] + PS43*P[12][13] + P[4][12]; -nextP[5][12] = PS190*P[12][15] - PS193*P[12][13] + PS201*P[2][12] - PS202*P[0][12] + PS203*P[3][12] - PS204*P[1][12] + PS75*P[12][14] + P[5][12]; -nextP[6][12] = -PS197*P[12][14] + PS199*P[12][13] - PS214*P[2][12] + PS215*P[3][12] + PS216*P[0][12] + PS217*P[1][12] + PS87*P[12][15] + P[6][12]; -nextP[7][12] = P[4][12]*dt + P[7][12]; -nextP[8][12] = P[5][12]*dt + P[8][12]; -nextP[9][12] = P[6][12]*dt + P[9][12]; -nextP[10][12] = P[10][12]; -nextP[11][12] = P[11][12]; -nextP[12][12] = P[12][12]; -nextP[0][13] = PS44; -nextP[1][13] = PS113; -nextP[2][13] = PS138; -nextP[3][13] = PS158; -nextP[4][13] = PS177; -nextP[5][13] = PS206; -nextP[6][13] = PS221; -nextP[7][13] = P[4][13]*dt + P[7][13]; -nextP[8][13] = P[5][13]*dt + P[8][13]; -nextP[9][13] = P[6][13]*dt + P[9][13]; -nextP[10][13] = P[10][13]; -nextP[11][13] = P[11][13]; -nextP[12][13] = P[12][13]; -nextP[13][13] = P[13][13]; -nextP[0][14] = PS57; -nextP[1][14] = PS117; -nextP[2][14] = PS142; -nextP[3][14] = PS162; -nextP[4][14] = PS180; -nextP[5][14] = PS205; -nextP[6][14] = PS220; -nextP[7][14] = P[4][14]*dt + P[7][14]; -nextP[8][14] = P[5][14]*dt + P[8][14]; -nextP[9][14] = P[6][14]*dt + P[9][14]; -nextP[10][14] = P[10][14]; -nextP[11][14] = P[11][14]; -nextP[12][14] = P[12][14]; -nextP[13][14] = P[13][14]; -nextP[14][14] = P[14][14]; -nextP[0][15] = PS46; -nextP[1][15] = PS114; -nextP[2][15] = PS139; -nextP[3][15] = PS159; -nextP[4][15] = PS178; -nextP[5][15] = PS209; -nextP[6][15] = PS219; -nextP[7][15] = P[4][15]*dt + P[7][15]; -nextP[8][15] = P[5][15]*dt + P[8][15]; -nextP[9][15] = P[6][15]*dt + P[9][15]; -nextP[10][15] = P[10][15]; -nextP[11][15] = P[11][15]; -nextP[12][15] = P[12][15]; -nextP[13][15] = P[13][15]; -nextP[14][15] = P[14][15]; -nextP[15][15] = P[15][15]; -nextP[0][16] = -PS11*P[1][16] - PS12*P[2][16] - PS13*P[3][16] + PS6*P[10][16] + PS7*P[11][16] + PS9*P[12][16] + P[0][16]; -nextP[1][16] = PS11*P[0][16] - PS12*P[3][16] + PS13*P[2][16] - PS34*P[10][16] - PS7*P[12][16] + PS9*P[11][16] + P[1][16]; -nextP[2][16] = PS11*P[3][16] + PS12*P[0][16] - PS13*P[1][16] - PS34*P[11][16] + PS6*P[12][16] - PS9*P[10][16] + P[2][16]; -nextP[3][16] = -PS11*P[2][16] + PS12*P[1][16] + PS13*P[0][16] - PS34*P[12][16] - PS6*P[11][16] + PS7*P[10][16] + P[3][16]; -nextP[4][16] = -PS171*P[15][16] + PS172*P[14][16] + PS173*P[1][16] + PS174*P[0][16] + PS175*P[2][16] - PS176*P[3][16] + PS43*P[13][16] + P[4][16]; -nextP[5][16] = PS190*P[15][16] - PS193*P[13][16] + PS201*P[2][16] - PS202*P[0][16] + PS203*P[3][16] - PS204*P[1][16] + PS75*P[14][16] + P[5][16]; -nextP[6][16] = -PS197*P[14][16] + PS199*P[13][16] - PS214*P[2][16] + PS215*P[3][16] + PS216*P[0][16] + PS217*P[1][16] + PS87*P[15][16] + P[6][16]; -nextP[7][16] = P[4][16]*dt + P[7][16]; -nextP[8][16] = P[5][16]*dt + P[8][16]; -nextP[9][16] = P[6][16]*dt + P[9][16]; -nextP[10][16] = P[10][16]; -nextP[11][16] = P[11][16]; -nextP[12][16] = P[12][16]; -nextP[13][16] = P[13][16]; -nextP[14][16] = P[14][16]; -nextP[15][16] = P[15][16]; -nextP[16][16] = P[16][16]; -nextP[0][17] = -PS11*P[1][17] - PS12*P[2][17] - PS13*P[3][17] + PS6*P[10][17] + PS7*P[11][17] + PS9*P[12][17] + P[0][17]; -nextP[1][17] = PS11*P[0][17] - PS12*P[3][17] + PS13*P[2][17] - PS34*P[10][17] - PS7*P[12][17] + PS9*P[11][17] + P[1][17]; -nextP[2][17] = PS11*P[3][17] + PS12*P[0][17] - PS13*P[1][17] - PS34*P[11][17] + PS6*P[12][17] - PS9*P[10][17] + P[2][17]; -nextP[3][17] = -PS11*P[2][17] + PS12*P[1][17] + PS13*P[0][17] - PS34*P[12][17] - PS6*P[11][17] + PS7*P[10][17] + P[3][17]; -nextP[4][17] = -PS171*P[15][17] + PS172*P[14][17] + PS173*P[1][17] + PS174*P[0][17] + PS175*P[2][17] - PS176*P[3][17] + PS43*P[13][17] + P[4][17]; -nextP[5][17] = PS190*P[15][17] - PS193*P[13][17] + PS201*P[2][17] - PS202*P[0][17] + PS203*P[3][17] - PS204*P[1][17] + PS75*P[14][17] + P[5][17]; -nextP[6][17] = -PS197*P[14][17] + PS199*P[13][17] - PS214*P[2][17] + PS215*P[3][17] + PS216*P[0][17] + PS217*P[1][17] + PS87*P[15][17] + P[6][17]; -nextP[7][17] = P[4][17]*dt + P[7][17]; -nextP[8][17] = P[5][17]*dt + P[8][17]; -nextP[9][17] = P[6][17]*dt + P[9][17]; -nextP[10][17] = P[10][17]; -nextP[11][17] = P[11][17]; -nextP[12][17] = P[12][17]; -nextP[13][17] = P[13][17]; -nextP[14][17] = P[14][17]; -nextP[15][17] = P[15][17]; -nextP[16][17] = P[16][17]; -nextP[17][17] = P[17][17]; -nextP[0][18] = -PS11*P[1][18] - PS12*P[2][18] - PS13*P[3][18] + PS6*P[10][18] + PS7*P[11][18] + PS9*P[12][18] + P[0][18]; -nextP[1][18] = PS11*P[0][18] - PS12*P[3][18] + PS13*P[2][18] - PS34*P[10][18] - PS7*P[12][18] + PS9*P[11][18] + P[1][18]; -nextP[2][18] = PS11*P[3][18] + PS12*P[0][18] - PS13*P[1][18] - PS34*P[11][18] + PS6*P[12][18] - PS9*P[10][18] + P[2][18]; -nextP[3][18] = -PS11*P[2][18] + PS12*P[1][18] + PS13*P[0][18] - PS34*P[12][18] - PS6*P[11][18] + PS7*P[10][18] + P[3][18]; -nextP[4][18] = -PS171*P[15][18] + PS172*P[14][18] + PS173*P[1][18] + PS174*P[0][18] + PS175*P[2][18] - PS176*P[3][18] + PS43*P[13][18] + P[4][18]; -nextP[5][18] = PS190*P[15][18] - PS193*P[13][18] + PS201*P[2][18] - PS202*P[0][18] + PS203*P[3][18] - PS204*P[1][18] + PS75*P[14][18] + P[5][18]; -nextP[6][18] = -PS197*P[14][18] + PS199*P[13][18] - PS214*P[2][18] + PS215*P[3][18] + PS216*P[0][18] + PS217*P[1][18] + PS87*P[15][18] + P[6][18]; -nextP[7][18] = P[4][18]*dt + P[7][18]; -nextP[8][18] = P[5][18]*dt + P[8][18]; -nextP[9][18] = P[6][18]*dt + P[9][18]; -nextP[10][18] = P[10][18]; -nextP[11][18] = P[11][18]; -nextP[12][18] = P[12][18]; -nextP[13][18] = P[13][18]; -nextP[14][18] = P[14][18]; -nextP[15][18] = P[15][18]; -nextP[16][18] = P[16][18]; -nextP[17][18] = P[17][18]; -nextP[18][18] = P[18][18]; -nextP[0][19] = -PS11*P[1][19] - PS12*P[2][19] - PS13*P[3][19] + PS6*P[10][19] + PS7*P[11][19] + PS9*P[12][19] + P[0][19]; -nextP[1][19] = PS11*P[0][19] - PS12*P[3][19] + PS13*P[2][19] - PS34*P[10][19] - PS7*P[12][19] + PS9*P[11][19] + P[1][19]; -nextP[2][19] = PS11*P[3][19] + PS12*P[0][19] - PS13*P[1][19] - PS34*P[11][19] + PS6*P[12][19] - PS9*P[10][19] + P[2][19]; -nextP[3][19] = -PS11*P[2][19] + PS12*P[1][19] + PS13*P[0][19] - PS34*P[12][19] - PS6*P[11][19] + PS7*P[10][19] + P[3][19]; -nextP[4][19] = -PS171*P[15][19] + PS172*P[14][19] + PS173*P[1][19] + PS174*P[0][19] + PS175*P[2][19] - PS176*P[3][19] + PS43*P[13][19] + P[4][19]; -nextP[5][19] = PS190*P[15][19] - PS193*P[13][19] + PS201*P[2][19] - PS202*P[0][19] + PS203*P[3][19] - PS204*P[1][19] + PS75*P[14][19] + P[5][19]; -nextP[6][19] = -PS197*P[14][19] + PS199*P[13][19] - PS214*P[2][19] + PS215*P[3][19] + PS216*P[0][19] + PS217*P[1][19] + PS87*P[15][19] + P[6][19]; -nextP[7][19] = P[4][19]*dt + P[7][19]; -nextP[8][19] = P[5][19]*dt + P[8][19]; -nextP[9][19] = P[6][19]*dt + P[9][19]; -nextP[10][19] = P[10][19]; -nextP[11][19] = P[11][19]; -nextP[12][19] = P[12][19]; -nextP[13][19] = P[13][19]; -nextP[14][19] = P[14][19]; -nextP[15][19] = P[15][19]; -nextP[16][19] = P[16][19]; -nextP[17][19] = P[17][19]; -nextP[18][19] = P[18][19]; -nextP[19][19] = P[19][19]; -nextP[0][20] = -PS11*P[1][20] - PS12*P[2][20] - PS13*P[3][20] + PS6*P[10][20] + PS7*P[11][20] + PS9*P[12][20] + P[0][20]; -nextP[1][20] = PS11*P[0][20] - PS12*P[3][20] + PS13*P[2][20] - PS34*P[10][20] - PS7*P[12][20] + PS9*P[11][20] + P[1][20]; -nextP[2][20] = PS11*P[3][20] + PS12*P[0][20] - PS13*P[1][20] - PS34*P[11][20] + PS6*P[12][20] - PS9*P[10][20] + P[2][20]; -nextP[3][20] = -PS11*P[2][20] + PS12*P[1][20] + PS13*P[0][20] - PS34*P[12][20] - PS6*P[11][20] + PS7*P[10][20] + P[3][20]; -nextP[4][20] = -PS171*P[15][20] + PS172*P[14][20] + PS173*P[1][20] + PS174*P[0][20] + PS175*P[2][20] - PS176*P[3][20] + PS43*P[13][20] + P[4][20]; -nextP[5][20] = PS190*P[15][20] - PS193*P[13][20] + PS201*P[2][20] - PS202*P[0][20] + PS203*P[3][20] - PS204*P[1][20] + PS75*P[14][20] + P[5][20]; -nextP[6][20] = -PS197*P[14][20] + PS199*P[13][20] - PS214*P[2][20] + PS215*P[3][20] + PS216*P[0][20] + PS217*P[1][20] + PS87*P[15][20] + P[6][20]; -nextP[7][20] = P[4][20]*dt + P[7][20]; -nextP[8][20] = P[5][20]*dt + P[8][20]; -nextP[9][20] = P[6][20]*dt + P[9][20]; -nextP[10][20] = P[10][20]; -nextP[11][20] = P[11][20]; -nextP[12][20] = P[12][20]; -nextP[13][20] = P[13][20]; -nextP[14][20] = P[14][20]; -nextP[15][20] = P[15][20]; -nextP[16][20] = P[16][20]; -nextP[17][20] = P[17][20]; -nextP[18][20] = P[18][20]; -nextP[19][20] = P[19][20]; -nextP[20][20] = P[20][20]; -nextP[0][21] = -PS11*P[1][21] - PS12*P[2][21] - PS13*P[3][21] + PS6*P[10][21] + PS7*P[11][21] + PS9*P[12][21] + P[0][21]; -nextP[1][21] = PS11*P[0][21] - PS12*P[3][21] + PS13*P[2][21] - PS34*P[10][21] - PS7*P[12][21] + PS9*P[11][21] + P[1][21]; -nextP[2][21] = PS11*P[3][21] + PS12*P[0][21] - PS13*P[1][21] - PS34*P[11][21] + PS6*P[12][21] - PS9*P[10][21] + P[2][21]; -nextP[3][21] = -PS11*P[2][21] + PS12*P[1][21] + PS13*P[0][21] - PS34*P[12][21] - PS6*P[11][21] + PS7*P[10][21] + P[3][21]; -nextP[4][21] = -PS171*P[15][21] + PS172*P[14][21] + PS173*P[1][21] + PS174*P[0][21] + PS175*P[2][21] - PS176*P[3][21] + PS43*P[13][21] + P[4][21]; -nextP[5][21] = PS190*P[15][21] - PS193*P[13][21] + PS201*P[2][21] - PS202*P[0][21] + PS203*P[3][21] - PS204*P[1][21] + PS75*P[14][21] + P[5][21]; -nextP[6][21] = -PS197*P[14][21] + PS199*P[13][21] - PS214*P[2][21] + PS215*P[3][21] + PS216*P[0][21] + PS217*P[1][21] + PS87*P[15][21] + P[6][21]; -nextP[7][21] = P[4][21]*dt + P[7][21]; -nextP[8][21] = P[5][21]*dt + P[8][21]; -nextP[9][21] = P[6][21]*dt + P[9][21]; -nextP[10][21] = P[10][21]; -nextP[11][21] = P[11][21]; -nextP[12][21] = P[12][21]; -nextP[13][21] = P[13][21]; -nextP[14][21] = P[14][21]; -nextP[15][21] = P[15][21]; -nextP[16][21] = P[16][21]; -nextP[17][21] = P[17][21]; -nextP[18][21] = P[18][21]; -nextP[19][21] = P[19][21]; -nextP[20][21] = P[20][21]; -nextP[21][21] = P[21][21]; -nextP[0][22] = -PS11*P[1][22] - PS12*P[2][22] - PS13*P[3][22] + PS6*P[10][22] + PS7*P[11][22] + PS9*P[12][22] + P[0][22]; -nextP[1][22] = PS11*P[0][22] - PS12*P[3][22] + PS13*P[2][22] - PS34*P[10][22] - PS7*P[12][22] + PS9*P[11][22] + P[1][22]; -nextP[2][22] = PS11*P[3][22] + PS12*P[0][22] - PS13*P[1][22] - PS34*P[11][22] + PS6*P[12][22] - PS9*P[10][22] + P[2][22]; -nextP[3][22] = -PS11*P[2][22] + PS12*P[1][22] + PS13*P[0][22] - PS34*P[12][22] - PS6*P[11][22] + PS7*P[10][22] + P[3][22]; -nextP[4][22] = -PS171*P[15][22] + PS172*P[14][22] + PS173*P[1][22] + PS174*P[0][22] + PS175*P[2][22] - PS176*P[3][22] + PS43*P[13][22] + P[4][22]; -nextP[5][22] = PS190*P[15][22] - PS193*P[13][22] + PS201*P[2][22] - PS202*P[0][22] + PS203*P[3][22] - PS204*P[1][22] + PS75*P[14][22] + P[5][22]; -nextP[6][22] = -PS197*P[14][22] + PS199*P[13][22] - PS214*P[2][22] + PS215*P[3][22] + PS216*P[0][22] + PS217*P[1][22] + PS87*P[15][22] + P[6][22]; -nextP[7][22] = P[4][22]*dt + P[7][22]; -nextP[8][22] = P[5][22]*dt + P[8][22]; -nextP[9][22] = P[6][22]*dt + P[9][22]; -nextP[10][22] = P[10][22]; -nextP[11][22] = P[11][22]; -nextP[12][22] = P[12][22]; -nextP[13][22] = P[13][22]; -nextP[14][22] = P[14][22]; -nextP[15][22] = P[15][22]; -nextP[16][22] = P[16][22]; -nextP[17][22] = P[17][22]; -nextP[18][22] = P[18][22]; -nextP[19][22] = P[19][22]; -nextP[20][22] = P[20][22]; -nextP[21][22] = P[21][22]; -nextP[22][22] = P[22][22]; -nextP[0][23] = -PS11*P[1][23] - PS12*P[2][23] - PS13*P[3][23] + PS6*P[10][23] + PS7*P[11][23] + PS9*P[12][23] + P[0][23]; -nextP[1][23] = PS11*P[0][23] - PS12*P[3][23] + PS13*P[2][23] - PS34*P[10][23] - PS7*P[12][23] + PS9*P[11][23] + P[1][23]; -nextP[2][23] = PS11*P[3][23] + PS12*P[0][23] - PS13*P[1][23] - PS34*P[11][23] + PS6*P[12][23] - PS9*P[10][23] + P[2][23]; -nextP[3][23] = -PS11*P[2][23] + PS12*P[1][23] + PS13*P[0][23] - PS34*P[12][23] - PS6*P[11][23] + PS7*P[10][23] + P[3][23]; -nextP[4][23] = -PS171*P[15][23] + PS172*P[14][23] + PS173*P[1][23] + PS174*P[0][23] + PS175*P[2][23] - PS176*P[3][23] + PS43*P[13][23] + P[4][23]; -nextP[5][23] = PS190*P[15][23] - PS193*P[13][23] + PS201*P[2][23] - PS202*P[0][23] + PS203*P[3][23] - PS204*P[1][23] + PS75*P[14][23] + P[5][23]; -nextP[6][23] = -PS197*P[14][23] + PS199*P[13][23] - PS214*P[2][23] + PS215*P[3][23] + PS216*P[0][23] + PS217*P[1][23] + PS87*P[15][23] + P[6][23]; -nextP[7][23] = P[4][23]*dt + P[7][23]; -nextP[8][23] = P[5][23]*dt + P[8][23]; -nextP[9][23] = P[6][23]*dt + P[9][23]; -nextP[10][23] = P[10][23]; -nextP[11][23] = P[11][23]; -nextP[12][23] = P[12][23]; -nextP[13][23] = P[13][23]; -nextP[14][23] = P[14][23]; -nextP[15][23] = P[15][23]; -nextP[16][23] = P[16][23]; -nextP[17][23] = P[17][23]; -nextP[18][23] = P[18][23]; -nextP[19][23] = P[19][23]; -nextP[20][23] = P[20][23]; -nextP[21][23] = P[21][23]; -nextP[22][23] = P[22][23]; -nextP[23][23] = P[23][23]; - - diff --git a/libraries/AP_NavEKF3/derivation/generated/yaw_generated.cpp b/libraries/AP_NavEKF3/derivation/generated/yaw_generated.cpp deleted file mode 100644 index dabbccac3330b4..00000000000000 --- a/libraries/AP_NavEKF3/derivation/generated/yaw_generated.cpp +++ /dev/null @@ -1,156 +0,0 @@ -// calculate 321 yaw observation matrix - option A -const ftype SA0 = 2*q3; -const ftype SA1 = 2*q2; -const ftype SA2 = SA0*q0 + SA1*q1; -const ftype SA3 = sq(q0) + sq(q1) - sq(q2) - sq(q3); -const ftype SA4 = 1.0/sq(SA3); -const ftype SA5 = 1.0F/(sq(SA2)*SA4 + 1); -const ftype SA6 = 1.0F/SA3; -const ftype SA7 = SA2*SA4; -const ftype SA8 = 2*SA7; -const ftype SA9 = 2*SA6; - - -H_YAW[0] = SA5*(SA0*SA6 - SA8*q0); -H_YAW[1] = SA5*(SA1*SA6 - SA8*q1); -H_YAW[2] = SA5*(SA1*SA7 + SA9*q1); -H_YAW[3] = SA5*(SA0*SA7 + SA9*q0); -H_YAW[4] = 0; -H_YAW[5] = 0; -H_YAW[6] = 0; -H_YAW[7] = 0; -H_YAW[8] = 0; -H_YAW[9] = 0; -H_YAW[10] = 0; -H_YAW[11] = 0; -H_YAW[12] = 0; -H_YAW[13] = 0; -H_YAW[14] = 0; -H_YAW[15] = 0; -H_YAW[16] = 0; -H_YAW[17] = 0; -H_YAW[18] = 0; -H_YAW[19] = 0; -H_YAW[20] = 0; -H_YAW[21] = 0; -H_YAW[22] = 0; -H_YAW[23] = 0; - - -// calculate 321 yaw observation matrix - option B -const ftype SB0 = 2*q0; -const ftype SB1 = 2*q1; -const ftype SB2 = SB0*q3 + SB1*q2; -const ftype SB3 = 1.0/sq(SB2); -const ftype SB4 = sq(q0) + sq(q1) - sq(q2) - sq(q3); -const ftype SB5 = 1.0F/(SB3*sq(SB4) + 1); -const ftype SB6 = 1.0F/SB2; -const ftype SB7 = SB3*SB4; -const ftype SB8 = 2*SB7; -const ftype SB9 = 2*SB6; - - -H_YAW[0] = -SB5*(SB0*SB6 - SB8*q3); -H_YAW[1] = -SB5*(SB1*SB6 - SB8*q2); -H_YAW[2] = -SB5*(-SB1*SB7 - SB9*q2); -H_YAW[3] = -SB5*(-SB0*SB7 - SB9*q3); -H_YAW[4] = 0; -H_YAW[5] = 0; -H_YAW[6] = 0; -H_YAW[7] = 0; -H_YAW[8] = 0; -H_YAW[9] = 0; -H_YAW[10] = 0; -H_YAW[11] = 0; -H_YAW[12] = 0; -H_YAW[13] = 0; -H_YAW[14] = 0; -H_YAW[15] = 0; -H_YAW[16] = 0; -H_YAW[17] = 0; -H_YAW[18] = 0; -H_YAW[19] = 0; -H_YAW[20] = 0; -H_YAW[21] = 0; -H_YAW[22] = 0; -H_YAW[23] = 0; - - -// calculate 312 yaw observation matrix - option A -const ftype SA0 = 2*q3; -const ftype SA1 = 2*q2; -const ftype SA2 = SA0*q0 - SA1*q1; -const ftype SA3 = sq(q0) - sq(q1) + sq(q2) - sq(q3); -const ftype SA4 = 1.0/sq(SA3); -const ftype SA5 = 1.0F/(sq(SA2)*SA4 + 1); -const ftype SA6 = 1.0F/SA3; -const ftype SA7 = SA2*SA4; -const ftype SA8 = 2*SA7; -const ftype SA9 = 2*SA6; - - -H_YAW[0] = SA5*(SA0*SA6 - SA8*q0); -H_YAW[1] = SA5*(-SA1*SA6 + SA8*q1); -H_YAW[2] = SA5*(-SA1*SA7 - SA9*q1); -H_YAW[3] = SA5*(SA0*SA7 + SA9*q0); -H_YAW[4] = 0; -H_YAW[5] = 0; -H_YAW[6] = 0; -H_YAW[7] = 0; -H_YAW[8] = 0; -H_YAW[9] = 0; -H_YAW[10] = 0; -H_YAW[11] = 0; -H_YAW[12] = 0; -H_YAW[13] = 0; -H_YAW[14] = 0; -H_YAW[15] = 0; -H_YAW[16] = 0; -H_YAW[17] = 0; -H_YAW[18] = 0; -H_YAW[19] = 0; -H_YAW[20] = 0; -H_YAW[21] = 0; -H_YAW[22] = 0; -H_YAW[23] = 0; - - -// calculate 312 yaw observation matrix - option B -const ftype SB0 = 2*q0; -const ftype SB1 = 2*q1; -const ftype SB2 = -SB0*q3 + SB1*q2; -const ftype SB3 = 1.0/sq(SB2); -const ftype SB4 = -sq(q0) + sq(q1) - sq(q2) + sq(q3); -const ftype SB5 = 1.0F/(SB3*sq(SB4) + 1); -const ftype SB6 = 1.0F/SB2; -const ftype SB7 = SB3*SB4; -const ftype SB8 = 2*SB7; -const ftype SB9 = 2*SB6; - - -H_YAW[0] = -SB5*(-SB0*SB6 + SB8*q3); -H_YAW[1] = -SB5*(SB1*SB6 - SB8*q2); -H_YAW[2] = -SB5*(-SB1*SB7 - SB9*q2); -H_YAW[3] = -SB5*(SB0*SB7 + SB9*q3); -H_YAW[4] = 0; -H_YAW[5] = 0; -H_YAW[6] = 0; -H_YAW[7] = 0; -H_YAW[8] = 0; -H_YAW[9] = 0; -H_YAW[10] = 0; -H_YAW[11] = 0; -H_YAW[12] = 0; -H_YAW[13] = 0; -H_YAW[14] = 0; -H_YAW[15] = 0; -H_YAW[16] = 0; -H_YAW[17] = 0; -H_YAW[18] = 0; -H_YAW[19] = 0; -H_YAW[20] = 0; -H_YAW[21] = 0; -H_YAW[22] = 0; -H_YAW[23] = 0; - - diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 19016f3f7044e1..12b0fb1ae3f55b 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -9,6 +9,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -76,7 +77,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Param: TESTS // @DisplayName: Test enable flags // @Description: Enable/Disable networking tests - // @Bitmask: 0:UDP echo test,1:TCP echo test, 2:TCP discard test + // @Bitmask: 0:UDP echo test,1:TCP echo test, 2:TCP discard test, 3:TCP reflect test // @RebootRequired: True // @User: Advanced AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0), @@ -89,7 +90,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Param: OPTIONS // @DisplayName: Networking options // @Description: Networking options - // @Bitmask: 0:EnablePPP Ethernet gateway + // @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast gateway, 2:Enable CAN2 multicast gateway // @RebootRequired: True // @User: Advanced AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0), @@ -148,26 +149,26 @@ void AP_Networking::init() /* when we are a PPP/Ethernet gateway we bring up the ethernet first */ - backend = new AP_Networking_ChibiOS(*this); - backend_PPP = new AP_Networking_PPP(*this); + backend = NEW_NOTHROW AP_Networking_ChibiOS(*this); + backend_PPP = NEW_NOTHROW AP_Networking_PPP(*this); } #endif #if AP_NETWORKING_BACKEND_PPP if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) { - backend = new AP_Networking_PPP(*this); + backend = NEW_NOTHROW AP_Networking_PPP(*this); } #endif #if AP_NETWORKING_BACKEND_CHIBIOS if (backend == nullptr) { - backend = new AP_Networking_ChibiOS(*this); + backend = NEW_NOTHROW AP_Networking_ChibiOS(*this); } #endif #if AP_NETWORKING_BACKEND_SITL if (backend == nullptr) { - backend = new AP_Networking_SITL(*this); + backend = NEW_NOTHROW AP_Networking_SITL(*this); } #endif @@ -198,8 +199,24 @@ void AP_Networking::init() start_tests(); #endif +#if AP_NETWORKING_CAN_MCAST_ENABLED && !defined(HAL_BOOTLOADER_BUILD) + if (option_is_set(OPTION::CAN1_MCAST_GATEWAY) || option_is_set(OPTION::CAN2_MCAST_GATEWAY)) { + // get mask of enabled buses + uint8_t bus_mask = 0; + if (option_is_set(OPTION::CAN1_MCAST_GATEWAY)) { + bus_mask |= (1U<<0); + } + if (option_is_set(OPTION::CAN2_MCAST_GATEWAY)) { + bus_mask |= (1U<<1); + } + mcast_server.start(bus_mask); + } +#endif + +#if AP_NETWORKING_REGISTER_PORT_ENABLED // init network mapped serialmanager ports ports_init(); +#endif } /* diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 128e6c2c29398e..5c7e8ebca18d62 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -8,6 +8,7 @@ #include "AP_Networking_address.h" #include "AP_Networking_Backend.h" +#include "AP_Networking_CAN.h" #include #include @@ -155,6 +156,10 @@ class AP_Networking enum class OPTION { PPP_ETHERNET_GATEWAY=(1U<<0), +#if AP_NETWORKING_CAN_MCAST_ENABLED + CAN1_MCAST_GATEWAY=(1U<<1), + CAN2_MCAST_GATEWAY=(1U<<2), +#endif }; bool option_is_set(OPTION option) const { return (param.options.get() & int32_t(option)) != 0; @@ -266,9 +271,11 @@ class AP_Networking uint32_t last_size_rx; bool packetise; bool connected; + uint32_t last_udp_connect_address; + uint16_t last_udp_connect_port; bool have_received; bool close_on_recv_error; - + uint32_t last_udp_srv_recv_time_ms; HAL_Semaphore sem; }; #endif // AP_NETWORKING_REGISTER_PORT_ENABLED @@ -281,11 +288,15 @@ class AP_Networking TEST_UDP_CLIENT = (1U<<0), TEST_TCP_CLIENT = (1U<<1), TEST_TCP_DISCARD = (1U<<2), + TEST_TCP_REFLECT = (1U<<3), + TEST_CONNECTOR_LOOPBACK = (1U<<4), }; void start_tests(void); void test_UDP_client(void); void test_TCP_client(void); void test_TCP_discard(void); + void test_TCP_reflect(void); + void test_connector_loopback(void); #endif // AP_NETWORKING_TESTS_ENABLED #if AP_NETWORKING_REGISTER_PORT_ENABLED @@ -293,6 +304,10 @@ class AP_Networking Port ports[AP_NETWORKING_NUM_PORTS]; #endif +#if AP_NETWORKING_CAN_MCAST_ENABLED + AP_Networking_CAN mcast_server; +#endif + // support for sendfile() struct SendFile { SocketAPM *sock; diff --git a/libraries/AP_Networking/AP_Networking_CAN.cpp b/libraries/AP_Networking/AP_Networking_CAN.cpp new file mode 100644 index 00000000000000..875fece574b334 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_CAN.cpp @@ -0,0 +1,227 @@ +/* + CAN UDP multicast server + */ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_CAN_MCAST_ENABLED + +#include "AP_Networking.h" + +#include +#include +#include +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include "hal.h" +#include +#include +#endif + +#define MCAST_ADDRESS_BASE "239.65.82.0" +#define MCAST_PORT 57732U +#define MCAST_MAGIC 0x2934U +#define MCAST_FLAG_CANFD 0x0001 +#define MCAST_MAX_PKT_LEN 74 // 64 byte data + 10 byte header + +struct PACKED mcast_pkt { + uint16_t magic; + uint16_t crc; + uint16_t flags; + uint32_t message_id; + uint8_t data[MCAST_MAX_PKT_LEN-10]; +}; + +#define MCAST_HDR_LENGTH offsetof(mcast_pkt, data) + +extern const AP_HAL::HAL& hal; + +#ifdef HAL_BOOTLOADER_BUILD +void AP_Networking_CAN::mcast_trampoline(void *ctx) +{ + auto *mcast = (AP_Networking_CAN *)ctx; + mcast->mcast_server(); +} +extern ChibiOS::CANIface can_iface[HAL_NUM_CAN_IFACES]; +extern void thread_sleep_us(uint32_t us); +#endif // HAL_BOOTLOADER_BUILD + +/* + get CAN interface for a bus + */ +AP_HAL::CANIface *AP_Networking_CAN::get_caniface(uint8_t bus) const +{ +#ifdef HAL_BOOTLOADER_BUILD + return &can_iface[bus]; +#else + return hal.can[bus]; +#endif +} + +/* + start the CAN multicast server + */ +void AP_Networking_CAN::start(const uint8_t _bus_mask) +{ + const uint32_t stack_size = 8192; + bus_mask = _bus_mask; + +#ifdef HAL_BOOTLOADER_BUILD + thread_create_alloc(THD_WORKING_AREA_SIZE(stack_size), + "CAN_MCAST", + 60, + mcast_trampoline, + this); +#else + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::mcast_server, void), + "CAN_MCAST", + stack_size, AP_HAL::Scheduler::PRIORITY_CAN, -1); +#endif +} + +/* + main thread for CAN multicast server + */ +void AP_Networking_CAN::mcast_server(void) +{ +#ifndef HAL_BOOTLOADER_BUILD + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } +#endif + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CAN_MCAST: starting"); + + ObjectBuffer *frame_buffers[HAL_NUM_CAN_IFACES] {}; + + for (uint8_t bus=0; busconnect(address, MCAST_PORT)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to connect", unsigned(bus)); + goto de_allocate; + } + + if (!cbus->register_frame_callback( + FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), + callback_id)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to register", unsigned(bus)); + goto de_allocate; + } + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + // tell the ethernet interface that we want to receive all + // multicast packets + ETH->MACPFR |= ETH_MACPFR_PM; +#endif + + frame_buffers[bus] = NEW_NOTHROW ObjectBuffer(buffer_size); + if (frame_buffers[bus] == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to allocate buffers", unsigned(bus)); + goto de_allocate; + } + continue; + + de_allocate: + delete mcast_sockets[bus]; + mcast_sockets[bus] = nullptr; + } + + + // main loop + while (true) { + const uint32_t delay_us = 100; // limit to 10k packets/s +#ifndef HAL_BOOTLOADER_BUILD + hal.scheduler->delay_microseconds(delay_us); +#else + thread_sleep_us(delay_us); +#endif + for (uint8_t bus=0; busrecv((void*)&pkt, sizeof(pkt), 0); + if (ret > MCAST_HDR_LENGTH && ret <= sizeof(pkt)) { + const uint8_t data_len = ret - MCAST_HDR_LENGTH; + bool is_canfd = false; +#if HAL_CANFD_SUPPORTED + is_canfd = (pkt.flags & MCAST_FLAG_CANFD) != 0; +#endif + if (pkt.magic != MCAST_MAGIC) { + continue; + } + const auto crc = crc16_ccitt((uint8_t*)&pkt.flags, ret - offsetof(mcast_pkt,flags), 0xFFFFU); + if (pkt.crc != crc) { + continue; + } + + // push into queue + frame_buffers[bus]->push(AP_HAL::CANFrame(pkt.message_id, pkt.data, data_len, is_canfd)); + } + + /* + send pending frames + */ + AP_HAL::CANFrame frame; + const uint16_t timeout_us = 2000; + + while (frame_buffers[bus]->peek(frame)) { + auto retcode = get_caniface(bus)->send(frame, + AP_HAL::micros64() + timeout_us, + AP_HAL::CANIface::IsMAVCAN); + if (retcode == 0) { + break; + } + // we either sent it or there was an error, either way we discard the frame + frame_buffers[bus]->pop(); + } + } + } +} + +/* + handler for CAN frames from the registered callback, sending frames + out as multicast UDP + */ +void AP_Networking_CAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) +{ + if (bus >= HAL_NUM_CAN_IFACES || mcast_sockets[bus] == nullptr) { + return; + } + + struct mcast_pkt pkt {}; + pkt.magic = MCAST_MAGIC; + pkt.flags = 0; +#if HAL_CANFD_SUPPORTED + if (frame.isCanFDFrame()) { + pkt.flags |= MCAST_FLAG_CANFD; + } +#endif + pkt.message_id = frame.id; + + const uint8_t data_length = AP_HAL::CANFrame::dlcToDataLength(frame.dlc); + + memcpy(pkt.data, frame.data, data_length); + // 6 is the size of the flags and message_id, ie header data after crc + pkt.crc = crc16_ccitt((uint8_t*)&pkt.flags, data_length+6, 0xFFFFU); + + mcast_sockets[bus]->send((void*)&pkt, data_length+MCAST_HDR_LENGTH); +} + +#endif // AP_NETWORKING_ENABLED && AP_NETWORKING_CAN_MCAST_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_CAN.h b/libraries/AP_Networking/AP_Networking_CAN.h new file mode 100644 index 00000000000000..3e968e4fdb4422 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_CAN.h @@ -0,0 +1,23 @@ +#pragma once + +#include "AP_Networking.h" +#include + +class AP_Networking_CAN { +public: + void start(const uint8_t bus_mask); + +private: + void mcast_server(void); + void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame); + SocketAPM *mcast_sockets[HAL_NUM_CAN_IFACES]; + + uint8_t bus_mask; + + AP_HAL::CANIface *get_caniface(uint8_t) const; + +#ifdef HAL_BOOTLOADER_BUILD + static void mcast_trampoline(void *ctx); +#endif +}; + diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 889a8526be7523..4248119a2d8adf 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -127,7 +127,7 @@ bool AP_Networking_ChibiOS::init() } #endif - thisif = new netif; + thisif = NEW_NOTHROW netif; if (thisif == nullptr) { return false; } diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 5b66134957849e..a29aed082c40aa 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -2,7 +2,7 @@ #include #if defined(AP_NETWORKING_BACKEND_PPP) && !defined(AP_NETWORKING_ENABLED) -// allow --enable-ppp to enable networking +// allow --enable-PPP to enable networking #define AP_NETWORKING_ENABLED AP_NETWORKING_BACKEND_PPP #endif @@ -103,6 +103,10 @@ #define AP_NETWORKING_TESTS_ENABLED 0 #endif +#ifndef AP_NETWORKING_CAN_MCAST_ENABLED +#define AP_NETWORKING_CAN_MCAST_ENABLED 0 +#endif + #if AP_NETWORKING_TESTS_ENABLED #ifndef AP_NETWORKING_TEST_IP #define AP_NETWORKING_TEST_IP "192.168.13.2" diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index 18f16f0bdbb56e..5d1128a781f2a7 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -25,6 +25,9 @@ extern const AP_HAL::HAL& hal; #define LWIP_TCPIP_UNLOCK() #endif +#define PPP_DEBUG_TX 0 +#define PPP_DEBUG_RX 0 + /* output some data to the uart */ @@ -34,6 +37,27 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 LWIP_UNUSED_ARG(pcb); uint32_t remaining = len; const uint8_t *ptr = (const uint8_t *)data; +#if PPP_DEBUG_TX + bool flag_end = false; + if (ptr[len-1] == 0x7E) { + flag_end = true; + remaining--; + } + if (ptr[0] == 0x7E) { + // send byte size + if (pkt_size > 0) { + printf("PPP: tx[%lu] %u\n", tx_index++, pkt_size); + } + // dump the packet + if (!(tx_index % 10)) { + for (uint32_t i = 0; i < pkt_size; i++) { + printf(" %02X", tx_bytes[i]); + } + printf("\n"); + } + pkt_size = 0; + } +#endif while (remaining > 0) { const auto n = driver.uart->write(ptr, remaining); if (n > 0) { @@ -43,6 +67,22 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 hal.scheduler->delay_microseconds(100); } } +#if PPP_DEBUG_TX + memcpy(&tx_bytes[pkt_size], data, len); + pkt_size += len; + if (flag_end) { + driver.uart->write(0x7E); + printf("PPP: tx[%lu] %u\n", tx_index++, pkt_size); + // dump the packet + if (!(tx_index % 10)) { + for (uint32_t i = 0; i < pkt_size; i++) { + printf(" %02X", tx_bytes[i]); + } + printf("\n"); + } + pkt_size = 0; + } +#endif return len; } @@ -96,7 +136,7 @@ bool AP_Networking_PPP::init() return false; } - pppif = new netif; + pppif = NEW_NOTHROW netif; if (pppif == nullptr) { return false; } @@ -224,6 +264,25 @@ void AP_Networking_PPP::ppp_loop(void) } else { hal.scheduler->delay_microseconds(200); } +#if PPP_DEBUG_RX + auto pppos = (pppos_pcb *)ppp->link_ctx_cb; + for (uint32_t i = 0; i < n; i++) { + if (buf[i] == 0x7E && last_ppp_frame_size != 1) { + // dump the packet + if (pppos->bad_pkt) { + printf("PPP: rx[%lu] %u\n", rx_index, last_ppp_frame_size); + for (uint32_t j = 0; j < last_ppp_frame_size; j++) { + printf("0x%02X,", rx_bytes[j]); + } + printf("\n"); + hal.scheduler->delay(1); + } + rx_index++; + last_ppp_frame_size = 0; + } + rx_bytes[last_ppp_frame_size++] = buf[i]; + } +#endif } } } diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 07c35ab070800d..d552da12bf17f8 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -13,6 +13,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -115,7 +116,7 @@ void AP_Networking::Port::thread_create(AP_HAL::MemberProc proc) */ void AP_Networking::Port::udp_client_init(void) { - sock = new SocketAPM(true); + sock = NEW_NOTHROW SocketAPM(true); if (sock == nullptr) { return; } @@ -133,7 +134,7 @@ void AP_Networking::Port::udp_client_init(void) */ void AP_Networking::Port::udp_server_init(void) { - sock = new SocketAPM(true); + sock = NEW_NOTHROW SocketAPM(true); if (sock == nullptr) { return; } @@ -151,7 +152,7 @@ void AP_Networking::Port::udp_server_init(void) */ void AP_Networking::Port::tcp_server_init(void) { - listen_sock = new SocketAPM(false); + listen_sock = NEW_NOTHROW SocketAPM(false); if (listen_sock == nullptr) { return; } @@ -165,7 +166,7 @@ void AP_Networking::Port::tcp_server_init(void) */ void AP_Networking::Port::tcp_client_init(void) { - sock = new SocketAPM(false); + sock = NEW_NOTHROW SocketAPM(false); if (sock != nullptr) { sock->set_blocking(true); thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::tcp_client_loop, void)); @@ -255,7 +256,7 @@ void AP_Networking::Port::tcp_server_loop(void) sock = listen_sock->accept(100); if (sock != nullptr) { sock->set_blocking(false); - char buf[16]; + char buf[IP4_STR_LEN]; uint16_t last_port; const char *last_addr = listen_sock->last_recv_address(buf, sizeof(buf), last_port); if (last_addr != nullptr) { @@ -286,7 +287,7 @@ void AP_Networking::Port::tcp_client_loop(void) hal.scheduler->delay_microseconds(100); } if (sock == nullptr) { - sock = new SocketAPM(false); + sock = NEW_NOTHROW SocketAPM(false); if (sock == nullptr) { continue; } @@ -345,6 +346,30 @@ bool AP_Networking::Port::send_receive(void) } } + if (type == NetworkPortType::UDP_SERVER && have_received) { + // connect the socket to the last receive address if we have one + uint32_t last_addr = 0; + uint16_t last_port = 0; + if (sock->last_recv_address(last_addr, last_port)) { + // we might be disconnected and want to reconnect to a different address/port + // if we haven't received anything for a while + bool maybe_disconnected = (AP_HAL::millis() - last_udp_srv_recv_time_ms) > 3000 && + ((last_addr != last_udp_connect_address) || (last_port != last_udp_connect_port)); + if (maybe_disconnected || !connected) { + char last_addr_str[IP4_STR_LEN]; + sock->inet_addr_to_str(last_addr, last_addr_str, sizeof(last_addr_str)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP[%u]: connected to %s:%u", unsigned(state.idx), last_addr_str, unsigned(last_port)); + connected = true; + last_udp_connect_address = last_addr; + last_udp_connect_port = last_port; + } + // if we received something from the same address, reset the timer + if (((last_addr == last_udp_connect_address) && (last_port == last_udp_connect_port))) { + last_udp_srv_recv_time_ms = AP_HAL::millis(); + } + } + } + if (connected) { // handle outgoing packets uint32_t available; @@ -353,7 +378,7 @@ bool AP_Networking::Port::send_receive(void) WITH_SEMAPHORE(sem); available = writebuffer->available(); available = MIN(300U, available); -#if HAL_GCS_ENABLED +#if AP_MAVLINK_PACKETISE_ENABLED if (packetise) { available = mavlink_packetise(*writebuffer, available); } @@ -368,23 +393,35 @@ bool AP_Networking::Port::send_receive(void) WITH_SEMAPHORE(sem); n = writebuffer->peekbytes(buf, available); } - if (n > 0) { - const auto ret = sock->send(buf, n); - if (ret > 0) { - WITH_SEMAPHORE(sem); - writebuffer->advance(ret); - active = true; - } + + // nothing to send return + if (n <= 0) { + return active; } - } else { - if (type == NetworkPortType::UDP_SERVER && have_received) { - // connect the socket to the last receive address if we have one - char buf[16]; - uint16_t last_port; - const char *last_addr = sock->last_recv_address(buf, sizeof(buf), last_port); - if (last_addr != nullptr && port != 0) { - connected = sock->connect(last_addr, last_port); + + ssize_t ret = -1; + if (type == NetworkPortType::UDP_SERVER) { + // UDP Server uses sendto, allowing us to change the destination address port on the fly + if(last_udp_connect_address != 0 && last_udp_connect_port != 0) { + ret = sock->sendto(buf, n, last_udp_connect_address, last_udp_connect_port); } + } else { + // TCP Server and Client and UDP Client use send + ret = sock->send(buf, n); + } + + if (ret > 0) { + WITH_SEMAPHORE(sem); + writebuffer->advance(ret); + active = true; + } else if (errno == ENOTCONN && + (type == NetworkPortType::TCP_CLIENT || type == NetworkPortType::TCP_SERVER)) { + // close socket and mark as disconnected, so we can reconnect with another client or when server comes back + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: disconnected", unsigned(state.idx)); + sock->close(); + delete sock; + sock = nullptr; + connected = false; } } @@ -444,12 +481,12 @@ bool AP_Networking::Port::init_buffers(const uint32_t size_rx, const uint32_t si } WITH_SEMAPHORE(sem); if (readbuffer == nullptr) { - readbuffer = new ByteBuffer(size_rx); + readbuffer = NEW_NOTHROW ByteBuffer(size_rx); } else { readbuffer->set_size_best(size_rx); } if (writebuffer == nullptr) { - writebuffer = new ByteBuffer(size_tx); + writebuffer = NEW_NOTHROW ByteBuffer(size_tx); } else { writebuffer->set_size_best(size_tx); } diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 839f17f74647ad..5494c1012648e0 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -33,6 +33,16 @@ void AP_Networking::start_tests(void) "TCP_discard", 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); } + if (param.tests & TEST_TCP_REFLECT) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_TCP_reflect, void), + "TCP_reflect", + 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); + } + if (param.tests & TEST_CONNECTOR_LOOPBACK) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_connector_loopback, void), + "connector_loopback", + 8192, AP_HAL::Scheduler::PRIORITY_IO, -1); + } } /* @@ -43,7 +53,7 @@ void AP_Networking::test_UDP_client(void) startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting"); const char *dest = param.test_ipaddr.get_str(); - auto *sock = new SocketAPM(true); + auto *sock = NEW_NOTHROW SocketAPM(true); if (sock == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket"); return; @@ -75,7 +85,7 @@ void AP_Networking::test_TCP_client(void) startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting"); const char *dest = param.test_ipaddr.get_str(); - auto *sock = new SocketAPM(false); + auto *sock = NEW_NOTHROW SocketAPM(false); if (sock == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket"); return; @@ -107,7 +117,7 @@ void AP_Networking::test_TCP_discard(void) startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: starting"); const char *dest = param.test_ipaddr.get_str(); - auto *sock = new SocketAPM(false); + auto *sock = NEW_NOTHROW SocketAPM(false); if (sock == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: failed to create socket"); return; @@ -140,4 +150,127 @@ void AP_Networking::test_TCP_discard(void) } } +/* + start TCP reflect (TCP echo throughput) test + */ +void AP_Networking::test_TCP_reflect(void) +{ + startup_wait(); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_reflect: starting"); + const char *dest = param.test_ipaddr.get_str(); + auto *sock = new SocketAPM(false); + if (sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_reflect: failed to create socket"); + return; + } + // connect to the echo service, which is port 7 + while (!sock->connect(dest, 7)) { + hal.scheduler->delay(10); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_reflect: connected"); + const uint32_t bufsize = 4096; + uint8_t *buf = (uint8_t*)malloc(bufsize); + for (uint32_t i=0; idelay(1); + continue; + } + const bool will_send = total_sent < total_recv + max_disparity; + if (will_send) { + total_sent += sock->send(buf, bufsize); + } + if (sock->pollin(0)) { + uint32_t n = sock->recv(buf, bufsize, 0); + if (n == 0 && !will_send) { + hal.scheduler->delay_microseconds(100); + } + total_recv += n; + } + const uint32_t now = AP_HAL::millis(); + + if (now - last_report_ms >= 1000) { + float dt = (now - last_report_ms)*0.001; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reflect throughput %.3f kbyte/sec (disparity %u)", ((total_recv-last_recv)/dt)*1.0e-3, unsigned(total_sent-total_recv)); + last_recv = total_recv; + last_report_ms = now; + } + } +} + +void AP_Networking::test_connector_loopback(void) +{ + startup_wait(); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Connector Loopback: starting"); + + // start tcp discard server + auto *listen_sock = new SocketAPM(false); + if (listen_sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to create socket"); + return; + } + listen_sock->reuseaddress(); + + // use netif ip address + char ipstr[16]; + SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr)); + if (!listen_sock->bind(ipstr, 9)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to bind"); + return; + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: bound"); + + if (!listen_sock->listen(1)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to listen"); + return; + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: listening"); + // create discard client + auto *client = new SocketAPM(false); + if (client == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to create client"); + return; + } + while (!client->connect(ipstr, 9)) { + hal.scheduler->delay(10); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback: connected"); + + // accept client + auto *sock = listen_sock->accept(100); + if (sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "connector_loopback: failed to accept"); + return; + } + + uint8_t buf[1024]; + uint32_t last_report_ms = AP_HAL::millis(); + uint32_t total_rx = 0; + while (true) { + if ((param.tests & TEST_CONNECTOR_LOOPBACK) == 0) { + hal.scheduler->delay(1); + continue; + } + client->send(buf, 1024); + if (sock->pollin(0)) { + const ssize_t ret = sock->recv(buf, sizeof(buf), 0); + if (ret > 0) { + total_rx += ret; + } + } + if (AP_HAL::millis() - last_report_ms >= 1000) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "connector_loopback throughput %lu kbytes/sec", total_rx/1024); + total_rx = 0; + last_report_ms = AP_HAL::millis(); + } + } +} + #endif // AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h index c1342901c60585..672a9356766938 100644 --- a/libraries/AP_Networking/config/lwipopts.h +++ b/libraries/AP_Networking/config/lwipopts.h @@ -69,6 +69,12 @@ extern "C" #define MEMP_MEM_MALLOC 1 #define LWIP_NETCONN_SEM_PER_THREAD 0 +/** + * SO_REUSE==1: Enable SO_REUSEADDR option. + */ +#ifndef SO_REUSE +#define SO_REUSE 1 +#endif #define NO_SYS 0 #define LWIP_SOCKET (NO_SYS==0) diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp index c84133a294bbd5..26747cdc85755e 100644 --- a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -85,7 +85,7 @@ class ThreadWrapper { sys_thread_t sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksize, int prio) { - auto *thread_data = new ThreadWrapper(function, arg); + auto *thread_data = NEW_NOTHROW ThreadWrapper(function, arg); if (!thread_data->create(name, stacksize, prio)) { AP_HAL::panic("lwip: Failed to start thread %s", name); } @@ -120,7 +120,7 @@ sys_mbox_new(struct sys_mbox **mb, int size) struct sys_mbox *mbox; LWIP_UNUSED_ARG(size); - mbox = new sys_mbox; + mbox = NEW_NOTHROW sys_mbox; if (mbox == NULL) { return ERR_MEM; } @@ -292,7 +292,7 @@ sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout_ms) err_t sys_sem_new(sys_sem_t *sem, u8_t count) { - *sem = (sys_sem_t)new HAL_BinarySemaphore(count); + *sem = (sys_sem_t)NEW_NOTHROW HAL_BinarySemaphore(count); if (*sem == NULL) { return ERR_MEM; } @@ -330,7 +330,7 @@ sys_sem_free(sys_sem_t *sem) err_t sys_mutex_new(sys_mutex_t *mutex) { - *mutex = (sys_mutex_t)new HAL_Semaphore; + *mutex = (sys_mutex_t)NEW_NOTHROW HAL_Semaphore; if (*mutex == nullptr) { return ERR_MEM; } diff --git a/libraries/AP_Notify/AP_BoardLED.cpp b/libraries/AP_Notify/AP_BoardLED.cpp index 8e137c43e077be..164e39a4a72a97 100644 --- a/libraries/AP_Notify/AP_BoardLED.cpp +++ b/libraries/AP_Notify/AP_BoardLED.cpp @@ -12,12 +12,13 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ -#include "AP_BoardLED.h" -#include "AP_Notify.h" +#include "AP_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_3_ENABLED -#if (defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) && \ - defined(HAL_GPIO_C_LED_PIN)) +#include "AP_BoardLED.h" +#include "AP_Notify.h" static_assert((HAL_GPIO_A_LED_PIN != HAL_GPIO_B_LED_PIN) && (HAL_GPIO_A_LED_PIN != HAL_GPIO_C_LED_PIN) && @@ -168,7 +169,5 @@ void AP_BoardLED::update(void) break; } } -#else -bool AP_BoardLED::init(void) {return true;} -void AP_BoardLED::update(void) {return;} -#endif + +#endif // AP_NOTIFY_GPIO_LED_3_ENABLED diff --git a/libraries/AP_Notify/AP_BoardLED.h b/libraries/AP_Notify/AP_BoardLED.h index 810cacbde88602..adede6cd7bb124 100644 --- a/libraries/AP_Notify/AP_BoardLED.h +++ b/libraries/AP_Notify/AP_BoardLED.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_3_ENABLED + #include #include @@ -29,9 +33,8 @@ class AP_BoardLED: public NotifyDevice void update(void) override; private: -#if (defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) && \ - defined(HAL_GPIO_C_LED_PIN)) // counter incremented at 50Hz uint8_t _counter; -#endif }; + +#endif // AP_NOTIFY_GPIO_LED_3_ENABLED diff --git a/libraries/AP_Notify/AP_BoardLED2.cpp b/libraries/AP_Notify/AP_BoardLED2.cpp index 24a80e455938e4..ef2cbd18edd382 100644 --- a/libraries/AP_Notify/AP_BoardLED2.cpp +++ b/libraries/AP_Notify/AP_BoardLED2.cpp @@ -11,15 +11,18 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . + + + show all status on only 2 leds */ -#include "AP_BoardLED2.h" -#include "AP_Notify.h" +#include "AP_Notify_config.h" +#if AP_NOTIFY_GPIO_LED_2_ENABLED -// show all status on only 2 leds +#include "AP_BoardLED2.h" -#if defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) +#include "AP_Notify.h" static_assert((HAL_GPIO_A_LED_PIN != HAL_GPIO_B_LED_PIN), "Duplicate LED assignments detected"); @@ -263,7 +266,5 @@ void AP_BoardLED2::update(void) break; } } -#else -bool AP_BoardLED2::init(void) {return true;} -void AP_BoardLED2::update(void) {return;} -#endif + +#endif // AP_NOTIFY_GPIO_LED_2_ENABLED diff --git a/libraries/AP_Notify/AP_BoardLED2.h b/libraries/AP_Notify/AP_BoardLED2.h index 2d6b5e19a01a8f..94791d41bf7cad 100644 --- a/libraries/AP_Notify/AP_BoardLED2.h +++ b/libraries/AP_Notify/AP_BoardLED2.h @@ -14,7 +14,9 @@ */ #pragma once +#include "AP_Notify_config.h" +#if AP_NOTIFY_GPIO_LED_2_ENABLED #include #include @@ -33,9 +35,9 @@ class AP_BoardLED2: public NotifyDevice private: // counter incremented at 50Hz uint8_t _counter; -#if defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) uint16_t _sat_cnt; uint8_t save_trim_counter; uint8_t arm_counter = 0; -#endif }; + +#endif // AP_NOTIFY_GPIO_LED_2_ENABLED diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index 3d7503f1ed0eca..b103f13168d9b1 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -20,6 +20,7 @@ #include "Buzzer.h" #include "Display.h" #include "ExternalLED.h" +#include "GPIO_LED_1.h" #include "IS31FL3195.h" #include "PCA9685LED_I2C.h" #include "NavigatorLED.h" @@ -41,6 +42,7 @@ #include "ProfiLED.h" #include "ScriptingLED.h" #include "DShotLED.h" +#include "ProfiLED_IOMCU.h" extern const AP_HAL::HAL& hal; @@ -88,18 +90,11 @@ AP_Notify *AP_Notify::_singleton; #endif #ifndef DEFAULT_NTF_LED_TYPES -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS) - -// Linux boards -#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS |\ Notify_LED_PCA9685LED_I2C_External) - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 - #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS) - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS |\ DRONECAN_LEDS) @@ -116,25 +111,24 @@ AP_Notify *AP_Notify::_singleton; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ #define DEFAULT_NTF_LED_TYPES (Notify_LED_ToshibaLED_I2C_External) + #endif // board subtype +#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX +#endif // defined (DEFAULT_NTF_LED_TYPES) - #else // other linux - #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS) - #endif - -// All other builds -#else - #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS) - -#endif // board selection - +#ifndef DEFAULT_NTF_LED_TYPES + #if HAL_WITH_IO_MCU && AP_IOMCU_PROFILED_SUPPORT_ENABLED + #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | Notify_LED_ProfiLED_IOMCU | I2C_LEDS) + #else + #define DEFAULT_NTF_LED_TYPES (Notify_LED_Board | I2C_LEDS) + #endif #endif // DEFAULT_NTF_LED_TYPES #ifndef BUZZER_ENABLE_DEFAULT #if HAL_CANMANAGER_ENABLED // Enable Buzzer messages over UAVCAN -#define BUZZER_ENABLE_DEFAULT (Notify_Buzz_Builtin | Notify_Buzz_UAVCAN) +#define BUZZER_ENABLE_DEFAULT (uint8_t(BuzzerType::BUILTIN) | uint8_t(BuzzerType::UAVCAN)) #else -#define BUZZER_ENABLE_DEFAULT Notify_Buzz_Builtin +#define BUZZER_ENABLE_DEFAULT uint8_t(BuzzerType::BUILTIN) #endif #endif @@ -214,7 +208,7 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = { // @Param: LED_TYPES // @DisplayName: LED Driver Types // @Description: Controls what types of LEDs will be enabled - // @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:DroneCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting, 11:DShot, 12:ProfiLED_SPI, 13:LP5562 External, 14: LP5562 Internal, 15:IS31FL3195 External, 16: IS31FL3195 Internal, 17: DiscreteRGB, 18: NeoPixelRGB + // @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:DroneCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting, 11:DShot, 12:ProfiLED_SPI, 13:LP5562 External, 14: LP5562 Internal, 15:IS31FL3195 External, 16: IS31FL3195 Internal, 17: DiscreteRGB, 18: NeoPixelRGB, 19:ProfiLED_IOMCU // @User: Advanced AP_GROUPINFO("LED_TYPES", 6, AP_Notify, _led_type, DEFAULT_NTF_LED_TYPES), @@ -287,128 +281,130 @@ void AP_Notify::add_backends(void) break; case Notify_LED_Board: // select the most appropriate built in LED driver type -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX - #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 - ADD_BACKEND(new Led_Sysfs("rgb_led0", "rgb_led2", "rgb_led1")); - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE - ADD_BACKEND(new RCOutputRGBLedInverted(12, 13, 14)); - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH - ADD_BACKEND(new RCOutputRGBLed(HAL_RCOUT_RGBLED_RED, HAL_RCOUT_RGBLED_GREEN, HAL_RCOUT_RGBLED_BLUE)); - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO - ADD_BACKEND(new DiscoLED()); - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR - ADD_BACKEND(new NavigatorLED()); - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 - ADD_BACKEND(new AP_BoardLED2()); - #endif -#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX +#if AP_NOTIFY_SYSFS_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW Led_Sysfs("rgb_led0", "rgb_led2", "rgb_led1")); +#elif AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW RCOutputRGBLedInverted(12, 13, 14)); +#elif AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW RCOutputRGBLed(HAL_RCOUT_RGBLED_RED, HAL_RCOUT_RGBLED_GREEN, HAL_RCOUT_RGBLED_BLUE)); +#elif AP_NOTIFY_DISCO_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW DiscoLED()); +#elif AP_NOTIFY_NAVIGATOR_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW NavigatorLED()); +#endif #if AP_NOTIFY_EXTERNALLED_ENABLED - ADD_BACKEND(new ExternalLED()); // despite the name this is a built in set of onboard LED's + ADD_BACKEND(NEW_NOTHROW ExternalLED()); // despite the name this is a built in set of onboard LED's #endif -#if defined(HAL_HAVE_PIXRACER_LED) - ADD_BACKEND(new PixRacerLED()); -#elif (defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) && defined(HAL_GPIO_C_LED_PIN)) - #if AP_NOTIFY_VRBOARD_LED_ENABLED - ADD_BACKEND(new VRBoard_LED()); - #else - ADD_BACKEND(new AP_BoardLED()); - #endif -#elif (defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN)) - ADD_BACKEND(new AP_BoardLED2()); +#if AP_NOTIFY_GPIO_LED_RGB_ENABLED + ADD_BACKEND(NEW_NOTHROW PixRacerLED()); +#elif AP_NOTIFY_VRBOARD_LED_ENABLED + ADD_BACKEND(NEW_NOTHROW VRBoard_LED()); +#elif AP_NOTIFY_GPIO_LED_3_ENABLED + ADD_BACKEND(NEW_NOTHROW AP_BoardLED()); +#elif AP_NOTIFY_GPIO_LED_2_ENABLED + ADD_BACKEND(NEW_NOTHROW AP_BoardLED2()); +#endif +#if AP_NOTIFY_GPIO_LED_1_ENABLED + ADD_BACKEND(NEW_NOTHROW GPIO_LED_1()); #endif break; #if AP_NOTIFY_TOSHIBALED_ENABLED case Notify_LED_ToshibaLED_I2C_Internal: - ADD_BACKEND(new ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_INTERNAL)); + ADD_BACKEND(NEW_NOTHROW ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_INTERNAL)); break; case Notify_LED_ToshibaLED_I2C_External: - ADD_BACKEND(new ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_EXTERNAL)); + ADD_BACKEND(NEW_NOTHROW ToshibaLED_I2C(TOSHIBA_LED_I2C_BUS_EXTERNAL)); break; #endif #if AP_NOTIFY_NCP5623_ENABLED case Notify_LED_NCP5623_I2C_External: FOREACH_I2C_EXTERNAL(b) { - ADD_BACKEND(new NCP5623(b)); + ADD_BACKEND(NEW_NOTHROW NCP5623(b)); } break; case Notify_LED_NCP5623_I2C_Internal: FOREACH_I2C_INTERNAL(b) { - ADD_BACKEND(new NCP5623(b)); + ADD_BACKEND(NEW_NOTHROW NCP5623(b)); } break; #endif #if AP_NOTIFY_PCA9685_ENABLED case Notify_LED_PCA9685LED_I2C_External: - ADD_BACKEND(new PCA9685LED_I2C()); + ADD_BACKEND(NEW_NOTHROW PCA9685LED_I2C()); break; #endif #if AP_NOTIFY_NEOPIXEL_ENABLED case Notify_LED_NeoPixel: case Notify_LED_NeoPixelRGB: - ADD_BACKEND(new NeoPixel()); + ADD_BACKEND(NEW_NOTHROW NeoPixel()); break; #endif #if AP_NOTIFY_PROFILED_ENABLED case Notify_LED_ProfiLED: - ADD_BACKEND(new ProfiLED()); + ADD_BACKEND(NEW_NOTHROW ProfiLED()); break; #endif #if AP_NOTIFY_PROFILED_SPI_ENABLED case Notify_LED_ProfiLED_SPI: - ADD_BACKEND(new ProfiLED_SPI()); + ADD_BACKEND(NEW_NOTHROW ProfiLED_SPI()); break; #endif #if AP_NOTIFY_OREOLED_ENABLED case Notify_LED_OreoLED: if (_oreo_theme) { - ADD_BACKEND(new OreoLED_I2C(0, _oreo_theme)); + ADD_BACKEND(NEW_NOTHROW OreoLED_I2C(0, _oreo_theme)); } break; #endif #if AP_NOTIFY_DRONECAN_LED_ENABLED case Notify_LED_DroneCAN: - ADD_BACKEND(new DroneCAN_RGB_LED()); + ADD_BACKEND(NEW_NOTHROW DroneCAN_RGB_LED()); break; #endif // AP_NOTIFY_DRONECAN_LED_ENABLED #if AP_NOTIFY_SCRIPTING_LED_ENABLED case Notify_LED_Scripting: - ADD_BACKEND(new ScriptingLED()); + ADD_BACKEND(NEW_NOTHROW ScriptingLED()); break; #endif #if AP_NOTIFY_DSHOT_LED_ENABLED case Notify_LED_DShot: - ADD_BACKEND(new DShotLED()); + ADD_BACKEND(NEW_NOTHROW DShotLED()); + break; +#endif +#if HAL_WITH_IO_MCU && AP_IOMCU_PROFILED_SUPPORT_ENABLED + case Notify_LED_ProfiLED_IOMCU: + ADD_BACKEND(NEW_NOTHROW ProfiLED_IOMCU()); break; #endif #if AP_NOTIFY_LP5562_ENABLED case Notify_LED_LP5562_I2C_External: FOREACH_I2C_EXTERNAL(b) { - ADD_BACKEND(new LP5562(b, 0x30)); + ADD_BACKEND(NEW_NOTHROW LP5562(b, 0x30)); } break; case Notify_LED_LP5562_I2C_Internal: FOREACH_I2C_INTERNAL(b) { - ADD_BACKEND(new LP5562(b, 0x30)); + ADD_BACKEND(NEW_NOTHROW LP5562(b, 0x30)); } break; #endif #if AP_NOTIFY_IS31FL3195_ENABLED case Notify_LED_IS31FL3195_I2C_External: FOREACH_I2C_EXTERNAL(b) { - ADD_BACKEND(new IS31FL3195(b, 0x54)); + ADD_BACKEND(NEW_NOTHROW IS31FL3195(b, 0x54)); } break; case Notify_LED_IS31FL3195_I2C_Internal: FOREACH_I2C_INTERNAL(b) { - ADD_BACKEND(new IS31FL3195(b, 0x54)); + ADD_BACKEND(NEW_NOTHROW IS31FL3195(b, 0x54)); } break; #endif #if AP_NOTIFY_DISCRETE_RGB_ENABLED case Notify_LED_DiscreteRGB: - ADD_BACKEND(new DiscreteRGBLed(DISCRETE_RGB_RED_PIN, + ADD_BACKEND(NEW_NOTHROW DiscreteRGBLed(DISCRETE_RGB_RED_PIN, DISCRETE_RGB_GREEN_PIN, DISCRETE_RGB_BLUE_PIN, DISCRETE_RGB_POLARITY)); @@ -419,16 +415,20 @@ void AP_Notify::add_backends(void) #if HAL_DISPLAY_ENABLED // Always try and add a display backend - ADD_BACKEND(new Display()); + ADD_BACKEND(NEW_NOTHROW Display()); #endif // ChibiOS noise makers #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - ADD_BACKEND(new Buzzer()); + ADD_BACKEND(NEW_NOTHROW Buzzer()); #if AP_NOTIFY_TONEALARM_ENABLED - ADD_BACKEND(new AP_ToneAlarm()); + ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); #endif +// ESP32 noise makers +#elif CONFIG_HAL_BOARD == HAL_BOARD_ESP32 + ADD_BACKEND(NEW_NOTHROW Buzzer()); + // Linux noise makers #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ @@ -444,17 +444,17 @@ void AP_Notify::add_backends(void) #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 - ADD_BACKEND(new Buzzer()); + ADD_BACKEND(NEW_NOTHROW Buzzer()); #else // other linux - ADD_BACKEND(new AP_ToneAlarm()); + ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL - ADD_BACKEND(new AP_ToneAlarm()); - ADD_BACKEND(new Buzzer()); + ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); + ADD_BACKEND(NEW_NOTHROW Buzzer()); #ifdef WITH_SITL_RGBLED - ADD_BACKEND(new SITL_SFML_LED()); + ADD_BACKEND(NEW_NOTHROW SITL_SFML_LED()); #endif #endif // Noise makers diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index b71988bdf13097..3f3cf9507ed213 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -17,6 +17,7 @@ #include #include #include "AP_Notify_config.h" +#include #include "NotifyDevice.h" @@ -25,8 +26,6 @@ #define RGB_LED_LOW 1 #define RGB_LED_MEDIUM 2 #define RGB_LED_HIGH 3 -#define BUZZER_ON 1 -#define BUZZER_OFF 0 #define NOTIFY_TEXT_BUFFER_SIZE 51 @@ -99,15 +98,18 @@ class AP_Notify #endif #if AP_NOTIFY_NEOPIXEL_ENABLED Notify_LED_NeoPixelRGB = (1 << 18), // NeoPixel AdaFruit 4544 Worldsemi WS2811 +#endif +#if HAL_WITH_IO_MCU && AP_IOMCU_PROFILED_SUPPORT_ENABLED + Notify_LED_ProfiLED_IOMCU = (1 << 19), // ProfiLED IOMCU #endif Notify_LED_MAX }; - enum Notify_Buzz_Type { - Notify_Buzz_None = 0, - Notify_Buzz_Builtin = (1 << 0), // Built in default Alarm Out - Notify_Buzz_DShot = (1 << 1), // DShot Alarm - Notify_Buzz_UAVCAN = (1 << 2), // UAVCAN Alarm + enum class BuzzerType : uint8_t { + NONE = 0, + BUILTIN = (1 << 0), // Built in default Alarm Out + DSHOT = (1 << 1), // DShot Alarm + UAVCAN = (1 << 2), // UAVCAN Alarm }; /// notify_flags_type - bitmask of notification flags diff --git a/libraries/AP_Notify/AP_Notify_config.h b/libraries/AP_Notify/AP_Notify_config.h index fb702a8d1e3f7e..0bc83f19051eaf 100644 --- a/libraries/AP_Notify/AP_Notify_config.h +++ b/libraries/AP_Notify/AP_Notify_config.h @@ -37,6 +37,48 @@ #define AP_NOTIFY_LP5562_ENABLED 1 #endif +#ifndef AP_NOTIFY_DISCO_LED_ENABLED +#define AP_NOTIFY_DISCO_LED_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_NAVIGATOR_LED_ENABLED +#define AP_NOTIFY_NAVIGATOR_LED_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_GPIO_LED_3_ENABLED +#define AP_NOTIFY_GPIO_LED_3_ENABLED 0 +#endif + +// this isn't the second-generation of board LEDs, this is a setup +// where there are two LEDs used: +#ifndef AP_NOTIFY_GPIO_LED_2_ENABLED +#define AP_NOTIFY_GPIO_LED_2_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_GPIO_LED_1_ENABLED +#define AP_NOTIFY_GPIO_LED_1_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_GPIO_LED_RGB_ENABLED +#define AP_NOTIFY_GPIO_LED_RGB_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED +#define AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_RCOUTPUTRGBLEDOFF_LED_ENABLED +#define AP_NOTIFY_RCOUTPUTRGBLEDOFF_LED_ENABLED 0 +#endif + +#ifndef AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED +#define AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED || AP_NOTIFY_RCOUTPUTRGBLEDOFF_LED_ENABLED +#endif + +#ifndef AP_NOTIFY_SYSFS_LED_ENABLED +#define AP_NOTIFY_SYSFS_LED_ENABLED 0 +#endif + #ifndef AP_NOTIFY_IS31FL3195_ENABLED #define AP_NOTIFY_IS31FL3195_ENABLED 1 #endif diff --git a/libraries/AP_Notify/DiscoLED.cpp b/libraries/AP_Notify/DiscoLED.cpp index 845972e623e269..ec2030d894d7a8 100644 --- a/libraries/AP_Notify/DiscoLED.cpp +++ b/libraries/AP_Notify/DiscoLED.cpp @@ -14,9 +14,13 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "AP_Notify_config.h" + +#if AP_NOTIFY_DISCO_LED_ENABLED + #include -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include "DiscoLED.h" #include @@ -92,4 +96,4 @@ bool DiscoLED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) return true; } -#endif +#endif // AP_NOTIFY_DISCO_LED_ENABLED diff --git a/libraries/AP_Notify/DiscoLED.h b/libraries/AP_Notify/DiscoLED.h index 3c7585327ed21d..d32ccf818fce34 100644 --- a/libraries/AP_Notify/DiscoLED.h +++ b/libraries/AP_Notify/DiscoLED.h @@ -16,9 +16,12 @@ */ #pragma once +#include "AP_Notify_config.h" + +#if AP_NOTIFY_DISCO_LED_ENABLED + #include -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include #include @@ -53,4 +56,4 @@ class DiscoLED: public RGBLed enum led_backend backend; }; -#endif +#endif // AP_NOTIFY_DISCO_LED_ENABLED diff --git a/libraries/AP_Notify/Display_SH1106_I2C.cpp b/libraries/AP_Notify/Display_SH1106_I2C.cpp index 0c5f36e4274545..275945210055f7 100644 --- a/libraries/AP_Notify/Display_SH1106_I2C.cpp +++ b/libraries/AP_Notify/Display_SH1106_I2C.cpp @@ -31,7 +31,7 @@ Display_SH1106_I2C::~Display_SH1106_I2C() Display_SH1106_I2C *Display_SH1106_I2C::probe(AP_HAL::OwnPtr dev) { - Display_SH1106_I2C *driver = new Display_SH1106_I2C(std::move(dev)); + Display_SH1106_I2C *driver = NEW_NOTHROW Display_SH1106_I2C(std::move(dev)); if (!driver || !driver->hw_init()) { delete driver; return nullptr; diff --git a/libraries/AP_Notify/Display_SITL.cpp b/libraries/AP_Notify/Display_SITL.cpp index 61effccca7db58..0d9206d032824f 100644 --- a/libraries/AP_Notify/Display_SITL.cpp +++ b/libraries/AP_Notify/Display_SITL.cpp @@ -33,7 +33,7 @@ Display_SITL::~Display_SITL() Display_SITL *Display_SITL::probe() { - Display_SITL *driver = new Display_SITL(); + Display_SITL *driver = NEW_NOTHROW Display_SITL(); if (!driver || !driver->hw_init()) { delete driver; return nullptr; @@ -46,7 +46,7 @@ void Display_SITL::update_thread(void) { { WITH_SEMAPHORE(AP::notify().sf_window_mutex); - w = new sf::RenderWindow(sf::VideoMode(COLUMNS*SCALE, ROWS*SCALE), "Display"); + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(COLUMNS*SCALE, ROWS*SCALE), "Display"); } if (!w) { AP_HAL::panic("Unable to create Display_SITL window"); diff --git a/libraries/AP_Notify/Display_SSD1306_I2C.cpp b/libraries/AP_Notify/Display_SSD1306_I2C.cpp index f292fbb32125c4..c57341442ee6d8 100644 --- a/libraries/AP_Notify/Display_SSD1306_I2C.cpp +++ b/libraries/AP_Notify/Display_SSD1306_I2C.cpp @@ -32,7 +32,7 @@ Display_SSD1306_I2C::~Display_SSD1306_I2C() Display_SSD1306_I2C *Display_SSD1306_I2C::probe(AP_HAL::OwnPtr dev) { - Display_SSD1306_I2C *driver = new Display_SSD1306_I2C(std::move(dev)); + Display_SSD1306_I2C *driver = NEW_NOTHROW Display_SSD1306_I2C(std::move(dev)); if (!driver || !driver->hw_init()) { delete driver; return nullptr; diff --git a/libraries/AP_Notify/GPIO_LED_1.cpp b/libraries/AP_Notify/GPIO_LED_1.cpp new file mode 100644 index 00000000000000..431256465f4440 --- /dev/null +++ b/libraries/AP_Notify/GPIO_LED_1.cpp @@ -0,0 +1,79 @@ +/* + 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_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_1_ENABLED + +#include "GPIO_LED_1.h" + +#include +#include "AP_Notify.h" + +#ifndef AP_NOTIFY_GPIO_LED_1_PIN +#error "define AP_NOTIFY_GPIO_LED_1_PIN" +#endif + +extern const AP_HAL::HAL& hal; + +bool GPIO_LED_1::init(void) +{ + // when HAL_GPIO_LED_ON is 0 then we must not use pinMode() + // as it could remove the OPENDRAIN attribute on the pin +#if HAL_GPIO_LED_ON != 0 + hal.gpio->pinMode(AP_NOTIFY_GPIO_LED_1_PIN, HAL_GPIO_OUTPUT); +#endif + hal.gpio->write(AP_NOTIFY_GPIO_LED_1_PIN, HAL_GPIO_LED_OFF); + return true; +} + +/* + main update function called at 50Hz + */ +void GPIO_LED_1::update(void) +{ + uint32_t new_pattern; + if (AP_Notify::flags.initialising) { + new_pattern = INITIALIZING; + } else if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_gcs || AP_Notify::flags.failsafe_battery) { + new_pattern = FAILSAFE; + } else if (AP_Notify::flags.armed) { + new_pattern = ARMED; + } else if (AP_Notify::flags.pre_arm_check) { + new_pattern = READY_TO_ARM; + } else { + new_pattern = NOT_READY_TO_ARM; + } + if (new_pattern != current_pattern) { + next_bit = 0; + current_pattern = new_pattern; + last_timestep_ms = 0; + } + + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_timestep_ms < 100) { + return; + } + last_timestep_ms = now_ms; + + const auto new_state = (current_pattern & (1U<write(AP_NOTIFY_GPIO_LED_1_PIN, new_state); + next_bit++; + if (next_bit > 31) { + next_bit = 0; + } +} + +#endif // AP_NOTIFY_GPIO_LED_1_ENABLED diff --git a/libraries/AP_Notify/GPIO_LED_1.h b/libraries/AP_Notify/GPIO_LED_1.h new file mode 100644 index 00000000000000..b9f2a0302ee32c --- /dev/null +++ b/libraries/AP_Notify/GPIO_LED_1.h @@ -0,0 +1,49 @@ +/* + 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_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_1_ENABLED + +#include +#include + +#include "NotifyDevice.h" + +class GPIO_LED_1 : public NotifyDevice +{ +public: + // initialise the LED driver + bool init(void) override; + + // should be called at 50Hz + void update(void) override; + +private: + + // left-to-right, each bit represents 100ms + static const uint32_t INITIALIZING = 0b10101010101010101010101010101010UL; + static const uint32_t NOT_READY_TO_ARM = 0b11110000000000001111111110000000UL; + static const uint32_t READY_TO_ARM = 0b11111111111111100000000000000000UL; + static const uint32_t ARMED = 0b11111111111111111111111111111111UL; + static const uint32_t FAILSAFE = 0b11110000111100001111000011110000UL; + + uint32_t current_pattern = INITIALIZING; + uint32_t last_timestep_ms; + uint8_t next_bit; +}; + +#endif // AP_NOTIFY_GPIO_LED_1_ENABLED diff --git a/libraries/AP_Notify/Led_Sysfs.cpp b/libraries/AP_Notify/Led_Sysfs.cpp index 3bdec24cb7ffc9..e611062a0fc0ef 100644 --- a/libraries/AP_Notify/Led_Sysfs.cpp +++ b/libraries/AP_Notify/Led_Sysfs.cpp @@ -14,12 +14,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ -#include +#include "AP_Notify_config.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX -#include "Led_Sysfs.h" +#if AP_NOTIFY_SYSFS_LED_ENABLED -#include +#include "Led_Sysfs.h" Led_Sysfs::Led_Sysfs(const char *red, const char *green, const char *blue, uint8_t off_brightness, uint8_t low_brightness, uint8_t medium_brightness, uint8_t high_brightness): @@ -47,4 +46,4 @@ bool Led_Sysfs::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) return true; } -#endif +#endif // AP_NOTIFY_SYSFS_LED_ENABLED diff --git a/libraries/AP_Notify/Led_Sysfs.h b/libraries/AP_Notify/Led_Sysfs.h index be8fab15e801e1..caab49c8488260 100644 --- a/libraries/AP_Notify/Led_Sysfs.h +++ b/libraries/AP_Notify/Led_Sysfs.h @@ -16,9 +16,10 @@ */ #pragma once -#include +#include "AP_Notify_config.h" + +#if AP_NOTIFY_SYSFS_LED_ENABLED -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include #include "RGBLed.h" @@ -39,4 +40,4 @@ class Led_Sysfs: public RGBLed Linux::Led_Sysfs green_led; Linux::Led_Sysfs blue_led; }; -#endif +#endif // AP_NOTIFY_SYSFS_LED_ENABLED diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index 962cceb21c0f51..9e01c5388279e0 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -72,7 +72,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) for (uint8_t i = 0; i < can_num_drivers; i++) { AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i); if (uavcan != nullptr && - (AP::notify().get_buzzer_types() & AP_Notify::Notify_Buzz_UAVCAN)) { + (AP::notify().get_buzzer_types() & uint8_t(AP_Notify::BuzzerType::UAVCAN))) { msg.frequency = frequency; msg.duration = _note_duration_us*1.0e-6; uavcan->buzzer.broadcast(msg); diff --git a/libraries/AP_Notify/NavigatorLED.cpp b/libraries/AP_Notify/NavigatorLED.cpp index 8c7b706aa16bff..7bdc68e397ea6e 100644 --- a/libraries/AP_Notify/NavigatorLED.cpp +++ b/libraries/AP_Notify/NavigatorLED.cpp @@ -19,6 +19,10 @@ // not used. The data is sent to the neopixel in 24 'SPI bytes', where each // spi byte is formatted to appear as a single bit of data to the neopixel. +#include "AP_Notify_config.h" + +#if AP_NOTIFY_NAVIGATOR_LED_ENABLED + #include #include "AP_Notify/AP_Notify.h" #include "NavigatorLED.h" @@ -79,3 +83,5 @@ void NavigatorLED::_setup_data(uint8_t red, uint8_t green, uint8_t blue) _data[16 + i] = (blue & (1<<(7-i))) ? LED_T1 : LED_T0; } } + +#endif // AP_NOTIFY_NAVIGATOR_LED_ENABLED diff --git a/libraries/AP_Notify/NavigatorLED.h b/libraries/AP_Notify/NavigatorLED.h index 9f93857eb1c8ac..f6ef3a23877e2a 100644 --- a/libraries/AP_Notify/NavigatorLED.h +++ b/libraries/AP_Notify/NavigatorLED.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_Notify_config.h" + +#if AP_NOTIFY_NAVIGATOR_LED_ENABLED + #include "RGBLed.h" #include @@ -30,3 +34,5 @@ class NavigatorLED: public RGBLed { void _setup_data(uint8_t red, uint8_t green, uint8_t blue); AP_HAL::OwnPtr _dev; }; + +#endif // AP_NOTIFY_NAVIGATOR_LED_ENABLED diff --git a/libraries/AP_Notify/PixRacerLED.cpp b/libraries/AP_Notify/PixRacerLED.cpp index 3e543a0cf38802..19da44e3e5f1a0 100644 --- a/libraries/AP_Notify/PixRacerLED.cpp +++ b/libraries/AP_Notify/PixRacerLED.cpp @@ -13,20 +13,22 @@ along with this program. If not, see . */ +#include "AP_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_RGB_ENABLED + #include "PixRacerLED.h" #include -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - -#ifndef HAL_GPIO_A_LED_PIN -#define HAL_GPIO_A_LED_PIN -1 +#ifndef AP_NOTIFY_GPIO_LED_RGB_RED_PIN +#error "define AP_NOTIFY_GPIO_LED_RGB_RED_PIN" #endif -#ifndef HAL_GPIO_B_LED_PIN -#define HAL_GPIO_B_LED_PIN -1 +#ifndef AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN +#error "define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN" #endif -#ifndef HAL_GPIO_C_LED_PIN -#define HAL_GPIO_C_LED_PIN -1 +#ifndef AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN +#error "define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN" #endif extern const AP_HAL::HAL& hal; @@ -41,25 +43,22 @@ bool PixRacerLED::init(void) // when HAL_GPIO_LED_ON is 0 then we must not use pinMode() // as it could remove the OPENDRAIN attribute on the pin #if HAL_GPIO_LED_ON != 0 - hal.gpio->pinMode(HAL_GPIO_A_LED_PIN, HAL_GPIO_OUTPUT); - hal.gpio->pinMode(HAL_GPIO_B_LED_PIN, HAL_GPIO_OUTPUT); - hal.gpio->pinMode(HAL_GPIO_C_LED_PIN, HAL_GPIO_OUTPUT); + hal.gpio->pinMode(AP_NOTIFY_GPIO_LED_RGB_RED_PIN, HAL_GPIO_OUTPUT); + hal.gpio->pinMode(AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN, HAL_GPIO_OUTPUT); + hal.gpio->pinMode(AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN, HAL_GPIO_OUTPUT); #endif - hal.gpio->write(HAL_GPIO_A_LED_PIN, HAL_GPIO_LED_OFF); - hal.gpio->write(HAL_GPIO_B_LED_PIN, HAL_GPIO_LED_OFF); - hal.gpio->write(HAL_GPIO_C_LED_PIN, HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_RED_PIN, HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN, HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN, HAL_GPIO_LED_OFF); return true; } bool PixRacerLED::hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) { - hal.gpio->write(HAL_GPIO_A_LED_PIN, (r > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); - hal.gpio->write(HAL_GPIO_B_LED_PIN, (g > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); - hal.gpio->write(HAL_GPIO_C_LED_PIN, (b > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_RED_PIN, (r > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN, (g > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); + hal.gpio->write(AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN, (b > 0)?HAL_GPIO_LED_ON:HAL_GPIO_LED_OFF); return true; } -#else -bool PixRacerLED::init(void) { return true; } -bool PixRacerLED::hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) { return true; } -#endif +#endif // AP_NOTIFY_GPIO_LED_RGB_ENABLED diff --git a/libraries/AP_Notify/PixRacerLED.h b/libraries/AP_Notify/PixRacerLED.h index 43dc34ac033028..ca93161abef8ff 100644 --- a/libraries/AP_Notify/PixRacerLED.h +++ b/libraries/AP_Notify/PixRacerLED.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_Notify_config.h" + +#if AP_NOTIFY_GPIO_LED_RGB_ENABLED + #include "RGBLed.h" class PixRacerLED: public RGBLed @@ -25,3 +29,5 @@ class PixRacerLED: public RGBLed protected: bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override; }; + +#endif // AP_NOTIFY_GPIO_LED_RGB_ENABLED diff --git a/libraries/AP_Notify/ProfiLED.cpp b/libraries/AP_Notify/ProfiLED.cpp index 872e7819a27218..72ee6599c8ec96 100644 --- a/libraries/AP_Notify/ProfiLED.cpp +++ b/libraries/AP_Notify/ProfiLED.cpp @@ -75,7 +75,7 @@ ProfiLED_SPI::ProfiLED_SPI() : bool ProfiLED_SPI::init() { num_leds = pNotify->get_led_len() + 1; // for some reason we have to send an additional LED data - rgb = new ProfiLED_SPI::RGB[num_leds]; + rgb = NEW_NOTHROW ProfiLED_SPI::RGB[num_leds]; if (!rgb) { return false; } diff --git a/libraries/AP_Notify/ProfiLED_IOMCU.h b/libraries/AP_Notify/ProfiLED_IOMCU.h new file mode 100644 index 00000000000000..ae4a9e0124fd1c --- /dev/null +++ b/libraries/AP_Notify/ProfiLED_IOMCU.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 "RGBLed.h" +#include +#include + +#if HAL_WITH_IO_MCU && AP_IOMCU_PROFILED_SUPPORT_ENABLED + +class ProfiLED_IOMCU : public RGBLed { +public: + ProfiLED_IOMCU() : RGBLed(0, 0xFF, 0x7F, 0x33) {} + + bool init(void) override { return true; } + +protected: + bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override { + const auto iomcu = AP::iomcu(); + if (iomcu == nullptr) { + return false; + } + iomcu->set_profiled(r, g, b); + return true; + } +}; + +#endif \ No newline at end of file diff --git a/libraries/AP_Notify/RCOutputRGBLed.cpp b/libraries/AP_Notify/RCOutputRGBLed.cpp index b9049f14684b25..b9147126f91ac5 100644 --- a/libraries/AP_Notify/RCOutputRGBLed.cpp +++ b/libraries/AP_Notify/RCOutputRGBLed.cpp @@ -15,6 +15,10 @@ * with this program. If not, see . */ +#include "AP_Notify_config.h" + +#if AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED + #include "RCOutputRGBLed.h" #include @@ -58,10 +62,12 @@ uint16_t RCOutputRGBLed::get_duty_cycle_for_color(const uint8_t color, const uin return usec_period * color / _led_bright; } +#if AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED uint16_t RCOutputRGBLedInverted::get_duty_cycle_for_color(const uint8_t color, const uint16_t usec_period) const { return usec_period * (255 - color) / _led_bright; } +#endif // AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED bool RCOutputRGBLed::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) @@ -91,3 +97,4 @@ bool RCOutputRGBLed::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) return true; } +#endif // AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED diff --git a/libraries/AP_Notify/RCOutputRGBLed.h b/libraries/AP_Notify/RCOutputRGBLed.h index aeae109e945f41..865d13fcfc997a 100644 --- a/libraries/AP_Notify/RCOutputRGBLed.h +++ b/libraries/AP_Notify/RCOutputRGBLed.h @@ -2,6 +2,7 @@ #include "RGBLed.h" +#if AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED class RCOutputRGBLed: public RGBLed { public: RCOutputRGBLed(uint8_t red_channel, uint8_t green_channel, @@ -20,7 +21,9 @@ class RCOutputRGBLed: public RGBLed { uint8_t _green_channel; uint8_t _blue_channel; }; +#endif // AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED +#if AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED class RCOutputRGBLedInverted : public RCOutputRGBLed { public: RCOutputRGBLedInverted(uint8_t red_channel, uint8_t green_channel, uint8_t blue_channel) @@ -29,7 +32,9 @@ class RCOutputRGBLedInverted : public RCOutputRGBLed { protected: virtual uint16_t get_duty_cycle_for_color(const uint8_t color, const uint16_t usec_period) const override; }; +#endif // AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED +#if AP_NOTIFY_RCOUTPUTRGBLEDOFF_LED_ENABLED class RCOutputRGBLedOff : public RCOutputRGBLed { public: RCOutputRGBLedOff(uint8_t red_channel, uint8_t green_channel, @@ -45,3 +50,4 @@ class RCOutputRGBLedOff : public RCOutputRGBLed { return RCOutputRGBLed::hw_set_rgb(_led_off, _led_off, _led_off); } }; +#endif // AP_NOTIFY_RCOUTPUTRGBLEDOFF_LED_ENABLED diff --git a/libraries/AP_Notify/RGBLed.cpp b/libraries/AP_Notify/RGBLed.cpp index b00ebdff0fa001..caa549fd94cae9 100644 --- a/libraries/AP_Notify/RGBLed.cpp +++ b/libraries/AP_Notify/RGBLed.cpp @@ -20,6 +20,7 @@ #include #include "RGBLed.h" #include "AP_Notify.h" +#include extern const AP_HAL::HAL& hal; @@ -47,15 +48,15 @@ void RGBLed::_set_rgb(uint8_t red, uint8_t green, uint8_t blue) } } -RGBLed::rgb_source_t RGBLed::rgb_source() const +RGBLed::Source RGBLed::rgb_source() const { - return rgb_source_t(pNotify->_rgb_led_override.get()); + return Source(pNotify->_rgb_led_override.get()); } // set_rgb - set color as a combination of red, green and blue values void RGBLed::set_rgb(uint8_t red, uint8_t green, uint8_t blue) { - if (rgb_source() == mavlink) { + if (rgb_source() == Source::mavlink) { // don't set if in override mode return; } @@ -136,33 +137,45 @@ uint32_t RGBLed::get_colour_sequence(void) const return sequence_failsafe_radio_or_battery; } +#if AP_GPS_ENABLED + Location loc; +#if AP_AHRS_ENABLED + // the AHRS can return "true" for get_location and still not be + // happy enough with the location to set its origin from that + // location: + const bool good_ahrs_location = AP::ahrs().get_location(loc) && AP::ahrs().get_origin(loc); +#else + const bool good_ahrs_location = true; +#endif + // solid green or blue if armed if (AP_Notify::flags.armed) { #if AP_GPS_ENABLED - // solid green if armed with GPS 3d lock - if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) { + // solid green if armed with GPS 3d lock and good location + if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D && + good_ahrs_location) { return sequence_armed; } #endif // solid blue if armed with no GPS lock - return sequence_armed_nogps; + return sequence_armed_no_gps_or_no_location; } // double flash yellow if failing pre-arm checks if (!AP_Notify::flags.pre_arm_check) { return sequence_prearm_failing; } -#if AP_GPS_ENABLED - if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS && AP_Notify::flags.pre_arm_gps_check) { - return sequence_disarmed_good_dgps; - } - - if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D && AP_Notify::flags.pre_arm_gps_check) { - return sequence_disarmed_good_gps; + if (AP_Notify::flags.pre_arm_gps_check && good_ahrs_location) { + if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS) { + return sequence_disarmed_good_dgps_and_location; + } + if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) { + return sequence_disarmed_good_gps_and_location; + } } #endif - return sequence_disarmed_bad_gps; + return sequence_disarmed_bad_gps_or_no_location; } uint32_t RGBLed::get_colour_sequence_traffic_light(void) const @@ -196,16 +209,16 @@ void RGBLed::update() uint32_t current_colour_sequence = 0; switch (rgb_source()) { - case mavlink: + case Source::mavlink: update_override(); return; // note this is a return not a break! - case standard: + case Source::standard: current_colour_sequence = get_colour_sequence(); break; - case obc: + case Source::obc: current_colour_sequence = get_colour_sequence_obc(); break; - case traffic_light: + case Source::traffic_light: current_colour_sequence = get_colour_sequence_traffic_light(); break; } @@ -235,7 +248,7 @@ void RGBLed::update() */ void RGBLed::handle_led_control(const mavlink_message_t &msg) { - if (rgb_source() != mavlink) { + if (rgb_source() != Source::mavlink) { // ignore LED_CONTROL commands if not in LED_OVERRIDE mode return; } diff --git a/libraries/AP_Notify/RGBLed.h b/libraries/AP_Notify/RGBLed.h index 461db449ee9238..3978f04806c67e 100644 --- a/libraries/AP_Notify/RGBLed.h +++ b/libraries/AP_Notify/RGBLed.h @@ -98,19 +98,19 @@ class RGBLed: public NotifyDevice { const uint32_t sequence_failsafe_radio_or_battery = DEFINE_COLOUR_SEQUENCE_FAILSAFE(BLACK); const uint32_t sequence_armed = DEFINE_COLOUR_SEQUENCE_SOLID(GREEN); - const uint32_t sequence_armed_nogps = DEFINE_COLOUR_SEQUENCE_SOLID(BLUE); + const uint32_t sequence_armed_no_gps_or_no_location = DEFINE_COLOUR_SEQUENCE_SOLID(BLUE); const uint32_t sequence_prearm_failing = DEFINE_COLOUR_SEQUENCE(YELLOW,YELLOW,BLACK,BLACK,YELLOW,YELLOW,BLACK,BLACK,BLACK,BLACK); - const uint32_t sequence_disarmed_good_dgps = DEFINE_COLOUR_SEQUENCE_ALTERNATE(GREEN,BLACK); - const uint32_t sequence_disarmed_good_gps = DEFINE_COLOUR_SEQUENCE_SLOW(GREEN); - const uint32_t sequence_disarmed_bad_gps = DEFINE_COLOUR_SEQUENCE_SLOW(BLUE); + const uint32_t sequence_disarmed_good_dgps_and_location = DEFINE_COLOUR_SEQUENCE_ALTERNATE(GREEN,BLACK); + const uint32_t sequence_disarmed_good_gps_and_location = DEFINE_COLOUR_SEQUENCE_SLOW(GREEN); + const uint32_t sequence_disarmed_bad_gps_or_no_location = DEFINE_COLOUR_SEQUENCE_SLOW(BLUE); uint8_t last_step; - enum rgb_source_t { + enum class Source { standard = 0, mavlink = 1, obc = 2, traffic_light = 3, }; - rgb_source_t rgb_source() const; + Source rgb_source() const; }; diff --git a/libraries/AP_Notify/SITL_SFML_LED.cpp b/libraries/AP_Notify/SITL_SFML_LED.cpp index 6bb96be714b27d..3a5ed202674445 100644 --- a/libraries/AP_Notify/SITL_SFML_LED.cpp +++ b/libraries/AP_Notify/SITL_SFML_LED.cpp @@ -126,7 +126,7 @@ void SITL_SFML_LED::update_serial_LEDs() if (!layout_size(layout, xsize, ysize)) { return; } - w = new sf::RenderWindow(sf::VideoMode(xsize*(serialLED_size+1), ysize*(serialLED_size+1)), "SerialLED"); + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(xsize*(serialLED_size+1), ysize*(serialLED_size+1)), "SerialLED"); if (!w) { return; } @@ -150,7 +150,7 @@ void SITL_SFML_LED::update_serial_LEDs() uint8_t *rgb = &sitl->led.rgb[chan][led].rgb[0]; if (leds[chan][led] == nullptr) { - leds[chan][led] = new sf::RectangleShape(sf::Vector2f(serialLED_size, serialLED_size)); + leds[chan][led] = NEW_NOTHROW sf::RectangleShape(sf::Vector2f(serialLED_size, serialLED_size)); if (!leds[chan][led]) { return; } diff --git a/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp b/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp index 6412bd03268b87..1247dd4287235e 100644 --- a/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp +++ b/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp @@ -12,15 +12,19 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +#if AP_NOTIFY_GPIO_LED_3_ENABLED // create board led object AP_BoardLED board_led; +#endif void setup() { hal.console->printf("AP_Notify library test\n"); +#if AP_NOTIFY_GPIO_LED_3_ENABLED // initialise the board leds board_led.init(); +#endif // turn on initialising notification AP_Notify::flags.initialising = true; diff --git a/libraries/AP_ONVIF/AP_ONVIF.cpp b/libraries/AP_ONVIF/AP_ONVIF.cpp index 6a0fae5672334c..d5c43e9278a901 100644 --- a/libraries/AP_ONVIF/AP_ONVIF.cpp +++ b/libraries/AP_ONVIF/AP_ONVIF.cpp @@ -63,13 +63,13 @@ bool AP_ONVIF::start(const char *user, const char *pass, const char *hostname) soap->connect_timeout = soap->recv_timeout = soap->send_timeout = 30; // 30 sec if (proxy_device == nullptr) { - proxy_device = new DeviceBindingProxy(soap); + proxy_device = NEW_NOTHROW DeviceBindingProxy(soap); } if (proxy_media == nullptr) { - proxy_media = new MediaBindingProxy(soap); + proxy_media = NEW_NOTHROW MediaBindingProxy(soap); } if (proxy_ptz == nullptr) { - proxy_ptz = new PTZBindingProxy(soap); + proxy_ptz = NEW_NOTHROW PTZBindingProxy(soap); } if (proxy_device == nullptr || diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 3f1a7b8a491070..34ee67df2be066 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -230,6 +230,22 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = { AP_GROUPINFO("_W_SNR", 34, AP_OSD, warn_snr, 0), #endif +#if HAL_OSD_SIDEBAR_ENABLE + // @Param: _SB_H_OFS + // @DisplayName: Sidebar horizontal offset + // @Description: Extends the spacing between the sidebar elements by this amount of columns. Positive values increases the width to the right of the screen. + // @Range: 0 20 + // @User: Standard + AP_GROUPINFO("_SB_H_OFS", 35, AP_OSD, sidebar_h_offset, 0), + + // @Param: _SB_V_EXT + // @DisplayName: Sidebar vertical extension + // @Description: Increase of vertical length of the sidebar itens by this amount of lines. Applied equally both above and below the default setting. + // @Range: 0 10 + // @User: Standard + AP_GROUPINFO("_SB_V_EXT", 36, AP_OSD, sidebar_v_ext, 0), +#endif // HAL_OSD_SIDEBAR_ENABLE + #endif //osd enabled #if OSD_PARAM_ENABLED // @Group: 5_ @@ -490,7 +506,7 @@ void AP_OSD::update_stats() // max esc temp AP_ESC_Telem& telem = AP::esc_telem(); int16_t highest_temperature = 0; - telem.get_highest_motor_temperature(highest_temperature); + telem.get_highest_temperature(highest_temperature); _stats.max_esc_temp = MAX(_stats.max_esc_temp, highest_temperature); #endif } diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index b57526b45bc0a3..5e6621621e35ec 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -33,6 +33,7 @@ #include #endif #include +#include class AP_OSD_Backend; class AP_MSP; @@ -259,6 +260,9 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen AP_Int8 txt_resolution; AP_Int8 font_index; #endif +#if HAL_WITH_ESC_TELEM + AP_Int8 esc_index; +#endif void draw_altitude(uint8_t x, uint8_t y); void draw_bat_volt(uint8_t instance,VoltageType type,uint8_t x, uint8_t y); @@ -331,7 +335,9 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen #if AP_FENCE_ENABLED void draw_fence(uint8_t x, uint8_t y); #endif +#if AP_RANGEFINDER_ENABLED void draw_rngf(uint8_t x, uint8_t y); +#endif #if AP_OSD_EXTENDED_LNK_STATS // Extended link stats data panels @@ -497,7 +503,7 @@ class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen #if AP_RC_CHANNEL_ENABLED Event map_rc_input_to_event() const; - RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const; + RC_Channel::AuxSwitchPos get_channel_pos(const class RC_Channel &chan) const; #endif uint8_t _selected_param = 1; @@ -591,6 +597,11 @@ class AP_OSD AP_Int8 warn_snr; #endif +#if HAL_OSD_SIDEBAR_ENABLE + AP_Int8 sidebar_h_offset; + AP_Int8 sidebar_v_ext; +#endif + enum { OPTION_DECIMAL_PACK = 1U<<0, OPTION_INVERTED_WIND = 1U<<1, diff --git a/libraries/AP_OSD/AP_OSD_MAX7456.cpp b/libraries/AP_OSD/AP_OSD_MAX7456.cpp index c5830e707837fe..81104399d6ce09 100644 --- a/libraries/AP_OSD/AP_OSD_MAX7456.cpp +++ b/libraries/AP_OSD/AP_OSD_MAX7456.cpp @@ -252,7 +252,7 @@ AP_OSD_Backend *AP_OSD_MAX7456::probe(AP_OSD &osd, AP_HAL::OwnPtr #include #include -#include #include #include #include @@ -390,14 +389,11 @@ void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev) } // return radio values as LOW, MIDDLE, HIGH -// this function uses different threshold values to RC_Chanel::get_channel_pos() +// this function uses different threshold values to RC_Chanel::get_aux_switch_pos() // to avoid glitching on the stick travel -RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) const +RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(const RC_Channel &chanref) const { - const RC_Channel* chan = rc().channel(rcmapchan-1); - if (chan == nullptr) { - return RC_Channel::AuxSwitchPos::LOW; - } + const auto *chan = &chanref; const uint16_t in = chan->get_radio_in(); if (in <= 900 || in >= 2200) { @@ -419,10 +415,10 @@ RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) // map rc input to an event AP_OSD_ParamScreen::Event AP_OSD_ParamScreen::map_rc_input_to_event() const { - const RC_Channel::AuxSwitchPos throttle = get_channel_pos(AP::rcmap()->throttle()); - const RC_Channel::AuxSwitchPos yaw = get_channel_pos(AP::rcmap()->yaw()); - const RC_Channel::AuxSwitchPos roll = get_channel_pos(AP::rcmap()->roll()); - const RC_Channel::AuxSwitchPos pitch = get_channel_pos(AP::rcmap()->pitch()); + const RC_Channel::AuxSwitchPos throttle = get_channel_pos(rc().get_throttle_channel()); + const RC_Channel::AuxSwitchPos yaw = get_channel_pos(rc().get_yaw_channel()); + const RC_Channel::AuxSwitchPos roll = get_channel_pos(rc().get_roll_channel()); + const RC_Channel::AuxSwitchPos pitch = get_channel_pos(rc().get_pitch_channel()); Event result = Event::NONE; diff --git a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp index 82424f7f4e80dc..a9a75981ac6467 100644 --- a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp @@ -139,7 +139,7 @@ static const char* SERIAL_PROTOCOL_VALUES[] = { "FSKY_TX", "LID360", "", "BEACN", "VOLZ", "SBUS", "ESC_TLM", "DEV_TLM", "OPTFLW", "RBTSRV", "NMEA", "WNDVNE", "SLCAN", "RCIN", "MGSQRT", "LTM", "RUNCAM", "HOT_TLM", "SCRIPT", "CRSF", "GEN", "WNCH", "MSP", "DJI", "AIRSPD", "ADSB", "AHRS", "AUDIO", "FETTEC", "TORQ", - "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", "IQ", "PPP", "IRIS_ORCA", + "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", "IQ", "PPP", "IRIS_ORCA", "IBUS_TLM" }; static_assert(AP_SerialManager::SerialProtocol_NumProtocols == ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), "Wrong size SerialProtocol_NumProtocols"); diff --git a/libraries/AP_OSD/AP_OSD_SITL.cpp b/libraries/AP_OSD/AP_OSD_SITL.cpp index 40599025600d33..be6a180b1d6509 100644 --- a/libraries/AP_OSD/AP_OSD_SITL.cpp +++ b/libraries/AP_OSD/AP_OSD_SITL.cpp @@ -52,7 +52,7 @@ void AP_OSD_SITL::load_font(void) for (uint16_t i=0; i<256; i++) { const uint8_t *c = &fd->data[i*54]; // each pixel is 4 bytes, RGBA - sf::Uint8 *pixels = new sf::Uint8[char_width * char_height * 4]; + sf::Uint8 *pixels = NEW_NOTHROW sf::Uint8[char_width * char_height * 4]; if (!font[i].create(char_width, char_height)) { AP_HAL::panic("Failed to create texture"); } @@ -125,7 +125,7 @@ void AP_OSD_SITL::update_thread(void) load_font(); { WITH_SEMAPHORE(AP::notify().sf_window_mutex); - w = new sf::RenderWindow(sf::VideoMode(video_cols*(char_width+char_spacing)*char_scale, + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(video_cols*(char_width+char_spacing)*char_scale, video_lines*(char_height+char_spacing)*char_scale), "OSD"); } @@ -194,7 +194,7 @@ bool AP_OSD_SITL::init(void) AP_OSD_Backend *AP_OSD_SITL::probe(AP_OSD &osd) { - AP_OSD_SITL *backend = new AP_OSD_SITL(osd); + AP_OSD_SITL *backend = NEW_NOTHROW AP_OSD_SITL(osd); if (!backend) { return nullptr; } diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 01ea15a25ef517..947203c3ab8126 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -358,7 +358,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { #if HAL_WITH_ESC_TELEM // @Param: ESCTEMP_EN // @DisplayName: ESCTEMP_EN - // @Description: Displays first esc's temp + // @Description: Displays highest temp of all active ESCs, or of a specific ECS if OSDx_ESC_IDX is set // @Values: 0:Disabled,1:Enabled // @Param: ESCTEMP_X @@ -374,7 +374,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ESCRPM_EN // @DisplayName: ESCRPM_EN - // @Description: Displays first esc's rpm + // @Description: Displays highest rpm of all active ESCs, or of a specific ESC if OSDx_ESC_IDX is set // @Values: 0:Disabled,1:Enabled // @Param: ESCRPM_X @@ -390,7 +390,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ESCAMPS_EN // @DisplayName: ESCAMPS_EN - // @Description: Displays first esc's current + // @Description: Displays the current of the ESC with the highest rpm of all active ESCs, or of a specific ESC if OSDx_ESC_IDX is set // @Values: 0:Disabled,1:Enabled // @Param: ESCAMPS_X @@ -1166,6 +1166,14 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = { AP_SUBGROUPINFO(rc_lq, "RC_LQ", 9, AP_OSD_Screen, AP_OSD_Setting), #endif +#if HAL_WITH_ESC_TELEM + // @Param: ESC_IDX + // @DisplayName: ESC_IDX + // @Description: Index of the ESC to use for displaying ESC information. 0 means use the ESC with the highest value. + // @Range: 0 32 + AP_GROUPINFO("ESC_IDX", 10, AP_OSD_Screen, esc_index, 0), +#endif + AP_GROUPEND }; @@ -1862,10 +1870,14 @@ void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y) static const int aspd_interval = 10; //units between large tick marks int alt_interval = (osd->units == AP_OSD::UNITS_AVIATION || osd->units == AP_OSD::UNITS_IMPERIAL) ? 20 : 10; + // Height values taking into account configurable vertical extension + const int bar_total_height = 7 + (osd->sidebar_v_ext * 2); + const int bar_middle = bar_total_height / 2; // Integer division + // render airspeed ladder int aspd_symbol_index = fmodf(scaled_aspd, aspd_interval) / aspd_interval * total_sectors; - for (int i = 0; i < 7; i++){ - if (i == 3) { + for (int i = 0; i < bar_total_height; i++){ + if (i == bar_middle) { // the middle section of the ladder with the currrent airspeed backend->write(x, y+i, false, "%3d%c%c", (int) scaled_aspd, u_icon(SPEED), SYMBOL(SYM_SIDEBAR_R_ARROW)); } else { @@ -1877,12 +1889,12 @@ void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y) // render the altitude ladder // similar formula to above, but accounts for negative altitudes int alt_symbol_index = fmodf(fmodf(scaled_alt, alt_interval) + alt_interval, alt_interval) / alt_interval * total_sectors; - for (int i = 0; i < 7; i++){ - if (i == 3) { + for (int i = 0; i < bar_total_height; i++){ + if (i == bar_middle) { // the middle section of the ladder with the currrent altitude - backend->write(x+16, y+i, false, "%c%d%c", SYMBOL(SYM_SIDEBAR_L_ARROW), (int) scaled_alt, u_icon(ALTITUDE)); + backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c%d%c", SYMBOL(SYM_SIDEBAR_L_ARROW), (int) scaled_alt, u_icon(ALTITUDE)); } else { - backend->write(x+16, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index])); + backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index])); } alt_symbol_index = (alt_symbol_index + 12) % 18; } @@ -1999,8 +2011,13 @@ void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y) void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y) { int16_t etemp; - // first parameter is index into array of ESC's. Hardwire to zero (first) for now. - if (!AP::esc_telem().get_temperature(0, etemp)) { + + if (esc_index > 0) { + if (!AP::esc_telem().get_temperature(esc_index-1, etemp)) { + return; + } + } + else if (!AP::esc_telem().get_highest_temperature(etemp)) { return; } @@ -2010,8 +2027,12 @@ void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y) void AP_OSD_Screen::draw_esc_rpm(uint8_t x, uint8_t y) { float rpm; - // first parameter is index into array of ESC's. Hardwire to zero (first) for now. - if (!AP::esc_telem().get_rpm(0, rpm)) { + uint8_t esc = AP::esc_telem().get_max_rpm_esc(); + if (esc_index > 0) { + if (!AP::esc_telem().get_rpm(esc_index-1, rpm)) { + return; + } + } else if (!AP::esc_telem().get_rpm(esc, rpm)) { return; } float krpm = rpm * 0.001f; @@ -2022,8 +2043,12 @@ void AP_OSD_Screen::draw_esc_rpm(uint8_t x, uint8_t y) void AP_OSD_Screen::draw_esc_amps(uint8_t x, uint8_t y) { float amps; - // first parameter is index into array of ESC's. Hardwire to zero (first) for now. - if (!AP::esc_telem().get_current(0, amps)) { + uint8_t esc = AP::esc_telem().get_max_rpm_esc(); + if (esc_index > 0) { + if (!AP::esc_telem().get_current(esc_index-1, amps)) { + return; + } + } else if (!AP::esc_telem().get_current(esc, amps)) { return; } backend->write(x, y, false, "%4.1f%c", amps, SYMBOL(SYM_AMP)); @@ -2509,6 +2534,7 @@ void AP_OSD_Screen::draw_fence(uint8_t x, uint8_t y) } #endif +#if AP_RANGEFINDER_ENABLED void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y) { RangeFinder *rangefinder = RangeFinder::get_singleton(); @@ -2522,6 +2548,7 @@ void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y) backend->write(x, y, false, "%c%4.1f%c", SYMBOL(SYM_RNGFD), u_scale(DISTANCE, distance), u_icon(DISTANCE)); } } +#endif #define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos) @@ -2547,7 +2574,9 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(hgt_abvterr); #endif +#if AP_RANGEFINDER_ENABLED DRAW_SETTING(rngf); +#endif DRAW_SETTING(waypoint); DRAW_SETTING(xtrack_error); DRAW_SETTING(bat_volt); @@ -2555,8 +2584,10 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(avgcellvolt); DRAW_SETTING(avgcellrestvolt); DRAW_SETTING(restvolt); +#if AP_RSSI_ENABLED DRAW_SETTING(rssi); DRAW_SETTING(link_quality); +#endif DRAW_SETTING(current); DRAW_SETTING(batused); DRAW_SETTING(bat2used); diff --git a/libraries/AP_OSD/fonts/HDFonts/WS/font_update.ini b/libraries/AP_OSD/fonts/HDFonts/WS/font_update.ini deleted file mode 100644 index 23d28317ad417a..00000000000000 --- a/libraries/AP_OSD/fonts/HDFonts/WS/font_update.ini +++ /dev/null @@ -1,13 +0,0 @@ -[config] -count=1 -1=ARDU_Europa - -[ARDU_Europa] -imgname_720=WS_APN_Europa_24.png -imgname_1080=WS_APN_Europa_36.png -font_width_720=24 -font_height_720=36 -font_width_1080=36 -font_height_1080=54 -x_offset=0 -y_offset=0 diff --git a/libraries/AP_OSD/fonts/HDFonts/AllWhite/font.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/AllWhite/font.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/AllWhite/font_2.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_2.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/AllWhite/font_2.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_2.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/AllWhite/font_hd.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_hd.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/AllWhite/font_hd.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_hd.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/AllWhite/font_hd_2.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_hd_2.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/AllWhite/font_hd_2.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/AllWhite/font_hd_2.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/Color/font.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/Color/font.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/Color/font_2.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_2.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/Color/font_2.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_2.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/Color/font_hd.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_hd.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/Color/font_hd.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_hd.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/Color/font_hd_2.bin b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_hd_2.bin similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/Color/font_hd_2.bin rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/Color/font_hd_2.bin diff --git a/libraries/AP_OSD/fonts/HDFonts/AllWhite/hd_flat_map.png b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/hd_allwhite_map.png similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/AllWhite/hd_flat_map.png rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/hd_allwhite_map.png diff --git a/libraries/AP_OSD/fonts/HDFonts/Color/hd_colour_map.png b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/hd_colour_map.png similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/Color/hd_colour_map.png rename to libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Pre-Ver0.12/hd_colour_map.png diff --git a/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/README.md b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/README.md new file mode 100644 index 00000000000000..6e56cecf77cf7b --- /dev/null +++ b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/README.md @@ -0,0 +1 @@ +Depending on which version of WTFOS MSP-OSD module you are using, copy the files to the base directory of your goggless diff --git a/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_24.png b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_24.png new file mode 100755 index 00000000000000..e4e84cb54ae967 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_36.png b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_36.png new file mode 100755 index 00000000000000..d6e40f024bf7d2 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/WS_ardu_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/font_update.ini b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/font_update.ini new file mode 100755 index 00000000000000..9172570c03160f --- /dev/null +++ b/libraries/AP_OSD/fonts/HDFonts/WTFOS-DJI/Ver0.12_or_later/font_update.ini @@ -0,0 +1,11 @@ +[config] +count=1 +1=ardu + +[ardu] +imgname_720=WS_ardu_24.png +imgname_1080=WS_ardu_36.png +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/Readme.txt b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/Readme.txt new file mode 100644 index 00000000000000..616d98b0c1dac5 --- /dev/null +++ b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/Readme.txt @@ -0,0 +1,7 @@ +Extract this zip to your SD card root folder. +As of Walksnail Avatar FW 34.40.15, user supplied fonts are to be in the userfont folder on the SD card. If you are using a lower FW version, move the content of the userfont folder, into the root of the SD card. + +This is a font selection that includes: + - the latest unify font versions + - a night flying suited font + - the original 8-bit looking font similar to what is observed in analogue video OSD \ No newline at end of file diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_24.png new file mode 100644 index 00000000000000..46048e67f2d98f Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_36.png new file mode 100644 index 00000000000000..85f512bbd1a0aa Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Blinder_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_24.png new file mode 100644 index 00000000000000..fb38fbcb62d42d Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_36.png new file mode 100644 index 00000000000000..cb7691348f504a Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Conthrax_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WS/WS_APN_Europa_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Europa_24.png similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/WS/WS_APN_Europa_24.png rename to libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Europa_24.png diff --git a/libraries/AP_OSD/fonts/HDFonts/WS/WS_APN_Europa_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Europa_36.png similarity index 100% rename from libraries/AP_OSD/fonts/HDFonts/WS/WS_APN_Europa_36.png rename to libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Europa_36.png diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_24.png new file mode 100644 index 00000000000000..6f52c4c26ee85e Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_36.png new file mode 100644 index 00000000000000..ca745d476fca39 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Hemi_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_24.png new file mode 100644 index 00000000000000..fe3db15f818b4e Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_36.png new file mode 100644 index 00000000000000..f52b76bfb2861a Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Nexus_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_24.png new file mode 100644 index 00000000000000..6b81a461bf29c5 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_36.png new file mode 100644 index 00000000000000..ecd2cf2c901eec Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_APC_Sphere_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_24.png new file mode 100644 index 00000000000000..bc2ac790fd2a04 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_36.png new file mode 100644 index 00000000000000..4a350bf409e1e5 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/WS_ARDU_Night_36.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/font_update.ini b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/font_update.ini new file mode 100644 index 00000000000000..6e0db21e5ff6b1 --- /dev/null +++ b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/font_update.ini @@ -0,0 +1,99 @@ +[config] +count=8 +1=AP_Original +2=AP_Blinder +3=AP_Conthrax +4=AP_Europa +5=AP_Hemi +6=AP_Nexus +7=AP_Night +8=AP_Sphere + +[AP_Original] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=user_ardu_24.png +imgname_1080=user_ardu_36.png +x_offset=0 +y_offset=0 + +[AP_Blinder] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Blinder_24.png +imgname_1080=WS_APC_Blinder_36.png +x_offset=0 +y_offset=0 + +[AP_Conthrax] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Conthrax_24.png +imgname_1080=WS_APC_Conthrax_36.png +x_offset=0 +y_offset=0 + +[AP_Europa] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Europa_24.png +imgname_1080=WS_APC_Europa_36.png +x_offset=0 +y_offset=0 + +[AP_Hemi] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Hemi_24.png +imgname_1080=WS_APC_Hemi_36.png +x_offset=0 +y_offset=0 + +[AP_Nexus] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Nexus_24.png +imgname_1080=WS_APC_Nexus_36.png +x_offset=0 +y_offset=0 + +[AP_Night] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_ARDU_Night_24.png +imgname_1080=WS_ARDU_Night_36.png +x_offset=0 +y_offset=0 + +[AP_Sphere] +fcid= +font_width_720=24 +font_height_720=36 +font_width_1080=36 +font_height_1080=54 +imgname_720=WS_APC_Sphere_24.png +imgname_1080=WS_APC_Sphere_36.png +x_offset=0 +y_offset=0 + diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_24.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_24.png new file mode 100644 index 00000000000000..fff43a54885f90 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_24.png differ diff --git a/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_36.png b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_36.png new file mode 100644 index 00000000000000..2b8f33a21233a4 Binary files /dev/null and b/libraries/AP_OSD/fonts/HDFonts/WalkSnail/userfont/user_ardu_36.png differ diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp index 0e643d8d863ad9..aeec6da73237ec 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp @@ -166,6 +166,11 @@ bool AP_OpenDroneID::pre_arm_check(char* failmsg, uint8_t failmsg_len) return true; } + if(_enable == 0) { + strncpy(failmsg, "DID_ENABLE must be 1", failmsg_len); + return false; + } + if (pkt_basic_id.id_type == MAV_ODID_ID_TYPE_NONE) { strncpy(failmsg, "UA_TYPE required in BasicID", failmsg_len); return false; diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp index 73becf04406da2..b15f2af98842e9 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp @@ -42,35 +42,35 @@ void AP_OpenDroneID::dronecan_init(AP_DroneCAN *uavcan) return; } - dc_location[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); + dc_location[driver_index] = NEW_NOTHROW Canard::Publisher(uavcan->get_canard_iface()); if (dc_location[driver_index] == nullptr) { goto alloc_failed; } dc_location[driver_index]->set_timeout_ms(20); dc_location[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_basic_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); + dc_basic_id[driver_index] = NEW_NOTHROW Canard::Publisher(uavcan->get_canard_iface()); if (dc_basic_id[driver_index] == nullptr) { goto alloc_failed; } dc_basic_id[driver_index]->set_timeout_ms(20); dc_basic_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_self_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); + dc_self_id[driver_index] = NEW_NOTHROW Canard::Publisher(uavcan->get_canard_iface()); if (dc_self_id[driver_index] == nullptr) { goto alloc_failed; } dc_self_id[driver_index]->set_timeout_ms(20); dc_self_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_system[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); + dc_system[driver_index] = NEW_NOTHROW Canard::Publisher(uavcan->get_canard_iface()); if (dc_system[driver_index] == nullptr) { goto alloc_failed; } dc_system[driver_index]->set_timeout_ms(20); dc_system[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_operator_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); + dc_operator_id[driver_index] = NEW_NOTHROW Canard::Publisher(uavcan->get_canard_iface()); if (dc_operator_id[driver_index] == nullptr) { goto alloc_failed; } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index 0a5c89aa6689d0..2b86e63f73d4f4 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -19,13 +19,7 @@ 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 Type::PIXART - #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP - #define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP - #else #define OPTICAL_FLOW_TYPE_DEFAULT Type::NONE - #endif #endif const AP_Param::GroupInfo AP_OpticalFlow::var_info[] = { @@ -140,8 +134,8 @@ void AP_OpticalFlow::init(uint32_t log_bit) #endif break; case Type::BEBOP: -#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP - backend = new AP_OpticalFlow_Onboard(*this); +#if AP_OPTICALFLOW_ONBOARD_ENABLED + backend = NEW_NOTHROW AP_OpticalFlow_Onboard(*this); #endif break; case Type::CXOF: @@ -156,7 +150,7 @@ void AP_OpticalFlow::init(uint32_t log_bit) break; case Type::UAVCAN: #if AP_OPTICALFLOW_HEREFLOW_ENABLED - backend = new AP_OpticalFlow_HereFlow(*this); + backend = NEW_NOTHROW AP_OpticalFlow_HereFlow(*this); #endif break; case Type::MSP: @@ -171,7 +165,7 @@ void AP_OpticalFlow::init(uint32_t log_bit) break; case Type::SITL: #if AP_OPTICALFLOW_SITL_ENABLED - backend = new AP_OpticalFlow_SITL(*this); + backend = NEW_NOTHROW AP_OpticalFlow_SITL(*this); #endif break; } @@ -243,7 +237,7 @@ void AP_OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt) void AP_OpticalFlow::start_calibration() { if (_calibrator == nullptr) { - _calibrator = new AP_OpticalFlow_Calibrator(); + _calibrator = NEW_NOTHROW AP_OpticalFlow_Calibrator(); if (_calibrator == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "FlowCal: failed to start"); return; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp index af3180b95dd8d8..f27e5f0aca8137 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp @@ -72,7 +72,7 @@ AP_OpticalFlow_CXOF *AP_OpticalFlow_CXOF::detect(AP_OpticalFlow &_frontend) } // we have found a serial port so use it - AP_OpticalFlow_CXOF *sensor = new AP_OpticalFlow_CXOF(_frontend, uart); + AP_OpticalFlow_CXOF *sensor = NEW_NOTHROW AP_OpticalFlow_CXOF(_frontend, uart); return sensor; } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index 123b3408c3abd3..9ba5a98dadbda1 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -26,15 +26,11 @@ AP_OpticalFlow_HereFlow::AP_OpticalFlow_HereFlow(AP_OpticalFlow &flow) : } //links the HereFlow messages to the backend -void AP_OpticalFlow_HereFlow::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_OpticalFlow_HereFlow::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("measurement_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, driver_index) != nullptr); } //updates driver states based on received HereFlow messages diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index afc75841631a07..7b457bf6c96161 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -15,7 +15,7 @@ class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { void update() override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp index 7a84b17623e3f5..9d26f141c25901 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp @@ -26,7 +26,7 @@ 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); + AP_OpticalFlow_MAV *sensor = NEW_NOTHROW AP_OpticalFlow_MAV(_frontend); return sensor; } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp index eaff53fde2a90a..8923a5846b5c01 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp @@ -29,7 +29,7 @@ using namespace MSP; 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); + return NEW_NOTHROW AP_OpticalFlow_MSP(_frontend); } // read latest values from sensor and fill in x,y and totals. diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp index 0f72760d02c307..aaf876e59a1265 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp @@ -40,7 +40,7 @@ extern const AP_HAL::HAL& hal; // detect the device AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(AP_OpticalFlow &_frontend) { - AP_OpticalFlow_PX4Flow *sensor = new AP_OpticalFlow_PX4Flow(_frontend); + AP_OpticalFlow_PX4Flow *sensor = NEW_NOTHROW AP_OpticalFlow_PX4Flow(_frontend); if (!sensor) { return nullptr; } @@ -78,7 +78,7 @@ bool AP_OpticalFlow_PX4Flow::scan_buses(void) struct i2c_integral_frame frame; success = tdev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame)); if (success) { - printf("Found PX4Flow on bus %u\n", bus); + printf("Found PX4Flow on bus %u\n", unsigned(bus)); dev = std::move(tdev); break; } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp index 5a976c8a3eb2f4..373c044ef3d6db 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp @@ -94,7 +94,7 @@ AP_OpticalFlow_Pixart::AP_OpticalFlow_Pixart(const char *devname, AP_OpticalFlow // detect the device AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(const char *devname, AP_OpticalFlow &_frontend) { - AP_OpticalFlow_Pixart *sensor = new AP_OpticalFlow_Pixart(devname, _frontend); + AP_OpticalFlow_Pixart *sensor = NEW_NOTHROW AP_OpticalFlow_Pixart(devname, _frontend); if (!sensor) { return nullptr; } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp index a4af1d4c86c2c0..6452cc1532f3a6 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp @@ -74,7 +74,7 @@ AP_OpticalFlow_UPFLOW *AP_OpticalFlow_UPFLOW::detect(AP_OpticalFlow &_frontend) } // we have found a serial port so use it - AP_OpticalFlow_UPFLOW *sensor = new AP_OpticalFlow_UPFLOW(_frontend, uart); + AP_OpticalFlow_UPFLOW *sensor = NEW_NOTHROW AP_OpticalFlow_UPFLOW(_frontend, uart); return sensor; } diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index b37f20051a97a8..8c88c2be26a3bb 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -2,6 +2,10 @@ /// @brief Parachute release library #pragma once +#include "AP_Parachute_config.h" + +#if HAL_PARACHUTE_ENABLED + #include #include @@ -22,13 +26,6 @@ #define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute #define AP_PARACHUTE_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release -#ifndef HAL_PARACHUTE_ENABLED -// default to parachute enabled to match previous configs -#define HAL_PARACHUTE_ENABLED 1 -#endif - -#if HAL_PARACHUTE_ENABLED - /// @class AP_Parachute /// @brief Class managing the release of a parachute class AP_Parachute { diff --git a/libraries/AP_Parachute/AP_Parachute_config.h b/libraries/AP_Parachute/AP_Parachute_config.h new file mode 100644 index 00000000000000..0d646cdb7a473e --- /dev/null +++ b/libraries/AP_Parachute/AP_Parachute_config.h @@ -0,0 +1,8 @@ +#pragma once + +#include + +#ifndef HAL_PARACHUTE_ENABLED +// default to parachute enabled to match previous configs +#define HAL_PARACHUTE_ENABLED 1 +#endif diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index ff4bd0a00b2c3d..9962780398a661 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -112,6 +112,9 @@ uint16_t AP_Param::param_overrides_len; uint16_t AP_Param::num_param_overrides; uint16_t AP_Param::num_read_only; +// goes true if we run out of param space +bool AP_Param::eeprom_full; + ObjectBuffer_TS AP_Param::save_queue{30}; bool AP_Param::registered_save_handler; @@ -265,7 +268,12 @@ void AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info, if (size == 0) { FATAL("invalid type in %s", group_info[i].name); } - if (prefix_length + strlen(group_info[i].name) > 16) { + uint8_t param_name_length = prefix_length + strlen(group_info[i].name); + if (type == AP_PARAM_VECTOR3F) { + // need room for _X/_Y/_Z + param_name_length += 2; + } + if (param_name_length > 16) { FATAL("suffix is too long in %s", group_info[i].name); } (*total_size) += size + sizeof(struct Param_header); @@ -1192,6 +1200,8 @@ void AP_Param::save_sync(bool force_save, bool send_to_gcs) return; } if (ofs == (uint16_t) ~0) { + eeprom_full = true; + DEV_PRINTF("EEPROM full\n"); return; } @@ -1224,6 +1234,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 + eeprom_full = true; DEV_PRINTF("EEPROM full\n"); return; } @@ -1260,6 +1271,7 @@ void AP_Param::save(bool force_save) if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) { // if we are armed in main thread then don't sleep, instead we lose the // parameter save + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return; } // when we are disarmed then loop waiting for a slot to become @@ -1353,8 +1365,7 @@ bool AP_Param::load(void) return false; } - AP_Param *ap; - ap = this; + AP_Param *ap = this; if (idx != 0) { ap = (AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float)); } @@ -1967,8 +1978,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc // find the new variable in the variable structures enum ap_var_type ptype; - AP_Param *ap2; - ap2 = find(&info->new_name[0], &ptype); + AP_Param *ap2 = find(&info->new_name[0], &ptype); if (ap2 == nullptr) { DEV_PRINTF("Unknown conversion '%s'\n", info->new_name); return; @@ -2099,7 +2109,7 @@ void AP_Param::convert_toplevel_objects(const TopLevelObjectConversion conversio convert width of a parameter, allowing update to wider scalar values without changing the parameter indexes */ -bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor) +bool AP_Param::_convert_parameter_width(ap_var_type old_ptype, float scale_factor, bool bitmask) { if (configured_in_storage()) { // already converted or set by the user @@ -2143,10 +2153,46 @@ bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor AP_Param *old_ap = (AP_Param *)&old_value[0]; - // going via float is safe as the only time we would be converting - // from AP_Int32 is when converting to float - float old_float_value = old_ap->cast_to_float(old_ptype); - set_value(new_ptype, this, old_float_value*scale_factor); + if (!bitmask) { + // Numeric conversion + // going via float is safe as the only time we would be converting + // from AP_Int32 is when converting to float + float old_float_value = old_ap->cast_to_float(old_ptype); + set_value(new_ptype, this, old_float_value*scale_factor); + + } else { + // Bitmask conversion, go via uint32 + // int8 -1 should convert to int16 255 + uint32_t mask; + switch (old_ptype) { + case AP_PARAM_INT8: + mask = (uint8_t)(*(AP_Int8*)old_ap); + break; + case AP_PARAM_INT16: + mask = (uint16_t)(*(AP_Int16*)old_ap); + break; + case AP_PARAM_INT32: + mask = (uint32_t)(*(AP_Int32*)old_ap); + break; + default: + return false; + } + + switch (new_ptype) { + case AP_PARAM_INT8: + ((AP_Int8 *)this)->set(mask); + break; + case AP_PARAM_INT16: + ((AP_Int16 *)this)->set(mask); + break; + case AP_PARAM_INT32: + ((AP_Int32 *)this)->set(mask); + break; + default: + return false; + } + } + // force save as the new type save(true); @@ -2357,7 +2403,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) num_param_overrides = 0; num_read_only = 0; - param_overrides = new param_override[num_defaults]; + param_overrides = NEW_NOTHROW param_override[num_defaults]; if (param_overrides == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate overrides"); return false; @@ -2452,7 +2498,7 @@ void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, boo return; } - param_overrides = new param_override[num_defaults]; + param_overrides = NEW_NOTHROW param_override[num_defaults]; if (param_overrides == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate overrides"); return; @@ -2493,7 +2539,7 @@ void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, boo AP_Param *vp = find(pname, &var_type); if (!vp) { if (last_pass) { -#if ENABLE_DEBUG +#if ENABLE_DEBUG && (AP_PARAM_MAX_EMBEDDED_PARAM > 0) ::printf("Ignored unknown param %s from embedded region (offset=%u)\n", pname, unsigned(ptr - param_defaults_data.data)); hal.console->printf( @@ -2848,7 +2894,7 @@ void AP_Param::add_default(AP_Param *ap, float v) } // add to list - defaults_list *new_item = new defaults_list; + defaults_list *new_item = NEW_NOTHROW defaults_list; if (new_item == nullptr) { return; } @@ -2904,14 +2950,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 + float default_value = NaNf; // from logger quiet_nanf for (ap=AP_Param::first(&token, &type, &default_value); ap; ap=AP_Param::next_scalar(&token, &type, &default_value)) { if (showKeyValues) { ::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"); + default_value = NaNf; } 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 589fd09fabfedc..2b2a4094ff5528 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -430,6 +430,11 @@ class AP_Param /// static bool load_all(); + // return true if eeprom is full, used for arming check + static bool get_eeprom_full(void) { + return eeprom_full; + } + // returns storage space used: static uint16_t storage_used() { return sentinal_offset; } @@ -495,11 +500,17 @@ class AP_Param values without changing the parameter indexes. This will return true if the parameter was converted from an old parameter value */ - bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0); + bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0) { + return _convert_parameter_width(old_ptype, scale_factor, false); + } bool convert_centi_parameter(ap_var_type old_ptype) { return convert_parameter_width(old_ptype, 0.01f); } - + // Converting bitmasks should be done bitwise rather than numerically + bool convert_bitmask_parameter_width(ap_var_type old_ptype) { + return _convert_parameter_width(old_ptype, 1.0, true); + } + // convert a single parameter with scaling enum { CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion @@ -785,6 +796,13 @@ class AP_Param // return true if the parameter is configured in EEPROM/FRAM bool configured_in_storage(void) const; + /* + convert width of a parameter, allowing update to wider scalar + values without changing the parameter indexes. This will return + true if the parameter was converted from an old parameter value + */ + bool _convert_parameter_width(ap_var_type old_ptype, float scale_factor, bool bitmask); + // send a parameter to all GCS instances void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const; @@ -852,6 +870,8 @@ class AP_Param }; static defaults_list *default_list; static void check_default(AP_Param *ap, float *default_value); + + static bool eeprom_full; }; namespace AP { diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp index 428f589b892700..54c5453bfb0c0b 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp @@ -209,7 +209,6 @@ void AP_PiccoloCAN::loop() uint16_t ecuCmdRateMs = 1000 / _ecu_hz; #endif - uint64_t timeout = AP_HAL::micros64() + 250ULL; // 1ms loop delay hal.scheduler->delay_microseconds(1000); @@ -235,7 +234,7 @@ void AP_PiccoloCAN::loop() #endif // Look for any message responses on the CAN bus - while (read_frame(rxFrame, timeout)) { + while (read_frame(rxFrame, 0)) { // Extract group and device ID values from the frame identifier frame_id_group = (rxFrame.id >> 24) & 0x1F; @@ -276,7 +275,7 @@ void AP_PiccoloCAN::loop() } // write frame on CAN bus, returns true on success -bool AP_PiccoloCAN::write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout) +bool AP_PiccoloCAN::write_frame(AP_HAL::CANFrame &out_frame, uint32_t timeout_us) { if (!_initialized) { debug_can(AP_CANManager::LOG_ERROR, "PiccoloCAN: Driver not initialized for write_frame\n\r"); @@ -285,26 +284,27 @@ bool AP_PiccoloCAN::write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout) bool read_select = false; bool write_select = true; - - bool ret = _can_iface->select(read_select, write_select, &out_frame, timeout); + const uint64_t deadline_us = AP_HAL::micros64() + timeout_us; + bool ret = _can_iface->select(read_select, write_select, &out_frame, deadline_us); if (!ret || !write_select) { return false; } - return (_can_iface->send(out_frame, timeout, AP_HAL::CANIface::AbortOnError) == 1); + return (_can_iface->send(out_frame, deadline_us, AP_HAL::CANIface::AbortOnError) == 1); } // read frame on CAN bus, returns true on succses -bool AP_PiccoloCAN::read_frame(AP_HAL::CANFrame &recv_frame, uint64_t timeout) +bool AP_PiccoloCAN::read_frame(AP_HAL::CANFrame &recv_frame, uint32_t timeout_us) { if (!_initialized) { debug_can(AP_CANManager::LOG_ERROR, "PiccoloCAN: Driver not initialized for read_frame\n\r"); return false; } + bool read_select = true; bool write_select = false; - bool ret = _can_iface->select(read_select, write_select, nullptr, timeout); + bool ret = _can_iface->select(read_select, write_select, nullptr, AP_HAL::micros64() + timeout_us); if (!ret || !read_select) { // No frame available @@ -409,8 +409,6 @@ void AP_PiccoloCAN::send_servo_messages(void) { AP_HAL::CANFrame txFrame {}; - uint64_t timeout = AP_HAL::micros64() + 1000ULL; - // No servos are selected? Don't send anything! if (_srv_bm == 0x00) { return; @@ -445,7 +443,7 @@ void AP_PiccoloCAN::send_servo_messages(void) // Servo is not enabled encodeServo_EnablePacket(&txFrame); txFrame.id |= (idx + 1); - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } else if (_servos[idx].newCommand) { // A new command is provided send_cmd = true; @@ -467,7 +465,7 @@ void AP_PiccoloCAN::send_servo_messages(void) // Broadcast the command to all servos txFrame.id |= 0xFF; - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } } } @@ -478,8 +476,6 @@ void AP_PiccoloCAN::send_esc_messages(void) { AP_HAL::CANFrame txFrame {}; - uint64_t timeout = AP_HAL::micros64() + 1000ULL; - // No ESCs are selected? Don't send anything if (_esc_bm == 0x00) { return; @@ -515,7 +511,7 @@ void AP_PiccoloCAN::send_esc_messages(void) if (is_esc_present(idx) && !is_esc_enabled(idx)) { encodeESC_EnablePacket(&txFrame); txFrame.id |= (idx + 1); - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } else if (_escs[idx].newCommand) { send_cmd = true; @@ -540,7 +536,7 @@ void AP_PiccoloCAN::send_esc_messages(void) // Broadcast the command to all ESCs txFrame.id |= 0xFF; - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } } @@ -553,7 +549,7 @@ void AP_PiccoloCAN::send_esc_messages(void) // Set the ESC address to the broadcast ID (0xFF) txFrame.id |= 0xFF; - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } } @@ -609,8 +605,6 @@ 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; @@ -622,7 +616,7 @@ void AP_PiccoloCAN::send_ecu_messages(void) _ecu_info.newCommand = false; - write_frame(txFrame, timeout); + write_frame(txFrame, 1000); } } @@ -687,26 +681,26 @@ bool AP_PiccoloCAN::is_esc_channel_active(uint8_t chan) /** * Determine if a servo is present on the CAN bus (has telemetry data been received) */ -bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint64_t timeout_ms) +bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint32_t timeout_us) { if (chan >= PICCOLO_CAN_MAX_NUM_SERVO) { return false; } - return _servos[chan].is_connected(timeout_ms); + return _servos[chan].is_connected(timeout_us); } /** * Determine if an ESC is present on the CAN bus (has telemetry data been received) */ -bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms) +bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint32_t timeout_us) { if (chan >= PICCOLO_CAN_MAX_NUM_ESC) { return false; } - return _escs[chan].is_connected(timeout_ms); + return _escs[chan].is_connected(timeout_us); } diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h index 3615f3db4fa29c..7353de1c034ed2 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h @@ -63,10 +63,10 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend bool is_esc_channel_active(uint8_t chan); // return true if a particular servo has been detected on the CAN interface - bool is_servo_present(uint8_t chan, uint64_t timeout_ms = 2000); + bool is_servo_present(uint8_t chan, uint32_t timeout_us = 2000000); // return true if a particular ESC has been detected on the CAN interface - bool is_esc_present(uint8_t chan, uint64_t timeout_ms = 2000); + bool is_esc_present(uint8_t chan, uint32_t timeout_us = 2000000); // return true if a particular servo is enabled bool is_servo_enabled(uint8_t chan); @@ -83,10 +83,10 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend void loop(); // write frame on CAN bus, returns true on success - bool write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout); + bool write_frame(AP_HAL::CANFrame &out_frame, uint32_t timeout_us); // read frame on CAN bus, returns true on succses - bool read_frame(AP_HAL::CANFrame &recv_frame, uint64_t timeout); + bool read_frame(AP_HAL::CANFrame &recv_frame, uint32_t timeout_us); // send ESC commands over CAN void send_esc_messages(void); diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN_Device.h b/libraries/AP_PiccoloCAN/AP_PiccoloCAN_Device.h index fff6e175395688..23cea2b24f7f94 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN_Device.h +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN_Device.h @@ -58,10 +58,10 @@ class AP_PiccoloCAN_Device virtual bool is_enabled(void) const { return false; } // Determine if this device has been seen within a specified timeframe - virtual bool is_connected(int64_t timeout_ms) const { + virtual bool is_connected(uint32_t timeout_us) const { uint64_t now = AP_HAL::micros64(); - return now < (last_msg_timestamp + (1000ULL * timeout_ms)); + return now < (last_msg_timestamp + timeout_us); } // Reset the received message timestamp diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 753b7eb0bc030f..1ba08b6228906b 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -153,7 +153,7 @@ void AP_Proximity::init() case Type::RPLidarA2: if (AP_Proximity_RPLidarA2::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_RPLidarA2(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_RPLidarA2(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -161,14 +161,14 @@ void AP_Proximity::init() #if AP_PROXIMITY_MAV_ENABLED case Type::MAV: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_MAV(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_MAV(*this, state[instance], params[instance]); break; #endif #if AP_PROXIMITY_TERARANGERTOWER_ENABLED case Type::TRTOWER: if (AP_Proximity_TeraRangerTower::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_TeraRangerTower(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_TeraRangerTower(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -177,7 +177,7 @@ void AP_Proximity::init() case Type::TRTOWEREVO: if (AP_Proximity_TeraRangerTowerEvo::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_TeraRangerTowerEvo(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_TeraRangerTowerEvo(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -185,14 +185,14 @@ void AP_Proximity::init() #if AP_PROXIMITY_RANGEFINDER_ENABLED case Type::RangeFinder: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_RangeFinder(*this, state[instance], params[instance]); break; #endif #if AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED case Type::SF40C: if (AP_Proximity_LightWareSF40C::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_LightWareSF40C(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_LightWareSF40C(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -201,7 +201,7 @@ void AP_Proximity::init() case Type::SF45B: if (AP_Proximity_LightWareSF45B::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_LightWareSF45B(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_LightWareSF45B(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -210,7 +210,7 @@ void AP_Proximity::init() case Type::CYGBOT_D1: if (AP_Proximity_Cygbot_D1::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_Cygbot_D1(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_Cygbot_D1(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; @@ -223,32 +223,32 @@ void AP_Proximity::init() #if AP_PROXIMITY_SCRIPTING_ENABLED case Type::Scripting: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_Scripting(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_Scripting(*this, state[instance], params[instance]); break; #endif #if AP_PROXIMITY_MR72_ENABLED case Type::MR72: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_MR72_CAN(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_MR72_CAN(*this, state[instance], params[instance]); break; # endif #if AP_PROXIMITY_SITL_ENABLED case Type::SITL: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_SITL(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_SITL(*this, state[instance], params[instance]); break; #endif #if AP_PROXIMITY_AIRSIMSITL_ENABLED case Type::AirSimSITL: state[instance].instance = instance; - drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance], params[instance]); + drivers[instance] = NEW_NOTHROW AP_Proximity_AirSimSITL(*this, state[instance], params[instance]); break; #endif #if AP_PROXIMITY_LD06_ENABLED case Type::LD06: if (AP_Proximity_LD06::detect(serial_instance)) { state[instance].instance = instance; - drivers[instance] = new AP_Proximity_LD06(*this, state[instance], params[instance], serial_instance); + drivers[instance] = NEW_NOTHROW AP_Proximity_LD06(*this, state[instance], params[instance], serial_instance); serial_instance++; } break; diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index 09f751491ea18d..430890fda1e94b 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -32,15 +32,11 @@ ObjectBuffer_TS AP_Proximity_DroneCAN::item //links the Proximity DroneCAN message to this backend -void AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("measurement_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, driver_index) != nullptr); } //Method to find the backend relating to the node id @@ -85,7 +81,7 @@ AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_dronecan_backend(AP_DroneCAN* //it up as DroneCAN type return nullptr; } - prx->drivers[i] = new AP_Proximity_DroneCAN(*prx, prx->state[i], prx->params[i]); + prx->drivers[i] = NEW_NOTHROW AP_Proximity_DroneCAN(*prx, prx->state[i], prx->params[i]); driver = (AP_Proximity_DroneCAN*)prx->drivers[i]; if (driver == nullptr) { break; diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index deee2b77df1eaf..db9f06094e0b7d 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -21,11 +21,9 @@ class AP_Proximity_DroneCAN : public AP_Proximity_Backend float distance_max() const override; float distance_min() const override; + static AP_Proximity_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); - static AP_Proximity_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); - - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg); diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp index 47e0e28e8e1d43..1911ea9126d2e3 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp @@ -99,11 +99,11 @@ void AP_Proximity_LightWareSF45B::process_replies() // process up to 1K of characters per iteration uint32_t nbytes = MIN(_uart->available(), 1024U); while (nbytes-- > 0) { - const int16_t r = _uart->read(); - if ((r < 0) || (r > 0xFF)) { + uint8_t c; + if (!_uart->read(c)) { continue; } - if (parse_byte((uint8_t)r)) { + if (parse_byte(c)) { process_message(); } } diff --git a/libraries/AP_Proximity/AP_Proximity_MR72_CAN.cpp b/libraries/AP_Proximity/AP_Proximity_MR72_CAN.cpp index 9d9618286c5b5f..2f762be1c8c790 100644 --- a/libraries/AP_Proximity/AP_Proximity_MR72_CAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MR72_CAN.cpp @@ -37,7 +37,7 @@ AP_Proximity_MR72_CAN::AP_Proximity_MR72_CAN(AP_Proximity &_frontend, AP_Proximity_Params& _params): AP_Proximity_Backend(_frontend, _state, _params) { - multican_MR72 = new MultiCAN{FUNCTOR_BIND_MEMBER(&AP_Proximity_MR72_CAN::handle_frame, bool, AP_HAL::CANFrame &), AP_CAN::Protocol::NanoRadar, "MR72 MultiCAN"}; + multican_MR72 = NEW_NOTHROW MultiCAN{FUNCTOR_BIND_MEMBER(&AP_Proximity_MR72_CAN::handle_frame, bool, AP_HAL::CANFrame &), AP_CAN::Protocol::NanoRadar, "MR72 MultiCAN"}; if (multican_MR72 == nullptr) { AP_BoardConfig::allocation_error("Failed to create proximity multican"); } @@ -117,6 +117,7 @@ bool AP_Proximity_MR72_CAN::parse_distance_message(AP_HAL::CANFrame &frame) const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(yaw); _temp_boundary.add_distance(face, yaw, objects_dist); + database_push(yaw, objects_dist); return true; } diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index b87ab8b049418b..fc31ef40f544b9 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -43,7 +43,7 @@ #include #if RP_DEBUG_LEVEL - #define Debug(level, fmt, args ...) do { if (level <= RP_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0) + #define Debug(level, fmt, args ...) do { if (level <= RP_DEBUG_LEVEL) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } } while (0) #else #define Debug(level, fmt, args ...) #endif @@ -252,7 +252,7 @@ void AP_Proximity_RPLidarA2::get_readings() Debug(1, "Got RPLidar Information"); char xbuffer[64]{}; memcpy((void*)xbuffer, (void*)&_payload.information, 63); - gcs().send_text(MAV_SEVERITY_INFO, "RPLidar: (%s)", xbuffer); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RPLidar: (%s)", xbuffer); #endif // 63 is the magic number of bytes in the spewed-out // reset data ... so now we'll just drop that stuff on diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index f467045035b323..4fe6fb6db07f85 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -65,8 +65,8 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data() int16_t nbytes = _uart->available(); while (nbytes-- > 0) { - int16_t c = _uart->read(); - if (c==-1) { + uint8_t c; + if (!_uart->read(c)) { return false; } if (char(c) == 'T' ) { diff --git a/libraries/AP_Quicktune/AP_Quicktune.cpp b/libraries/AP_Quicktune/AP_Quicktune.cpp new file mode 100644 index 00000000000000..c8c5e5a5e573c4 --- /dev/null +++ b/libraries/AP_Quicktune/AP_Quicktune.cpp @@ -0,0 +1,689 @@ +/* + C++ implementation of quicktune based on original lua script + */ + +// quicktune is not performance sensitive, save flash +#pragma GCC optimize("Os") + +#include "AP_Quicktune.h" + +#if AP_QUICKTUNE_ENABLED + +#define UPDATE_RATE_HZ 40 +#define STAGE_DELAY 4000 +#define PILOT_INPUT_DELAY 4000 +#define YAW_FLTE_MAX 2.0 +#define FLTD_MUL 0.5 +#define FLTT_MUL 0.5 +#define DEFAULT_SMAX 50.0 +#define OPTIONS_TWO_POSITION (1<<0) + +#include +#include +#include +#include +#include +#include + +const AP_Param::GroupInfo AP_Quicktune::var_info[] = { + // @Param: ENABLE + // @DisplayName: Quicktune enable + // @Description: Enable quicktune system + // @Values: 0:Disabled,1:Enabled + // @User: Standard + AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Quicktune, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: AXES + // @DisplayName: Quicktune axes + // @Description: Axes to tune + // @Bitmask: 0:Roll,1:Pitch,2:Yaw + // @User: Standard + AP_GROUPINFO("AXES", 2, AP_Quicktune, axes_enabled, 7), + + // @Param: DOUBLE_TIME + // @DisplayName: Quicktune doubling time + // @Description: Time to double a tuning parameter. Raise this for a slower tune. + // @Range: 5 20 + // @Units: s + // @User: Standard + AP_GROUPINFO("DOUBLE_TIME", 3, AP_Quicktune, double_time, 10), + + // @Param: GAIN_MARGIN + // @DisplayName: Quicktune gain margin + // @Description: Reduction in gain after oscillation detected. Raise this number to get a more conservative tune + // @Range: 20 80 + // @Units: % + // @User: Standard + AP_GROUPINFO("GAIN_MARGIN", 4, AP_Quicktune, gain_margin, 60), + + // @Param: OSC_SMAX + // @DisplayName: Quicktune oscillation rate threshold + // @Description: Threshold for oscillation detection. A lower value will lead to a more conservative tune. + // @Range: 1 10 + // @User: Standard + AP_GROUPINFO("OSC_SMAX", 5, AP_Quicktune, osc_smax, 4), + + // @Param: YAW_P_MAX + // @DisplayName: Quicktune Yaw P max + // @Description: Maximum value for yaw P gain + // @Range: 0.1 3 + // @User: Standard + AP_GROUPINFO("YAW_P_MAX", 6, AP_Quicktune, yaw_p_max, 0.5), + + // @Param: YAW_D_MAX + // @DisplayName: Quicktune Yaw D max + // @Description: Maximum value for yaw D gain + // @Range: 0.001 1 + // @User: Standard + AP_GROUPINFO("YAW_D_MAX", 7, AP_Quicktune, yaw_d_max, 0.01), + + // @Param: RP_PI_RATIO + // @DisplayName: Quicktune roll/pitch PI ratio + // @Description: Ratio between P and I gains for roll and pitch. Raise this to get a lower I gain + // @Range: 1.0 2.0 + // @User: Standard + AP_GROUPINFO("RP_PI_RATIO", 8, AP_Quicktune, rp_pi_ratio, 1.0), + + // @Param: Y_PI_RATIO + // @DisplayName: Quicktune Yaw PI ratio + // @Description: Ratio between P and I gains for yaw. Raise this to get a lower I gain + // @Range: 1.0 20 + // @User: Standard + AP_GROUPINFO("Y_PI_RATIO", 9, AP_Quicktune, y_pi_ratio, 10), + + // @Param: AUTO_FILTER + // @DisplayName: Quicktune auto filter enable + // @Description: When enabled the PID filter settings are automatically set based on INS_GYRO_FILTER + // @Values: 0:Disabled,1:Enabled + // @User: Standard + AP_GROUPINFO("AUTO_FILTER", 10, AP_Quicktune, auto_filter, 1), + + // @Param: AUTO_SAVE + // @DisplayName: Quicktune auto save + // @Description: Number of seconds after completion of tune to auto-save. This is useful when using a 2 position switch for quicktune. Zero (the default value) disables automatic saving, and you will need to have a 3 position switch to save or use GCS auxilliary functions. + // @Units: s + // @User: Standard + AP_GROUPINFO("AUTO_SAVE", 11, AP_Quicktune, auto_save, 0), + + // @Param: REDUCE_MAX + // @DisplayName: Quicktune maximum gain reduction + // @Description: This controls how much quicktune is allowed to lower gains from the original gains. If the vehicle already has a reasonable tune and is not oscillating then you can set this to zero to prevent gain reductions. The default of 20% is reasonable for most vehicles. Using a maximum gain reduction lowers the chance of an angle P oscillation happening if quicktune gets a false positive oscillation at a low gain, which can result in very low rate gains and a dangerous angle P oscillation. + // @Units: % + // @Range: 0 100 + // @User: Standard + AP_GROUPINFO("REDUCE_MAX", 12, AP_Quicktune, reduce_max, 20), + + // @Param: OPTIONS + // @DisplayName: Quicktune options + // @Description: Additional options. When the Two Position Switch option is enabled then a high switch position will start the tune, low will disable the tune. you should also set a QUIK_AUTO_SAVE time so that you will be able to save the tune. + // @Bitmask: 0:UseTwoPositionSwitch + // @User: Standard + AP_GROUPINFO("OPTIONS", 13, AP_Quicktune, options, 0), + + // @Param: ANGLE_MAX + // @DisplayName: maximum angle error for tune abort + // @Description: If while tuning the angle error goes over this limit then the tune will aborts to prevent a bad oscillation in the case of the tuning algorithm failing. If you get an error "Quicktune: attitude error ABORTING" and you think it is a false positive then you can either raise this parameter or you can try increasing the QWIK_DOUBLE_TIME to do the tune more slowly. + // @Units: deg + // @User: Standard + AP_GROUPINFO("ANGLE_MAX", 14, AP_Quicktune, angle_max, 10), + + AP_GROUPEND +}; + +// Call at loop rate +void AP_Quicktune::update(bool mode_supports_quicktune) +{ + if (enable < 1) { + if (need_restore) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "QuickTune disabled"); + abort_tune(); + } + return; + } + const uint32_t now = AP_HAL::millis(); + + if (!mode_supports_quicktune) { + /* + user has switched to a non-quicktune mode. If we have + pending parameter changes then revert + */ + if (need_restore) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "QuickTune aborted"); + } + abort_tune(); + return; + } + + if (need_restore) { + const float att_error = AC_AttitudeControl::get_singleton()->get_att_error_angle_deg(); + if (angle_max > 0 && att_error > angle_max) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Quicktune: attitude error %.1fdeg - ABORTING", att_error); + abort_tune(); + return; + } + } + + if (have_pilot_input()) { + last_pilot_input_ms = now; + } + + SwitchPos sw_pos_tune = SwitchPos::MID; + SwitchPos sw_pos_save = SwitchPos::HIGH; + if ((options & OPTIONS_TWO_POSITION) != 0) { + sw_pos_tune = SwitchPos::HIGH; + sw_pos_save = SwitchPos::NONE; + } + + const auto &vehicle = *AP::vehicle(); + + if (sw_pos == sw_pos_tune && + (!hal.util->get_soft_armed() || !vehicle.get_likely_flying())) { + if (now - last_warning_ms > 5000) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Quicktune: Must be flying to tune"); + last_warning_ms = now; + } + return; + } + if (sw_pos == SwitchPos::LOW || !hal.util->get_soft_armed() || !vehicle.get_likely_flying()) { + // Abort, revert parameters + if (need_restore) { + need_restore = false; + restore_all_params(); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Quicktune: Reverted"); + tune_done_time_ms = 0; + } + reset_axes_done(); + return; + } + if (sw_pos == sw_pos_save) { + // Save all params + if (need_restore) { + need_restore = false; + save_all_params(); + } + } + if (sw_pos != sw_pos_tune) { + return; + } + + if (now - last_stage_change_ms < STAGE_DELAY) { + // Update slew gain + if (slew_parm != Param::END) { + const float P = get_param_value(slew_parm); + const AxisName axis = get_axis(slew_parm); + adjust_gain(slew_parm, P+slew_delta); + slew_steps = slew_steps - 1; + Write_QWIK(get_slew_rate(axis), P, slew_parm); + if (slew_steps == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %.4f", get_param_name(slew_parm), P); + slew_parm = Param::END; + if (get_current_axis() == AxisName::DONE) { + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Quicktune: DONE"); + tune_done_time_ms = now; + } + } + } + return; + } + + const AxisName axis = get_current_axis(); + + if (axis == AxisName::DONE) { + // Nothing left to do, check autosave time + if (tune_done_time_ms != 0 && auto_save > 0) { + if (now - tune_done_time_ms > (auto_save*1000)) { + need_restore = false; + save_all_params(); + tune_done_time_ms = 0; + } + } + return; + } + + if (!need_restore) { + need_restore = true; + // We are just starting tuning, get current values + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Quicktune: Starting tune"); + // Get all params + for (uint8_t p = 0; p < uint8_t(Param::END); p++) { + param_saved[p] = get_param_value(Param(p)); + } + // Set up SMAX + const Param is[3] { Param::RLL_SMAX, Param::PIT_SMAX, Param::YAW_SMAX }; + for (const auto p : is) { + const float smax = get_param_value(p); + if (smax <= 0) { + adjust_gain(p, DEFAULT_SMAX); + } + } + } + + if (now - last_pilot_input_ms < PILOT_INPUT_DELAY) { + return; + } + + if (!BIT_IS_SET(filters_done, uint8_t(axis))) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting %s tune", get_axis_name(axis)); + setup_filters(axis); + } + + const Param pname = get_pname(axis, current_stage); + const float pval = get_param_value(pname); + const float limit = gain_limit(pname); + const bool limited = (limit > 0.0 && pval >= limit); + const float srate = get_slew_rate(axis); + const bool oscillating = srate > osc_smax; + + // Check if reached limit + if (limited || oscillating) { + float reduction = (100.0-gain_margin)*0.01; + if (!oscillating) { + reduction = 1.0; + } + float new_gain = pval * reduction; + if (limit > 0.0 && new_gain > limit) { + new_gain = limit; + } + float old_gain = param_saved[uint8_t(pname)]; + if (new_gain < old_gain && (pname == Param::PIT_D || pname == Param::RLL_D)) { + // 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 + const float ratio = fmaxf(new_gain / old_gain, 0.5); + const uint8_t P_TO_D_OFS = uint8_t(Param::RLL_D) - uint8_t(Param::RLL_P); + const Param P_name = Param(uint8_t(pname)-P_TO_D_OFS); //from D to P + const float old_pval = get_param_value(P_name);; + const float new_pval = old_pval * ratio; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Adjusting %s %.3f -> %.3f", get_param_name(P_name), old_pval, new_pval); + adjust_gain_limited(P_name, new_pval); + } + // Set up slew gain + slew_parm = pname; + const float slew_target = limit_gain(pname, new_gain); + slew_steps = UPDATE_RATE_HZ/2; + slew_delta = (slew_target - get_param_value(pname)) / slew_steps; + + Write_QWIK(srate, pval, pname); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Quicktune: %s done", get_param_name(pname)); + advance_stage(axis); + last_stage_change_ms = now; + } else { + float new_gain = pval*get_gain_mul(); + // cope with the gain starting at zero (some users with have a zero D gain) + new_gain = MAX(new_gain, 0.0001); + adjust_gain_limited(pname, new_gain); + Write_QWIK(srate, pval, pname); + if (now - last_gain_report_ms > 3000U) { + last_gain_report_ms = now; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %.4f sr:%.2f", get_param_name(pname), new_gain, srate); + } + } +} + +/* + abort the tune if it has started + */ +void AP_Quicktune::abort_tune() +{ + if (need_restore) { + need_restore = false; + restore_all_params(); + } + tune_done_time_ms = 0; + reset_axes_done(); + sw_pos = SwitchPos::LOW; +} + +void AP_Quicktune::update_switch_pos(const RC_Channel::AuxSwitchPos ch_flag) +{ + sw_pos = SwitchPos(ch_flag); +} + +void AP_Quicktune::reset_axes_done() +{ + axes_done = 0; + filters_done = 0; + current_stage = Stage::D; +} + +void AP_Quicktune::setup_filters(AP_Quicktune::AxisName axis) +{ + if (auto_filter <= 0) { + BIT_SET(filters_done, uint8_t(axis)); + return; + } + AP_InertialSensor *imu = AP_InertialSensor::get_singleton(); + if (imu == nullptr) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } + const float gyro_filter = imu->get_gyro_filter_hz(); + adjust_gain(get_pname(axis, Stage::FLTT), gyro_filter * FLTT_MUL); + adjust_gain(get_pname(axis, Stage::FLTD), gyro_filter * FLTD_MUL); + + if (axis == AxisName::YAW) { + const float FLTE = get_param_value(Param::YAW_FLTE); + if (FLTE < 0.0 || FLTE > YAW_FLTE_MAX) { + adjust_gain(Param::YAW_FLTE, YAW_FLTE_MAX); + } + } + BIT_SET(filters_done, uint8_t(axis)); +} + +// Check for pilot input to pause tune +bool AP_Quicktune::have_pilot_input() const +{ + auto &RC = rc(); + const float roll = RC.get_roll_channel().norm_input_dz(); + const float pitch = RC.get_pitch_channel().norm_input_dz(); + const float yaw = RC.get_yaw_channel().norm_input_dz(); + + if (fabsf(roll) > 0 || fabsf(pitch) > 0 || fabsf(yaw) > 0) { + return true; + } + return false; +} + +// Get the axis name we are working on, or DONE for all done +AP_Quicktune::AxisName AP_Quicktune::get_current_axis() const +{ + for (int8_t i = 0; i < int8_t(AxisName::DONE); i++) { + if (BIT_IS_SET(axes_enabled, i) && !BIT_IS_SET(axes_done, i)) { + return AxisName(i); + } + } + return AxisName::DONE; +} + +// get the AC_PID object for an axis +AC_PID *AP_Quicktune::get_axis_pid(AP_Quicktune::AxisName axis) const +{ + auto &attitude_control = *AC_AttitudeControl::get_singleton(); + switch(axis) { + case AxisName::RLL: + return &attitude_control.get_rate_roll_pid(); + case AxisName::PIT: + return &attitude_control.get_rate_pitch_pid(); + case AxisName::YAW: + return &attitude_control.get_rate_yaw_pid(); + default: + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + break; + } + return nullptr; +} + +// get slew rate parameter for an axis +float AP_Quicktune::get_slew_rate(AP_Quicktune::AxisName axis) const +{ + auto *pid = get_axis_pid(axis); + if (pid == nullptr) { + return 0; + } + return pid->get_pid_info().slew_rate; +} + +// Move to next stage of tune +void AP_Quicktune::advance_stage(AP_Quicktune::AxisName axis) +{ + if (current_stage == Stage::D) { + current_stage = Stage::P; + } else { + BIT_SET(axes_done, uint8_t(axis)); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Quicktune: %s done", get_axis_name(axis)); + current_stage = Stage::D; + } +} + +void AP_Quicktune::adjust_gain(AP_Quicktune::Param param, float value) +{ + need_restore = true; + BIT_SET(param_changed, uint8_t(param)); + set_param_value(param, value); + + if (get_stage(param) == Stage::P) { + // Also change I gain + const uint8_t P_TO_I_OFS = uint8_t(Param::RLL_I) - uint8_t(Param::RLL_P); + const uint8_t P_TO_FF_OFS = uint8_t(Param::RLL_FF) - uint8_t(Param::RLL_P); + const Param iname = Param(uint8_t(param)+P_TO_I_OFS); + const Param ffname = Param(uint8_t(param)+P_TO_FF_OFS); + float FF = get_param_value(ffname); + if (FF > 0) { + // If we have any FF on an axis then we don't couple I to P, + // usually we want I = FF for a one second time constant for trim + return; + } + BIT_SET(param_changed, uint8_t(iname)); + + // Work out ratio of P to I that we want + float pi_ratio = rp_pi_ratio; + if (get_axis(param) == AxisName::YAW) { + pi_ratio = y_pi_ratio; + } + if (pi_ratio >= 1) { + set_param_value(iname, value/pi_ratio); + } + } + +} + +void AP_Quicktune::adjust_gain_limited(AP_Quicktune::Param param, float value) +{ + adjust_gain(param, limit_gain(param, value)); +} + +float AP_Quicktune::limit_gain(AP_Quicktune::Param param, float value) +{ + const float saved_value = param_saved[uint8_t(param)]; + if (reduce_max >= 0 && reduce_max < 100 && saved_value > 0) { + // Check if we exceeded gain reduction + const float reduction_pct = 100.0 * (saved_value - value) / saved_value; + if (reduction_pct > reduce_max) { + const float new_value = saved_value * (100 - reduce_max) * 0.01; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Limiting %s %.3f -> %.3f", get_param_name(param), value, new_value); + value = new_value; + } + } + return value; +} + +const char* AP_Quicktune::get_param_name(AP_Quicktune::Param param) const +{ + switch (param) + { + case Param::RLL_P: + return "Roll P"; + case Param::RLL_I: + return "Roll I"; + case Param::RLL_D: + return "Roll D"; + case Param::PIT_P: + return "Pitch P"; + case Param::PIT_I: + return "Pitch I"; + case Param::PIT_D: + return "Pitch D"; + case Param::YAW_P: + return "Yaw P"; + case Param::YAW_I: + return "Yaw I"; + case Param::YAW_D: + return "Yaw D"; + default: + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return "UNK"; + } +} + +float AP_Quicktune::get_gain_mul() const +{ + return expf(logf(2.0)/(UPDATE_RATE_HZ*MAX(1,double_time))); +} + +void AP_Quicktune::restore_all_params() +{ + for (uint8_t p = 0; p < uint8_t(Param::END); p++) { + const auto param = Param(p); + if (BIT_IS_SET(param_changed, p)) { + set_param_value(param, param_saved[p]); + BIT_CLEAR(param_changed, p); + } + } +} + +void AP_Quicktune::save_all_params() +{ + for (uint8_t p = 0; p < uint8_t(Param::END); p++) { + const auto param = Param(p); + set_and_save_param_value(param, get_param_value(param)); + param_saved[p] = get_param_value(param); + BIT_CLEAR(param_changed, p); + } + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Quicktune: Saved"); +} + +AP_Quicktune::Param AP_Quicktune::get_pname(AP_Quicktune::AxisName axis, AP_Quicktune::Stage stage) const +{ + const uint8_t axis_offset = uint8_t(axis) * param_per_axis; + switch (stage) + { + case Stage::P: + return Param(uint8_t(Param::RLL_P) + axis_offset); + case Stage::D: + return Param(uint8_t(Param::RLL_D) + axis_offset); + case Stage::FLTT: + return Param(uint8_t(Param::RLL_FLTT) + axis_offset); + case Stage::FLTD: + return Param(uint8_t(Param::RLL_FLTD) + axis_offset); + default: + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return Param::END; + } +} + +AP_Quicktune::Stage AP_Quicktune::get_stage(AP_Quicktune::Param param) const +{ + if (param == Param::RLL_P || param == Param::PIT_P || param == Param::YAW_P) { + return Stage::P; + } else { + return Stage::END; //Means "anything but P gain" + } +} + +AP_Float *AP_Quicktune::get_param_pointer(AP_Quicktune::Param param) const +{ + const AxisName axis = get_axis(param); + auto *pid = get_axis_pid(axis); + if (pid == nullptr) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return nullptr; + } + const Param roll_param = Param(uint8_t(param) % param_per_axis); + switch (roll_param) + { + case Param::RLL_P: + return &pid->kP(); + case Param::RLL_I: + return &pid->kI(); + case Param::RLL_D: + return &pid->kD(); + case Param::RLL_SMAX: + return &pid->slew_limit(); + case Param::RLL_FLTT: + return &pid->filt_T_hz(); + case Param::RLL_FLTD: + return &pid->filt_D_hz(); + case Param::RLL_FLTE: + return &pid->filt_E_hz(); + case Param::RLL_FF: + return &pid->ff(); + default: + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return nullptr; + } +} + +float AP_Quicktune::get_param_value(AP_Quicktune::Param param) const +{ + AP_Float *ptr = get_param_pointer(param); + if (ptr != nullptr) { + return ptr->get(); + } + return 0.0; +} + +void AP_Quicktune::set_param_value(AP_Quicktune::Param param, float value) +{ + AP_Float *ptr = get_param_pointer(param); + if (ptr != nullptr) { + ptr->set(value); + } +} + +void AP_Quicktune::set_and_save_param_value(AP_Quicktune::Param param, float value) +{ + AP_Float *ptr = get_param_pointer(param); + if (ptr != nullptr) { + ptr->set_and_save(value); + } +} + +AP_Quicktune::AxisName AP_Quicktune::get_axis(AP_Quicktune::Param param) const +{ + if (param >= Param::END) { + return AxisName::END; + } + return AxisName(uint8_t(param) / param_per_axis); +} + +const char* AP_Quicktune::get_axis_name(AP_Quicktune::AxisName axis) const +{ + switch (axis) + { + case AxisName::RLL: + return "Roll"; + case AxisName::PIT: + return "Pitch"; + case AxisName::YAW: + return "Yaw"; + default: + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return "UNK"; + } +} + +float AP_Quicktune::gain_limit(AP_Quicktune::Param param) const +{ + if (get_axis(param) == AxisName::YAW) { + if (param == Param::YAW_P) { + return yaw_p_max; + } + if (param == Param::YAW_D) { + return yaw_d_max; + } + } + return 0.0; +} + + +// @LoggerMessage: QWIK +// @Description: Quicktune +// @Field: TimeUS: Time since system startup +// @Field: ParamNo: number of parameter being tuned +// @Field: SRate: slew rate +// @Field: Gain: test gain for current axis and PID element +// @Field: Param: name of parameter being being tuned +void AP_Quicktune::Write_QWIK(float srate, float gain, AP_Quicktune::Param param) +{ +#if HAL_LOGGING_ENABLED + AP::logger().WriteStreaming("QWIK","TimeUS,ParamNo,SRate,Gain,Param", "s#---", "-----", "QBffN", + AP_HAL::micros64(), + unsigned(param), + srate, + gain, + get_param_name(param)); +#endif +} + +#endif //AP_QUICKTUNE_ENABLED diff --git a/libraries/AP_Quicktune/AP_Quicktune.h b/libraries/AP_Quicktune/AP_Quicktune.h new file mode 100644 index 00000000000000..5c495a9e010acd --- /dev/null +++ b/libraries/AP_Quicktune/AP_Quicktune.h @@ -0,0 +1,167 @@ +#pragma once + +#include + +#ifndef AP_QUICKTUNE_ENABLED +#define AP_QUICKTUNE_ENABLED 1 // NOTE: may be disabled by vehicle header +#endif + +#if AP_QUICKTUNE_ENABLED + +#include +#include +#include + +class AP_Quicktune { +public: + AP_Quicktune() + { + AP_Param::setup_object_defaults(this, var_info); + } + + // Empty destructor to suppress compiler warning + virtual ~AP_Quicktune() {} + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Quicktune); + + // Parameter block + static const struct AP_Param::GroupInfo var_info[]; + + void update(bool mode_supports_quicktune); + void update_switch_pos(const RC_Channel::AuxSwitchPos ch_flag); + +private: + + // Parameters + AP_Int8 enable; + AP_Int8 axes_enabled; + AP_Float double_time; + AP_Float gain_margin; + AP_Float osc_smax; + AP_Float yaw_p_max; + AP_Float yaw_d_max; + AP_Float rp_pi_ratio; + AP_Float y_pi_ratio; + AP_Int8 auto_filter; + AP_Float auto_save; + AP_Float reduce_max; + AP_Int16 options; + AP_Int8 angle_max; + + // Low, Mid and High must be in the same positions as they are in RC_Channel::AuxSwitchPos + enum class SwitchPos : uint8_t { + LOW, + MID, + HIGH, + NONE, + }; + + + enum class AxisName : uint8_t { + RLL = 0, + PIT, + YAW, + DONE, + END, + }; + + /* + note! we rely on the enum being in the same order between axes + */ + enum class Param : uint8_t { + RLL_P = 0, + RLL_I, + RLL_D, + RLL_SMAX, + RLL_FLTT, + RLL_FLTD, + RLL_FLTE, + RLL_FF, + + PIT_P, + PIT_I, + PIT_D, + PIT_SMAX, + PIT_FLTT, + PIT_FLTD, + PIT_FLTE, + PIT_FF, + + YAW_P, + YAW_I, + YAW_D, + YAW_SMAX, + YAW_FLTT, + YAW_FLTD, + YAW_FLTE, + YAW_FF, + END, + }; + + static const uint8_t param_per_axis = uint8_t(Param::PIT_P) - uint8_t(Param::RLL_P); + static_assert(uint8_t(Param::END) == 3*param_per_axis, "AP_Quicktune Param error"); + + // Also the gains + enum class Stage : uint8_t { + D, + P, + DONE, + I, + FF, + SMAX, + FLTT, + FLTD, + FLTE, + END, + }; + + // Time keeping + uint32_t last_stage_change_ms; + uint32_t last_gain_report_ms; + uint32_t last_pilot_input_ms; + uint32_t last_warning_ms; + uint32_t tune_done_time_ms; + + // Bitmasks + uint32_t axes_done; + uint32_t filters_done; + uint32_t param_changed; //Bitmask of changed parameters + + Stage current_stage = Stage::D; + Param slew_parm = Param::END; + uint8_t slew_steps; + float slew_delta; + SwitchPos sw_pos; //Switch pos to be set by aux func + bool need_restore; + float param_saved[uint8_t(Param::END)]; //Saved values of the parameters + + void reset_axes_done(); + void setup_filters(AxisName axis); + bool have_pilot_input() const; + AxisName get_current_axis() const; + float get_slew_rate(AxisName axis) const; + void advance_stage(AxisName axis); + void adjust_gain(Param param, float value); + void adjust_gain_limited(Param param, float value); + float get_gain_mul() const; + void restore_all_params(); + void save_all_params(); + Param get_pname(AxisName axis, Stage stage) const; + AP_Float *get_param_pointer(Param param) const; + float get_param_value(Param param) const; + void set_param_value(Param param, float value); + void set_and_save_param_value(Param param, float value); + float gain_limit(Param param) const; + AxisName get_axis(Param param) const; + float limit_gain(Param param, float value); + const char* get_param_name(Param param) const; + Stage get_stage(Param param) const; + const char* get_axis_name(AxisName axis) const; + AC_PID *get_axis_pid(AxisName axis) const; + void Write_QWIK(float SRate, float Gain, Param param); + + void abort_tune(void); +}; + +#endif // AP_QUICKTUNE_ENABLED diff --git a/libraries/AP_RCMapper/AP_RCMapper.cpp b/libraries/AP_RCMapper/AP_RCMapper.cpp index fc09016e1dfcc9..39af6944ae7b8b 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.cpp +++ b/libraries/AP_RCMapper/AP_RCMapper.cpp @@ -1,3 +1,7 @@ +#include "AP_RCMapper_config.h" + +#if AP_RCMAPPER_ENABLED + #include #include "AP_RCMapper.h" @@ -75,3 +79,5 @@ RCMapper::RCMapper(void) RCMapper *AP::rcmap() { return RCMapper::get_singleton(); } + +#endif // AP_RCMAPPER_ENABLED diff --git a/libraries/AP_RCMapper/AP_RCMapper_config.h b/libraries/AP_RCMapper/AP_RCMapper_config.h index ad11cb1785b850..021ff08c2579f7 100644 --- a/libraries/AP_RCMapper/AP_RCMapper_config.h +++ b/libraries/AP_RCMapper/AP_RCMapper_config.h @@ -1,5 +1,7 @@ #pragma once +#include + #ifndef AP_RCMAPPER_ENABLED #define AP_RCMAPPER_ENABLED 1 #endif diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index b7b6bfdf945da9..f8bc3b55b385b0 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -38,6 +38,7 @@ #include "AP_RCProtocol_Joystick_SFML.h" #include "AP_RCProtocol_UDP.h" #include "AP_RCProtocol_FDM.h" +#include "AP_RCProtocol_Radio.h" #include #include @@ -48,69 +49,71 @@ extern const AP_HAL::HAL& hal; void AP_RCProtocol::init() { #if AP_RCPROTOCOL_PPMSUM_ENABLED - backend[AP_RCProtocol::PPMSUM] = new AP_RCProtocol_PPMSum(*this); + backend[AP_RCProtocol::PPMSUM] = NEW_NOTHROW AP_RCProtocol_PPMSum(*this); #endif #if AP_RCPROTOCOL_IBUS_ENABLED - backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this); + backend[AP_RCProtocol::IBUS] = NEW_NOTHROW AP_RCProtocol_IBUS(*this); #endif #if AP_RCPROTOCOL_SBUS_ENABLED - backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true, 100000); + backend[AP_RCProtocol::SBUS] = NEW_NOTHROW AP_RCProtocol_SBUS(*this, true, 100000); #endif #if AP_RCPROTOCOL_FASTSBUS_ENABLED - backend[AP_RCProtocol::FASTSBUS] = new AP_RCProtocol_SBUS(*this, true, 200000); + backend[AP_RCProtocol::FASTSBUS] = NEW_NOTHROW AP_RCProtocol_SBUS(*this, true, 200000); #endif #if AP_RCPROTOCOL_DSM_ENABLED - backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this); + backend[AP_RCProtocol::DSM] = NEW_NOTHROW AP_RCProtocol_DSM(*this); #endif #if AP_RCPROTOCOL_SUMD_ENABLED - backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this); + backend[AP_RCProtocol::SUMD] = NEW_NOTHROW AP_RCProtocol_SUMD(*this); #endif #if AP_RCPROTOCOL_SRXL_ENABLED - backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this); + backend[AP_RCProtocol::SRXL] = NEW_NOTHROW AP_RCProtocol_SRXL(*this); #endif #if AP_RCPROTOCOL_SBUS_NI_ENABLED - backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000); + backend[AP_RCProtocol::SBUS_NI] = NEW_NOTHROW AP_RCProtocol_SBUS(*this, false, 100000); #endif #if AP_RCPROTOCOL_SRXL2_ENABLED - backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this); + backend[AP_RCProtocol::SRXL2] = NEW_NOTHROW AP_RCProtocol_SRXL2(*this); #endif #if AP_RCPROTOCOL_CRSF_ENABLED - backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this); + backend[AP_RCProtocol::CRSF] = NEW_NOTHROW AP_RCProtocol_CRSF(*this); #endif #if AP_RCPROTOCOL_FPORT2_ENABLED - backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true); + backend[AP_RCProtocol::FPORT2] = NEW_NOTHROW AP_RCProtocol_FPort2(*this, true); #endif #if AP_RCPROTOCOL_ST24_ENABLED - backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this); + backend[AP_RCProtocol::ST24] = NEW_NOTHROW AP_RCProtocol_ST24(*this); #endif #if AP_RCPROTOCOL_FPORT_ENABLED - backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true); + backend[AP_RCProtocol::FPORT] = NEW_NOTHROW AP_RCProtocol_FPort(*this, true); #endif #if AP_RCPROTOCOL_DRONECAN_ENABLED - backend[AP_RCProtocol::DRONECAN] = new AP_RCProtocol_DroneCAN(*this); + backend[AP_RCProtocol::DRONECAN] = NEW_NOTHROW AP_RCProtocol_DroneCAN(*this); #endif #if AP_RCPROTOCOL_GHST_ENABLED - backend[AP_RCProtocol::GHST] = new AP_RCProtocol_GHST(*this); + backend[AP_RCProtocol::GHST] = NEW_NOTHROW AP_RCProtocol_GHST(*this); #endif #if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED - backend[AP_RCProtocol::MAVLINK_RADIO] = new AP_RCProtocol_MAVLinkRadio(*this); + backend[AP_RCProtocol::MAVLINK_RADIO] = NEW_NOTHROW AP_RCProtocol_MAVLinkRadio(*this); #endif #if AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED - backend[AP_RCProtocol::JOYSTICK_SFML] = new AP_RCProtocol_Joystick_SFML(*this); + backend[AP_RCProtocol::JOYSTICK_SFML] = NEW_NOTHROW AP_RCProtocol_Joystick_SFML(*this); #endif #if AP_RCPROTOCOL_UDP_ENABLED - const auto UDP_backend = new AP_RCProtocol_UDP(*this); + const auto UDP_backend = NEW_NOTHROW AP_RCProtocol_UDP(*this); backend[AP_RCProtocol::UDP] = UDP_backend; #endif #if AP_RCPROTOCOL_FDM_ENABLED - const auto FDM_backend = new AP_RCProtocol_FDM(*this);; + const auto FDM_backend = NEW_NOTHROW AP_RCProtocol_FDM(*this);; backend[AP_RCProtocol::FDM] = FDM_backend; #if AP_RCPROTOCOL_UDP_ENABLED // the UDP-Packed16Bit backend gives way to the FDM backend: UDP_backend->set_fdm_backend(FDM_backend); #endif // AP_RCPROTOCOL_UDP_ENABLED #endif // AP_RCPROTOCOL_FDM_ENABLED - +#if AP_RCPROTOCOL_RADIO_ENABLED + backend[AP_RCProtocol::RADIO] = NEW_NOTHROW AP_RCProtocol_Radio(*this); +#endif } AP_RCProtocol::~AP_RCProtocol() @@ -472,6 +475,9 @@ bool AP_RCProtocol::new_input() #endif #if AP_RCPROTOCOL_FDM_ENABLED AP_RCProtocol::FDM, +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + AP_RCProtocol::RADIO, #endif }; for (const auto protocol : pollable) { @@ -620,6 +626,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol) #if AP_RCPROTOCOL_FDM_ENABLED case FDM: return "FDM"; +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + case RADIO: + return "Radio"; #endif case NONE: break; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index 6234e0a1a13099..bcf7038ba96bd4 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -89,6 +89,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_FDM_ENABLED FDM = 18, +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + RADIO = 19, #endif NONE //last enum always is None }; @@ -125,6 +128,14 @@ class AP_RCProtocol { _disabled_for_pulses |= (1U<<(uint8_t)protocol); } +#if !defined(__clang__) +// in the case we've disabled most backends then the "return true" in +// the following method can never be reached, and the compiler gets +// annoyed at that. +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wswitch-unreachable" +#endif + // for protocols without strong CRCs we require 3 good frames to lock on bool requires_3_frames(enum rcprotocol_t p) { switch (p) { @@ -185,12 +196,18 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_FDM_ENABLED case FDM: +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + case RADIO: #endif case NONE: return false; } return false; } +#if !defined(__clang__) +#pragma GCC diagnostic pop +#endif uint8_t num_channels(); uint16_t read(uint8_t chan); diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp index ce870cd0ac7753..9372946a6a71ce 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp @@ -178,7 +178,7 @@ AP_RCProtocol_CRSF::AP_RCProtocol_CRSF(AP_RCProtocol &_frontend) : AP_RCProtocol _singleton = this; } #endif -#if HAL_CRSF_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_iofirmware) && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +#if HAL_CRSF_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) _uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_CRSF, 0); if (_uart) { start_uart(); @@ -561,7 +561,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 HAL_CRSF_TELEM_ENABLED if (AP_CRSF_Telem::get_telem_data(&_telemetry_frame, is_tx_active())) { telem_available = true; } else { diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h index aaaf0fb2bf2d8f..e4ebba502775e5 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h @@ -80,7 +80,9 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { enum FrameType { CRSF_FRAMETYPE_GPS = 0x02, + CRSF_FRAMETYPE_VARIO = 0x07, CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08, + CRSF_FRAMETYPE_BARO_VARIO = 0x09, CRSF_FRAMETYPE_HEARTBEAT = 0x0B, CRSF_FRAMETYPE_VTX = 0x0F, CRSF_FRAMETYPE_VTX_TELEM = 0x10, diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp index 879344e3236cee..80b7cf9fdc537d 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp @@ -14,15 +14,11 @@ extern const AP_HAL::HAL& hal; AP_RCProtocol_DroneCAN::Registry AP_RCProtocol_DroneCAN::registry; AP_RCProtocol_DroneCAN *AP_RCProtocol_DroneCAN::_singleton; -void AP_RCProtocol_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_RCProtocol_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rcinput, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("rc_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rcinput, driver_index) != nullptr); } AP_RCProtocol_DroneCAN* AP_RCProtocol_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.h b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.h index d2c81025d76c63..aa4693020d9695 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.h @@ -18,7 +18,7 @@ class AP_RCProtocol_DroneCAN : public AP_RCProtocol_Backend { _singleton = this; } - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); void update() override; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp index 0523987598e7ad..3389920cbe674c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -280,6 +280,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() const RadioFrame* radio_frame = (const RadioFrame*)(&_frame.payload); const Channels12Bit_4Chan* channels = &(radio_frame->channels); const uint8_t* lowres_channels = radio_frame->lowres_channels; + bool rc_frame = false; // Scaling from Betaflight // Scaling 12bit channels (8bit channels in brackets) @@ -328,6 +329,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[1]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[3]); + rc_frame = true; break; } case GHST_UL_RC_CHANS_HS4_12_5TO8: @@ -338,6 +340,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[1]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[3]); + rc_frame = true; break; } case GHST_UL_RC_CHANS_RSSI: @@ -355,7 +358,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() } #endif - return true; + return rc_frame; } // send out telemetry diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp new file mode 100644 index 00000000000000..f0f37703f3f00f --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp @@ -0,0 +1,53 @@ +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_RADIO_ENABLED + +#include "AP_RCProtocol_Radio.h" +#include + +void AP_RCProtocol_Radio::update() +{ + auto *radio = AP_Radio::get_singleton(); + if (radio == nullptr) { + return; + } + if (!init_done) { + radio->init(); + init_done = true; + } + + // allow the radio to handle mavlink on the main thread: + radio->update(); + + const uint32_t last_recv_us = radio->last_recv_us(); + if (last_recv_us == last_input_us) { + // no new data + return; + } + last_input_us = last_recv_us; + + const auto num_channels = radio->num_channels(); + uint16_t rcin_values[MAX_RCIN_CHANNELS]; + for (uint8_t i=0; iread(i); + } + + add_input( + num_channels, + rcin_values, + false, // failsafe + 0, // check me + 0 // link quality + ); +} + +void AP_RCProtocol_Radio::start_bind() +{ + auto *radio = AP_Radio::get_singleton(); + if (radio == nullptr) { + return; + } + radio->start_recv_bind(); +} + +#endif // AP_RCPROTOCOL_RADIO_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h new file mode 100644 index 00000000000000..0144e0e42697a0 --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h @@ -0,0 +1,32 @@ +#pragma once + +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_RADIO_ENABLED + +/* + * Reads fixed-length packets containing either 8 or 16 2-byte values, + * and interprets them as RC input. + */ + +#include "AP_RCProtocol_Backend.h" + +class AP_RCProtocol_Radio : public AP_RCProtocol_Backend { +public: + + using AP_RCProtocol_Backend::AP_RCProtocol_Backend; + + void update() override; + + void start_bind(void) override; + +private: + + bool init(); + bool init_done; + + uint32_t last_input_us; +}; + + +#endif // AP_RCPROTOCOL_RADIO_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index a648b0969bbc98..4cb2b651246110 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -3,6 +3,7 @@ #include #include #include +#include #ifndef AP_RCPROTOCOL_ENABLED #define AP_RCPROTOCOL_ENABLED 1 @@ -43,6 +44,10 @@ #define AP_RCPROTOCOL_PPMSUM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_RCPROTOCOL_RADIO_ENABLED +#define AP_RCPROTOCOL_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RADIO_ENABLED +#endif + #ifndef AP_RCPROTOCOL_SBUS_ENABLED #define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_RCProtocol/SoftSerial.cpp b/libraries/AP_RCProtocol/SoftSerial.cpp index 0f06cfb8efcee7..6bae175d3b63d5 100644 --- a/libraries/AP_RCProtocol/SoftSerial.cpp +++ b/libraries/AP_RCProtocol/SoftSerial.cpp @@ -22,8 +22,8 @@ SoftSerial::SoftSerial(uint32_t _baudrate, serial_config _config) : baudrate(_baudrate), - config(_config), - half_bit((1000000U / baudrate)/2) + half_bit((1000000U / baudrate)/2), + config(_config) { switch (config) { case SERIAL_CONFIG_8N1: diff --git a/libraries/AP_RCProtocol/spm_srxl.cpp b/libraries/AP_RCProtocol/spm_srxl.cpp index 8dfcf495b58d29..4c8653a3f2e931 100644 --- a/libraries/AP_RCProtocol/spm_srxl.cpp +++ b/libraries/AP_RCProtocol/spm_srxl.cpp @@ -1304,7 +1304,7 @@ void srxlOnFrameError(uint8_t busIndex) SrxlFullID srxlGetTelemetryEndpoint(void) { - SrxlFullID retVal = {0}; + SrxlFullID retVal = {{0}}; if(srxlRx.pTelemRcvr) { retVal.deviceID = srxlRx.pTelemRcvr->deviceID; diff --git a/libraries/AP_RCProtocol/spm_srxl.h b/libraries/AP_RCProtocol/spm_srxl.h index c1aecc3abdc22a..799abfdcdedfd8 100644 --- a/libraries/AP_RCProtocol/spm_srxl.h +++ b/libraries/AP_RCProtocol/spm_srxl.h @@ -55,27 +55,6 @@ typedef enum SrxlDevType_Broadcast = 15 } SrxlDevType; -// Default device ID list used by master when polling -static const uint8_t SRXL_DEFAULT_ID_OF_TYPE[16] = -{ - [SrxlDevType_None] = 0x00, - [SrxlDevType_RemoteReceiver] = 0x10, - [SrxlDevType_Receiver] = 0x21, - [SrxlDevType_FlightController] = 0x30, - [SrxlDevType_ESC] = 0x40, - [5] = 0x60, - [SrxlDevType_SRXLServo1] = 0x60, - [SrxlDevType_SRXLServo2] = 0x70, - [SrxlDevType_VTX] = 0x81, - [9] = 0xFF, - [10] = 0xFF, - [11] = 0xFF, - [12] = 0xFF, - [13] = 0xFF, - [14] = 0xFF, - [SrxlDevType_Broadcast] = 0xFF, -}; - // Set SRXL_CRC_OPTIMIZE_MODE in spm_srxl_config.h to one of the following values #define SRXL_CRC_OPTIMIZE_EXTERNAL (0) // Uses an external function defined by SRXL_CRC_EXTERNAL_FN for CRC #define SRXL_CRC_OPTIMIZE_SPEED (1) // Uses table lookup for CRC computation (requires 512 const bytes for CRC table) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index c645add90fcba7..77002b39cd610c 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_RCTelemetry_config.h" + +#if HAL_CRSF_TELEM_ENABLED + #include "AP_CRSF_Telem.h" #include #include @@ -30,7 +34,7 @@ #include #include -#if HAL_CRSF_TELEM_ENABLED +#include #include @@ -66,6 +70,13 @@ bool AP_CRSF_Telem::init(void) return false; } +#if AP_VIDEOTX_ENABLED + // Someone explicitly configure CRSF control for VTX + if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) { + AP::vtx().set_provider_enabled(AP_VideoTX::VTXType::CRSF); + } +#endif + return AP_RCTelemetry::init(); } @@ -81,6 +92,7 @@ void AP_CRSF_Telem::setup_wfq_scheduler(void) // CRSF telemetry rate is 150Hz (4ms) max, so these rates must fit add_scheduler_entry(50, 100); // heartbeat 10Hz add_scheduler_entry(5, 20); // parameters 50Hz (generally not active unless requested by the TX) + add_scheduler_entry(50, 200); // baro_vario 5Hz add_scheduler_entry(50, 120); // Attitude and compass 8Hz add_scheduler_entry(200, 1000); // VTX parameters 1Hz add_scheduler_entry(1300, 500); // battery 2Hz @@ -152,6 +164,8 @@ void AP_CRSF_Telem::update_custom_telemetry_rates(AP_RCProtocol_CRSF::RFMode rf_ // standard telemetry for high data rates set_scheduler_entry(BATTERY, 1000, 1000); // 1Hz set_scheduler_entry(ATTITUDE, 1000, 1000); // 1Hz + set_scheduler_entry(BARO_VARIO, 1000, 1000); // 1Hz + set_scheduler_entry(VARIO, 1000, 1000); // 1Hz // custom telemetry for high data rates set_scheduler_entry(GPS, 550, 500); // 2.0Hz set_scheduler_entry(PASSTHROUGH, 100, 100); // 8Hz @@ -160,6 +174,8 @@ 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 + set_scheduler_entry(BARO_VARIO, 1000, 3000); // 0.33Hz + set_scheduler_entry(VARIO, 1000, 3000); // 0.33Hz if (is_elrs()) { // ELRS custom telemetry for low data rates set_scheduler_entry(GPS, 550, 1000); // 1.0Hz @@ -320,6 +336,8 @@ void AP_CRSF_Telem::queue_message(MAV_SEVERITY severity, const char *text) void AP_CRSF_Telem::disable_tx_entries() { disable_scheduler_entry(ATTITUDE); + disable_scheduler_entry(BARO_VARIO); + disable_scheduler_entry(VARIO); disable_scheduler_entry(BATTERY); disable_scheduler_entry(GPS); disable_scheduler_entry(FLIGHT_MODE); @@ -334,6 +352,8 @@ void AP_CRSF_Telem::disable_tx_entries() void AP_CRSF_Telem::enable_tx_entries() { enable_scheduler_entry(ATTITUDE); + enable_scheduler_entry(BARO_VARIO); + enable_scheduler_entry(VARIO); enable_scheduler_entry(BATTERY); enable_scheduler_entry(GPS); enable_scheduler_entry(FLIGHT_MODE); @@ -428,6 +448,12 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) case PARAMETERS: // update parameter settings process_pending_requests(); break; + case BARO_VARIO: + calc_baro_vario(); + break; + case VARIO: + calc_vario(); + break; case ATTITUDE: calc_attitude(); break; @@ -554,6 +580,8 @@ void AP_CRSF_Telem::process_vtx_frame(VTXFrame* vtx) { return; } + apvtx.set_provider_enabled(AP_VideoTX::VTXType::CRSF); + apvtx.set_band(vtx->band); apvtx.set_channel(vtx->channel); if (vtx->is_in_user_frequency_mode) { @@ -600,6 +628,8 @@ void AP_CRSF_Telem::process_vtx_telem_frame(VTXTelemetryFrame* vtx) return; } + apvtx.set_provider_enabled(AP_VideoTX::VTXType::CRSF); + apvtx.set_frequency_mhz(vtx->frequency); AP_VideoTX::VideoBand band; @@ -731,11 +761,6 @@ void AP_CRSF_Telem::process_param_read_frame(ParameterSettingsReadFrame* read_fr _pending_request.frame_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAMETER_READ; } -// process any changed settings and schedule for transmission -void AP_CRSF_Telem::update() -{ -} - void AP_CRSF_Telem::process_pending_requests() { // handle general parameter requests @@ -766,7 +791,8 @@ void AP_CRSF_Telem::update_vtx_params() { AP_VideoTX& vtx = AP::vtx(); - if (!vtx.get_enabled()) { + // This function does ugly things with the vtx parameters which will upset other providers + if (!vtx.get_enabled() || !vtx.is_provider_enabled(AP_VideoTX::VTXType::CRSF)) { return; } @@ -914,6 +940,60 @@ void AP_CRSF_Telem::calc_battery() _telem_pending = true; } +uint16_t AP_CRSF_Telem::get_altitude_packed() +{ + int32_t altitude_dm = get_nav_alt_m(Location::AltFrame::ABOVE_HOME) * 10; + + enum : int32_t { + ALT_MIN_DM = 10000, // minimum altitude in dm + ALT_THRESHOLD_DM = 0x8000 - ALT_MIN_DM, // altitude of precision changing in dm + ALT_MAX_DM = 0x7ffe * 10 - 5, // maximum altitude in dm + }; + + if (altitude_dm < -ALT_MIN_DM) { // less than minimum altitude + return 0; // minimum + } + if (altitude_dm > ALT_MAX_DM) { // more than maximum + return 0xFFFEU; // maximum + } + if(altitude_dm < ALT_THRESHOLD_DM) { //dm-resolution range + return uint16_t(altitude_dm + ALT_MIN_DM); + } + return uint16_t((altitude_dm + 5) / 10) | uint16_t(0x8000); // meter-resolution range +} + +int8_t AP_CRSF_Telem::get_vertical_speed_packed() +{ + float vspeed = get_vspeed_ms(); + float vertical_speed_cm_s = vspeed * 100.0f; + const int16_t Kl = 100; // linearity constant; + const float Kr = .026f; // range constant; + int8_t vspeed_packed = int8_t(logf(fabsf(vertical_speed_cm_s)/Kl + 1)/Kr); + return vspeed_packed * (is_negative(vertical_speed_cm_s) ? -1 : 1); +} + +// prepare vario data +void AP_CRSF_Telem::calc_baro_vario() +{ + _telem.bcast.baro_vario.altitude_packed = htobe16(get_altitude_packed()); + _telem.bcast.baro_vario.vertical_speed_packed = get_vertical_speed_packed(); + + _telem_size = sizeof(BaroVarioFrame); + _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_BARO_VARIO; + + _telem_pending = true; +} + +// prepare vario data +void AP_CRSF_Telem::calc_vario() +{ + _telem.bcast.vario.v_speed = htobe16(int16_t(get_vspeed_ms() * 100.0f)); + _telem_size = sizeof(VarioFrame); + _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_VARIO; + + _telem_pending = true; +} + // prepare gps data void AP_CRSF_Telem::calc_gps() { @@ -1196,7 +1276,7 @@ void AP_CRSF_Telem::calc_parameter() { _pending_request.frame_type = 0; _telem_pending = true; -#endif +#endif // OSD_PARAM_ENABLED } #if HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED @@ -1208,8 +1288,13 @@ void AP_CRSF_Telem::calc_parameter() { class BufferChunker { public: BufferChunker(uint8_t* buf, uint16_t chunk_size, uint16_t start_chunk) : - _buf(buf), _idx(0), _start_chunk(start_chunk), _chunk_size(chunk_size), _chunk(0), _bytes(0) { - } + _buf(buf), + _idx(0), + _bytes(0), + _chunk(0), + _start_chunk(start_chunk), + _chunk_size(chunk_size) + { } // accumulate a string, writing to the underlying buffer as required void put_string(const char* str, uint16_t str_len) { @@ -1346,7 +1431,7 @@ void AP_CRSF_Telem::calc_text_selection(AP_OSD_ParamSetting* param, uint8_t chun _pending_request.frame_type = 0; _telem_pending = true; } -#endif +#endif // HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED // write parameter information back into AP - assumes we already know the encoding for floats void AP_CRSF_Telem::process_param_write_frame(ParameterSettingsWriteFrame* write_frame) @@ -1416,7 +1501,7 @@ void AP_CRSF_Telem::process_param_write_frame(ParameterSettingsWriteFrame* write default: break; } -#endif +#endif // OSD_PARAM_ENABLED } // get status text data @@ -1560,7 +1645,7 @@ AP_CRSF_Telem *AP_CRSF_Telem::get_singleton(void) { if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_CRSF_Telem object then try to allocate one - new AP_CRSF_Telem(); + NEW_NOTHROW AP_CRSF_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(); @@ -1575,4 +1660,4 @@ namespace AP { } }; -#endif +#endif // HAL_CRSF_TELEM_ENABLED diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h index e0d557cb74cc79..dcebf23d0c94d9 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h @@ -64,6 +64,15 @@ class AP_CRSF_Telem : public AP_RCTelemetry { uint8_t remaining; // ( percent ) }; + struct PACKED BaroVarioFrame { + uint16_t altitude_packed; // Altitude above start (calibration) point. + int8_t vertical_speed_packed; // vertical speed. + }; + + struct PACKED VarioFrame { + int16_t v_speed; // vertical speed cm/s + }; + struct PACKED VTXFrame { #if __BYTE_ORDER != __LITTLE_ENDIAN #error "Only supported on little-endian architectures" @@ -201,6 +210,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { union PACKED BroadcastFrame { GPSFrame gps; HeartbeatFrame heartbeat; + BaroVarioFrame baro_vario; + VarioFrame vario; BatteryFrame battery; VTXFrame vtx; AttitudeFrame attitude; @@ -232,8 +243,6 @@ class AP_CRSF_Telem : public AP_RCTelemetry { // 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, bool is_tx_active); // start bind request @@ -244,6 +253,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { enum SensorType { HEARTBEAT, PARAMETERS, + BARO_VARIO, + VARIO, ATTITUDE, VTX_PARAMETERS, BATTERY, @@ -267,6 +278,10 @@ class AP_CRSF_Telem : public AP_RCTelemetry { void calc_parameter_ping(); void calc_heartbeat(); void calc_battery(); + uint16_t get_altitude_packed(); + int8_t get_vertical_speed_packed(); + void calc_baro_vario(); + void calc_vario(); void calc_gps(); void calc_attitude(); void calc_flight_mode(); diff --git a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp index 821742273a44e1..801b2574404bca 100644 --- a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp @@ -373,7 +373,7 @@ AP_GHST_Telem *AP_GHST_Telem::get_singleton(void) { if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_GHST_Telem object then try to allocate one - new AP_GHST_Telem(); + NEW_NOTHROW AP_GHST_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(); diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index c57c3d35cefe17..3c7d4e3358e73e 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #ifdef TELEM_DEBUG # define debug(fmt, args...) hal.console->printf("Telem: " fmt "\n", ##args) @@ -293,3 +294,46 @@ uint32_t AP_RCTelemetry::sensor_status_flags() const return ~health & enabled & present; } + +/* + * get vertical speed from ahrs, if not available fall back to baro climbrate, units is m/s + */ +float AP_RCTelemetry::get_vspeed_ms(void) +{ + { + // release semaphore as soon as possible + AP_AHRS &_ahrs = AP::ahrs(); + Vector3f v; + WITH_SEMAPHORE(_ahrs.get_semaphore()); + if (_ahrs.get_velocity_NED(v)) { + return -v.z; + } + } + auto &_baro = AP::baro(); + WITH_SEMAPHORE(_baro.get_semaphore()); + return _baro.get_climb_rate(); +} + +/* + * prepare altitude between vehicle and home location data + */ +float AP_RCTelemetry::get_nav_alt_m(Location::AltFrame frame) +{ + Location loc; + float current_height = 0; + + AP_AHRS &_ahrs = AP::ahrs(); + WITH_SEMAPHORE(_ahrs.get_semaphore()); + + if (frame == Location::AltFrame::ABOVE_HOME) { + _ahrs.get_relative_position_D_home(current_height); + return -current_height; + } + + if (_ahrs.get_location(loc)) { + if (!loc.get_alt_m(frame, current_height)) { + // ignore this error + } + } + return current_height; +} diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.h b/libraries/AP_RCTelemetry/AP_RCTelemetry.h index 40fc27ca838b25..5ebea0ff35770e 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.h +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.h @@ -18,6 +18,7 @@ #include #include #include +#include #define TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent) @@ -77,6 +78,9 @@ class AP_RCTelemetry { return _scheduler.max_packet_rate; } + static float get_vspeed_ms(void); + static float get_nav_alt_m(Location::AltFrame frame = Location::AltFrame::ABSOLUTE); + protected: uint8_t run_wfq_scheduler(const bool use_shaper = true); // process a specific entry diff --git a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp index 7caa87cfc9504a..c5daa09ea75079 100644 --- a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp @@ -578,11 +578,17 @@ void AP_Spektrum_Telem::calc_gps_status() void AP_Spektrum_Telem::calc_esc() { #if HAL_WITH_ESC_TELEM - const volatile AP_ESC_Telem_Backend::TelemetryData& td = AP::esc_telem().get_telem_data(0); // ideally should rotate between ESCs + uint8_t esc = AP::esc_telem().get_max_rpm_esc(); + const volatile AP_ESC_Telem_Backend::TelemetryData& td = AP::esc_telem().get_telem_data(esc); // ideally should rotate between ESCs + float rpm = 0.0f; + uint16_t rpmdata = 0xFFFFU; + if (AP::esc_telem().get_rpm(esc, rpm)) { + rpmdata = uint16_t(roundf(rpm)); + } _telem.esc.identifier = TELE_DEVICE_ESC; // Source device = 0x20 _telem.esc.sID = 0; // Secondary ID - _telem.esc.RPM = htobe16(uint16_t(roundf(AP::esc_telem().get_average_motor_frequency_hz() * 60))); // Electrical RPM, 10RPM (0-655340 RPM) 0xFFFF --> "No data" + _telem.esc.RPM = htobe16(rpmdata); // Electrical RPM, 10RPM (0-655340 RPM) 0xFFFF --> "No data" _telem.esc.voltsInput = htobe16(td.voltage * 100); // Volts, 0.01v (0-655.34V) 0xFFFF --> "No data" _telem.esc.tempFET = htobe16(td.temperature_cdeg * 10); // Temperature, 0.1C (0-6553.4C) 0xFFFF --> "No data" _telem.esc.currentMotor = htobe16(td.current * 100); // Current, 10mA (0-655.34A) 0xFFFF --> "No data" @@ -618,7 +624,7 @@ bool AP_Spektrum_Telem::get_telem_data(uint8_t* data) if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_Spektrum_Telem object then try to allocate one - new AP_Spektrum_Telem(); + NEW_NOTHROW AP_Spektrum_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(); diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index 3a8542e199093b..df4e6ad69f8481 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -45,10 +45,9 @@ const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name) } /* - find a compressed file and uncompress it. Space for decompressed data comes - from malloc. Caller must be careful to free the resulting data after use. The - file data buffer is guaranteed to contain at least one null (though it may be - at buf[size]). + Find the named file and return its decompressed data and size. Caller must + call AP_ROMFS::free() on the return value after use to free it. The data is + guaranteed to be null-terminated such that it can be treated as a string. */ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) { @@ -61,20 +60,18 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) size = f->decompressed_size; return f->contents; #else + // add one byte for null termination; ArduPilot's malloc will zero it. uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1); if (!decompressed_data) { return nullptr; } if (f->decompressed_size == 0) { - // empty file + // empty file, avoid decompression problems size = 0; return decompressed_data; } - // explicitly null-terminate the data - decompressed_data[f->decompressed_size] = 0; - TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA)); if (!d) { ::free(decompressed_data); @@ -106,7 +103,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) #endif } -// free returned data +// free decompressed file data void AP_ROMFS::free(const uint8_t *data) { #ifndef HAL_ROMFS_UNCOMPRESSED diff --git a/libraries/AP_ROMFS/AP_ROMFS.h b/libraries/AP_ROMFS/AP_ROMFS.h index 57efa9f5b8c96d..940810dc4172bc 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.h +++ b/libraries/AP_ROMFS/AP_ROMFS.h @@ -7,13 +7,13 @@ class AP_ROMFS { public: - // find a file and de-compress, assumning gzip format. The - // decompressed data will be allocated with malloc(). You must - // call AP_ROMFS::free() on the return value after use. The next byte after - // the file data is guaranteed to be null. + // Find the named file and return its decompressed data and size. Caller + // must call AP_ROMFS::free() on the return value after use to free it. + // The data is guaranteed to be null-terminated such that it can be + // treated as a string. static const uint8_t *find_decompress(const char *name, uint32_t &size); - // free returned data + // free decompressed file data static void free(const uint8_t *data); // get the size of a file without decompressing diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index ef0061553eaa7f..30bfcedc60ef57 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -24,6 +24,7 @@ #include "RPM_Generator.h" #include "RPM_HarmonicNotch.h" #include "RPM_ESC_Telem.h" +#include "RPM_DroneCAN.h" #include @@ -43,6 +44,18 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = { AP_SUBGROUPINFO(_params[1], "2_", 15, AP_RPM, AP_RPM_Params), #endif +#if RPM_MAX_INSTANCES > 2 + // @Group: 3_ + // @Path: AP_RPM_Params.cpp + AP_SUBGROUPINFO(_params[2], "3_", 16, AP_RPM, AP_RPM_Params), +#endif + +#if RPM_MAX_INSTANCES > 3 + // @Group: 4_ + // @Path: AP_RPM_Params.cpp + AP_SUBGROUPINFO(_params[3], "4_", 17, AP_RPM, AP_RPM_Params), +#endif + AP_GROUPEND }; @@ -74,34 +87,39 @@ void AP_RPM::init(void) case RPM_TYPE_PWM: case RPM_TYPE_PIN: // PWM option same as PIN option, for upgrade - drivers[i] = new AP_RPM_Pin(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_Pin(*this, i, state[i]); break; #endif // AP_RPM_PIN_ENABLED #if AP_RPM_ESC_TELEM_ENABLED case RPM_TYPE_ESC_TELEM: - drivers[i] = new AP_RPM_ESC_Telem(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_ESC_Telem(*this, i, state[i]); break; #endif // AP_RPM_ESC_TELEM_ENABLED #if AP_RPM_EFI_ENABLED case RPM_TYPE_EFI: - drivers[i] = new AP_RPM_EFI(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_EFI(*this, i, state[i]); break; #endif // AP_RPM_EFI_ENABLED #if AP_RPM_GENERATOR_ENABLED case RPM_TYPE_GENERATOR: - drivers[i] = new AP_RPM_Generator(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_Generator(*this, i, state[i]); break; #endif // AP_RPM_GENERATOR_ENABLED #if AP_RPM_HARMONICNOTCH_ENABLED // include harmonic notch last // this makes whatever process is driving the dynamic notch appear as an RPM value case RPM_TYPE_HNTCH: - drivers[i] = new AP_RPM_HarmonicNotch(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_HarmonicNotch(*this, i, state[i]); break; #endif // AP_RPM_HARMONICNOTCH_ENABLED +#if AP_RPM_DRONECAN_ENABLED + case RPM_TYPE_DRONECAN: + drivers[i] = NEW_NOTHROW AP_RPM_DroneCAN(*this, i, state[i]); + break; +#endif // AP_RPM_DRONECAN_ENABLED #if AP_RPM_SIM_ENABLED case RPM_TYPE_SITL: - drivers[i] = new AP_RPM_SITL(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_RPM_SITL(*this, i, state[i]); break; #endif // AP_RPM_SIM_ENABLED } @@ -208,9 +226,7 @@ void AP_RPM::update(void) } #if HAL_LOGGING_ENABLED - if (enabled(0) || enabled(1)) { - Log_RPM(); - } + Log_RPM(); #endif } @@ -289,21 +305,38 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const #if HAL_LOGGING_ENABLED void AP_RPM::Log_RPM() const { - float rpm1 = -1, rpm2 = -1; + // update logging for each instance + for (uint8_t i=0; i. + */ + +#include "AP_RPM_config.h" + +#if AP_RPM_DRONECAN_ENABLED + +#include "RPM_DroneCAN.h" +#include + +AP_RPM_DroneCAN* AP_RPM_DroneCAN::_drivers[]; +uint8_t AP_RPM_DroneCAN::_driver_instance; +HAL_Semaphore AP_RPM_DroneCAN::_driver_sem; + +AP_RPM_DroneCAN::AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) : + AP_RPM_Backend(_ap_rpm, instance, _state) +{ + // Register self in static driver list + WITH_SEMAPHORE(_driver_sem); + _drivers[_driver_instance] = this; + _driver_instance++; +} + +// Subscribe to incoming rpm messages +bool AP_RPM_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + const auto driver_index = ap_dronecan->get_driver_index(); + + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rpm, driver_index) != nullptr); +} + +// Receive new CAN message +void AP_RPM_DroneCAN::handle_rpm(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rpm_RPM &msg) +{ + WITH_SEMAPHORE(_driver_sem); + + for (uint8_t i = 0; i < _driver_instance; i++) { + if (_drivers[i] == nullptr) { + continue; + } + // Find params for this instance + const uint8_t instance = _drivers[i]->state.instance; + const AP_RPM_Params& params = _drivers[i]->ap_rpm._params[instance]; + + if (params.dronecan_sensor_id == msg.sensor_id) { + // Driver loaded and looking for this ID, add reading + _drivers[i]->last_reading_ms = AP_HAL::millis(); + _drivers[i]->rpm = msg.rpm * params.scaling; + + const bool heathy = (msg.flags & DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY) == 0; + _drivers[i]->signal_quality = heathy ? 0.5 : 0.0; + } + } +} + +void AP_RPM_DroneCAN::update(void) +{ + WITH_SEMAPHORE(_driver_sem); + + // Update state from temporay variables + state.last_reading_ms = last_reading_ms; + state.signal_quality = signal_quality; + state.rate_rpm = rpm; + + // assume we get readings at at least 1Hz, otherwise reset quality to zero + if ((AP_HAL::millis() - state.last_reading_ms) > 1000) { + state.signal_quality = 0; + state.rate_rpm = 0; + } +} + +#endif // AP_RPM_DRONECAN_ENABLED diff --git a/libraries/AP_RPM/RPM_DroneCAN.h b/libraries/AP_RPM/RPM_DroneCAN.h new file mode 100644 index 00000000000000..ae6924071346b4 --- /dev/null +++ b/libraries/AP_RPM/RPM_DroneCAN.h @@ -0,0 +1,52 @@ +/* + 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_config.h" + +#if AP_RPM_DRONECAN_ENABLED + +#include "RPM_Backend.h" +#include + +class AP_RPM_DroneCAN : public AP_RPM_Backend +{ +public: + AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state); + + // Subscribe to incoming rpm messages + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); + + // update state + void update(void) override; + +private: + + // Receive new CAN message + static void handle_rpm(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rpm_RPM &msg); + + // Temporay variables used to update main state in update call + float rpm; + uint32_t last_reading_ms; + float signal_quality; + + // Static list of drivers + static AP_RPM_DroneCAN *_drivers[RPM_MAX_INSTANCES]; + static uint8_t _driver_instance; + static HAL_Semaphore _driver_sem; + +}; + +#endif // AP_RPM_DRONECAN_ENABLED diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 033e6122b76795..7db287006324e1 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -48,7 +48,7 @@ const AP_Param::GroupInfo AP_RSSI::var_info[] = { // @Param: ANA_PIN // @DisplayName: Receiver RSSI sensing pin - // @Description: Pin used to read the RSSI voltage or PWM value + // @Description: Pin used to read the RSSI voltage or PWM value. Analog Airspeed ports can be used for Analog inputs (some autopilots provide others also), Non-IOMCU Servo/MotorOutputs can be used for PWM input when configured as "GPIOs". Values for some autopilots are given as examples. Search wiki for "Analog pins" for analog pin or "GPIOs", if PWM input type, to determine pin number. // @Values: 8:V5 Nano,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("ANA_PIN", 1, AP_RSSI, rssi_analog_pin, BOARD_RSSI_ANA_PIN), diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index a57c3242852fd5..46c5df2d9b1369 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -9,6 +9,12 @@ #include #include +#define DEBUG_RTC_SHIFT 0 + +#if DEBUG_RTC_SHIFT +#include +#endif + extern const AP_HAL::HAL& hal; AP_RTC::AP_RTC() @@ -47,9 +53,19 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) { const uint64_t oldest_acceptable_date_us = 1640995200ULL*1000*1000; // 2022-01-01 0:00 - if (type >= rtc_source_type) { - // e.g. system-time message when we've been set by the GPS - return; + // only allow time to be moved forward from the same sourcetype + // while the vehicle is disarmed: + if (hal.util->get_soft_armed()) { + if (type >= rtc_source_type) { + // e.g. system-time message when we've been set by the GPS + return; + } + } else { + // vehicle is disarmed; accept (e.g.) GPS time source updates + if (type > rtc_source_type) { + // e.g. system-time message when we've been set by the GPS + return; + } } // check it's from an allowed sources: @@ -70,6 +86,11 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) } WITH_SEMAPHORE(rsem); +#if DEBUG_RTC_SHIFT + uint64_t old_utc = 0; + UNUSED_RESULT(get_utc_usec(old_utc)); +#endif + rtc_shift = tmp; // update hardware clock: @@ -83,6 +104,31 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type) // update signing timestamp GCS_MAVLINK::update_signing_timestamp(time_utc_usec); #endif + +#if DEBUG_RTC_SHIFT + uint64_t new_utc = 0; + UNUSED_RESULT(get_utc_usec(new_utc)); + if (old_utc != new_utc) { + if (AP::logger().should_log(0xFFFF)){ + // log to AP_Logger + // @LoggerMessage: RTC + // @Description: Information about RTC clock resets + // @Field: TimeUS: Time since system startup + // @Field: old_utc: old time + // @Field: new_utc: new time + AP::logger().WriteStreaming( + "RTC", + "TimeUS,old_utc,new_utc", + "sss", + "FFF", + "QQQ", + AP_HAL::micros64(), + old_utc, + new_utc + ); + } + } +#endif } bool AP_RTC::get_utc_usec(uint64_t &usec) const diff --git a/libraries/AP_Radio/AP_Radio.cpp b/libraries/AP_Radio/AP_Radio.cpp index 5afaa5764b6032..6f62c9c90cf2ff 100644 --- a/libraries/AP_Radio/AP_Radio.cpp +++ b/libraries/AP_Radio/AP_Radio.cpp @@ -155,17 +155,17 @@ bool AP_Radio::init(void) switch (radio_type) { #if AP_RADIO_CYRF6936_ENABLED case RADIO_TYPE_CYRF6936: - driver = new AP_Radio_cypress(*this); + driver = NEW_NOTHROW AP_Radio_cypress(*this); break; #endif #if AP_RADIO_CC2500_ENABLED case RADIO_TYPE_CC2500: - driver = new AP_Radio_cc2500(*this); + driver = NEW_NOTHROW AP_Radio_cc2500(*this); break; #endif #if AP_RADIO_BK2425_ENABLED case RADIO_TYPE_BK2425: - driver = new AP_Radio_beken(*this); + driver = NEW_NOTHROW AP_Radio_beken(*this); break; #endif #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 @@ -173,12 +173,12 @@ bool AP_Radio::init(void) // auto-detect between cc2500 and beken radios #if AP_RADIO_CC2500_ENABLED if (AP_Radio_cc2500::probe()) { - driver = new AP_Radio_cc2500(*this); + driver = NEW_NOTHROW AP_Radio_cc2500(*this); } #endif #if AP_RADIO_BK2425_ENABLED if (driver == nullptr) { - driver = new AP_Radio_beken(*this); + driver = NEW_NOTHROW AP_Radio_beken(*this); } #endif break; diff --git a/libraries/AP_Radio/AP_Radio_bk2425.cpp b/libraries/AP_Radio/AP_Radio_bk2425.cpp index 2ed5b64f1b710a..773205cf8823e2 100644 --- a/libraries/AP_Radio/AP_Radio_bk2425.cpp +++ b/libraries/AP_Radio/AP_Radio_bk2425.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; // This is for debugging issues with frequency hopping and synchronisation. #define DebugPrintf(level, fmt, args...) do { if (AP_Radio_beken::radio_singleton && ((level) <= AP_Radio_beken::radio_singleton->get_debug_level())) { printf(fmt, ##args); }} while (0) // Output debug information on the mavlink to the UART connected to the WiFi, wrapped in MavLink packets -#define DebugMavlink(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) +#define DebugMavlink(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) #if SUPPORT_BK_DEBUG_PINS diff --git a/libraries/AP_Radio/AP_Radio_cc2500.cpp b/libraries/AP_Radio/AP_Radio_cc2500.cpp index 34ef0eef3041d6..cce9b4ffcf0f90 100644 --- a/libraries/AP_Radio/AP_Radio_cc2500.cpp +++ b/libraries/AP_Radio/AP_Radio_cc2500.cpp @@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal; -#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) +#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) // object instance for trampoline AP_Radio_cc2500 *AP_Radio_cc2500::radio_singleton; diff --git a/libraries/AP_Radio/AP_Radio_config.h b/libraries/AP_Radio/AP_Radio_config.h index 92ab9fbd789a29..47c53b8c42d98c 100644 --- a/libraries/AP_Radio/AP_Radio_config.h +++ b/libraries/AP_Radio/AP_Radio_config.h @@ -3,7 +3,7 @@ #include #ifndef AP_RADIO_ENABLED -#define AP_RADIO_ENABLED HAL_RCINPUT_WITH_AP_RADIO +#define AP_RADIO_ENABLED 0 #endif #ifndef AP_RADIO_BACKEND_DEFAULT_ENABLED diff --git a/libraries/AP_Radio/AP_Radio_cypress.cpp b/libraries/AP_Radio/AP_Radio_cypress.cpp index 7d3d2101be0fa2..fc27088469221c 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.cpp +++ b/libraries/AP_Radio/AP_Radio_cypress.cpp @@ -42,7 +42,7 @@ extern const AP_HAL::HAL& hal; -#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) +#define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ##args); }} while (0) #define LP_FIFO_SIZE 16 // Physical data FIFO lengths in Radio diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 0da1912c84e5ee..2134162eab2486 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -14,6 +14,9 @@ */ #include "AP_RangeFinder.h" + +#if AP_RANGEFINDER_ENABLED + #include "AP_RangeFinder_analog.h" #include "AP_RangeFinder_PulsedLightLRF.h" #include "AP_RangeFinder_MaxsonarI2CXL.h" @@ -273,7 +276,6 @@ 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(); @@ -386,14 +388,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) // 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); + _add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } break; #endif #if AP_RANGEFINDER_BBB_PRU_ENABLED case Type::BBB_PRU: if (AP_RangeFinder_BBB_PRU::detect()) { - _add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); } break; #endif @@ -415,14 +417,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_BEBOP_ENABLED case Type::BEBOP: if (AP_RangeFinder_Bebop::detect()) { - _add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Bebop(state[instance], params[instance]), instance); } break; #endif #if AP_RANGEFINDER_MAVLINK_ENABLED case Type::MAVLink: if (AP_RangeFinder_MAVLink::detect()) { - _add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); } break; #endif @@ -435,7 +437,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) case Type::ANALOG: // 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); + _add_backend(NEW_NOTHROW AP_RangeFinder_analog(state[instance], params[instance]), instance); } break; #endif @@ -443,7 +445,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) case Type::HC_SR04: // 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); + _add_backend(NEW_NOTHROW AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); } break; #endif @@ -480,7 +482,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_PWM_ENABLED case Type::PWM: if (AP_RangeFinder_PWM::detect()) { - _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } break; #endif @@ -519,32 +521,32 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_SIM_ENABLED case Type::SIM: - _add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); break; #endif #if HAL_MSP_RANGEFINDER_ENABLED case Type::MSP: if (AP_RangeFinder_MSP::detect()) { - _add_backend(new AP_RangeFinder_MSP(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_MSP(state[instance], params[instance]), instance); } break; #endif // HAL_MSP_RANGEFINDER_ENABLED #if AP_RANGEFINDER_USD1_CAN_ENABLED case Type::USD1_CAN: - _add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED case Type::Benewake_CAN: - _add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_LUA_ENABLED case Type::Lua_Scripting: - _add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Lua(state[instance], params[instance]), instance); break; #endif @@ -562,12 +564,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED case Type::TOFSenseP_CAN: - _add_backend(new AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_NRA24_CAN_ENABLED case Type::NRA24_CAN: - _add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED @@ -618,7 +620,6 @@ 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 { @@ -925,3 +926,4 @@ RangeFinder *rangefinder() } +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index f94b0205ef7b83..4d66101b8b6ab9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -16,6 +16,8 @@ #include "AP_RangeFinder_config.h" +#if AP_RANGEFINDER_ENABLED + #include #include #include @@ -192,11 +194,11 @@ class RangeFinder }; enum class Status { - NotConnected = 0, - NoData, - OutOfRangeLow, - OutOfRangeHigh, - Good + NotConnected = 0, + NoData = 1, + OutOfRangeLow = 2, + OutOfRangeHigh = 3, + Good = 4, }; static constexpr int8_t SIGNAL_QUALITY_MIN = 0; @@ -319,3 +321,5 @@ class RangeFinder namespace AP { RangeFinder *rangefinder(); }; + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp index 3e18c96bbe3aa4..775a004268af1c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp @@ -71,8 +71,6 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m) reading_m = UINT16_VALUE(buffer[3], buffer[4]) * 0.01; const uint8_t snr = buffer[5]; - has_data = true; - #if AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS const uint32_t now_ms = AP_HAL::millis(); if (malfunction_alert_prev != malfunction_alert && now_ms - malfunction_alert_last_send_ms >= 1000) { @@ -102,6 +100,7 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m) state.status = RangeFinder::Status::NoData; } } else { + has_data = true; state.status = RangeFinder::Status::Good; } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h index f39bdea95b1ec5..3bf2d348c56aa3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h @@ -22,7 +22,7 @@ class AP_RangeFinder_Ainstein_LR_D1 : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Ainstein_LR_D1(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Ainstein_LR_D1(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index 04fccaae4e35e2..c96830997b568c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -124,7 +124,7 @@ class AP_RangeFinder_BLPing : public 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); + return NEW_NOTHROW AP_RangeFinder_BLPing(_state, _params); } /** diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp index bd0e9be2945ace..3ae267a928cf3e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include #include #include "AP_RangeFinder.h" @@ -89,3 +93,4 @@ void AP_RangeFinder_Backend::get_state(RangeFinder::RangeFinder_State &state_arg } #endif +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index ca2decd044e309..e1ae5b50122c1d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include #include #include @@ -100,3 +104,5 @@ class AP_RangeFinder_Backend virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0; }; + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp index 659a4af1991067..69e43afc481fdb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp @@ -13,11 +13,13 @@ along with this program. If not, see . */ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_BACKEND_CAN_ENABLED + #include #include "AP_RangeFinder_Backend_CAN.h" -#if HAL_MAX_CAN_PROTOCOL_DRIVERS - const AP_Param::GroupInfo AP_RangeFinder_Backend_CAN::var_info[] = { // @Param: RECV_ID @@ -45,7 +47,7 @@ AP_RangeFinder_Backend_CAN::AP_RangeFinder_Backend_CAN( { AP_Param::setup_object_defaults(this, var_info); state.var_info = var_info; - multican_rangefinder = new MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name}; + multican_rangefinder = NEW_NOTHROW MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name}; if (multican_rangefinder == nullptr) { AP_BoardConfig::allocation_error("Failed to create rangefinder multican"); } @@ -87,4 +89,4 @@ bool AP_RangeFinder_Backend_CAN::is_correct_id(uint32_t id) const return true; } -#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_BACKEND_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h index 96d62aa94dedf9..5f915094198e4e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h @@ -1,9 +1,10 @@ #pragma once -#include "AP_RangeFinder_Backend.h" +#include "AP_RangeFinder_config.h" -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#if AP_RANGEFINDER_BACKEND_CAN_ENABLED +#include "AP_RangeFinder_Backend.h" #include #include @@ -61,4 +62,4 @@ class AP_RangeFinder_Backend_CAN : public AP_RangeFinder_Backend uint32_t _distance_count; }; -#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_BACKEND_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp index af27aaf5a7ad42..0dacdca94d0c2a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include #include "AP_RangeFinder_Backend_Serial.h" #include @@ -61,3 +65,5 @@ void AP_RangeFinder_Backend_Serial::update(void) set_status(RangeFinder::Status::NoData); } } + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h index e4349d75b8a8f2..35f3f8dca4f24c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include "AP_RangeFinder_Backend.h" class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend @@ -38,3 +42,5 @@ class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend // maximum time between readings before we change state to NoData: virtual uint16_t read_timeout_ms() const { return 200; } }; + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp index 5d1dd73ff4b435..043397d1e38e88 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp @@ -64,7 +64,7 @@ static const uint16_t waveform_mode1[32] = { AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : AP_RangeFinder_Backend(_state, _params), - _thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void))) + _thread(NEW_NOTHROW Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void))) { _init(); _freq = RNFD_BEBOP_DEFAULT_FREQ; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h index f6b62d4ac2e6ec..785bbdf0c1f021 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h @@ -13,7 +13,7 @@ class AP_RangeFinder_Benewake_TF02 : public 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); + return NEW_NOTHROW AP_RangeFinder_Benewake_TF02(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h index 2e2318ae22ee55..82790796a8b2a3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h @@ -13,7 +13,7 @@ class AP_RangeFinder_Benewake_TF03 : public 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); + return NEW_NOTHROW AP_RangeFinder_Benewake_TF03(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h index 451cdfe5259c7e..71cd0e8932c52e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h @@ -13,7 +13,7 @@ class AP_RangeFinder_Benewake_TFMini : public 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); + return NEW_NOTHROW AP_RangeFinder_Benewake_TFMini(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp index fc4e227c74b051..0e3e9548166112 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp @@ -56,7 +56,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_Benewake_TFMiniPlus::detect( } AP_RangeFinder_Benewake_TFMiniPlus *sensor - = new AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev)); if (!sensor || !sensor->init()) { delete sensor; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 4db29571beda1b..37c623b53166aa 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -13,14 +13,11 @@ extern const AP_HAL::HAL& hal; #define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) //links the rangefinder uavcan message to this backend -void AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("measurement_sub"); - } + const auto driver_index = ap_dronecan->get_driver_index(); + + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, driver_index) != nullptr); } //Method to find the backend relating to the node id @@ -60,7 +57,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneC //it up as UAVCAN type return nullptr; } - frontend.drivers[i] = new AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]); + frontend.drivers[i] = NEW_NOTHROW AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]); driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i]; if (driver == nullptr) { break; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 6d763b2b97fba8..6f575db8391144 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -16,7 +16,7 @@ class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend { void update() override; - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_RangeFinder_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h index 7347e649e14408..4a4363ab1fe504 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h @@ -15,7 +15,7 @@ class AP_RangeFinder_GYUS42v2 : public 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); + return NEW_NOTHROW AP_RangeFinder_GYUS42v2(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp index 6e7cc156ec47a3..942d0eeb9e44a1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp @@ -104,7 +104,7 @@ void AP_RangeFinder_HC_SR04::update(void) state.distance_m = 0.0f; } } else { - // gcs().send_text(MAV_SEVERITY_WARNING, "Pong!"); + // GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Pong!"); // a new reading - convert time to distance state.distance_m = (value_us * (1.0/58.0f)) * 0.01f; // 58 is from datasheet, mult for performance @@ -134,7 +134,7 @@ void AP_RangeFinder_HC_SR04::update(void) // consider sending new ping if (now - last_ping_ms > 67) { // read ~@15Hz - recommended 60ms delay from datasheet last_ping_ms = now; - // gcs().send_text(MAV_SEVERITY_INFO, "Ping!"); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Ping!"); // raise stop pin for n-microseconds hal.gpio->pinMode(trigger_pin, HAL_GPIO_OUTPUT); hal.gpio->write(trigger_pin, 1); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h index e37030a9713989..ea44688440b8c9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -70,7 +70,7 @@ class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_JRE_Serial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_JRE_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h index 0a655c51837b54..8ca44d30f56be8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h @@ -15,7 +15,7 @@ class AP_RangeFinder_Lanbao : public 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); + return NEW_NOTHROW AP_RangeFinder_Lanbao(_state, _params); } // Lanbao is always 115200: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h index 43ee3f09ba98b7..8053c7b496dd17 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h @@ -49,7 +49,7 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_LeddarOne(_state, _params); + return NEW_NOTHROW AP_RangeFinder_LeddarOne(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h index 68db11394ebc38..b3d71b9098e89c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h @@ -17,7 +17,7 @@ class AP_RangeFinder_LeddarVu8 : public 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); + return NEW_NOTHROW AP_RangeFinder_LeddarVu8(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 725b76f4f63ad6..5e600ca463dd27 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -81,7 +81,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder::RangeFi } AP_RangeFinder_LightWareI2C *sensor - = new AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev)); if (!sensor) { return nullptr; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index 13f4e776cdd0e5..632f9534c7f914 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -15,7 +15,7 @@ class AP_RangeFinder_LightWareSerial : public 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); + return NEW_NOTHROW AP_RangeFinder_LightWareSerial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp index 75e22b2aaba5f4..9d5facdb5af91a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp @@ -48,16 +48,11 @@ bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { WITH_SEMAPHORE(_sem); - // Time out on incoming data; if we don't get new data in 500ms, dump it - if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { - set_status(_state_pending, RangeFinder::Status::NoData); - } else { - _state_pending.last_reading_ms = now; - _state_pending.distance_m = dist_m; - _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; - _state_pending.voltage_mv = 0; - update_status(_state_pending); - } + _state_pending.last_reading_ms = now; + _state_pending.distance_m = dist_m; + _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; + _state_pending.voltage_mv = 0; + update_status(_state_pending); return true; } @@ -66,6 +61,12 @@ bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { void AP_RangeFinder_Lua::update(void) { WITH_SEMAPHORE(_sem); + + // Time out on incoming data + if (_state_pending.status != RangeFinder::Status::NotConnected && + AP_HAL::millis() - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { + set_status(_state_pending, RangeFinder::Status::NoData); + } state = _state_pending; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 1cb7cdc5af66b3..a5aedb1758013a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -54,7 +54,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeF } AP_RangeFinder_MaxsonarI2CXL *sensor - = new AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index b0693c11e3247e..62ac3de22f115c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -15,7 +15,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_MaxsonarSerialLV(_state, _params); + return NEW_NOTHROW AP_RangeFinder_MaxsonarSerialLV(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index d8c7ff3d145201..7f18c05916343d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -30,7 +30,7 @@ class AP_RangeFinder_NMEA : public 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); + return NEW_NOTHROW AP_RangeFinder_NMEA(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h index e40fe11dd62f43..eeedf71cecea2d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h @@ -14,7 +14,7 @@ class AP_RangeFinder_NoopLoop : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_NoopLoop(_state, _params); + return NEW_NOTHROW AP_RangeFinder_NoopLoop(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index 83816dd8653764..72630f95f3949c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -1,3 +1,7 @@ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include "AP_RangeFinder_Params.h" #include "AP_RangeFinder.h" @@ -10,13 +14,14 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @Param: TYPE // @DisplayName: Rangefinder type // @Description: Type of connected rangefinder + // @SortValues: AlphabeticalZeroAtTop // @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,36:Lua_Scripting,37:NoopLoop_TOFSense,38:NoopLoop_TOFSense_CAN,39:NRA24_CAN,40:NoopLoop_TOFSenseF_I2C,41:JRE_Serial,42:Ainstein_LR_D1,43:RDS02UF,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. For PWM input, the pin must be configured as a digital GPIO, see the Wiki's "GPIOs" section for details. + // @Description: Analog or PWM input pin that rangefinder is connected to. Analog RSSI or Airspeed ports can be used for Analog inputs (some autopilots provide others also), Non-IOMCU Servo/MotorOutputs can be used for PWM input when configured as "GPIOs". Values for some autopilots are given as examples. Search wiki for "Analog pins" for analog pin or "GPIOs", if PWM input type, to determine pin number. // @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), @@ -139,3 +144,5 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { AP_RangeFinder_Params::AP_RangeFinder_Params(void) { AP_Param::setup_object_defaults(this, var_info); } + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.h b/libraries/AP_RangeFinder/AP_RangeFinder_Params.h index 23e4406d073b0a..17893c3e6812fb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_ENABLED + #include #include @@ -27,3 +31,5 @@ class AP_RangeFinder_Params { AP_Int8 address; AP_Int8 orientation; }; + +#endif // AP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 608f2492efa3bd..dbb4ace8aa8db4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -62,7 +62,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus, RangeFinder::Type rftype) { AP_RangeFinder_PulsedLightLRF *sensor - = new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype); + = NEW_NOTHROW AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype); if (!sensor || !sensor->init()) { delete sensor; @@ -207,7 +207,7 @@ bool AP_RangeFinder_PulsedLightLRF::init(void) } } - printf("Found LidarLite device=0x%x v2=%d v3hp=%d\n", _dev->get_bus_id(), (int)v2_hardware, (int)v3hp_hardware); + printf("Found LidarLite device=0x%x v2=%d v3hp=%d\n", unsigned(_dev->get_bus_id()), (int)v2_hardware, (int)v3hp_hardware); _dev->get_semaphore()->give(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.cpp index 6e6087aaa66427..5044d4bb1f9126 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.cpp @@ -97,8 +97,9 @@ bool AP_RangeFinder_RDS02UF::get_reading(float &distance_m) } } - // reset buffer - body_length = 0; + // consume this message: + move_header_in_buffer(ARRAY_SIZE(u.parse_buffer)); + return true; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h index e4fc161c091649..6b480a17765c86 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h @@ -35,7 +35,7 @@ class AP_RangeFinder_RDS02UF : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_RDS02UF(_state, _params); + return NEW_NOTHROW AP_RangeFinder_RDS02UF(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp index 55f0e497d62f06..9c81e4e0c1aa46 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp @@ -47,7 +47,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TOFSenseF_I2C::detect(RangeFinder::RangeF } AP_RangeFinder_TOFSenseF_I2C *sensor - = new AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index c1772bfbad1f98..ab63b192dd1156 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -53,7 +53,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeF return nullptr; } - AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev)); + AP_RangeFinder_TeraRangerI2C *sensor = NEW_NOTHROW AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h index aba2d08df84510..90b65af283e554 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h @@ -15,7 +15,7 @@ class AP_RangeFinder_TeraRanger_Serial : public AP_RangeFinder_Backend_Serial static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_TeraRanger_Serial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_TeraRanger_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h index 3c48c38628f4b2..02cbb6e7045def 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h @@ -15,7 +15,7 @@ class AP_RangeFinder_USD1_Serial : public 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); + return NEW_NOTHROW AP_RangeFinder_USD1_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index 51c10dec8cd005..2286532cc315a2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -229,7 +229,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder::RangeFinder_ return nullptr; } AP_RangeFinder_VL53L0X *sensor - = new AP_RangeFinder_VL53L0X(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_VL53L0X(_state, _params, std::move(dev)); if (!sensor) { delete sensor; @@ -259,7 +259,7 @@ bool AP_RangeFinder_VL53L0X::check_id(void) v2 != 0xAA) { return false; } - printf("Detected VL53L0X on bus 0x%x\n", dev->get_bus_id()); + printf("Detected VL53L0X on bus 0x%x\n", unsigned(dev->get_bus_id())); return true; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index e0eba359eee8f1..97e778eb703760 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -48,7 +48,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L1X::detect(RangeFinder::RangeFinder_ } AP_RangeFinder_VL53L1X *sensor - = new AP_RangeFinder_VL53L1X(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_VL53L1X(_state, _params, std::move(dev)); if (!sensor) { delete sensor; @@ -81,7 +81,7 @@ bool AP_RangeFinder_VL53L1X::check_id(void) (v2 != 0xCC)) { return false; } - printf("Detected VL53L1X on bus 0x%x\n", dev->get_bus_id()); + printf("Detected VL53L1X on bus 0x%x\n", unsigned(dev->get_bus_id())); return true; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h index e0a3e15ca2b27c..f70d1b3f4e1a02 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h @@ -17,7 +17,7 @@ class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend_Serial { static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Wasp(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Wasp(_state, _params); } void update(void) override; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h index 71e1d012170a03..1f5407adaf5e73 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include #include @@ -14,15 +15,16 @@ #define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED AP_RANGEFINDER_ENABLED #endif +#ifndef AP_RANGEFINDER_BACKEND_CAN_ENABLED +#define AP_RANGEFINDER_BACKEND_CAN_ENABLED AP_RANGEFINDER_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif + #ifndef AP_RANGEFINDER_ANALOG_ENABLED #define AP_RANGEFINDER_ANALOG_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif #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 \ - ) +#define AP_RANGEFINDER_BBB_PRU_ENABLED (AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI) #endif #ifndef AP_RANGEFINDER_BENEWAKE_ENABLED @@ -94,7 +96,7 @@ #endif #ifndef AP_RANGEFINDER_LUA_ENABLED -#define AP_RANGEFINDER_LUA_ENABLED AP_SCRIPTING_ENABLED +#define AP_RANGEFINDER_LUA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED #endif #ifndef AP_RANGEFINDER_MAVLINK_ENABLED @@ -110,7 +112,7 @@ #endif #ifndef HAL_MSP_RANGEFINDER_ENABLED -#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED +#define HAL_MSP_RANGEFINDER_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_MSP_ENABLED #endif #ifndef AP_RANGEFINDER_NMEA_ENABLED @@ -141,12 +143,16 @@ #define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif +#ifndef HAL_MSP_RANGEFINDER_ENABLED +#define HAL_MSP_RANGEFINDER_ENABLED (AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_MSP_ENABLED) +#endif + #ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED #define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED -#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_RANGEFINDER_BACKEND_CAN_ENABLED #endif #ifndef AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED @@ -158,7 +164,7 @@ #endif #ifndef AP_RANGEFINDER_USD1_CAN_ENABLED -#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#define AP_RANGEFINDER_USD1_CAN_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_RANGEFINDER_BACKEND_CAN_ENABLED #endif #ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index fe3a73ab2d984c..2a64e19f59b75c 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -353,7 +353,11 @@ void AP_Relay::init() continue; } - if (function == AP_Relay_Params::FUNCTION::RELAY) { + bool use_default_param = (function == AP_Relay_Params::FUNCTION::RELAY); +#ifdef HAL_BUILD_AP_PERIPH + use_default_param |= (function >= AP_Relay_Params::FUNCTION::DroneCAN_HARDPOINT_0 && function <= AP_Relay_Params::FUNCTION::DroneCAN_HARDPOINT_15); +#endif + if (use_default_param) { // relay by instance number, set the state to match our output const AP_Relay_Params::DefaultState default_state = _params[instance].default_state; if ((default_state == AP_Relay_Params::DefaultState::OFF) || diff --git a/libraries/AP_RobotisServo/AP_RobotisServo.cpp b/libraries/AP_RobotisServo/AP_RobotisServo.cpp index 5261b1615db716..b234c1409c2dec 100644 --- a/libraries/AP_RobotisServo/AP_RobotisServo.cpp +++ b/libraries/AP_RobotisServo/AP_RobotisServo.cpp @@ -39,6 +39,7 @@ #if AP_ROBOTISSERVO_ENABLED #include +#include #include #include #include @@ -268,6 +269,9 @@ void AP_RobotisServo::send_command(uint8_t id, uint16_t reg, uint32_t value, uin txpacket[PKT_INSTRUCTION] = INST_WRITE; txpacket[PKT_INSTRUCTION+1] = DXL_LOBYTE(reg); txpacket[PKT_INSTRUCTION+2] = DXL_HIBYTE(reg); + + // Register values are transmitted as little-endian. + value = htole32(value); memcpy(&txpacket[PKT_INSTRUCTION+3], &value, MIN(len,4)); send_packet(txpacket); diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index 62a702bb86b198..0c3ae78f87e2b2 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -21,6 +21,8 @@ #include "AP_Scheduler_config.h" +#if AP_SCHEDULER_ENABLED + #include "AP_Scheduler.h" #include @@ -59,8 +61,9 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = { // @Param: LOOP_RATE // @DisplayName: Scheduling main loop rate // @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental. - // @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz + // @Range: 50 400 // @RebootRequired: True + // @Units: Hz // @User: Advanced AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE), @@ -123,7 +126,7 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint _num_tasks = _num_vehicle_tasks + _num_common_tasks; - _last_run = new uint16_t[_num_tasks]; + _last_run = NEW_NOTHROW uint16_t[_num_tasks]; _tick_counter = 0; // setup initial performance counters @@ -345,7 +348,8 @@ void AP_Scheduler::loop() _rsem.take_blocking(); hal.util->persistent_data.scheduler_task = -1; - const uint32_t sample_time_us = AP_HAL::micros(); + _loop_sample_time_us = AP_HAL::micros64(); + const uint32_t sample_time_us = uint32_t(_loop_sample_time_us); if (_loop_timer_start_us == 0) { _loop_timer_start_us = sample_time_us; @@ -443,6 +447,11 @@ void AP_Scheduler::update_logging() // Write a performance monitoring packet void AP_Scheduler::Log_Write_Performance() { + uint64_t rtc = 0; +#if AP_RTC_ENABLED + UNUSED_RESULT(AP::rtc().get_utc_usec(rtc)); +#endif + const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; struct log_Performance pkt = { LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG), @@ -460,6 +469,7 @@ void AP_Scheduler::Log_Write_Performance() i2c_count : pd.i2c_count, i2c_isr_count : pd.i2c_isr_count, extra_loop_us : extra_loop_us, + rtc : rtc, }; AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); } @@ -539,3 +549,5 @@ AP_Scheduler &scheduler() } }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/AP_Scheduler.h b/libraries/AP_Scheduler/AP_Scheduler.h index 68f39de24a4e7b..baf5534d62d2c1 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.h +++ b/libraries/AP_Scheduler/AP_Scheduler.h @@ -22,6 +22,8 @@ #include "AP_Scheduler_config.h" +#if AP_SCHEDULER_ENABLED + #include #include #include @@ -174,6 +176,11 @@ class AP_Scheduler return _last_loop_time_s; } + // get the time in microseconds that the current loop started + uint64_t get_loop_start_time_us(void) const { + return _loop_sample_time_us; + } + // get the amount of extra time being added on each loop uint32_t get_extra_loop_us(void) const { return extra_loop_us; @@ -238,12 +245,15 @@ class AP_Scheduler // number of ticks that _spare_micros is counted over uint8_t _spare_ticks; - // start of loop timing + // start of previous loop uint32_t _loop_timer_start_us; // time of last loop in seconds float _last_loop_time_s; - + + // start of current loop + uint64_t _loop_sample_time_us; + // bitmask bit which indicates if we should log PERF message uint32_t _log_performance_bit; @@ -268,3 +278,5 @@ class AP_Scheduler namespace AP { AP_Scheduler &scheduler(); }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/PerfInfo.cpp b/libraries/AP_Scheduler/PerfInfo.cpp index 1a9db4a96ecd1e..42ad17d7313cc6 100644 --- a/libraries/AP_Scheduler/PerfInfo.cpp +++ b/libraries/AP_Scheduler/PerfInfo.cpp @@ -1,3 +1,7 @@ +#include "AP_Scheduler_config.h" + +#if AP_SCHEDULER_ENABLED + #include "PerfInfo.h" #include @@ -13,6 +17,11 @@ extern const AP_HAL::HAL& hal; // we measure the main loop time // +// loops over time by this amount or more won't be counted in filtered loop time (and thus loop rate) +#ifndef AP_SCHEDULER_OVERTIME_MARGIN_US +#define AP_SCHEDULER_OVERTIME_MARGIN_US 10000UL +#endif + // reset - reset all records of loop time to zero void AP::PerfInfo::reset() { @@ -36,7 +45,7 @@ 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]; + _task_info = NEW_NOTHROW TaskInfo[num_tasks]; if (_task_info == nullptr) { DEV_PRINTF("Unable to allocate scheduler TaskInfo\n"); _num_tasks = 0; @@ -136,8 +145,16 @@ void AP::PerfInfo::check_loop_time(uint32_t time_in_micros) const uint32_t now = AP_HAL::micros(); const uint32_t loop_time_us = now - last_check_us; last_check_us = now; - if (loop_time_us < overtime_threshold_micros + 10000UL) { + if (loop_time_us < overtime_threshold_micros + AP_SCHEDULER_OVERTIME_MARGIN_US) { filtered_loop_time = 0.99f * filtered_loop_time + 0.01f * loop_time_us * 1.0e-6f; + } else { + // esp32 is most likely to regularly trigger long loops, might be + // helpful for bringup of other boards too +#if CONFIG_HAL_BOARD == HAL_BOARD_ESP32 +#ifdef SCHEDDEBUG + DEV_PRINTF("way overtime: %dus\n", loop_time_us); +#endif +#endif } } @@ -217,3 +234,5 @@ void AP::PerfInfo::set_loop_rate(uint16_t rate_hz) filtered_loop_time = 1.0f / rate_hz; } } + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/PerfInfo.h b/libraries/AP_Scheduler/PerfInfo.h index 83a8e3bdf94140..bbf6052e60ab58 100644 --- a/libraries/AP_Scheduler/PerfInfo.h +++ b/libraries/AP_Scheduler/PerfInfo.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_Scheduler_config.h" + +#if AP_SCHEDULER_ENABLED + #include #include @@ -76,3 +80,5 @@ class PerfInfo { }; }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index b54b890dceced7..1d19108bd1d438 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -94,6 +94,7 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = { // @Bitmask: 3: log runtime memory usage and execution time // @Bitmask: 4: Disable pre-arm check // @Bitmask: 5: Save CRC of current scripts to loaded and running checksum parameters enabling pre-arm + // @Bitmask: 6: Disable heap expansion on allocation failure // @User: Advanced AP_GROUPINFO("DEBUG_OPTS", 4, AP_Scripting, _debug_options, 0), @@ -160,6 +161,43 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = { // @RebootRequired: True // @User: Advanced AP_GROUPINFO("THD_PRIORITY", 14, AP_Scripting, _thd_priority, uint8_t(ThreadPriority::NORMAL)), + +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + // @Param: SDEV_EN + // @DisplayName: Scripting serial device enable + // @Description: Enable scripting serial devices + // @Values: 0:Disabled, 1:Enabled + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("SDEV_EN", 15, AP_Scripting, _serialdevice.enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: SDEV1_PROTO + // @DisplayName: Serial protocol of scripting serial device + // @Description: Serial protocol of scripting serial device + // @CopyFieldsFrom: SERIAL1_PROTOCOL + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("SDEV1_PROTO", 16, AP_Scripting, _serialdevice.ports[0].state.protocol, -1), + +#if AP_SCRIPTING_SERIALDEVICE_NUM_PORTS > 1 + // @Param: SDEV2_PROTO + // @DisplayName: Serial protocol of scripting serial device + // @Description: Serial protocol of scripting serial device + // @CopyFieldsFrom: SCR_SDEV1_PROTO + AP_GROUPINFO("SDEV2_PROTO", 17, AP_Scripting, _serialdevice.ports[1].state.protocol, -1), +#endif + +#if AP_SCRIPTING_SERIALDEVICE_NUM_PORTS > 2 + // @Param: SDEV3_PROTO + // @DisplayName: Serial protocol of scripting serial device + // @Description: Serial protocol of scripting serial device + // @CopyFieldsFrom: SCR_SDEV1_PROTO + AP_GROUPINFO("SDEV3_PROTO", 18, AP_Scripting, _serialdevice.ports[2].state.protocol, -1), +#endif +#endif // AP_SCRIPTING_SERIALDEVICE_ENABLED + + // WARNING: additional parameters must be listed before SDEV_EN (but have an + // index after SDEV3_PROTO) so they are not disabled by it! AP_GROUPEND }; @@ -220,14 +258,23 @@ void AP_Scripting::init(void) { } } +#if AP_SCRIPTING_SERIALDEVICE_ENABLED +void AP_Scripting::init_serialdevice_ports(void) { + if (!_enable) { + return; + } + + _serialdevice.init(); +} +#endif + #if HAL_GCS_ENABLED MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t &packet) { switch ((SCRIPTING_CMD)packet.param1) { case SCRIPTING_CMD_REPL_START: - return repl_start() ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; case SCRIPTING_CMD_REPL_STOP: - repl_stop(); - return MAV_RESULT_ACCEPTED; + return MAV_RESULT_DENIED; + case SCRIPTING_CMD_STOP: _restart = false; _stop = true; @@ -244,41 +291,6 @@ MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t & } #endif -bool AP_Scripting::repl_start(void) { - if (terminal.session) { // it's already running, this is fine - return true; - } - - // nuke the old folder and all contents - struct stat st; - if ((AP::FS().stat(REPL_DIRECTORY, &st) == -1) && - (AP::FS().unlink(REPL_DIRECTORY) == -1) && - (errno != EEXIST)) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno)); - } - - // create a new folder - AP::FS().mkdir(REPL_DIRECTORY); - // delete old files in case we couldn't - AP::FS().unlink(REPL_DIRECTORY "/in"); - AP::FS().unlink(REPL_DIRECTORY "/out"); - - // 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, "Scripting: %s", "Unable to make new REPL"); - return false; - } - - terminal.session = true; - return true; -} - -void AP_Scripting::repl_stop(void) { - terminal.session = false; - // 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 @@ -295,11 +307,16 @@ void AP_Scripting::thread(void) { _restart = false; _init_failed = false; - lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options, terminal); + lua_scripts *lua = NEW_NOTHROW lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options); if (lua == nullptr || !lua->heap_allocated()) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory"); _init_failed = true; } else { +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + // clear data in serial buffers that the script wasn't ready to + // receive + _serialdevice.clear(); +#endif // run won't return while scripting is still active lua->run(); @@ -334,6 +351,11 @@ void AP_Scripting::thread(void) { } } #endif // AP_NETWORKING_ENABLED + +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + // clear data in serial buffers that hasn't been transmitted + _serialdevice.clear(); +#endif // Clear blocked commands { @@ -359,7 +381,7 @@ void AP_Scripting::thread(void) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted"); break; } - if ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { + if (option_is_set(DebugOption::NO_SCRIPTS_TO_RUN)) { GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped"); } } @@ -376,7 +398,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd if (mission_data == nullptr) { // load buffer - mission_data = new ObjectBuffer(mission_cmd_queue_size); + mission_data = NEW_NOTHROW ObjectBuffer(mission_cmd_queue_size); if (mission_data != nullptr && mission_data->get_size() == 0) { delete mission_data; mission_data = nullptr; @@ -399,7 +421,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& 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)) { + if (!enabled() || option_is_set(DebugOption::DISABLE_PRE_ARM)) { return true; } @@ -497,9 +519,7 @@ void AP_Scripting::update() { // Check if DEBUG_OPTS bit has been set to save current checksum values to params void AP_Scripting::save_checksum() { - const uint8_t opts = _debug_options.get(); - const uint8_t save_bit = uint8_t(lua_scripts::DebugLevel::SAVE_CHECKSUM); - if ((opts & save_bit) == 0) { + if (!option_is_set(DebugOption::SAVE_CHECKSUM)) { // Bit not set, nothing to do return; } @@ -509,7 +529,7 @@ void AP_Scripting::save_checksum() { _required_running_checksum.set_and_save(lua_scripts::get_running_checksum() & checksum_param_mask); // Un-set debug option bit - _debug_options.set_and_save(opts & ~save_bit); + option_clear(DebugOption::SAVE_CHECKSUM); GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "saved checksums"); diff --git a/libraries/AP_Scripting/AP_Scripting.h b/libraries/AP_Scripting/AP_Scripting.h index f7139775c02f6b..869e11df547ef8 100644 --- a/libraries/AP_Scripting/AP_Scripting.h +++ b/libraries/AP_Scripting/AP_Scripting.h @@ -14,6 +14,8 @@ */ #pragma once +#include "AP_Scripting/AP_Scripting_config.h" + #if AP_SCRIPTING_ENABLED #include @@ -39,6 +41,10 @@ class SocketAPM; #endif +#if AP_SCRIPTING_SERIALDEVICE_ENABLED +#include "AP_Scripting_SerialDevice.h" +#endif + class AP_Scripting { public: @@ -49,6 +55,10 @@ class AP_Scripting void init(void); +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + void init_serialdevice_ports(void); +#endif + void update(); bool enabled(void) const { return _enable != 0; }; @@ -78,12 +88,6 @@ class AP_Scripting // User parameters for inputs into scripts AP_Float _user[6]; - struct terminal_s { - int output_fd; - off_t input_offset; - bool session; - } terminal; - enum class SCR_DIR { ROMFS = 1 << 0, SCRIPTS = 1 << 1, @@ -116,8 +120,8 @@ class AP_Scripting // PWMSource storage uint8_t num_pwm_source; AP_HAL::PWMSource *_pwm_source[SCRIPTING_MAX_NUM_PWM_SOURCE]; - int get_current_ref() { return current_ref; } - void set_current_ref(int ref) { current_ref = ref; } + int get_current_env_ref() { return current_env_ref; } + void set_current_env_ref(int ref) { current_env_ref = ref; } #if AP_NETWORKING_ENABLED // SocketAPM storage @@ -144,10 +148,21 @@ class AP_Scripting command_block_list *mavlink_command_block_list; HAL_Semaphore mavlink_command_block_list_sem; -private: + #if AP_SCRIPTING_SERIALDEVICE_ENABLED + AP_Scripting_SerialDevice _serialdevice; + #endif + + enum class DebugOption : uint8_t { + NO_SCRIPTS_TO_RUN = 1U << 0, + RUNTIME_MSG = 1U << 1, + SUPPRESS_SCRIPT_LOG = 1U << 2, + LOG_RUNTIME = 1U << 3, + DISABLE_PRE_ARM = 1U << 4, + SAVE_CHECKSUM = 1U << 5, + DISABLE_HEAP_EXPANSION = 1U << 6, + }; - bool repl_start(void); - void repl_stop(void); +private: void thread(void); // main script execution thread @@ -180,13 +195,21 @@ class AP_Scripting AP_Enum _thd_priority; + bool option_is_set(DebugOption option) const { + return (uint8_t(_debug_options.get()) & uint8_t(option)) != 0; + } + + void option_clear(DebugOption option) { + _debug_options.set_and_save(_debug_options.get() & ~uint8_t(option)); + } + 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 static AP_Scripting *_singleton; - int current_ref; + int current_env_ref; }; namespace AP { diff --git a/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp b/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp index 39f1bf9f870a09..796462e8a7e2e6 100644 --- a/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp +++ b/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp @@ -39,7 +39,7 @@ void ScriptingCANSensor::handle_frame(AP_HAL::CANFrame &frame) ScriptingCANBuffer* ScriptingCANSensor::add_buffer(uint32_t buffer_len) { WITH_SEMAPHORE(sem); - ScriptingCANBuffer *new_buff = new ScriptingCANBuffer(*this, buffer_len); + ScriptingCANBuffer *new_buff = NEW_NOTHROW ScriptingCANBuffer(*this, buffer_len); if (buffer_list == nullptr) { buffer_list = new_buff; } else { diff --git a/libraries/AP_Scripting/AP_Scripting_CANSensor.h b/libraries/AP_Scripting/AP_Scripting_CANSensor.h index 962aef8fbfa5f2..33b57360310236 100644 --- a/libraries/AP_Scripting/AP_Scripting_CANSensor.h +++ b/libraries/AP_Scripting/AP_Scripting_CANSensor.h @@ -60,7 +60,10 @@ class ScriptingCANSensor : public CANSensor { class ScriptingCANBuffer { public: - ScriptingCANBuffer(ScriptingCANSensor &_sensor, uint32_t buffer_size):sensor(_sensor), buffer(buffer_size) {}; + ScriptingCANBuffer(ScriptingCANSensor &_sensor, uint32_t buffer_size): + buffer(buffer_size), + sensor(_sensor) + {}; // Call main sensor write method bool write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us); diff --git a/libraries/AP_Scripting/AP_Scripting_SerialAccess.cpp b/libraries/AP_Scripting/AP_Scripting_SerialAccess.cpp new file mode 100644 index 00000000000000..f82ef3a127e9ef --- /dev/null +++ b/libraries/AP_Scripting/AP_Scripting_SerialAccess.cpp @@ -0,0 +1,72 @@ +/* + generic object to allow a script to use a serial driver stream from both + driver and device perspectives + */ + +#include "AP_Scripting_config.h" +#include "AP_Scripting.h" +#include "AP_Scripting_SerialAccess.h" + +#if AP_SCRIPTING_ENABLED + +#if AP_SCRIPTING_SERIALDEVICE_ENABLED +#define check_is_device_port() (is_device_port) +#define ON_DEVICE_PORT(func, ...) (((AP_Scripting_SerialDevice::Port*)stream)->device_##func (__VA_ARGS__)) +#else +#define check_is_device_port() (false) +#define ON_DEVICE_PORT(...) (0) // not executed +#endif + +void AP_Scripting_SerialAccess::begin(uint32_t baud) +{ + if (!check_is_device_port()) { + stream->begin(baud); + } +} + +size_t AP_Scripting_SerialAccess::write(uint8_t c) +{ + return write(&c, 1); +} + +size_t AP_Scripting_SerialAccess::write(const uint8_t *buffer, size_t size) +{ + if (!check_is_device_port()) { + return stream->write(buffer, size); + } + return ON_DEVICE_PORT(write, buffer, size); +} + +int16_t AP_Scripting_SerialAccess::read(void) +{ + uint8_t c; + if (read(&c, 1) != 1) { + return -1; + } + return c; +} + +ssize_t AP_Scripting_SerialAccess::read(uint8_t* buffer, uint16_t count) +{ + if (!check_is_device_port()) { + return stream->read(buffer, count); + } + return ON_DEVICE_PORT(read, buffer, count); +} + +uint32_t AP_Scripting_SerialAccess::available(void) +{ + if (!check_is_device_port()) { + return stream->available(); + } + return ON_DEVICE_PORT(available); +} + +void AP_Scripting_SerialAccess::set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs) +{ + if (!check_is_device_port()) { + stream->set_flow_control(fcs); + } +} + +#endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/AP_Scripting_SerialAccess.h b/libraries/AP_Scripting/AP_Scripting_SerialAccess.h new file mode 100644 index 00000000000000..7231359c818552 --- /dev/null +++ b/libraries/AP_Scripting/AP_Scripting_SerialAccess.h @@ -0,0 +1,33 @@ +#pragma once + +#include "AP_Scripting_config.h" +#include "AP_Scripting.h" + +#include + +class AP_Scripting_SerialAccess { +public: + /* Do not allow copies */ + CLASS_NO_COPY(AP_Scripting_SerialAccess); + + AP_Scripting_SerialAccess() {} + + void begin(uint32_t baud); + + size_t write(uint8_t c); + size_t write(const uint8_t *buffer, size_t size); + + int16_t read(void); + ssize_t read(uint8_t *buffer, uint16_t count); + + uint32_t available(void); + + void set_flow_control(enum AP_HAL::UARTDriver::flow_control fcs); + + AP_HAL::UARTDriver *stream; +#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + bool is_device_port; +#endif +#endif +}; diff --git a/libraries/AP_Scripting/AP_Scripting_SerialDevice.cpp b/libraries/AP_Scripting/AP_Scripting_SerialDevice.cpp new file mode 100644 index 00000000000000..7f7f13fb6486d1 --- /dev/null +++ b/libraries/AP_Scripting/AP_Scripting_SerialDevice.cpp @@ -0,0 +1,161 @@ +/* + port for a script to access from a device perspective + */ + +#include "AP_Scripting_config.h" + +#if AP_SCRIPTING_ENABLED && AP_SCRIPTING_SERIALDEVICE_ENABLED + +#include "AP_Scripting.h" + +#include +#include + +#ifndef AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE +#define AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE 2048 +#endif + +#ifndef AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE +#define AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE 2048 +#endif + +/* + initialise scripting serial ports +*/ +void AP_Scripting_SerialDevice::init(void) +{ + if (enable == 0) { + return; + } + + for (uint8_t i=0; iclear(); + } + if (writebuffer) { + writebuffer->clear(); + } +} + +size_t AP_Scripting_SerialDevice::Port::device_write(const uint8_t *buffer, size_t size) +{ + WITH_SEMAPHORE(sem); + if (readbuffer) { + return readbuffer->write(buffer, size); + } + return 0; +} + +ssize_t AP_Scripting_SerialDevice::Port::device_read(uint8_t *buffer, uint16_t count) +{ + WITH_SEMAPHORE(sem); + if (writebuffer) { + return writebuffer->read(buffer, count); + } + return 0; +} + +uint32_t AP_Scripting_SerialDevice::Port::device_available(void) +{ + WITH_SEMAPHORE(sem); + if (writebuffer) { + return writebuffer->available(); + } + return 0; +} + +/* + available space in outgoing buffer + */ +uint32_t AP_Scripting_SerialDevice::Port::txspace(void) +{ + WITH_SEMAPHORE(sem); + return writebuffer != nullptr ? writebuffer->space() : 0; +} + +void AP_Scripting_SerialDevice::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS) +{ + rxS = MAX(rxS, AP_SCRIPTING_SERIALDEVICE_MIN_RXSIZE); + txS = MAX(txS, AP_SCRIPTING_SERIALDEVICE_MIN_TXSIZE); + init_buffers(rxS, txS); +} + +size_t AP_Scripting_SerialDevice::Port::_write(const uint8_t *buffer, size_t size) +{ + WITH_SEMAPHORE(sem); + return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0; +} + +ssize_t AP_Scripting_SerialDevice::Port::_read(uint8_t *buffer, uint16_t count) +{ + WITH_SEMAPHORE(sem); + return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1; +} + +uint32_t AP_Scripting_SerialDevice::Port::_available() +{ + WITH_SEMAPHORE(sem); + return readbuffer != nullptr ? readbuffer->available() : 0; +} + + +bool AP_Scripting_SerialDevice::Port::_discard_input() +{ + WITH_SEMAPHORE(sem); + if (readbuffer != nullptr) { + readbuffer->clear(); + } + return true; +} + +/* + initialise read/write buffers + */ +bool AP_Scripting_SerialDevice::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx) +{ + if (size_tx == last_size_tx && + size_rx == last_size_rx) { + return true; + } + WITH_SEMAPHORE(sem); + if (readbuffer == nullptr) { + readbuffer = NEW_NOTHROW ByteBuffer(size_rx); + } else { + readbuffer->set_size_best(size_rx); + } + if (writebuffer == nullptr) { + writebuffer = NEW_NOTHROW ByteBuffer(size_tx); + } else { + writebuffer->set_size_best(size_tx); + } + last_size_rx = size_rx; + last_size_tx = size_tx; + return readbuffer != nullptr && writebuffer != nullptr; +} + +#endif // AP_SCRIPTING_ENABLED && AP_SCRIPTING_SERIALDEVICE_ENABLED diff --git a/libraries/AP_Scripting/AP_Scripting_SerialDevice.h b/libraries/AP_Scripting/AP_Scripting_SerialDevice.h new file mode 100644 index 00000000000000..86273f126697f5 --- /dev/null +++ b/libraries/AP_Scripting/AP_Scripting_SerialDevice.h @@ -0,0 +1,69 @@ +#pragma once + +#include "AP_Scripting_config.h" + +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + +#include + +#ifndef AP_SCRIPTING_SERIALDEVICE_NUM_PORTS +#define AP_SCRIPTING_SERIALDEVICE_NUM_PORTS 3 +#endif + +class AP_Scripting; + +class AP_Scripting_SerialDevice +{ +public: + /* Do not allow copies */ + CLASS_NO_COPY(AP_Scripting_SerialDevice); + + AP_Scripting_SerialDevice() {} + + AP_Int8 enable; + + void init(void); + void clear(void); + +public: + class Port : public AP_SerialManager::RegisteredPort { + public: + friend class AP_Scripting_SerialDevice; + void init(void); + void clear(void); + + size_t device_write(const uint8_t *buffer, size_t size); + ssize_t device_read(uint8_t *buffer, uint16_t count); + uint32_t device_available(void); + + private: + bool is_initialized() override { + return true; + } + bool tx_pending() override { + return false; + } + + bool init_buffers(const uint32_t size_rx, const uint32_t size_tx); + + uint32_t txspace() override; + void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + size_t _write(const uint8_t *buffer, size_t size) override; + ssize_t _read(uint8_t *buffer, uint16_t count) override; + uint32_t _available() override; + void _end() override {} + void _flush() override {} + bool _discard_input() override; + + ByteBuffer *readbuffer; + ByteBuffer *writebuffer; + uint32_t last_size_tx; + uint32_t last_size_rx; + + HAL_Semaphore sem; + }; + + Port ports[AP_SCRIPTING_SERIALDEVICE_NUM_PORTS]; +}; + +#endif // AP_SCRIPTING_SERIALDEVICE_ENABLED diff --git a/libraries/AP_Scripting/AP_Scripting_config.h b/libraries/AP_Scripting/AP_Scripting_config.h index a58d83062b9d34..768e751ca7bb1d 100644 --- a/libraries/AP_Scripting/AP_Scripting_config.h +++ b/libraries/AP_Scripting/AP_Scripting_config.h @@ -1,6 +1,7 @@ #pragma once #include +#include #ifndef AP_SCRIPTING_ENABLED #define AP_SCRIPTING_ENABLED (BOARD_FLASH_SIZE > 1024) @@ -8,7 +9,12 @@ #if AP_SCRIPTING_ENABLED #include - #if !AP_FILESYSTEM_FILE_READING_ENABLED + // enumerate all of the possible places we can read a script from. + #if !AP_FILESYSTEM_POSIX_ENABLED && !AP_FILESYSTEM_FATFS_ENABLED && !AP_FILESYSTEM_ESP32_ENABLED && !AP_FILESYSTEM_ROMFS_ENABLED #error "Scripting requires a filesystem" #endif #endif + +#ifndef AP_SCRIPTING_SERIALDEVICE_ENABLED +#define AP_SCRIPTING_SERIALDEVICE_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024) +#endif diff --git a/libraries/AP_Scripting/AP_Scripting_helpers.cpp b/libraries/AP_Scripting/AP_Scripting_helpers.cpp index 01e13c99f847d6..380ac3ef73ca0b 100644 --- a/libraries/AP_Scripting/AP_Scripting_helpers.cpp +++ b/libraries/AP_Scripting/AP_Scripting_helpers.cpp @@ -20,9 +20,7 @@ int lua_new_Parameter(lua_State *L) { } // This chunk is the same as the auto generated constructor - luaL_checkstack(L, 2, "Out of stack"); void *ud = lua_newuserdata(L, sizeof(Parameter)); - memset(ud, 0, sizeof(Parameter)); new (ud) Parameter(); luaL_getmetatable(L, "Parameter"); lua_setmetatable(L, -2); @@ -54,16 +52,16 @@ bool Parameter::init_by_info(uint16_t key, uint32_t group_element, enum ap_var_t { switch (type) { case AP_PARAM_INT8: - vp = new AP_Int8; + vp = NEW_NOTHROW AP_Int8; break; case AP_PARAM_INT16: - vp = new AP_Int16; + vp = NEW_NOTHROW AP_Int16; break; case AP_PARAM_INT32: - vp = new AP_Int32; + vp = NEW_NOTHROW AP_Int32; break; case AP_PARAM_FLOAT: - vp = new AP_Float; + vp = NEW_NOTHROW AP_Float; break; default: return false; diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua index c0b674e5ae8508..a6100ad6ba0554 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua @@ -6,6 +6,10 @@ 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 ]]-- -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil +---@diagnostic disable: cast-local-type +---@diagnostic disable: undefined-global DO_JUMP = 177 k_throttle = 70 diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index 50da4616dd9d74..9dee1d007e037d 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -5,6 +5,13 @@ assistance from Paul Riseborough, testing by Henry Wurzburg ]]-- -- luacheck: ignore 212 (Unused argument) +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: undefined-field +---@diagnostic disable: missing-parameter +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil +---@diagnostic disable: undefined-global +---@diagnostic disable: inject-field -- setup param block for aerobatics, reserving 35 params beginning with AERO_ local PARAM_TABLE_KEY = 70 @@ -2117,7 +2124,9 @@ end -- log a pose from position and quaternion attitude function log_pose(logname, pos, quat) - logger.write(logname, 'px,py,pz,q1,q2,q3,q4,r,p,y', 'ffffffffff', + local loc = ahrs:get_origin():copy() + loc:offset(pos:x(),pos:y()) + logger.write(logname, 'px,py,pz,q1,q2,q3,q4,r,p,y,Lat,Lon', 'ffffffffffLL', pos:x(), pos:y(), pos:z(), @@ -2127,7 +2136,9 @@ function log_pose(logname, pos, quat) quat:q4(), math.deg(quat:get_euler_roll()), math.deg(quat:get_euler_pitch()), - math.deg(quat:get_euler_yaw())) + math.deg(quat:get_euler_yaw()), + loc:lat(), + loc:lng()) end --[[ diff --git a/libraries/AP_Scripting/applets/BattEstimate.lua b/libraries/AP_Scripting/applets/BattEstimate.lua index 1221a4b74dbb94..497e89fa53a69f 100644 --- a/libraries/AP_Scripting/applets/BattEstimate.lua +++ b/libraries/AP_Scripting/applets/BattEstimate.lua @@ -4,6 +4,9 @@ See Tools/scripts/battery_fit.py for a tool to calculate the coefficients from a log --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type + local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local PARAM_TABLE_KEY = 14 diff --git a/libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua b/libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua index 84d2343f0e56a4..63f95da179b0b3 100644 --- a/libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua +++ b/libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua @@ -5,6 +5,7 @@ -- the value of the 50% point on the curve. This can be used to set the collective position to aid with hovering -- at the midstick. -- luacheck: only 0 +---@diagnostic disable: cast-local-type -- Tested and working as of 25th Aug 2020 (Copter Dev) diff --git a/libraries/AP_Scripting/applets/Heli_idle_control.lua b/libraries/AP_Scripting/applets/Heli_idle_control.lua index 16e7de0a0056bf..64e1a71bc8b8d1 100644 --- a/libraries/AP_Scripting/applets/Heli_idle_control.lua +++ b/libraries/AP_Scripting/applets/Heli_idle_control.lua @@ -1,4 +1,6 @@ -- idle_control.lua: a closed loop control throttle control while on ground idle (trad-heli) +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil local PARAM_TABLE_KEY = 73 local PARAM_TABLE_PREFIX = 'IDLE_' diff --git a/libraries/AP_Scripting/applets/MissionSelector.lua b/libraries/AP_Scripting/applets/MissionSelector.lua index b20c01835efc25..b5a1c72807bd11 100644 --- a/libraries/AP_Scripting/applets/MissionSelector.lua +++ b/libraries/AP_Scripting/applets/MissionSelector.lua @@ -2,7 +2,6 @@ -- Must have Mission Reset switch assigned, it will function normally when armed or disarmed -- but also on the disarm to arm transition, it will load (if file exists) a file in the root named -- missionH.txt, missionM.txt, or missionH.txt corresponding to the the Mission Reset switch position of High/Mid/Low --- luacheck: only 0 local mission_loaded = false local rc_switch = rc:find_channel_for_option(24) --AUX FUNC sw for mission restart @@ -13,12 +12,12 @@ end local function read_mission(file_name) - -- Open file try and read header + -- Open file try and read header local file = io.open(file_name,"r") - local header = file:read('l') - if not header then + if not file then return update, 1000 --could not read, file probably does not exist end + local header = file:read('l') -- check header assert(string.find(header,'QGC WPL 110') == 1, file_name .. ': incorrect format') @@ -62,7 +61,6 @@ local function read_mission(file_name) end index = index + 1 end - file:close() end function update() @@ -86,4 +84,6 @@ function update() return update, 1000 end +gcs:send_text(5,"Loaded MissionSelector.lua") + return update, 5000 diff --git a/libraries/AP_Scripting/applets/Param_Controller.lua b/libraries/AP_Scripting/applets/Param_Controller.lua new file mode 100644 index 00000000000000..bb9764369fbfdc --- /dev/null +++ b/libraries/AP_Scripting/applets/Param_Controller.lua @@ -0,0 +1,94 @@ +--[[ + a script to select other parameters using an auxillary switch + from subdirectories in scripts directory labeled /1,/2, or /3 +--]] + +local SEL_CH = 302 +local PARAM_FILENAME = "params.param" + +--[[ + check that directory exists +--]] +function check_subdir_exists(n) + return dirlist(get_scripts_dir() .. "/" .. n ) +end + +--[[ + get the path to the scripts directory. This will be scripts/ on SITL + and APM/scripts on a ChibiOS board +--]] +function get_scripts_dir() + local dlist1 = dirlist("APM/scripts") + if dlist1 and #dlist1 > 0 then + return "APM/scripts" + end + -- otherwise assume scripts/ + return "scripts" +end + +--[[ +load parameters from a file PARAM_FILENAME from directory n +--]] +function param_load(n) + count = 0 + failed = false + file_name = get_scripts_dir() .. "/" .. n .."/" .. PARAM_FILENAME + -- Open file + file = io.open(file_name) + if not file then + gcs:send_text(0,string.format("%s not present",file_name)) + return + end + while true do + local line = file:read() + if not line then + break + end + -- trim trailing spaces + line = string.gsub(line, '^(.-)%s*$', '%1') + local _, _, parm, value = string.find(line, "^([%w_]+)%s*([%d]*.[%d]*)") + if parm then + if not param:set(parm,value) then + failed = true + else + count = count +1 + end + end + end + if not failed then + gcs:send_text(6,string.format("Loaded %u parameters",count)) + else + gcs:send_text(6,string.format("Loaded %u parameters but some params did not exist to set",count)) + end +end + +local sw_last = -1 +local load_param = true + +function update() + local sw_current = rc:get_aux_cached(SEL_CH) + if (sw_current == sw_last) or (sw_current == nil) then + return update, 500 + end + if sw_current == 0 then + subdir = 1 + elseif sw_current == 2 then + subdir = 3 + else + subdir = 2 + end + sw_last = sw_current + if not check_subdir_exists(subdir) then + gcs:send_text(0,string.format("Scripts subdirectory /%s does not exist!",subdir)) + return update, 500 + end + if load_param then + param_load(subdir) + load_param = false + end + + return update, 500 +end + +gcs:send_text(5,"Loaded Parameter_Controller.lua") +return update, 500 diff --git a/libraries/AP_Scripting/applets/Param_Controller.md b/libraries/AP_Scripting/applets/Param_Controller.md new file mode 100644 index 00000000000000..9a028a326af263 --- /dev/null +++ b/libraries/AP_Scripting/applets/Param_Controller.md @@ -0,0 +1,9 @@ +# Param_Controller LUA script + +This script allows the user to have different parameters (in files named "params.parm") in three subdirectories of the main scripting directory and load them based on the position of a switch with the auxiliary function of "302". This allows easy, at the field selection of parameter sets. It uses the same switch function and directories as the Scripting_Controller.lua script selector and the two may be used together, if desired. + +# Setup and Operation + +The user must setup an RCx_OPTION to function 302 to determine which of the three scripts subdirectories will be used: LOW:scripts/1, MIDDLE:scripts/2, or HIGH:scripts/3. If no RC has been established during ground start, it will behave as if subdirectory 1 is selected. Changing this switch position either prior to ground start or after, will load a "params.param" file from the desginated subdirectory (if it and its subdirectory exists). Mission Planner also provides a means of executing the same function as an RC switch assigned to 302 in its AUX Function tab, so a transmitter switch does not necessarily need to be used. + +Note that loaded parameter changes are not saved across reboots, that must be done manually. diff --git a/libraries/AP_Scripting/applets/RockBlock.lua b/libraries/AP_Scripting/applets/RockBlock.lua index f8e675cbb0484a..2c5e175b1be1c0 100644 --- a/libraries/AP_Scripting/applets/RockBlock.lua +++ b/libraries/AP_Scripting/applets/RockBlock.lua @@ -24,12 +24,14 @@ The param SCR_VM_I_COUNT may need to be increased in some circumstances Written by Stephen Dade (stephen_dade@hotmail.com) ]]-- +---@diagnostic disable: cast-local-type + local PARAM_TABLE_KEY = 10 local PARAM_TABLE_PREFIX = "RCK_" local port = serial:find_serial(0) -if not port or baud == 0 then +if not port then gcs:send_text(0, "Rockblock: No Scripting Serial Port") return end diff --git a/libraries/AP_Scripting/applets/Script_Controller.lua b/libraries/AP_Scripting/applets/Script_Controller.lua index 6957455ae37418..4fb787b00874d5 100644 --- a/libraries/AP_Scripting/applets/Script_Controller.lua +++ b/libraries/AP_Scripting/applets/Script_Controller.lua @@ -3,6 +3,8 @@ /1 /2 or /3 subdirectories of the scripts directory --]] -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch + local THIS_SCRIPT = "Script_Controller.lua" local sel_ch = Parameter("SCR_USER6") diff --git a/libraries/AP_Scripting/applets/SmartAudio.lua b/libraries/AP_Scripting/applets/SmartAudio.lua index a5820d598e8cd7..00a3142f08fb17 100644 --- a/libraries/AP_Scripting/applets/SmartAudio.lua +++ b/libraries/AP_Scripting/applets/SmartAudio.lua @@ -20,6 +20,9 @@ ---------and set to -1 for unchanged, 0 (PitMode),1,2,3, or 4 for power level (1 lowest,4 maximum) -- 3. Attach the UART's TX for the Serial port chosen above to the VTX's SmartAudio input +---@diagnostic disable: need-check-nil + + -- init local variables local startup_pwr = param:get('SCR_USER1') local scripting_rc = rc:find_channel_for_option(300) diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index 79d6af069ac83f..29c5c3ae2646e7 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.lua +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -6,6 +6,9 @@ --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil +---@diagnostic disable: missing-parameter --[[ - TODO: @@ -398,7 +401,7 @@ function adjust_gain(pname, value) 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 + -- usually we want I = FF for a one second time constant for trim return end param_changed[iname] = true diff --git a/libraries/AP_Scripting/applets/advance-wp.lua b/libraries/AP_Scripting/applets/advance-wp.lua new file mode 100644 index 00000000000000..eec8633a89317c --- /dev/null +++ b/libraries/AP_Scripting/applets/advance-wp.lua @@ -0,0 +1,168 @@ +--[[---------------------------------------------------------------------------- + +advance-wp ArduPilot Lua script + +Set WAYPT_ADVANCE to an aux function number (e.g. 300). +Set RCx_OPTION to the chosen aux function number (preferably on a momentary switch). + +When the RC switch is activated, waypoint index will be advanced to the next waypoint +(wraps to WP1 after the last waypoint). + +Mission Planner's Aux Function tab can be used in lieu of dedicating RC channels. + +Optionally: + Set WAYPT_ANNOUNCE to another aux function number (e.g. 301). + Set WAYPT_ANNOUNCE_S to desired interval (s) between waypoint announcements (0 to disable). + Set WAYPT_BUZ_ENABLE to 1 to enable buzzer feedback vs waypoint distance. + Set RCx_OPTION to the chosen aux function number. + + When the announce switch is activated, the current waypoint index, bearing, and distance + will be broadcast as a GCS message every WAYPT_ANNOUNCE_S seconds (useful when using a + telemetry link like "Yaapu" where named float values are not always readily displayed). + + If WAYPT_BUZ_ENABLE is set, the buzzer will increase in frequency and pitch as distance + to the selected waypoint decreases (useful if no telemetry source is readily available). + +CAUTION: This script is capable of engaging and disengaging autonomous control +of a vehicle. Use this script AT YOUR OWN RISK. + +-- Yuri -- Apr 2024 + +LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html +------------------------------------------------------------------------------]] + +local RUN_INTERVAL_MS = 100 +local PARAM_TABLE_KEY = 193 +local PARAM_TABLE_PREFIX = 'WAYPT_' +local MAV_SEVERITY = { + EMERGENCY = 0, + ALERT = 1, + CRITICAL = 2, + ERROR = 3, + WARNING = 4, + NOTICE = 5, + INFO = 6, + DEBUG = 7 +} + +-- borrowed from Rover QuikTune +local function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format("Advance WP: Could not find %s parameter", name)) + return p +end + +local 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 + +local function get_wp_location(item) + local loc = Location() + loc:lat(item:x()) + loc:lng(item:y()) + loc:alt(math.floor(item:z() * 100)) + return loc +end + +local function get_pitch_by_distance(distance) + local max_distance = 300 + local min_distance = 0.01 + local total_notes = 73 + + distance = math.max(min_distance, math.min(distance, max_distance)) + local scale_factor = 105 -- scale factor adjusted for a good spread over the distance range + local log_ratio = math.log(max_distance / distance) + local max_log_ratio = math.log(max_distance / min_distance) -- max possible value of log_ratio + local log_distance_scaled = log_ratio / max_log_ratio * total_notes * scale_factor / 100 + local note_index = math.min(math.floor(log_distance_scaled), total_notes - 1) + + return 'N' .. math.max(1, note_index) +end + +local function get_buzz_interval(distance) + local max_distance = 100 + local min_distance = 0.01 + local max_interval = 2000 + local min_interval = 250 + + distance = math.max(min_distance, math.min(distance, max_distance)) + local interval = max_interval - (max_interval - min_interval) * ((max_distance - distance) / max_distance) + return math.floor(interval) +end + +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 4), 'Advance WP: Could not add param table') + +local WAYPT_ADVANCE = bind_add_param('ADVANCE', 1, 300) +local WAYPT_ANNOUNCE = bind_add_param('ANNOUNCE', 2, 301) +local WAYPT_ANNOUNCE_S = bind_add_param('ANNOUNCE_S', 3, 0) +local WAYPT_BUZ_ENABLE = bind_add_param('BUZ_ENABLE', 4, 1) + +local last_advance_sw_pos = -1 +local last_announce_ms = uint32_t(0) +local last_buzz_ms = uint32_t(0) +function update() + ---- WAYPT_ADVANCE ---- + local advance_opt = WAYPT_ADVANCE:get() + if not advance_opt then return update, RUN_INTERVAL_MS end + + local adv_sw_pos = rc:get_aux_cached(advance_opt) + if not adv_sw_pos then return update, RUN_INTERVAL_MS end + + local num_commands = mission:num_commands() + if num_commands < 1 then return update, RUN_INTERVAL_MS end + + if adv_sw_pos > 0 and adv_sw_pos ~= last_advance_sw_pos then + local nav_index = mission:get_current_nav_index() + local new_index = (nav_index + 1) % mission:num_commands() + mission:set_current_cmd(new_index) + gcs:send_text(MAV_SEVERITY.NOTICE, ('Advance WP -> %d'):format(mission:get_current_nav_index())) + end + last_advance_sw_pos = adv_sw_pos or 0 + + ---- WAYPT_ANNOUNCE ---- + local announce_s = WAYPT_ANNOUNCE_S:get() + if not announce_s then return update, RUN_INTERVAL_MS end + if announce_s <= 0 then return update, RUN_INTERVAL_MS end + + local announce_opt = WAYPT_ANNOUNCE:get() + if not announce_opt then return update, RUN_INTERVAL_MS end + + local ann_sw_pos = rc:get_aux_cached(announce_opt) + if not ann_sw_pos then return update, RUN_INTERVAL_MS end + + local now = millis() + + if ann_sw_pos > 0 then + -- to work when mission is inactive, need to convert current nav item to location + local nav_index = mission:get_current_nav_index() + local item = mission:get_item(nav_index) + local wp_loc = get_wp_location(item) + local cur_loc = ahrs:get_location() + if cur_loc then + local bearing = math.deg(cur_loc:get_bearing(wp_loc)) + local distance = cur_loc:get_distance(wp_loc) + + local buzz_enable = WAYPT_BUZ_ENABLE:get() + if buzz_enable and buzz_enable > 0 and now - last_buzz_ms > get_buzz_interval(distance) then + notify:play_tune('MFT240MSL8' .. get_pitch_by_distance(distance)) + last_buzz_ms = now + end + + if now - last_announce_ms > announce_s * 1000 then + gcs:send_text(MAV_SEVERITY.NOTICE, ('WP %d: %03.0f° / %.3fm'):format(nav_index, bearing, distance)) + last_announce_ms = now + end + elseif now - last_announce_ms > announce_s * 1000 then + gcs:send_text(MAV_SEVERITY.WARNING, 'Advance WP: Invalid AHRS location') + last_announce_ms = now + end + end + + return update, RUN_INTERVAL_MS +end + +gcs:send_text(MAV_SEVERITY.INFO, 'Advance WP Script Active') + +return update, RUN_INTERVAL_MS diff --git a/libraries/AP_Scripting/applets/advance-wp.md b/libraries/AP_Scripting/applets/advance-wp.md new file mode 100644 index 00000000000000..dd92415dce4529 --- /dev/null +++ b/libraries/AP_Scripting/applets/advance-wp.md @@ -0,0 +1,34 @@ +# Advance Waypoint + +Advance Waypoint (`advance-wp.lua`) allows for advancing the current mission waypoint via an RC switch. When the RC switch state is high, the mission waypoint is advanced to the next waypoint (wraps back to WP 1 if the end of the mission is reached). + +## How to Use + +Install this script in the autopilot's SD card in the `APM/scripts` directory. Set SCR_ENABLE to 1 and reboot the autopilot. + +* Set WAYPT_ADVANCE to an available aux function (300 by default). +* Set RCx_OPTION to the chosen aux function number. Preferably, set this to a channel assigned to a momentary switch. + +Mission Planner's Aux Function tab can be used in lieu of dedicating an RC channel. + +## Additional Features + +If Yaapu telemetry (or similar) is in use on the RC transmitter, it may be useful to display bearing and distance to the currently selected waypoint in the messages view, regardless of flight mode or arming state. To enable this: + +* Set WAYPT_ANNOUNCE to another available aux function (301 by default). +* Set RCx_OPTION to the chosen aux function. +* Set WAYPT_ANNOUNCE_S to desired interval (in seconds) between waypoint announcements (0 disables the feature). + +As above, Mission Planner's Aux Function tab can be used in lieu of dedicating an RC channel. + +When the announce switch is activated, the current waypoint index, bearing, and distance will be broadcast as a GCS message every WAYPT_ANNOUNCE_S seconds. + +Additionally, there is an audio feedback feature: + +* Set WAYPT_BUZ_ENABLE to 1 to enable buzzer feedback (0 to disable). + +If WAYPT_BUZ_ENABLE is set, the buzzer will beep when the announce switch is activated, increasing in frequency and pitch as distance to the selected waypoint decreases (useful as a rangefinder for the selected waypoint if no telemetry source is readily available). + +### Author's Note + +I used this script to create a survey "prism pole" of sorts out of a spare autopilot, RTK GPS module/antenna, RC receiver, and telemetry radio. Using the existing SaveWP feature along with this script, I can save waypoints and subsequently relocate them precisely with the additional features above. \ No newline at end of file diff --git a/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.lua b/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.lua index 759cb6d0a5b03b..7b980ce88fa318 100644 --- a/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.lua +++ b/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.lua @@ -2,7 +2,7 @@ -- this script is intended to help vehicles automatically switch between ExternalNav and optical flow -- -- configure a downward facing lidar with a range of at least 5m --- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=external nav, middle=opticalflow, high=Not Used) +-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=external nav, middle=opticalflow, high=Not Used) -- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected -- SRC_ENABLE = 1 (enable scripting) -- setup EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary @@ -135,7 +135,7 @@ end function update() -- check for EKF Source Select switch position change - local rc_ekfsrc_pos = rc:get_aux_cached(90) -- RCx_OPTION = 90 (EKF Pos Source) + local rc_ekfsrc_pos = rc:get_aux_cached(90) -- RCx_OPTION = 90 (EKF Source Set) if rc_ekfsrc_pos == nil then rc_ekfsrc_pos = 0 end diff --git a/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.md b/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.md index 37eb93d157d2b9..39eb2feca1f5a9 100644 --- a/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.md +++ b/libraries/AP_Scripting/applets/ahrs-source-extnav-optflow.md @@ -14,7 +14,7 @@ This script is intended to help vehicles automatically switch between ExternalNa ## How to use Configure a downward facing lidar with a range of at least 5m -Set RCx_OPTION = 90 (EKF Pos Source) to select the source (low=ExternalNav, middle=opticalflow, high=Not Used) +Set RCx_OPTION = 90 (EKF Source Set) to select the source (low=ExternalNav, middle=opticalflow, high=Not Used) Set RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected Set SRC_ENABLE = 1 (enable scripting) Set EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary diff --git a/libraries/AP_Scripting/applets/camera-change-setting.lua b/libraries/AP_Scripting/applets/camera-change-setting.lua new file mode 100644 index 00000000000000..1161283dcfed0e --- /dev/null +++ b/libraries/AP_Scripting/applets/camera-change-setting.lua @@ -0,0 +1,94 @@ +--[[ +script to allow users to more easily change camera settings +--]] + +local PARAM_TABLE_KEY = 85 +local PARAM_TABLE_PREFIX = "CAM1_" + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +local CAMERA_SETTINGS = {THERMAL_PALETTE=0, THERMAL_GAIN=1, THERMAL_RAW_DATA=2} -- see AP_Camera_shareddefs.h + +-- 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 + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 3), 'could not add param table') + +--[[ + // @Param: CAM1_THERM_PAL + // @DisplayName: Camera1 Thermal Palette + // @Description: thermal image colour palette + // @Values: -1:Leave Unchanged, 0:WhiteHot, 2:Sepia, 3:IronBow, 4:Rainbow, 5:Night, 6:Aurora, 7:RedHot, 8:Jungle, 9:Medical, 10:BlackHot, 11:GloryHot + // @User: Standard +--]] +local CAM1_THERM_PAL = bind_add_param('THERM_PAL', 1, -1) + +--[[ + // @Param: CAM1_THERM_GAIN + // @DisplayName: Camera1 Thermal Gain + // @Description: thermal image temperature range + // @Values: -1:Leave Unchanged, 0:LowGain (50C to 550C), 1:HighGain (-20C to 150C) + // @User: Standard +--]] +local CAM1_THERM_GAIN = bind_add_param('THERM_GAIN', 2, -1) + +--[[ + // @Param: CAM1_THERM_RAW + // @DisplayName: Camera1 Thermal Raw Data + // @Description: save images with raw temperatures + // @Values: -1:Leave Unchanged, 0:Disabled (30fps), 1:Enabled (25 fps) + // @Units: m + // @User: Standard +--]] +local CAM1_THERM_RAW = bind_add_param('THERM_RAW', 3, -1) + +-- local variables +local update_rate_ms = 3000 -- update every 3 seconds +local CAM1_THERM_PAL_saved_value = -1 -- true if thermal palette has been saved +local CAM1_THERM_GAIN_saved_value = -1 -- true if thermal gain has been saved +local CAM1_THERM_RAW_saved_value = -1 -- true if thermal raw data has been saved + +--[[ + main update function, called at 1Hz +--]] +function update() + + -- check if we should update any settings + if CAM1_THERM_PAL:get() >= 0 and CAM1_THERM_PAL:get() ~= CAM1_THERM_PAL_saved_value then + if camera:change_setting(0, CAMERA_SETTINGS.THERMAL_PALETTE, CAM1_THERM_PAL:get()) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Camera1 Thermal Palette to %d", CAM1_THERM_PAL:get())) + CAM1_THERM_PAL_saved_value = CAM1_THERM_PAL:get() + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Failed to set Camera1 Thermal Palette to %d", CAM1_THERM_PAL:get())) + end + end + + if CAM1_THERM_GAIN:get() >= 0 and CAM1_THERM_GAIN:get() ~= CAM1_THERM_GAIN_saved_value then + if camera:change_setting(0, CAMERA_SETTINGS.THERMAL_GAIN, CAM1_THERM_GAIN:get()) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Camera1 Thermal Gain to %d", CAM1_THERM_GAIN:get())) + CAM1_THERM_GAIN_saved_value = CAM1_THERM_GAIN:get() + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Failed to set Camera1 Thermal Gain to %d", CAM1_THERM_GAIN:get())) + end + end + + if CAM1_THERM_RAW:get() >= 0 and CAM1_THERM_RAW:get() ~= CAM1_THERM_RAW_saved_value then + if camera:change_setting(0, CAMERA_SETTINGS.THERMAL_RAW_DATA, CAM1_THERM_RAW:get()) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Camera1 Thermal Raw Data to %d", CAM1_THERM_RAW:get())) + CAM1_THERM_RAW_saved_value = CAM1_THERM_RAW:get() + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Failed to set Camera1 Thermal Raw Data to %d", CAM1_THERM_RAW:get())) + end + end + + return update, update_rate_ms +end + +-- print welcome message +gcs:send_text(MAV_SEVERITY.INFO, "Loaded camera-change-settings.lua") + +-- start running update loop +return update, update_rate_ms diff --git a/libraries/AP_Scripting/applets/camera-change-settings.md b/libraries/AP_Scripting/applets/camera-change-settings.md new file mode 100644 index 00000000000000..513466c8a5da35 --- /dev/null +++ b/libraries/AP_Scripting/applets/camera-change-settings.md @@ -0,0 +1,47 @@ +# Camera Change Settings + +Allows changing some camera settings that are not normallly used by the autopilot + +# Parameters + +## CAM1_THERM_PAL + +Set the camera's thermal palette + +Supported values are +-1: leave unchanged +0: WhiteHot +2: Sepia +3: IronBow +4: Rainbow +5: Night +6: Aurora +7: RedHot +8: Jungle +9: Medical +10: BlackHot +11: GloryHot + +## CAM1_THERM_GAIN + +Set the camera's thermal gain + +Supported values are +-1: leave unchanged +0: LowGain (50C to 550C) +1: HighGain (-20C to 150C) + +## CAM1_THERM_RAW + +Enable/Disable the saving of raw thermal images. Enabling raw iamges slightly slows the live video feed + +Supported values are +-1: leave unchanged +0: Disabled (30fps) +1: Enabled (25 fps) + +# Operation + +Install the lua script in the APM/SCRIPTS directory on the flight +controllers microSD card. Review the above parameter descriptions and +decide on the right parameter values for your vehicle and operations. diff --git a/libraries/AP_Scripting/applets/copter-deadreckon-home.lua b/libraries/AP_Scripting/applets/copter-deadreckon-home.lua index cb4b5cce6a8fa1..31d5f377859087 100644 --- a/libraries/AP_Scripting/applets/copter-deadreckon-home.lua +++ b/libraries/AP_Scripting/applets/copter-deadreckon-home.lua @@ -31,8 +31,8 @@ -- -- 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 +-- b. set SIM_GPS1_ENABLE = 0 to disable GPS (confirm dead reckoning begins) +-- c. set SIM_GPS1_ENABLE = 1 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!) -- @@ -56,6 +56,9 @@ -- b. SIM_WIND_SPD <-- sets wind speed in m/s -- +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type + -- 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') diff --git a/libraries/AP_Scripting/applets/copter-deadreckon-home.md b/libraries/AP_Scripting/applets/copter-deadreckon-home.md index c45ae3080ccd2f..b750eb4d2bf895 100644 --- a/libraries/AP_Scripting/applets/copter-deadreckon-home.md +++ b/libraries/AP_Scripting/applets/copter-deadreckon-home.md @@ -39,8 +39,8 @@ Deadreckoning will only be activated while the vehicle is in autonomous modes (e ## Testing in SITL - set map setshowsimpos 1 (to allow seeing where vehicle really is in simulator even with GPS disabled) - - set SIM_GPS_DISABLE = 1 to disable GPS (confirm dead reckoning begins) - - set SIM_GPS_DISABLE = 0 to re-enable GPS + - set SIM_GPS1_ENABLE = 0 to disable GPS (confirm dead reckoning begins) + - set SIM_GPS1_ENABLE = 1 to re-enable GPS - set SIM_GPS_NUMSAT = 3 to lower simulated satellite count to confirm script triggers - 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!) diff --git a/libraries/AP_Scripting/applets/copter-slung-payload.lua b/libraries/AP_Scripting/applets/copter-slung-payload.lua new file mode 100644 index 00000000000000..9cf511fe0d8423 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter-slung-payload.lua @@ -0,0 +1,396 @@ +-- Move a Copter so as to reduce a slung payload's oscillation. Requires the payload be capable of sending its position and velocity to the main vehicle +-- +-- How To Use +-- 1. copy this script to the autopilot's "scripts" directory +-- 2. within the "scripts" directory create a "modules" directory +-- 3. copy the MAVLink/mavlink_msgs_xxx files to the "scripts" directory +-- 4. add an autopilot and GPS to the payload and configure it to send GLOBAL_POSITION_INT messages at 10hz to the vehicle +-- 5. create a mission with a SCRIPT_TIME or PAYLOAD_PLACE command included +-- 6. fly the mission and the vehicle should move so as to reduce the payload's oscillations while executing the SCRIPT_TIME or PAYLOAD_PLACE commands +-- 7. optionally set SLUP_SYSID to the system id of the payload autopilot +-- 8. optionally set WP_YAW_BEHAVIOR to 0 to prevent the vehicle from yawing while moving to the payload + +-- load mavlink message definitions from modules/MAVLink directory +local mavlink_msgs = require("MAVLink/mavlink_msgs") + +-- global definitions +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +local UPDATE_INTERVAL_MS = 10 -- update at about 100hz +local COPTER_MODE_AUTO = 3 +local MAV_CMD_NAV_PAYLOAD_PLACE = 94 +local MAV_CMD_NAV_SCRIPT_TIME = 42702 +local PAYLOAD_OFFSET_COMP_VEL_MAX = 1 -- payload offset compensation will be active when the payload's horizontal velocity is no more than this speed in m/s +local PAYLOAD_UPDATE_TIMEOUT_MS = 1000 -- payload update timeout, used to warn user on loss of connection +local CONTROL_TIMEOUT_MS = 3000 -- control timeout, used to reset offsets if they have not been set for more than 3 seconds +local TEXT_PREFIX_STR = "copter-slung-payload:" -- prefix for all text messages + + -- setup script specific parameters +local PARAM_TABLE_KEY = 82 +local PARAM_TABLE_PREFIX = "SLUP_" +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 7), 'could not add param table') + +-- 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', PARAM_TABLE_PREFIX .. name)) + return Parameter(PARAM_TABLE_PREFIX .. name) + end + +--[[ + // @Param: SLUP_ENABLE + // @DisplayName: Slung Payload enable + // @Description: Slung Payload enable + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local SLUP_ENABLE = bind_add_param("ENABLE", 1, 1) + +--[[ + // @Param: SLUP_VEL_P + // @DisplayName: Slung Payload Velocity P gain + // @Description: Slung Payload Velocity P gain, higher values will result in faster movements in sync with payload + // @Range: 0 0.8 + // @User: Standard +--]] +local SLUP_VEL_P = bind_add_param("VEL_P", 2, 0.5) + +--[[ + // @Param: SLUP_DIST_MAX + // @DisplayName: Slung Payload horizontal distance max + // @Description: Oscillation is suppressed when vehicle and payload are no more than this distance horizontally. Set to 0 to always suppress + // @Range: 0 30 + // @User: Standard +--]] +local SLUP_DIST_MAX = bind_add_param("DIST_MAX", 3, 15) + +--[[ + // @Param: SLUP_SYSID + // @DisplayName: Slung Payload mavlink system id + // @Description: Slung Payload mavlink system id. 0 to use any/all system ids + // @Range: 0 255 + // @User: Standard +--]] +local SLUP_SYSID = bind_add_param("SYSID", 4, 0) + +--[[ + // @Param: SLUP_WP_POS_P + // @DisplayName: Slung Payload return to WP position P gain + // @Description: WP position P gain. higher values will result in vehicle moving more quickly back to the original waypoint + // @Range: 0 1 + // @User: Standard +--]] +local SLUP_WP_POS_P = bind_add_param("WP_POS_P", 5, 0.05) + +--[[ + // @Param: SLUP_RESTOFS_TC + // @DisplayName: Slung Payload resting offset estimate filter time constant + // @Description: payload's position estimator's time constant used to compensate for GPS errors and wind. Higher values result in smoother estimate but slower response + // @Range: 1 20 + // @User: Standard +--]] +local SLUP_RESTOFS_TC = bind_add_param("RESTOFS_TC", 6, 10) + +--[[ + // @Param: SLUP_DEBUG + // @DisplayName: Slung Payload debug output + // @Description: Slung payload debug output, set to 1 to enable debug + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local SLUP_DEBUG = bind_add_param("DEBUG", 7, 0) + +-- mavlink definitions +local GLOBAL_POSITION_INT_ID = 33 +local msg_map = {} +msg_map[GLOBAL_POSITION_INT_ID] = "GLOBAL_POSITION_INT" + +-- initialize MAVLink rx with number of messages, and buffer depth +mavlink:init(2, 5) + +-- register message id to receive +mavlink:register_rx_msgid(GLOBAL_POSITION_INT_ID) + +-- variables +local payload_sysid = nil -- holds sysid of payload once a matching global position int message has been received +local payload_loc = Location() -- payload location +local payload_vel = Vector3f() -- payload velocity +local payload_acc = Vector3f() -- payload acceleration +local payload_update_timeout_prev = true -- payload update timeout state from previous iteration, used to detect loss/recovery of payload updates +local payload_loc_update_ms = uint32_t(0) -- system time that payload_loc was last updated +local payload_dist_NED = Vector3f() -- distance between vehicle and payload in NED frame +local global_pos_int_timebootms_prev = 0 -- global position int message's time_boot_ms field from previous iteration (used to calc dt) +local resting_offset_NED = Vector3f() -- estimated position offset between payload and vehicle +local resting_vel_NED = Vector3f() -- estimated velocity offset. should be near zero when hovering +local resting_offset_valid = false -- true if resting_offset_NED and resting_vel_NED can be used +local resting_offset_update_ms = uint32_t(0) -- system time that resting_offset_NED was last updated +local resting_offset_notify_ms = uint32_t(0) -- system time that the user was sent the resting_offset_NED +local send_velocity_offsets = false -- true if we should send vehicle velocity offset commands to reduce payload oscillation +local sent_velocity_offsets_ms = uint32_t(0) -- system time that the last velocity offset was sent to the vehicle +local control_timeout_ms = uint32_t(0) -- system time that the control timeout occurred +local payload_vel_prev = Vector3f() -- previous iterations payload velocity used to calculate acceleration +local print_warning_ms = uint32_t(0) -- system time that the last warning was printed. used to prevent spamming the user with warnings + +-- display a text warning to the user. only displays a warning every second +-- prefix is automatically added +function print_warning(text_warning) + local now_ms = millis() + if (now_ms - print_warning_ms > 1000) then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("%s %s", TEXT_PREFIX_STR, text_warning)) + print_warning_ms = now_ms + end +end + +-- calculate sign of a number. 1 if positive, -1 if negative, 0 if exactly zero +function get_sign(value) + if value > 0 then + return 1 + elseif value < 0 then + return -1 + end + return 0 +end + +-- calculate an alpha for a first order low pass filter +function calc_lowpass_alpha(dt, time_constant) + local rc = time_constant/(math.pi*2) + return dt/(dt+rc) +end + +-- handle global position int message +-- returns true if the message was from the payload and updates payload_loc, payload_vel, payload_acc and payload_loc_update_ms +function handle_global_position_int(msg) + -- check if message is from the correct system id + if (SLUP_SYSID:get() > 0 and msg.sysid ~= SLUP_SYSID:get()) then + return false + end + + -- lock onto the first matching system id + if payload_sysid == nil then + payload_sysid = msg.sysid + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s found sysid:%d", TEXT_PREFIX_STR, msg.sysid)) + elseif payload_sysid ~= msg.sysid then + return false + end + + -- check for duplicate messages and calculate dt + local time_boot_ms = msg.time_boot_ms + local dt = (time_boot_ms - global_pos_int_timebootms_prev) * 0.001 + global_pos_int_timebootms_prev = time_boot_ms + if dt <= 0 or dt > 1 then + return false + end + + -- update payload location + payload_loc:lat(msg.lat) + payload_loc:lng(msg.lon) + payload_loc:alt(msg.alt * 0.1) + + -- update payload velocity + payload_vel:x(msg.vx * 0.01) + payload_vel:y(msg.vy * 0.01) + payload_vel:z(msg.vz * 0.01) + + -- calc payload acceleration + payload_acc:x((payload_vel:x() - payload_vel_prev:x()) / dt) + payload_acc:y((payload_vel:y() - payload_vel_prev:y()) / dt) + payload_acc:z((payload_vel:z() - payload_vel_prev:z()) / dt) + payload_vel_prev = payload_vel:copy() + + -- record time of update + payload_loc_update_ms = millis() + return true +end + +-- estimate the payload's resting position offset based on its current offset and velocity +-- relies on payload_dist_NED and payload_vel being updated +function update_payload_resting_offset() + + -- calculate dt since last update + local now_ms = millis() + local dt = (now_ms - resting_offset_update_ms):tofloat() * 0.001 + resting_offset_update_ms = now_ms + + -- sanity check dt + if (dt <= 0) then + resting_offset_valid = false + do return end + end + + -- if not updated for more than 1 second, reset resting offset to current offset + if (dt > 1) then + resting_offset_NED = payload_dist_NED + resting_vel_NED = payload_vel + resting_offset_valid = false + do return end + end + + -- use a low-pass filter to move the resting offset NED towards the pos_offset_NED + local alpha = calc_lowpass_alpha(dt, SLUP_RESTOFS_TC:get()) + resting_offset_NED:x(resting_offset_NED:x() + (payload_dist_NED:x() - resting_offset_NED:x()) * alpha) + resting_offset_NED:y(resting_offset_NED:y() + (payload_dist_NED:y() - resting_offset_NED:y()) * alpha) + resting_offset_NED:z(resting_offset_NED:z() + (payload_dist_NED:z() - resting_offset_NED:z()) * alpha) + resting_vel_NED:x(resting_vel_NED:x() + (payload_vel:x() - resting_vel_NED:x()) * alpha) + resting_vel_NED:y(resting_vel_NED:y() + (payload_vel:y() - resting_vel_NED:y()) * alpha) + resting_vel_NED:z(resting_vel_NED:z() + (payload_vel:z() - resting_vel_NED:z()) * alpha) + + -- debug output every 3 seconds + local print_debug = false + if (SLUP_DEBUG:get() > 0) and (now_ms - resting_offset_notify_ms > 3000) then + print_debug = true + resting_offset_notify_ms = now_ms + end + + -- validate that resting offsets are valid + -- resting velocity should be low to ensure the resting position estimate is accurate + if (resting_vel_NED:xy():length() > PAYLOAD_OFFSET_COMP_VEL_MAX) then + resting_offset_valid = false + if print_debug then + print_warning("resting velocity too high") + end + return + end + + -- resting position should be within SLUP_DIST_MAX of the vehicle + if resting_offset_NED:xy():length() > SLUP_DIST_MAX:get() then + resting_offset_valid = false + if print_debug then + print_warning("payload resting pos too far, ignoring"); + end + return + end + + -- update user + if (print_debug) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("resting a:%f px:%4.1f py:%4.1f pz:%4.1f vx:%4.1f vy:%4.1f vz:%4.1f", alpha, resting_offset_NED:x(), resting_offset_NED:y(), resting_offset_NED:z(), resting_vel_NED:x(), resting_vel_NED:y(), resting_vel_NED:z())) + end + + -- if set got this far the resting offsets must be valid + resting_offset_valid = true +end + +-- move vehicle to reduce payload oscillation +-- relies on payload_dist_NED, payload_vel, payload_acc, resting_offset_NED, resting_vel_NED being updated +function move_vehicle() + + -- check horizontal distance is less than SLUP_DIST_MAX + if SLUP_DIST_MAX:get() > 0 then + local dist_xy = payload_dist_NED:xy():length() + if (dist_xy > SLUP_DIST_MAX:get()) then + print_warning(string.format("payload too far %4.1fm", dist_xy)); + do return end + end + end + + -- get long-term payload offset used to compensate for GPS errors and wind + local payload_offset_NED = Vector3f() + if resting_offset_valid then + payload_offset_NED = resting_offset_NED + end + + -- get position offset (cumulative effect of velocity offsets) and use to slowly move back to waypoint + local pos_offset_NED, _, _ = poscontrol:get_posvelaccel_offset() + if pos_offset_NED == nil then + print_warning("unable to get dist to waypoint") + pos_offset_NED = Vector3f() + end + + -- calculate send velocity offsets in m/s in NED frame + local vel_offset_NED = Vector3f() + vel_offset_NED:x(-payload_acc:x() * SLUP_VEL_P:get() + (-pos_offset_NED:x() - payload_offset_NED:x()) * SLUP_WP_POS_P:get()) + vel_offset_NED:y(-payload_acc:y() * SLUP_VEL_P:get() + (-pos_offset_NED:y() - payload_offset_NED:y()) * SLUP_WP_POS_P:get()) + if poscontrol:set_posvelaccel_offset(pos_offset_NED, vel_offset_NED, Vector3f()) then + sent_velocity_offsets_ms = millis() + end +end + +-- display welcome message +gcs:send_text(MAV_SEVERITY.INFO, "copter-slung-payload script loaded") + +-- update function to receive location from payload and move vehicle to reduce payload's oscillation +function update() + + -- exit immediately if not enabled + if (SLUP_ENABLE:get() <= 0) then + return update, 1000 + end + + -- get vehicle location + local curr_loc = ahrs:get_location() + if curr_loc == nil then + return update, UPDATE_INTERVAL_MS + end + + -- consume all available mavlink messages + local payload_update_received = false + local msg + repeat + msg, _ = mavlink:receive_chan() + if (msg ~= nil) then + local parsed_msg = mavlink_msgs.decode(msg, msg_map) + if (parsed_msg ~= nil) then + if parsed_msg.msgid == GLOBAL_POSITION_INT_ID then + if handle_global_position_int(parsed_msg) then + payload_update_received = true + end + end + end + end + until msg == nil + + -- warn user on loss of recovery of telemetry from payload + local payload_timeout = millis() - payload_loc_update_ms > PAYLOAD_UPDATE_TIMEOUT_MS + if payload_timeout ~= payload_update_timeout_prev then + if payload_timeout then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("%s payload updates lost", TEXT_PREFIX_STR)) + else + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s payload updates received", TEXT_PREFIX_STR)) + end + end + payload_update_timeout_prev = payload_timeout + + if payload_update_received then + -- calculate position difference vs vehicle + payload_dist_NED = curr_loc:get_distance_NED(payload_loc) + + -- estimate the payload's resting position offset based on its current offset and velocity + -- relies on payload_dist_NED and payload_vel being updated + update_payload_resting_offset() + end + + -- check if we can control the vehicle + -- vehicle must be in Auto mode executing a SCRIPT_TIME or PAYLOAD_PLACE command + local send_velocity_offsets_prev = send_velocity_offsets + local armed_and_flying = arming:is_armed() and vehicle:get_likely_flying() + local takingoff_or_landing = vehicle:is_landing() or vehicle:is_taking_off() + local auto_mode = (vehicle:get_mode() == COPTER_MODE_AUTO) + local scripting_or_payloadplace = (mission:get_current_nav_id() == MAV_CMD_NAV_SCRIPT_TIME) or (mission:get_current_nav_id() == MAV_CMD_NAV_PAYLOAD_PLACE) + send_velocity_offsets = armed_and_flying and not takingoff_or_landing and auto_mode and scripting_or_payloadplace and not payload_timeout + + -- alert user if we start or stop sending velocity offsets + if (send_velocity_offsets and not send_velocity_offsets_prev) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s activated", TEXT_PREFIX_STR)) + end + if (not send_velocity_offsets and send_velocity_offsets_prev) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s deactivated", TEXT_PREFIX_STR)) + poscontrol:set_posvelaccel_offset(Vector3f(), Vector3f(), Vector3f()) + end + + -- move vehicle to reduce payload oscillation + if send_velocity_offsets then + move_vehicle() + + -- check for unexpected control timeout + -- reset vehicle offsets if not sent within last 3 seconds + local now_ms = millis() + local time_since_vel_offset_sent = now_ms - sent_velocity_offsets_ms + local time_since_last_control_timeout = now_ms - control_timeout_ms + if (time_since_vel_offset_sent > CONTROL_TIMEOUT_MS) and (time_since_last_control_timeout > CONTROL_TIMEOUT_MS) then + poscontrol:set_posvelaccel_offset(Vector3f(), Vector3f(), Vector3f()) + control_timeout_ms = now_ms + print_warning("control timeout, clearing offsets") + end + end + + return update, UPDATE_INTERVAL_MS +end + +return update() diff --git a/libraries/AP_Scripting/applets/copter-slung-payload.md b/libraries/AP_Scripting/applets/copter-slung-payload.md new file mode 100644 index 00000000000000..b4953565ccf222 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter-slung-payload.md @@ -0,0 +1,30 @@ +# Slung Payload + +This script moves a Copter so as to reduce a slung payload's oscillation. Requires the payload be capable of sending its position and velocity to the main vehicle + +# Parameters + +- SLUP_ENABLE : Set to 1 to enable this script +- SLUP_VEL_P : Oscillation controller velocity P gain. Higher values will result in the vehicle moving more quickly in sync with the payload +- SLUP_DIST_MAX : maximum acceptable distance between vehicle and payload. Within this distance oscillation suppression will operate +- SLUP_SYSID : System id of payload's autopilot. If zero any system id is accepted +- SLUP_WP_POS_P : Return to waypoint position P gain. Higher values result in the vehicle returning more quickly to the latest waypoint +- SLUP_RESTOFS_TC : Slung Payload resting offset estimate filter time constant. Higher values result in smoother estimate but slower response +- SLUP_DEBUG : Slung payload debug output, set to 1 to enable debug + +# How To Use + +1. mount an autopilot on the payload connected to the main vehicle using telemetry +2. ensure the vehicle and payload autopilots have unique system ids +3. copy this script to the vehicle autopilot's "scripts" directory +4. within the "scripts" directory create a "modules" directory +5. copy the MAVLink/mavlink_msgs_xxx files to the "scripts" directory + +# How It Works + +The script's algorithm is implemented as follows + +1. Consume GLOBAL_POSITION_INT messages from the payload +2. Calculate the payload's position vs the vehicle position +3. Use a P controller to move the vehicle towards the payload to reduce oscillation +4. Simultaneously the vehicle moves back towards the original location. The speed depends upon the SLUP_WP_POS_P parameter diff --git a/libraries/AP_Scripting/applets/copter_terrain_brake.lua b/libraries/AP_Scripting/applets/copter_terrain_brake.lua new file mode 100644 index 00000000000000..dad77c5ff18648 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter_terrain_brake.lua @@ -0,0 +1,130 @@ +--[[ +script to prevent terrain impact in LOITER mode while flying copters in steep terrain +--]] + +local PARAM_TABLE_KEY = 84 +local PARAM_TABLE_PREFIX = "TERR_BRK_" + +local MODE_LOITER = 5 +local MODE_BRAKE = 17 + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- 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 + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 14), 'could not add param table') + +--[[ + // @Param: TERR_BRK_ENABLE + // @DisplayName: terrain brake enable + // @Description: terrain brake enable + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local TERR_BRK_ENABLE = bind_add_param('ENABLE', 1, 1) + +--[[ + // @Param: TERR_BRK_ALT + // @DisplayName: terrain brake altitude + // @Description: terrain brake altitude. The altitude above the ground below which BRAKE mode will be engaged if in LOITER mode. + // @Range: 1 100 + // @Units: m + // @User: Standard +--]] +local TERR_BRK_ALT = bind_add_param('ALT', 2, 30) + +--[[ + // @Param: TERR_BRK_HDIST + // @DisplayName: terrain brake home distance + // @Description: terrain brake home distance. The distance from home where the auto BRAKE will be enabled. When within this distance of home the script will not activate + // @Range: 0 1000 + // @Units: m + // @User: Standard +--]] +local TERR_BRK_HDIST = bind_add_param('HDIST', 3, 100) + +--[[ + // @Param: TERR_BRK_SPD + // @DisplayName: terrain brake speed threshold + // @Description: terrain brake speed threshold. Don't trigger BRAKE if both horizontal speed and descent rate are below this threshold. By setting this to a small value this can be used to allow the user to climb up to a safe altitude in LOITER mode. A value of 0.5 is recommended if you want to use LOITER to recover from an emergency terrain BRAKE mode change. + // @Range: 0 5 + // @Units: m/s + // @User: Standard +--]] +local TERR_BRK_SPD = bind_add_param('SPD', 4, 0) + +local function sq(x) + return x*x +end + +local function run_checks() + if TERR_BRK_ENABLE:get() ~= 1 then + return + end + if not arming:is_armed() then + return + end + if vehicle:get_mode() ~= MODE_LOITER then + return + end + + if not ahrs:home_is_set() then + return + end + local home = ahrs:get_home() + local pos = ahrs:get_location() + if not pos then + return + end + local home_dist = pos:get_distance(home) + if home_dist <= TERR_BRK_HDIST:get() then + return + end + + --[[ + get height above terrain with extrapolation + --]] + local hagl = terrain:height_above_terrain(true) + if hagl >= TERR_BRK_ALT:get() then + return + end + + --[[ + allow for climbing in LOITER mode if enabled + --]] + if TERR_BRK_SPD:get() > 0 then + local spd = ahrs:get_velocity_NED() + if spd ~= nil then + local hspd = math.sqrt(sq(spd:x())+sq(spd:y())) + local drate = spd:z() + if hspd < TERR_BRK_SPD:get() and drate < TERR_BRK_SPD:get() then + return + end + end + end + + if vehicle:set_mode(MODE_BRAKE) then + gcs:send_text(MAV_SEVERITY.EMERGENCY, string.format("Terrain %.1fm - BRAKE", hagl)) + end +end + +--[[ + main update function, called at 1Hz +--]] +function update() + run_checks() + return update, 100 +end + +if TERR_BRK_ENABLE:get() == 1 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Loaded Loiter/Brake checker")) +end + +-- start running update loop +return update, 1000 + diff --git a/libraries/AP_Scripting/applets/copter_terrain_brake.md b/libraries/AP_Scripting/applets/copter_terrain_brake.md new file mode 100644 index 00000000000000..02edf1d9e88435 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter_terrain_brake.md @@ -0,0 +1,72 @@ +# Copter Loiter Brake + +This script implements an emergency change to BRAKE mode in copter if +you are in LOITER mode and break a terrain altitude limit. The script +is useful when flying in LOITER mode in steep terrain. + +# Parameters + +The script adds the following parameters to control it's behaviour. + +## TERR_BRK_ENABLE + +This must be set to 1 to enable the script. + +## TERR_BRK_ALT + +This is the terrain altitude threshold for engaging BRAKE mode. The +onboard terrain system must be enabled with TERRAIN_ENABLE=1 and +terrain must have either been preloaded to the vehicle (see +https://terrain.ardupilot.org ) or be available from the ground +station over MAVLink. + +Make sure you set sufficient margin to cope with obstacles such as +trees or any local towers or other obstacles. + +## TERR_BRK_HDIST + +This is the distance from home for the BRAKE checking to be +enabled. The default of 100 meters is good for most operations. This +threshold allows you to take over in LOITER mode for low altitude +operations and takeoff/landing when close to home. + +## TERR_BRK_SPD + +This is a speed threshold BRAKE checking to be enabled. If both the +horizontal speed and the descent rate are below this threshold then +BRAKE will not be engaged. This defaults to zero which means no speed +checking is performed. + +You should set this to a small value if you want to be able to recover +from BRAKE mode by climbing straight up in LOITER mode. A value of 0.5 +m/s is recommended. The value needed will be dependent on the amount +of noise there is in your velocity measurement and how gusty the wind +is, but 0.5 should work in most applications. + +If you set this value then to recover in LOITER mode you should raise +the throttle stick to demand climb before you switch back to LOITER +mode. The positive climb rate means BRAKE will not re-engage. + +# Operation + +Install the lua script in the APM/SCRIPTS directory on the flight +controllers microSD card. Review the above parameter descriptions and +decide on the right parameter values for your vehicle and operations. + +Make sure TERRAIN_ENABLE is 1 and you should preload terrain data for +the flight area from https://terrain.ardupilot.org + +It is strongly recommended that you set TERRAIN_SPACING=30 and preload +the SRTM1 terrain data for 30m horizontal resolution of terrain data. + +When the system engages you will see a message like this + "Terrain 29.2m - BRAKE" +where in this example you are 29.2m above the terrain. + +To recover you could use GUIDED mode, or RTL (make sure you have set +RTL_ALT_TYPE to terrain) or if you have set TERR_BRK_SPD to a positive +value then you could raise the throttle stick and switch back to +LOITER mode. + +If the system is continually giving false positives then set +TERR_BRK_ENABLE to zero to disable. diff --git a/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua index 50f856b47158f9..202b3db30abb24 100644 --- a/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua +++ b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua @@ -5,6 +5,8 @@ -- slew up and down times allow to configure how fast the motors are disabled and re-enabled -- luacheck: only 0 +---@diagnostic disable: cast-local-type + -- Config @@ -91,7 +93,6 @@ local slew local slew_pwm function update() - local switch_pos = switch:get_aux_switch_pos() if switch:get_aux_switch_pos() == 2 then if not script_enabled then gcs:send_text(0, "Lua: Forward flight motor shutdown enabled") diff --git a/libraries/AP_Scripting/applets/leds_on_a_switch.lua b/libraries/AP_Scripting/applets/leds_on_a_switch.lua index 9126289f34048d..e80f12be59d1f8 100644 --- a/libraries/AP_Scripting/applets/leds_on_a_switch.lua +++ b/libraries/AP_Scripting/applets/leds_on_a_switch.lua @@ -1,6 +1,8 @@ -- leds_on_a_switch.lua: control led brightness with a radio switch -- +---@diagnostic disable: cast-local-type + -- constants local AuxSwitchPos = {LOW=0, MIDDLE=1, HIGH=2} local NTF_LED_BRIGHT = Parameter("NTF_LED_BRIGHT") diff --git a/libraries/AP_Scripting/applets/mount-poi.lua b/libraries/AP_Scripting/applets/mount-poi.lua index aa42620bc01447..da56cfd6e8c22e 100644 --- a/libraries/AP_Scripting/applets/mount-poi.lua +++ b/libraries/AP_Scripting/applets/mount-poi.lua @@ -19,6 +19,10 @@ -- 10. interpolate between test_loc and prev_test_loc to find the lat, lon, alt (above sea-level) where alt-above-terrain is zero -- 11. display the POI to the user +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type +---@diagnostic disable: missing-parameter + -- global definitions local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local ALT_FRAME_ABSOLUTE = 0 diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index 278acd2b2575f0..e8f7e2ad0fc52a 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -1,6 +1,10 @@ --[[ example script to test lua socket API --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: undefined-field +---@diagnostic disable: need-check-nil +---@diagnostic disable: redundant-parameter local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} diff --git a/libraries/AP_Scripting/applets/pelco_d_antennatracker.lua b/libraries/AP_Scripting/applets/pelco_d_antennatracker.lua new file mode 100644 index 00000000000000..9f80c82fa7dae2 --- /dev/null +++ b/libraries/AP_Scripting/applets/pelco_d_antennatracker.lua @@ -0,0 +1,110 @@ +--[[ + Pelco-D control implementation for antennatracker. + Implemented by using knowledge from the excellent python implementation in https://gist.github.com/jn0/cc5c78f4a0f447a6fb2e45a5d9efa13d. +--]] + +local SERVO_PAN = 71 +local SERVO_TILT = 72 +local SERIAL_BAUD = 9600 + +-- Antennattracker modes +local MODE_STOP = 1 +local MODE_SCAN = 2 +local MODE_SERVOTEST = 3 +local MODE_GUIDED = 4 + +gcs:send_text(0, "Starting Pelco-D Control") + +local port = assert(serial:find_serial(0), "Pelco-D: No Scripting Serial Port") +port:begin(SERIAL_BAUD) +port:set_flow_control(0) + +function set_bit(value, n) + return value | (0x01 << n) +end + +function PelcoD_msg_addchecksum(msg) + local sum = 0 + for i = 2, #msg-1 do + sum = sum + msg[i] + end + checksum = sum % 256 + msg[7] = checksum +end + +function PelcoD_move(panspeed, tiltspeed) + local command = 0x00 + local scale = 63 -- max pelcod speed + if panspeed < 0 then -- left + command = set_bit(command, 2) + elseif panspeed > 0 then -- right + command = set_bit(command, 1) + end + if tiltspeed < 0 then -- down + command = set_bit(command, 4) + elseif tiltspeed > 0 then -- up + command = set_bit(command, 3) + end + local msg = {0xFF, 0x01, 0x00, command, math.floor(math.abs(panspeed) * scale), math.floor(math.abs(tiltspeed) * scale), 0x00} + PelcoD_msg_addchecksum(msg) + return msg +end + +-- write msg to the serial port +function send_message(msg) + for _, v in ipairs(msg) do + port:write(v) + end +end + +function update() + tilt_norm = SRV_Channels:get_output_scaled(SERVO_TILT) + pan_norm = SRV_Channels:get_output_scaled(SERVO_PAN) + if (vehicle:get_mode() == MODE_SCAN or vehicle:get_mode() == MODE_SERVOTEST or vehicle:get_mode() == MODE_GUIDED) then + -- Limit pan and tilt to -1...+1 + pan_norm=math.max(pan_norm,-1.0) + pan_norm=math.min(pan_norm,1.0) + tilt_norm=math.max(tilt_norm,-1.0) + tilt_norm=math.min(tilt_norm,1.0) + local msg=PelcoD_move(-pan_norm,tilt_norm) + send_message(msg) + elseif (vehicle:get_mode() == MODE_STOP) then + local msg=PelcoD_move(0,0) + send_message(msg) + end + + return update, 20 -- 50 hz +end + +PelcoD_move(0,0) +return update() + + +--[[ +function PelcoD_pan_absolute_position(degrees) + centidegrees = degrees*100 + local msg = {0xFF, 0x01, 0x00, 0x4b, (centidegrees >> 8) & 255 , centidegrees & 255, 0x00} + PelcoD_msg_addchecksum(msg) + return msg +end + +function PelcoD_tilt_absolute_position(degrees) + centidegrees = degrees*100 + local msg = {0xFF, 0x01, 0x00, 0x4d, (centidegrees >> 8) & 255 , centidegrees & 255, 0x00} + PelcoD_msg_addchecksum(msg) + return msg +end + +function PelcoD_zoom_absolute_position(position) + local msg = {0xFF, 0x01, 0x00, 0x4f, (position >> 8) & 255 , position & 255, 0x00} + PelcoD_msg_addchecksum(msg) + return msg +end + +function PelcoD_zero_absolute_position(degrees) + centidegrees = degrees*100 + local msg = {0xFF, 0x01, 0x00, 0x49, 0x00, 0x00, 0x00} + PelcoD_msg_addchecksum(msg) + return msg +end +--]] \ No newline at end of file diff --git a/libraries/AP_Scripting/applets/pelco_d_antennatracker.md b/libraries/AP_Scripting/applets/pelco_d_antennatracker.md new file mode 100644 index 00000000000000..3f79577c2d7593 --- /dev/null +++ b/libraries/AP_Scripting/applets/pelco_d_antennatracker.md @@ -0,0 +1,16 @@ +# Pelco-D antennatracker lua script + +This scripts uses the scaled output from the antennatracker servos and map them to corresponding Pelco-D messages to be sent via a RS-485 interface to a motorized base (can be anything from motorized tracker to a PTZ camera). If your FCU doesnt offer a RS-485 interface by default, you can use or TTL-RS485- or USB-RS485-adapters. I tested this script using a USB-RS485 adapter using Linux/Obal board and a Hikvision PTZ camera. + +Pelco-D allows to control using either speed-/differential- or absolute-control control of the pan-/tilt-axis. Currently the script uses speed based control using by mapping the "ContinuousRotation" type servos outputs to the corresponding Pelco-D messages. The absolute control messages are implemented nevertheless for future use. + +The script assumes the following parameters to be set: + +SCR_ENABLE = 1 +SERVO_PITCH_TYPE = 2 # ContinuousRotation type servo +SERVO_YAW_TYPE = 2 # ContinuousRotation type servo +SERIALx_PROTOCOL = 28 # replace 'x' with the serial port used by luascript + +Additionally the PITCH2SRV, YAW2SRV tuning needs to be done as described by the antennatracker description. +Also keep attention to the PITCH_MIN, PITCH_MAX and YAW_RANGE parameters to fit your Pelco-D hardware! + diff --git a/libraries/AP_Scripting/applets/plane_package_place.lua b/libraries/AP_Scripting/applets/plane_package_place.lua index 242435fc7f34b6..cd690728702fb6 100644 --- a/libraries/AP_Scripting/applets/plane_package_place.lua +++ b/libraries/AP_Scripting/applets/plane_package_place.lua @@ -2,6 +2,7 @@ support package place for quadplanes --]] -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch local PARAM_TABLE_KEY = 9 diff --git a/libraries/AP_Scripting/applets/plane_precland.lua b/libraries/AP_Scripting/applets/plane_precland.lua index 9adcfdd84fba09..1d5dc96cd8f00a 100644 --- a/libraries/AP_Scripting/applets/plane_precland.lua +++ b/libraries/AP_Scripting/applets/plane_precland.lua @@ -5,6 +5,8 @@ for development of a custom solution --]] +---@diagnostic disable: param-type-mismatch + local PARAM_TABLE_KEY = 12 local PARAM_TABLE_PREFIX = "PLND_" diff --git a/libraries/AP_Scripting/applets/plane_ship_landing.lua b/libraries/AP_Scripting/applets/plane_ship_landing.lua index 45bc9be2d42c4e..da89c77e2f2bb7 100644 --- a/libraries/AP_Scripting/applets/plane_ship_landing.lua +++ b/libraries/AP_Scripting/applets/plane_ship_landing.lua @@ -4,6 +4,10 @@ See this post for details: https://discuss.ardupilot.org/t/ship-landing-support --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil + local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local PARAM_TABLE_KEY = 7 diff --git a/libraries/AP_Scripting/applets/repl.lua b/libraries/AP_Scripting/applets/repl.lua new file mode 100644 index 00000000000000..eedf551aa6e7a4 --- /dev/null +++ b/libraries/AP_Scripting/applets/repl.lua @@ -0,0 +1,358 @@ +-- Interactive REPL (read-evaluate-print-loop) for the Lua scripting engine +-- accessible over serial, with line editing, history, and output formatting. + +-- 0-based index of Scripting protocol port to use, or nil to use MAVLink +local PORT_IDX = 0 +local MAX_HISTORY = 50 -- number of lines of history to keep (must be >= 1) +local VERSION = "v1.0" -- version is convenience for the user + +local port +if PORT_IDX == nil then + port = require("mavport") +else + port = serial:find_serial(PORT_IDX) +end +assert(port, "REPL scripting port not configured") + +-- scan through parameters to find our port and grab its baud rate +do + local serial_info = "" + local baud = 115200 + if PORT_IDX ~= nil then + local port_num = 0 + while PORT_IDX >= 0 and port_num <= 9 do + local protocol = param:get(("SERIAL%d_PROTOCOL"):format(port_num)) + port_num = port_num + 1 + if protocol == 28 then PORT_IDX = PORT_IDX - 1 end + end + if PORT_IDX == -1 then -- correct port index found + port_num = port_num - 1 + baud = param:get(("SERIAL%d_BAUD"):format(port_num)) or 115200 + serial_info = (" on SERIAL%d, BAUD=%d"):format(port_num, baud) + end + end + -- if we can't find the right port, the baud probably does not matter + -- (e.g. CAN or network port) + port:begin(baud) + + gcs:send_text(6, "Lua REPL "..VERSION.." starting"..serial_info) +end + +-- grab things we use from the environment in case the user messes them up +local string = string +local table = table + +-- declaration of main state variable and functions +local state_func, state_read, state_eval, state_print + +-- write the string s to the port, buffering if not all could be written. +-- buffer starts of with the first message and prompt +local tx_buf = {"\r\n\r\nLua REPL "..VERSION.." started.\r\n> "} +local writestring +if port.writestring then -- use more efficient method if we have it + writestring = function(s) + if tx_buf then -- stuff already in the buffer? + tx_buf[#tx_buf+1] = s -- this needs to go after + else + local written = port:writestring(s) + if written < #s then + -- write was short i.e. port buffer is full. buffer the rest of the + -- string ourselves and transmit it later + tx_buf = { s:sub(written+1) } + end + end + end +else + writestring = function(s) + if tx_buf then -- stuff already in the buffer? + tx_buf[#tx_buf+1] = s -- this needs to go after + else + for ci = 1, #s do + if port:write(s:byte(ci)) == 0 then + -- write failed i.e. port buffer is full. we now buffer the rest of + -- the string ourselves and transmit it later + tx_buf = { s:sub(ci) } + break + end + end + end + end +end + +-- don't use print substitute in the REPL's code (e.g. for debugging the REPL) +local print = print -- luacheck: ignore 211 (unused variable warning) + +-- substitute print function for within the REPL that prints to the port +function _ENV.print(...) + local t = table.pack(...) + for i = 1, t.n do + writestring(tostring(t[i])) + writestring((i ~= t.n) and "\t" or "\r\n") + end +end + +-- write the character c to the port, buffering if failed +local function writechar(c) + -- buffer character if stuff already in buffer or write fails + if tx_buf or port:write(c) == 0 then + tx_buf[#tx_buf+1] = string.char(c) -- massive overhead... + end +end + +local function writeobj(o) + if type(o) == "table" then + writestring("{ ") + for k, v in pairs(o) do + if type(k) ~= "number" then k = '"'..k..'"' end + writestring("["..k.."] = ") + writeobj(v) + writestring(", ") + end + writestring("}") + else + writestring(tostring(o)) + end +end + +local curr_line = nil -- table of line bytes, or nil if viewing history +local curr_pos = 1 -- position the next character will be put at +local curr_esc = nil -- table of escape sequence bytes + +local eval_pieces = {} -- pieces of code being evaluated + +local history_lines = {""} -- lines in the history (one is always being edited) +local history_pos = 1 -- position in the history being edited + +local function writeprompt() + writestring((#eval_pieces > 0) and ">> " or "> ") +end + +local function movehistory(dir) + if curr_line then -- current line was edited, store it in history + history_lines[history_pos] = string.char(table.unpack(curr_line)) + curr_line = nil + end + + history_pos = history_pos + dir -- move to new position + + writestring("\x1B[2K\r") -- erase line and return cursor to start + writeprompt() -- draw prompt + local line = history_lines[history_pos] -- and current line from history + writestring(line) + curr_pos = #line + 1 +end + +local function readesc(c) + assert(curr_esc) -- only called if curr_esc isn't nil + + if c == 27 then -- another escape, clear line and buffer and exit escape mode + curr_line = nil + curr_pos = 1 + curr_esc = nil + eval_pieces = {} + history_pos = #history_lines + history_lines[history_pos] = "" + writestring("\r\n") + writeprompt() + return + else + curr_esc[#curr_esc+1] = c + end + + if curr_esc[1] ~= 91 then -- not a [, exit escape mode + curr_esc = nil + return + end + + if #curr_esc < 2 then return end -- command character not yet present + + local line_len = #history_lines[history_pos] + if curr_line then line_len = #curr_line end + + -- c is now the command character + if c == 65 then -- up + if history_pos > 1 then + movehistory(-1) + end + elseif c == 66 then -- down + if history_pos < #history_lines then + movehistory(1) + end + elseif c == 67 then -- right + if curr_pos < line_len + 1 then + writestring("\x1B[C") + curr_pos = curr_pos + 1 + end + elseif c == 68 then -- left + if curr_pos > 1 then + writestring("\x1B[D") + curr_pos = curr_pos - 1 + end + elseif c == 72 then -- home + if curr_pos > 1 then + writestring(("\x1B[%dD"):format(curr_pos-1)) + curr_pos = 1 + end + elseif c == 70 then -- end + if curr_pos < line_len + 1 then + writestring(("\x1B[%dC"):format(line_len-curr_pos+1)) + curr_pos = line_len + 1 + end + end + + curr_esc = nil -- exit escape mode, handling complete +end + +local last_c = 0 +state_read = function () + while true do + local c = port:read() + if c == -1 then return end -- no new character, give time for more to come + + if curr_esc then -- in escape sequence + readesc(c) + elseif c == 27 then -- escape, start of a control sequence + curr_esc = {} -- engage escape sequence handler + elseif c == 13 or c == 10 then -- line complete + if last_c ~= 13 or c ~= 10 then -- ignore \n after \r + writestring("\r\n") + last_c = c + break + end + elseif c == 8 or c == 127 then -- backspace + if curr_pos > 1 then -- a character to delete? + if curr_line == nil then -- retrieve line for editing + curr_line = table.pack(history_lines[history_pos]:byte(1, -1)) + end + table.remove(curr_line, curr_pos-1) -- delete the character + writechar(8) -- back cursor up + curr_pos = curr_pos - 1 + if curr_pos <= #curr_line then -- draw characters after deletion point + writestring(string.char(table.unpack(curr_line, curr_pos))) + end + -- blank out trailing character and back cursor up to deletion point + writestring((" \x1B[%dD"):format(#curr_line-curr_pos+2)) + end + elseif c >= 32 and c <= 126 then -- a character to type + if curr_line == nil then -- retrieve line for editing + curr_line = table.pack(history_lines[history_pos]:byte(1, -1)) + end + table.insert(curr_line, curr_pos, c) -- store character in the line + writechar(c) -- draw the new character + curr_pos = curr_pos + 1 + if curr_pos <= #curr_line then -- and any after + writestring(string.char(table.unpack(curr_line, curr_pos))) + -- back cursor up to insertion point + writestring(("\x1B[%dD"):format(#curr_line-curr_pos+1)) + end + end + + last_c = c + if tx_buf then return end -- give time to flush if buffer full + end + + -- loop break, line is complete! + local line = history_lines[history_pos] + if curr_line then + line = string.char(table.unpack(curr_line)) -- store line for processing + curr_line = nil + end + + if #line == 0 then -- line is empty, ignore it + writeprompt() + return + end + + -- if this line is different to the last one added (one before the last entry) + if history_lines[#history_lines-1] ~= line then + history_lines[#history_lines] = line -- insert it at history end + history_lines[#history_lines+1] = "" -- create empty entry for next line + if #history_lines > MAX_HISTORY then table.remove(history_lines, 1) end + else -- don't create a new entry with a duplicate line + history_lines[#history_lines] = "" -- just clear and reuse the last entry + end + history_pos = #history_lines -- now editing the last entry + curr_pos = 1 + + eval_pieces[#eval_pieces+1] = line -- evaluate the line + state_func = state_eval +end + +local function to_chunk(pieces) + local pos = 1 + + local function next_piece() + -- going past the last piece returns nil which signals the end + local piece = pieces[pos] + pos = pos + 1 + return piece + end + + return next_piece +end + +local eval_results +state_eval = function () + local func, err + -- try to compile a single line as "return %s;" assuming it could be an + -- expression. technique borrowed from the official Lua REPL. + if #eval_pieces == 1 then + local expr_pieces = {"return ", eval_pieces[1], ";"} + func = load(to_chunk(expr_pieces), "=input", "t", _ENV) + end + if func == nil then -- compilation unsuccessful, load normally + func, err = load(to_chunk(eval_pieces), "=input", "t", _ENV) + end + + -- if there is an error at the end of the statement, assume we need more to + -- complete it. technique borrowed from the official Lua REPL. + -- ignore check since load defines that err is not nil if func is nil + ---@diagnostic disable-next-line: need-check-nil + if func == nil and err:sub(-5, -1) == "" then + -- add a newline and get another line from the user + eval_pieces[#eval_pieces+1] = "\n" + writeprompt() + state_func = state_read + return + end + + eval_pieces = {} -- destroy to make room for result + if func == nil then -- result is the load error message + eval_results = { false, err, n = 2 } + else + eval_results = table.pack(pcall(func)) + end + state_func = state_print +end + +state_print = function () + for i = 2, eval_results.n do -- skip pcall result + writeobj(eval_results[i]) -- write each result separated by tabs + writestring((i ~= eval_results.n) and "\t" or "\r\n") + eval_results[i] = nil -- destroy to make room for stringified version + end + eval_results = nil + + writeprompt() + state_func = state_read -- loop back to read +end + +state_func = state_read +local function update() + if tx_buf then -- write out stuff in tx buffer if present + local old_buf = tx_buf + tx_buf = nil + for _, s in ipairs(old_buf) do -- re-write all data + writestring(s) + end + else -- otherwise we have time to process + state_func() + end + + ---@diagnostic disable-next-line: undefined-field + if PORT_IDX == nil then port:flush() end -- flush MAVLink port if using it + + return update, 10 +end + +return update() diff --git a/libraries/AP_Scripting/applets/repl.md b/libraries/AP_Scripting/applets/repl.md new file mode 100644 index 00000000000000..e7fc55e0f598ec --- /dev/null +++ b/libraries/AP_Scripting/applets/repl.md @@ -0,0 +1,63 @@ +# Lua REPL + +This script implements an interactive REPL (read-evaluate-print-loop) for the +Lua scripting engine accessible over serial, with line editing, history, and +output formatting. + +The script can also act as a client for QGroundControl's MAVLink Console +functionality (within the Analyze view), subject to limitations detailed +below. + +### Basic Usage +* Configure a serial port (e.g. `SERIALn_PROTOCOL`) to protocol 28 (Scripting). + * By default the first such port is used; this can be adjusted in the script + text. + * `SERIAL6` is the alternate USB serial port on Cube Orange, and convenient + for bench testing. CAN and network serial ports will also work. +* Load the `repl.lua` script onto the autopilot. +* Connect a terminal emulator to the port and enter Lua statements/expressions + at the `> ` prompt, then press Enter to execute. Results and errors will be + printed back. + * A `>> ` prompt indicates that more input is needed to complete the + statement. + * You can use the arrow keys to edit the current and previous inputs. + * Press ESC twice to clear the input and any incomplete statement then + return to an empty prompt. + +### Autopilot Connection +* On Linux a convenient command is e.g. `minicom -w -D /dev/ttyACM1 -b 115200`, + assuming you have the minicom terminal emulator installed. +* Any terminal emulator on any platform should work; see notes below about + control codes and other configuration. + +### SITL Connection +* Start SITL with a command like `Tools/autotest/sim_vehicle.py -A --serialN=tcp:9995:wait` to allow connection to the selected serial port. +* Connect a terminal emulator to localhost TCP port 9995 + * On Linux a convenient command is `stty -icanon -echo -icrnl && netcat localhost 9995`. + * Note that you must execute `reset` to turn echo back on once disconnected. + * Scripting must be restarted after a TCP reconnection. + +### MAVLink Connection +* Requires at least Ardupilot 4.6. +* Set the port in the script text to `nil` to enable. +* In addition to `repl.lua`, copy the `mavport.lua` file and `MAVLink` directory + from `AP_Scripting/modules` to `APM/SCRIPTS/MODULES` on your autopilot. +* The ESC key is not supported; cause a syntax error to reset the prompt. +* The experience over a radio link might be sub-par due to lack of any sort of + packet loss tracking or retransmission. + +### Notes and Limitations +* Statements like `local x = 3` create a variable which immediately goes out of + scope once evaluated. Names must be global to survive to the next prompt. +* There is currently no facility for installing periodic update callbacks. +* While theoretically impossible to accidentally crash the autopilot software, + certain scripting APIs can cause damage to you or your vehicle if used + improperly. Use extreme caution with an armed vehicle! +* The script expects Enter to be `\r`, `\r\n`, or `\n`. It prints `\r\n` for a + new line, and uses ANSI cursor control codes for line editing and history. + Check your terminal configuration if Enter doesn't work or you see garbage + characters. Lines longer than the terminal width likely won't edit properly. +* Evaluating complex statements or printing complex results can cause an + `exceeded time limit` error, stopping the script and losing variables and + history. Increasing the vehicle's `SCR_VM_I_COUNT` parameter reduces the + chance of this occurring. diff --git a/libraries/AP_Scripting/applets/revert_param.lua b/libraries/AP_Scripting/applets/revert_param.lua index 27dc9cc943bcf5..009c4c72b8d77e 100644 --- a/libraries/AP_Scripting/applets/revert_param.lua +++ b/libraries/AP_Scripting/applets/revert_param.lua @@ -2,6 +2,10 @@ parameter reversion utility. This helps with manual tuning in-flight by giving a way to instantly revert parameters to the startup parameters --]] + +---@diagnostic disable: param-type-mismatch + + local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local PARAM_TABLE_KEY = 31 @@ -56,9 +60,14 @@ local PSC_prefixes = { "PSC", "Q_P" } local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" } local PID_suffixes = { "FF", "P", "I", "D", "D_FF", "PDMX", "NEF", "NTF", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" } local angle_axes = { "RLL", "PIT", "YAW" } +local rate_limit_axes = { "R", "P", "Y"} local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" } local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER", "PTCH2SRV_TCONST", "RLL2SRV_TCONST" } +-- TECS params +TECS_PARAMS = { "TECS_APPR_SMAX", "TECS_CLMB_MAX", "TECS_FLARE_HGT", "TECS_HDEM_TCONST", "TECS_HGT_OMEGA", "TECS_INTEG_GAIN", "TECS_LAND_ARSPD", "TECS_LAND_DAMP", "TECS_LAND_IGAIN", "TECS_LAND_PDAMP", "TECS_LAND_PMAX", "TECS_LAND_SINK", "TECS_LAND_SPDWGT", "TECS_LAND_SRC", "TECS_LAND_TCONST", "TECS_LAND_TDAMP", "TECS_LAND_THR", "TECS_OPTIONS", "TECS_PITCH_MAX", "TECS_PITCH_MIN", "TECS_PTCH_DAMP", "TECS_PTCH_FF_K", "TECS_PTCH_FF_V0", "TECS_RLL2THR", "TECS_SINK_MAX", "TECS_SINK_MIN", "TECS_SPDWEIGHT", "TECS_SPD_OMEGA", "TECS_SYNAIRSPEED", "TECS_THR_DAMP", "TECS_TIME_CONST", "TECS_TKOFF_IGAIN", "TECS_VERT_ACC" } + + if PREV_ENABLE:get() == 0 then return end @@ -89,6 +98,13 @@ for _, atc in ipairs(ATC_prefixes) do end end +-- add angular rate limits +for _, atc in ipairs(ATC_prefixes) do + for _, axis in ipairs(rate_limit_axes) do + add_param(atc .. "_RATE_" .. axis .. "_MAX") + end +end + -- add fixed wing tuning for _, suffix in ipairs(PID_suffixes) do add_param("RLL_RATE_" .. suffix) @@ -105,6 +121,11 @@ for _, psc in ipairs(PSC_prefixes) do end end +-- add in TECS parameters +for _, p in ipairs(TECS_PARAMS) do + add_param(p) +end + -- add in other parameters for _, p in ipairs(OTHER_PARAMS) do add_param(p) diff --git a/libraries/AP_Scripting/applets/revert_param.md b/libraries/AP_Scripting/applets/revert_param.md index 63d564db7b4905..7d27cee978ce7f 100644 --- a/libraries/AP_Scripting/applets/revert_param.md +++ b/libraries/AP_Scripting/applets/revert_param.md @@ -47,6 +47,7 @@ The script covers the following parameters on quadplanes: - Q_A_ANG_RLL_P - Q_A_ANG_PIT_P - Q_A_ANG_YAW_P + - Q_A_RATE_*_MAX - Q_P_ACCZ_* - Q_P_VELZ_* - Q_P_POSZ_* @@ -61,6 +62,7 @@ The script covers the following parameters on copters: - ATC_ANG_RLL_P - ATC_ANG_PIT_P - ATC_ANG_YAW_P + - ATC_RATE_*_MAX - PSC_ACCZ_* - PSC_VELZ_* - PSC_POSZ_* @@ -73,3 +75,4 @@ For fixed wing the following parameters are covered: - PTCH_RATE_* - RLL2SRV_TCONST - PTCH2SRV_TCONST + - all TECS parameters diff --git a/libraries/AP_Scripting/applets/rover-quicktune.lua b/libraries/AP_Scripting/applets/rover-quicktune.lua index 0d09c6f5f921c9..7a05a5331735e8 100644 --- a/libraries/AP_Scripting/applets/rover-quicktune.lua +++ b/libraries/AP_Scripting/applets/rover-quicktune.lua @@ -18,6 +18,9 @@ See the accompanying rover-quiktune.md file for instructions on how to use --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil + -- global definitions local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} diff --git a/libraries/AP_Scripting/applets/winch-control.lua b/libraries/AP_Scripting/applets/winch-control.lua index 12496f8891f5dc..2e242df4136c2d 100644 --- a/libraries/AP_Scripting/applets/winch-control.lua +++ b/libraries/AP_Scripting/applets/winch-control.lua @@ -10,6 +10,9 @@ -- Alternatively Mission Planner's Aux Function screen can be used in place of an actual RC switch -- +---@diagnostic disable: param-type-mismatch + + -- global definitions local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local PARAM_TABLE_KEY = 80 diff --git a/libraries/AP_Scripting/applets/x-quad-cg-allocation.lua b/libraries/AP_Scripting/applets/x-quad-cg-allocation.lua new file mode 100644 index 00000000000000..89d80e988318d0 --- /dev/null +++ b/libraries/AP_Scripting/applets/x-quad-cg-allocation.lua @@ -0,0 +1,283 @@ +-- x-quad-cg-allocation.lua: Adjust the control allocation matrix for offset CoG. +-- +-- WARNING: This script is applicable only to X-type quadrotors and quadplanes. +-- +-- How To Use +-- 1. Place this script in the "scripts" directory. +-- 2. Set FRAME_CLASS or Q_FRAME_CLASS to 17 to enable the dynamic scriptable mixer. +-- 3. Enable Lua scripting via the SCR_ENABLE parameter. +-- 4. Reboot. +-- 5. Fly the vehicle. +-- 6. Adjust the value of the CGA_RATIO parameter. +-- +-- How It Works +-- 1. The control allocation matrix is adjusted for thrust and pitch based on the ??? parameter value. + +--[[ +Global definitions. +--]] +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +local SCRIPT_NAME = "CoG adjust script" +local LOOP_RATE_HZ = 10 +local last_warning_time_ms = uint32_t() -- Time we last sent a warning message to the user. +local WARNING_DEADTIME_MS = 1000 -- How often the user should be warned. +local is_mixer_matrix_static = false +local is_mixer_matrix_dynamic = false +local last_ratio = 1 + +-- State machine states. +local FSM_STATE = { + INACTIVE = 0, + INITIALIZE = 1, + ACTIVE = 2, + FINISHED = 3 +} +local current_state = FSM_STATE.INACTIVE +local next_state = FSM_STATE.INACTIVE + + +--[[ +New parameter declarations +--]] +local PARAM_TABLE_KEY = 139 +local PARAM_TABLE_PREFIX = "CGA_" + +-- Bind a parameter to a variable. +function bind_param(name) + return Parameter(name) +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 + +-- Add param table. +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 1), SCRIPT_NAME .. ': Could not add param table.') + +--[[ + // @Param: CGA_RATIO + // @DisplayName: CoG adjustment ratio + // @Description: The ratio between the front and back motor outputs during steady-state hover. Positive when the CoG is in front of the motors midpoint (front motors work harder). + // @Range: 0.5 2 + // @User: Advanced +--]] +CGA_RATIO = bind_add_param('RATIO', 1, 1) + +-- Bindings to existing parameters + +--[[ +Potential additions: +--]] +-- Warn the user, throttling the message rate. +function warn_user(msg, severity) + severity = severity or MAV_SEVERITY.WARNING -- Optional severity argument. + if millis() - last_warning_time_ms > WARNING_DEADTIME_MS then + gcs:send_text(severity, SCRIPT_NAME .. ": " .. msg) + last_warning_time_ms = millis() + end +end + +-- Decide if the given ratio value makes sense. +function sanitize_ratio(ratio) + if (ratio < 0.5) or (ratio > 2) then + warn_user("CGA_RATIO value out of bounds.", MAV_SEVERITY.ERROR) + CGA_RATIO:set(1.0) + return 1.0 -- Return default. + else + return ratio + end +end + +-- Normalize the throttle factors to max 1 +function normalize_throttle(factors) + -- Find maximum value. + local max_factor = 0 + for _, factor in ipairs(factors) do + max_factor = math.max(max_factor, factor) + end + -- Adjust all values by it. + normalized_factors = {} + for _, factor in ipairs(factors) do + table.insert(normalized_factors, factor / max_factor) + end + return normalized_factors +end + +-- Calculate the thrust factors given a ratio. +function build_factors(ratio) + local r1 = 2.0/(1+ratio) + local r2 = 2.0*ratio/(1+ratio) + local quad_x_factors = {r2, r1, r2, r1} + return normalize_throttle(quad_x_factors) +end + +-- Adjust the dynamic motor mixer. +function update_dynamic_mixer(ratio) + + Motors_dynamic:add_motor(0, 1) + Motors_dynamic:add_motor(1, 3) + Motors_dynamic:add_motor(2, 4) + Motors_dynamic:add_motor(3, 2) + + factors = motor_factor_table() + + -- Roll stays as-is. + factors:roll(0, -0.5) + factors:roll(1, 0.5) + factors:roll(2, 0.5) + factors:roll(3, -0.5) + + -- Pitch stays as-is. + factors:pitch(0, 0.5) + factors:pitch(1, -0.5) + factors:pitch(2, 0.5) + factors:pitch(3, -0.5) + + -- Yaw stays as-is. + factors:yaw(0, 0.5) + factors:yaw(1, 0.5) + factors:yaw(2, -0.5) + factors:yaw(3, -0.5) + + -- Throttle is modulated. + throttle_factors = build_factors(ratio) + factors:throttle(0, throttle_factors[1]) + factors:throttle(1, throttle_factors[2]) + factors:throttle(2, throttle_factors[3]) + factors:throttle(3, throttle_factors[4]) + + Motors_dynamic:load_factors(factors) + + if not Motors_dynamic:init(4) then + warn_user("Failed to initialize motor matrix!", MAV_SEVERITY.EMERGENCY) + else + if ratio ~= last_ratio then + warn_user("Set ratio to " .. tostring(ratio), MAV_SEVERITY.INFO) + last_ratio = ratio + end + end + motors:set_frame_string("Dynamic CoM adjust") + +end + +-- Adjust the static motor mixer. +function update_static_mixer(ratio) + MotorsMatrix:add_motor_raw(0,-0.5, 0.5, 0.5, 2) + MotorsMatrix:add_motor_raw(1, 0.5,-0.5, 0.5, 4) + MotorsMatrix:add_motor_raw(2, 0.5, 0.5,-0.5, 1) + MotorsMatrix:add_motor_raw(3,-0.5,-0.5,-0.5, 3) + + throttle_factors = build_factors(ratio) + MotorsMatrix:set_throttle_factor(0, throttle_factors[1]) + MotorsMatrix:set_throttle_factor(1, throttle_factors[2]) + MotorsMatrix:set_throttle_factor(2, throttle_factors[3]) + MotorsMatrix:set_throttle_factor(3, throttle_factors[4]) + + if not MotorsMatrix:init(4) then + warn_user("Failed to initialize motor matrix!", MAV_SEVERITY.EMERGENCY) + else + if ratio ~= last_ratio then + warn_user("Set ratio to " .. tostring(ratio), MAV_SEVERITY.INFO) + last_ratio = ratio + end + end + motors:set_frame_string("Static CoM adjust") +end + +-- Decide if the UA is a Quad X quadplane. +function inspect_frame_class_fw() + + Q_ENABLE = bind_param("Q_ENABLE") + Q_FRAME_CLASS = bind_param("Q_FRAME_CLASS") + + if FWVersion:type()==3 then + -- Test for the validity of the parameters. + if Q_ENABLE:get()==1 then + if Q_FRAME_CLASS:get()==15 then + is_mixer_matrix_static = true + elseif Q_FRAME_CLASS:get()==17 then + is_mixer_matrix_dynamic = true + end + end + end +end + +-- Decide if the UA is a Quad X multicopter. +function inspect_frame_class_mc() + + FRAME_CLASS = bind_param("FRAME_CLASS") + + if FWVersion:type()==2 then + if FRAME_CLASS:get()==15 then + is_mixer_matrix_static = true + elseif FRAME_CLASS:get()==17 then + is_mixer_matrix_dynamic = true + end + end +end + +--[[ +Activation conditions +--]] +-- Check for script activating conditions here. +-- Check frame types. +function can_start() + result = is_mixer_matrix_static or is_mixer_matrix_dynamic + return result +end + +--[[ +State machine +--]] +function fsm_step() + if current_state == FSM_STATE.INACTIVE then + if can_start() then + next_state = FSM_STATE.INITIALIZE + else + next_state = FSM_STATE.FINISHED + warn_user("Could not find scriptable mixer", MAV_SEVERITY.ERROR) + end + + elseif current_state == FSM_STATE.INITIALIZE then + if is_mixer_matrix_static then + local ratio = sanitize_ratio(CGA_RATIO:get()) + update_static_mixer(ratio) + next_state = FSM_STATE.FINISHED + else + next_state = FSM_STATE.ACTIVE + end + + elseif current_state == FSM_STATE.ACTIVE then + -- Assert the parameter limits. + local ratio = sanitize_ratio(CGA_RATIO:get()) + -- Create the control allocation matrix parameters. + update_dynamic_mixer(ratio) + + else + gcs:send_text(MAV_SEVERITY.CRITICAL, "Unexpected FSM state!") + end + + current_state = next_state +end + +-- Check once on boot if the frame type is suitable for this script. +pcall(inspect_frame_class_mc) +pcall(inspect_frame_class_fw) +gcs:send_text(MAV_SEVERITY.INFO, SCRIPT_NAME .. string.format(" loaded.")) + +-- Wrapper around update() to catch errors. +function protected_wrapper() + local success, err = pcall(fsm_step) + if not success then + gcs:send_text(MAV_SEVERITY.EMERGENCY, "Internal Error: " .. err) + return protected_wrapper, 1000 + end + if not (current_state == FSM_STATE.FINISHED) then + return protected_wrapper, 1000.0/LOOP_RATE_HZ + end +end + +-- Start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/applets/x-quad-cg-allocation.md b/libraries/AP_Scripting/applets/x-quad-cg-allocation.md new file mode 100644 index 00000000000000..ef876880995e67 --- /dev/null +++ b/libraries/AP_Scripting/applets/x-quad-cg-allocation.md @@ -0,0 +1,65 @@ +# Multicopter CoM compensation + +This script allows for adjusting the control allocation matrix. + +When the Center of Mass (CoM) of an airframe does not coincide with the center +of its thrusters, then there is a lever arm between the thrust vector and the +CoM. This often is the case in VTOL fixed-wing aircraft (quadplanes) where +typically the CoM is more forward than the center of thrust. As a result, the +thrust produces a pitch-down moment. This produces a disturbance in the pitch +control and requires significant wind-up in the pitch integrator. + +To compensate for this issue, this script employs the scriptable control +allocation matrix to request asymmeterical front and back thrust. + +WARNING: This script is applicable only to X-type quadrotors and quadplanes. Do +not use in any other frame configuration! + +# Parameters + +The script adds 1 parameter to control its behaviour. + +## CGA_RATIO + +This is the desired ratio between the front and back thrust. To have the front +motors produce more lift that the rear, increase higher than 1. + +Reasonable extreme values are 2 (front works twice as hard as the rear) and 0.5 +(the inverse case). Given an out-of-bounds parameter value, the script will +revert to the default 1.0. + +# Operation + +## How To Use + +First of all, place this script in the "scripts" directory. + +To tune `CGA_RATIO` on the fly: + + 1. Set `FRAME_CLASS` or `Q_FRAME_CLASS` (for quadplanes) to 17 to enable the + dynamic scriptable mixer. + 2. Enable Lua scripting via the `SCR_ENABLE` parameter. + 3. Reboot. + 4. Fly the vehicle. + 5. Adjust the value of the `CGA_RATIO` parameter. A good indicator of a good + tune is to monitor the telemetry value `PID_TUNE[2].I` (pitch rate controller + integrator) until it reaches zero during a stable hover. + +Once you are happy with the tuning, you can fall back to the static motor +matrix, which consumes no resources from the scripting engine: + + 1. Set `FRAME_CLASS` or `Q_FRAME_CLASS` (for quadplanes) to 15 to enable the + static scriptable mixer. + 2. Ensure Lua scripting is enabled via the `SCR_ENABLE` parameter. + 3. Reboot. + +The aircraft is ready to fly. +Keep in mind that any further changes to `CGA_RATIO` will now require a reboot. + +## How It Works + + 1. The dynamic control allocation matrix is able to change the coefficients + that convert the throttle command to individual PWM commands for every motor. + These coefficients have a default value of 1. + 2. The parameter `CGA_RATIO` is used to alter these coefficients, so that the + front and back thrust commands are not equal. \ No newline at end of file diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 0807c406d1dfcf..0a689dd344e750 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1,3 +1,4 @@ +---@meta -- ArduPilot lua scripting documentation in EmmyLua Annotations -- This file should be auto generated and then manual edited -- generate with --scripting-docs, eg ./waf copter --scripting-docs @@ -6,18 +7,32 @@ -- luacheck: ignore 122 (Setting a read-only field of a global variable) -- luacheck: ignore 212 (Unused argument) -- luacheck: ignore 241 (Local variable is mutated but never accessed) +-- luacheck: ignore 221 (Local variable is accessed but never set.) -- set and get for field types share function names ---@diagnostic disable: duplicate-set-field ---@diagnostic disable: missing-return +-- integer enum value unknown by docs generator +---@type integer +local enum_integer + -- manual bindings ----@class uint32_t_ud +---@class (exact) uint32_t_ud +---@operator add(uint32_t_ud|integer|number): uint32_t_ud +---@operator sub(uint32_t_ud|integer|number): uint32_t_ud +---@operator mul(uint32_t_ud|integer|number): uint32_t_ud +---@operator div(uint32_t_ud|integer|number): uint32_t_ud +---@operator mod(uint32_t_ud|integer|number): uint32_t_ud +---@operator band(uint32_t_ud|integer|number): uint32_t_ud +---@operator bor(uint32_t_ud|integer|number): uint32_t_ud +---@operator shl(uint32_t_ud|integer|number): uint32_t_ud +---@operator shr(uint32_t_ud|integer|number): uint32_t_ud local uint32_t_ud = {} -- create uint32_t_ud with optional value ----@param value? number|integer +---@param value? uint32_t_ud|integer|number ---@return uint32_t_ud function uint32_t(value) end @@ -29,6 +44,44 @@ function uint32_t_ud:tofloat() end ---@return integer function uint32_t_ud:toint() end +---@class (exact) uint64_t_ud +---@operator add(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator sub(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator mul(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator div(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator mod(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator band(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator bor(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator shl(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +---@operator shr(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud +local uint64_t_ud = {} + +-- create uint64_t_ud with optional value +-- Note that lua ints are 32 bits and lua floats will loose resolution at large values +---@param value? uint64_t_ud|uint32_t_ud|integer|number +---@return uint64_t_ud +function uint64_t(value) end + +-- create uint64_t_ud from a low and high half +-- value = (high << 32) | low +---@param high uint32_t_ud|integer|number +---@param low uint32_t_ud|integer|number +---@return uint64_t_ud +function uint64_t(high, low) end + +-- Convert to number, will loose resolution at large values +---@return number +function uint64_t_ud:tofloat() end + +-- Convert to integer, nil if too large to be represented by native int32 +---@return integer|nil +function uint64_t_ud:toint() end + +-- Split into high and low half's, returning each as a uint32_t_ud +---@return uint32_t_ud -- high (value >> 32) +---@return uint32_t_ud -- low (value & 0xFFFFFFFF) +function uint64_t_ud:split() end + -- system time in milliseconds ---@return uint32_t_ud -- milliseconds function millis() end @@ -52,36 +105,41 @@ function mission_receive() end function print(text) end -- data flash logging to SD card ----@class logger logger = {} --- write value to data flash log with given types and names, optional units and multipliers, timestamp will be automatically added +-- write value to data flash log with given types and names with units and multipliers, timestamp will be automatically added +---@param name string -- up to 4 characters +---@param labels string -- comma separated value labels, up to 58 characters +---@param format string -- type format string, see https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Logger/README.md +---@param units string -- units string +---@param multipliers string -- multipliers string +---@param ... integer|number|uint32_t_ud|string -- data to be logged, type to match format string +function logger:write(name, labels, format, units, multipliers, ...) end + +-- write value to data flash log with given types and names, timestamp will be automatically added ---@param name string -- up to 4 characters ---@param labels string -- comma separated value labels, up to 58 characters ---@param format string -- type format string, see https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Logger/README.md ----@param units? string -- optional units string ----@param multipliers? string -- optional multipliers string ----@param data1 integer|number|uint32_t_ud|string -- data to be logged, type to match format string -function logger:write(name, labels, format, units, multipliers, data1, ...) end +---@param ... integer|number|uint32_t_ud|string -- data to be logged, type to match format string +function logger:write(name, labels, format, ...) end -- log a files content to onboard log ---@param filename string -- file name function logger:log_file_content(filename) end -- i2c bus interaction ----@class i2c i2c = {} -- get a i2c device handler ---@param bus integer -- bus number ---@param address integer -- device address 0 to 128 ----@param clock? uint32_t_ud -- optional bus clock, default 400000 +---@param clock? uint32_t_ud|integer|number -- optional bus clock, default 400000 ---@param smbus? boolean -- optional sumbus flag, default false ---@return AP_HAL__I2CDevice_ud function i2c:get_device(bus, address, clock, smbus) end -- EFI state structure ----@class EFI_State_ud +---@class (exact) EFI_State_ud local EFI_State_ud = {} ---@return EFI_State_ud @@ -236,7 +294,7 @@ function EFI_State_ud:spark_dwell_time_ms(value) end function EFI_State_ud:engine_speed_rpm() end -- set field ----@param value uint32_t_ud +---@param value uint32_t_ud|integer|number function EFI_State_ud:engine_speed_rpm(value) end -- get field @@ -260,12 +318,12 @@ function EFI_State_ud:general_error(value) end function EFI_State_ud:last_updated_ms() end -- set field ----@param value uint32_t_ud +---@param value uint32_t_ud|integer|number function EFI_State_ud:last_updated_ms(value) end -- EFI Cylinder_Status structure ----@class Cylinder_Status_ud +---@class (exact) Cylinder_Status_ud local Cylinder_Status_ud = {} ---@return Cylinder_Status_ud @@ -328,36 +386,48 @@ function Cylinder_Status_ud:ignition_timing_deg() end function Cylinder_Status_ud:ignition_timing_deg(value) end -- desc ----@class efi efi = {} -- desc ---@return EFI_State_ud function efi:get_state() end +-- get last update time in milliseconds +---@return uint32_t_ud +function efi:get_last_update_ms() end + -- desc ---@param instance integer ----@return AP_EFI_Backend_ud +---@return AP_EFI_Backend_ud|nil function efi:get_backend(instance) end -- CAN bus interaction ----@class CAN CAN = {} --- get a CAN bus device handler first scripting driver ----@param buffer_len uint32_t_ud -- buffer length 1 to 25 ----@return ScriptingCANBuffer_ud +-- get a CAN bus device handler first scripting driver, will return nil if no driver with protocol Scripting is configured +---@param buffer_len uint32_t_ud|integer|number -- buffer length 1 to 25 +---@return ScriptingCANBuffer_ud|nil function CAN:get_device(buffer_len) end --- get a CAN bus device handler second scripting driver ----@param buffer_len uint32_t_ud -- buffer length 1 to 25 ----@return ScriptingCANBuffer_ud +-- get a CAN bus device handler second scripting driver, will return nil if no driver with protocol Scripting2 is configured +---@param buffer_len uint32_t_ud|integer|number -- buffer length 1 to 25 +---@return ScriptingCANBuffer_ud|nil function CAN:get_device2(buffer_len) end + +-- get latest FlexDebug message from a CAN node +---@param bus number -- CAN bus number, 0 for first bus, 1 for 2nd +---@param node number -- CAN node +---@param id number -- FlexDebug message ID +---@param last_us uint32_t_ud|integer|number -- timestamp of last received message, new message will be returned if timestamp is different +---@return uint32_t_ud|nil -- timestamp of message (first frame arrival time) +---@return string|nil -- up to 255 byte buffer +function DroneCAN_get_FlexDebug(bus,node,id,last_us) end + -- Auto generated binding -- desc ----@class CANFrame_ud +---@class (exact) CANFrame_ud local CANFrame_ud = {} ---@return CANFrame_ud @@ -386,7 +456,7 @@ function CANFrame_ud:data(index, value) end function CANFrame_ud:id() end -- set field ----@param value uint32_t_ud +---@param value uint32_t_ud|integer|number function CANFrame_ud:id(value) end -- desc @@ -406,7 +476,7 @@ function CANFrame_ud:isExtended() end function CANFrame_ud:id_signed() end -- desc ----@class motor_factor_table_ud +---@class (exact) motor_factor_table_ud local motor_factor_table_ud = {} ---@return motor_factor_table_ud @@ -453,11 +523,23 @@ function motor_factor_table_ud:roll(index) end function motor_factor_table_ud:roll(index, value) end -- network socket class ----@class SocketAPM_ud +---@class (exact) SocketAPM_ud local SocketAPM_ud = {} --- desc -function Socket(param1) end +-- Get a new socket +---@param datagram integer -- set to 1 for UDP, 0 for TCP +---@return SocketAPM_ud +function Socket(datagram) end + +-- return an IPv4 address given a string +---@param str_address string -- ipv4 address as string +---@return uint32_t_ud -- ipv4 address +function string_to_ipv4_addr(str_address) end + +-- return a string representation of ipv4 address +---@param addr uint32_t_ud|integer|number -- ipv4 address +---@return string -- string representation of address +function ipv4_addr_to_string(addr) end -- return true if a socket is connected ---@return boolean @@ -475,10 +557,18 @@ function SocketAPM_ud:listen(backlog) end -- send a lua string. May contain binary data ---@param str string ----@param len uint32_t_ud +---@param len uint32_t_ud|integer|number ---@return integer function SocketAPM_ud:send(str, len) end +-- send a lua string to a specified address. May contain binary data +---@param str string +---@param len uint32_t_ud|integer|number +---@param ipaddr uint32_t_ud|integer|number -- ipv4 address +---@param port integer -- ipv4 port +---@return integer +function SocketAPM_ud:sendto(str, len, ipaddr, port) end + -- bind to an address. Use "0.0.0.0" for wildcard bind ---@param IP_address string ---@param port integer @@ -494,20 +584,23 @@ function SocketAPM_ud:connect(IP_address, port) end --[[ accept new incoming sockets, returning a new socket. Must be used on a stream socket in listen state --]] -function SocketAPM_ud:accept(param1) end +---@return SocketAPM_ud|nil +function SocketAPM_ud:accept() end -- receive data from a socket ----@param length ----@return data +---@param length integer +---@return string|nil +---@return uint32_t_ud|nil -- source IP +---@return integer|nil -- source port function SocketAPM_ud:recv(length) end -- check for available input ----@param timeout_ms uint32_t_ud +---@param timeout_ms uint32_t_ud|integer|number ---@return boolean function SocketAPM_ud:pollin(timeout_ms) end -- check for availability of space to write to socket ----@param timeout_ms uint32_t_ud +---@param timeout_ms uint32_t_ud|integer|number ---@return boolean function SocketAPM_ud:pollout(timeout_ms) end @@ -523,6 +616,8 @@ function SocketAPM_ud:close() end this also "closes" the socket and the file from the point of view of lua the underlying socket and file are both closed on end of file --]] +---@param filehandle string +---@return boolean -- success function SocketAPM_ud:sendfile(filehandle) end -- enable SO_REUSEADDR on a socket @@ -530,7 +625,7 @@ function SocketAPM_ud:sendfile(filehandle) end function SocketAPM_ud:reuseaddress() end -- desc ----@class AP_HAL__PWMSource_ud +---@class (exact) AP_HAL__PWMSource_ud local AP_HAL__PWMSource_ud = {} ---@return AP_HAL__PWMSource_ud @@ -551,7 +646,7 @@ function AP_HAL__PWMSource_ud:set_pin(pin_number) end -- desc ----@class mavlink_mission_item_int_t_ud +---@class (exact) mavlink_mission_item_int_t_ud local mavlink_mission_item_int_t_ud = {} ---@return mavlink_mission_item_int_t_ud @@ -646,40 +741,41 @@ function mavlink_mission_item_int_t_ud:param1() end function mavlink_mission_item_int_t_ud:param1(value) end --- desc ----@class Parameter_ud +-- Parameter access helper. +---@class (exact) Parameter_ud local Parameter_ud = {} +-- Create a new parameter helper, init must be called with a parameter name. ---@return Parameter_ud ----@param name? string -function Parameter(name) end +function Parameter() end --- desc +-- Set the defualt value of this parameter, if the parameter has not been configured by the user its value will be updated to the new defualt. ---@param value number ---@return boolean function Parameter_ud:set_default(value) end --- desc +-- Return true if the parameter has been configured by the user. ---@return boolean function Parameter_ud:configured() end --- desc +-- Set the parameter to the given value and save. The value will be persistant after a reboot. ---@param value number ---@return boolean function Parameter_ud:set_and_save(value) end --- desc +-- Set the parameter to the given value. The value will not persist a reboot. ---@param value number ---@return boolean function Parameter_ud:set(value) end --- desc +-- Get the current value of a parameter. +-- Returns nil if the init has not been called and a valid parameter found. ---@return number|nil function Parameter_ud:get() end --- desc +-- Init the paramter from a key. This allows the script to load old parameter that have been removed from the main code. ---@param key integer ----@param group_element uint32_t_ud +---@param group_element uint32_t_ud|integer|number ---@param type integer ---| '1' # AP_PARAM_INT8 ---| '2' # AP_PARAM_INT16 @@ -688,150 +784,193 @@ function Parameter_ud:get() end ---@return boolean function Parameter_ud:init_by_info(key, group_element, type) end --- desc +-- Init this parameter from a name. ---@param name string ---@return boolean function Parameter_ud:init(name) end +-- Parameter access helper +---@class (exact) Parameter_ud_const +local Parameter_ud_const = {} --- desc ----@class Vector2f_ud +-- Create a new parameter helper with a parameter name. +-- This will error if no parameter with the given name is found. +---@return Parameter_ud_const +---@param name string +function Parameter(name) end + +-- Set the defualt value of this parameter, if the parameter has not been configured by the user its value will be updated to the new defualt. +---@param value number +---@return boolean +function Parameter_ud_const:set_default(value) end + +-- Retrun true if the parameter has been configured by the user. +---@return boolean +function Parameter_ud_const:configured() end + +-- Set the parameter to the given value and save. The value will be persistant after a reboot. +---@param value number +---@return boolean +function Parameter_ud_const:set_and_save(value) end + +-- Set the parameter to the given value. The value will not persist a reboot. +---@param value number +---@return boolean +function Parameter_ud_const:set(value) end + +-- Get the current value of a parameter. +---@return number +function Parameter_ud_const:get() end + +-- Vector2f is a userdata object that holds a 2D vector with x and y components. The components are stored as floating point numbers. +-- To create a new Vector2f you can call Vector2f() to allocate a new one, or call a method that returns one to you. +---@class (exact) Vector2f_ud +---@operator add(Vector2f_ud): Vector2f_ud +---@operator sub(Vector2f_ud): Vector2f_ud local Vector2f_ud = {} +-- Create Vector2f object ---@return Vector2f_ud function Vector2f() end --- copy ----@return Vector2f_ud +-- Copy this Vector2f returning a new userdata object +---@return Vector2f_ud -- a copy of this Vector2f function Vector2f_ud:copy() end --- get field +-- get y component ---@return number function Vector2f_ud:y() end --- set field +-- set y component ---@param value number function Vector2f_ud:y(value) end --- get field +-- get x component ---@return number function Vector2f_ud:x() end --- set field +-- set x component ---@param value number function Vector2f_ud:x(value) end --- desc ----@param angle_rad number +-- rotate vector by angle in radians +---@param angle_rad number -- angle in radians function Vector2f_ud:rotate(angle_rad) end --- desc ----@return boolean +-- Check if both components of the vector are zero +---@return boolean -- true if both components are zero function Vector2f_ud:is_zero() end --- desc ----@return boolean +-- Check if either components of the vector are infinite +---@return boolean -- true if either components are infinite function Vector2f_ud:is_inf() end --- desc ----@return boolean +-- Check if either components of the vector are nan +---@return boolean -- true if either components are nan function Vector2f_ud:is_nan() end --- desc +-- normalize this vector to a unit length function Vector2f_ud:normalize() end --- desc ----@return number +-- Calculate length of this vector sqrt(x^2 + y^2) +---@return number -- length of this vector function Vector2f_ud:length() end --- desc ----@return number +-- Calculate the angle of this vector in radians +-- 2PI + atan2(-x, y) +---@return number -- angle in radians function Vector2f_ud:angle() end --- desc ----@class Vector3f_ud +-- Vector3f is a userdata object that holds a 3D vector with x, y and z components. +-- The components are stored as floating point numbers. +-- To create a new Vector3f you can call Vector3f() to allocate a new one, or call a method that returns one to you. +---@class (exact) Vector3f_ud +---@operator add(Vector3f_ud): Vector3f_ud +---@operator sub(Vector3f_ud): Vector3f_ud local Vector3f_ud = {} +-- Create Vector3f object ---@return Vector3f_ud function Vector3f() end --- copy ----@return Vector3f_ud +-- Copy this Vector3f returning a new userdata object +---@return Vector3f_ud -- a copy of this Vector3f function Vector3f_ud:copy() end --- get field +-- get z component ---@return number function Vector3f_ud:z() end --- set field +-- set z component ---@param value number function Vector3f_ud:z(value) end --- get field +-- get y component ---@return number function Vector3f_ud:y() end --- set field +-- set y component ---@param value number function Vector3f_ud:y(value) end --- get field +-- get x component ---@return number function Vector3f_ud:x() end --- set field +-- set x component ---@param value number function Vector3f_ud:x(value) end --- desc +-- Return a new Vector3 based on this one with scaled length and the same changing direction ---@param scale_factor number ----@return Vector3f_ud +---@return Vector3f_ud -- scaled copy of this vector function Vector3f_ud:scale(scale_factor) end --- desc +-- Cross product of two Vector3fs ---@param vector Vector3f_ud ----@return Vector3f_ud +---@return Vector3f_ud -- result function Vector3f_ud:cross(vector) end --- desc +-- Dot product of two Vector3fs ---@param vector Vector3f_ud ----@return number +---@return number -- result function Vector3f_ud:dot(vector) end --- desc ----@return boolean +-- Check if all components of the vector are zero +---@return boolean -- true if all components are zero function Vector3f_ud:is_zero() end --- desc ----@return boolean +-- Check if any components of the vector are infinite +---@return boolean -- true if any components are infinite function Vector3f_ud:is_inf() end --- desc ----@return boolean +-- Check if any components of the vector are nan +---@return boolean -- true if any components are nan function Vector3f_ud:is_nan() end --- desc +-- normalize this vector to a unit length function Vector3f_ud:normalize() end --- desc ----@return number +-- Calculate length of this vector sqrt(x^2 + y^2 + z^2) +---@return number -- length of this vector function Vector3f_ud:length() end -- Computes angle between this vector and vector v2 ----@param v2 Vector3f_ud +---@param v2 Vector3f_ud ---@return number function Vector3f_ud:angle(v2) end --- desc +-- Rotate vector by angle in radians in xy plane leaving z untouched ---@param param1 number -- XY rotation in radians function Vector3f_ud:rotate_xy(param1) end --- desc +-- return the x and y components of this vector as a Vector2f ---@return Vector2f_ud function Vector3f_ud:xy() end -- desc ----@class Quaternion_ud +---@class (exact) Quaternion_ud +---@operator mul(Quaternion_ud): Quaternion_ud local Quaternion_ud = {} ---@return Quaternion_ud @@ -916,83 +1055,86 @@ function Quaternion_ud:normalize() end ---@return number function Quaternion_ud:length() end --- desc ----@class Location_ud +-- Location is a userdata object that holds locations expressed as latitude, longitude, altitude. +-- The altitude can be in several different frames, relative to home, absolute altitude above mean sea level, or relative to terrain. +-- To create a new Location userdata you can call Location() to allocate an empty location object, or call a method that returns one to you. +---@class (exact) Location_ud local Location_ud = {} +-- Create location object ---@return Location_ud function Location() end --- copy ----@return Location_ud +-- Copy this location returning a new userdata object +---@return Location_ud -- a copy of this location function Location_ud:copy() end --- get field ----@return boolean +-- get loiter xtrack +---@return boolean -- Get if the location is used for a loiter location this flags if the aircraft should track from the center point, or from the exit location of the loiter. function Location_ud:loiter_xtrack() end --- set field ----@param value boolean +-- set loiter xtrack +---@param value boolean -- Set if the location is used for a loiter location this flags if the aircraft should track from the center point, or from the exit location of the loiter. function Location_ud:loiter_xtrack(value) end --- get field ----@return boolean +-- get origin alt +---@return boolean -- true if altitude is relative to origin function Location_ud:origin_alt() end --- set field ----@param value boolean +-- set origin alt +---@param value boolean -- set true if altitude is relative to origin function Location_ud:origin_alt(value) end --- get field ----@return boolean +-- get terrain alt +---@return boolean -- true if altitude is relative to terrain function Location_ud:terrain_alt() end --- set field ----@param value boolean +-- set terrain alt +---@param value boolean -- set true if altitude is relative to home function Location_ud:terrain_alt(value) end --- get field ----@return boolean +-- get relative alt +---@return boolean -- true if altitude is relative to home function Location_ud:relative_alt() end --- set field ----@param value boolean +-- set relative alt +---@param value boolean -- set true if altitude is relative to home function Location_ud:relative_alt(value) end --- get field ----@return integer +-- get altitude in cm +---@return integer -- altitude in cm function Location_ud:alt() end --- set field +-- set altitude in cm ---@param value integer function Location_ud:alt(value) end --- get field ----@return integer +-- get longitude in degrees * 1e7 +---@return integer -- longitude in degrees * 1e7 function Location_ud:lng() end --- set field ----@param value integer +-- set longitude in degrees * 1e7 +---@param value integer -- longitude in degrees * 1e7 function Location_ud:lng(value) end --- get field ----@return integer +-- get latitude in degrees * 1e7 +---@return integer -- latitude in degrees * 1e7 function Location_ud:lat() end --- set field ----@param value integer +-- set latitude in degrees * 1e7 +---@param value integer -- latitude in degrees * 1e7 function Location_ud:lat(value) end --- get altitude frame ----@return integer +-- get altitude frame of this location +---@return integer -- altitude frame ---| '0' # ABSOLUTE ---| '1' # ABOVE_HOME ---| '2' # ABOVE_ORIGIN ---| '3' # ABOVE_TERRAIN function Location_ud:get_alt_frame() end --- desc ----@param desired_frame integer +-- Set the altitude frame of this location +---@param desired_frame integer -- altitude frame ---| '0' # ABSOLUTE ---| '1' # ABOVE_HOME ---| '2' # ABOVE_ORIGIN @@ -1000,48 +1142,49 @@ function Location_ud:get_alt_frame() end ---@return boolean function Location_ud:change_alt_frame(desired_frame) end --- desc ----@param loc Location_ud ----@return Vector2f_ud +-- Given a Location this calculates the north and east distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return Vector2f_ud -- North east distance vector in meters function Location_ud:get_distance_NE(loc) end --- desc ----@param loc Location_ud ----@return Vector3f_ud +-- Given a Location this calculates the north, east and down distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return Vector3f_ud -- North east down distance vector in meters function Location_ud:get_distance_NED(loc) end --- desc ----@param loc Location_ud ----@return number +-- Given a Location this calculates the relative bearing to the location in radians +---@param loc Location_ud -- location to compare with +---@return number -- bearing in radians function Location_ud:get_bearing(loc) end --- desc ----@return Vector3f_ud|nil +-- Returns the offset from the EKF origin to this location. +-- Returns nil if the EKF origin wasn’t available at the time this was called. +---@return Vector3f_ud|nil -- Vector between origin and location north east up in meters function Location_ud:get_vector_from_origin_NEU() end --- desc ----@param bearing_deg number ----@param distance number +-- Translates this Location by the specified distance given a bearing. +---@param bearing_deg number -- bearing in degrees +---@param distance number -- distance in meters function Location_ud:offset_bearing(bearing_deg, distance) end --- desc ----@param bearing_deg number ----@param pitch_deg number ----@param distance number +-- Translates this Location by the specified distance given a bearing and pitch. +---@param bearing_deg number -- bearing in degrees +---@param pitch_deg number -- pitch in degrees +---@param distance number -- distance in meters function Location_ud:offset_bearing_and_pitch(bearing_deg, pitch_deg, distance) end --- desc ----@param ofs_north number ----@param ofs_east number +-- Translates this Location by the specified north and east distance in meters. +---@param ofs_north number -- north offset in meters +---@param ofs_east number -- east offset in meters function Location_ud:offset(ofs_north, ofs_east) end --- desc ----@param loc Location_ud ----@return number +-- Given a Location this calculates the horizontal distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return number -- horizontal distance in meters function Location_ud:get_distance(loc) end -- desc ----@class AP_EFI_Backend_ud +---@class (exact) AP_EFI_Backend_ud local AP_EFI_Backend_ud = {} -- desc @@ -1050,7 +1193,7 @@ local AP_EFI_Backend_ud = {} function AP_EFI_Backend_ud:handle_scripting(state) end -- desc ----@class ScriptingCANBuffer_ud +---@class (exact) ScriptingCANBuffer_ud local ScriptingCANBuffer_ud = {} -- desc @@ -1060,20 +1203,20 @@ function ScriptingCANBuffer_ud:read_frame() end -- Add a filter to the CAN buffer, mask is bitwise ANDed with the frame id and compared to value if not match frame is not buffered -- By default no filters are added and all frames are buffered, write is not affected by filters -- Maximum number of filters is 8 ----@param mask uint32_t_ud ----@param value uint32_t_ud +---@param mask uint32_t_ud|integer|number +---@param value uint32_t_ud|integer|number ---@return boolean -- returns true if the filler was added successfully function ScriptingCANBuffer_ud:add_filter(mask, value) end -- desc ---@param frame CANFrame_ud ----@param timeout_us uint32_t_ud +---@param timeout_us uint32_t_ud|integer|number ---@return boolean function ScriptingCANBuffer_ud:write_frame(frame, timeout_us) end -- desc ----@class AP_HAL__AnalogSource_ud +---@class (exact) AP_HAL__AnalogSource_ud local AP_HAL__AnalogSource_ud = {} -- desc @@ -1095,13 +1238,20 @@ function AP_HAL__AnalogSource_ud:set_pin(pin_number) end -- desc ----@class AP_HAL__I2CDevice_ud +---@class (exact) AP_HAL__I2CDevice_ud local AP_HAL__I2CDevice_ud = {} -- desc ---@param address integer function AP_HAL__I2CDevice_ud:set_address(address) end +-- Performs an I2C transfer, sending data_str bytes (see string.pack) and +-- returning a string of any requested read bytes (see string.unpack) +---@param data_str string +---@param read_length integer +---@return string|nil +function AP_HAL__I2CDevice_ud:transfer(data_str, read_length) end + -- 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 @@ -1120,45 +1270,50 @@ function AP_HAL__I2CDevice_ud:write_register(register_num, value) end function AP_HAL__I2CDevice_ud:set_retries(retries) end --- desc ----@class AP_HAL__UARTDriver_ud -local AP_HAL__UARTDriver_ud = {} +-- Serial port access object +---@class (exact) AP_Scripting_SerialAccess_ud +local AP_Scripting_SerialAccess_ud = {} --- desc ----@param flow_control_setting integer ----| '0' # disabled ----| '1' # enabled ----| '2' # auto -function AP_HAL__UARTDriver_ud:set_flow_control(flow_control_setting) end +-- Start serial port with the given baud rate (no effect for device ports) +---@param baud_rate uint32_t_ud|integer|number +function AP_Scripting_SerialAccess_ud:begin(baud_rate) end --- desc ----@return uint32_t_ud -function AP_HAL__UARTDriver_ud:available() end +-- Writes a single byte +---@param value integer -- byte to write +---@return uint32_t_ud -- 1 if success else 0 +function AP_Scripting_SerialAccess_ud:write(value) end --- desc ----@param value integer ----@return uint32_t_ud -function AP_HAL__UARTDriver_ud:write(value) end +-- Writes a string. The number of bytes actually written, i.e. the length of the +-- written prefix of the string, is returned. It may be 0 up to the length of +-- the string. +---@param data string -- string of bytes to write +---@return integer -- number of bytes actually written, which may be 0 +function AP_Scripting_SerialAccess_ud:writestring(data) end --- desc ----@return integer -function AP_HAL__UARTDriver_ud:read() end +-- Reads a single byte from the serial port +---@return integer -- byte, -1 if error or none available +function AP_Scripting_SerialAccess_ud:read() end --- desc ----@param baud_rate uint32_t_ud -function AP_HAL__UARTDriver_ud:begin(baud_rate) end +-- Reads up to `count` bytes and returns the bytes read as a string. No bytes +-- may be read, in which case a 0-length string is returned. +---@param count integer -- maximum number of bytes to read +---@return string|nil -- bytes actually read, which may be 0-length, or nil on error +function AP_Scripting_SerialAccess_ud:readstring(count) end ---[[ - read count bytes from a uart and return as a lua string. Note - that the returned string can be shorter than the requested length ---]] ----@param count integer ----@return string|nil -function AP_HAL__UARTDriver_ud:readstring(count) end +-- Returns number of available bytes to read. +---@return uint32_t_ud +function AP_Scripting_SerialAccess_ud:available() end + +-- Set flow control option for serial port (no effect for device ports) +---@param flow_control_setting integer +---| '0' # disabled +---| '1' # enabled +---| '2' # auto +function AP_Scripting_SerialAccess_ud:set_flow_control(flow_control_setting) end -- desc ----@class RC_Channel_ud +---@class (exact) RC_Channel_ud local RC_Channel_ud = {} -- desc @@ -1182,7 +1337,6 @@ function RC_Channel_ud:norm_input() end function RC_Channel_ud:norm_input_dz() end -- desc ----@class winch winch = {} -- desc @@ -1205,7 +1359,6 @@ function winch:relax() end function winch:healthy() end -- desc ----@class iomcu iomcu = {} -- Check if the IO is healthy @@ -1213,7 +1366,6 @@ iomcu = {} function iomcu:healthy() end -- desc ----@class compass compass = {} -- Check if the compass is healthy @@ -1222,7 +1374,6 @@ compass = {} function compass:healthy(instance) end -- desc ----@class camera camera = {} -- desc @@ -1241,7 +1392,7 @@ function camera:record_video(instance, start_recording) end function camera:take_picture(instance) end -- desc ----@class AP_Camera__camera_state_t_ud +---@class (exact) AP_Camera__camera_state_t_ud local AP_Camera__camera_state_t_ud = {} ---@return AP_Camera__camera_state_t_ud @@ -1288,8 +1439,259 @@ function AP_Camera__camera_state_t_ud:take_pic_incr() end ---@return AP_Camera__camera_state_t_ud|nil function camera:get_state(instance) end +-- Change a camera setting to a given value +---@param instance integer +---@param setting integer +---| '0' # THERMAL_PALETTE +---| '1' # THERMAL_GAIN +---| '2' # THERMAL_RAW_DATA +---@param value number +---@return boolean +function camera:change_setting(instance, setting, value) end + +-- The MAVLink CAMERA_INFORMATION message struct +---@class (exact) mavlink_camera_information_t_ud +local mavlink_camera_information_t_ud = {} + +---@return mavlink_camera_information_t_ud +function mavlink_camera_information_t() end + +-- get field +---@return uint32_t_ud +function mavlink_camera_information_t_ud:time_boot_ms() end + +-- set field +---@param value uint32_t_ud|integer|number +function mavlink_camera_information_t_ud:time_boot_ms(value) end + +-- get field +---@return uint32_t_ud +function mavlink_camera_information_t_ud:firmware_version() end + + -- set field +---@param value uint32_t_ud|integer|number +function mavlink_camera_information_t_ud:firmware_version(value) end + +-- get field +---@return number +function mavlink_camera_information_t_ud:focal_length() end + + -- set field +---@param value number +function mavlink_camera_information_t_ud:focal_length(value) end + +-- get field +---@return number +function mavlink_camera_information_t_ud:sensor_size_h() end + + -- set field +---@param value number +function mavlink_camera_information_t_ud:sensor_size_h(value) end + +-- get field +---@return number +function mavlink_camera_information_t_ud:sensor_size_v() end + + -- set field +---@param value number +function mavlink_camera_information_t_ud:sensor_size_v(value) end + +-- get field +---@return uint32_t_ud +function mavlink_camera_information_t_ud:flags() end + + -- set field +---@param value uint32_t_ud|integer|number +function mavlink_camera_information_t_ud:flags(value) end + +-- get field +---@return integer +function mavlink_camera_information_t_ud:resolution_h() end + + -- set field +---@param value integer +function mavlink_camera_information_t_ud:resolution_h(value) end + +-- get field +---@return integer +function mavlink_camera_information_t_ud:resolution_v() end + + -- set field +---@param value integer +function mavlink_camera_information_t_ud:resolution_v(value) end + +-- get field +---@return integer +function mavlink_camera_information_t_ud:cam_definition_version() end + + -- set field +---@param value integer +function mavlink_camera_information_t_ud:cam_definition_version(value) end + +-- get array field +---@param index integer +---@return integer +function mavlink_camera_information_t_ud:vendor_name(index) end + +-- set array field +---@param index integer +---@param value integer +function mavlink_camera_information_t_ud:vendor_name(index, value) end + +-- get array field +---@param index integer +---@return integer +function mavlink_camera_information_t_ud:model_name(index) end + +-- set array field +---@param index integer +---@param value integer +function mavlink_camera_information_t_ud:model_name(index, value) end + +-- get field +---@return integer +function mavlink_camera_information_t_ud:lens_id() end + + -- set field +---@param value integer +function mavlink_camera_information_t_ud:lens_id(value) end + +-- get array field +---@param index integer +---@return integer +function mavlink_camera_information_t_ud:cam_definition_uri(index) end + +-- set array field +---@param index integer +---@param value integer +function mavlink_camera_information_t_ud:cam_definition_uri(index, value) end + +-- get field +---@return integer +function mavlink_camera_information_t_ud:gimbal_device_id() end + + -- set field +---@param value integer +function mavlink_camera_information_t_ud:gimbal_device_id(value) end + +-- Populate the fields of the CAMERA_INFORMATION message +---@param instance integer +---@param cam_info mavlink_camera_information_t_ud +function camera:set_camera_information(instance, cam_info) end + +-- The MAVLink VIDEO_STREAM_INFORMATION message struct +---@class (exact) mavlink_video_stream_information_t_ud +local mavlink_video_stream_information_t_ud = {} + +---@return mavlink_video_stream_information_t_ud +function mavlink_video_stream_information_t() end + +-- get field +---@return number +function mavlink_video_stream_information_t_ud:framerate() end + +-- set field +---@param value number +function mavlink_video_stream_information_t_ud:framerate(value) end + +-- get field +---@return uint32_t_ud +function mavlink_video_stream_information_t_ud:bitrate() end + +-- set field +---@param value uint32_t_ud|integer|number +function mavlink_video_stream_information_t_ud:bitrate(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:flags() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:flags(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:resolution_h() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:resolution_h(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:resolution_v() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:resolution_v(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:rotation() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:rotation(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:hfov() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:hfov(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:stream_id() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:stream_id(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:count() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:count(value) end + +-- get field +---@return integer +function mavlink_video_stream_information_t_ud:type() end + +-- set field +---@param value integer +function mavlink_video_stream_information_t_ud:type(value) end + +-- get array field +---@param index integer +---@return integer +function mavlink_video_stream_information_t_ud:name(index) end + +-- set array field +---@param index integer +---@param value integer +function mavlink_video_stream_information_t_ud:name(index, value) end + +-- get array field +---@param index integer +---@return integer +function mavlink_video_stream_information_t_ud:uri(index) end + +-- set array field +---@param index integer +---@param value integer +function mavlink_video_stream_information_t_ud:uri(index, value) end + +-- Populate the fields of the VIDEO_STREAM_INFORMATION message +---@param instance integer +---@param stream_info mavlink_video_stream_information_t_ud +function camera:set_stream_information(instance, stream_info) end + -- desc ----@class mount mount = {} -- desc @@ -1359,7 +1761,6 @@ function mount:get_mode(instance) end function mount:get_attitude_euler(instance) end -- desc ----@class motors motors = {} -- Get motors interlock state, the state of motors controlled by AP_Motors, Copter and Quadplane VTOL motors. Not plane forward flight motors. @@ -1430,7 +1831,6 @@ function motors:get_roll_ff() end function motors:get_roll() end -- desc ----@class FWVersion FWVersion = {} -- get field @@ -1467,7 +1867,6 @@ function FWVersion:string() end -- desc ----@class periph periph = {} -- desc @@ -1487,7 +1886,6 @@ function periph:can_printf(text) end function periph:reboot(hold_in_bootloader) end -- desc ----@class ins ins = {} -- desc @@ -1506,7 +1904,7 @@ function ins:gyros_consistent(threshold) end function ins:get_gyro_health(instance) end -- Check if the accelerometers are consistent ----@param threshold float -- the threshold allowed before returning false +---@param threshold number -- the threshold allowed before returning false ---@return boolean function ins:accels_consistent(threshold) end @@ -1530,7 +1928,6 @@ function ins:get_gyro(instance) end function ins:get_accel(instance) end -- desc ----@class Motors_dynamic Motors_dynamic = {} -- desc @@ -1549,16 +1946,22 @@ function Motors_dynamic:init(expected_num_motors) end -- desc ----@class analog analog = {} +-- return MCU temperature in degrees C +---@return number -- MCU temperature +function analog:mcu_temperature() end + +-- return The current MCU voltage +---@return number -- MCU voltage +function analog:mcu_voltage() end + -- desc ----@return AP_HAL__AnalogSource_ud +---@return AP_HAL__AnalogSource_ud|nil function analog:channel() end -- Control of general purpose input/output pins ----@class gpio gpio = {} -- set GPIO pin mode @@ -1584,9 +1987,28 @@ function gpio:write(pin_number, value) end ---@return boolean -- pin state function gpio:read(pin_number) end +-- desc +---@param pin_number integer +---@param mode uint32_t_ud|integer|number +function gpio:set_mode(pin_number, mode) end + +-- desc +---@param pin_number integer +---@return uint32_t_ud|nil -- full pin mode ioline_t in chibios +function gpio:get_mode(pin_number) end + +-- desc +---@param pin_number integer +---@param mode uint32_t_ud|integer|number +function gpio:setPinFullMode(pin_number, mode) end + +-- desc +---@param pin_number integer +---@return uint32_t_ud|nil -- full pin mode ioline_t in chibios +function gpio:getPinFullMode(pin_number) end + -- desc ----@class Motors_6DoF Motors_6DoF = {} -- desc @@ -1608,7 +2030,6 @@ function Motors_6DoF:init(expected_num_motors) end -- desc ----@class attitude_control attitude_control = {} -- desc @@ -1626,7 +2047,6 @@ function attitude_control:set_lateral_enable(bool) end -- desc ----@class frsky_sport frsky_sport = {} -- desc @@ -1646,7 +2066,6 @@ function frsky_sport:sport_telemetry_push(sensor, frame, appid, data) end -- desc ----@class MotorsMatrix MotorsMatrix = {} -- desc @@ -1678,7 +2097,6 @@ function MotorsMatrix:get_thrust_boost() end -- Sub singleton ----@class sub sub = {} -- Return true if joystick button is currently pressed @@ -1696,17 +2114,16 @@ function sub:get_and_clear_button_count(index) end function sub:rangefinder_alt_ok() end -- SURFTRAK mode: return the rangefinder target in cm ----@return float +---@return number function sub:get_rangefinder_target_cm() end -- SURFTRAK mode: set the rangefinder target in cm, return true if successful ----@param new_target_cm float +---@param new_target_cm number ---@return boolean function sub:set_rangefinder_target_cm(new_target_cm) end -- desc ----@class quadplane quadplane = {} -- desc @@ -1727,7 +2144,6 @@ function quadplane:abort_landing() end -- desc ----@class LED LED = {} -- desc @@ -1737,32 +2153,29 @@ LED = {} function LED:get_rgb() end --- desc ----@class button +-- button handling button = {} --- desc ----@param button_number integer +-- Returns button state if available. Buttons are 1 indexed. +---@param button_number integer -- button number 1 indexed. ---@return boolean function button:get_button_state(button_number) end --- desc ----@class RPM +-- RPM handling RPM = {} --- desc ----@param instance integer ----@return number|nil +-- Returns RPM of given instance, or nil if not available +---@param instance integer -- RPM instance +---@return number|nil -- RPM value if available function RPM:get_rpm(instance) end -- desc ----@class mission ----@field MISSION_COMPLETE number ----@field MISSION_RUNNING number ----@field MISSION_STOPPED number mission = {} +mission.MISSION_COMPLETE = enum_integer +mission.MISSION_RUNNING = enum_integer +mission.MISSION_STOPPED = enum_integer -- clear - clears out mission ---@return boolean @@ -1844,34 +2257,33 @@ function mission:get_last_jump_tag() end function mission:jump_to_landing_sequence() end -- Jump to the landing abort sequence --- @return boolean +---@return boolean function mission:jump_to_abort_landing_sequence() end --- desc ----@class param +-- Parameter access param = {} --- desc ----@param name string ----@param value number ----@return boolean +-- set and save parameter value, this will be saved for subsequent boots +---@param name string -- parameter name +---@param value number -- value to set and save +---@return boolean -- true if parameter was found function param:set_and_save(name, value) end --- desc ----@param name string ----@param value number ----@return boolean +-- set parameter value, this will not be retained over a reboot +---@param name string -- parameter name +---@param value number -- value to set +---@return boolean -- true if parameter was found function param:set(name, value) end --- desc ----@param name string ----@return number|nil +-- Get parameter value +---@param name string -- parameter name +---@return number|nil -- nill if parameter was not found function param:get(name) end --- desc ----@param name string ----@param value number ----@return boolean +-- Set default value for a given parameter. If the parameter has not been configured by the user then the set to this default value. +---@param name string -- parameter name +---@param value number -- default value +---@return boolean -- true if parameter was found function param:set_default(name, value) end -- desc @@ -1890,7 +2302,7 @@ function param:add_table(table_key, prefix, num_params) end function param:add_param(table_key, param_num, name, default_value) end -- desc ----@class ESCTelemetryData_ud +---@class (exact) ESCTelemetryData_ud local ESCTelemetryData_ud = {} ---@return ESCTelemetryData_ud @@ -1917,63 +2329,66 @@ function ESCTelemetryData_ud:voltage(value) end function ESCTelemetryData_ud:temperature_cdeg(value) end -- desc ----@class esc_telem esc_telem = {} -- update telemetry data for an ESC instance ----@param instance integer -- 0 is first motor +---@param instance integer -- esc instance 0 indexed ---@param telemdata ESCTelemetryData_ud ---@param data_mask integer -- bit mask of what fields are filled in function esc_telem:update_telem_data(instance, telemdata, data_mask) end --- desc ----@param param1 integer ----@return uint32_t_ud|nil +-- Returns an individual ESC’s usage time in seconds, or nil if not available. +---@param instance integer -- esc instance 0 indexed +---@return uint32_t_ud|nil -- usage time in seconds, nill if not available. function esc_telem:get_usage_seconds(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_consumption_mah(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_voltage(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_current(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return integer|nil function esc_telem:get_motor_temperature(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return integer|nil function esc_telem:get_temperature(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_rpm(instance) end -- update RPM for an ESC ----@param esc_index integer -- ESC number +---@param esc_index integer -- esc instance 0 indexed ---@param rpm integer -- RPM ---@param error_rate number -- error rate function esc_telem:update_rpm(esc_index, rpm, error_rate) end -- set scale factor for RPM on a motor ----@param esc_index integer -- index (0 is first motor) +---@param esc_index integer -- esc instance 0 indexed ---@param scale_factor number -- factor function esc_telem:set_rpm_scale(esc_index, scale_factor) end +-- get the timestamp of last telemetry data for an ESC +---@param esc_index integer +---@return uint32_t_ud +function esc_telem:get_last_telem_data_ms(esc_index) end + -- desc ----@class optical_flow optical_flow = {} -- desc @@ -1990,19 +2405,18 @@ function optical_flow:enabled() end -- desc ----@class baro baro = {} --- desc ----@return number +-- get external temperature in degrees C +---@return number -- temperature in degrees C function baro:get_external_temperature() end --- temperature in degrees C ----@return number +-- get temperature in degrees C +---@return number -- temperature in degrees C function baro:get_temperature() end --- pressure in Pascal. Divide by 100 for millibars or hectopascals ----@return number +-- Returns pressure in Pascal. Divide by 100 for millibars or hectopascals +---@return number -- pressure in Pascal function baro:get_pressure() end -- get current altitude in meters relative to altitude at the time @@ -2015,26 +2429,40 @@ function baro:get_altitude() end ---@return boolean function baro:healthy(instance) end +-- get altitude difference from a base pressure and current pressure +---@param base_pressure number -- first reference pressure in Pa +---@param pressure number -- 2nd pressure in Pa +---@return number -- altitude difference in meters +function baro:get_altitude_difference(base_pressure,pressure) end --- desc ----@class serial +-- Serial ports serial = {} --- 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. +-- Returns a serial access object that allows a script to interface with a +-- device over a port set to protocol 28 (Scripting) (e.g. SERIALx_PROTOCOL). +-- Instance 0 is the first such port, instance 1 the second, and so on. If the +-- requested instance is not found, returns nil. +---@param instance integer -- 0-based index of the Scripting port to access +---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found function serial:find_serial(instance) end +-- Returns a serial access object that allows a script to simulate a device +-- attached via a specific protocol. The device protocol is configured by +-- SCR_SDEVx_PROTO. Instance 0 is the first such protocol, instance 1 the +-- second, and so on. If the requested instance is not found, or SCR_SDEV_EN is +-- disabled, returns nil. +---@param protocol integer -- protocol to access +---@param instance integer -- 0-based index of the protocol instance to access +---@return AP_Scripting_SerialAccess_ud|nil -- access object for that instance, or nil if not found +function serial:find_simulated_device(protocol, instance) end + -- desc ----@class rc rc = {} -- desc ---@param chan_num integer ----@return RC_Channel_ud +---@return RC_Channel_ud|nil function rc:get_channel(chan_num) end -- desc @@ -2057,17 +2485,16 @@ function rc:run_aux_function(aux_fun, ch_flag) end -- desc ---@param aux_fun integer ----@return RC_Channel_ud +---@return RC_Channel_ud|nil function rc:find_channel_for_option(aux_fun) end --- desc ----@param chan_num integer ----@return integer|nil +-- Returns the RC input PWM value given a channel number. Note that channel here is indexed from 1. Returns nill if channel is not available. +---@param chan_num integer -- input channel number, 1 indexed +---@return integer|nil -- pwm input or nil if not availables function rc:get_pwm(chan_num) end -- desc ----@class SRV_Channels SRV_Channels = {} -- Get emergency stop state if active no motors of any kind will be active @@ -2083,95 +2510,93 @@ function SRV_Channels:get_emergency_stop() end function SRV_Channels:get_safety_state() end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param range integer function SRV_Channels:set_range(function_num, range) end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param angle integer function SRV_Channels:set_angle(function_num, angle) end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param value number function SRV_Channels:set_output_norm(function_num, value) end --- desc ----@param function_num integer ----@return number +-- Get the scaled value for a given servo function +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return number -- scaled value function SRV_Channels:get_output_scaled(function_num) end --- desc ----@param function_num integer ----@return integer|nil +-- Returns first servo output PWM value an output assigned output_function (See SERVOx_FUNCTION parameters). Nil if none is assigned. +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return integer|nil -- output pwm if available function SRV_Channels:get_output_pwm(function_num) end --- desc ----@param function_num integer ----@param value number +-- Set the scaled value of the output function, scale is out of the value set with the set_range or set_angle call +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@param value number -- scaled value function SRV_Channels:set_output_scaled(function_num, value) end --- desc ----@param chan integer ----@param pwm integer ----@param timeout_ms integer +-- Sets servo channel to specified PWM for a time in ms. This overrides any commands from the autopilot until the timeout expires. +---@param chan integer -- servo channel number (zero indexed) +---@param pwm integer -- pwm value +---@param timeout_ms integer -- duration of the override function SRV_Channels:set_output_pwm_chan_timeout(chan, pwm, timeout_ms) end --- desc ----@param chan integer ----@param pwm integer +-- Set the pwm for a given servo output channel +---@param chan integer -- servo channel number (zero indexed) +---@param pwm integer -- pwm value function SRV_Channels:set_output_pwm_chan(chan, pwm) end --- desc ----@param function_num integer ----@param pwm integer +-- Set the pwm for a given servo output function +---@param function_num integer -- servo function number (See SERVOx_FUNCTION parameters) +---@param pwm integer -- pwm value function SRV_Channels:set_output_pwm(function_num, pwm) end --- desc ----@param function_num integer ----@return integer|nil +-- Returns first servo output number (zero indexed) of an output assigned output_function (See SERVOx_FUNCTION parameters ). 0 = SERVO1_FUNCTION ect. Nil if none is assigned. +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return integer|nil -- output channel number if available function SRV_Channels:find_channel(function_num) end --- desc ----@class serialLED +-- This library allows the control of RGB LED strings via an output reserved for scripting and selected by SERVOx_FUNCTION = 94 thru 109 (Script Out 1 thru 16) serialLED = {} --- desc ----@param chan integer ----@return boolean +-- Send the configured RGB values to the LED string +---@param chan integer -- output number to which the leds are attached 1-16 +---@return boolean -- true if successful function serialLED:send(chan) end --- desc ----@param chan integer ----@param led_index integer ----@param red integer ----@param green integer ----@param blue integer ----@return boolean +-- Set the data for LED_number on the string attached channel output +---@param chan integer -- output number to which the leds are attached 1-16 +---@param led_index integer -- led number 0 index, -1 sets all +---@param red integer -- red value 0 to 255 +---@param green integer -- green value 0 to 255 +---@param blue integer -- blue value 0 to 255 +---@return boolean -- true if successful function serialLED:set_RGB(chan, led_index, red, green, blue) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a profiled string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_profiled(chan, num_leds) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a neopixel string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_neopixel(chan, num_leds) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a rgb neopixel string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_neopixel_rgb(chan, num_leds) end -- desc ----@class vehicle vehicle = {} -- override landing descent rate, times out in 1s @@ -2235,9 +2660,17 @@ function vehicle:get_circle_radius() end ---@return boolean function vehicle:set_target_angle_and_climbrate(roll_deg, pitch_deg, yaw_deg, climb_rate_ms, use_yaw_rate, yaw_rate_degs) end --- desc ----@param vel_ned Vector3f_ud ----@return boolean +-- Set vehicles roll, pitch, and yaw rates with throttle in guided mode +---@param roll_rate_dps number -- roll rate in degrees per second +---@param pitch_rate_dps number -- pitch rate in degrees per second +---@param yaw_rate_dps number -- yaw rate in degrees per second +---@param throttle number -- throttle demand 0.0 to 1.0 +---@return boolean -- true if successful +function vehicle:set_target_rate_and_throttle(roll_rate_dps, pitch_rate_dps, yaw_rate_dps, throttle) end + +-- Sets the target velocity using a Vector3f object in a guided mode. +---@param vel_ned Vector3f_ud -- North, East, Down meters / second +---@return boolean -- true on success function vehicle:set_target_velocity_NED(vel_ned) end -- desc @@ -2286,18 +2719,18 @@ function vehicle:set_target_pos_NED(target_pos, use_yaw, yaw_deg, use_yaw_rate, ---@return boolean function vehicle:update_target_location(current_target, new_target) end --- desc ----@return Location_ud|nil +-- Get the current target location if available in current mode +---@return Location_ud|nil -- target location function vehicle:get_target_location() end --- desc ----@param target_loc Location_ud ----@return boolean +-- Set the target veicle location in a guided mode +---@param target_loc Location_ud -- target location +---@return boolean -- true on success function vehicle:set_target_location(target_loc) end --- desc ----@param alt number ----@return boolean +-- Trigger a takeoff start if in a auto or guided mode. Not supported by all vehicles +---@param alt number -- takeoff altitude in meters +---@return boolean -- true on success function vehicle:start_takeoff(alt) end -- desc @@ -2313,25 +2746,25 @@ function vehicle:start_takeoff(alt) end ---@return number|nil function vehicle:get_control_output(control_output) end --- desc ----@return uint32_t_ud +-- Returns time in milliseconds since the autopilot thinks it started flying, or zero if not currently flying. +---@return uint32_t_ud -- flying time in milliseconds function vehicle:get_time_flying_ms() end --- desc ----@return boolean +-- Returns true if the autopilot thinks it is flying. Not guaranteed to be accurate. +---@return boolean -- true if likely flying function vehicle:get_likely_flying() end -- desc ---@return integer function vehicle:get_control_mode_reason() end --- desc ----@return integer +-- Returns current vehicle mode by mode_number. +---@return integer -- mode number. Values for each vehcile type can be found here: https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE function vehicle:get_mode() end --- desc ----@param mode_number integer ----@return boolean +-- Attempts to change vehicle mode to mode_number. Returns true if successful, false if mode change is not successful. +---@param mode_number integer -- mode number values for each vehcile type can be found here: https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE +---@return boolean -- success function vehicle:set_mode(mode_number) end -- desc @@ -2367,10 +2800,12 @@ function vehicle:set_target_throttle_rate_rpy(param1, param2, param3, param4) en function vehicle:nav_script_time_done(param1) end -- desc ----@return integer|nil ----@return integer|nil ----@return number|nil ----@return number|nil +---@return integer|nil -- id +---@return integer|nil -- cmd +---@return number|nil -- arg1 +---@return number|nil -- arg2 +---@return integer|nil -- arg3 +---@return integer|nil -- arg4 function vehicle:nav_script_time() end -- desc @@ -2385,8 +2820,32 @@ function vehicle:is_taking_off() end ---@return boolean function vehicle:is_landing() end +-- Set the previous target location for crosstrack and crosstrack if available in the current mode +-- It's up to the Lua code to ensure the new_start_location makes sense +---@param new_start_location Location_ud +---@return boolean -- true on success +function vehicle:set_crosstrack_start(new_start_location) end + +-- Register a custom mode. This behaves like guided mode but will report with a custom number and name +---@param number integer -- mode number to use, should be over 100 +---@param full_name string -- Full mode name +---@param short_name string -- Short mode name upto 4 characters +---@return AP_Vehicle__custom_mode_state_ud|nil -- Returns custom mode state which allows customisation of behavior, nil if mode register fails +function vehicle:register_custom_mode(number, full_name, short_name) end + +-- Custom mode state, allows customisation of mode behavior +---@class (exact) AP_Vehicle__custom_mode_state_ud +local AP_Vehicle__custom_mode_state_ud = {} + +-- get allow_entry, if true the vehicle is allowed to enter this custom mode +---@return boolean +function AP_Vehicle__custom_mode_state_ud:allow_entry() end + +-- set allow_entry, if true the vehicle is allowed to enter this custom mode +---@param value boolean +function AP_Vehicle__custom_mode_state_ud:allow_entry(value) end + -- desc ----@class onvif onvif = {} -- desc @@ -2413,7 +2872,6 @@ function onvif:start(username, password, httphostname) end -- MAVLink interaction with ground control station ----@class gcs gcs = {} -- send named float value using NAMED_VALUE_FLOAT message @@ -2423,7 +2881,7 @@ function gcs:send_named_float(name, value) end -- set message interval for a given serial port and message id ---@param port_num integer -- serial port number ----@param msg_id uint32_t_ud -- MAVLink message id +---@param msg_id uint32_t_ud|integer|number -- MAVLink message id ---@param interval_us integer -- interval in micro seconds ---@return integer ---| '0' # Accepted @@ -2507,94 +2965,101 @@ function gcs:send_text(severity, text) end ---@return uint32_t_ud -- system time in milliseconds function gcs:last_seen() end --- desc ----@class relay +-- call a MAVLink MAV_CMD_xxx command via command_int interface +---@param command integer -- MAV_CMD_xxx +---@param params table -- parameters of p1, p2, p3, p4, x, y and z and frame. Any not specified taken as zero +---@return integer -- MAV_RESULT +function gcs:run_command_int(command, params) end + +-- The relay library provides access to controlling relay outputs. relay = {} --- desc ----@param instance integer +-- Toggles the requested relay from on to off or from off to on. +---@param instance integer -- relay instance function relay:toggle(instance) end --- desc ----@param instance integer +-- Returns true if the requested relay is enabled. +---@param instance integer -- relay instance ---@return boolean function relay:enabled(instance) end -- return state of a relay ----@param instance integer ----@return integer +---@param instance integer -- relay instance +---@return integer -- relay state function relay:get(instance) end --- desc ----@param instance integer +-- Turns the requested relay off. +---@param instance integer -- relay instance function relay:off(instance) end --- desc ----@param instance integer +-- Turns the requested relay on. +---@param instance integer -- relay instance function relay:on(instance) end --- desc ----@class terrain ----@field TerrainStatusOK number ----@field TerrainStatusUnhealthy number ----@field TerrainStatusDisabled number +-- The terrain library provides access to checking heights against a terrain database. terrain = {} +terrain.TerrainStatusOK = enum_integer +terrain.TerrainStatusUnhealthy = enum_integer +terrain.TerrainStatusDisabled = enum_integer --- desc +-- Returns the height (in meters) that the vehicle is currently above the terrain, or returns nil if that is not available. +-- If extrapolate is true then allow return of an extrapolated terrain altitude based on the last available data ---@param extrapolate boolean ----@return number|nil +---@return number|nil -- height above terrain in meters if available function terrain:height_above_terrain(extrapolate) end --- desc +-- find difference between home terrain height and the terrain height at the current location in meters. A positive result means the terrain is higher than home. +-- return false is terrain at the current location or at home location is not available +-- If extrapolate is true then allow return of an extrapolated terrain altitude based on the last available data ---@param extrapolate boolean ----@return number|nil +---@return number|nil -- height difference in meters if available function terrain:height_terrain_difference_home(extrapolate) end --- desc ----@param loc Location_ud ----@param corrected boolean ----@return number|nil +-- Returns the terrain height (in meters) above mean sea level at the provided Location userdata, or returns nil if that is not available. +---@param loc Location_ud -- location at which to lookup terrain +---@param corrected boolean -- if true the terrain altitude should be correced based on the diffrence bettween the database and measured altitude at home +---@return number|nil -- amsl altitude of terrain at given locaiton in meters function terrain:height_amsl(loc, corrected) end --- desc ----@return integer +-- Returns the current status of the terrain. Compare this to one of the terrain statuses (terrain.TerrainStatusDisabled, terrain.TerrainStatusUnhealthy, terrain.TerrainStatusOK). +---@return integer -- terrain status function terrain:status() end --- desc +-- Returns true if terrain is enabled. ---@return boolean function terrain:enabled() end -- RangeFinder state structure ----@class RangeFinder_State_ud +---@class (exact) RangeFinder_State_ud local RangeFinder_State_ud = {} ---@return RangeFinder_State_ud function RangeFinder_State() end -- get system time (ms) of last successful update from sensor ----@return number +---@return uint32_t_ud function RangeFinder_State_ud:last_reading() end -- set system time (ms) of last successful update from sensor ----@param value number +---@param value uint32_t_ud|integer|number function RangeFinder_State_ud:last_reading(value) end -- get sensor status ----@return number +---@return integer function RangeFinder_State_ud:status() end -- set sensor status ----@param value number +---@param value integer function RangeFinder_State_ud:status(value) end -- get number of consecutive valid readings (max out at 10) ----@return number +---@return integer function RangeFinder_State_ud:range_valid_count() end -- set number of consecutive valid readings (max out at 10) ----@param value number +---@param value integer function RangeFinder_State_ud:range_valid_count(value) end -- get distance in meters @@ -2606,24 +3071,24 @@ function RangeFinder_State_ud:distance() end function RangeFinder_State_ud:distance(value) end -- get measurement quality in percent 0-100, -1 -> quality is unknown ----@return number +---@return integer function RangeFinder_State_ud:signal_quality() end -- set measurement quality in percent 0-100, -1 -> quality is unknown ----@param value number +---@param value integer function RangeFinder_State_ud:signal_quality(value) end -- get voltage in millivolts, if applicable, otherwise 0 ----@return number +---@return integer function RangeFinder_State_ud:voltage() end -- set voltage in millivolts, if applicable, otherwise 0 ----@param value number +---@param value integer function RangeFinder_State_ud:voltage(value) end -- RangeFinder backend ----@class AP_RangeFinder_Backend_ud +---@class (exact) AP_RangeFinder_Backend_ud local AP_RangeFinder_Backend_ud = {} -- Send range finder measurement to lua rangefinder backend. Returns false if failed @@ -2657,12 +3122,11 @@ function AP_RangeFinder_Backend_ud:get_state() end -- desc ----@class rangefinder rangefinder = {} -- get backend based on rangefinder instance provided ---@param rangefinder_instance integer ----@return AP_RangeFinder_Backend_ud +---@return AP_RangeFinder_Backend_ud|nil function rangefinder:get_backend(rangefinder_instance) end -- desc @@ -2715,7 +3179,7 @@ function rangefinder:has_orientation(orientation) end function rangefinder:num_sensors() end -- Proximity backend methods ----@class AP_Proximity_Backend_ud +---@class (exact) AP_Proximity_Backend_ud local AP_Proximity_Backend_ud = {} -- Push virtual proximity boundary into actual boundary @@ -2747,12 +3211,11 @@ function AP_Proximity_Backend_ud:handle_script_3d_msg(vector_3d, update_boundary function AP_Proximity_Backend_ud:handle_script_distance_msg(dist_m, yaw_deg, pitch_deg, update_boundary) end -- desc ----@class proximity proximity = {} -- get backend based on proximity instance provided ---@param instance integer ----@return AP_Proximity_Backend_ud +---@return AP_Proximity_Backend_ud|nil function proximity:get_backend(instance) end -- desc @@ -2780,7 +3243,6 @@ function proximity:get_status() end -- desc ----@class notify notify = {} -- desc @@ -2797,7 +3259,8 @@ function notify:handle_rgb_id(red, green, blue, id) end ---@param rate_hz integer function notify:handle_rgb(red, green, blue, rate_hz) end --- desc +-- Plays a MML tune through the buzzer on the vehicle. The tune is provided as a string. +-- An online tune tester can be found here: https://firmware.ardupilot.org/Tools/ToneTester/ ---@param tune string function notify:play_tune(tune) end @@ -2810,116 +3273,130 @@ function notify:send_text(text, row) end ---@param row integer function notify:release_text(row) end --- desc ----@class gps ----@field GPS_OK_FIX_3D_RTK_FIXED number ----@field GPS_OK_FIX_3D_RTK_FLOAT number ----@field GPS_OK_FIX_3D_DGPS number ----@field GPS_OK_FIX_3D number ----@field GPS_OK_FIX_2D number ----@field NO_FIX number ----@field NO_GPS number +-- The GPS library provides access to information about the GPS’s on the vehicle. gps = {} - --- desc +gps.GPS_OK_FIX_3D_RTK_FIXED = enum_integer +gps.GPS_OK_FIX_3D_RTK_FLOAT = enum_integer +gps.GPS_OK_FIX_3D_DGPS = enum_integer +gps.GPS_OK_FIX_3D = enum_integer +gps.GPS_OK_FIX_2D = enum_integer +gps.NO_FIX = enum_integer +gps.NO_GPS = enum_integer + +-- get unix time +---@param instance integer -- instance number +---@return uint64_t_ud -- unix time microseconds +function gps:time_epoch_usec(instance) end + +-- get yaw from GPS in degrees +---@param instance integer -- instance number +---@return number|nil -- yaw in degrees +---@return number|nil -- yaw accuracy in degrees +---@return uint32_t_ud|nil -- time in milliseconds of last yaw reading +function gps:gps_yaw_deg(instance) end + +-- Returns nil or the instance number of the first GPS that has not been fully configured. If all GPS’s have been configured this returns nil. ---@return integer|nil function gps:first_unconfigured_gps() end --- desc ----@param instance integer ----@return Vector3f_ud +-- Returns a Vector3f that contains the offsets of the GPS in meters in the body frame. +---@param instance integer -- instance number +---@return Vector3f_ud -- anteena offset vector forward, right, down in meters function gps:get_antenna_offset(instance) end --- desc ----@param instance integer ----@return boolean +-- Returns true if the GPS instance can report the vertical velocity. +---@param instance integer -- instance number +---@return boolean -- true if vertical velocity is available function gps:have_vertical_velocity(instance) end -- desc ----@param instance integer +---@param instance integer -- instance number ---@return uint32_t_ud function gps:last_message_time_ms(instance) end --- desc ----@param instance integer ----@return uint32_t_ud +-- Returns the time of the last fix in system milliseconds. +---@param instance integer -- instance number +---@return uint32_t_ud -- system time of last fix in milliseconds function gps:last_fix_time_ms(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the vertical dilution of precision of the GPS instance. +---@param instance integer -- instance number +---@return integer -- vdop function gps:get_vdop(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the horizontal dilution of precision of the GPS instance. +---@param instance integer -- instance number +---@return integer -- hdop function gps:get_hdop(instance) end --- desc ----@param instance integer ----@return uint32_t_ud +-- Returns the number of milliseconds into the current week. +---@param instance integer -- instance number +---@return uint32_t_ud -- milliseconds of current week function gps:time_week_ms(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the GPS week number. +---@param instance integer -- instance number +---@return integer -- week number function gps:time_week(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the number of satellites that the GPS is currently tracking. +---@param instance integer -- instance number +---@return integer -- number of satellites function gps:num_sats(instance) end --- desc ----@param instance integer ----@return number +-- Returns the ground course of the vehicle in degrees. You must check the status to know if the ground course is still current. +---@param instance integer -- instance number +---@return number -- ground course in degrees function gps:ground_course(instance) end --- desc ----@param instance integer ----@return number +-- Returns the ground speed of the vehicle in meters per second. You must check the status to know if the ground speed is still current. +---@param instance integer -- instance number +---@return number -- ground speed m/s function gps:ground_speed(instance) end --- desc ----@param instance integer ----@return Vector3f_ud +-- Returns a Vector3f that contains the velocity as observed by the GPS. +-- You must check the status to know if the velocity is still current. +---@param instance integer -- instance number +---@return Vector3f_ud -- 3D velocity in m/s, in NED format function gps:velocity(instance) end -- desc ----@param instance integer +---@param instance integer -- instance number ---@return number|nil function gps:vertical_accuracy(instance) end --- desc ----@param instance integer ----@return number|nil +-- horizontal RMS accuracy estimate in m +---@param instance integer -- instance number +---@return number|nil -- accuracy in meters function gps:horizontal_accuracy(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns nil, or the speed accuracy of the GPS in meters per second, if the information is available for the GPS instance. +---@param instance integer -- instance number +---@return number|nil -- 3D velocity RMS accuracy estimate in m/s if available function gps:speed_accuracy(instance) end --- desc ----@param instance integer ----@return Location_ud +-- eturns a Location userdata for the last GPS position. You must check the status to know if the location is still current, if it is NO_GPS, or NO_FIX then it will be returning old data. +---@param instance integer -- instance number +---@return Location_ud --gps location function gps:location(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the GPS fix status. Compare this to one of the GPS fix types. +-- Posible status are provided as values on the gps object. eg: gps.GPS_OK_FIX_3D +---@param instance integer -- instance number +---@return integer -- status function gps:status(instance) end --- desc ----@return integer +-- Returns which GPS is currently being used as the primary GPS device. +---@return integer -- primary sensor instance function gps:primary_sensor() end --- desc ----@return integer +-- Returns the number of connected GPS devices. +-- If GPS blending is turned on that will show up as the third sensor, and be reported here. +---@return integer -- number of sensors function gps:num_sensors() end -- desc ----@class BattMonitorScript_State_ud +---@class (exact) BattMonitorScript_State_ud local BattMonitorScript_State_ud = {} ---@return BattMonitorScript_State_ud @@ -2966,8 +3443,15 @@ function BattMonitorScript_State_ud:voltage(value) end ---@param value boolean function BattMonitorScript_State_ud:healthy(value) end --- desc ----@class battery +-- The temperature library provides access to information about the currently connected temperature sensors on the vehicle. +temperature_sensor = {} + +-- Returns the temperature from this sensor in degrees Celsius +---@param instance integer -- temperature instance +---@return number|nil -- temperature if available +function temperature_sensor:get_temperature(instance) end + +-- The battery library provides access to information about the currently connected batteries on the vehicle. battery = {} -- desc @@ -2977,72 +3461,77 @@ battery = {} function battery:handle_scripting(idx, state) end -- desc ----@param instance integer +---@param instance integer -- battery instance ---@param percentage number ---@return boolean function battery:reset_remaining(instance, percentage) end --- desc ----@param instance integer ----@return integer|nil +-- Returns cycle count of the battery or nil if not available. +---@param instance integer -- battery instance +---@return integer|nil -- cycle count if available function battery:get_cycle_count(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the temperature of the battery in degrees Celsius if the battery supports temperature monitoring. +---@param instance integer -- battery instance +---@return number|nil -- temperature if available function battery:get_temperature(instance) end --- desc ----@param instance integer ----@return boolean +-- returns true if too much power is being drawn from the battery being monitored. +---@param instance integer -- battery instance +---@return boolean -- true if in overpower condition function battery:overpower_detected(instance) end --- desc ----@return boolean +-- Returns true if any of the batteries being monitored have triggered a failsafe. +---@return boolean -- true if any battery has failsafed function battery:has_failsafed() end --- desc ----@param instance integer ----@return integer +-- Returns the full pack capacity (in milliamp hours) from the battery. +---@param instance integer -- battery instance +---@return integer -- capacity in milliamp hours function battery:pack_capacity_mah(instance) end --- desc ----@param instance integer ----@return integer|nil +-- Returns the remaining percentage of battery (from 0 to 100), or nil if energy monitoring is not available. +---@param instance integer -- battery instance +---@return integer|nil -- remaining capacity as a percentage of total capacity if available function battery:capacity_remaining_pct(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the used watt hours from the battery, or nil if energy monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- consumed energy in watt hours if available function battery:consumed_wh(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the capacity (in milliamp hours) used from the battery, or nil if current monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- consumed capacity in milliamp hours function battery:consumed_mah(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the current (in Amps) that is currently being consumed by the battery, or nil if current monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- current in amps if available function battery:current_amps(instance) end --- desc ----@param instance integer ----@return number +-- Returns the estimated battery voltage if it was not under load. +---@param instance integer -- battery instance +---@return number -- resting voltage function battery:voltage_resting_estimate(instance) end --- desc ----@param instance integer ----@return number +-- Returns the estimated internal battery resistance in Ohms +---@param instance integer -- battery instance +---@return number -- estimated internal resistance in Ohms +function battery:get_resistance(instance) end + +-- Returns the voltage of the selected battery instance. +---@param instance integer -- battery instance +---@return number -- voltage function battery:voltage(instance) end --- desc ----@param instance integer +-- Returns true if the requested battery instance is healthy. Healthy is considered to be ArduPilot is currently able to monitor the battery. +---@param instance integer -- battery instance ---@return boolean function battery:healthy(instance) end --- desc ----@return integer +-- Returns the number of battery instances currently available. +---@return integer -- number of instances function battery:num_instances() end -- get individual cell voltage @@ -3052,8 +3541,7 @@ function battery:num_instances() end function battery:get_cell_voltage(instance, cell) end --- desc ----@class arming +-- The Arming library provides access to arming status and commands. arming = {} -- desc @@ -3069,27 +3557,38 @@ function arming:set_aux_auth_passed(auth_id) end ---@return integer|nil function arming:get_aux_auth_id() end --- desc ----@return boolean +-- Attempts to arm the vehicle. Returns true if successful. +---@return boolean -- true if armed successfully function arming:arm() end --- desc ----@return boolean +-- force arm the vehicle +---@return boolean -- true if armed +function arming:arm_force() end + +-- Returns a true if vehicle is currently armed. +---@return boolean -- true if armed function arming:is_armed() end -- desc ---@return boolean function arming:pre_arm_checks() end --- desc ----@return boolean +-- Disarms the vehicle in all cases. Returns false only if already disarmed. +---@return boolean -- true if disarmed successfully, false if already disarmed. function arming:disarm() end --- desc ----@class ahrs +-- The ahrs library represents the Attitude Heading Reference System computed by the autopilot. +-- It provides estimates for the vehicles attitude, and position. ahrs = {} +-- supply an external position estimate to the AHRS (supported by EKF3) +---@param location Location_ud -- estimated location, altitude is ignored +---@param accuracy number -- 1-sigma accuracy in meters +---@param timestamp_ms uint32_t_ud|integer|number -- timestamp of reading in ms since boot +---@return boolean -- true if call was handled successfully +function ahrs:handle_external_position_estimate(location, accuracy, timestamp_ms) end + -- desc ---@return Quaternion_ud|nil function ahrs:get_quaternion() end @@ -3124,6 +3623,9 @@ function ahrs:get_vel_innovations_and_variances_for_source(source) end -- desc ---@param source_set_idx integer +---| '0' # PRIMARY +---| '1' # SECONDARY +---| '2' # TERTIARY function ahrs:set_posvelyaw_source_set(source_set_idx) end -- desc @@ -3152,16 +3654,16 @@ function ahrs:earth_to_body(vector) end ---@return Vector3f_ud function ahrs:get_vibration() end --- desc ----@return number|nil +-- Return the estimated airspeed of the vehicle if available +---@return number|nil -- airspeed in meters / second if available function ahrs:airspeed_estimate() end -- desc ---@return boolean function ahrs:healthy() end --- desc ----@return boolean +-- Returns a true if home position has been set. +---@return boolean -- true if home position has been set function ahrs:home_is_set() end -- desc @@ -3176,16 +3678,16 @@ function ahrs:get_relative_position_NED_origin() end ---@return Vector3f_ud|nil function ahrs:get_relative_position_NED_home() end --- desc ----@return Vector3f_ud|nil +-- Returns nil, or a Vector3f containing the current NED vehicle velocity in meters/second in north, east, and down components. +---@return Vector3f_ud|nil -- North, east, down velcoity in meters / second if available function ahrs:get_velocity_NED() end --- desc ----@return Vector2f_ud +-- Get current groundspeed vector in meter / second +---@return Vector2f_ud -- ground speed vector, North East, meters / second function ahrs:groundspeed_vector() end --- desc ----@return Vector3f_ud +-- Returns a Vector3f containing the current wind estimate for the vehicle. +---@return Vector3f_ud -- wind estiamte North, East, Down meters / second function ahrs:wind_estimate() end -- Determine how aligned heading_deg is with the wind. Return result @@ -3200,44 +3702,44 @@ function ahrs:wind_alignment(heading_deg) end ---@return number function ahrs:head_wind() end --- desc ----@return number|nil +-- Returns nil, or the latest altitude estimate above ground level in meters +---@return number|nil -- height above ground level in meters function ahrs:get_hagl() end -- desc ---@return Vector3f_ud function ahrs:get_accel() end --- desc ----@return Vector3f_ud +-- Returns a Vector3f containing the current smoothed and filtered gyro rates (in radians/second) +---@return Vector3f_ud -- roll, pitch, yaw gyro rates in radians / second function ahrs:get_gyro() end --- desc ----@return Location_ud +-- Returns a Location that contains the vehicles current home waypoint. +---@return Location_ud -- home location function ahrs:get_home() end --- desc ----@return Location_ud|nil +-- Returns nil or Location userdata that contains the vehicles current position. +-- Note: This will only return a Location if the system considers the current estimate to be reasonable. +---@return Location_ud|nil -- current location if available function ahrs:get_location() end -- same as `get_location` will be removed ---@return Location_ud|nil function ahrs:get_position() end --- desc ----@return number +-- Returns the current vehicle euler yaw angle in radians. +---@return number -- yaw angle in radians. function ahrs:get_yaw() end --- desc ----@return number +-- Returns the current vehicle euler pitch angle in radians. +---@return number -- pitch angle in radians. function ahrs:get_pitch() end --- desc ----@return number +-- Returns the current vehicle euler roll angle in radians. +---@return number -- roll angle in radians function ahrs:get_roll() end -- desc ----@class AC_AttitudeControl AC_AttitudeControl = {} -- return slew rates for VTOL controller @@ -3247,7 +3749,6 @@ AC_AttitudeControl = {} function AC_AttitudeControl:get_rpy_srate() end -- desc ----@class AR_AttitudeControl AR_AttitudeControl = {} -- return attitude controller slew rates for rovers @@ -3255,8 +3756,23 @@ AR_AttitudeControl = {} ---@return number -- spees slew rate function AR_AttitudeControl:get_srate() end +-- copter position controller +poscontrol = {} + +-- add an offset to position controller's target position, velocity and acceleration +---@param pos_offset_NED Vector3f_ud +---@param vel_offset_NED Vector3f_ud +---@param accel_offset_NED Vector3f_ud +---@return boolean +function poscontrol:set_posvelaccel_offset(pos_offset_NED, vel_offset_NED, accel_offset_NED) end + +-- get position controller's target position, velocity and acceleration offsets +---@return Vector3f_ud|nil +---@return Vector3f_ud|nil +---@return Vector3f_ud|nil +function poscontrol:get_posvelaccel_offset() end + -- desc ----@class AR_PosControl AR_PosControl = {} -- return position controller slew rates for rovers @@ -3264,7 +3780,6 @@ AR_PosControl = {} function AR_PosControl:get_srate() end -- precision landing access ----@class precland precland = {} -- get Location of target or nil if target not acquired @@ -3288,7 +3803,6 @@ function precland:target_acquired() end function precland:healthy() end -- desc ----@class follow follow = {} -- desc @@ -3314,7 +3828,6 @@ function follow:get_last_update_ms() end function follow:have_target() end -- desc ----@class scripting scripting = {} -- desc @@ -3322,24 +3835,28 @@ function scripting:restart_all() end -- desc ---@param directoryname string ----@return table -- table of filenames +---@return table|nil -- table of filenames +---@return string|nil -- error string if fails function dirlist(directoryname) end --desc ---@param filename string +---@return boolean|nil -- true on success +---@return nil|string -- error string +---@return integer -- error number function remove(filename) end -- desc ----@class mavlink mavlink = {} -- initializes mavlink ----@param num_rx_msgid uint32_t_ud|integer ----@param msg_queue_length uint32_t_ud|integer +---@param num_rx_msgid uint32_t_ud|integer|number +---@param msg_queue_length uint32_t_ud|integer|number function mavlink:init(num_rx_msgid, msg_queue_length) end -- marks mavlink message for receive, message id can be get using mavlink_msgs.get_msgid("MSG_NAME") ---@param msg_id number +---@return boolean -- false if id has been registered already function mavlink:register_rx_msgid(msg_id) end -- receives mavlink message marked for receive using mavlink:register_rx_msgid @@ -3353,14 +3870,15 @@ function mavlink:receive_chan() end ---@param chan integer ---@param msgid integer ---@param message string +---@return boolean -- success function mavlink:send_chan(chan, msgid, message) end --- Block a given MAV_CMD from being procceced by ArduPilot +-- Block a given MAV_CMD from being processed by ArduPilot ---@param comand_id integer +---@return boolean function mavlink:block_command(comand_id) end -- Geofence library ----@class fence fence = {} -- Returns the time at which the current breach started @@ -3376,7 +3894,7 @@ function fence:get_breach_time() end function fence:get_breaches() end -- desc ----@class stat_t_ud +---@class (exact) stat_t_ud local stat_t_ud = {} ---@return stat_t_ud @@ -3407,21 +3925,20 @@ function stat_t_ud:size() end function stat_t_ud:is_directory() end -- desc ----@class rtc rtc = {} -- return a time since 1970 in seconds from GMT date elements ---@param year integer -- 20xx ---@param month integer -- 0-11 ----@param day integer -- 1-31 ----@param hour integer -- 0-23 +---@param day integer -- 1-31 +---@param hour integer -- 0-23 ---@param min integer -- 0-60 ---@param sec integer -- 0-60 ---@return uint32_t_ud function rtc:date_fields_to_clock_s(year, month, day, hour, min, sec) end -- break a time in seconds since 1970 to GMT date elements ----@param param1 uint32_t_ud +---@param param1 uint32_t_ud|integer|number ---@return integer|nil -- year 20xx ---@return integer|nil -- month 0-11 ---@return integer|nil -- day 1-31 @@ -3432,7 +3949,6 @@ function rtc:date_fields_to_clock_s(year, month, day, hour, min, sec) end function rtc:clock_s_to_date_fields(param1) end -- desc ----@class fs fs = {} -- desc @@ -3445,19 +3961,19 @@ function fs:stat(param1) end function fs:format() end -- Get the current status of a format. 0=NOT_STARTED, 1=PENDING, 2=IN_PROGRESS, 3=SUCCESS, 4=FAILURE ----@return number +---@return integer function fs:get_format_status() end -- Get crc32 checksum of a file with given name +---@param file_name string ---@return uint32_t_ud|nil function fs:crc32(file_name) end -- desc ----@class networking networking = {} -- conver uint32_t address to string ----@param ip4addr uint32_t_ud +---@param ip4addr uint32_t_ud|integer|number ---@return string function networking:address_to_str(ip4addr) end diff --git a/libraries/AP_Scripting/drivers/BattMon_ANX.lua b/libraries/AP_Scripting/drivers/BattMon_ANX.lua index 80b32b924dc8e8..d963850186fad6 100644 --- a/libraries/AP_Scripting/drivers/BattMon_ANX.lua +++ b/libraries/AP_Scripting/drivers/BattMon_ANX.lua @@ -2,6 +2,9 @@ device driver for ANX CAN battery monitor --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: missing-parameter + local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local PARAM_TABLE_KEY = 45 diff --git a/libraries/AP_Scripting/drivers/EFI_HFE.lua b/libraries/AP_Scripting/drivers/EFI_HFE.lua index 08a28724142317..0ed813159b42d4 100644 --- a/libraries/AP_Scripting/drivers/EFI_HFE.lua +++ b/libraries/AP_Scripting/drivers/EFI_HFE.lua @@ -2,6 +2,11 @@ EFI Scripting backend driver for HFE based on HFEDCN0191 Rev E --]] -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: redundant-parameter +---@diagnostic disable: undefined-field +---@diagnostic disable: missing-parameter +---@diagnostic disable: need-check-nil -- Check Script uses a miniumum firmware version diff --git a/libraries/AP_Scripting/drivers/EFI_Halo6000.lua b/libraries/AP_Scripting/drivers/EFI_Halo6000.lua index 4bb457b6f80594..c739449f2620e2 100644 --- a/libraries/AP_Scripting/drivers/EFI_Halo6000.lua +++ b/libraries/AP_Scripting/drivers/EFI_Halo6000.lua @@ -2,6 +2,11 @@ EFI Scripting backend driver for Halo6000 generator --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: undefined-field +---@diagnostic disable: missing-parameter +---@diagnostic disable: need-check-nil + -- Check Script uses a miniumum firmware version local SCRIPT_AP_VERSION = 4.3 local SCRIPT_NAME = "EFI: Halo6000 CAN" @@ -50,7 +55,7 @@ end local efi_backend = nil -- Setup EFI Parameters -assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'could not add EFI_H6K param table') +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add EFI_H6K param table') --[[ // @Param: EFI_H6K_ENABLE @@ -97,6 +102,17 @@ local EFI_H6K_TELEM_RT = bind_add_param('TELEM_RT', 4, 2) --]] local EFI_H6K_FUELTOT = bind_add_param('FUELTOT', 5, 20) +--[[ + // @Param: EFI_H6K_OPTIONS + // @DisplayName: Halo6000 options + // @Description: Halo6000 options + // @Bitmask: 0:LogAllCanPackets + // @User: Standard +--]] +local EFI_H6K_OPTIONS = bind_add_param('OPTIONS', 6, 0) + +local OPTION_LOGALLFRAMES = 0x01 + if EFI_H6K_ENABLE:get() == 0 then return end @@ -116,6 +132,20 @@ if not driver1 then return end +local frame_count = 0 + +--[[ + frame logging - can be replayed with Tools/scripts/CAN/CAN_playback.py +--]] +local function log_can_frame(frame) + logger.write("CANF",'Id,DLC,FC,B0,B1,B2,B3,B4,B5,B6,B7','IBIBBBBBBBB', + frame:id(), + frame:dlc(), + frame_count, + frame:data(0), frame:data(1), frame:data(2), frame:data(3), + frame:data(4), frame:data(5), frame:data(6), frame:data(7)) + frame_count = frame_count + 1 +end --[[ EFI Engine Object @@ -153,6 +183,10 @@ local function engine_control() break end + if EFI_H6K_OPTIONS:get() & OPTION_LOGALLFRAMES ~= 0 then + log_can_frame(frame) + end + -- All Frame IDs for this EFI Engine are in the 11-bit address space if not frame:isExtended() then self.handle_packet(frame) diff --git a/libraries/AP_Scripting/drivers/EFI_Halo6000.md b/libraries/AP_Scripting/drivers/EFI_Halo6000.md index d27d304c1592ae..f31853d5d665e8 100644 --- a/libraries/AP_Scripting/drivers/EFI_Halo6000.md +++ b/libraries/AP_Scripting/drivers/EFI_Halo6000.md @@ -31,6 +31,16 @@ control. This is the rate in Hz at which NAMED_VALUE_FLOAT messages are used to send additional telemetry data to the GCS for display to the operator. +## EFI_H6K_FUELTOT + +This is the total fuel tank capacity in litres + +## EFI_H6K_OPTIONS + +This provides additional options. Currently just one option is +available. If you set EFI_H6K_OPTIONS to 1 then all CAN frames will be +logged in the message CANF. + # Operation This driver should be loaded by placing the lua script in the diff --git a/libraries/AP_Scripting/drivers/EFI_NMEA2k.lua b/libraries/AP_Scripting/drivers/EFI_NMEA2k.lua new file mode 100644 index 00000000000000..42993852eeeb63 --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_NMEA2k.lua @@ -0,0 +1,196 @@ +--[[ + EFI driver using NMEA 2000 marine CAN protocol +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +PARAM_TABLE_KEY = 48 +PARAM_TABLE_PREFIX = "EFI_2K_" + +local efi_backend = nil +local efi_state = EFI_State() +local cylinder_state = Cylinder_Status() +if not efi_state or not cylinder_state then + return +end + +-- bind a parameter to a variable given +function bind_param(name) + local p = Parameter(name) + assert(p, 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 EFI Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add EFI_2K param table') + +--[[ + // @Param: EFI_2K_ENABLE + // @DisplayName: Enable NMEA 2000 EFI driver + // @Description: Enable NMEA 2000 EFI driver + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local EFI_2K_ENABLE = bind_add_param('ENABLE', 1, 1) +if EFI_2K_ENABLE:get() < 1 then + return +end + +--[[ + // @Param: EFI_2K_CANDRV + // @DisplayName: NMEA 2000 CAN driver + // @Description: NMEA 2000 CAN driver. Use 1 for first CAN scripting driver, 2 for 2nd driver + // @Values: 0:Disabled,1:FirstCAN,2:SecondCAN + // @User: Standard +--]] +local EFI_2K_CANDRV = bind_add_param('CANDRV', 2, 0) -- CAN driver number + +--[[ + // @Param: EFI_2K_OPTIONS + // @DisplayName: NMEA 2000 options + // @Description: NMEA 2000 driver options + // @Bitmask: 0:EnableLogging + // @User: Standard +--]] +EFI_2K_OPTIONS = bind_add_param("OPTIONS", 3, 0) + +local OPTION_LOGGING = (1<<0) + +--[[ + return true if an option is enabled +--]] +local function option_enabled(option) + return (EFI_2K_OPTIONS:get() & option) ~= 0 +end + +-- Register for the CAN drivers +local CAN_BUF_LEN = 25 +local can_driver = nil + +if EFI_2K_CANDRV:get() == 1 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("EFI_2K: attaching to CAN1")) + can_driver = CAN:get_device(CAN_BUF_LEN) +elseif EFI_2K_CANDRV:get() == 2 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("EFI_2K: attaching to CAN2")) + can_driver = CAN:get_device2(CAN_BUF_LEN) +end + +if not can_driver then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("EFI_2K: invalid CAN driver")) + return +end + +-- load NMEA_2000 module +local NMEA_2000 = require("NMEA_2000") +if not NMEA_2000 then + gcs:send_text(MAV_SEVERITY.ERROR, "EFI_2K: Unable to load NMEA_2000.lua module") + return +end + +--[[ + create PGN table +--]] +local PGN_ENGINE_PARAM_RAPID = 0x1F200 +local PGN_ENGINE_PARAM_DYNAMIC = 0x1F201 + +local PGN_TABLE = { + [PGN_ENGINE_PARAM_RAPID] = 8, + [PGN_ENGINE_PARAM_DYNAMIC] = 26 +} + +NMEA_2000.set_PGN_table(PGN_TABLE) + +local frame_count = 0 +local state = {} + +local function log_frame(frame) + local id = frame:id() + logger:write("CANF",'Id,DLC,FC,B0,B1,B2,B3,B4,B5,B6,B7','IBIBBBBBBBB', + id, + frame:dlc(), + frame_count, + frame:data(0), frame:data(1), frame:data(2), frame:data(3), + frame:data(4), frame:data(5), frame:data(6), frame:data(7)) + frame_count = frame_count + 1 +end + +--[[ + parse the higher rate engine data, giving RPM and pressure +--]] +local function parse_engine_param_rapid(data) + state.instance, state.speed, state.boost_presssure, state.tilt, _ = string.unpack(" last_state_update_t then -- update state if we have an updated RPM @@ -350,6 +358,8 @@ local function engine_control(_driver) current_load = get_uint16(frame, 2) * 0.1 elseif id == 0x113 then gen.amps = get_uint16(frame, 2) + elseif id == 0x114 then + supply_voltage2 = get_uint16(frame, 4) * 0.01 elseif id == 0x2E0 then starter_rpm = get_uint16(frame, 4) elseif id == 0x10B then @@ -362,7 +372,8 @@ local function engine_control(_driver) last_fuel_s = now_s end else - -- original SkyPower driver + assert(EFI_SP_MODEL:get() == MODEL_SRE_180, string.format('%s Invalid EFI_SP_MODEL', SCRIPT_NAME)) + -- original SkyPower driver, SRE_180 if id == 0x100 then rpm = get_uint16(frame, 0) ignition_angle = get_uint16(frame, 2) * 0.1 @@ -389,6 +400,8 @@ local function engine_control(_driver) temps.imt = get_uint16(frame, 2) * 0.1 temps.egt = get_uint16(frame, 4) * 0.1 temps.oilt = get_uint16(frame, 6) * 0.1 + elseif id == 0x178 then + supply_voltage2 = get_uint16(frame, 4) * 0.01 end end end @@ -582,6 +595,7 @@ local function engine_control(_driver) gcs:send_named_float('EFI_OILTMP', temps.oilt) gcs:send_named_float('EFI_TRLOAD', target_load) gcs:send_named_float('EFI_VOLTS', supply_voltage) + gcs:send_named_float('EFI_VOLTS2', supply_voltage2) gcs:send_named_float('EFI_GEN_AMPS', gen.amps) gcs:send_named_float('EFI_CHT2', temps.cht2) gcs:send_named_float('EFI_STARTRPM', starter_rpm) diff --git a/libraries/AP_Scripting/drivers/Generator_SVFFI.lua b/libraries/AP_Scripting/drivers/Generator_SVFFI.lua index a5267b4a099c6f..eae7678a253c41 100644 --- a/libraries/AP_Scripting/drivers/Generator_SVFFI.lua +++ b/libraries/AP_Scripting/drivers/Generator_SVFFI.lua @@ -3,6 +3,9 @@ See http://www.svffi.com/en/ --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: missing-parameter + local PARAM_TABLE_KEY = 42 local PARAM_TABLE_PREFIX = "EFI_SVF_" diff --git a/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua index d1be31dfad657a..76a490146a9eb5 100644 --- a/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua +++ b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua @@ -2,6 +2,8 @@ driver for HobbyWing DataLink ESC telemetry --]] +---@diagnostic disable: param-type-mismatch + local PARAM_TABLE_KEY = 44 local PARAM_TABLE_PREFIX = "ESC_HW_" diff --git a/libraries/AP_Scripting/drivers/INF_Inject.lua b/libraries/AP_Scripting/drivers/INF_Inject.lua index 8685ba52a343e9..d967439a9f4bff 100644 --- a/libraries/AP_Scripting/drivers/INF_Inject.lua +++ b/libraries/AP_Scripting/drivers/INF_Inject.lua @@ -9,6 +9,15 @@ local PARAM_TABLE_PREFIX = "EFI_INF_" local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +local CMD_CDI1 = 1 +local CMD_CDI2 = 2 +local CMD_OIL_PUMP = 3 +-- local CMD_SHUTDOWN = 4 +-- local CMD_PRE_INJECTION = 5 +local CMD_THROTTLE = 6 + +local K_THROTTLE = 70 + -- bind a parameter to a variable given local function bind_param(name) local p = Parameter() @@ -34,11 +43,48 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 8), 'could not add p --]] EFI_INF_ENABLE = bind_add_param("ENABLE", 1, 1) +--[[ + // @Param: EFI_INF_OPTIONS + // @DisplayName: EFI INF-Inject options + // @Description: EFI INF driver options + // @Bitmask: 0:EnableLogging + // @User: Standard +--]] +EFI_INF_OPTIONS = bind_add_param("OPTIONS", 2, 0) + +--[[ + // @Param: EFI_INF_THR_HZ + // @DisplayName: EFI INF-Inject throttle rate + // @Description: EFI INF throttle output rate + // @Range: 0 50 + // @Units: Hz + // @User: Standard +--]] +EFI_INF_THR_HZ = bind_add_param("THR_HZ", 3, 0) + +--[[ + // @Param: EFI_INF_IGN_AUX + // @DisplayName: EFI INF-Inject ignition aux function + // @Description: EFI INF throttle ignition aux function + // @User: Standard +--]] +EFI_INF_IGN_AUX = bind_add_param("IGN_AUX", 4, 300) + +local OPTION_LOGGING = (1<<0) + +--[[ + return true if an option is enabled +--]] +local function option_enabled(option) + return (EFI_INF_OPTIONS:get() & option) ~= 0 +end + if EFI_INF_ENABLE:get() ~= 1 then return end local EFI_FUEL_DENS = bind_param("EFI_FUEL_DENS") +local SCR_VM_I_COUNT = bind_param("SCR_VM_I_COUNT") local uart = serial:find_serial(0) -- first scripting serial if not uart then @@ -53,12 +99,43 @@ if not efi_backend then return end +--[[ + we need a bit more time in this driver +--]] +if SCR_VM_I_COUNT:get() < 50000 then + gcs:send_text(MAV_SEVERITY.INFO, "EFI_INF: raising SCR_VM_I_COUNT to 50000") + SCR_VM_I_COUNT:set_and_save(50000) +end + local state = {} state.last_read_us = uint32_t(0) state.chk0 = 0 state.chk1 = 0 state.total_fuel_g = 0.0 +local last_throttle_send_ms = uint32_t(0) +local last_ignition_send_ms = uint32_t(0) +local last_ign_sw_pos = -1 + +local file_handle = nil +local efi_device_id = nil + +--[[ + log a set of bytes +--]] +local function log_bytes(s) + if not file_handle then + file_handle = io.open("INF_Inject.log", "w") + end + if file_handle then + local magic = 0x7fe53b04 + local now_ms = millis():toint() + local hdr = string.pack("= packet_size and not header_ok do + state.chk0 = 0 + state.chk1 = 0 local header0 = string.unpack("= 1 then + command = 1 + end + if sw_pos ~= last_ign_sw_pos then + onoff = "OFF" + if command == 1 then + onoff = "ON" + end + gcs:send_text(MAV_SEVERITY.INFO, string.format("EFI_INF: ignition %s", onoff)) + end + last_ign_sw_pos = sw_pos + send_packet(CMD_CDI1, command) + send_packet(CMD_CDI2, command) + send_packet(CMD_OIL_PUMP, command) +end + --[[ main update function @@ -232,7 +401,10 @@ local function update() if check_input() then update_EFI() end - + if efi_device_id then + update_throttle() + update_ignition() + end return update, 10 end diff --git a/libraries/AP_Scripting/drivers/INF_Inject.md b/libraries/AP_Scripting/drivers/INF_Inject.md index 34adfb3b2ddee7..50cbe85fcd905d 100644 --- a/libraries/AP_Scripting/drivers/INF_Inject.md +++ b/libraries/AP_Scripting/drivers/INF_Inject.md @@ -13,6 +13,12 @@ The script used the following parameters: this must be set to 1 to enable the driver +## EFI_INF_OPTIONS + +This sets options for the driver. Currently the only option is to set +EFI_INF_OPTIONS to 1 to enable logging of the raw serial bytes to a +file called INF_Inject.log + # Operation This driver should be loaded by placing the lua script in the @@ -20,6 +26,7 @@ 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 + - SCR_VM_I_COUNT should be set to at least 50000 - EFI_TYPE should be set to 7 - EFI_INF_ENABLE should be set to 1 - SERIALn_PROTOCOL should be set to 28 for the connected EFI serial diff --git a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.lua b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.lua index f5b3dc7ba10007..8f53c081cc6f6f 100644 --- a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.lua +++ b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.lua @@ -2,6 +2,9 @@ Driver for NoopLoop TOFSense-M CAN Version. Can be used as a 1-D RangeFidner or 3-D proximity sensor. Upto 3 CAN devices supported in this script although its easy to extend. --]] +---@diagnostic disable: undefined-field +---@diagnostic disable: undefined-global + local update_rate_ms = 10 -- update rate (in ms) of the driver. 10ms was found to be appropriate -- Global variables (DO NOT CHANGE) diff --git a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua index d6c495422cc23c..bc487de7343749 100644 --- a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua +++ b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua @@ -2,6 +2,10 @@ Upto 3 CAN devices supported in this script although its easy to extend. --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type +---@diagnostic disable: undefined-global + local sensor_no = 1 -- Sensor ID. Upload a copy of this script to the flight controller with this variable changed if you would like to use multiple of these sensors as serial. Switching to CAN highly recommended in that case local update_rate_ms = 10 -- update rate (in ms) of the driver. 10ms was found to be appropriate local bytes_to_parse = 100 -- serial bytes to parse in one interation of lua script. Reduce this if script is not able to complete in time diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 61113d05d7d545..eaf28b7c6b95c6 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -1,5 +1,4 @@ -- mount-djirs2-driver.lua: DJIRS2 mount/gimbal driver --- luacheck: only 0 --[[ How to use @@ -12,6 +11,12 @@ Reboot the autopilot Copy this script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot set DJIR_DEBUG to 1 to display parsing and errors stats at 5sec. Set to 2 to display gimbal angles + + Advanced usage + The gimbal can be connected to an existing DroneCAN bus (on ArduPilot 4.6 or later) by setting CAN_Dx_PROTOCOL2=10 on that bus's driver + The gimbal can be used as the Nth mount (instead of the first) by setting MNTn_TYPE = 9 and modifying the script's user definitions + The gimbal can be used with the Scripting2 protocol by modifying the script's user definitions + Multiple gimbals can be used at once by duplicating the script and connecting them to different buses The following sources were used as a reference during the development of this script Constant Robotics DJIR SDK: https://github.com/ConstantRobotics/DJIR_SDK @@ -71,13 +76,16 @@ --]] +-- user definitions +local MOUNT_INSTANCE = 0 -- default to MNT1 +local CAN_INSTANCE = 0 -- default to first scripting CAN protocol + -- global definitions local INIT_INTERVAL_MS = 3000 -- attempt to initialise the gimbal at this interval local UPDATE_INTERVAL_MS = 1 -- update interval in millis local REPLY_TIMEOUT_MS = 100 -- timeout waiting for reply after 0.1 sec local REQUEST_ATTITUDE_INTERVAL_MS = 100-- request attitude at 10hz local SET_ATTITUDE_INTERVAL_MS = 100 -- set attitude at 10hz -local MOUNT_INSTANCE = 0 -- always control the first mount/gimbal local SEND_FRAMEID = 0x223 -- send CAN messages with this frame id local RECEIVE_FRAMEID = 0x222 -- receive CAN messages with this frame id local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} @@ -106,15 +114,6 @@ local DJIR_DEBUG = Parameter("DJIR_DEBUG") -- debug level. 0:disabl --]] local DJIR_UPSIDEDOWN = Parameter("DJIR_UPSIDEDOWN") -- 0:rightsideup, 1:upsidedown --- bind parameters to variables -local CAN_P1_DRIVER = Parameter("CAN_P1_DRIVER") -- If using CAN1, should be 1:First driver -local CAN_P1_BITRATE = Parameter("CAN_P1_BITRATE") -- If using CAN1, should be 1000000 -local CAN_D1_PROTOCOL = Parameter("CAN_D1_PROTOCOL") -- If using CAN1, should be 10:Scripting -local CAN_P2_DRIVER = Parameter("CAN_P2_DRIVER") -- If using CAN2, should be 2:Second driver -local CAN_P2_BITRATE = Parameter("CAN_P2_BITRATE") -- If using CAN2, should be 1000000 -local CAN_D2_PROTOCOL = Parameter("CAN_D2_PROTOCOL") -- If using CAN2, should be 10:Scripting -local MNT1_TYPE = Parameter("MNT1_TYPE") -- should be 9:Scripting - -- message definitions local HEADER = 0xAA local RETURN_CODE = {SUCCESS=0x00, PARSE_ERROR=0x01, EXECUTION_FAILED=0x02, UNDEFINED=0xFF} @@ -140,18 +139,17 @@ local parse_length = 0 -- incoming message's packet length local parse_buff = {} -- message buffer holding roll, pitch and yaw angles from gimbal local parse_bytes_recv = 0 -- message buffer length. count of the number of bytes received in the message so far local last_send_seq = 0 -- last sequence number sent -local last_req_attitude_ms = 0 -- system time of last request for attitude -local last_set_attitude_ms = 0 -- system time of last set attitude call +local last_req_attitude_ms = uint32_t(0) -- system time of last request for attitude +local last_set_attitude_ms = uint32_t(0) -- system time of last set attitude call local REPLY_TYPE = {NONE=0, ATTITUDE=1, POSITION_CONTROL=2, SPEED_CONTROL=3} -- enum of expected reply types local expected_reply = REPLY_TYPE.NONE -- currently expected reply type -local expected_reply_ms = 0 -- system time that reply is first expected. used for timeouts +local expected_reply_ms = uint32_t(0) -- system time that reply is first expected. used for timeouts -- parsing status reporting variables -local last_print_ms = 0 -- system time that debug output was last printed +local last_print_ms = uint32_t(0) -- system time that debug output was last printed local bytes_read = 0 -- number of bytes read from gimbal local bytes_written = 0 -- number of bytes written to gimbal local bytes_error = 0 -- number of bytes read that could not be parsed -local msg_ignored = 0 -- number of ignored messages (because frame id does not match) local write_fails = 0 -- number of times write failed local execute_fails = 0 -- number of times that gimbal was unable to execute the command local reply_timeouts = 0 -- number of timeouts waiting for replies @@ -310,43 +308,21 @@ end -- perform any require initialisation function init() - -- check parameter settings - if CAN_D1_PROTOCOL:get() ~= 10 and CAN_D2_PROTOCOL:get() ~= 10 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_D1_PROTOCOL or CAN_D2_PROTOCOL=10") - do return end - end - if CAN_D1_PROTOCOL:get() == 10 and CAN_D2_PROTOCOL:get() == 10 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_D1_PROTOCOL or CAN_D2_PROTOCOL=0") - do return end - end - if CAN_D1_PROTOCOL:get() == 10 then - if CAN_P1_DRIVER:get() <= 0 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_P1_DRIVER=1") - do return end - end - if CAN_P1_BITRATE:get() ~= 1000000 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_P1_BITRATE=1000000") - do return end - end - end - if CAN_D2_PROTOCOL:get() == 10 then - if CAN_P2_DRIVER:get() <= 0 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_P2_DRIVER=2") - do return end - end - if CAN_P2_BITRATE:get() ~= 1000000 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set CAN_P2_BITRATE=1000000") - do return end - end - end - if MNT1_TYPE:get() ~= 9 then - gcs:send_text(MAV_SEVERITY.CRITICAL, "DJIR: set MNT1_TYPE=9") + local mnt_type_name = ("MNT%d_TYPE"):format(MOUNT_INSTANCE+1) + local mnt_type = param:get(mnt_type_name) + if mnt_type ~= 9 then + gcs:send_text(MAV_SEVERITY.CRITICAL, ("DJIR: set %s=9"):format(mnt_type_name)) do return end end - -- get CAN device - driver = CAN:get_device(25) - if driver then + -- get CAN device and filter to receive only replies from the gimbal + local buffer_size = 8 -- buffer up to two replies + if CAN_INSTANCE == 0 then + driver = CAN:get_device(buffer_size) + elseif CAN_INSTANCE == 1 then + driver = CAN:get_device2(buffer_size) + end + if driver and driver:add_filter(-1, RECEIVE_FRAMEID) then initialised = true gcs:send_text(MAV_SEVERITY.INFO, "DJIR: mount driver started") else @@ -516,7 +492,6 @@ function send_target_rates(roll_rate_degs, pitch_rate_degs, yaw_rate_degs) roll_rate_degs = roll_rate_degs or 0 pitch_rate_degs = pitch_rate_degs or 0 yaw_rate_degs = yaw_rate_degs or 0 - time_sec = time_sec or 2 -- ensure rates are integers. invert roll direction roll_rate_degs = -math.floor(roll_rate_degs + 0.5) @@ -561,18 +536,13 @@ end -- consume incoming CAN packets function read_incoming_packets() local canframe - repeat + while true do canframe = driver:read_frame() - if canframe then - if uint32_t(canframe:id()) == uint32_t(RECEIVE_FRAMEID) then - for i = 0, canframe:dlc()-1 do - parse_byte(canframe:data(i)) - end - else - msg_ignored = msg_ignored + 1 - end + if not canframe then return end + for i = 0, canframe:dlc()-1 do + parse_byte(canframe:data(i)) end - until not canframe + end end -- parse an byte from the gimbal @@ -743,12 +713,7 @@ function update() -- report parsing status if (DJIR_DEBUG:get() > 0) and ((now_ms - last_print_ms) > 5000) then last_print_ms = now_ms - gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: r:%u w:%u fail:%u,%u perr:%u to:%u ign:%u", bytes_read, bytes_written, write_fails, execute_fails, bytes_error, reply_timeouts, msg_ignored)) - end - - -- do not send any messages until CAN traffic has been seen - if msg_ignored == 0 and bytes_read == 0 then - return update, UPDATE_INTERVAL_MS + gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: r:%u w:%u fail:%u,%u perr:%u to:%u", bytes_read, bytes_written, write_fails, execute_fails, bytes_error, reply_timeouts)) end -- handle expected reply timeouts @@ -787,8 +752,8 @@ function update() return update, UPDATE_INTERVAL_MS end - -- send rate target - local roll_degs, pitch_degs, yaw_degs, yaw_is_ef = mount:get_rate_target(MOUNT_INSTANCE) + -- send rate target (ignoring earth-frame flag as the gimbal doesn't use it) + local roll_degs, pitch_degs, yaw_degs, _ = mount:get_rate_target(MOUNT_INSTANCE) if roll_degs and pitch_degs and yaw_degs then send_target_rates(roll_degs, pitch_degs, yaw_degs) return update, UPDATE_INTERVAL_MS diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.md b/libraries/AP_Scripting/drivers/mount-djirs2-driver.md index 7f4d6e058c36b9..fc45b3773bcf2d 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.md +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.md @@ -13,6 +13,12 @@ DJI RS2 and RS3-Pro gimbal mount driver lua script - Reboot the autopilot - Copy the mount-djirs2-driver.lua script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot +## Advanced usage +- The gimbal can be connected to an existing DroneCAN bus (on ArduPilot 4.6 or later) by setting CAN_Dx_PROTOCOL2=10 on that bus's driver +- The gimbal can be used as the Nth mount (instead of the first) by setting MNTn_TYPE = 9 and modifying the script's user definitions +- The gimbal can be used with the Scripting2 protocol by modifying the script's user definitions +- Multiple gimbals can be used at once by duplicating the script and connecting them to different buses + ## Issues If the ground station reports "Pre-arm: Mount not healthy", update the diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua index 9786e6327bba34..3f04dff228e86a 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua @@ -31,6 +31,9 @@ n+2 checksum XOR of byte3 to n+1 (inclusive) --]] +---@diagnostic disable: cast-local-type +---@diagnostic disable: undefined-global + -- parameters local PARAM_TABLE_KEY = 39 assert(param:add_table(PARAM_TABLE_KEY, "VIEP_", 6), "could not add param table") diff --git a/libraries/AP_Scripting/examples/AHRS_switch.lua b/libraries/AP_Scripting/examples/AHRS_switch.lua index e24478cf24b9eb..72d85703a0608f 100644 --- a/libraries/AP_Scripting/examples/AHRS_switch.lua +++ b/libraries/AP_Scripting/examples/AHRS_switch.lua @@ -1,16 +1,21 @@ --- switch between DCM and EKF3 on a switch +-- switch between EKF2 and EKF3 on a switch -local scripting_rc1 = rc:find_channel_for_option(300) +local AUX_FUNCTION_NUM = 300 local EKF_TYPE = Parameter('AHRS_EKF_TYPE') function update() - local sw_pos = scripting_rc1:get_aux_switch_pos() - if sw_pos == 0 then + local sw_pos = rc:get_aux_cached(AUX_FUNCTION_NUM) + if not sw_pos then + return update, 100 + end + if sw_pos == 2 then EKF_TYPE:set(3) else - EKF_TYPE:set(0) + EKF_TYPE:set(2) end return update, 100 end +gcs:send_text(0, "Loaded AHRS switch for EKF3/EKF2") + return update() diff --git a/libraries/AP_Scripting/examples/BQ40Z_bms_shutdown.lua b/libraries/AP_Scripting/examples/BQ40Z_bms_shutdown.lua new file mode 100644 index 00000000000000..27dee597cc91b5 --- /dev/null +++ b/libraries/AP_Scripting/examples/BQ40Z_bms_shutdown.lua @@ -0,0 +1,108 @@ +-- TI BQ40Z BMS shutdown script + +local mavlink_msgs = require("MAVLink/mavlink_msgs") + +local COMMAND_ACK_ID = mavlink_msgs.get_msgid("COMMAND_ACK") +local COMMAND_LONG_ID = mavlink_msgs.get_msgid("COMMAND_LONG") +local msg_map = {} +msg_map[COMMAND_ACK_ID] = "COMMAND_ACK" +msg_map[COMMAND_LONG_ID] = "COMMAND_LONG" + +local PARAM_TABLE_KEY = 51 +local PARAM_TABLE_PREFIX = "BATT_BQ40Z_" +-- add a parameter and bind it to a variable +local 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') +--[[ + // @Param: BATT_BQ40Z_BUS + // @DisplayName: Bus number for the BQ40Z + // @Description: Bus number for the BQ40Z + // @Range: 0 3 + // @User: Standard +--]] +local BATT_BQ40Z_BUS = bind_add_param('BUS', 1, 0) + + +local MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 +local MAV_RESULT_ACCEPTED = 0 +local MAV_RESULT_FAILED = 4 + +-- Initialize MAVLink rx with number of messages, and buffer depth +mavlink:init(1, 10) +-- Register message id to receive +mavlink:register_rx_msgid(COMMAND_LONG_ID) +-- Block MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN so we can handle the ACK +mavlink:block_command(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) + +-- Init BMS i2c device +local i2c_addr = BATT_BQ40Z_BUS:get() +assert(i2c_addr ~= nil, "BATT_BQ40Z_BUS not retrievable") +local bms = i2c:get_device(math.floor(i2c_addr), 0x0B) + +-- Exit emergency shutdown (for BQ40Z60, twice for redundancy) +bms:transfer("\x00\xA7\x23", 0) +bms:transfer("\x00\xA7\x23", 0) + +-- Function that is returned to the AP scheduler when we want to shutdown +local function shutdown_loop() + local ret = bms:transfer("\x00\x10\x00", 0) + if ret == nil then + gcs:send_text(0, "BQ40Z shutdown transfer failed") + end + + return shutdown_loop, 500 +end + +-- Main loop +local function update() + local msg, chan = mavlink:receive_chan() + local parsed_msg = nil + + if (msg ~= nil) then + parsed_msg = mavlink_msgs.decode(msg, msg_map) + end + + if parsed_msg ~= nil and (parsed_msg.msgid == COMMAND_LONG_ID) and (parsed_msg.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) then + -- Prepare ack + local ack = {} + ack.command = parsed_msg.command + ack.result = MAV_RESULT_ACCEPTED + ack.progress = 0 + ack.result_param2 = 0 + ack.target_system = parsed_msg.sysid + ack.target_component = parsed_msg.compid + + -- Don't shutdown if armed + if arming:is_armed() and parsed_msg.param1 == 2 then + gcs:send_text(1, "Not sutting down BQ40Z as vehicle is armed") + ack.result = MAV_RESULT_FAILED + mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack)) + + -- Shutdown + elseif parsed_msg.param1 == 2 then + gcs:send_text(1, "Shutting down BQ40Z!!!") + mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack)) + return shutdown_loop, 0 + + -- Pass through the command if it isn't requesting shutdown + else + local command_int = { + p1 = parsed_msg.param1, + p2 = parsed_msg.param2, + p3 = parsed_msg.param3, + p4 = parsed_msg.param4, + } + local result = gcs:run_command_int(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, command_int) + ack.result = result + mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack)) + end + end + + return update, 1000 +end + + +return update, 1000 diff --git a/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua b/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua index a06f15b76294c7..46a66434018129 100644 --- a/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua +++ b/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua @@ -1,6 +1,9 @@ -- Control MiniCheetah motor driver over CAN -- https://os.mbed.com/users/benkatz/code/HKC_MiniCheetah/docs/tip/CAN__com_8cpp_source.html +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil + -- Load CAN driver with a buffer size of 20 local driver = CAN:get_device(20) diff --git a/libraries/AP_Scripting/examples/CAN_logger.lua b/libraries/AP_Scripting/examples/CAN_logger.lua index aa3c5ff990a643..d23ccf8076bad9 100644 --- a/libraries/AP_Scripting/examples/CAN_logger.lua +++ b/libraries/AP_Scripting/examples/CAN_logger.lua @@ -4,6 +4,8 @@ Also need LOG_DISARMED set to 1 if running this while disarmed. --]] +---@diagnostic disable: param-type-mismatch + local can_driver = CAN:get_device(25) if not can_driver then diff --git a/libraries/AP_Scripting/examples/CAN_read.lua b/libraries/AP_Scripting/examples/CAN_read.lua index 789f9e32002f4d..bafaf37dae8782 100644 --- a/libraries/AP_Scripting/examples/CAN_read.lua +++ b/libraries/AP_Scripting/examples/CAN_read.lua @@ -1,4 +1,5 @@ -- This script is an example of reading from the CAN bus +---@diagnostic disable: need-check-nil -- 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 diff --git a/libraries/AP_Scripting/examples/CAN_write.lua b/libraries/AP_Scripting/examples/CAN_write.lua index 30763917519589..5fb551fb6bea20 100644 --- a/libraries/AP_Scripting/examples/CAN_write.lua +++ b/libraries/AP_Scripting/examples/CAN_write.lua @@ -1,4 +1,5 @@ -- This script is an example of writing to CAN bus +---@diagnostic disable: need-check-nil -- Load CAN driver, using the scripting protocol and with a buffer size of 5 local driver = CAN:get_device(5) diff --git a/libraries/AP_Scripting/examples/EFI_tester.lua b/libraries/AP_Scripting/examples/EFI_tester.lua index 0bb2719d85e336..4015e079ec37a0 100644 --- a/libraries/AP_Scripting/examples/EFI_tester.lua +++ b/libraries/AP_Scripting/examples/EFI_tester.lua @@ -3,6 +3,10 @@ this can be used with a loopback cable between CAN1 and CAN2 to test CAN EFI Drivers --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: missing-parameter + + local driver2 = CAN.get_device2(25) if not driver2 then gcs:send_text(0,string.format("EFISIM: Failed to load CAN driver")) diff --git a/libraries/AP_Scripting/examples/ESC_slew_rate.lua b/libraries/AP_Scripting/examples/ESC_slew_rate.lua new file mode 100644 index 00000000000000..b85991a01721a5 --- /dev/null +++ b/libraries/AP_Scripting/examples/ESC_slew_rate.lua @@ -0,0 +1,54 @@ +--[[ + run an ESC with a sinisoidal demand, with settable limits and frequency +--]] + +local PARAM_TABLE_KEY = 136 +local PARAM_TABLE_PREFIX = "ETEST_" + +-- 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 + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add param table') + +local ETEST_CHAN = bind_add_param('CHAN', 1, 0) +local ETEST_PCT = bind_add_param('PCT', 2, 100) +local ETEST_PWM_MIN = bind_add_param('PWM_MIN', 3, 1000) +local ETEST_PWM_MAX = bind_add_param('PWM_MAX', 4, 2000) +local ETEST_FREQ = bind_add_param('FREQ', 5, 1) +local ETEST_WTYPE = bind_add_param('WTYPE', 6, 0) + +-- local WTYPE_SIN = 0 +local WTYPE_SQUARE = 1 + +function update() + local chan = ETEST_CHAN:get() + local freq = ETEST_FREQ:get() + if chan > 0 and freq > 0 then + local t = 0.001 * millis():tofloat() + local pi = 3.1415 + local out_sin = math.sin(pi * t * freq * 2.0) + if ETEST_WTYPE:get() == WTYPE_SQUARE then + if out_sin > 0 then + out_sin = 1 + else + out_sin = -1 + end + end + local output = out_sin * ETEST_PCT:get() * 0.01 + local pwm_min = ETEST_PWM_MIN:get() + local pwm_max = ETEST_PWM_MAX:get() + local pwm_mid = 0.5*(pwm_min+pwm_max) + local pwm = math.floor(pwm_mid + (pwm_max-pwm_mid) * output) + SRV_Channels:set_output_pwm_chan_timeout(chan-1, pwm, 100) + logger:write('ESLW', 'PWM,Freq', 'If', pwm, freq) + gcs:send_named_float('PWN',pwm) + gcs:send_named_float('FREQ',freq) + end + return update, 5 -- 200Hz +end + +return update() diff --git a/libraries/AP_Scripting/examples/FlexDebug.lua b/libraries/AP_Scripting/examples/FlexDebug.lua new file mode 100644 index 00000000000000..5b15906ae1d1d2 --- /dev/null +++ b/libraries/AP_Scripting/examples/FlexDebug.lua @@ -0,0 +1,50 @@ +--[[ + ArduPilot lua script to log debug messages from AM32 DroneCAN + ESCs on the flight controller + + To install set SCR_ENABLE=1 and put this script in APM/SCRIPTS/ on + the microSD of the flight controller then restart the flight + controller +--]] + +-- assume ESCs are nodes 30, 31, 32 and 33 +local ESC_BASE = 30 + +local AM32_DEBUG = 100 + +local last_tstamp = {} +local ts_zero = uint32_t(0) +local reported_version_error = false + +function log_AM32() + for i = 0, 3 do + local last_ts = last_tstamp[i] or ts_zero + tstamp_us, msg = DroneCAN_get_FlexDebug(0, ESC_BASE+i, AM32_DEBUG, last_ts) + if tstamp_us and msg then + version, commutation_interval, num_commands, num_input, rx_errors, rxframe_error, rx_ecode, auto_advance_level = string.unpack(" 0.1 then + pitch_dir = 1.0 + elseif pilot_pitch:norm_input_dz() < -0.1 then + pitch_dir = -1.0 + elseif pilot_roll:norm_input_dz() >= 0 then + roll_dir = 1.0 + else + roll_dir = -1.0 + end + + -- Record start attitude to be used in recovery stage + start_attitude.roll = math.deg(ahrs:get_roll()) + start_attitude.pitch = math.deg(ahrs:get_pitch()) + start_attitude.yaw = math.deg(ahrs:get_yaw()) + +end + +local FLIP_THR_INC = 0.2 +local FLIP_THR_DEC = 0.24 +local FLIP_ROTATION_RATE = 400 + +local function run() + local NOW = millis() + + -- Disarmed, pilot input or timeout then return to previous mode + local PILOT_INPUT = (math.abs(pilot_roll:norm_input_dz()) > 0.85) or (math.abs(pilot_pitch:norm_input_dz()) > 0.85) + if (not arming:is_armed()) or PILOT_INPUT or ((NOW - start_ms) > 2500) then + vehicle:set_mode(previous_mode) + return + end + + local roll_deg = math.deg(ahrs:get_roll()) + local pitch_deg = math.deg(ahrs:get_pitch()) + + if state == FLIP_STATE.RECOVER then + -- Target original attitude with 0 climb rate + vehicle:set_target_angle_and_climbrate(start_attitude.roll, start_attitude.pitch, start_attitude.yaw, 0.0, false, 0.0) + + -- See if we have returned to the desired angle + local recovery_angle = math.abs((roll_deg - start_attitude.roll) * roll_dir) + math.abs((pitch_deg - start_attitude.pitch) * pitch_dir) + + if recovery_angle < 5.0 then + -- Complete, return to original mode + vehicle:set_mode(previous_mode) + end + return + end + + local throttle_out = get_pilot_desired_throttle() + + local flip_angle = roll_deg * roll_dir + pitch_deg * pitch_dir + + if state == FLIP_STATE.START then + -- Increase throttle + throttle_out = math.min(throttle_out + FLIP_THR_INC, 1.0) + + -- Check for next stage + if flip_angle >= 45.0 then + if roll_dir ~= 0 then + -- Rolling flip + state = FLIP_STATE.ROLL + else + -- Pitching flip + state = FLIP_STATE.PITCH_A + end + end + + elseif state == FLIP_STATE.ROLL then + -- decrease throttle + throttle_out = math.max(throttle_out - FLIP_THR_DEC, 0.0) + + -- beyond 90deg move on to recovery + if (flip_angle < 45.0) and (flip_angle > -90.0) then + state = FLIP_STATE.RECOVER + end + + elseif state == FLIP_STATE.PITCH_A then + -- decrease throttle + throttle_out = math.max(throttle_out - FLIP_THR_DEC, 0.0) + + -- check roll for inversion + if (math.abs(roll_deg) > 90.0) and (flip_angle > 45.0) then + state = FLIP_STATE.PITCH_B + end + + elseif state == FLIP_STATE.PITCH_B then + -- decrease throttle + throttle_out = math.max(throttle_out - FLIP_THR_DEC, 0.0) + + -- check roll for un-inversion + if (math.abs(roll_deg) < 90.0) and (flip_angle > -45.0) then + state = FLIP_STATE.RECOVER + end + + end + + -- Send rate and throttle command to vehicle + local roll_rate = FLIP_ROTATION_RATE * roll_dir + local pitch_rate = FLIP_ROTATION_RATE * pitch_dir + + vehicle:set_target_rate_and_throttle(roll_rate, pitch_rate, 0.0, throttle_out) + +end + +local function exit() + -- Nothing to do here +end + +local function update() + + -- Only allow entry into flip mode if armed and flying + local armed = arming:is_armed() + local flying = vehicle:get_likely_flying() + FLIP_MODE_STATE:allow_entry(armed and flying) + + local mode = vehicle:get_mode() + if mode == MODE_NUMBER then + if last_mode_number ~= MODE_NUMBER then + -- Fist call after entering + init() + else + -- Runtime function + run() + end + + elseif last_mode_number == MODE_NUMBER then + -- Exit mode + exit() + end + last_mode_number = mode + + -- Run at 100Hz + return update, 10 +end + +return update() diff --git a/libraries/AP_Scripting/examples/MAVLinkHL.lua b/libraries/AP_Scripting/examples/MAVLinkHL.lua index 3ee4f4f5e0f789..21cc968a63ec6a 100644 --- a/libraries/AP_Scripting/examples/MAVLinkHL.lua +++ b/libraries/AP_Scripting/examples/MAVLinkHL.lua @@ -17,9 +17,14 @@ Caveats: Written by Stephen Dade (stephen_dade@hotmail.com) --]] + +---@diagnostic disable: need-check-nil +---@diagnostic disable: cast-local-type + + local port = serial:find_serial(0) -if not port or baud == 0 then +if not port then gcs:send_text(0, "No Scripting Serial Port") return end diff --git a/libraries/AP_Scripting/examples/Motor_mixer_dynamic_setup.lua b/libraries/AP_Scripting/examples/Motor_mixer_dynamic_setup.lua index e0eb0fd64d302f..62cc85f54f2a4a 100644 --- a/libraries/AP_Scripting/examples/Motor_mixer_dynamic_setup.lua +++ b/libraries/AP_Scripting/examples/Motor_mixer_dynamic_setup.lua @@ -45,5 +45,5 @@ Motors_dynamic:load_factors(factors) motors:set_frame_string("Dynamic example") --- if doing changes in flight it is a good idea to us pcall to protect the script from crashing +-- if doing changes in flight it is a good idea to use pcall to protect the script from crashing -- see 'protected_call.lua' example diff --git a/libraries/AP_Scripting/examples/RC_override.lua b/libraries/AP_Scripting/examples/RC_override.lua index 52b19f2945c06e..460c6e9ab66b9b 100644 --- a/libraries/AP_Scripting/examples/RC_override.lua +++ b/libraries/AP_Scripting/examples/RC_override.lua @@ -1,5 +1,8 @@ -- example of overriding RC inputs +---@diagnostic disable: need-check-nil +---@diagnostic disable: param-type-mismatch + local RC4 = rc:get_channel(4) function update() diff --git a/libraries/AP_Scripting/examples/RM3100_self_test.lua b/libraries/AP_Scripting/examples/RM3100_self_test.lua new file mode 100644 index 00000000000000..7f16a1d0f936cc --- /dev/null +++ b/libraries/AP_Scripting/examples/RM3100_self_test.lua @@ -0,0 +1,107 @@ +-- Runs the Built-In Self Test on the RM3100 LR circuits +-- Note COMPASS_DISBLMSK should have the 16th bit set to 1 (RM3100) + +-- Init RM3100 on bus 0 +local rm3100 = i2c:get_device(0, 0x20) +assert(rm3100 ~= nil, "i2c get_device error, cannot run RM3100 self test") + +-- Queues a Built-In Self Test +function queue_test() + gcs:send_text(1, "Running RM3100 self test") + + -- Queue a self test by setting BIST register + local ret = rm3100:transfer("\x33\x8F", 0) + if ret == nil then + gcs:send_text(1, "Rm3100 BIST transfer failed") + return queue_test, 1000 + end + + -- Send a POLL request to run a BIST + ret = rm3100:transfer("\x00\x70", 0) + if ret == nil then + gcs:send_text(1, "Rm3100 POLL transfer failed") + return queue_test, 1000 + end + + -- As a measurement takes time, delay a bit by scheduling a different function + return read_test, 1000 +end + + +-- Reads back values from a Built-In Self Test +function read_test() + -- Read the BIST results + local results_str = rm3100:transfer("\x33", 1) + if results_str ~= nil then + local results = results_str:byte() + + if results & (1 << 4) == 0 then + gcs:send_text(1, "RM3100 X is unhealthy") + else + gcs:send_text(1, "RM3100 X is OK") + end + + if results & (1 << 5) == 0 then + gcs:send_text(1, "RM3100 Y is unhealthy") + else + gcs:send_text(1, "RM3100 Y is OK") + end + + if results & (1 << 6) == 0 then + gcs:send_text(1, "RM3100 Z is unhealthy") + else + gcs:send_text(1, "RM3100 Z is OK") + end + else + gcs:send_text(1, "Rm3100 BIST read transfer failed") + return queue_test, 1000 + end + + -- Reset the BIST register + local ret = rm3100:transfer("\x33\x0F", 0) + if ret == nil then + gcs:send_text(1, "Rm3100 BIST reset transfer failed") + return queue_test, 1000 + end + + -- Send a POLL request to take a data point + ret = rm3100:transfer("\x00\x70", 0) + if ret == nil then + gcs:send_text(1, "Rm3100 POLL data transfer failed") + return queue_test, 1000 + end + + -- As a measurement takes time, delay a bit by scheduling a different function + return read_data, 1000 +end + +-- Reads data from the RM3100 +function read_data() + -- Check that data is ready for a read + local status_str = rm3100:transfer("\x34", 1) + if status_str ~= nil then + local status = status_str:byte() + if status & (1 << 7) == 0 then + gcs:send_text(1, "RM3100 data not ready for reading") + return queue_test, 1000 + end + else + gcs:send_text(1, "Rm3100 BIST status reg transfer failed") + return queue_test, 1000 + end + + -- Read measured values + local measurements_str = rm3100:transfer("\x24", 9) + if measurements_str ~= nil then + local MX, MY, MZ = string.unpack(">i3>i3>i3", measurements_str) + gcs:send_text(6, string.format("RM3100 Mag: X=%8d Y=%8d Z=%8d", MX, MY, MZ)) + else + gcs:send_text(1, "Rm3100 data read transfer failed") + return queue_test, 1000 + end + + -- Loop back to the first function to run another set of tests + return queue_test, 1000 +end + +return queue_test, 1000 diff --git a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua index 163ae6ca8aa85e..524eb685cc04d6 100644 --- a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua +++ b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua @@ -8,6 +8,9 @@ https://github.com/sparkfun/SparkFun_Particle_Sensor_SN-GCJA5_Arduino_Library ]]-- +---@diagnostic disable: need-check-nil +---@diagnostic disable: undefined-global + -- search for a index without a file, this stops us overwriting from a previous run local index = 0 local file_name diff --git a/libraries/AP_Scripting/examples/Serial_Dump.lua b/libraries/AP_Scripting/examples/Serial_Dump.lua index bfff5392e8c35a..aae1eef966a7b7 100644 --- a/libraries/AP_Scripting/examples/Serial_Dump.lua +++ b/libraries/AP_Scripting/examples/Serial_Dump.lua @@ -1,5 +1,9 @@ -- this script reads data from a serial port and dumps it to a file +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil +---@diagnostic disable: cast-local-type + local file_name = 'raw serial dump.txt' local file_name_plain = 'serial dump.txt' local baud_rate = 9600 diff --git a/libraries/AP_Scripting/examples/UART_log.lua b/libraries/AP_Scripting/examples/UART_log.lua index 927b6054c6ae1c..37a26ed286e6d6 100644 --- a/libraries/AP_Scripting/examples/UART_log.lua +++ b/libraries/AP_Scripting/examples/UART_log.lua @@ -3,7 +3,7 @@ -- find the serial first (0) scripting serial port instance local port = serial:find_serial(0) -if not port or baud == 0 then +if not port then gcs:send_text(0, "No Scripting Serial Port") return end diff --git a/libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua b/libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua index 090c8288f7bc6e..f4fcee1e69e3a4 100644 --- a/libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua +++ b/libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua @@ -1,6 +1,8 @@ -- example script for using "set_home()" -- sets the home location to the current vehicle location every 5 seconds +---@diagnostic disable: param-type-mismatch + function update () if ahrs:home_is_set() then diff --git a/libraries/AP_Scripting/examples/ahrs-source-gps-optflow.lua b/libraries/AP_Scripting/examples/ahrs-source-gps-optflow.lua index 5ce72deced6c6d..4db7fcd3f64625 100644 --- a/libraries/AP_Scripting/examples/ahrs-source-gps-optflow.lua +++ b/libraries/AP_Scripting/examples/ahrs-source-gps-optflow.lua @@ -2,9 +2,9 @@ -- this script is intended to help vehicles automatically switch between GPS and optical flow -- -- configure a forward or downward facing lidar with a range of at least 5m --- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=GPS, middle=opticalflow, high=Not Used) +-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=GPS, middle=opticalflow, high=Not Used) -- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected --- SRC_ENABLE = 1 (enable scripting) +-- SCR_ENABLE = 1 (enable scripting) -- setup EK3_SRCn_ parameters so that GPS is the primary source, opticalflow is secondary. -- EK3_SRC1_POSXY = 3 (GPS) -- EK3_SRC1_VELXY = 3 (GPS) @@ -27,6 +27,8 @@ -- -- When the 2nd auxiliary switch (300/Scripting1) is pulled high automatic source selection uses these thresholds: -- luacheck: only 0 +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil local rangefinder_rotation = 25 -- check downward (25) facing lidar local source_prev = 0 -- previous source, defaults to primary source diff --git a/libraries/AP_Scripting/examples/ahrs-source-gps-wheelencoders.lua b/libraries/AP_Scripting/examples/ahrs-source-gps-wheelencoders.lua index 75d54583f2129e..4b1f1080c998bb 100644 --- a/libraries/AP_Scripting/examples/ahrs-source-gps-wheelencoders.lua +++ b/libraries/AP_Scripting/examples/ahrs-source-gps-wheelencoders.lua @@ -1,6 +1,6 @@ -- This script helps vehicles move between GPS and Non-GPS environments using GPS and Wheel Encoders -- --- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=primary, middle=secondary, high=tertiary) +-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=primary, middle=secondary, high=tertiary) -- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected -- setup EK3_SRCn_ parameters so that GPS is the primary source, WheelEncoders are the secondary -- @@ -10,6 +10,8 @@ -- if GPS speed accuracy <= SCR_USER2 and GPS innovations <= SRC_USER3 then the GPS (primary source set) will be used -- otherwise wheel encoders (secondary source set) will be used -- luacheck: only 0 +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil local source_prev = 0 -- previous source, defaults to primary source local sw_source_prev = -1 -- previous source switch position diff --git a/libraries/AP_Scripting/examples/ahrs-source.lua b/libraries/AP_Scripting/examples/ahrs-source.lua index 186bee0832bf81..4e269b6442cded 100644 --- a/libraries/AP_Scripting/examples/ahrs-source.lua +++ b/libraries/AP_Scripting/examples/ahrs-source.lua @@ -1,7 +1,7 @@ -- switches between AHRS/EKF sources based on the pilot's source selection switch or using an automatic source selection algorithm -- this script is intended to help vehicles move between GPS and Non-GPS environments -- --- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=primary, middle=secondary, high=tertiary) +-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=primary, middle=secondary, high=tertiary) -- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected -- setup EK3_SRCn_ parameters so that GPS is the primary source, Non-GPS (i.e. T265) is secondary and optical flow tertiary -- configure a forward or downward facing lidar with a range of more than 5m @@ -16,6 +16,9 @@ -- otherwise source2 (T265) or source3 (optical flow) will be used based on rangefinder distance -- luacheck: only 0 +---@diagnostic disable: need-check-nil +---@diagnostic disable: cast-local-type + local rangefinder_rotation = 25 -- check downward (25) facing lidar local source_prev = 0 -- previous source, defaults to primary source local sw_source_prev = -1 -- previous source switch position diff --git a/libraries/AP_Scripting/examples/analog_input_and_GPIO.lua b/libraries/AP_Scripting/examples/analog_input_and_GPIO.lua index 5d0048b547c7ca..0cb20b6be79fa6 100644 --- a/libraries/AP_Scripting/examples/analog_input_and_GPIO.lua +++ b/libraries/AP_Scripting/examples/analog_input_and_GPIO.lua @@ -2,6 +2,8 @@ -- for these examples BRD_PWM_COUNT must be 0 +---@diagnostic disable: need-check-nil + -- load the analog pin, there are only 16 of these available -- some are used by the main AP code, ie battery monitors -- assign them like this in the init, not in the main loop diff --git a/libraries/AP_Scripting/examples/arming-check-wp1-takeoff.lua b/libraries/AP_Scripting/examples/arming-check-wp1-takeoff.lua index e4f7360766c189..60f3fa44666080 100644 --- a/libraries/AP_Scripting/examples/arming-check-wp1-takeoff.lua +++ b/libraries/AP_Scripting/examples/arming-check-wp1-takeoff.lua @@ -1,4 +1,4 @@ --- This script runs a custom arming check for index == 1 and it must be a takeoff missionn item +-- This script runs a custom arming check for index == 1 and it must be a takeoff mission item local auth_id = arming:get_aux_auth_id() diff --git a/libraries/AP_Scripting/examples/battery_internal_resistance_check.lua b/libraries/AP_Scripting/examples/battery_internal_resistance_check.lua new file mode 100644 index 00000000000000..63a811e2e2a573 --- /dev/null +++ b/libraries/AP_Scripting/examples/battery_internal_resistance_check.lua @@ -0,0 +1,35 @@ +--[[ + script implementing pre-arm check that internal resistance is sensible +--]] + +local MAX_RESISTANCE = 0.03 -- Ohms + +local auth_id = assert(arming:get_aux_auth_id()) + +local warning_last_sent_ms = uint32_t() -- time we last sent a warning message to the user +warning_interval_ms = 10000 + +function update() + local num_batts = battery:num_instances() + local ok = true + for i=0,num_batts do + local resistance = battery:get_resistance(i) + failed = resistance > MAX_RESISTANCE + if failed then + msg = string.format("Batt[%u] high internal resistance %.5f Ohms", i+1, resistance) + if millis() - warning_last_sent_ms > warning_interval_ms then + gcs:send_text(0, msg) + warning_last_sent_ms = millis() + end + arming:set_aux_auth_failed(auth_id, msg) + ok = false + end + end + + if ok then + arming:set_aux_auth_passed(auth_id) + end + return update, 500 +end + +return update() diff --git a/libraries/AP_Scripting/examples/benewakeH30_can_rangefinder.lua b/libraries/AP_Scripting/examples/benewakeH30_can_rangefinder.lua index ca1539ccceeea4..f3fe89fa9bb9ce 100644 --- a/libraries/AP_Scripting/examples/benewakeH30_can_rangefinder.lua +++ b/libraries/AP_Scripting/examples/benewakeH30_can_rangefinder.lua @@ -1,5 +1,8 @@ -- Lua Can Driver for Benewake CAN Rangefinder +---@diagnostic disable: undefined-global +---@diagnostic disable: need-check-nil + -- User settable parameters local update_rate_ms = 10 -- update rate (in ms) of the driver local debug_enable = false -- true to enable debug messages diff --git a/libraries/AP_Scripting/examples/camera-test.lua b/libraries/AP_Scripting/examples/camera-test.lua index 9dec743e6a472c..c55343be5281e2 100644 --- a/libraries/AP_Scripting/examples/camera-test.lua +++ b/libraries/AP_Scripting/examples/camera-test.lua @@ -1,5 +1,7 @@ -- camera-test.lua. Tests triggering taking pictures at regular intervals +---@diagnostic disable: cast-local-type + -- global definitions local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local TAKE_PIC_INTERVAL_MS = 5000 -- take pictures at this interval diff --git a/libraries/AP_Scripting/examples/cell_balance_check.lua b/libraries/AP_Scripting/examples/cell_balance_check.lua index a7274a4d14d21d..64bec40178f1aa 100644 --- a/libraries/AP_Scripting/examples/cell_balance_check.lua +++ b/libraries/AP_Scripting/examples/cell_balance_check.lua @@ -2,6 +2,8 @@ script implementing pre-arm check that batteries are well balanced --]] +---@diagnostic disable: param-type-mismatch + local MAX_CELL_DEVIATION = 0.2 local auth_id = arming:get_aux_auth_id() diff --git a/libraries/AP_Scripting/examples/command_int.lua b/libraries/AP_Scripting/examples/command_int.lua new file mode 100644 index 00000000000000..b86792c4569ed1 --- /dev/null +++ b/libraries/AP_Scripting/examples/command_int.lua @@ -0,0 +1,56 @@ +--[[ + demonstrate using the gcs:command_int() interface to send commands from MAVLink MAV_CMD_xxx set +--]] + +local MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 + +local MAV_CMD_DO_SET_MODE = 176 +local MAV_CMD_DO_REPOSITION = 192 + +-- some plane flight modes for testing +local MODE_LOITER = 12 +local MODE_GUIDED = 15 + +local MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 + +--[[ +create a NaN value +--]] +local function NaN() + return 0/0 +end + +--[[ + test API calls. When in LOITER mode change to GUIDED and force flying to a location NE of home +--]] +local function test_command_int() + if vehicle:get_mode() ~= MODE_LOITER then + return + end + local home = ahrs:get_home() + if not home then + return + end + + -- force mode GUIDED + gcs:run_command_int(MAV_CMD_DO_SET_MODE, { p1 = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, p2 = MODE_GUIDED }) + + -- and fly to 200m NE of home and 100m above home + local dest = home:copy() + dest:offset_bearing(45, 200) + + gcs:run_command_int(MAV_CMD_DO_REPOSITION, { frame = MAV_FRAME_GLOBAL_RELATIVE_ALT, + p1 = -1, + p4 = NaN(), + x = dest:lat(), + y = dest:lng(), + z = 100 }) +end + +local function update() + test_command_int() + return update, 1000 +end + +return update, 1000 + diff --git a/libraries/AP_Scripting/examples/copter-fast-descent.lua b/libraries/AP_Scripting/examples/copter-fast-descent.lua index 0b4ab0bfa12836..77bd9eba47fd22 100644 --- a/libraries/AP_Scripting/examples/copter-fast-descent.lua +++ b/libraries/AP_Scripting/examples/copter-fast-descent.lua @@ -6,6 +6,10 @@ -- b) slows the spiral and stops at the preset altitude -- c) switches to RTL +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil + -- constants local copter_guided_mode_num = 4 -- Guided mode is 4 on copter local copter_rtl_mode_num = 6 -- RTL is 6 on copter diff --git a/libraries/AP_Scripting/examples/copter-nav-script-time.lua b/libraries/AP_Scripting/examples/copter-nav-script-time.lua index ebb8c4621355b8..5c6c93c54db259 100644 --- a/libraries/AP_Scripting/examples/copter-nav-script-time.lua +++ b/libraries/AP_Scripting/examples/copter-nav-script-time.lua @@ -12,6 +12,9 @@ -- "arg2" specifies the height (e.g. North-South) in meters -- Once the vehicle completes the square or the timeout expires the mission will continue and the vehicle should RTL home +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: need-check-nil + local running = false local last_id = -1 -- unique id used to detect if a new NAV_SCRIPT_TIME command has started local start_loc -- vehicle's location when command starts (South-West corner of square) diff --git a/libraries/AP_Scripting/examples/copter-posoffset.lua b/libraries/AP_Scripting/examples/copter-posoffset.lua new file mode 100644 index 00000000000000..b0fd3774c92a66 --- /dev/null +++ b/libraries/AP_Scripting/examples/copter-posoffset.lua @@ -0,0 +1,160 @@ +-- Example showing how a position offset can be added to a Copter's auto mission plan +-- +-- CAUTION: This script only works for Copter +-- this script waits for the vehicle to be armed and in auto mode and then +-- adds an offset to the position or velocity target +-- +-- How To Use +-- 1. copy this script to the autopilot's "scripts" directory +-- 2. set PSC_OFS_xx parameter to the desired position OR velocity offsets desired +-- 3. fly the vehicle in Auto mode (or almost any mode) +-- 4. use the Scripting1 aux switch to enable and disable the offsets + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- setup script specific parameters +local PARAM_TABLE_KEY = 71 +local PARAM_TABLE_PREFIX = "PSC_OFS_" +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'could not add param table') + +-- 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', PARAM_TABLE_PREFIX .. name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +--[[ + // @Param: PSC_OFS_POS_N + // @DisplayName: Position Controller Position Offset North + // @Description: Position controller offset North + // @Range: 0 1000 + // @Units: m + // @User: Standard +--]] +local PSC_OFS_POS_N = bind_add_param("POS_N", 1, 0) + +--[[ + // @Param: PSC_OFS_POS_E + // @DisplayName: Position Controller Position Offset East + // @Description: Position controller offset North + // @Range: 0 1000 + // @Units: m + // @User: Standard +--]] +local PSC_OFS_POS_E = bind_add_param("POS_E", 2, 0) + +--[[ + // @Param: PSC_OFS_POS_D + // @DisplayName: Position Controller Position Offset Down + // @Description: Position controller offset Down + // @Range: 0 1000 + // @Units: m + // @User: Standard +--]] +local PSC_OFS_POS_D = bind_add_param("POS_D", 3, 0) + +--[[ + // @Param: PSC_OFS_VEL_N + // @DisplayName: Position Controller Velocity Offset North + // @Description: Position controller velocity offset North + // @Range: 0 10 + // @Units: m/s + // @User: Standard +--]] +local PSC_OFS_VEL_N = bind_add_param("VEL_N", 4, 0) + +--[[ + // @Param: PSC_OFS_VEL_E + // @DisplayName: Position Controller Velocity Offset East + // @Description: Position controller velocity offset East + // @Range: 0 10 + // @Units: m/s + // @User: Standard +--]] +local PSC_OFS_VEL_E = bind_add_param("VEL_E", 5, 0) + +--[[ + // @Param: PSC_OFS_VEL_D + // @DisplayName: Position Controller Velocity Offset Down + // @Description: Position controller velocity offset Down + // @Range: 0 10 + // @Units: m/s + // @User: Standard +--]] +local PSC_OFS_VEL_D = bind_add_param("VEL_D", 6, 0) + +-- local variables +local aux_sw_pos_last = 0 + +-- welcome message to user +gcs:send_text(MAV_SEVERITY.INFO, "copter-posoffset.lua loaded") + +function update() + + -- must be armed, flying and in auto mode + if (not arming:is_armed()) or (not vehicle:get_likely_flying()) then + return update, 1000 + end + + -- Scripting1 aux switch enables/disables offsets + local aux_sw_pos = rc:get_aux_cached(300) + if aux_sw_pos == nil then + aux_sw_pos = 0 + end + + -- check for change in aux switch position + if aux_sw_pos ~= aux_sw_pos_last then + aux_sw_pos_last = aux_sw_pos + if aux_sw_pos == 0 then + -- if switch is in low position clear offsets + if poscontrol:set_posvelaccel_offset(Vector3f(), Vector3f(), Vector3f()) then + gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: offsets cleared") + return update, 1000 + else + gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to clear offsets") + end + else + gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: offsets activated") + end + end + + if aux_sw_pos == 0 then + return update, 1000 + end + + local pos_offsets_zero = PSC_OFS_POS_N:get() == 0 and PSC_OFS_POS_E:get() == 0 and PSC_OFS_POS_D:get() == 0 + local vel_offsets_zero = PSC_OFS_VEL_N:get() == 0 and PSC_OFS_VEL_E:get() == 0 and PSC_OFS_VEL_D:get() == 0 + + -- if position offsets are non-zero or all offsets are zero then send position offsets + if not pos_offsets_zero or vel_offsets_zero then + -- set the position offset in meters in NED frame + local pos_offset_NED = Vector3f() + pos_offset_NED:x(PSC_OFS_POS_N:get()) + pos_offset_NED:y(PSC_OFS_POS_E:get()) + pos_offset_NED:z(PSC_OFS_POS_D:get()) + if not poscontrol:set_posvelaccel_offset(pos_offset_NED, Vector3f(), Vector3f()) then + gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to set pos offset") + end + test_position = not pos_offsets_zero + else + -- first get position offset (cumulative effect of velocity offsets) + local pos_offset_NED, _, _ = poscontrol:get_posvelaccel_offset() + if pos_offset_NED == nil then + print_warning("unable to get position offset") + pos_offset_NED = Vector3f() + end + -- test velocity offsets in m/s in NED frame + local vel_offset_NED = Vector3f() + vel_offset_NED:x(PSC_OFS_VEL_N:get()) + vel_offset_NED:y(PSC_OFS_VEL_E:get()) + vel_offset_NED:z(PSC_OFS_VEL_D:get()) + if not poscontrol:set_posvelaccel_offset(pos_offset_NED, vel_offset_NED, Vector3f()) then + gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to set vel offset") + end + end + + -- update at 1hz + return update, 1000 +end + +return update() diff --git a/libraries/AP_Scripting/examples/copter_alt_offset.lua b/libraries/AP_Scripting/examples/copter_alt_offset.lua index d0daf2369754fb..0b90581d149846 100644 --- a/libraries/AP_Scripting/examples/copter_alt_offset.lua +++ b/libraries/AP_Scripting/examples/copter_alt_offset.lua @@ -1,7 +1,7 @@ --[[ add ALT_OFFSET parameter for copter - This behaves similarly to ALT_OFFSET in plane. It operators only in AUTO mode, and slews the BARO_ALT_OFFSET to allow - for change of altitude without mission change + This behaves similarly to ALT_OFFSET in plane. It operates only in AUTO mode, and slews the BARO_ALT_OFFSET to allow + for change of altitude without mission change. --]] diff --git a/libraries/AP_Scripting/examples/copter_deploy.lua b/libraries/AP_Scripting/examples/copter_deploy.lua new file mode 100644 index 00000000000000..19efeec6196517 --- /dev/null +++ b/libraries/AP_Scripting/examples/copter_deploy.lua @@ -0,0 +1,84 @@ +--[[ + script to auto-deploy a vehicle on descent after reaching a specified altitude + uses raw pressure to not depend on either GPS or on home alt +--]] +local PARAM_TABLE_KEY = 72 +local PARAM_TABLE_PREFIX = "DEPL_" +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +---@diagnostic disable: missing-parameter +---@diagnostic disable: param-type-mismatch + +-- 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 + +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add param table') + +local end_pos = bind_add_param('OPEN_POS', 1, 1200) +local offset = bind_add_param('OPEN_OFFSET', 2, 400) +local deployment_alt = bind_add_param('ALT', 3, 1) +local DEPL_CLIMB_ALT = bind_add_param('CLIMB_ALT', 4, 2) +local base_pressure = nil +local SERVO_FUNCTION = 94 +local reached_climb_alt = false +local deployed = false + +local MODE_LAND = 9 + +function update_state() + local pressure = baro:get_pressure() + if not pressure then + return + end + if not base_pressure then + base_pressure = pressure + end + local altitude = baro:get_altitude_difference(base_pressure, pressure) + if not altitude then + return + end + gcs:send_named_float('DALT',altitude) + logger.write("DEPL",'BP,P,Alt','fff', + base_pressure, pressure, altitude) + if not reached_climb_alt then + local start_pos = end_pos:get() + offset:get() + SRV_Channels:set_output_pwm(SERVO_FUNCTION, start_pos) + if altitude > DEPL_CLIMB_ALT:get() then + reached_climb_alt = true + gcs:send_text(MAV_SEVERITY.ERROR, "DEPL: Reached climb alt") + end + return + end + if deployed then + return + end + if altitude > deployment_alt:get() then + return + end + deployed = true + gcs:send_text(MAV_SEVERITY.INFO, "DEPL: deploying") + vehicle:set_mode(MODE_LAND) + arming:arm_force() + if not vehicle:get_mode() == MODE_LAND or not arming:is_armed() then + gcs:send_text(MAV_SEVERITY.INFO, "DEPL: Arming failed") + return + end + --SRV_Channels:set_output_pwm(SERVO_FUNCTION, end_pos:get()) + gcs:send_text(MAV_SEVERITY.INFO, "DEPL: Deployed successfully") +end +function update() -- this is the loop which periodically runs + update_state() + return update, 20 -- Reschedules the loop at 50Hz +end +gcs:send_text(MAV_SEVERITY.INFO, "DEPL: loaded") +return update() -- Run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/examples/crosstrack_restore.lua b/libraries/AP_Scripting/examples/crosstrack_restore.lua new file mode 100644 index 00000000000000..345977db398a48 --- /dev/null +++ b/libraries/AP_Scripting/examples/crosstrack_restore.lua @@ -0,0 +1,99 @@ +--[[ + + example script to show interrupting a mission and then + reseting the crosstracking to the correct line when + returning to the mission after the interruption + + this functionality is only available in Plane +--]] + +SCRIPT_NAME = "Crosstrack Restore" +SCRIPT_NAME_SHORT = "XTrack" +SCRIPT_VERSION = "4.6.0-001" + + +MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +FLIGHT_MODE = {AUTO=10, RTL=11, LOITER=12, GUIDED=15, QHOVER=18, QLOITER=19, QRTL=21} + +local last_sw = -1 +local AUX_FN = 300 + +-- Attempts to duplicate the code that updates the prev_WP_loc variable in the c++ code +local function LocationTracker() + + local self = {} + + -- to get this to work, need to keep 2 prior generations of "target_location" + local previous_target_location -- the target prior to the current one + local previous_previous_target_location -- the target prior to that - this is the one we want + + function self.same_loc_as(A, B) + if A == nil or B == nil then + return false + end + if (A:lat() ~= B:lat()) or (A:lng() ~= B:lng()) then + return false + end + return (A:alt() == B:alt()) and (A:get_alt_frame() == B:get_alt_frame()) + end + + function self.save_previous_target_location() + local target_location = vehicle:get_target_location() + if target_location ~= nil then + if not self.same_loc_as(previous_target_location, target_location) then + -- maintain three generations of location + previous_previous_target_location = previous_target_location + previous_target_location = target_location + end + else + previous_target_location = ahrs:get_location() + previous_previous_target_location = previous_target_location + end + end + + function self.get_saved_location() + return previous_previous_target_location + end + + return self +end + +local location_tracker = LocationTracker() + +local function update() + + -- save the previous target location only if in auto mode, if restoring it in AUTO mode + if vehicle:get_mode() == FLIGHT_MODE.AUTO and location_tracker ~= nil then + location_tracker.save_previous_target_location() + end + + local sw_current = rc:get_aux_cached(AUX_FN) + if not sw_current then + sw_current = 0 + end + if sw_current ~= last_sw then + last_sw = sw_current + if sw_current == 0 then + vehicle:set_mode(FLIGHT_MODE.AUTO) + if location_tracker ~= nil then + local previous_location = location_tracker.get_saved_location() + if previous_location ~= nil then + vehicle:set_crosstrack_start(previous_location) + end + end + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s: Switched to AUTO", SCRIPT_NAME_SHORT)) + else + vehicle:set_mode(FLIGHT_MODE.LOITER) + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s: Switched to LOITER", SCRIPT_NAME_SHORT)) + end + end + + return update,100 +end + +if FWVersion:type() == 3 then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("%s %s script loaded", SCRIPT_NAME, SCRIPT_VERSION) ) + return update() +else + gcs:send_text(MAV_SEVERITY.NOTICE,string.format("%s: Must run on Plane", SCRIPT_NAME_SHORT)) +end diff --git a/libraries/AP_Scripting/examples/fault_handling.lua b/libraries/AP_Scripting/examples/fault_handling.lua new file mode 100644 index 00000000000000..27657c48a34441 --- /dev/null +++ b/libraries/AP_Scripting/examples/fault_handling.lua @@ -0,0 +1,59 @@ +--[[ + example script to test fault handling with pcall +--]] + +---@diagnostic disable: need-check-nil +---@diagnostic disable: undefined-field + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +gcs:send_text(MAV_SEVERITY.INFO, "Loading fault test") + +local test_count = 0 +local fault_count = 0 + +--[[ + evaluate a lua function and return nil on fault or the functions return value +--]] +local function evaluate(f) + local ok, s = pcall(f) + eval_func = nil + if ok then + return s + end + fault_count = fault_count + 1 + return nil +end + +local function nil_deref() + local loc = nil + return loc:lat() +end + +local function bad_random() + return math.random(1,0) +end + +local function run_test() + local script_variant = test_count % 2 + if script_variant == 0 then + evaluate(nil_deref) + elseif script_variant == 1 then + evaluate(bad_random) + end +end + +local function update() + if test_count % 100 == 0 then + gcs:send_text(MAV_SEVERITY.INFO,string.format("Test %u fault_count %u", test_count, fault_count)) + end + test_count = test_count + 1 + run_test() + assert(fault_count == test_count, "fault and test counts should match") + return update,1 +end + +gcs:send_text(MAV_SEVERITY.INFO, "Starting fault test in 2 seconds") + +-- wait a while for GCS to connect +return update,2000 diff --git a/libraries/AP_Scripting/examples/frsky_wp.lua b/libraries/AP_Scripting/examples/frsky_wp.lua index 3ec41571382798..91b8c083d842d9 100644 --- a/libraries/AP_Scripting/examples/frsky_wp.lua +++ b/libraries/AP_Scripting/examples/frsky_wp.lua @@ -18,6 +18,7 @@ Note: 17 is the index, 0x71 is the actual ID --]] -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch local loop_time = 1000 -- number of ms between runs diff --git a/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua b/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua index 08638ef1695fb1..93eea1843f7b4c 100644 --- a/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua +++ b/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua @@ -8,6 +8,8 @@ -- 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. +---@diagnostic disable: cast-local-type + -- setup param block for VTOL failsafe params local PARAM_TABLE_KEY = 77 local PARAM_TABLE_PREFIX = "VTFS_" diff --git a/libraries/AP_Scripting/examples/gen_control.lua b/libraries/AP_Scripting/examples/gen_control.lua index 018c6ce23f8c4e..a8013c049a48a0 100644 --- a/libraries/AP_Scripting/examples/gen_control.lua +++ b/libraries/AP_Scripting/examples/gen_control.lua @@ -7,6 +7,8 @@ --]] -- luacheck: only 0 +---@diagnostic disable: need-check-nil +---@diagnostic disable: param-type-mismatch UPDATE_RATE_HZ = 10 diff --git a/libraries/AP_Scripting/examples/gps_synth.lua b/libraries/AP_Scripting/examples/gps_synth.lua new file mode 100644 index 00000000000000..ef3ce6b00b5a07 --- /dev/null +++ b/libraries/AP_Scripting/examples/gps_synth.lua @@ -0,0 +1,170 @@ +-- get GPS data from ardupilot's native bindings then resynthesize into a +-- virtual NMEA GPS and feed back through the serial device sim bindings. +-- demonstrates the bindings and provides the opportunity for script-controlled +-- tampering and other such activities. + +-- parameters: +-- SCR_ENABLE 1 +-- SCR_SDEV_EN 1 +-- SCR_SDEV1_PROTO 5 +-- SERIAL3_PROTOCOL 5 +-- SERIAL4_PROTOCOL -1 +-- GPS2_TYPE 5 +-- GPS_PRIMARY 1 +-- GPS_AUTO_SWITCH 0 + +local ser_device = serial:find_simulated_device(5, 0) +if not ser_device then + error("SCR_SDEV_EN must be 1 and SCR_SDEVn_PROTO must be 5") +end + +function convert_coord(coord, dir) + -- convert ardupilot degrees*1e7 to NMEA degrees + decimal minutes + dir. + -- the first character of dir is used if the coordinate is positive, + -- the second if negative. + + -- handle sign + if coord < 0 then + coord = -coord + dir = dir:sub(2, 2) + else + dir = dir:sub(1, 1) + end + + local degrees = coord // 10000000 -- integer divide + coord = coord - (degrees * 10000000) -- remove that portion + local minutes = coord * (60/10000000) -- float divide + + return ("%03d%08.5f,%s"):format(degrees, minutes, dir) +end + +function convert_time(time_week, time_week_ms) + -- convert ardupilot GPS time to NMEA UTC date/time strings + + -- GPS week 1095 starts on Dec 31 2000 + local seconds_per_week = uint32_t(86400*7) + timestamp_s = uint32_t(time_week - 1095)*seconds_per_week + -- subtract one day to get to Jan 1 2001, then 18 additional seconds to + -- account for the GPS to UTC leap second induced offset + timestamp_s = timestamp_s - uint32_t(86400 + 18) + -- add in time within the week + timestamp_s = timestamp_s + (time_week_ms/uint32_t(1000)) + + timestamp_s = timestamp_s:toint() -- seconds since Jan 1 2001 + + local ts_year = 2001 + local day_seconds = 86400 + while true do + local year_seconds = day_seconds * ((ts_year % 4 == 0) and 366 or 365) + if timestamp_s >= year_seconds then + timestamp_s = timestamp_s - year_seconds + ts_year = ts_year + 1 + else + break + end + end + + local month_days = {31, (ts_year % 4 == 0) and 29 or 28, + 31, 30, 31, 30, 31, 31, 30, 31, 30, 31} + + local ts_month = 1 + for _, md in ipairs(month_days) do + local month_seconds = 86400 * md + if timestamp_s >= month_seconds then + timestamp_s = timestamp_s - month_seconds + ts_month = ts_month + 1 + else + break + end + end + + local ts_day = 1+(timestamp_s // 86400) + timestamp_s = timestamp_s % 86400 + + local ts_hour = timestamp_s // 3600 + timestamp_s = timestamp_s % 3600 + + local ts_minute = timestamp_s // 60 + local ts_second = timestamp_s % 60 + + local date = ("%02d%02d%02d"):format(ts_year-2000, ts_month, ts_day) + local time = ("%02d%02d%02d.%01d"):format(ts_hour, ts_minute, ts_second, + (time_week_ms % 1000):toint()//100) + + return date, time +end + +function get_gps_data(instance) + -- get GPS data from ardupilot scripting bindings in native format + local data = { + hdop = gps:get_hdop(instance), + time_week_ms = gps:time_week_ms(instance), + time_week = gps:time_week(instance), + sats = gps:num_sats(instance), + crs = gps:ground_course(instance), + spd = gps:ground_speed(instance), + loc = gps:location(instance), + status = gps:status(instance), + } + if data.status < gps.GPS_OK_FIX_3D then + return nil -- don't bother with invalid data + end + return data +end + +function arrange_nmea(data) + -- convert ardupilot data entries to NMEA-compatible format + local ts_date, ts_time = convert_time(data.time_week, data.time_week_ms) + + return { + time = ts_time, + lat = convert_coord(data.loc:lat(), "NS"), + lng = convert_coord(data.loc:lng(), "EW"), + spd = data.spd / 0.514, -- m/s to knots + crs = data.crs, -- degrees + date = ts_date, + sats = data.sats, + hdop = data.hdop, + alt = data.loc:alt()/100, + } +end + +function wrap_nmea(msg) + -- compute checksum and add header and footer + local checksum = 0 + for i = 1,#msg do + checksum = checksum ~ msg:byte(i, i) + end + + return ("$%s*%02X\r\n"):format(msg, checksum) +end + +function format_nmea(data) + -- format data into complete NMEA sentences + local rmc_raw = ("GPRMC,%s,A,%s,%s,%03f,%03f,%s,000.0,E"):format( + data.time, data.lat, data.lng, data.spd, data.crs, data.date) + + local gga_raw = ("GPGGA,%s,%s,%s,1,%02d,%05.2f,%06.2f,M,0,M,,"):format( + data.time, data.lat, data.lng, data.sats, data.hdop/100, data.alt) + + return wrap_nmea(rmc_raw), wrap_nmea(gga_raw) +end + +function update() + -- get data from first instance (we are the second) + local ardu_data = get_gps_data(0) + + if ardu_data then + local nmea_data = arrange_nmea(ardu_data) + local rmc, gga = format_nmea(nmea_data) + + if ser_device:writestring(rmc) ~= #rmc + or ser_device:writestring(gga) ~= #gga then + error("overflow, ardupilot is not processing the data, check config!") + end + end + + return update, 200 -- 5Hz like a real GPS +end + +return update() diff --git a/libraries/AP_Scripting/examples/i2c_scan.lua b/libraries/AP_Scripting/examples/i2c_scan.lua index 9e93806af75ae3..8600c1e21ba45b 100644 --- a/libraries/AP_Scripting/examples/i2c_scan.lua +++ b/libraries/AP_Scripting/examples/i2c_scan.lua @@ -1,4 +1,7 @@ -- This script scans for devices on the i2c bus + +---@diagnostic disable: need-check-nil + local address = 0 local found = 0 diff --git a/libraries/AP_Scripting/examples/land_hagl.lua b/libraries/AP_Scripting/examples/land_hagl.lua new file mode 100644 index 00000000000000..3bdbc36329aea6 --- /dev/null +++ b/libraries/AP_Scripting/examples/land_hagl.lua @@ -0,0 +1,69 @@ +--[[ + demonstrate proving HAGL to plane code for landing +--]] + +local MAV_CMD_SET_HAGL = 43005 + +local ROTATION_PITCH_90 = 24 +local ROTATION_PITCH_270 = 25 + +-- for normal landing use PITCH_270, for inverted use PITCH_90 +local RANGEFINDER_ORIENT = ROTATION_PITCH_270 + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +local RNG_STATUS = { NotConnected = 0, NoData = 1, OutOfRangeLow = 2, OutOfRangeHigh = 3, Good = 4 } + + +--[[ + create a NaN value +--]] +local function NaN() + return 0/0 +end + +local last_active = false + +--[[ + send HAGL data +--]] +local function send_HAGL() + local status = rangefinder:status_orient(RANGEFINDER_ORIENT) + if status ~= RNG_STATUS.Good then + last_active = false + return + end + local rangefinder_dist = rangefinder:distance_cm_orient(RANGEFINDER_ORIENT)*0.01 + local correction = math.cos(ahrs:get_roll())*math.cos(ahrs:get_pitch()) + local rangefinder_corrected = rangefinder_dist * correction + if RANGEFINDER_ORIENT == ROTATION_PITCH_90 then + rangefinder_corrected = -rangefinder_corrected + end + if rangefinder_corrected < 0 then + last_active = false + return + end + + -- tell plane the height above ground level + local timeout_s = 0.2 + local accuracy = NaN() + gcs:run_command_int(MAV_CMD_SET_HAGL, { p1 = rangefinder_corrected, p2 = accuracy, p3=timeout_s }) + + if not last_active then + last_active = true + gcs:send_text(MAV_SEVERITY.INFO, string.format("HAGL Active %.1f", rangefinder_corrected)) + end + + -- log it + logger:write("HAGL", "RDist,HAGL", "ff", rangefinder_dist, rangefinder_corrected) +end + +local function update() + send_HAGL() + return update, 50 +end + +gcs:send_text(MAV_SEVERITY.INFO, "Loaded land_hagl") + +return update, 1000 + diff --git a/libraries/AP_Scripting/examples/message_interval.lua b/libraries/AP_Scripting/examples/message_interval.lua index e52025da4f76f3..48f844a987973c 100644 --- a/libraries/AP_Scripting/examples/message_interval.lua +++ b/libraries/AP_Scripting/examples/message_interval.lua @@ -5,17 +5,50 @@ -- during the initial connection, so by resetting them periodically we ensure we get -- the expected telemetry rate +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +local loop_time = 5000 -- number of ms between runs + +-- mavlink message ids +local AHRS_ID = uint32_t(163) +local AHRS2_ID = uint32_t(178) +local ATTITUDE_ID = uint32_t(30) +--local EKF_STATUS_REPORT_ID = uint32_t(193) +--local GLOBAL_POSITION_INT_ID = uint32_t(33) +--local GPS_RAW_INT_ID = uint32_t(24) +--local LOCAL_POSITION_NED_ID = uint32_t(32) +--local NAV_CONTROLLER_OUTPUT_ID = uint32_t(62) +--local POWER_STATUS_ID = uint32_t(125) +--local RAW_IMU_ID = uint32_t(27) +--local RC_CHANNELS_ID = uint32_t(65) +--local SERVO_OUTPUT_RAW_ID = uint32_t(36) +--local SYS_STATUS_ID = uint32_t(1) +--local SYSTEM_TIME_ID = uint32_t(2) +--local VFR_HUD_ID = uint32_t(74) +--local VIBRATION_ID = uint32_t(241) +--local WIND_ID = uint32_t(168) + +-- serial port +local serial_port = 0 + -- intervals is a table which contains a table for each entry we want to adjust -- each entry is arranged as {the serial link to adjust, the mavlink message ID, and the broadcast interval in Hz} -local intervals = {{0, uint32_t(30), 2.0}, -- First serial, ATTITUDE, 2Hz - {0, uint32_t(163), 5.0}} -- First serial, AHRS, 5Hz +local intervals = {{serial_port, ATTITUDE_ID, 2.0}, -- ATTITUDE, 2Hz + {serial_port, AHRS_ID, 5.0}, -- AHRS, 5Hz + {serial_port, AHRS2_ID, 0}, -- AHRS2, 0hz + } -local loop_time = 5000 -- number of ms between runs +-- print welcome message +gcs:send_text(MAV_SEVERITY.INFO, "Loaded message_interval.lua") function update() -- this is the loop which periodically runs for i = 1, #intervals do -- we want to iterate over every specified interval local channel, message, interval_hz = table.unpack(intervals[i]) -- this extracts the channel, MAVLink ID, and interval - gcs:set_message_interval(channel, message, math.floor(1000000 / interval_hz)) -- actually sets the interval as appropriate + local interval_us = -1 + if interval_hz > 0 then + interval_us = math.floor(1000000 / interval_hz) -- convert the interval to microseconds + end + gcs:set_message_interval(channel, message, interval_us) -- actually sets the interval as appropriate end return update, loop_time -- reschedules the loop end diff --git a/libraries/AP_Scripting/examples/mission-edit-demo.lua b/libraries/AP_Scripting/examples/mission-edit-demo.lua index ecbebe9c54af4c..d750d3f3bf50db 100644 --- a/libraries/AP_Scripting/examples/mission-edit-demo.lua +++ b/libraries/AP_Scripting/examples/mission-edit-demo.lua @@ -2,6 +2,9 @@ -- by Buzz 2020 -- luacheck: only 0 +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: undefined-field + current_pos = nil home = 0 a = {} diff --git a/libraries/AP_Scripting/examples/mission-load.lua b/libraries/AP_Scripting/examples/mission-load.lua index 76f465b1fbb55b..0ea6506e77eb3e 100644 --- a/libraries/AP_Scripting/examples/mission-load.lua +++ b/libraries/AP_Scripting/examples/mission-load.lua @@ -5,7 +5,7 @@ --The "mission1.txt" file containing the mission items should be placed in the directory above the "scripts" directory. --In case of placing it on SD Card, mission1.txt file should be placed in the APM directory root. - +---@diagnostic disable: param-type-mismatch local function read_mission(file_name) diff --git a/libraries/AP_Scripting/examples/mission-save.lua b/libraries/AP_Scripting/examples/mission-save.lua index 84d19da296f49b..806a37eb3d038b 100644 --- a/libraries/AP_Scripting/examples/mission-save.lua +++ b/libraries/AP_Scripting/examples/mission-save.lua @@ -1,5 +1,7 @@ -- Example of saving the current mission to a file on the SD card on arming +---@diagnostic disable: need-check-nil + local function save_to_SD() -- check if there is a mission to save diff --git a/libraries/AP_Scripting/examples/mount-test.lua b/libraries/AP_Scripting/examples/mount-test.lua index 18ef644989076f..93f66f473df57b 100644 --- a/libraries/AP_Scripting/examples/mount-test.lua +++ b/libraries/AP_Scripting/examples/mount-test.lua @@ -12,6 +12,8 @@ -- stage 9: point North and Down -- stage 10: move angle to neutral position +---@diagnostic disable: cast-local-type + local stage = 0 local stage_time_ms = 5000 local stage_start_time_ms = 0 diff --git a/libraries/AP_Scripting/examples/net_test.lua b/libraries/AP_Scripting/examples/net_test.lua index b83fa2f8f4ba97..42a9818cacdb1d 100644 --- a/libraries/AP_Scripting/examples/net_test.lua +++ b/libraries/AP_Scripting/examples/net_test.lua @@ -101,10 +101,13 @@ local function test_server(name, sock) sock = sock_tcp_in2 end - local r = sock:recv(1024) + local r, ip, port = sock:recv(1024) if r and #r > 0 then gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_server(%s): got input '%s'", name, r)) end + if ip then + gcs:send_text(MAV_SEVERITY.INFO, string.format("packet from %s:%u", ipv4_addr_to_string(ip), port)) + end end local function update() diff --git a/libraries/AP_Scripting/examples/notch_switch.lua b/libraries/AP_Scripting/examples/notch_switch.lua new file mode 100644 index 00000000000000..977a19a7207f76 --- /dev/null +++ b/libraries/AP_Scripting/examples/notch_switch.lua @@ -0,0 +1,48 @@ +--[[ + + example script to switch between two notch setups by changing the + attenuation to zero on the notch to disable. This allows for easy + in-flight switching between two different notch setups +--]] +local INS_HNTCH_ATT = Parameter('INS_HNTCH_ATT') +local INS_HNTC2_ATT = Parameter('INS_HNTC2_ATT') + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +if not INS_HNTCH_ATT:get() or not INS_HNTC2_ATT:get() then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Need 2 notches configured")) + return +end + +local last_sw = -1 +local AUX_FN = 300 + +local attenuation = INS_HNTCH_ATT:get() +if not attenuation then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Unable to get attenuation")) + return +end + +function update() + local sw_current = rc:get_aux_cached(AUX_FN) + if not sw_current then + -- treat unset as notch1 + sw_current = 0 + end + if sw_current ~= last_sw then + last_sw = sw_current + if sw_current == 0 then + INS_HNTC2_ATT:set(0) + INS_HNTCH_ATT:set(attenuation) + gcs:send_text(MAV_SEVERITY.INFO, string.format("Switched to notch1 %.2f", attenuation)) + else + INS_HNTC2_ATT:set(attenuation) + INS_HNTCH_ATT:set(0) + gcs:send_text(MAV_SEVERITY.INFO, string.format("Switched to notch2 %.2f", attenuation)) + end + end + return update,100 +end + +return update() + diff --git a/libraries/AP_Scripting/examples/plane-callout-alt.lua b/libraries/AP_Scripting/examples/plane-callout-alt.lua new file mode 100644 index 00000000000000..4a7181dbad1260 --- /dev/null +++ b/libraries/AP_Scripting/examples/plane-callout-alt.lua @@ -0,0 +1,219 @@ +--[[ + + 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 . + +--]] + +SCRIPT_VERSION = "4.6.0-003" +SCRIPT_NAME = "Plane Altitude Callouts" +SCRIPT_NAME_SHORT = "Callout" + +-- This script calls out altitude if the user is near (WARN) or above (MAX) +-- Allows for units to be feet even if you do everything else in metric because the laws typically specify 400 feet for UAV/RPAS in most countries +-- all of the settings are stored in parameters: +-- CALLOUT_ALT_UNITS 1 = metric, 2 (default) = imperial +-- CALLOUT_ALT_MAX max allowed altitude (its still a message there is no action) +-- CALLOUT_ALT_STEP callout (via GC message) when altitude changes by this amount or more +-- CALLOUT_ALT_CALL seconds between callout of flying altitude +-- CALLOUT_ALT_WARN seconds between callouts that you are less than ALT_STEP below ALT_MAX +-- CALLOUT_ALT_HIGH seconds between callouts that you have exceeded ALT_MAX + +REFRESH_RATE = 1000 --check every 1 second + +MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +local PARAM_TABLE_KEY = 102 +local PARAM_TABLE_PREFIX = "ZPC_" + +-- add a parameter and bind it to a variable +local 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 + +-- setup follow mode specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add param table') + + +-- Add these ZPC_ parameters specifically for this script +--[[ + // @Param: ZPC_ALT_UNITS + // @DisplayName: Plane Callouts Units - defaults to feet + // @Description: 1: Metric/meters or 2: Imperial/feet + // @User: Standard +--]] +ZPC_ALT_UNITS = bind_add_param('ALT_UNITS', 1, 2) + +--[[ + // @Param: ZPC_ALT_MAX + // @DisplayName: Plane Callouts max altitude + // @Description: Maximum altitude in ALT_UNITS + // @Range: 0 30 + // @Units: seconds +--]] +ZPC_ALT_MAX = bind_add_param("ALT_MAX", 2, 400) + +--[[ + // @Param: ZPC_ALT_STEP + // @DisplayName: Plane Callouts altitude steps + // @Description: Altitude steps for callouts in ALT_UNITS + // @Range: 0 100 + // @Units: ALT_UNIT +--]] +ZPC_ALT_STEP = bind_add_param("ALT_STEP", 3, 25) + +--[[ + // @Param: ZPC_ALT_CALL + // @DisplayName: Plane Callouts frequency + // @Description: How often to callout altitude when flying normally + // @Range: 0 30 + // @Units: seconds +--]] +ZPC_ALT_CALL = bind_add_param("ALT_CALL", 4, 25) + +--[[ + // @Param: ZPC_ALT_WARN + // @DisplayName: Plane altitude warning frequency + // @Description: How often to nag about almost hitting MAX + // @Range: 0 30 + // @Units: seconds +--]] +ZPC_ALT_WARN = bind_add_param("ALT_WARN", 5, 25) + +--[[ + // @Param: ZPC_ALT_HIGH + // @DisplayName: Plane altitude max altitude callout frequency + // @Description: How often to nag about exceeding MAX + // @Range: 0 30 + // @Units: seconds +--]] +ZPC_ALT_HIGH = bind_add_param("ALT_HIGH", 6, 10) + +local alt_units = ZPC_ALT_UNITS:get() or 2 -- default to feet because "thats what it is" +local alt_max = ZPC_ALT_MAX:get() or 400 -- most places this is the legal limit, if you have a different limit, change this +local alt_step = ZPC_ALT_STEP:get() or 25 +local alt_call_sec = ZPC_ALT_CALL:get() or 25 +local alt_warn_sec = ZPC_ALT_WARN:get() or 25 +local alt_high_sec = ZPC_ALT_HIGH:get() or 10 + +local alt_last = 0 +local alt_warn = alt_max - alt_step + +local unit = "meters" +if (alt_units == 2) then + unit = "feet" +end +local altitude_max = string.format("%i %s", math.floor(alt_max+0.5), unit ) + +local time_last_warn_s = millis() / 1000 +local time_last_max_s = millis() / 1000 +local time_last_update_s = millis() / 1000 +local alt_max_exceeded = false +local alt_warn_exceeded = false + +local function update() -- this is the loop which periodically runs + local current_time_s = millis() / 1000 + -- setting the height/altitude variables like this means all the code below works without change for either metric or Imperial units + local terrain_height = terrain:height_above_terrain(true) + + -- if terrain height is not available use height above home + if terrain_height == nil then + -- override terrain height with home height (TODO: parameterize this) + local pos = ahrs:get_relative_position_NED_home() + if pos == nil then + return + else + terrain_height = -pos:z() + end + end + + --- allow these parameters to be changed at runtime. + alt_units = ZPC_ALT_UNITS:get() or 2 + alt_max = ZPC_ALT_MAX:get() or 400 -- most places this is the legal limit, if you have a different limit, change this + alt_step = ZPC_ALT_STEP:get() or 25 + alt_call_sec = ZPC_ALT_CALL:get() or 25 + alt_warn_sec = ZPC_ALT_WARN:get() or 25 + alt_high_sec = ZPC_ALT_HIGH:get() or 10 + if (alt_units == 2) then + unit = "feet" + else + unit = "meters" + end + + if (alt_units == 2) then + terrain_height = terrain_height * 3.28084 + end + local altitude = string.format("%i %s", math.floor(terrain_height+0.5), unit ) + + if terrain_height > alt_max then + if (time_last_max_s < current_time_s - alt_high_sec) then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("Altitude %s too high max %s", altitude, altitude_max )) + time_last_max_s = current_time_s + alt_max_exceeded = true + end + elseif terrain_height > alt_warn then + if (time_last_warn_s < current_time_s - alt_warn_sec) then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("Warning altitude is %s", altitude )) + time_last_warn_s = current_time_s + alt_warn_exceeded = true + end + else + -- we are fine now, but maybe we were not fine before. + -- So if we previously displayed altitude warn/error messages, let the pilot know we are now fine + if(alt_max_exceeded or alt_warn_exceeded) then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("Altitude %s is Ok", altitude )) + else + -- nothing else important happened, so see if our altitude has gone up or down by more than ALT_STEP + -- in which case we call it out + if (time_last_update_s < current_time_s - alt_call_sec) then + local alt_diff = (terrain_height - alt_last) + if (math.abs(alt_diff) > alt_step) then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("Altitude is %s", altitude )) + alt_last = math.floor(terrain_height / alt_step + 0.5) * alt_step + end + time_last_update_s = current_time_s + end + end + alt_max_exceeded = false + alt_warn_exceeded = false + end +end + +local displayed_banner = false +-- wrapper around update(). This calls update() at 1Hz, +-- and if update faults then an error is displayed, but the script is not +-- stopped +local function protected_wrapper() + + if not displayed_banner then + gcs:send_text(MAV_SEVERITY.INFO, string.format("%s %s script loaded callouts in %s", SCRIPT_NAME, SCRIPT_VERSION, unit) ) + displayed_banner = true + end + + if not arming:is_armed() then return protected_wrapper, REFRESH_RATE * 10 end + + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY.ALERT, SCRIPT_NAME_SHORT .. "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, REFRESH_RATE +end + + + -- start running update loop - wait 20 seconds before starting up +return protected_wrapper, 20000 + diff --git a/libraries/AP_Scripting/examples/plane-doublets.lua b/libraries/AP_Scripting/examples/plane-doublets.lua index 2c34a381f6cd55..da806fe754c724 100644 --- a/libraries/AP_Scripting/examples/plane-doublets.lua +++ b/libraries/AP_Scripting/examples/plane-doublets.lua @@ -8,6 +8,9 @@ -- starting a doublet -- Charlie Johnson, Oklahoma State University 2020 +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type + local DOUBLET_ACTION_CHANNEL = 6 -- RCIN channel to start a doublet when high (>1700) local DOUBLET_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high) local DOUBLET_FUCNTION = 19 -- which control surface (SERVOx_FUNCTION) number will have a doublet happen diff --git a/libraries/AP_Scripting/examples/plane-wind-fs.lua b/libraries/AP_Scripting/examples/plane-wind-fs.lua index ef5fcfccd2eb26..2369a1d5a31c8f 100644 --- a/libraries/AP_Scripting/examples/plane-wind-fs.lua +++ b/libraries/AP_Scripting/examples/plane-wind-fs.lua @@ -3,6 +3,9 @@ -- -- CAUTION: This script only works for Plane +---@diagnostic disable: cast-local-type +---@diagnostic disable: undefined-global + -- store the batt info as { instance, filtered, capacity, margin_mah } -- instance: the battery monitor instance (zero indexed) -- filtered: internal variable for current draw diff --git a/libraries/AP_Scripting/examples/plane_guided_follow.lua b/libraries/AP_Scripting/examples/plane_guided_follow.lua index 89e5ef09cd3639..c5d6252f3ca8f8 100644 --- a/libraries/AP_Scripting/examples/plane_guided_follow.lua +++ b/libraries/AP_Scripting/examples/plane_guided_follow.lua @@ -1,5 +1,7 @@ -- support follow in GUIDED mode in plane -- luacheck: only 0 +---@diagnostic disable: cast-local-type + local PARAM_TABLE_KEY = 11 local PARAM_TABLE_PREFIX = "GFOLL_" diff --git a/libraries/AP_Scripting/examples/plane_guided_terrain.lua b/libraries/AP_Scripting/examples/plane_guided_terrain.lua new file mode 100644 index 00000000000000..86f6ded9f329b9 --- /dev/null +++ b/libraries/AP_Scripting/examples/plane_guided_terrain.lua @@ -0,0 +1,234 @@ +--[[ + + example script to show reseting guided mode to terrain height. + It's intended to be used when selecting "fly to altitude" in a ground station + for example by right clicking on the map in QGC. + + This is actually a workaround to QGC and Mission Planner not having a + way to set guided altitude above terrain. + + Depending on ZGP_MODE + When the GCS requests a guided altitude X above home + 1: reset to current terrain height ignore X + 2: reset to X above terrain + 3: reset to current alt + X + + this functionality is only available in Plane and + requires TERRAIN_ENABLE = 1 and TERRAIN_FOLLOW =1 +--]] + +SCRIPT_NAME = "OverheadIntel Guided Terrain" +SCRIPT_NAME_SHORT = "TerrGuided" +SCRIPT_VERSION = "4.6.0-005" + +REFRESH_RATE = 0.2 -- in seconds, so 5Hz +ALTITUDE_MIN = 50 +ALTITUDE_MAX = 120 + +MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +MAV_FRAME = { GLOBAL = 0, GLOBAL_RELATIVE_ALT = 3} +ALT_FRAME = { ABSOLUTE = 0, ABOVE_HOME = 1, ABOVE_ORIGIN = 2, ABOVE_TERRAIN = 3 } +FLIGHT_MODE = {AUTO=10, RTL=11, LOITER=12, GUIDED=15, QHOVER=18, QLOITER=19, QRTL=21} + +PARAM_TABLE_KEY = 101 +PARAM_TABLE_PREFIX = "ZGT_" + +local now = millis():tofloat() * 0.001 + +-- bind a parameter to a variable +function bind_param(name) + return Parameter(name) +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), SCRIPT_NAME_SHORT .. string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup follow mode specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), SCRIPT_NAME_SHORT .. 'could not add param table: ' .. PARAM_TABLE_PREFIX) + +--[[ + // @Param: ZGT_MODE + // @DisplayName: Guided Terrain Mode + // @Description: When the GCS requests a guided altitude X above home 1: reset to current terrain height ignore X 2: reset to X above terrain 3: reset to current alt + X + // @Range: 1,2,3 +--]] +ZGT_MODE = bind_add_param("MODE", 1, 1) +TERRAIN_ENABLE = bind_param("TERRAIN_ENABLE") +TERRAIN_FOLLOW = bind_param("TERRAIN_FOLLOW") + +local zgt_mode = ZGT_MODE:get() +local terrain_enable = TERRAIN_ENABLE:get() +local terrain_follow = TERRAIN_FOLLOW:get() + +MAV_CMD_INT = { DO_SET_MODE = 176, DO_CHANGE_SPEED = 178, DO_REPOSITION = 192, + GUIDED_CHANGE_SPEED = 43000, GUIDED_CHANGE_ALTITUDE = 43001, GUIDED_CHANGE_HEADING = 43002 } +MAV_FRAME = { GLOBAL = 0, GLOBAL_RELATIVE_ALT = 3, GLOBAL_TERRAIN_ALT = 10} + +-- constrain a value between limits +local function constrain(v, vmin, vmax) + if v < vmin then + v = vmin + end + if v > vmax then + v = vmax + end + return v +end + +local function follow_frame_to_mavlink(follow_frame) + local mavlink_frame = MAV_FRAME.GLOBAL + if (follow_frame == ALT_FRAME.ABOVE_TERRAIN) then + mavlink_frame = MAV_FRAME.GLOBAL_TERRAIN_ALT + elseif (follow_frame == ALT_FRAME.ABOVE_HOME) then + mavlink_frame = MAV_FRAME.GLOBAL_RELATIVE_ALT + end + return mavlink_frame + end + +local now_altitude = millis():tofloat() * 0.001 +-- target.alt = new target altitude in meters +-- set_vehicle_target_altitude() Parameters +-- target.frame = Altitude frame MAV_FRAME, it's very important to get this right! +-- target.alt = altitude in meters to acheive +-- target.accel = z acceleration to altitude (1000.0 = max) +local function set_vehicle_target_altitude(target) + local acceleration = target.accel or 1000.0 -- default to maximum z acceleration + if math.floor(now) ~= math.floor(now_altitude) then + now_altitude = millis():tofloat() * 0.001 + end + if target.alt == nil then + gcs:send_text(MAV_SEVERITY.ERROR, SCRIPT_NAME_SHORT .. ": set_vehicle_target_altitude no altiude") + return + end + -- GUIDED_CHANGE_ALTITUDE takes altitude in meters + local mavlink_result = gcs:run_command_int(MAV_CMD_INT.GUIDED_CHANGE_ALTITUDE, { + frame = follow_frame_to_mavlink(target.frame), + p3 = acceleration, + z = target.alt }) + if mavlink_result > 0 then + gcs:send_text(MAV_SEVERITY.ERROR, SCRIPT_NAME_SHORT .. string.format(": MAVLink GUIDED_CHANGE_ALTITUDE returned %d", mavlink_result)) + return false + else + return true + end +end + +local vehicle_mode = vehicle:get_mode() +local save_target_altitude = -1 +local save_old_target_altitude = -1 +local save_zgt_mode = -1 +local save_vehicle_mode = -1 + +local function update() + + vehicle_mode = vehicle:get_mode() + + terrain_enable = TERRAIN_ENABLE:get() + terrain_follow = TERRAIN_FOLLOW:get() + zgt_mode = ZGT_MODE:get() + if zgt_mode ~= save_zgt_mode then + -- user changed modes, reset everything + save_target_altitude = -1 + save_old_target_altitude = -1 + end + save_zgt_mode = zgt_mode + + -- We should only reset the altitude if newly switched to guided mode + if save_vehicle_mode ~= vehicle_mode and vehicle_mode == FLIGHT_MODE.GUIDED and terrain_enable == 1 and + ((terrain_follow & 1) == 1 or (terrain_follow & (1 << 6)) == 64) then + local target_location = vehicle:get_target_location() + if target_location ~= nil then + local target_location_frame = target_location:get_alt_frame() + -- need to convert the target_location to ABOVE_TERRAIN so we have apples and apples + local new_target_location = target_location:copy() + local new_target_altitude = save_target_altitude + local old_target_altitude = new_target_location:alt()/100 + + if save_old_target_altitude ~= old_target_altitude then + if target_location_frame ~= ALT_FRAME.ABOVE_TERRAIN then + if new_target_location:change_alt_frame(ALT_FRAME.ABOVE_TERRAIN) then + old_target_altitude = new_target_location:alt()/100 + end + end + -- adjust target_location for home altitude + local home_location = ahrs:get_home() + if home_location ~= nil then + local home_amsl = terrain:height_amsl(home_location, true) + local above_home = (target_location:alt() * 0.01 - home_amsl) + local location = ahrs:get_location() + if location ~= nil then + if location:get_alt_frame() ~= ALT_FRAME.ABOVE_TERRAIN then + location:change_alt_frame(ALT_FRAME.ABOVE_TERRAIN) + end + local current_altitude = location:alt() * 0.01 + -- @Description: When the GCS requests a guided altitude X above home + -- 1: reset to current terrain height ignore X + -- 2: reset to X above terrain + -- 3: reset to current alt + X + if zgt_mode == 1 then + new_target_altitude = current_altitude + elseif zgt_mode == 2 then + new_target_altitude = above_home + elseif zgt_mode == 3 then + new_target_altitude = current_altitude + above_home + end + new_target_altitude = constrain(new_target_altitude, ALTITUDE_MIN, ALTITUDE_MAX) + end + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("%s: FAILED to get HOME terrain height", SCRIPT_NAME_SHORT)) + end + + if new_target_altitude > 0 and + set_vehicle_target_altitude({alt = new_target_altitude, frame = ALT_FRAME.ABOVE_TERRAIN}) then -- pass altitude in meters (location has it in cm) + if new_target_altitude ~= save_target_altitude then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("%s: Reset to alt %.0fm above terrain", SCRIPT_NAME_SHORT, + new_target_altitude + )) + save_target_altitude = new_target_altitude + end + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("%s: FAILED to set altitude ABOVE_TERRAIN ait %.0f", SCRIPT_NAME_SHORT, + new_target_altitude + )) + end + end + save_old_target_altitude = old_target_altitude + else + gcs:send_text(MAV_SEVERITY.ERROR, string.format("%s: altitude not available", SCRIPT_NAME_SHORT)) + end + else + -- we switched out of guided, so forget what we thought we knew + save_target_altitude = -1 + save_old_target_altitude = -1 + end + save_vehicle_mode = vehicle_mode + + return update, 1000 * REFRESH_RATE +end + +-- wrapper around update(). This calls update() at 1/REFRESHRATE Hz, +-- and if update faults then an error is displayed, but the script is not +-- stopped +local function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(0, SCRIPT_NAME_SHORT .. ": 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 * REFRESH_RATE +end + +gcs:send_text(MAV_SEVERITY.NOTICE, string.format("%s %s script loaded", SCRIPT_NAME, SCRIPT_VERSION) ) + +-- start running update loop +if FWVersion:type() == 3 and terrain_enable then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("%s %s script loaded", SCRIPT_NAME, SCRIPT_VERSION) ) + return protected_wrapper() +else + gcs:send_text(MAV_SEVERITY.NOTICE,string.format("%s: Must run on Plane with terrain follow", SCRIPT_NAME_SHORT)) +end diff --git a/libraries/AP_Scripting/examples/quadruped.lua b/libraries/AP_Scripting/examples/quadruped.lua index a8d5536512d7de..f74e89b1f0ca56 100644 --- a/libraries/AP_Scripting/examples/quadruped.lua +++ b/libraries/AP_Scripting/examples/quadruped.lua @@ -19,6 +19,8 @@ -- -- CAUTION: This script should only be used with ArduPilot Rover's firmware +---@diagnostic disable: cast-local-type + local FRAME_LEN = 80 -- frame length in mm local FRAME_WIDTH = 150 -- frame width in mm diff --git a/libraries/AP_Scripting/examples/rangefinder_quality_test.lua b/libraries/AP_Scripting/examples/rangefinder_quality_test.lua index 28c78e7ff25156..45772d4d35d70b 100644 --- a/libraries/AP_Scripting/examples/rangefinder_quality_test.lua +++ b/libraries/AP_Scripting/examples/rangefinder_quality_test.lua @@ -10,6 +10,9 @@ -- "RNGFND1_MIN_CM": 10, -- "RNGFND1_MAX_CM": 5000, +---@diagnostic disable: cast-local-type + + -- UPDATE_PERIOD_MS is the time between when a distance is set and -- when it is read. There is a periodic task that copies the set distance to -- the state structure that it is read from. If UPDATE_PERIOD_MS is too short this periodic diff --git a/libraries/AP_Scripting/examples/rover-MinFixType.lua b/libraries/AP_Scripting/examples/rover-MinFixType.lua index aabe1f44d618b5..7afb3d67f36fb1 100644 --- a/libraries/AP_Scripting/examples/rover-MinFixType.lua +++ b/libraries/AP_Scripting/examples/rover-MinFixType.lua @@ -13,6 +13,8 @@ of a vehicle. Use this script AT YOUR OWN RISK. LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html ------------------------------------------------------------------------------]] +---@diagnostic disable: param-type-mismatch + local SCRIPT_NAME = 'MinFixType' -------- MAVLINK/AUTOPILOT 'CONSTANTS' -------- diff --git a/libraries/AP_Scripting/examples/rover-SaveTurns.lua b/libraries/AP_Scripting/examples/rover-SaveTurns.lua index 9e530f23313350..4aa68d021aaf9b 100644 --- a/libraries/AP_Scripting/examples/rover-SaveTurns.lua +++ b/libraries/AP_Scripting/examples/rover-SaveTurns.lua @@ -12,6 +12,9 @@ of a vehicle. Use this script AT YOUR OWN RISK. LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html ------------------------------------------------------------------------------]] +---@diagnostic disable: cast-local-type +---@diagnostic disable: need-check-nil + local SCRIPT_NAME = 'SaveTurns' -------- USER EDITABLE GLOBALS -------- diff --git a/libraries/AP_Scripting/examples/rover-TerrainDetector.lua b/libraries/AP_Scripting/examples/rover-TerrainDetector.lua index 7ba864682103f9..e220e7be282de8 100644 --- a/libraries/AP_Scripting/examples/rover-TerrainDetector.lua +++ b/libraries/AP_Scripting/examples/rover-TerrainDetector.lua @@ -28,6 +28,8 @@ https://www.youtube.com/watch?v=UdXGXjigxAo&t=7155s Credit to @ktrussell for the idea and discussion! ------------------------------------------------------------------------------]] +---@diagnostic disable: param-type-mismatch + 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 diff --git a/libraries/AP_Scripting/examples/serial_test.lua b/libraries/AP_Scripting/examples/serial_test.lua index 6f7a2a5a03831c..a1108923c708cf 100644 --- a/libraries/AP_Scripting/examples/serial_test.lua +++ b/libraries/AP_Scripting/examples/serial_test.lua @@ -1,5 +1,7 @@ -- Lua script to write and read from a serial +---@diagnostic disable: need-check-nil + local port = serial:find_serial(0) port:begin(115200) diff --git a/libraries/AP_Scripting/examples/servo_set_get.lua b/libraries/AP_Scripting/examples/servo_set_get.lua index 0834bacce5865f..61ed0d20e39fc3 100644 --- a/libraries/AP_Scripting/examples/servo_set_get.lua +++ b/libraries/AP_Scripting/examples/servo_set_get.lua @@ -5,7 +5,7 @@ local flipflop = true local K_AILERON = 4 -local aileron_channel = SRV_Channels:find_channel(K_AILERON) +local aileron_channel = assert(SRV_Channels:find_channel(K_AILERON)) function update() if flipflop then diff --git a/libraries/AP_Scripting/examples/servo_slew.lua b/libraries/AP_Scripting/examples/servo_slew.lua index 36d0f103bd788a..4bb52294261fef 100644 --- a/libraries/AP_Scripting/examples/servo_slew.lua +++ b/libraries/AP_Scripting/examples/servo_slew.lua @@ -1,4 +1,4 @@ --- move a servo in a sinisoidal fashion, with settable limits and frequency +-- move a servo in a sinusoidal fashion, with settable limits and frequency local PARAM_TABLE_KEY = 135 local PARAM_TABLE_PREFIX = "STEST_" diff --git a/libraries/AP_Scripting/examples/set_CAMERA_INFORMATION.lua b/libraries/AP_Scripting/examples/set_CAMERA_INFORMATION.lua new file mode 100644 index 00000000000000..76ec4ccd38e0a7 --- /dev/null +++ b/libraries/AP_Scripting/examples/set_CAMERA_INFORMATION.lua @@ -0,0 +1,38 @@ + --[[ + Populate the fields of the CAMERA_INFORMATION message sent by the selected camera instance. + --]] + function set_camera_information() + -- set the Camera Information data + local cam_info = mavlink_camera_information_t() + + local INSTANCE = 0 + local vendor_name = 'Unknown' + local model_name = 'Camera' + local uri = '' + + -- "time_boot_ms" is populated automatically by the camera backend + for i = 0, #vendor_name do + cam_info:vendor_name(i, vendor_name:byte(i+1)) + end + for i = 0, #model_name do + cam_info:model_name(i, model_name:byte(i+1)) + end + cam_info:firmware_version(0) + cam_info:focal_length(1.6) + cam_info:sensor_size_h(3840) + cam_info:sensor_size_v(2160) + cam_info:resolution_h(1920) + cam_info:resolution_v(1080) + -- "lens_id" is populated automatically by the camera backend + cam_info:flags(256) -- CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM + cam_info:cam_definition_version(0) + for i = 0, #uri do + cam_info:cam_definition_uri(i, uri:byte(i+1)) + end + -- "gimbal_device_id" is populated automatically by the camera backend + + camera:set_camera_information(INSTANCE, cam_info) + +end + +return set_camera_information() diff --git a/libraries/AP_Scripting/examples/set_VIDEO_STREAM_INFORMATION.lua b/libraries/AP_Scripting/examples/set_VIDEO_STREAM_INFORMATION.lua new file mode 100644 index 00000000000000..7f8a20844e8ba4 --- /dev/null +++ b/libraries/AP_Scripting/examples/set_VIDEO_STREAM_INFORMATION.lua @@ -0,0 +1,33 @@ + --[[ + Populate the fields of the VIDEO_STREAM_INFORMATION message sent by the selected camera instance. + --]] + function set_video_stream_information() + -- set the Video Stream Information data + local stream_info = mavlink_video_stream_information_t() + + local INSTANCE = 0 + local name = 'Video' + local uri = '127.0.0.1:5600' + + stream_info:framerate(30) + stream_info:bitrate(1500) + stream_info:flags(1) -- VIDEO_STREAM_STATUS_FLAGS_RUNNING + stream_info:resolution_h(1920) + stream_info:resolution_v(1080) + stream_info:rotation(0) + stream_info:hfov(50) + stream_info:stream_id(1) + stream_info:count(1) + stream_info:type(1) -- VIDEO_STREAM_TYPE_RTPUDP + for i = 0, #name do + stream_info:name(i, name:byte(i+1)) + end + for i = 0, #uri do + stream_info:uri(i, uri:byte(i+1)) + end + + camera:set_stream_information(INSTANCE, stream_info) + +end + +return set_video_stream_information() diff --git a/libraries/AP_Scripting/examples/set_target_posvel_circle.lua b/libraries/AP_Scripting/examples/set_target_posvel_circle.lua index 87d4d953826340..3e068faa446a42 100644 --- a/libraries/AP_Scripting/examples/set_target_posvel_circle.lua +++ b/libraries/AP_Scripting/examples/set_target_posvel_circle.lua @@ -8,6 +8,9 @@ -- 3) the vehilce will follow a circle in clockwise direction with increasing speed until ramp_up_time_s time has passed. -- 4) switch out of and into the GUIDED mode any time to restart the trajectory from the start. +---@diagnostic disable: cast-local-type +---@diagnostic disable: redundant-parameter + -- Edit these variables local rad_xy_m = 10.0 -- circle radius in xy plane in m local target_speed_xy_mps = 5.0 -- maximum target speed in m/s diff --git a/libraries/AP_Scripting/examples/ship_vel_match.lua b/libraries/AP_Scripting/examples/ship_vel_match.lua index 38594caed4849b..9ceee3debc00ba 100644 --- a/libraries/AP_Scripting/examples/ship_vel_match.lua +++ b/libraries/AP_Scripting/examples/ship_vel_match.lua @@ -1,5 +1,7 @@ -- support takeoff with velocity matching for quadplanes +---@diagnostic disable: need-check-nil + local PARAM_TABLE_KEY = 35 local PARAM_TABLE_PREFIX = "SHIPV_" diff --git a/libraries/AP_Scripting/examples/sitl_standby_sim.lua b/libraries/AP_Scripting/examples/sitl_standby_sim.lua new file mode 100644 index 00000000000000..1ce2ecacf76650 --- /dev/null +++ b/libraries/AP_Scripting/examples/sitl_standby_sim.lua @@ -0,0 +1,87 @@ +-- This script is a allow to switch the standby function by the switch of the remote controller on 2 simulated fcus. + +-- variable to limit the number of messages sent to GCS +local last_rc_input = 0 + +-- constants +local switch_high = 2 +local switch_low = 0 + +-- Standby function number in ArduPilot +local standby_function = 76 +-- RC pin to use to select the FCU +local rc_input_pin = 8 + + +-- for fast param access it is better to get a param object, +-- this saves the code searching for the param by name every time +local JSON_MASTER = Parameter() +if not JSON_MASTER:init('SIM_JSON_MASTER') then + gcs:send_text(6, 'get SIM_JSON_MASTER failed') +end + +local SYSID_THISMAV = Parameter() +if not SYSID_THISMAV:init('SYSID_THISMAV') then + gcs:send_text(6, 'get SYSID_THISMAV failed') +end + +local sysid = SYSID_THISMAV:get() + +gcs:send_text(6, 'LUA: Standby LUA loaded') + +-- The loop check the value of the switch of the remote controller and switch the standby function of the simulated fcus. +-- FCU should have SYSID_THISMAV set to 1 or 2. +-- The switch is on the channel 8 (default) of the remote controller. +-- fcu1 and fcu2 have mirrored standby function, so only one is active at a time. +-- As this is for simulation, the SIM_JSON_MASTER param is also update to select which fcu control the motors. + +function update() -- this is the loop which periodically runs + rc_input = rc:get_pwm(rc_input_pin) + + if rc_input == nil then + gcs:send_text(6, 'LUA: rc_input is nil') + return update, 1000 -- reschedules the loop + end + + if rc_input ~= last_rc_input then + if sysid == 2 then + if rc_input > 1500 then + if not JSON_MASTER:set(0) then + gcs:send_text(6, string.format('LUA: failed to set SIM_JSON_MASTER')) + else + rc:run_aux_function(standby_function, switch_high) + gcs:send_text(6, string.format('LUA: set SIM_JSON_MASTER to 0')) + end + else + if not JSON_MASTER:set(1) then + gcs:send_text(6, string.format('LUA: failed to set SIM_JSON_MASTER')) + else + rc:run_aux_function(standby_function, switch_low) + gcs:send_text(6, string.format('LUA: set SIM_JSON_MASTER to 1')) + end + end + end + if sysid == 1 then + if rc_input > 1500 then + if not JSON_MASTER:set(0) then + gcs:send_text(6, string.format('LUA: failed to set SIM_JSON_MASTER')) + else + rc:run_aux_function(standby_function, switch_low) + gcs:send_text(6, string.format('LUA: set SIM_JSON_MASTER to 0')) + end + else + if not JSON_MASTER:set(1) then + gcs:send_text(6, string.format('LUA: failed to set SIM_JSON_MASTER')) + else + rc:run_aux_function(standby_function, switch_high) + gcs:send_text(6, string.format('LUA: set SIM_JSON_MASTER to 1')) + end + end + end + last_rc_input = rc_input + end + + return update, 1000 -- reschedules the loop +end + +return update() -- run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/examples/sub_test_synthetic_seafloor.lua b/libraries/AP_Scripting/examples/sub_test_synthetic_seafloor.lua index a7815dec89f7a3..f05b4625b5ac6c 100644 --- a/libraries/AP_Scripting/examples/sub_test_synthetic_seafloor.lua +++ b/libraries/AP_Scripting/examples/sub_test_synthetic_seafloor.lua @@ -8,11 +8,14 @@ -- in the perpendicular direction to define a 2-D height function (h=f(x,y)). -- -- The following Parameters can be set by the test script to control how this driver behaves --- SCR_USER1 is an index into a table of configuration bundles. +-- SCR_USER1 is an index into a table of configuration bundles -- SCR_USER2 is the average bottom depth in meters --- SCR_USER3 is a bit field that controls driver logging. +-- SCR_USER3 is a bit field that controls driver logging +-- SRC_USER4 is the rangefinder target in meters -- +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type local UPDATE_PERIOD_MS = 50 @@ -31,6 +34,8 @@ local RNGFND_STATUS_GOOD = 4 -- Copied from libraries/AP_RangeFinder/AP_RangeFinder.h local SIGNAL_QUALITY_MIN = 0 local SIGNAL_QUALITY_MAX = 100 +-- Copied from ArduSub/mode.h enum Mode::Number {}. +local MODE_SURFTRAK = 21 @@ -534,7 +539,7 @@ local rngfnd_backend local range_model local measurement_noise_func -local signal_quality_noise_func +local signal_quality_func @@ -558,7 +563,7 @@ local function range_finder_driver(sub_loc) -- Generate a simulated range measurement local true_range_m = range_model:get_range(sub_loc) local range_m = measurement_noise_func(true_range_m) - local signal_quality = signal_quality_noise_func(SIGNAL_QUALITY_MAX) + local signal_quality = signal_quality_func(range_m, true_range_m) -- Return this measurement to the range finder backend rf_state:status(RNGFND_STATUS_GOOD) @@ -625,16 +630,7 @@ local function initialize_model() outlier_rate_ops = 0.0, outlier_mean = 0.0, outlier_std_dev = 0.0, - delay_s = 0.0, - callback_interval_ms = UPDATE_PERIOD_MS, - } - - local config_signal_quality_noise = { - mean = 0.0, - std_dev = 0.0, - outlier_rate_ops = 0.0, - outlier_mean = 0.0, - outlier_std_dev = 0.0, + outlier_good_sq_limit = 0.0, delay_s = 0.0, callback_interval_ms = UPDATE_PERIOD_MS, } @@ -647,6 +643,7 @@ local function initialize_model() config_measurement_noise.outlier_rate_ops = .2 config_measurement_noise.outlier_mean = 5 config_measurement_noise.outlier_std_dev = 2 + config_measurement_noise.outlier_good_sq_limit = 1 config_measurement_noise.delay_s = 0.00 end @@ -655,17 +652,15 @@ local function initialize_model() measurement_noise_func = add_noise_funcfactory(config_measurement_noise) - -- Constrain signal quality values - local signal_quality_noise_pre = add_noise_funcfactory(config_signal_quality_noise) - signal_quality_noise_func = function(m) - m = signal_quality_noise_pre(m) - if m > SIGNAL_QUALITY_MAX then + -- A rapid series of large outliers can cause test failure + -- Mark large outliers with a poor signal quality to minimize flakiness + -- This also exercises signal_quality handling + signal_quality_func = function(m, true_m) + if math.abs(m - true_m) > config_measurement_noise.outlier_good_sq_limit then + return 50 + else return SIGNAL_QUALITY_MAX end - if m < SIGNAL_QUALITY_MIN then - return SIGNAL_QUALITY_MIN - end - return m end end @@ -674,6 +669,13 @@ end -- update functions + +-- SCR_USER4 is the rangefinder target in meters +local rf_target_cm = param:get('SCR_USER4') * 100 +if not rf_target_cm or rf_target_cm < 50 or rf_target_cm > 5000 then + rf_target_cm = 1500 +end + local function update_run() local loc_c = ahrs:get_location() @@ -691,6 +693,12 @@ local function update_run() end end + -- Check if we have to set the rangefinder target + if vehicle:get_mode() == MODE_SURFTRAK and sub:get_rangefinder_target_cm() ~= rf_target_cm then + gcs:send_text(6, string.format("Set rangefinder target to %g cm", rf_target_cm)) + sub:set_rangefinder_target_cm(rf_target_cm) + end + -- Update with range finder driver range_finder_driver(loc_c) @@ -714,7 +722,7 @@ local function update_init() initialize_model() - if not range_model or not measurement_noise_func or not signal_quality_noise_func then + if not range_model or not measurement_noise_func or not signal_quality_func then return fatal_error("Could not initialize model") end diff --git a/libraries/AP_Scripting/examples/temperature_sensor.lua b/libraries/AP_Scripting/examples/temperature_sensor.lua new file mode 100644 index 00000000000000..ca3bec775d0a53 --- /dev/null +++ b/libraries/AP_Scripting/examples/temperature_sensor.lua @@ -0,0 +1,18 @@ +--[[ + simple example of reading a temperature sensor +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +--[[ + main update function, called at 1Hz +--]] +function update() + local temperature_C = temperature_sensor:get_temperature(0) + gcs:send_text(MAV_SEVERITY.INFO, string.format("Temperature: %f", temperature_C)) + return update, 1000 +end + +-- start running update loop +return update, 1000 + diff --git a/libraries/AP_Scripting/examples/test_get_target_location.lua b/libraries/AP_Scripting/examples/test_get_target_location.lua new file mode 100644 index 00000000000000..0b22618aeb9496 --- /dev/null +++ b/libraries/AP_Scripting/examples/test_get_target_location.lua @@ -0,0 +1,16 @@ +-- test get_target_location functions for copter +-- https://discuss.ardupilot.org/t/vehicle-get-target-location-in-lua-copter/108901 + +function update() + local next_WP = vehicle:get_target_location() + if not next_WP then + -- not in a flight mode with a target location + gcs:send_text(0,"not in a flight mode with target loc") + else + gcs:send_text(0,"target loc : " .. next_WP:lat() .. " ; " .. next_WP:lng()) + end + + return update, 10000 +end + +return update() diff --git a/libraries/AP_Scripting/examples/test_load.lua b/libraries/AP_Scripting/examples/test_load.lua index f09d6a48274036..1d09e515c486f7 100644 --- a/libraries/AP_Scripting/examples/test_load.lua +++ b/libraries/AP_Scripting/examples/test_load.lua @@ -1,6 +1,7 @@ --[[ test the load function for loading new code from strings --]] +---@diagnostic disable: undefined-global gcs:send_text(0,"Testing load() method") diff --git a/libraries/AP_Scripting/examples/test_update_target_location.lua b/libraries/AP_Scripting/examples/test_update_target_location.lua new file mode 100644 index 00000000000000..90adf7a8d6af8b --- /dev/null +++ b/libraries/AP_Scripting/examples/test_update_target_location.lua @@ -0,0 +1,46 @@ +-- test update_target_location functions for copter + +local current_target = nil +local cur_loc = nil +local new_target= nil + +function update() + + if not (vehicle:get_mode() == 4) then + gcs:send_text(0, "not in Guided") + return update, 1000 + end + + current_target = vehicle:get_target_location() + if not current_target then + return update, 1000 + end + + gcs:send_text(6, string.format("Current target %d %d %d frame %d", current_target:lat(), current_target:lng(), current_target:alt(), current_target:get_alt_frame())) + + cur_loc = ahrs:get_position() + if not cur_loc then + gcs:send_text(0, "current position is not good") + return update, 1000 + end + + gcs:send_text(6, string.format("alt is %f", cur_loc:alt()*0.01)) + if cur_loc:alt()*0.01 < 650 then + gcs:send_text(0, "too low") + return update, 1000 + end + + -- just add some offset to current location + new_target = cur_loc:copy() + new_target:lat(cur_loc:lat() + 1000) + new_target:lng(cur_loc:lng() + 1000) + new_target:alt(cur_loc:alt() + 1000) + + gcs:send_text(6, string.format("New target %d %d %d frame %d", new_target:lat(), new_target:lng(), new_target:alt(), new_target:get_alt_frame())) + + vehicle:update_target_location(current_target, new_target) + + return update, 2000 +end + +return update() diff --git a/libraries/AP_Scripting/examples/wrap32_test.lua b/libraries/AP_Scripting/examples/wrap32_test.lua index 9e088d58cbd518..1ae5e90ffa9cd3 100644 --- a/libraries/AP_Scripting/examples/wrap32_test.lua +++ b/libraries/AP_Scripting/examples/wrap32_test.lua @@ -8,6 +8,8 @@ a script to test handling of 32 bit micros timer wrap with BDShot - BRD_SAFETY_DFLT must be 0 - BDShot must be enabled on outputs 9-12 --]] +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: cast-local-type local PARAM_TABLE_KEY = 138 local PARAM_TABLE_PREFIX = "WRAP32_" diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index c02040c7098d29..0a2653a55b280a 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -53,7 +53,7 @@ singleton AP_AHRS method earth_to_body Vector3f Vector3f singleton AP_AHRS method body_to_earth Vector3f Vector3f singleton AP_AHRS method get_EAS2TAS float singleton AP_AHRS method get_variances boolean float'Null float'Null float'Null Vector3f'Null float'Null -singleton AP_AHRS method set_posvelyaw_source_set void uint8_t 0 2 +singleton AP_AHRS method set_posvelyaw_source_set void AP_NavEKF_Source::SourceSetSelection'enum AP_NavEKF_Source::SourceSetSelection::PRIMARY AP_NavEKF_Source::SourceSetSelection::TERTIARY singleton AP_AHRS method get_vel_innovations_and_variances_for_source boolean uint8_t 3 6 Vector3f'Null Vector3f'Null singleton AP_AHRS method set_home boolean Location singleton AP_AHRS method get_origin boolean Location'Null @@ -61,6 +61,7 @@ singleton AP_AHRS method set_origin boolean Location singleton AP_AHRS method initialised boolean singleton AP_AHRS method get_posvelyaw_source_set uint8_t singleton AP_AHRS method get_quaternion boolean Quaternion'Null +singleton AP_AHRS method handle_external_position_estimate boolean Location float'skip_check uint32_t'skip_check include AP_Arming/AP_Arming.h @@ -70,6 +71,7 @@ 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 arm_force 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'skip_check singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string @@ -94,6 +96,7 @@ singleton AP_BattMonitor depends AP_BATTERY_ENABLED 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() +singleton AP_BattMonitor method get_resistance float uint8_t 0 ud->num_instances() singleton AP_BattMonitor method voltage_resting_estimate float uint8_t 0 ud->num_instances() singleton AP_BattMonitor method current_amps boolean float'Null uint8_t 0 ud->num_instances() singleton AP_BattMonitor method consumed_mah boolean float'Null uint8_t 0 ud->num_instances() @@ -134,6 +137,8 @@ singleton AP_GPS method last_message_time_ms uint32_t uint8_t 0 ud->num_sensors( singleton AP_GPS method have_vertical_velocity boolean uint8_t 0 ud->num_sensors() singleton AP_GPS method get_antenna_offset Vector3f uint8_t 0 ud->num_sensors() singleton AP_GPS method first_unconfigured_gps boolean uint8_t'Null +singleton AP_GPS method gps_yaw_deg boolean uint8_t 0 ud->num_sensors() float'Null float'Null uint32_t'Null +singleton AP_GPS method time_epoch_usec uint64_t uint8_t 0 ud->num_sensors() include AP_Math/AP_Math.h @@ -219,7 +224,7 @@ singleton AP_Proximity method get_backend AP_Proximity_Backend uint8_t'skip_chec include AP_RangeFinder/AP_RangeFinder.h include AP_RangeFinder/AP_RangeFinder_Backend.h -userdata RangeFinder::RangeFinder_State depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +userdata RangeFinder::RangeFinder_State depends AP_RANGEFINDER_ENABLED userdata RangeFinder::RangeFinder_State rename RangeFinder_State userdata RangeFinder::RangeFinder_State field last_reading_ms uint32_t'skip_check read write userdata RangeFinder::RangeFinder_State field last_reading_ms rename last_reading @@ -232,17 +237,17 @@ userdata RangeFinder::RangeFinder_State field signal_quality_pct rename signal_q userdata RangeFinder::RangeFinder_State field voltage_mv uint16_t'skip_check read write userdata RangeFinder::RangeFinder_State field voltage_mv rename voltage -ap_object AP_RangeFinder_Backend depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +ap_object AP_RangeFinder_Backend depends AP_RANGEFINDER_ENABLED ap_object AP_RangeFinder_Backend method distance float ap_object AP_RangeFinder_Backend method signal_quality_pct float ap_object AP_RangeFinder_Backend method signal_quality_pct rename signal_quality ap_object AP_RangeFinder_Backend method orientation Rotation'enum ap_object AP_RangeFinder_Backend method type uint8_t ap_object AP_RangeFinder_Backend method status uint8_t -ap_object AP_RangeFinder_Backend manual handle_script_msg lua_range_finder_handle_script_msg 1 +ap_object AP_RangeFinder_Backend manual handle_script_msg lua_range_finder_handle_script_msg 1 1 ap_object AP_RangeFinder_Backend method get_state void RangeFinder::RangeFinder_State'Ref -singleton RangeFinder depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +singleton RangeFinder depends AP_RANGEFINDER_ENABLED singleton RangeFinder rename rangefinder singleton RangeFinder method num_sensors uint8_t singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1 @@ -279,7 +284,7 @@ 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 depends HAL_GCS_ENABLED +singleton GCS depends (HAL_GCS_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) 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'skip_check int32_t -1 INT32_MAX @@ -294,6 +299,7 @@ singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED = singleton GCS method enable_high_latency_connections void boolean singleton GCS method enable_high_latency_connections depends HAL_HIGH_LATENCY2_ENABLED == 1 +singleton GCS manual run_command_int lua_GCS_command_int 2 1 include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1 singleton AP_ONVIF depends ENABLE_ONVIF == 1 @@ -303,6 +309,9 @@ singleton AP_ONVIF method set_absolutemove boolean float'skip_check float'skip_c singleton AP_ONVIF method get_pan_tilt_limit_min Vector2f singleton AP_ONVIF method get_pan_tilt_limit_max Vector2f +ap_object AP_Vehicle::custom_mode_state depends (!defined(HAL_BUILD_AP_PERIPH)) +ap_object AP_Vehicle::custom_mode_state field allow_entry boolean read write + include AP_Vehicle/AP_Vehicle.h singleton AP_Vehicle depends (!defined(HAL_BUILD_AP_PERIPH)) singleton AP_Vehicle rename vehicle @@ -323,6 +332,7 @@ singleton AP_Vehicle method set_target_posvelaccel_NED boolean Vector3f Vector3f singleton AP_Vehicle method set_target_velaccel_NED boolean Vector3f Vector3f boolean float -360 +360 boolean float'skip_check boolean singleton AP_Vehicle method set_target_velocity_NED boolean Vector3f singleton AP_Vehicle method set_target_angle_and_climbrate boolean float -180 180 float -90 90 float -360 360 float'skip_check boolean float'skip_check +singleton AP_Vehicle method set_target_rate_and_throttle boolean float'skip_check float'skip_check float'skip_check float'skip_check singleton AP_Vehicle method get_circle_radius boolean float'Null singleton AP_Vehicle method set_circle_rate boolean float'skip_check singleton AP_Vehicle method set_steering_and_throttle boolean float -1 1 float -1 1 @@ -344,6 +354,9 @@ singleton AP_Vehicle method has_ekf_failsafed boolean singleton AP_Vehicle method reboot void boolean singleton AP_Vehicle method is_landing boolean singleton AP_Vehicle method is_taking_off boolean +singleton AP_Vehicle method set_crosstrack_start boolean Location +singleton AP_Vehicle method register_custom_mode AP_Vehicle::custom_mode_state uint8_t'skip_check string string + include AP_SerialLED/AP_SerialLED.h singleton AP_SerialLED rename serialLED @@ -369,7 +382,7 @@ singleton SRV_Channels method set_output_norm void SRV_Channel::Aux_servo_functi singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check 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'skip_check singleton SRV_Channels method get_emergency_stop boolean -singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0 +singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0 1 ap_object RC_Channel depends AP_RC_CHANNEL_ENABLED ap_object RC_Channel method norm_input float @@ -390,18 +403,21 @@ singleton RC_Channels method lua_rc_channel RC_Channel uint8_t 1 NUM_RC_CHANNELS 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 - -ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX -ap_object AP_HAL::UARTDriver method read int16_t -ap_object AP_HAL::UARTDriver manual readstring AP_HAL__UARTDriver_readstring 1 -ap_object AP_HAL::UARTDriver method write uint32_t uint8_t'skip_check -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 rename serial -singleton AP_SerialManager depends HAL_GCS_ENABLED -singleton AP_SerialManager method find_serial AP_HAL::UARTDriver AP_SerialManager::SerialProtocol_Scripting'literal uint8_t'skip_check +include AP_Scripting/AP_Scripting_SerialAccess.h +-- don't let user create access objects +userdata AP_Scripting_SerialAccess creation null -1 +userdata AP_Scripting_SerialAccess method begin void uint32_t 1U UINT32_MAX +userdata AP_Scripting_SerialAccess method write uint32_t uint8_t'skip_check +userdata AP_Scripting_SerialAccess manual writestring lua_serial_writestring 1 1 +userdata AP_Scripting_SerialAccess method read int16_t +userdata AP_Scripting_SerialAccess manual readstring lua_serial_readstring 1 1 +userdata AP_Scripting_SerialAccess method available uint32_t +userdata AP_Scripting_SerialAccess method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_RTS_DE + +-- serial is not a real C++ type here, but its name never gets used in C++ as we only have manual methods +singleton serial depends AP_SERIALMANAGER_ENABLED +singleton serial manual find_serial lua_serial_find_serial 1 1 +singleton serial manual find_simulated_device lua_serial_find_simulated_device 2 1 depends AP_SCRIPTING_SERIALDEVICE_ENABLED include AP_Baro/AP_Baro.h singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO)) @@ -411,6 +427,7 @@ singleton AP_Baro method get_temperature float singleton AP_Baro method get_external_temperature float singleton AP_Baro method get_altitude float singleton AP_Baro method healthy boolean uint8_t'skip_check +singleton AP_Baro method get_altitude_difference float float'skip_check float'skip_check include AP_OpticalFlow/AP_OpticalFlow.h singleton AP_OpticalFlow depends AP_OPTICALFLOW_ENABLED @@ -431,16 +448,17 @@ userdata AP_ESC_Telem_Backend::TelemetryData field motor_temp_cdeg int16_t'skip_ singleton AP_ESC_Telem depends HAL_WITH_ESC_TELEM == 1 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 -singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null -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 update_telem_data void uint8_t 0 NUM_SERVO_CHANNELS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check -singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check +singleton AP_ESC_Telem method get_rpm boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_temperature boolean uint8_t'skip_check int16_t'Null +singleton AP_ESC_Telem method get_motor_temperature boolean uint8_t'skip_check int16_t'Null +singleton AP_ESC_Telem method get_current boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_voltage boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t'skip_check uint32_t'Null +singleton AP_ESC_Telem method update_rpm void uint8_t 0 ESC_TELEM_MAX_ESCS uint16_t'skip_check float'skip_check +singleton AP_ESC_Telem method update_telem_data void uint8_t 0 ESC_TELEM_MAX_ESCS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check +singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 ESC_TELEM_MAX_ESCS float'skip_check +singleton AP_ESC_Telem method get_last_telem_data_ms uint32_t uint8_t 0 ESC_TELEM_MAX_ESCS include AP_Param/AP_Param.h singleton AP_Param rename param @@ -457,7 +475,7 @@ singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string fl singleton AP_Param method add_param depends AP_PARAM_DYNAMIC_ENABLED include AP_Scripting/AP_Scripting_helpers.h -userdata Parameter creation lua_new_Parameter 1 +userdata Parameter creation lua_new_Parameter 0 userdata Parameter method init boolean string userdata Parameter method init_by_info boolean uint16_t'skip_check uint32_t'skip_check ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT userdata Parameter method get boolean float'Null @@ -540,8 +558,11 @@ singleton Sub depends APM_BUILD_TYPE(APM_BUILD_ArduSub) singleton Sub method get_and_clear_button_count uint8_t uint8_t 1 4 singleton Sub method is_button_pressed boolean uint8_t 1 4 singleton Sub method rangefinder_alt_ok boolean +singleton Sub method rangefinder_alt_ok depends AP_RANGEFINDER_ENABLED singleton Sub method get_rangefinder_target_cm float +singleton Sub method get_rangefinder_target_cm depends AP_RANGEFINDER_ENABLED singleton Sub method set_rangefinder_target_cm boolean float'skip_check +singleton Sub method set_rangefinder_target_cm depends AP_RANGEFINDER_ENABLED 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 @@ -576,26 +597,30 @@ 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'skip_check uint8_t'skip_check -ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2 +ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2 1 +ap_object AP_HAL::I2CDevice manual transfer AP_HAL__I2CDevice_transfer 2 1 ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1) -global manual Socket lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1) +global manual Socket lua_get_SocketAPM 1 1 depends (AP_NETWORKING_ENABLED==1) +global manual ipv4_addr_to_string SocketAPM_ipv4_addr_to_string 1 1 depends (AP_NETWORKING_ENABLED==1) +global manual string_to_ipv4_addr SocketAPM_string_to_ipv4_addr 1 1 depends (AP_NETWORKING_ENABLED==1) ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1) ap_object SocketAPM method connect boolean string uint16_t'skip_check ap_object SocketAPM method bind boolean string uint16_t'skip_check ap_object SocketAPM method send int32_t string uint32_t'skip_check +ap_object SocketAPM method sendto int32_t string uint32_t'skip_check uint32_t'skip_check uint16_t'skip_check ap_object SocketAPM method listen boolean uint8_t'skip_check ap_object SocketAPM method set_blocking boolean boolean ap_object SocketAPM method is_connected boolean ap_object SocketAPM method pollout boolean uint32_t'skip_check ap_object SocketAPM method pollin boolean uint32_t'skip_check ap_object SocketAPM method reuseaddress boolean -ap_object SocketAPM manual sendfile SocketAPM_sendfile 1 -ap_object SocketAPM manual close SocketAPM_close 0 -ap_object SocketAPM manual recv SocketAPM_recv 1 -ap_object SocketAPM manual accept SocketAPM_accept 1 +ap_object SocketAPM manual sendfile SocketAPM_sendfile 1 1 +ap_object SocketAPM manual close SocketAPM_close 0 0 +ap_object SocketAPM manual recv SocketAPM_recv 1 3 +ap_object SocketAPM manual accept SocketAPM_accept 0 1 ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER) ap_object AP_HAL::AnalogSource method set_pin boolean uint8_t'skip_check @@ -603,7 +628,7 @@ 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 -global manual PWMSource lua_get_PWMSource 0 +global manual PWMSource lua_get_PWMSource 0 1 ap_object AP_HAL::PWMSource method set_pin boolean uint8_t'skip_check "Scripting"'literal ap_object AP_HAL::PWMSource method get_pwm_us uint16_t @@ -615,11 +640,19 @@ singleton hal.gpio method read boolean uint8_t'skip_check singleton hal.gpio method write void uint8_t'skip_check uint8_t 0 1 singleton hal.gpio method toggle void uint8_t'skip_check singleton hal.gpio method pinMode void uint8_t'skip_check uint8_t 0 1 +singleton hal.gpio method get_mode boolean uint8_t'skip_check uint32_t'Null +singleton hal.gpio method get_mode alias getPinFullMode +singleton hal.gpio method set_mode void uint8_t'skip_check uint32_t'skip_check +singleton hal.gpio method set_mode alias setPinFullMode singleton hal.analogin depends !defined(HAL_DISABLE_ADC_DRIVER) singleton hal.analogin rename analog singleton hal.analogin literal singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal +singleton hal.analogin method mcu_temperature float +singleton hal.analogin method mcu_temperature depends HAL_WITH_MCU_MONITORING +singleton hal.analogin method mcu_voltage float +singleton hal.analogin method mcu_voltage depends HAL_WITH_MCU_MONITORING 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 @@ -647,8 +680,8 @@ singleton AP_InertialSensor method get_gyro Vector3f uint8_t'skip_check singleton AP_InertialSensor method get_accel Vector3f uint8_t'skip_check singleton AP_InertialSensor method gyros_consistent boolean uint8_t'skip_check -singleton CAN manual get_device lua_get_CAN_device 1 -singleton CAN manual get_device2 lua_get_CAN_device2 1 +singleton CAN manual get_device lua_get_CAN_device 1 1 +singleton CAN manual get_device2 lua_get_CAN_device2 1 1 singleton CAN depends AP_SCRIPTING_CAN_SENSOR_ENABLED include AP_Scripting/AP_Scripting_CANSensor.h @@ -669,6 +702,9 @@ ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_ ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null ap_object ScriptingCANBuffer method add_filter boolean uint32_t'skip_check uint32_t'skip_check +include AP_DroneCAN/AP_DroneCAN.h +global manual DroneCAN_get_FlexDebug lua_DroneCAN_get_FlexDebug 4 2 depends (HAL_ENABLE_DRONECAN_DRIVERS==1) + 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 rename periph @@ -732,6 +768,12 @@ include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD 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 AC_AttitudeControl/AC_PosControl.h depends APM_BUILD_COPTER_OR_HELI +singleton AC_PosControl depends APM_BUILD_COPTER_OR_HELI +singleton AC_PosControl rename poscontrol +singleton AC_PosControl method set_posvelaccel_offset boolean Vector3f Vector3f Vector3f +singleton AC_PosControl method get_posvelaccel_offset boolean Vector3f'Null Vector3f'Null Vector3f'Null + include APM_Control/AR_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover) singleton AR_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_Rover) singleton AR_AttitudeControl method get_srate void float'Ref float'Ref @@ -754,6 +796,36 @@ singleton AP_Mount method get_angle_target boolean uint8_t'skip_check float'Null singleton AP_Mount method get_location_target boolean uint8_t'skip_check Location'Null singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check +userdata mavlink_camera_information_t depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +userdata mavlink_camera_information_t field time_boot_ms uint32_t'skip_check read write +userdata mavlink_camera_information_t field firmware_version uint32_t'skip_check read write +userdata mavlink_camera_information_t field focal_length float'skip_check read write +userdata mavlink_camera_information_t field sensor_size_h float'skip_check read write +userdata mavlink_camera_information_t field sensor_size_v float'skip_check read write +userdata mavlink_camera_information_t field flags uint32_t'skip_check read write +userdata mavlink_camera_information_t field resolution_h uint16_t'skip_check read write +userdata mavlink_camera_information_t field resolution_v uint16_t'skip_check read write +userdata mavlink_camera_information_t field cam_definition_version uint16_t'skip_check read write +userdata mavlink_camera_information_t field vendor_name'array 32 uint8_t'skip_check read write +userdata mavlink_camera_information_t field model_name'array 32 uint8_t'skip_check read write +userdata mavlink_camera_information_t field lens_id uint8_t'skip_check read write +userdata mavlink_camera_information_t field cam_definition_uri'array 140 uint8_t'skip_check read write +userdata mavlink_camera_information_t field gimbal_device_id uint8_t'skip_check read write + +userdata mavlink_video_stream_information_t depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +userdata mavlink_video_stream_information_t field framerate float'skip_check read write +userdata mavlink_video_stream_information_t field bitrate uint32_t'skip_check read write +userdata mavlink_video_stream_information_t field flags uint16_t'skip_check read write +userdata mavlink_video_stream_information_t field resolution_h uint16_t'skip_check read write +userdata mavlink_video_stream_information_t field resolution_v uint16_t'skip_check read write +userdata mavlink_video_stream_information_t field rotation uint16_t'skip_check read write +userdata mavlink_video_stream_information_t field hfov uint16_t'skip_check read write +userdata mavlink_video_stream_information_t field stream_id uint8_t'skip_check read write +userdata mavlink_video_stream_information_t field count uint8_t'skip_check read write +userdata mavlink_video_stream_information_t field type uint8_t'skip_check read write +userdata mavlink_video_stream_information_t field name'array 32 uint8_t'skip_check read write +userdata mavlink_video_stream_information_t field uri'array 160 uint8_t'skip_check read write + include AP_Camera/AP_Camera.h singleton AP_Camera depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1) singleton AP_Camera rename camera @@ -772,6 +844,11 @@ userdata AP_Camera::camera_state_t field tracking_type uint8_t'skip_check read userdata AP_Camera::camera_state_t field tracking_p1 Vector2f read userdata AP_Camera::camera_state_t field tracking_p2 Vector2f read singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null +singleton AP_Camera method change_setting boolean uint8_t'skip_check CameraSetting'enum CameraSetting::THERMAL_PALETTE CameraSetting::THERMAL_RAW_DATA float'skip_check +singleton AP_Camera method set_camera_information void uint8_t'skip_check mavlink_camera_information_t +singleton AP_Camera method set_camera_information depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED +singleton AP_Camera method set_stream_information void uint8_t'skip_check mavlink_video_stream_information_t +singleton AP_Camera method set_stream_information depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED include AP_Winch/AP_Winch.h singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI @@ -836,52 +913,76 @@ 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'skip_check singleton AP_EFI method get_state void EFI_State'Ref +singleton AP_EFI method get_last_update_ms uint32_t -- ----END EFI Library---- include AP_Logger/AP_Logger.h singleton AP_Logger depends HAL_LOGGING_ENABLED singleton AP_Logger rename logger -singleton AP_Logger manual write AP_Logger_Write 7 +singleton AP_Logger manual write AP_Logger_Write 6 0 singleton AP_Logger method log_file_content void string singleton AP_Logger method log_file_content depends HAL_LOGGER_FILE_CONTENTS_ENABLED -singleton i2c manual get_device lua_get_i2c_device 4 +singleton i2c manual get_device lua_get_i2c_device 4 1 -global manual millis lua_millis 0 -global manual micros lua_micros 0 -global manual mission_receive lua_mission_receive 0 depends AP_MISSION_ENABLED +global manual millis lua_millis 0 1 +global manual micros lua_micros 0 1 +global manual mission_receive lua_mission_receive 0 5 depends AP_MISSION_ENABLED userdata uint32_t creation lua_new_uint32_t 1 -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 operator_getter coerce_to_uint32_t +userdata uint32_t operator + +userdata uint32_t operator - +userdata uint32_t operator * +userdata uint32_t operator / +-- We know name of the generated function so we can point at it again with a manual operator so idiv is the same as div 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 operator % +userdata uint32_t operator & +userdata uint32_t operator | +userdata uint32_t operator ^ +userdata uint32_t operator << +userdata uint32_t operator >> +userdata uint32_t operator == +userdata uint32_t operator < +userdata uint32_t operator <= +userdata uint32_t operator ~ userdata uint32_t manual_operator __tostring uint32_t___tostring -userdata uint32_t manual toint uint32_t_toint 0 -userdata uint32_t manual tofloat uint32_t_tofloat 0 - -global manual dirlist lua_dirlist 1 -global manual remove lua_removefile 1 -global manual print lua_print 1 - -singleton mavlink depends HAL_GCS_ENABLED -singleton mavlink manual init lua_mavlink_init 2 -singleton mavlink manual register_rx_msgid lua_mavlink_register_rx_msgid 1 -singleton mavlink manual send_chan lua_mavlink_send_chan 3 -singleton mavlink manual receive_chan lua_mavlink_receive_chan 0 -singleton mavlink manual block_command lua_mavlink_block_command 1 +userdata uint32_t manual toint uint32_t_toint 0 1 +userdata uint32_t manual tofloat uint32_t_tofloat 0 1 + +userdata uint64_t creation lua_new_uint64_t 2 +userdata uint64_t operator_getter coerce_to_uint64_t +userdata uint64_t operator + +userdata uint64_t operator - +userdata uint64_t operator * +userdata uint64_t operator / +userdata uint64_t operator % +userdata uint64_t operator & +userdata uint64_t operator | +userdata uint64_t operator ^ +userdata uint64_t operator << +userdata uint64_t operator >> +userdata uint64_t operator == +userdata uint64_t operator < +userdata uint64_t operator <= +userdata uint64_t operator ~ +userdata uint64_t manual_operator __tostring uint64_t___tostring +userdata uint64_t manual toint uint64_t_toint 0 1 +userdata uint64_t manual tofloat uint64_t_tofloat 0 1 +userdata uint64_t manual split uint64_t_split 0 2 + +global manual dirlist lua_dirlist 1 2 +global manual remove lua_removefile 1 3 +global manual print lua_print 1 0 + +singleton mavlink depends (HAL_GCS_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) +singleton mavlink manual init lua_mavlink_init 2 0 +singleton mavlink manual register_rx_msgid lua_mavlink_register_rx_msgid 1 1 +singleton mavlink manual send_chan lua_mavlink_send_chan 3 1 +singleton mavlink manual receive_chan lua_mavlink_receive_chan 0 3 +singleton mavlink manual block_command lua_mavlink_block_command 1 1 include AC_Fence/AC_Fence.h depends AP_FENCE_ENABLED include AC_Fence/AC_Fence_config.h @@ -930,3 +1031,9 @@ singleton AP_VisualOdom depends HAL_VISUALODOM_ENABLED singleton AP_VisualOdom rename visual_odom singleton AP_VisualOdom method healthy boolean singleton AP_VisualOdom method quality int8_t + +-- ----AP_TemperatureSensor Library---- +include AP_TemperatureSensor/AP_TemperatureSensor.h +singleton AP_TemperatureSensor depends AP_TEMPERATURE_SENSOR_ENABLED +singleton AP_TemperatureSensor rename temperature_sensor +singleton AP_TemperatureSensor method get_temperature boolean float'Null uint8_t'skip_check diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index d0ce2c7fcf69a4..92278a34a1273c 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -31,6 +31,7 @@ char keyword_manual[] = "manual"; char keyword_global[] = "global"; char keyword_creation[] = "creation"; char keyword_manual_operator[] = "manual_operator"; +char keyword_operator_getter[] = "operator_getter"; // attributes (should include the leading ' ) char keyword_attr_enum[] = "'enum"; @@ -137,7 +138,17 @@ enum operator_type { OP_SUB = (1U << 1), OP_MUL = (1U << 2), OP_DIV = (1U << 3), - OP_MANUAL = (1U << 4), + OP_MOD = (1U << 4), + OP_BAND = (1U << 5), + OP_BOR = (1U << 6), + OP_BXOR = (1U << 7), + OP_SHL = (1U << 8), + OP_SHR = (1U << 9), + OP_EQ = (1U << 10), + OP_LT = (1U << 11), + OP_LE = (1U << 12), + OP_BNOT = (1U << 13), + OP_MANUAL = (1U << 14), OP_LAST }; @@ -367,6 +378,7 @@ struct method_alias { char *alias; int line; int num_args; + int num_ret; enum alias_type type; char *dependency; }; @@ -409,6 +421,7 @@ struct userdata { char *dependency; char *creation; // name of a manual creation function if set, note that this will not be used internally int creation_args; // number of args for custom creation function + char *operator_getter; // Custom function to get values for use in operators }; static struct userdata *parsed_userdata; @@ -887,6 +900,12 @@ void handle_manual(struct userdata *node, enum alias_type type) { error(ERROR_SINGLETON, "Expected number of args for manual method %s %s", node->name, name); } alias->num_args = atoi(num_args); + + char *num_ret = next_token(); + if (num_ret == NULL) { + error(ERROR_SINGLETON, "Expected number of returns for manual method %s %s", node->name, name); + } + alias->num_ret = atoi(num_ret); } char *depends_keyword = next_token(); @@ -927,6 +946,26 @@ void handle_operator(struct userdata *data) { operation = OP_MUL; } else if (strcmp(operator, "/") == 0) { operation = OP_DIV; + } else if (strcmp(operator, "%") == 0) { + operation = OP_MOD; + } else if (strcmp(operator, "&") == 0) { + operation = OP_BAND; + } else if (strcmp(operator, "|") == 0) { + operation = OP_BOR; + } else if (strcmp(operator, "^") == 0) { + operation = OP_BXOR; + } else if (strcmp(operator, "<<") == 0) { + operation = OP_SHL; + } else if (strcmp(operator, ">>") == 0) { + operation = OP_SHR; + } else if (strcmp(operator, "==") == 0) { + operation = OP_EQ; + } else if (strcmp(operator, "<") == 0) { + operation = OP_LT; + } else if (strcmp(operator, "<=") == 0) { + operation = OP_LE; + } else if (strcmp(operator, "~") == 0) { + operation = OP_BNOT; } else { error(ERROR_USERDATA, "Unknown operation type: %s", operator); } @@ -1025,6 +1064,16 @@ void handle_userdata(void) { handle_manual(node, ALIAS_TYPE_MANUAL_OPERATOR); node->operations |= OP_MANUAL; + } else if (strcmp(type, keyword_operator_getter) == 0) { + if (node->operator_getter != NULL) { + error(ERROR_USERDATA, "Userdata only support a single getter string"); + } + char *name = next_token(); + if (name == NULL) { + error(ERROR_USERDATA, "Expected a getter string for %s",node->name); + } + string_copy(&(node->operator_getter), name); + } else { error(ERROR_USERDATA, "Unknown or unsupported type for userdata: %s", type); } @@ -1173,8 +1222,11 @@ void handle_ap_object(void) { } else if (strcmp(type, keyword_manual) == 0) { handle_manual(node, ALIAS_TYPE_MANUAL); + } else if (strcmp(type, keyword_field) == 0) { + handle_userdata_field(node); + } else { - error(ERROR_SINGLETON, "AP_Objects only support renames, methods, semaphore or manual keywords (got %s)", type); + error(ERROR_SINGLETON, "AP_Objects only support renames, methods, field, semaphore or manual keywords (got %s)", type); } // check that we didn't just add 2 singleton flags @@ -1253,13 +1305,12 @@ void emit_userdata_allocators(void) { while (node) { start_dependency(source, node->dependency); // New method used internally - fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name); - fprintf(source, " luaL_checkstack(L, 2, \"Out of stack\");\n"); // ensure we have sufficent stack to push the return + fprintf(source, "%s * new_%s(lua_State *L) {\n", node->name, node->sanatized_name); fprintf(source, " void *ud = lua_newuserdata(L, sizeof(%s));\n", node->name); fprintf(source, " new (ud) %s();\n", 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, " return (%s *)ud;\n", node->name); fprintf(source, "}\n"); // New method used externally, includes argcheck, overridden by custom creation function if provided @@ -1273,7 +1324,8 @@ void emit_userdata_allocators(void) { fprintf(source, " warned = true;\n"); fprintf(source, " }\n"); - fprintf(source, " return new_%s(L);\n", node->sanatized_name); + fprintf(source, " new_%s(L);\n", node->sanatized_name); + fprintf(source, " return 1;\n"); fprintf(source, "}\n"); } @@ -1287,8 +1339,8 @@ void emit_ap_object_allocators(void) { struct userdata * node = parsed_ap_objects; while (node) { start_dependency(source, node->dependency); - fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name); - fprintf(source, " return new_ap_object(L, sizeof(%s *), \"%s\");\n", node->name, node->name); + fprintf(source, "%s ** new_%s(lua_State *L) {\n", node->name, node->sanatized_name); + fprintf(source, " return (%s **)new_ap_object(L, sizeof(%s *), \"%s\");\n", node->name, node->name, node->name); fprintf(source, "}\n"); end_dependency(source, node->dependency); fprintf(source, "\n"); @@ -1301,8 +1353,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->rename ? node->rename : node->name); - fprintf(source, " return (%s *)data;\n", node->name); + fprintf(source, " return (%s *)luaL_checkudata(L, arg, \"%s\");\n", node->name, node->rename ? node->rename : node->name); fprintf(source, "}\n"); end_dependency(source, node->dependency); fprintf(source, "\n"); @@ -1315,13 +1366,7 @@ void emit_ap_object_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, " %s ** data = (%s**)luaL_checkudata(L, arg, \"%s\");\n", node->name, node->name, node->name); - fprintf(source, " %s * ud = *data;\n", node->name); - fprintf(source, " if (ud == NULL) {\n"); - fprintf(source, " // This error will never return, so there is no danger of returning a NULL\n"); - fprintf(source, " luaL_error(L, \"Internal error, null pointer\");\n"); - fprintf(source, " }\n"); - fprintf(source, " return data;\n"); + fprintf(source, " return (%s **)check_ap_object(L, arg, \"%s\");\n", node->name, node->name); fprintf(source, "}\n"); end_dependency(source, node->dependency); fprintf(source, "\n"); @@ -1353,7 +1398,7 @@ void emit_userdata_declarations(void) { struct userdata * node = parsed_userdata; while (node) { start_dependency(header, node->dependency); - fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name); + fprintf(header, "%s * new_%s(lua_State *L);\n", node->name, node->sanatized_name); if (node->creation == NULL) { fprintf(header, "int lua_new_%s(lua_State *L);\n", node->sanatized_name); } @@ -1367,7 +1412,7 @@ void emit_ap_object_declarations(void) { struct userdata * node = parsed_ap_objects; while (node) { start_dependency(header, node->dependency); - fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name); + fprintf(header, "%s ** new_%s(lua_State *L);\n", node->name, node->sanatized_name); fprintf(header, "%s ** check_%s(lua_State *L, int arg);\n", node->name, node->sanatized_name); end_dependency(header, node->dependency); node = node->next; @@ -1693,8 +1738,7 @@ void emit_field(const struct userdata_field *field, const char* object_name, con fprintf(source, "%slua_pushinteger(L, static_cast(%s%s%s%s));\n", indent, object_name, object_access, field->name, index_string); break; case TYPE_UINT32_T: - fprintf(source, "%snew_uint32_t(L);\n", indent); - fprintf(source, "%s*static_cast(luaL_checkudata(L, -1, \"uint32_t\")) = %s%s%s%s;\n", indent, object_name, object_access, field->name, index_string); + fprintf(source, "%s*new_uint32_t(L) = %s%s%s%s;\n", indent, object_name, object_access, field->name, index_string); break; case TYPE_NONE: error(ERROR_INTERNAL, "Can't access a NONE field"); @@ -1706,9 +1750,7 @@ void emit_field(const struct userdata_field *field, const char* object_name, con fprintf(source, "%slua_pushstring(L, %s%s%s%s);\n", indent, object_name, object_access, field->name, index_string); break; case TYPE_USERDATA: - // userdatas must allocate a new container to return - fprintf(source, "%snew_%s(L);\n", indent, field->type.data.ud.sanatized_name); - fprintf(source, "%s*check_%s(L, -1) = %s%s%s%s;\n", indent, field->type.data.ud.sanatized_name, object_name, object_access, field->name, index_string); + fprintf(source, "%s*new_%s(L) = %s%s%s%s;\n", indent, field->type.data.ud.sanatized_name, object_name, object_access, field->name, index_string); break; case TYPE_AP_OBJECT: // FIXME: collapse the identical cases here, and use the type string function error(ERROR_USERDATA, "AP_Object does not currently support access to userdata field's"); @@ -1731,7 +1773,7 @@ void emit_field(const struct userdata_field *field, const char* object_name, con if (use_switch) { fprintf(source, " default:\n"); - fprintf(source, " return luaL_argerror(L, lua_gettop(L), \"too many arguments\");\n"); + fprintf(source, " return field_argerror(L); // too many arguments\n"); fprintf(source, " }\n"); } @@ -1791,13 +1833,46 @@ void emit_singleton_fields() { } } +void emit_ap_object_field(const struct userdata *data, const struct userdata_field *field) { + fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, field->name); + fprintf(source, " %s *ud = *check_%s(L, 1);\n", data->name, data->sanatized_name); + emit_field(field, "ud", "->"); +} + +void emit_ap_object_fields() { + struct userdata * node = parsed_ap_objects; + while(node) { + struct userdata_field *field = node->fields; + if (field) { + start_dependency(source, node->dependency); + while(field) { + emit_ap_object_field(node, field); + field = field->next; + } + end_dependency(source, node->dependency); + } + node = node->next; + } +} + // emit refences functions for a call, return the number of arduments added int emit_references(const struct argument *arg, const char * tab) { int arg_index = NULLABLE_ARG_COUNT_BASE + 2; int return_count = 0; + // count arguments to return so we know if we need to check the stack + const struct argument *count_arg = arg; + while (count_arg != NULL) { + if (count_arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE)) { + return_count++; + } + count_arg = count_arg->next; + } + // add one to have a spare stack slot for userdata creation funcs + fprintf(source, "#if %d > LUA_MINSTACK\n", return_count+1); + fprintf(source, "%sluaL_checkstack(L, %d, nullptr);\n", tab, return_count+1); + fprintf(source, "#endif\n\n"); while (arg != NULL) { if (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE)) { - return_count++; switch (arg->type.type) { case TYPE_BOOLEAN: fprintf(source, "%slua_pushboolean(L, data_%d);\n", tab, arg_index); @@ -1814,16 +1889,13 @@ int emit_references(const struct argument *arg, const char * tab) { fprintf(source, "%slua_pushinteger(L, data_%d);\n", tab, arg_index); break; case TYPE_UINT32_T: - fprintf(source, "%snew_uint32_t(L);\n", tab); - fprintf(source, "%s*static_cast(luaL_checkudata(L, -1, \"uint32_t\")) = data_%d;\n", tab, arg_index); + fprintf(source, "%s*new_uint32_t(L) = data_%d;\n", tab, arg_index); break; case TYPE_STRING: fprintf(source, "%slua_pushstring(L, data_%d);\n", tab, arg_index); break; case TYPE_USERDATA: - // userdatas must allocate a new container to return - fprintf(source, "%snew_%s(L);\n", tab, arg->type.data.ud.sanatized_name); - fprintf(source, "%s*check_%s(L, -1) = data_%d;\n", tab, arg->type.data.ud.sanatized_name, arg_index); + fprintf(source, "%s*new_%s(L) = data_%d;\n", tab, arg->type.data.ud.sanatized_name, arg_index); break; case TYPE_NONE: error(ERROR_INTERNAL, "Attempted to emit a nullable or reference argument of type none"); @@ -1853,11 +1925,6 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth // emit comments on expected arg/type struct argument *arg = method->arguments; - if ((data->ud_type == UD_SINGLETON) && !(data->flags & UD_FLAG_LITERAL)) { - // fetch and check the singleton pointer - fprintf(source, " %s * ud = check_%s(L);\n", data->name, data->sanatized_name); - } - // emit warning if configured if (method->deprecate != NULL) { fprintf(source, " static bool warned = false;\n"); @@ -1867,7 +1934,6 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth fprintf(source, " }\n\n"); } - // sanity check number of args called with arg_count = 1; while (arg != NULL) { @@ -1884,8 +1950,12 @@ 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: + if (!(data->flags & UD_FLAG_LITERAL)) { + // fetch and check the singleton pointer + fprintf(source, " %s * ud = check_%s(L);\n", data->name, data->sanatized_name); + } + break; case UD_GLOBAL: - // this was bound early break; case UD_AP_OBJECT: // extract the userdata, it was a pointer, so we need to grab it @@ -2091,23 +2161,19 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth fprintf(source, " lua_pushinteger(L, data);\n"); break; case TYPE_UINT32_T: - fprintf(source, " new_uint32_t(L);\n"); - fprintf(source, " *static_cast(luaL_checkudata(L, -1, \"uint32_t\")) = data;\n"); + fprintf(source, " *new_uint32_t(L) = data;\n"); break; case TYPE_STRING: fprintf(source, " lua_pushstring(L, data);\n"); break; case TYPE_USERDATA: - // userdatas must allocate a new container to return - fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name); - fprintf(source, " *check_%s(L, -1) = data;\n", method->return_type.data.ud.sanatized_name); + fprintf(source, " *new_%s(L) = data;\n", method->return_type.data.ud.sanatized_name); break; case TYPE_AP_OBJECT: fprintf(source, " if (data == NULL) {\n"); fprintf(source, " return 0;\n"); fprintf(source, " }\n"); - fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name); - fprintf(source, " *(%s**)luaL_checkudata(L, -1, \"%s\") = data;\n", method->return_type.data.ud.name, method->return_type.data.ud.name); + fprintf(source, " *new_%s(L) = data;\n", method->return_type.data.ud.sanatized_name); break; case TYPE_NONE: case TYPE_LITERAL: @@ -2135,10 +2201,28 @@ const char * get_name_for_operation(enum operator_type op) { return "__sub"; case OP_MUL: return "__mul"; - break; case OP_DIV: return "__div"; - break; + case OP_MOD: + return "__mod"; + case OP_BAND: + return "__band"; + case OP_BOR: + return "__bor"; + case OP_BXOR: + return "__bxor"; + case OP_SHL: + return "__shl"; + case OP_SHR: + return "__shr"; + case OP_EQ: + return "__eq"; + case OP_LT: + return "__lt"; + case OP_LE: + return "__le"; + case OP_BNOT: + return "__bnot"; case OP_MANUAL: case OP_LAST: return NULL; @@ -2146,6 +2230,93 @@ const char * get_name_for_operation(enum operator_type op) { return NULL; } +const char * get_sym_for_operation(enum operator_type op) { + switch (op) { + case OP_ADD: + return "+"; + case OP_SUB: + return "-"; + case OP_MUL: + return "*"; + case OP_DIV: + return "/"; + case OP_MOD: + return "%"; + case OP_BAND: + return "&"; + case OP_BOR: + return "|"; + case OP_BXOR: + return "^"; + case OP_SHL: + return "<<"; + case OP_SHR: + return ">>"; + case OP_EQ: + return "=="; + case OP_LT: + return "<"; + case OP_LE: + return "<="; + case OP_BNOT: + return "~"; + case OP_MANUAL: + case OP_LAST: + return NULL; + } + return NULL; +} + +int operation_is_bool(enum operator_type op) { + switch (op) { + case OP_ADD: + case OP_SUB: + case OP_MUL: + case OP_DIV: + case OP_MOD: + case OP_BAND: + case OP_BOR: + case OP_BXOR: + case OP_SHL: + case OP_SHR: + case OP_BNOT: + case OP_MANUAL: + case OP_LAST: + return FALSE; + + case OP_EQ: + case OP_LT: + case OP_LE: + return TRUE; + } + return FALSE; +} + +int operation_is_unary(enum operator_type op) { + switch (op) { + case OP_ADD: + case OP_SUB: + case OP_MUL: + case OP_DIV: + case OP_MOD: + case OP_BAND: + case OP_BOR: + case OP_BXOR: + case OP_SHL: + case OP_SHR: + case OP_EQ: + case OP_LT: + case OP_LE: + case OP_MANUAL: + case OP_LAST: + return FALSE; + + case OP_BNOT: + return TRUE; + } + return FALSE; +} + void emit_operators(struct userdata *data) { trace(TRACE_USERDATA, "Emitting operators for %s", data->name); @@ -2154,39 +2325,50 @@ void emit_operators(struct userdata *data) { start_dependency(source, data->dependency); for (uint32_t i = 1; i < OP_LAST; i = (i << 1)) { - const char * op_name = get_name_for_operation((data->operations) & i); + const enum operator_type type = (data->operations) & i; + + const char * op_name = get_name_for_operation(type); if (op_name == NULL) { continue; } - char op_sym; - switch ((data->operations) & i) { - case OP_ADD: - op_sym = '+'; - break; - case OP_SUB: - op_sym = '-'; - break; - case OP_MUL: - op_sym = '*'; - break; - case OP_DIV: - op_sym = '/'; - break; - case OP_MANUAL: - case OP_LAST: - return; + const char * op_sym = get_sym_for_operation(type); + if (op_sym == NULL) { + error(ERROR_USERDATA, "No symbol for %s operation %u", data->name, type); } + // The generated check functions return pointers, the manual getters return a value directly + const int have_getter = data->operator_getter != NULL; + const char * access = have_getter ? "" : "*"; + const char * getter_prefix = have_getter ? "" : "check_"; + const char * getter = have_getter ? data->operator_getter : data->sanatized_name; + fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, op_name); // check number of arguments fprintf(source, " binding_argcheck(L, 2);\n"); // check the pointers - fprintf(source, " %s *ud = check_%s(L, 1);\n", data->name, data->sanatized_name); - fprintf(source, " %s *ud2 = check_%s(L, 2);\n", data->name, data->sanatized_name); - // create a container for the result - fprintf(source, " new_%s(L);\n", data->sanatized_name); - fprintf(source, " *check_%s(L, -1) = *ud %c *ud2;\n", data->sanatized_name, op_sym); + fprintf(source, " %s %sud = %s%s(L, 1);\n", data->name, access, getter_prefix, getter); + + if (!operation_is_unary(type)) { + // Need two values + fprintf(source, " %s %sud2 = %s%s(L, 2);\n", data->name, access, getter_prefix, getter); + + if (operation_is_bool(type)) { + // Return bool + fprintf(source, " lua_pushboolean(L, (%sud) %s (%sud2));\n", access, op_sym, access); + + } else { + // Return same type + // create a container for the result + fprintf(source, " *new_%s(L) = (%sud) %s (%sud2);\n", data->sanatized_name, access, op_sym, access); + } + + } else { + // Only a single value, lua pushes the same value onto the stack twice, so we still check for 2 arguments + fprintf(source, " *new_%s(L) = %s (%sud);\n", data->sanatized_name, op_sym, access); + + } + // return the first pointer fprintf(source, " return 1;\n"); fprintf(source, "}\n\n"); @@ -2214,7 +2396,7 @@ void emit_methods(struct userdata *node) { } void emit_enum(struct userdata * data) { - fprintf(source, "struct userdata_enum %s_enums[] = {\n", data->sanatized_name); + fprintf(source, "const struct userdata_enum %s_enums[] = {\n", data->sanatized_name); struct userdata_enum *ud_enum = data->enums; while (ud_enum != NULL) { fprintf(source, " {\"%s\", %s::%s},\n", ud_enum->name, data->name, ud_enum->name); @@ -2247,11 +2429,13 @@ void emit_index(struct userdata *head) { struct method_alias *alias = node->method_aliases; while(alias) { + start_dependency(source, alias->dependency); 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); } + end_dependency(source, alias->dependency); alias = alias->next; } @@ -2282,15 +2466,11 @@ void emit_index(struct userdata *head) { } fprintf(source, "static int %s_index(lua_State *L) {\n", node->sanatized_name); - fprintf(source, " const char * name = luaL_checkstring(L, 2);\n"); - fprintf(source, " if (load_function(L,%s_meta,ARRAY_SIZE(%s_meta),name)",node->sanatized_name,node->sanatized_name); + fprintf(source, " return load_function(L,%s_meta,ARRAY_SIZE(%s_meta))",node->sanatized_name,node->sanatized_name); if (node->enums != NULL) { - fprintf(source, " || load_enum(L,%s_enums,ARRAY_SIZE(%s_enums),name)",node->sanatized_name,node->sanatized_name); + fprintf(source, " || load_enum(L,%s_enums,ARRAY_SIZE(%s_enums))",node->sanatized_name,node->sanatized_name); } - fprintf(source, ") {\n"); - fprintf(source, " return 1;\n"); - fprintf(source, " }\n"); - fprintf(source, " return 0;\n"); + fprintf(source, ";\n"); fprintf(source, "}\n"); end_dependency(source, node->dependency); fprintf(source, "\n"); @@ -2330,68 +2510,75 @@ void emit_loaders(void) { emit_type_index(parsed_singletons, "singleton"); emit_type_index(parsed_ap_objects, "ap_object"); + fprintf(source, "static int binding_index(lua_State *L) {\n"); + fprintf(source, " const char * name = luaL_checkstring(L, 2);\n"); + fprintf(source, "\n"); + fprintf(source, " bool found = false;\n"); + fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(singleton_fun); i++) {\n"); + fprintf(source, " if (strcmp(name, singleton_fun[i].name) == 0) {\n"); + fprintf(source, " lua_newuserdata(L, 0);\n"); + fprintf(source, " if (luaL_newmetatable(L, name)) { // need to create metatable\n"); + fprintf(source, " lua_pushcfunction(L, singleton_fun[i].func);\n"); + fprintf(source, " lua_setfield(L, -2, \"__index\");\n"); + fprintf(source, " }\n"); + fprintf(source, " lua_setmetatable(L, -2);\n"); + fprintf(source, " found = true;\n"); + fprintf(source, " break;\n"); + fprintf(source, " }\n"); + fprintf(source, " }\n"); + fprintf(source, " if (!found) {\n"); + fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(new_userdata); i++) {\n"); + fprintf(source, " if (strcmp(name, new_userdata[i].name) == 0) {\n"); + fprintf(source, " lua_pushcfunction(L, new_userdata[i].fun);\n"); + fprintf(source, " found = true;\n"); + fprintf(source, " break;\n"); + fprintf(source, " }\n"); + fprintf(source, " }\n"); + fprintf(source, " }\n"); + fprintf(source, " if (!found) {\n"); + fprintf(source, " return 0;\n"); + fprintf(source, " }\n"); + fprintf(source, "\n"); + fprintf(source, " // store found value to avoid a re-index\n"); + fprintf(source, " lua_pushvalue(L, -2);\n"); + fprintf(source, " lua_pushvalue(L, -2);\n"); + fprintf(source, " lua_settable(L, -5);\n"); + fprintf(source, "\n"); + fprintf(source, " return 1;\n"); + fprintf(source, "}\n\n"); + fprintf(source, "void load_generated_bindings(lua_State *L) {\n"); - fprintf(source, " luaL_checkstack(L, 5, \"Out of stack\");\n"); // this is more stack space then we need, but should never fail + fprintf(source, " luaL_checkstack(L, 5, nullptr);\n"); // this is more stack space then we need, but should never fail fprintf(source, " // userdata metatables\n"); fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(userdata_fun); i++) {\n"); fprintf(source, " luaL_newmetatable(L, userdata_fun[i].name);\n"); - fprintf(source, " lua_pushcclosure(L, userdata_fun[i].func, 0);\n"); + fprintf(source, " lua_pushcfunction(L, userdata_fun[i].func);\n"); fprintf(source, " lua_setfield(L, -2, \"__index\");\n"); fprintf(source, " if (userdata_fun[i].operators != nullptr) {\n"); fprintf(source, " luaL_setfuncs(L, userdata_fun[i].operators, 0);\n"); fprintf(source, " }\n"); - fprintf(source, " lua_pushstring(L, \"__call\");\n"); - fprintf(source, " lua_pushvalue(L, -2);\n"); - fprintf(source, " lua_settable(L, -3);\n"); - fprintf(source, " lua_pop(L, 1);\n"); - fprintf(source, " lua_newuserdata(L, 0);\n"); - fprintf(source, " luaL_getmetatable(L, userdata_fun[i].name);\n"); - fprintf(source, " lua_setmetatable(L, -2);\n"); - fprintf(source, " lua_setglobal(L, userdata_fun[i].name);\n"); fprintf(source, " }\n"); fprintf(source, "\n"); fprintf(source, " // ap object metatables\n"); fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(ap_object_fun); i++) {\n"); fprintf(source, " luaL_newmetatable(L, ap_object_fun[i].name);\n"); - fprintf(source, " lua_pushcclosure(L, ap_object_fun[i].func, 0);\n"); + fprintf(source, " lua_pushcfunction(L, ap_object_fun[i].func);\n"); fprintf(source, " lua_setfield(L, -2, \"__index\");\n"); - fprintf(source, " lua_pushstring(L, \"__call\");\n"); - fprintf(source, " lua_pushvalue(L, -2);\n"); - fprintf(source, " lua_settable(L, -3);\n"); fprintf(source, " lua_pop(L, 1);\n"); - fprintf(source, " lua_newuserdata(L, 0);\n"); - fprintf(source, " luaL_getmetatable(L, ap_object_fun[i].name);\n"); - fprintf(source, " lua_setmetatable(L, -2);\n"); - fprintf(source, " lua_setglobal(L, ap_object_fun[i].name);\n"); fprintf(source, " }\n"); fprintf(source, "\n"); - fprintf(source, " // singleton metatables\n"); - fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(singleton_fun); i++) {\n"); - fprintf(source, " luaL_newmetatable(L, singleton_fun[i].name);\n"); - fprintf(source, " lua_pushcclosure(L, singleton_fun[i].func, 0);\n"); - fprintf(source, " lua_setfield(L, -2, \"__index\");\n"); - fprintf(source, " lua_pushstring(L, \"__call\");\n"); - fprintf(source, " lua_pushvalue(L, -2);\n"); - fprintf(source, " lua_settable(L, -3);\n"); - - fprintf(source, " lua_pop(L, 1);\n"); - fprintf(source, " lua_newuserdata(L, 0);\n"); - fprintf(source, " luaL_getmetatable(L, singleton_fun[i].name);\n"); - fprintf(source, " lua_setmetatable(L, -2);\n"); - fprintf(source, " lua_setglobal(L, singleton_fun[i].name);\n"); - fprintf(source, " }\n"); + fprintf(source, " // singletons and userdata creation funcs are loaded dynamically\n"); - fprintf(source, "\n"); fprintf(source, "}\n\n"); } -void emit_sandbox(void) { +void emit_userdata_new_funcs(void) { struct userdata *data = parsed_userdata; fprintf(source, "const struct userdata {\n"); fprintf(source, " const char *name;\n"); @@ -2401,8 +2588,8 @@ void emit_sandbox(void) { // Dont expose creation function for all read only items int expose_creation = FALSE; if (data->creation || data->methods) { - // Custom creation or methods - expose_creation = TRUE; + // Custom creation or methods, if not specifically disabled + expose_creation = !(data->creation && data->creation_args == -1); } else { // Feilds only struct userdata_field * field = data->fields; @@ -2440,23 +2627,14 @@ void emit_sandbox(void) { } } fprintf(source, "};\n\n"); +} +void emit_sandbox(void) { fprintf(source, "void load_generated_sandbox(lua_State *L) {\n"); - // load the singletons - fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(singleton_fun); i++) {\n"); - fprintf(source, " lua_pushstring(L, singleton_fun[i].name);\n"); - fprintf(source, " lua_getglobal(L, singleton_fun[i].name);\n"); - fprintf(source, " lua_settable(L, -3);\n"); - fprintf(source, " }\n"); - - // 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"); - fprintf(source, " lua_settable(L, -3);\n"); - fprintf(source, " }\n"); - - fprintf(source, "\n"); + fprintf(source, " lua_createtable(L, 0, 1);\n"); + fprintf(source, " lua_pushcfunction(L, binding_index);\n"); + fprintf(source, " lua_setfield(L, -2, \"__index\");\n"); + fprintf(source, " lua_setmetatable(L, -2);\n"); fprintf(source, "}\n"); } @@ -2473,6 +2651,10 @@ void emit_argcheck_helper(void) { fprintf(source, " return 0;\n"); fprintf(source, "}\n\n"); + fprintf(source, "int field_argerror(lua_State *L) {\n"); + fprintf(source, " return binding_argcheck(L, -1); // force too many args error\n"); + fprintf(source, "}\n\n"); + // emit warning if augments are parsed fprintf(source, "bool userdata_zero_arg_check(lua_State *L) {\n"); fprintf(source, " if (lua_gettop(L) == 0) {\n"); @@ -2542,12 +2724,19 @@ void emit_argcheck_helper(void) { fprintf(source, " return lua_unint32;\n"); fprintf(source, "}\n\n"); - fprintf(source, "int new_ap_object(lua_State *L, size_t size, const char * name) {\n"); - fprintf(source, " luaL_checkstack(L, 2, \"Out of stack\");\n"); - fprintf(source, " lua_newuserdata(L, size);\n"); + fprintf(source, "void * new_ap_object(lua_State *L, size_t size, const char * name) {\n"); + fprintf(source, " void * ud = lua_newuserdata(L, size);\n"); fprintf(source, " luaL_getmetatable(L, name);\n"); fprintf(source, " lua_setmetatable(L, -2);\n"); - fprintf(source, " return 1;\n"); + fprintf(source, " return ud;\n"); + fprintf(source, "}\n\n"); + + fprintf(source, "void ** check_ap_object(lua_State *L, int arg_num, const char * name) {\n"); + fprintf(source, " void ** data = (void **)luaL_checkudata(L, arg_num, name);\n"); + fprintf(source, " if (*data == NULL) {\n"); + fprintf(source, " luaL_error(L, \"internal error: %%s is null\", name); // does not return\n"); + fprintf(source, " }\n"); + fprintf(source, " return data;\n"); fprintf(source, "}\n\n"); } @@ -2608,6 +2797,22 @@ void emit_docs_type(struct type type, const char *prefix, const char *suffix) { } } +void emit_docs_param_type(struct type type, const char *prefix, const char *suffix) { + if (type.type == TYPE_UINT32_T) { + // we will try and convert int and numbers to uint32 + fprintf(docs, "%s uint32_t_ud|integer|number%s", prefix, suffix); + return; + } + + emit_docs_type(type, prefix, suffix); +} + +void emit_docs_return_type(struct type type, int nullable) { + // AP_Objects can be nil + nullable |= (type.type == TYPE_AP_OBJECT); + emit_docs_type(type, "---@return", (nullable == 0) ? "\n" : "|nil\n"); +} + void emit_docs_method(const char *name, const char *method_name, struct method *method) { fprintf(docs, "-- desc\n"); @@ -2623,7 +2828,7 @@ void emit_docs_method(const char *name, const char *method_name, struct method * 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"); + emit_docs_param_type(arg->type, param_name, "\n"); free(param_name); count++; } @@ -2632,18 +2837,14 @@ void emit_docs_method(const char *name, const char *method_name, struct method * // return type if ((method->flags & TYPE_FLAGS_NULLABLE) == 0) { - emit_docs_type(method->return_type, "---@return", "\n"); + emit_docs_return_type(method->return_type, FALSE); } 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"); - } + emit_docs_return_type(arg->type, arg->type.flags & TYPE_FLAGS_NULLABLE); } arg = arg->next; } @@ -2670,7 +2871,9 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { fprintf(docs, "-- desc\n"); - fprintf(docs, "---@class %s\n", name); + if (is_userdata) { + fprintf(docs, "---@class %s\n", name); + } // enums if (node->enums != NULL) { @@ -2685,8 +2888,15 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { // local userdata fprintf(docs, "local %s = {}\n\n", name); - if (emit_creation) { + int creation_disabled = (node->creation && node->creation_args == -1); + if (emit_creation && (!node->creation || !creation_disabled)) { // creation function + if (node->creation != NULL) { + for (int i = 0; i < node->creation_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + } + fprintf(docs, "---@return %s\n", name); fprintf(docs, "function %s(", node->rename ? node->rename : node->sanatized_name); if (node->creation == NULL) { @@ -2721,7 +2931,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { } if (field->access_flags & ACCESS_FLAG_WRITE) { fprintf(docs, "-- set field\n"); - emit_docs_type(field->type, "---@param value", "\n"); + emit_docs_param_type(field->type, "---@param value", "\n"); fprintf(docs, "function %s:%s(value) end\n\n", name, field->rename ? field->rename : field->name); } } else { @@ -2735,7 +2945,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { 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"); + emit_docs_param_type(field->type, "---@param value", "\n"); fprintf(docs, "function %s:%s(index, value) end\n\n", name, field->rename ? field->rename : field->name); } } @@ -2768,7 +2978,17 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { } else if (alias->type == ALIAS_TYPE_MANUAL) { // Cant do a great job, don't know types or return - fprintf(docs, "-- desc\nfunction %s:%s(", name, alias->alias); + fprintf(docs, "-- desc\n"); + + for (int i = 0; i < alias->num_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + + for (int i = 0; i < alias->num_ret; ++i) { + fprintf(docs, "---@return UNKNOWN\n"); + } + + fprintf(docs, "function %s:%s(", name, alias->alias); for (int i = 0; i < alias->num_args; ++i) { fprintf(docs, "param%i", i+1); if (i < alias->num_args-1) { @@ -2787,14 +3007,15 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { void emit_index_helpers(void) { - fprintf(source, "static bool load_function(lua_State *L, const luaL_Reg *list, const uint8_t length, const char* name) {\n"); + fprintf(source, "static int load_function(lua_State *L, const luaL_Reg *list, const uint8_t length) {\n"); + fprintf(source, " const char * name = luaL_checkstring(L, 2);\n"); fprintf(source, " for (uint8_t i = 0; i < length; i++) {\n"); fprintf(source, " if (strcmp(name,list[i].name) == 0) {\n"); fprintf(source, " lua_pushcfunction(L, list[i].func);\n"); - fprintf(source, " return true;\n"); + fprintf(source, " return 1;\n"); fprintf(source, " }\n"); fprintf(source, " }\n"); - fprintf(source, " return false;\n"); + fprintf(source, " return 0;\n"); fprintf(source, "}\n\n"); // If enough stuff is defined out we can end up with no enums. @@ -2802,14 +3023,15 @@ void emit_index_helpers(void) { fprintf(source, "#pragma GCC diagnostic push\n"); fprintf(source, "#pragma GCC diagnostic ignored \"-Wunused-function\"\n"); - fprintf(source, "static bool load_enum(lua_State *L, const userdata_enum *list, const uint8_t length, const char* name) {\n"); + fprintf(source, "static int load_enum(lua_State *L, const userdata_enum *list, const uint8_t length) {\n"); + fprintf(source, " const char * name = luaL_checkstring(L, 2);\n"); fprintf(source, " for (uint8_t i = 0; i < length; i++) {\n"); fprintf(source, " if (strcmp(name,list[i].name) == 0) {\n"); fprintf(source, " lua_pushinteger(L, list[i].value);\n"); - fprintf(source, " return true;\n"); + fprintf(source, " return 1;\n"); fprintf(source, " }\n"); fprintf(source, " }\n"); - fprintf(source, " return false;\n"); + fprintf(source, " return 0;\n"); fprintf(source, "}\n"); fprintf(source, "#pragma GCC diagnostic pop\n\n"); @@ -2927,6 +3149,9 @@ int main(int argc, char **argv) { // for set_and_print_new_error_message deprecate warning fprintf(source, "#include \n"); + fprintf(source, "\n"); + // the generated source uses the Scehduler singleton: + fprintf(source, "#include \n"); fprintf(source, "extern const AP_HAL::HAL& hal;\n"); @@ -2962,11 +3187,11 @@ int main(int argc, char **argv) { emit_methods(parsed_userdata); emit_index(parsed_userdata); - + emit_ap_object_fields(); emit_methods(parsed_ap_objects); emit_index(parsed_ap_objects); - + emit_userdata_new_funcs(); emit_loaders(); emit_sandbox(); @@ -2997,6 +3222,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"); + fprintf(header, "int field_argerror(lua_State *L);\n"); fprintf(header, "bool userdata_zero_arg_check(lua_State *L);\n"); fprintf(header, "lua_Integer get_integer(lua_State *L, int arg_num, lua_Integer min_val, lua_Integer max_val);\n"); fprintf(header, "int8_t get_int8_t(lua_State *L, int arg_num);\n"); @@ -3005,7 +3231,8 @@ int main(int argc, char **argv) { fprintf(header, "uint16_t get_uint16_t(lua_State *L, int arg_num);\n"); fprintf(header, "float get_number(lua_State *L, int arg_num, float min_val, float max_val);\n"); fprintf(header, "uint32_t get_uint32(lua_State *L, int arg_num, uint32_t min_val, uint32_t max_val);\n"); - fprintf(header, "int new_ap_object(lua_State *L, size_t size, const char * name);\n"); + fprintf(header, "void * new_ap_object(lua_State *L, size_t size, const char * name);\n"); + fprintf(header, "void ** check_ap_object(lua_State *L, int arg_num, const char * name);\n"); struct userdata * node = parsed_singletons; while (node) { @@ -3053,7 +3280,17 @@ int main(int argc, char **argv) { while(alias) { if (alias->type == ALIAS_TYPE_MANUAL) { // Cant do a great job, don't know types or return - fprintf(docs, "-- desc\nfunction %s(", alias->alias); + fprintf(docs, "-- desc\n"); + + for (int i = 0; i < alias->num_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + + for (int i = 0; i < alias->num_ret; ++i) { + fprintf(docs, "---@return UNKNOWN\n"); + } + + fprintf(docs, "function %s(", alias->alias); for (int i = 0; i < alias->num_args; ++i) { fprintf(docs, "param%i", i+1); if (i < alias->num_args-1) { diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index c07f4fdb32854c..6c627dc3a9fe15 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -142,10 +142,10 @@ int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { lj.status = LUA_OK; lj.previous = L->errorJmp; /* chain new error handler */ L->errorJmp = &lj; - LUAI_TRY(L, &lj, #ifdef ARM_MATH_CM7 __asm__("vpush {s16-s31}"); #endif + LUAI_TRY(L, &lj, (*f)(L, ud); ); #ifdef ARM_MATH_CM7 diff --git a/libraries/AP_Scripting/lua/src/loadlib.c b/libraries/AP_Scripting/lua/src/loadlib.c index 20af8e47660c02..12ff54b6d0f397 100644 --- a/libraries/AP_Scripting/lua/src/loadlib.c +++ b/libraries/AP_Scripting/lua/src/loadlib.c @@ -622,26 +622,25 @@ static void findloader (lua_State *L, const char *name) { static int ll_require (lua_State *L) { const char *name = luaL_checkstring(L, 1); lua_settop(L, 1); - lua_rawgeti(L, LUA_REGISTRYINDEX, lua_get_current_ref()); /* get the current script */ - lua_getupvalue(L, 2, 1); /* get the environment of the script */ - lua_getfield(L, 3, LUA_LOADED_TABLE); /* get _LOADED */ - lua_getfield(L, 4, name); /* LOADED[name] */ + lua_rawgeti(L, LUA_REGISTRYINDEX, lua_get_current_env_ref()); /* get the environment of the current script */ + lua_getfield(L, 2, LUA_LOADED_TABLE); /* get _LOADED */ + lua_getfield(L, 3, name); /* LOADED[name] */ if (lua_toboolean(L, -1)) /* is it there? */ return 1; /* package is already loaded */ /* else must load package */ lua_pop(L, 1); /* remove 'getfield' result */ findloader(L, name); - lua_pushvalue(L, 3); /* push current script's environment */ + lua_pushvalue(L, 2); /* push current script's environment */ lua_setupvalue(L, -3, 1); /* set the environment of the module */ lua_pushstring(L, name); /* pass name as argument to module loader */ lua_insert(L, -2); /* name is 1st argument (before search data) */ lua_call(L, 2, 1); /* run loader to load module */ if (!lua_isnil(L, -1)) /* non-nil return? */ - lua_setfield(L, 4, name); /* LOADED[name] = returned value */ - if (lua_getfield(L, 4, name) == LUA_TNIL) { /* module set no value? */ + lua_setfield(L, 3, name); /* LOADED[name] = returned value */ + if (lua_getfield(L, 3, name) == LUA_TNIL) { /* module set no value? */ lua_pushboolean(L, 1); /* use true as result */ lua_pushvalue(L, -1); /* extra copy to be returned */ - lua_setfield(L, 4, name); /* LOADED[name] = true */ + lua_setfield(L, 3, name); /* LOADED[name] = true */ } return 1; } diff --git a/libraries/AP_Scripting/lua/src/loslib.c b/libraries/AP_Scripting/lua/src/loslib.c index 9510105778b6c0..a6ddefbae3c8ac 100644 --- a/libraries/AP_Scripting/lua/src/loslib.c +++ b/libraries/AP_Scripting/lua/src/loslib.c @@ -106,6 +106,19 @@ static time_t l_checktime (lua_State *L, int arg) { ** it uses mkstemp. ** =================================================================== */ + +#if defined(ARDUPILOT_BUILD) + +/* os lib is not available in ArduPilot, and tmpnam is not available on some + platforms, so define useless but harmless lua_tmpnam to avoid needing it */ + +#define LUA_TMPNAMBUFSIZE 1 + +/* always report error */ +#define lua_tmpnam(b, e) { e = 1; } + +#endif // defined(ARDUPILOT_BUILD) + #if !defined(lua_tmpnam) /* { */ #if defined(LUA_USE_POSIX) /* { */ diff --git a/libraries/AP_Scripting/lua/src/lstrlib.c b/libraries/AP_Scripting/lua/src/lstrlib.c index 5f649b6f6f84dc..99ea2477edf8f5 100644 --- a/libraries/AP_Scripting/lua/src/lstrlib.c +++ b/libraries/AP_Scripting/lua/src/lstrlib.c @@ -1585,7 +1585,11 @@ static void createmetatable (lua_State *L) { */ LUAMOD_API int luaopen_string (lua_State *L) { luaL_newlib(L, strlib); +#if defined(ARDUPILOT_BUILD) + // metatable setup handled by Ardupilot scripting system +#else createmetatable(L); +#endif return 1; } diff --git a/libraries/AP_Scripting/lua/src/lundump.c b/libraries/AP_Scripting/lua/src/lundump.c index ee86a91ed61214..432db3c337210b 100644 --- a/libraries/AP_Scripting/lua/src/lundump.c +++ b/libraries/AP_Scripting/lua/src/lundump.c @@ -241,7 +241,7 @@ static void fchecksize (LoadState *S, size_t size, const char *tname) { #define checksize(S,t) fchecksize(S,sizeof(t),#t) static void checkHeader (LoadState *S) { - checkliteral(S, LUA_SIGNATURE + 1, "not a"); /* 1st char already checked */ + checkliteral(S, &LUA_SIGNATURE[1], "not a"); /* 1st char already checked */ if (LoadByte(S) != LUAC_VERSION) error(S, "version mismatch in"); if (LoadByte(S) != LUAC_FORMAT) diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index b1f7baea561525..dfb0b0a1689c8a 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -16,6 +16,7 @@ #include "lua_boxed_numerics.h" #include +#include #include #include @@ -33,8 +34,7 @@ extern const AP_HAL::HAL& hal; int lua_millis(lua_State *L) { binding_argcheck(L, 0); - new_uint32_t(L); - *check_uint32_t(L, -1) = AP_HAL::millis(); + *new_uint32_t(L) = AP_HAL::millis(); return 1; } @@ -43,8 +43,7 @@ int lua_millis(lua_State *L) { int lua_micros(lua_State *L) { binding_argcheck(L, 0); - new_uint32_t(L); - *check_uint32_t(L, -1) = AP_HAL::micros(); + *new_uint32_t(L) = AP_HAL::micros(); return 1; } @@ -64,13 +63,13 @@ int lua_mavlink_init(lua_State *L) { struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data; if (data.rx_buffer == nullptr) { - data.rx_buffer = new ObjectBuffer(queue_size); + data.rx_buffer = NEW_NOTHROW ObjectBuffer(queue_size); if (data.rx_buffer == nullptr) { return luaL_error(L, "Failed to allocate mavlink rx buffer"); } } if (data.accept_msg_ids == nullptr) { - data.accept_msg_ids = new uint32_t[num_msgs]; + data.accept_msg_ids = NEW_NOTHROW uint32_t[num_msgs]; if (data.accept_msg_ids == nullptr) { return luaL_error(L, "Failed to allocate mavlink rx registry"); } @@ -100,8 +99,7 @@ int lua_mavlink_receive_chan(lua_State *L) { luaL_addlstring(&b, (char *)&msg.msg, sizeof(msg.msg)); luaL_pushresult(&b); lua_pushinteger(L, msg.chan); - new_uint32_t(L); - *check_uint32_t(L, -1) = msg.timestamp_ms; + *new_uint32_t(L) = msg.timestamp_ms; return 3; } else { // no MAVLink to handle, just return no results @@ -203,7 +201,7 @@ int lua_mavlink_block_command(lua_State *L) { } // Add new list item - AP_Scripting::command_block_list *new_item = new AP_Scripting::command_block_list; + AP_Scripting::command_block_list *new_item = NEW_NOTHROW AP_Scripting::command_block_list; if (new_item == nullptr) { lua_pushboolean(L, false); return 1; @@ -239,8 +237,7 @@ int lua_mission_receive(lua_State *L) { return 0; } - new_uint32_t(L); - *check_uint32_t(L, -1) = cmd.time_ms; + *new_uint32_t(L) = cmd.time_ms; lua_pushinteger(L, cmd.p1); lua_pushnumber(L, cmd.content_p1); @@ -381,9 +378,8 @@ int AP_Logger_Write(lua_State *L) { switch(fmt_cat[index]) { // logger variable types not available to scripting // 'd': double - // 'Q': uint64_t // 'q': int64_t - // 'a': arrays + // 'a': int16_t[32] case 'b': { // int8_t int isnum; const lua_Integer tmp1 = lua_tointegerx(L, arg_index, &isnum); @@ -460,11 +456,17 @@ int AP_Logger_Write(lua_State *L) { case 'M': // uint8_t (flight mode) case 'B': { // uint8_t int isnum; - const lua_Integer tmp1 = lua_tointegerx(L, arg_index, &isnum); + lua_Integer tmp1 = lua_tointegerx(L, arg_index, &isnum); if (!isnum || (tmp1 < 0) || (tmp1 > UINT8_MAX)) { - luaM_free(L, buffer); - luaL_argerror(L, arg_index, "argument out of range"); - // no return + // Also allow boolean + if (!isnum && lua_isboolean(L, arg_index)) { + tmp1 = lua_toboolean(L, arg_index); + + } else { + luaM_free(L, buffer); + luaL_argerror(L, arg_index, "argument out of range"); + // no return + } } uint8_t tmp = static_cast(tmp1); memcpy(&buffer[offset], &tmp, sizeof(uint8_t)); @@ -496,6 +498,18 @@ int AP_Logger_Write(lua_State *L) { offset += sizeof(uint32_t); break; } + case 'Q': { // uint64_t + void * ud = luaL_testudata(L, arg_index, "uint64_t"); + if (ud == nullptr) { + luaM_free(L, buffer); + luaL_argerror(L, arg_index, "argument out of range"); + // no return + } + uint64_t tmp = *static_cast(ud); + memcpy(&buffer[offset], &tmp, sizeof(uint64_t)); + offset += sizeof(uint64_t); + break; + } case 'N': { // char[16] charlen = 16; break; @@ -577,7 +591,7 @@ int lua_get_i2c_device(lua_State *L) { return luaL_argerror(L, 1, "no i2c devices available"); } - scripting->_i2c_dev[scripting->num_i2c_devices] = new AP_HAL::OwnPtr; + scripting->_i2c_dev[scripting->num_i2c_devices] = NEW_NOTHROW AP_HAL::OwnPtr; if (scripting->_i2c_dev[scripting->num_i2c_devices] == nullptr) { return luaL_argerror(L, 1, "i2c device nullptr"); } @@ -588,8 +602,7 @@ int lua_get_i2c_device(lua_State *L) { return luaL_argerror(L, 1, "i2c device nullptr"); } - new_AP_HAL__I2CDevice(L); - *((AP_HAL::I2CDevice**)luaL_checkudata(L, -1, "AP_HAL::I2CDevice")) = scripting->_i2c_dev[scripting->num_i2c_devices]->get(); + *new_AP_HAL__I2CDevice(L) = scripting->_i2c_dev[scripting->num_i2c_devices]->get(); scripting->num_i2c_devices++; @@ -638,27 +651,30 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) { return success; } -int AP_HAL__UARTDriver_readstring(lua_State *L) { - binding_argcheck(L, 2); +int AP_HAL__I2CDevice_transfer(lua_State *L) { + binding_argcheck(L, 3); - AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1); + AP_HAL::I2CDevice * ud = *check_AP_HAL__I2CDevice(L, 1); - const uint16_t count = get_uint16_t(L, 2); - uint8_t *data = (uint8_t*)malloc(count); - if (data == nullptr) { - return 0; - } + // Parse string of bytes to send + size_t send_len; + const uint8_t* send_data = (const uint8_t*)(lua_tolstring(L, 2, &send_len)); - const auto ret = ud->read(data, count); - if (ret < 0) { - free(data); + // Parse and setup rx buffer + uint32_t rx_len = get_uint8_t(L, 3); + uint8_t rx_data[rx_len]; + + // Transfer + ud->get_semaphore()->take_blocking(); + const bool success = ud->transfer(send_data, send_len, rx_data, rx_len); + ud->get_semaphore()->give(); + + if (!success) { return 0; } - // push to lua string - lua_pushlstring(L, (const char *)data, ret); - free(data); - + // Return a string + lua_pushlstring(L, (const char *)rx_data, rx_len); return 1; } @@ -676,14 +692,19 @@ int lua_get_CAN_device(lua_State *L) { auto *scripting = AP::scripting(); if (scripting->_CAN_dev == nullptr) { - scripting->_CAN_dev = new ScriptingCANSensor(AP_CAN::Protocol::Scripting); + scripting->_CAN_dev = NEW_NOTHROW ScriptingCANSensor(AP_CAN::Protocol::Scripting); if (scripting->_CAN_dev == nullptr) { return luaL_argerror(L, 1, "CAN device nullptr"); } } - new_ScriptingCANBuffer(L); - *((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev->add_buffer(buffer_len); + if (!scripting->_CAN_dev->initialized()) { + // Driver not initialized, probably because there is no can driver set to scripting + // Return nil + return 0; + } + + *new_ScriptingCANBuffer(L) = scripting->_CAN_dev->add_buffer(buffer_len); return 1; } @@ -701,19 +722,127 @@ int lua_get_CAN_device2(lua_State *L) { auto *scripting = AP::scripting(); if (scripting->_CAN_dev2 == nullptr) { - scripting->_CAN_dev2 = new ScriptingCANSensor(AP_CAN::Protocol::Scripting2); + scripting->_CAN_dev2 = NEW_NOTHROW ScriptingCANSensor(AP_CAN::Protocol::Scripting2); if (scripting->_CAN_dev2 == nullptr) { return luaL_argerror(L, 1, "CAN device nullptr"); } } - new_ScriptingCANBuffer(L); - *((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev2->add_buffer(buffer_len); + if (!scripting->_CAN_dev2->initialized()) { + // Driver not initialized, probably because there is no can driver set to scripting 2 + // Return nil + return 0; + } + + *new_ScriptingCANBuffer(L) = scripting->_CAN_dev2->add_buffer(buffer_len); return 1; } #endif // AP_SCRIPTING_CAN_SENSOR_ENABLED +#if AP_SERIALMANAGER_ENABLED +int lua_serial_find_serial(lua_State *L) { + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "serial") != NULL) ? 1 : 0; + + binding_argcheck(L, 1 + arg_offset); + + uint8_t instance = get_uint8_t(L, 1 + arg_offset); + + AP_SerialManager *mgr = &AP::serialmanager(); + AP_HAL::UARTDriver *driver_stream = mgr->find_serial( + AP_SerialManager::SerialProtocol_Scripting, instance); + + if (driver_stream == nullptr) { // not found + return 0; + } + + AP_Scripting_SerialAccess *port = new_AP_Scripting_SerialAccess(L); + port->stream = driver_stream; +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + port->is_device_port = false; +#endif + + return 1; +} +#endif // AP_SERIALMANAGER_ENABLED + +#if AP_SCRIPTING_SERIALDEVICE_ENABLED +int lua_serial_find_simulated_device(lua_State *L) { + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "serial") != NULL) ? 1 : 0; + + binding_argcheck(L, 2 + arg_offset); + + const int8_t protocol = (int8_t)get_uint32(L, 1 + arg_offset, 0, 127); + uint32_t instance = get_uint16_t(L, 2 + arg_offset); + + auto *scripting = AP::scripting(); + AP_Scripting_SerialDevice::Port *device_stream = nullptr; + + for (auto &port : scripting->_serialdevice.ports) { + if (port.state.protocol == protocol) { + if (instance-- == 0) { + device_stream = &port; + break; + } + } + } + + if (!scripting->_serialdevice.enable || device_stream == nullptr) { + // serial devices as a whole are disabled, or port not found + return 0; + } + + AP_Scripting_SerialAccess *port = new_AP_Scripting_SerialAccess(L); + port->stream = device_stream; + port->is_device_port = true; + + return 1; +} +#endif // AP_SCRIPTING_SERIALDEVICE_ENABLED + +int lua_serial_writestring(lua_State *L) +{ + binding_argcheck(L, 2); + + AP_Scripting_SerialAccess * port = check_AP_Scripting_SerialAccess(L, 1); + + // get the bytes the user wants to write, along with their length + size_t req_bytes; + const char *data = lua_tolstring(L, 2, &req_bytes); + + // write up to that number of bytes + const uint32_t written_bytes = port->write((const uint8_t*)data, req_bytes); + + // return the number of bytes that were actually written + lua_pushinteger(L, written_bytes); + + return 1; +} + +int lua_serial_readstring(lua_State *L) { + binding_argcheck(L, 2); + + AP_Scripting_SerialAccess * port = check_AP_Scripting_SerialAccess(L, 1); + + // create a buffer sized to hold the number of bytes the user wants to read + luaL_Buffer b; + const uint16_t req_bytes = get_uint16_t(L, 2); + uint8_t *data = (uint8_t *)luaL_buffinitsize(L, &b, req_bytes); + + // read up to that number of bytes + const ssize_t read_bytes = port->read(data, req_bytes); + if (read_bytes < 0) { + return 0; // error, return nil + } + + // push the buffer as a string, truncated to the number of bytes actually read + luaL_pushresultsize(&b, read_bytes); + + return 1; +} + /* directory listing, return table of files in a directory */ @@ -751,7 +880,7 @@ int lua_dirlist(lua_State *L) { int lua_removefile(lua_State *L) { binding_argcheck(L, 1); const char *filename = luaL_checkstring(L, 1); - return luaL_fileresult(L, remove(filename) == 0, filename); + return luaL_fileresult(L, AP::FS().unlink(filename) == 0, filename); } // Manual binding to allow SRV_Channels table to see safety state @@ -772,13 +901,12 @@ int lua_get_PWMSource(lua_State *L) { return luaL_argerror(L, 1, "no PWMSources available"); } - scripting->_pwm_source[scripting->num_pwm_source] = new AP_HAL::PWMSource; + scripting->_pwm_source[scripting->num_pwm_source] = NEW_NOTHROW AP_HAL::PWMSource; if (scripting->_pwm_source[scripting->num_pwm_source] == nullptr) { return luaL_argerror(L, 1, "PWMSources device nullptr"); } - new_AP_HAL__PWMSource(L); - *((AP_HAL::PWMSource**)luaL_checkudata(L, -1, "AP_HAL::PWMSource")) = scripting->_pwm_source[scripting->num_pwm_source]; + *new_AP_HAL__PWMSource(L) = scripting->_pwm_source[scripting->num_pwm_source]; scripting->num_pwm_source++; @@ -794,15 +922,14 @@ int lua_get_SocketAPM(lua_State *L) { const uint8_t datagram = get_uint8_t(L, 1); auto *scripting = AP::scripting(); - auto *sock = new SocketAPM(datagram); + auto *sock = NEW_NOTHROW SocketAPM(datagram); if (sock == nullptr) { return luaL_argerror(L, 1, "SocketAPM device nullptr"); } for (uint8_t i=0; i_net_sockets[i] == nullptr) { scripting->_net_sockets[i] = sock; - new_SocketAPM(L); - *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i]; + *new_SocketAPM(L) = scripting->_net_sockets[i]; return 1; } } @@ -877,11 +1004,23 @@ int SocketAPM_recv(lua_State *L) { return 0; } - // push to lua string + int retcount = 1; + + // push data to lua string lua_pushlstring(L, (const char *)data, ret); + + // also push the address and port if available + uint32_t ip_addr; + uint16_t port; + if (ud->last_recv_address(ip_addr, port)) { + *new_uint32_t(L) = ip_addr; + lua_pushinteger(L, port); + retcount += 2; + } + free(data); - return 1; + return retcount; } /* @@ -901,8 +1040,7 @@ int SocketAPM_accept(lua_State *L) { if (scripting->_net_sockets[i] == nullptr) { return 0; } - new_SocketAPM(L); - *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i]; + *new_SocketAPM(L) = scripting->_net_sockets[i]; return 1; } } @@ -911,13 +1049,38 @@ int SocketAPM_accept(lua_State *L) { return 0; } +/* + convert a uint32_t ipv4 address to a string + */ +int SocketAPM_ipv4_addr_to_string(lua_State *L) { + binding_argcheck(L, 1); + const uint32_t ip_addr = get_uint32(L, 1, 0, UINT32_MAX); + char buf[IP4_STR_LEN]; + const char *ret = SocketAPM::inet_addr_to_str(ip_addr, buf, sizeof(buf)); + if (ret == nullptr) { + return 0; + } + lua_pushlstring(L, (const char *)ret, strlen(ret)); + return 1; +} + +/* + convert a ipv4 string address to a uint32_t + */ +int SocketAPM_string_to_ipv4_addr(lua_State *L) { + binding_argcheck(L, 1); + const char *str = luaL_checkstring(L, 1); + *new_uint32_t(L) = SocketAPM::inet_str_to_addr(str); + return 1; +} + #endif // AP_NETWORKING_ENABLED -int lua_get_current_ref() +int lua_get_current_env_ref() { auto *scripting = AP::scripting(); - return scripting->get_current_ref(); + return scripting->get_current_env_ref(); } // This is used when loading modules with require, lua must only look in enabled directory's @@ -957,7 +1120,7 @@ int lua_print(lua_State *L) { return 0; } -#if (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +#if AP_RANGEFINDER_ENABLED int lua_range_finder_handle_script_msg(lua_State *L) { // Arg 1 => self (an instance of rangefinder_backend) // Arg 2 => a float distance or a RangeFinder_State user data @@ -981,7 +1144,7 @@ int lua_range_finder_handle_script_msg(lua_State *L) { lua_pushboolean(L, result); return 1; } -#endif +#endif // AP_RANGEFINDER_ENABLED /* lua wants to abort, and doesn't have access to a panic function @@ -1002,4 +1165,106 @@ void lua_abort() #endif } +#if (HAL_GCS_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) +/* + implement gcs:command_int() access to MAV_CMD_xxx commands + */ +int lua_GCS_command_int(lua_State *L) +{ + GCS *_gcs = check_GCS(L); + binding_argcheck(L, 3); + + const uint16_t command = get_uint16_t(L, 2); + if (!lua_istable(L, 3)) { + // must have parameter table + return 0; + } + + mavlink_command_int_t pkt {}; + + pkt.command = command; + + float *params = &pkt.param1; + int32_t *xy = &pkt.x; + + // extract the first 4 parameters as floats + for (uint8_t i=0; i<4; i++) { + char pname[3] { 'p' , char('1' + i), 0 }; + lua_pushstring(L, pname); + lua_gettable(L, 3); + if (lua_isnumber(L, -1)) { + params[i] = lua_tonumber(L, -1); + } + lua_pop(L, 1); + } + + // extract the xy values + for (uint8_t i=0; i<2; i++) { + const char *names[] = { "x", "y" }; + lua_pushstring(L, names[i]); + lua_gettable(L, 3); + if (lua_isinteger(L, -1)) { + xy[i] = lua_tointeger(L, -1); + } + lua_pop(L, 1); + } + + // and z + lua_pushstring(L, "z"); + lua_gettable(L, 3); + if (lua_isnumber(L, -1)) { + pkt.z = lua_tonumber(L, -1); + } + lua_pop(L, 1); + + // optional frame + lua_pushstring(L, "frame"); + lua_gettable(L, 3); + if (lua_isinteger(L, -1)) { + pkt.frame = lua_tointeger(L, -1); + } + lua_pop(L, 1); + + // call the interface with scheduler lock + WITH_SEMAPHORE(AP::scheduler().get_semaphore()); + + auto result = _gcs->lua_command_int_packet(pkt); + + // Return the resulting MAV_RESULT + lua_pushinteger(L, result); + + return 1; +} +#endif + +#if HAL_ENABLE_DRONECAN_DRIVERS +/* + get FlexDebug from a DroneCAN node + */ +int lua_DroneCAN_get_FlexDebug(lua_State *L) +{ + binding_argcheck(L, 4); + + const uint8_t bus = get_uint8_t(L, 1); + const uint8_t node_id = get_uint8_t(L, 2); + const uint16_t msg_id = get_uint16_t(L, 3); + uint32_t tstamp_us = get_uint32(L, 4, 0, UINT32_MAX); + + const auto *dc = AP_DroneCAN::get_dronecan(bus); + if (dc == nullptr) { + return 0; + } + dronecan_protocol_FlexDebug msg; + + if (!dc->get_FlexDebug(node_id, msg_id, tstamp_us, msg)) { + return 0; + } + + *new_uint32_t(L) = tstamp_us; + lua_pushlstring(L, (const char *)msg.u8.data, msg.u8.len); + + return 2; +} +#endif // HAL_ENABLE_DRONECAN_DRIVERS + #endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index add40faa0a7bd8..d064df4552df60 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -8,9 +8,13 @@ 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 AP_HAL__UARTDriver_readstring(lua_State *L); +int AP_HAL__I2CDevice_transfer(lua_State *L); int lua_get_CAN_device(lua_State *L); int lua_get_CAN_device2(lua_State *L); +int lua_serial_find_serial(lua_State *L); +int lua_serial_find_simulated_device(lua_State *L); +int lua_serial_writestring(lua_State *L); +int lua_serial_readstring(lua_State *L); int lua_dirlist(lua_State *L); int lua_removefile(lua_State *L); int SRV_Channels_get_safety_state(lua_State *L); @@ -20,6 +24,8 @@ int SocketAPM_recv(lua_State *L); int SocketAPM_accept(lua_State *L); int SocketAPM_close(lua_State *L); int SocketAPM_sendfile(lua_State *L); +int SocketAPM_ipv4_addr_to_string(lua_State *L); +int SocketAPM_string_to_ipv4_addr(lua_State *L); int lua_mavlink_init(lua_State *L); int lua_mavlink_receive_chan(lua_State *L); int lua_mavlink_register_rx_msgid(lua_State *L); @@ -27,3 +33,5 @@ int lua_mavlink_send_chan(lua_State *L); int lua_mavlink_block_command(lua_State *L); int lua_print(lua_State *L); int lua_range_finder_handle_script_msg(lua_State *L); +int lua_GCS_command_int(lua_State *L); +int lua_DroneCAN_get_FlexDebug(lua_State *L); diff --git a/libraries/AP_Scripting/lua_boxed_numerics.cpp b/libraries/AP_Scripting/lua_boxed_numerics.cpp index fe2304df978ef5..4aa1f3aad0fe36 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.cpp +++ b/libraries/AP_Scripting/lua_boxed_numerics.cpp @@ -39,6 +39,39 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) { return luaL_argerror(L, arg, "Unable to coerce to uint32_t"); } +uint64_t coerce_to_uint64_t(lua_State *L, int arg) { + { // uint64_t userdata + const uint64_t * ud = static_cast(luaL_testudata(L, arg, "uint64_t")); + if (ud != nullptr) { + return *ud; + } + } + { // integer + int success; + const lua_Integer v = lua_tointegerx(L, arg, &success); + + // Lua int maps to int32. However, because of the size difference negatives numbers wont come out correctly as they do for uint32 + if (success && v >= 0) { + return static_cast(v); + } + } + { // uint32_t userdata + const uint32_t * ud = static_cast(luaL_testudata(L, arg, "uint32_t")); + if (ud != nullptr) { + return static_cast(*ud); + } + } + { // float + int success; + const lua_Number v = lua_tonumberx(L, arg, &success); + if (success && (v >= 0) && (v <= float(UINT64_MAX))) { + return static_cast(v); + } + } + // failure + return luaL_argerror(L, arg, "Unable to coerce to uint64_t"); +} + // the exposed constructor to lua calls to create a uint32_t int lua_new_uint32_t(lua_State *L) { const int args = lua_gettop(L); @@ -46,68 +79,59 @@ int lua_new_uint32_t(lua_State *L) { return luaL_argerror(L, args, "too many arguments"); } - *static_cast(lua_newuserdata(L, sizeof(uint32_t))) = (args == 1) ? coerce_to_uint32_t(L, 1) : 0; - luaL_getmetatable(L, "uint32_t"); - lua_setmetatable(L, -2); + *new_uint32_t(L) = (args == 1) ? coerce_to_uint32_t(L, 1) : 0; return 1; } -#define UINT32_T_BOX_OP(name, sym) \ - 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); \ - \ - new_uint32_t(L); \ - *static_cast(luaL_checkudata(L, -1, "uint32_t")) = v1 sym v2; \ - return 1; \ - } - -UINT32_T_BOX_OP(add, +) -UINT32_T_BOX_OP(sub, -) -UINT32_T_BOX_OP(mul, *) -UINT32_T_BOX_OP(div, /) -UINT32_T_BOX_OP(mod, %) -UINT32_T_BOX_OP(band, &) -UINT32_T_BOX_OP(bor, |) -UINT32_T_BOX_OP(bxor, ^) -UINT32_T_BOX_OP(shl, <<) -UINT32_T_BOX_OP(shr, >>) - -#define UINT32_T_BOX_OP_BOOL(name, sym) \ - 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); \ - \ - lua_pushboolean(L, v1 sym v2); \ - return 1; \ +// the exposed constructor to lua calls to create a uint64_t +int lua_new_uint64_t(lua_State *L) { + const int args = lua_gettop(L); + if (args > 2) { + return luaL_argerror(L, args, "too many arguments"); } -UINT32_T_BOX_OP_BOOL(eq, ==) -UINT32_T_BOX_OP_BOOL(lt, <) -UINT32_T_BOX_OP_BOOL(le, <=) - -#define UINT32_T_BOX_OP_UNARY(name, sym) \ - int uint32_t___##name(lua_State *L) { \ - binding_argcheck(L, 2); \ - \ - uint32_t v1 = coerce_to_uint32_t(L, 1); \ - \ - new_uint32_t(L); \ - *static_cast(luaL_checkudata(L, -1, "uint32_t")) = sym v1; \ - return 1; \ + uint64_t value = 0; + switch (args) { + case 0: + default: + // No arguments, init to 0 + break; + case 1: + // Single argument + value = coerce_to_uint64_t(L, 1); + break; + + case 2: + // Two uint32 giving high and low half + const uint64_t high = coerce_to_uint32_t(L, 1); + const uint64_t low = coerce_to_uint32_t(L, 2); + value = (high << 32) | low; + break; } -// DO NOT SUPPORT UNARY NEGATION -UINT32_T_BOX_OP_UNARY(bnot, ~) + *new_uint64_t(L) = value; + return 1; +} int uint32_t_toint(lua_State *L) { binding_argcheck(L, 1); - uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); + const uint32_t v = *check_uint32_t(L, 1); + + lua_pushinteger(L, static_cast(v)); + + return 1; +} + +int uint64_t_toint(lua_State *L) { + binding_argcheck(L, 1); + + const uint64_t v = *check_uint64_t(L, 1); + + if (v > INT32_MAX) { + // uint64_t too large to convert to int return nill rather than giving error + return 0; + } lua_pushinteger(L, static_cast(v)); @@ -117,7 +141,17 @@ int uint32_t_toint(lua_State *L) { int uint32_t_tofloat(lua_State *L) { binding_argcheck(L, 1); - uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); + const uint32_t v = *check_uint32_t(L, 1); + + lua_pushnumber(L, static_cast(v)); + + return 1; +} + +int uint64_t_tofloat(lua_State *L) { + binding_argcheck(L, 1); + + const uint64_t v = *check_uint64_t(L, 1); lua_pushnumber(L, static_cast(v)); @@ -127,14 +161,42 @@ int uint32_t_tofloat(lua_State *L) { int uint32_t___tostring(lua_State *L) { binding_argcheck(L, 1); - uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); + const uint32_t v = *check_uint32_t(L, 1); char buf[32]; - hal.util->snprintf(buf, ARRAY_SIZE(buf), "%u", (unsigned)v); + hal.util->snprintf(buf, ARRAY_SIZE(buf), "%lu", (unsigned long)v); lua_pushstring(L, buf); return 1; } +int uint64_t___tostring(lua_State *L) { + binding_argcheck(L, 1); + + const uint64_t v = *check_uint64_t(L, 1); + + char buf[32]; + hal.util->snprintf(buf, ARRAY_SIZE(buf), "%llu", (unsigned long long)v); + + lua_pushstring(L, buf); + + return 1; +} + +// Split uint64 into a high and low uint32 +int uint64_t_split(lua_State *L) { + binding_argcheck(L, 1); + + const uint64_t v = *check_uint64_t(L, 1); + + // high + *new_uint32_t(L) = v >> 32; + + // low + *new_uint32_t(L) = v & 0xFFFFFFFF; + + return 2; +} + #endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/lua_boxed_numerics.h b/libraries/AP_Scripting/lua_boxed_numerics.h index e98ce89826066c..34c6e048422e65 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.h +++ b/libraries/AP_Scripting/lua_boxed_numerics.h @@ -5,20 +5,15 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg); int lua_new_uint32_t(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); + +int lua_new_uint64_t(lua_State *L); +uint64_t coerce_to_uint64_t(lua_State *L, int arg); + +int uint64_t___tostring(lua_State *L); +int uint64_t_toint(lua_State *L); +int uint64_t_tofloat(lua_State *L); +int uint64_t_split(lua_State *L); + diff --git a/libraries/AP_Scripting/lua_common_defs.h b/libraries/AP_Scripting/lua_common_defs.h index 9776e687a89001..f48a79c19d60b5 100644 --- a/libraries/AP_Scripting/lua_common_defs.h +++ b/libraries/AP_Scripting/lua_common_defs.h @@ -2,14 +2,6 @@ #include -#ifndef REPL_DIRECTORY - #if HAL_OS_FATFS_IO - #define REPL_DIRECTORY "/APM/repl" - #else - #define REPL_DIRECTORY "./repl" - #endif //HAL_OS_FATFS_IO -#endif // REPL_DIRECTORY - #ifndef SCRIPTING_DIRECTORY #if HAL_OS_FATFS_IO #define SCRIPTING_DIRECTORY "/APM/scripts" @@ -18,15 +10,7 @@ #endif //HAL_OS_FATFS_IO #endif // SCRIPTING_DIRECTORY -#ifndef REPL_IN - #define REPL_IN REPL_DIRECTORY "/in" -#endif // REPL_IN - -#ifndef REPL_OUT - #define REPL_OUT REPL_DIRECTORY "/out" -#endif // REPL_OUT - -int lua_get_current_ref(); +int lua_get_current_env_ref(); const char* lua_get_modules_path(); void lua_abort(void) __attribute__((noreturn)); diff --git a/libraries/AP_Scripting/lua_repl.cpp b/libraries/AP_Scripting/lua_repl.cpp deleted file mode 100644 index c20bb4f320a576..00000000000000 --- a/libraries/AP_Scripting/lua_repl.cpp +++ /dev/null @@ -1,264 +0,0 @@ -// this implements a Lua REPL, and is based off of a cut down version of -// lua/src/lua.c. It overall modified the functions to the minimum amount -// required, with the exception of fixing whitespace/indentation on if's - -#include "AP_Scripting_config.h" - -#if AP_SCRIPTING_ENABLED - -#include "lua_scripts.h" -#include - -#include "lua/src/lua.h" -#include "lua/src/lauxlib.h" -#include "lua/src/lualib.h" - -#include - -#if !defined(LUA_MAXINPUT) -#define LUA_MAXINPUT 256 -#endif - -#if !defined(LUA_PROMPT) -#define LUA_PROMPT "> " -#define LUA_PROMPT2 ">> " -#endif - -extern const AP_HAL::HAL& hal; - -/* -** Message handler used to run all chunks -*/ -static int msghandler(lua_State *L) { - const char *msg = lua_tostring(L, 1); - if (msg == NULL) { /* is error object not a string? */ - if (luaL_callmeta(L, 1, "__tostring") && /* does it have a metamethod */ - lua_type(L, -1) == LUA_TSTRING) { /* that produces a string? */ - return 1; /* that is the message */ - } else { - msg = lua_pushfstring(L, "(error object is a %s value)", - luaL_typename(L, 1)); - } - } - luaL_traceback(L, L, msg, 1); /* append a standard traceback */ - return 1; /* return the traceback */ -} - - -/* -** Interface to 'lua_pcall', which sets appropriate message function -** and C-signal handler. Used to run all chunks. -*/ -int lua_scripts::docall(lua_State *L, int narg, int nres) const { - int status; - int base = lua_gettop(L) - narg; /* function index */ - lua_rawgeti(L, LUA_REGISTRYINDEX, sandbox_ref); - lua_setupvalue(L, -2, 1); - lua_pushcfunction(L, msghandler); /* push message handler */ - lua_insert(L, base); /* put it under function and args */ - status = lua_pcall(L, narg, nres, base); - lua_remove(L, base); /* remove message handler from the stack */ - return status; -} - - -/* -** Returns the string to be used as a prompt by the interpreter. -*/ -const char * lua_scripts::get_prompt(lua_State *L, int firstline) { - const char *p; - lua_getglobal(L, firstline ? "_PROMPT" : "_PROMPT2"); - p = lua_tostring(L, -1); - if (p == NULL) { - p = (firstline ? LUA_PROMPT : LUA_PROMPT2); - } - return p; -} - -/* mark in error messages for incomplete statements */ -#define EOFMARK "" -#define marklen (sizeof(EOFMARK)/sizeof(char) - 1) - - -/* -** Check whether 'status' signals a syntax error and the error -** message at the top of the stack ends with the above mark for -** incomplete statements. -*/ -int lua_scripts::incomplete(lua_State *L, int status) { - if (status == LUA_ERRSYNTAX) { - size_t lmsg; - const char *msg = lua_tolstring(L, -1, &lmsg); - if (lmsg >= marklen && strcmp(msg + lmsg - marklen, EOFMARK) == 0) { - lua_pop(L, 1); - return 1; - } - } - return 0; /* else... */ -} - - -/* -** Prompt the user, read a line, and push it into the Lua stack. -*/ -int lua_scripts::pushline(lua_State *L, int firstline) { - char buffer[LUA_MAXINPUT + 1] = {}; - size_t l = 0; - - // send prompt to the user - terminal_print(get_prompt(L, firstline)); - - while (terminal.session) { - // reseek to where we need input from, as invalid reads could have done weird stuff, and we want to start from the last valid input - int input_fd = AP::FS().open(REPL_IN, O_RDONLY); - if (input_fd != -1) { - AP::FS().lseek(input_fd, terminal.input_offset, SEEK_SET); - ssize_t read_bytes = AP::FS().read(input_fd, buffer, ARRAY_SIZE(buffer) - 1); - AP::FS().close(input_fd); - if (read_bytes > 0) { - // locate the first newline - char * newline_chr = strchr(buffer, '\n'); - if (newline_chr != NULL) { - newline_chr[0] = '\0'; - // only advance to the newline - l = strlen(buffer); - terminal.input_offset += l + 1; - break; - } - } - } - // wait for any input - hal.scheduler->delay(100); - } - - lua_pop(L, 1); /* remove prompt */ - lua_pushlstring(L, buffer, l); - return 1; -} - - -/* -** Try to compile line on the stack as 'return ;'; on return, stack -** has either compiled chunk or original line (if compilation failed). -*/ -int lua_scripts::addreturn(lua_State *L) { - const char *line = lua_tostring(L, -1); /* original line */ - const char *retline = lua_pushfstring(L, "return %s;", line); - int status = luaL_loadbuffer(L, retline, strlen(retline), "=stdin"); - if (status == LUA_OK) { - lua_remove(L, -2); /* remove modified line */ - } else { - lua_pop(L, 2); /* pop result from 'luaL_loadbuffer' and modified line */ - } - return status; -} - - -/* -** Read multiple lines until a complete Lua statement -*/ -int lua_scripts::multiline (lua_State *L) { - for (;;) { /* repeat until gets a complete statement */ - size_t len; - const char *line = lua_tolstring(L, 1, &len); /* get what it has */ - int status = luaL_loadbuffer(L, line, len, "=stdin"); /* try it */ - if (!incomplete(L, status) || !pushline(L, 0)) { - return status; /* cannot or should not try to add continuation line */ - } - lua_pushliteral(L, "\n"); /* add newline... */ - lua_insert(L, -2); /* ...between the two lines */ - lua_concat(L, 3); /* join them */ - } -} - - -/* -** Read a line and try to load (compile) it first as an expression (by -** adding "return " in front of it) and second as a statement. Return -** the final status of load/call with the resulting function (if any) -** in the top of the stack. -*/ -int lua_scripts::loadline(lua_State *L) { - int status; - lua_settop(L, 0); - if (!pushline(L, 1)) { - return -1; /* no input */ - } - if ((status = addreturn(L)) != LUA_OK) { /* 'return ...' did not work? */ - status = multiline(L); /* try as command, maybe with continuation lines */ - } else { - } - lua_remove(L, 1); /* remove line from the stack */ - lua_assert(lua_gettop(L) == 1); - return status; -} - -// push the tring into the terminal, blocks until it's queued -void lua_scripts::terminal_print(const char *str) { - if ((AP::FS().write(terminal.output_fd, str, strlen(str)) == -1) || - (AP::FS().fsync(terminal.output_fd) != 0)) { - terminal.session = false; - } -} - -/* -** Prints (calling the Lua 'print' function) any values on the stack -*/ -void lua_scripts::l_print(lua_State *L) { - int n = lua_gettop(L); - if (n > 0) { /* any result to be printed? */ - luaL_checkstack(L, LUA_MINSTACK, "too many results to print"); - // grab all the internal functions via the sandbox - lua_rawgeti(L, LUA_REGISTRYINDEX, sandbox_ref); - lua_getfield(L, -1, "string"); - lua_getfield(L, -1, "format"); - lua_insert(L, 1); - lua_remove(L, -2); - lua_getfield(L, -1, "rep"); - lua_remove(L, -2); - lua_pushliteral(L, "%s"); - lua_pushinteger(L, n); - lua_pushliteral(L, "\t"); - if (lua_pcall(L, 3, 1, 0) != LUA_OK) { - // should never happen - lua_error(L); - } - lua_insert(L, 2); - if (lua_pcall(L, n + 1, 1, 0) != LUA_OK) { - terminal_print(lua_pushfstring(L, "error calling 'print' (%s)\n", lua_tostring(L, -1))); - } else { - terminal_print(lua_pushfstring(L, "%s\n", lua_tostring(L, -1))); - } - } -} - -/* -** Do the REPL: repeatedly read (load) a line, evaluate (call) it, and -** print any results. -*/ -void lua_scripts::doREPL(lua_State *L) { - int status; - // clear out any old script results - reset_loop_overtime(L); - // prep the sandbox - create_sandbox(L); - sandbox_ref = luaL_ref(L, LUA_REGISTRYINDEX); - terminal.input_offset = 0; - while (((status = loadline(L)) != -1) && terminal.session) { - if (status == LUA_OK) { - status = docall(L, 0, LUA_MULTRET); - } - if (status == LUA_OK) { - l_print(L); - } else { - terminal_print(lua_pushfstring(L, "%s\n", lua_tostring(L, -1))); - } - reset_loop_overtime(L); - } - lua_settop(L, 0); /* clear stack */ - luaL_unref(L, LUA_REGISTRYINDEX, sandbox_ref); - repl_cleanup(); -} - - -#endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/lua_scripts.cpp b/libraries/AP_Scripting/lua_scripts.cpp index 98960a11ceba6e..b635d1d4dfeb8e 100644 --- a/libraries/AP_Scripting/lua_scripts.cpp +++ b/libraries/AP_Scripting/lua_scripts.cpp @@ -40,12 +40,12 @@ uint32_t lua_scripts::loaded_checksum; uint32_t lua_scripts::running_checksum; HAL_Semaphore lua_scripts::crc_sem; -lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_options, struct AP_Scripting::terminal_s &_terminal) +lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, AP_Int8 &debug_options) : _vm_steps(vm_steps), - _debug_options(debug_options), - terminal(_terminal) + _debug_options(debug_options) { - _heap.create(heap_size, 4); + const bool allow_heap_expansion = !option_is_set(AP_Scripting::DebugOption::DISABLE_HEAP_EXPANSION); + _heap.create(heap_size, 10, allow_heap_expansion, 20*1024); } lua_scripts::~lua_scripts() { @@ -130,14 +130,14 @@ int lua_scripts::atpanic(lua_State *L) { // helper for print and log of runtime stats void lua_scripts::update_stats(const char *name, uint32_t run_time, int total_mem, int run_mem) { - if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) { + if (option_is_set(AP_Scripting::DebugOption::RUNTIME_MSG)) { GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d", (unsigned int)run_time, (int)total_mem, (int)run_mem); } #if HAL_LOGGING_ENABLED - if ((_debug_options.get() & uint8_t(DebugLevel::LOG_RUNTIME)) != 0) { + if (option_is_set(AP_Scripting::DebugOption::LOG_RUNTIME)) { struct log_Scripting pkt { LOG_PACKET_HEADER_INIT(LOG_SCRIPTING_MSG), time_us : AP_HAL::micros64(), @@ -192,7 +192,8 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename) create_sandbox(L); - lua_setupvalue(L, -2, 1); + lua_pushvalue(L, -1); // duplicate environment for reference below + lua_setupvalue(L, -3, 1); const uint32_t loadEnd = AP_HAL::micros(); const int endMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0); @@ -200,7 +201,8 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename) update_stats(filename, loadEnd-loadStart, endMem, loadMem); new_script->name = filename; - new_script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); // cache the reference + new_script->env_ref = luaL_ref(L, LUA_REGISTRYINDEX); // store reference to script's environment + new_script->run_ref = luaL_ref(L, LUA_REGISTRYINDEX); // store reference to function to run new_script->next_run_ms = AP_HAL::millis64() - 1; // force the script to be stale // Get checksum of file @@ -254,10 +256,13 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) { if (dirname == nullptr) { return; } - auto *d = AP::FS().opendir(dirname); if (d == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Lua: open directory (%s) failed", dirname); + // this disk_space check will return 0 if we don't have a real + // filesystem (ie. no Posix or FatFs). Do not warn in this case. + if (AP::FS().disk_space(dirname) != 0) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Lua: open directory (%s) failed", dirname); + } return; } @@ -269,8 +274,8 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) { continue; } - if (strncmp(&de->d_name[length-4], ".lua", 4)) { - // doesn't end in .lua + if ((de->d_name[0] == '.') || strncmp(&de->d_name[length-4], ".lua", 4)) { + // starts with . (hidden file) or doesn't end in .lua continue; } @@ -291,7 +296,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) { reschedule_script(script); #if HAL_LOGGER_FILE_CONTENTS_ENABLED - if ((_debug_options.get() & uint8_t(DebugLevel::SUPPRESS_SCRIPT_LOG)) == 0) { + if (!option_is_set(AP_Scripting::DebugOption::SUPPRESS_SCRIPT_LOG)) { AP::logger().log_file_content(filename); } #endif @@ -326,8 +331,9 @@ void lua_scripts::run_next_script(lua_State *L) { int stack_top = lua_gettop(L); // pop the function to the top of the stack - lua_rawgeti(L, LUA_REGISTRYINDEX, script->lua_ref); - AP::scripting()->set_current_ref(script->lua_ref); + lua_rawgeti(L, LUA_REGISTRYINDEX, script->run_ref); + // set current environment for other users + AP::scripting()->set_current_env_ref(script->env_ref); if(lua_pcall(L, 0, LUA_MULTRET, 0)) { if (overtime) { @@ -365,8 +371,8 @@ void lua_scripts::run_next_script(lua_State *L) { // types match the expectations, go ahead and reschedule script->next_run_ms = start_time_ms + (uint64_t)luaL_checknumber(L, -1); lua_pop(L, 1); - int old_ref = script->lua_ref; - script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); + int old_ref = script->run_ref; + script->run_ref = luaL_ref(L, LUA_REGISTRYINDEX); luaL_unref(L, LUA_REGISTRYINDEX, old_ref); reschedule_script(script); break; @@ -410,7 +416,8 @@ void lua_scripts::remove_script(lua_State *L, script_info *script) { if (L != nullptr) { // state could be null if we are force killing all scripts - luaL_unref(L, LUA_REGISTRYINDEX, script->lua_ref); + luaL_unref(L, LUA_REGISTRYINDEX, script->env_ref); + luaL_unref(L, LUA_REGISTRYINDEX, script->run_ref); } _heap.deallocate(script->name); _heap.deallocate(script); @@ -458,19 +465,6 @@ void *lua_scripts::alloc(void *ud, void *ptr, size_t osize, size_t nsize) { return _heap.change_size(ptr, osize, nsize); } -void lua_scripts::repl_cleanup (void) { - if (terminal.session) { - terminal.session = false; - if (terminal.output_fd != -1) { - AP::FS().close(terminal.output_fd); - terminal.output_fd = -1; - AP::FS().unlink(REPL_DIRECTORY "/in"); - AP::FS().unlink(REPL_DIRECTORY "/out"); - AP::FS().unlink(REPL_DIRECTORY); - } - } -} - void lua_scripts::run(void) { bool succeeded_initial_load = false; @@ -493,8 +487,6 @@ void lua_scripts::run(void) { } scripts = nullptr; overtime = false; - // end any open REPL sessions - repl_cleanup(); } lua_state = lua_newstate(alloc, NULL); @@ -511,6 +503,16 @@ void lua_scripts::run(void) { lua_atpanic(L, atpanic); load_generated_bindings(L); + // set up string metatable. we set up one for all scripts that no script has + // access to, as it's impossible to set up one per-script and we don't want + // any script to be able to mess with it. + lua_pushliteral(L, ""); /* dummy string */ + lua_createtable(L, 0, 1); /* table to be metatable for strings */ + luaopen_string(L); /* get string library */ + lua_setfield(L, -2, "__index"); /* metatable.__index = string */ + lua_setmetatable(L, -2); /* set table as metatable for strings */ + lua_pop(L, 1); /* pop dummy string */ + #ifndef HAL_CONSOLE_DISABLED const int loaded_mem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0); DEV_PRINTF("Lua: State memory usage: %i + %i\n", inital_mem, loaded_mem - inital_mem); @@ -538,13 +540,9 @@ void lua_scripts::run(void) { succeeded_initial_load = true; #endif // __clang_analyzer__ - while (AP_Scripting::get_singleton()->should_run()) { - // handle terminal data if we have any - if (terminal.session) { - doREPL(L); - continue; - } + uint32_t expansion_size = 0; + while (AP_Scripting::get_singleton()->should_run()) { #if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1 if (lua_gettop(L) != 0) { AP_HAL::panic("Lua: Stack should be empty before running scripts"); @@ -569,11 +567,14 @@ void lua_scripts::run(void) { hal.scheduler->delay(scripts->next_run_ms - now_ms); } - if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) { + if (option_is_set(AP_Scripting::DebugOption::RUNTIME_MSG)) { GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name); } - // copy name for logging, cant do it after as script reschedule moves the pointers - const char * script_name = scripts->name; + // take a copy of the script name for the purposes of + // logging statistics. "scripts" may become invalid + // during the "run_next_script" call, below. + char script_name[128+1] {}; + strncpy_noterm(script_name, scripts->name, 128); #if DISABLE_INTERRUPTS_FOR_SCRIPT_RUN void *istate = hal.scheduler->disable_interrupts_save(); @@ -582,6 +583,10 @@ void lua_scripts::run(void) { const int startMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0); const uint32_t loadEnd = AP_HAL::micros(); + // NOTE! the base pointer of our scripts linked list, + // *and all its contents* may become invalid as part of + // "run_next_script"! So do *NOT* attempt to access + // anything that was in *scripts after this call. run_next_script(L); const uint32_t runEnd = AP_HAL::micros(); @@ -598,12 +603,23 @@ void lua_scripts::run(void) { lua_gc(L, LUA_GCCOLLECT, 0); } else { - if ((_debug_options.get() & uint8_t(DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { + if (option_is_set(AP_Scripting::DebugOption::NO_SCRIPTS_TO_RUN)) { GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: No scripts to run"); } hal.scheduler->delay(1000); } + /* + report a warning if SCR_HEAP_SIZE wasn't adequate and we + expanded at runtime, so the user can fix it for future + flights + */ + const uint32_t new_expansion_size = _heap.get_expansion_size(); + if (new_expansion_size > expansion_size) { + expansion_size = new_expansion_size; + set_and_print_new_error_message(MAV_SEVERITY_WARNING, "Required SCR_HEAP_SIZE over %u", unsigned(expansion_size)); + } + // 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)) { diff --git a/libraries/AP_Scripting/lua_scripts.h b/libraries/AP_Scripting/lua_scripts.h index 04001f39bfb605..d08bb6fe59a9a5 100644 --- a/libraries/AP_Scripting/lua_scripts.h +++ b/libraries/AP_Scripting/lua_scripts.h @@ -26,7 +26,7 @@ #include #include #include -#include +#include #include "lua_common_defs.h" #include "lua/src/lua.hpp" @@ -34,7 +34,7 @@ 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); + lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, AP_Int8 &debug_options); ~lua_scripts(); @@ -48,22 +48,13 @@ class lua_scripts static bool overtime; // script exceeded it's execution slot, and we are bailing out - enum class DebugLevel { - NO_SCRIPTS_TO_RUN = 1U << 0, - RUNTIME_MSG = 1U << 1, - SUPPRESS_SCRIPT_LOG = 1U << 2, - LOG_RUNTIME = 1U << 3, - DISABLE_PRE_ARM = 1U << 4, - SAVE_CHECKSUM = 1U << 5, - }; - private: void create_sandbox(lua_State *L); - void repl_cleanup(void); typedef struct script_info { - int lua_ref; // reference to the loaded script object + int env_ref; // reference to the script's environment table + int run_ref; // reference to the function to run uint64_t next_run_ms; // time (in milliseconds) the script should next be run at uint32_t crc; // crc32 checksum char *name; // filename for the script // FIXME: This information should be available from Lua @@ -83,20 +74,6 @@ class lua_scripts // reschedule the script for execution. It is assumed the script is not in the list already void reschedule_script(script_info *script); - // REPL stuff - struct AP_Scripting::terminal_s &terminal; - void doREPL(lua_State *L); - void l_print(lua_State *L); - void terminal_print(const char *str); - int loadline(lua_State *L); - int multiline(lua_State *L); - int addreturn(lua_State *L); - int pushline(lua_State *L, int firstline); - int incomplete(lua_State *L, int status); - const char * get_prompt(lua_State *L, int firstline); - int docall(lua_State *L, int narg, int nres) const; - int sandbox_ref; - script_info *scripts; // linked list of scripts to be run, sorted by next run time (soonest first) // hook will be run when CPU time for a script is exceeded @@ -110,7 +87,11 @@ class lua_scripts lua_State *lua_state; const AP_Int32 & _vm_steps; - const AP_Int8 & _debug_options; + AP_Int8 & _debug_options; + + bool option_is_set(AP_Scripting::DebugOption option) const { + return (uint8_t(_debug_options.get()) & uint8_t(option)) != 0; + } static void *alloc(void *ud, void *ptr, size_t osize, size_t nsize); @@ -125,7 +106,6 @@ class lua_scripts static HAL_Semaphore error_msg_buf_sem; static uint8_t print_error_count; static uint32_t last_print_ms; - int current_ref; // XOR of crc32 of running scripts static uint32_t loaded_checksum; diff --git a/libraries/AP_Scripting/modules/MAVLink/Readme.md b/libraries/AP_Scripting/modules/MAVLink/Readme.md new file mode 100644 index 00000000000000..c2424727643b46 --- /dev/null +++ b/libraries/AP_Scripting/modules/MAVLink/Readme.md @@ -0,0 +1,8 @@ +These .lua definition for messages can be generated using pymavlink with the following command: +(change the last path accordingly to place the files where you need them) +``` +cd ardupilot/modules/mavlink +python ./pymavlink/tools/mavgen.py --lang Lua ./message_definitions/v1.0/all.xml --out ./modules/MAVLink +``` + +Add `--wire-protocol 2.0` to include extension fields in the generated code diff --git a/libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_LONG.lua b/libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_LONG.lua index ba40100f41ae0b..7302529ea4c308 100644 --- a/libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_LONG.lua +++ b/libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_LONG.lua @@ -1,5 +1,6 @@ local COMMAND_LONG = {} COMMAND_LONG.id = 76 +COMMAND_LONG.crc_extra = 152 COMMAND_LONG.fields = { { "param1", "> 8) ~ (tmp << 8) ~ (tmp << 3) ~ (tmp >> 4) + crc = crc & 0xFFFF + end + return crc +end + +-- Note that this does not parse the serial data, it parses the MAVLink 2 C structure `mavlink_message_t` +-- This structure is passed in by the ArduPilot bindings as a string +---@param message any -- encoded message +---@param msg_map table -- table containing message objects with keys of the message ID +---@return table|nil -- a table representing the contents of the message, or nill if decode failed function mavlink_msgs.decode(message, msg_map) - local result, offset = mavlink_msgs.decode_header(message) + local result = mavlink_msgs.decode_header(message) local message_map = require("MAVLink/mavlink_msg_" .. msg_map[result.msgid]) if not message_map then -- we don't know how to decode this message, bail on it return nil end + -- If we have a crc extra for this message then check it + -- This ensures compatibility with message definitions generated before the crc check was added + if message_map.crc_extra then + -- crc of payload and header values + local crc_buffer + if result.protocol_version == 2 then + crc_buffer = string.sub(message, 4, 12 + result.payload_length) + + else + -- V1 does not include all fields on the wire + crc_buffer = string.char(result.payload_length) + crc_buffer = crc_buffer .. string.char(result.seq) + crc_buffer = crc_buffer .. string.char(result.sysid) + crc_buffer = crc_buffer .. string.char(result.compid) + crc_buffer = crc_buffer .. string.char(result.msgid) + if result.payload_length > 0 then + crc_buffer = crc_buffer .. string.sub(message, 13, 12 + result.payload_length) + end + + end + + local crc = mavlink_msgs.generateCRC(crc_buffer .. string.char(message_map.crc_extra)) + + if crc ~= result.checksum then + -- crc failed + return nil + end + end + -- map all the fields out + local offset = 13 for _,v in ipairs(message_map.fields) do if v[3] then result[v[1]] = {} @@ -55,14 +113,22 @@ function mavlink_msgs.decode(message, msg_map) end else result[v[1]], offset = string.unpack(v[2], message, offset) + if string.sub(v[2],2,2) == 'c' then + -- Got string, unpack includes 0 values to the set length + -- this is annoying, so remove them + result[v[1]] = string.gsub(result[v[1]], string.char(0), "") + end end end - -- ignore the idea of a checksum - - return result; + return result end +---Encode the payload section of a given message +---@param msgname string -- name of message to encode +---@param message table -- table containing key value pairs representing the data fields in the message +---@return integer -- message id +---@return string -- encoded payload function mavlink_msgs.encode(msgname, message) local message_map = require("MAVLink/mavlink_msg_" .. msgname) if not message_map then diff --git a/libraries/AP_Scripting/modules/NMEA_2000.lua b/libraries/AP_Scripting/modules/NMEA_2000.lua new file mode 100644 index 00000000000000..3a4b63d1d961ef --- /dev/null +++ b/libraries/AP_Scripting/modules/NMEA_2000.lua @@ -0,0 +1,119 @@ +--[[ + NMEA 2000 parser as lua module + with thanks to https://canboat.github.io/canboat/canboat.html + + caller must setup a PGN expected size table with set_PGN_table() +--]] + +local M = {} + +M.PGN_table = {} + +-- multi-frame pending data +M.pending = { pgn = nil, data = "", count = 0, expected_size = 0 } + +-- Extract the PGN (Parameter Group Number) from the message ID +local function extract_pgn(message_id) + local PF = (message_id >> 16) & 0xFF + local RDP = (message_id >> 24) & 0x3 + if PF < 0xF0 then + return (RDP << 16) | (PF << 8) + else + local PS = (message_id >> 8) & 0xFF + return (RDP << 16) | (PF << 8) | PS + end +end + +--[[ + extract data from a CAN frame as a lua binary string +--]] +local function extract_data(frame, max_len) + local ret = "" + local dlc = frame:dlc() + local len = math.min(dlc, max_len) + for ofs = 1, len do + ret = ret .. string.char(frame:data(ofs-1)) + end + return ret +end + +--[[ + set table of PGNs that we are interested in along with the expected packet size + + The table should be indexed by the PGN and give the expected size + of that PGN any frames with PGNs not in this table will be + discarded +--]] +function M.set_PGN_table(t) + M.PGN_table = t +end + +-- Parse CAN frame and reassemble messages +function M.parse(can_frame) + if not can_frame:isExtended() then + -- NMEA 2000 frame are always extended (29 bit address) + return nil + end + local message_id = can_frame:id_signed() + + local pgn = extract_pgn(message_id) + local dlc = can_frame:dlc() + + local exp_size = M.PGN_table[pgn] + if not exp_size then + -- discard unwated frame and reset pending + M.pending.pgn = nil + return nil + end + + if exp_size <= 8 and exp_size > dlc then + -- discard short frame + M.pending.pgn = nil + return nil + end + + if exp_size <= 8 then + -- single frame + local data = extract_data(can_frame, exp_size) + M.pending.pgn = nil + return pgn, data + end + + -- multi-frame + local data = extract_data(can_frame, dlc) + local subframe = string.byte(data, 1) & 0x1F + if M.pending.pgn ~= pgn or subframe ~= M.pending.count then + -- reset + M.pending.pgn = nil + M.pending.data = "" + M.pending.count = 0 + + if subframe ~= 0 then + -- discard, lost first frame or out of order + return nil + end + end + + if subframe == 0 then + M.pending.expected_size = string.byte(data, 2) + if M.pending.expected_size < exp_size then + M.pending.pgn = nil + return nil + end + M.pending.data = M.pending.data .. string.sub(data, 3, #data) + else + M.pending.data = M.pending.data .. string.sub(data, 2, #data) + end + M.pending.pgn = pgn + M.pending.count = M.pending.count + 1 + + -- do we have a complete frame + if #M.pending.data >= M.pending.expected_size then + M.pending.pgn = nil + return pgn, M.pending.data + end + + return nil +end + +return M diff --git a/libraries/AP_Scripting/modules/mavport.lua b/libraries/AP_Scripting/modules/mavport.lua new file mode 100644 index 00000000000000..7bb616899fbf4b --- /dev/null +++ b/libraries/AP_Scripting/modules/mavport.lua @@ -0,0 +1,166 @@ +-- class to cast mavlink SERIAL_CONTROL message functionality as a serial port. +-- currently always uses the "dev shell" device (which is ignored by Ardupilot). +-- designed for use with the Lua REPL applet. +-- note that flush() must be called to empty internal transmit buffers. + +local mavport = {} + +local mavlink_msgs = require("MAVLink/mavlink_msgs") + +local SERIAL_CONTROL_DATA_LEN = 70 +local SERIAL_CONTROL = require("MAVLink/mavlink_msg_SERIAL_CONTROL") +local msg_map = { + [SERIAL_CONTROL.id] = "SERIAL_CONTROL", +} + +function mavport:begin(_) + local data = {} + for i = 1, SERIAL_CONTROL_DATA_LEN do + data[i] = 0 + end + self._tx_template = { + baudrate = 0, + timeout = 0, + device = 10, -- dev shell + flags = 1, -- is reply + count = 0, + data = data, + } + + self._tx_buf = data + self._tx_count = 0 + self._tx_msg = nil + + self._chan = 0 -- send to channel 0 by default + + self._rx_buf = nil + self._rx_pos = 1 + + mavlink.init(1, 4) -- only one message we care about, don't need huge queue + mavlink.register_rx_msgid(SERIAL_CONTROL.id) -- register it +end + +function mavport:write(value) + return self:writestring(string.char(value)) +end + +function mavport:writestring(str) + if self._tx_msg then -- message already queued? + self:flush() + if self._tx_msg then return 0 end -- reject if flush failed + end + + local count = self._tx_count + local buf = self._tx_buf + for ci = 1, #str do + if count == SERIAL_CONTROL_DATA_LEN then break end + count = count + 1 + buf[count] = str:byte(ci) + end + local sent = count - self._tx_count + self._tx_count = count + + if count == SERIAL_CONTROL_DATA_LEN then + self:flush() + end + + return sent +end + +function mavport:flush() -- send queued data if possible + if not self._tx_msg and self._tx_count > 0 then + -- encode the message and store it for transmission + local msg = self._tx_template + msg.count = self._tx_count + _, self._tx_msg = mavlink_msgs.encode("SERIAL_CONTROL", msg) + self._tx_count = 0 + end + + if self._tx_msg then -- message to send? + if mavlink.send_chan(self._chan, SERIAL_CONTROL.id, self._tx_msg) then + self._tx_msg = nil -- successfully sent + end + end +end + +function mavport:read() + if not self._rx_buf then + self:_receive() + if not self._rx_buf then return -1 end + end + + local b = self._rx_buf + local pos = self._rx_pos + local c = b[pos] + + self._rx_pos = pos + 1 + if pos == #b then + self._rx_buf = nil + end + + return c +end + +function mavport:readstring(count) + local avail = self:available() -- also fills rx buf + if avail == 0 then return "" end + if count > avail then count = avail end + + local b = self._rx_buf + local pos = self._rx_pos + local s = string.char(table.unpack(b, pos, pos+count-1)) + + pos = pos + count + if pos > #b then + self._rx_buf = nil + end + self._rx_pos = pos + + return s +end + +function mavport:_receive() + local msg, chan + while true do + msg, chan = mavlink.receive_chan() + if not msg then return end -- no new messages + + -- decode message and handle if it's for us + msg = mavlink_msgs.decode(msg, msg_map) + if msg.device == 10 then -- for the dev shell? + self._chan = chan -- reply on the same channel + break + end + end + + local data = msg.data + local count = msg.count + -- remove trailing nulls, they shouldn't happen but they do + while data[count] == 0 do + count = count - 1 + end + + -- store received bytes + if count > 0 then + if count < SERIAL_CONTROL_DATA_LEN then -- remove trailing junk + data = table.move(data, 1, count, 1, {}) + end + self._rx_buf = data + self._rx_pos = 1 + end +end + +function mavport:available() + if not self._rx_buf then + self:_receive() + if not self._rx_buf then return 0 end + end + + return #self._rx_buf - self._rx_pos + 1 +end + +-- for completeness +function mavport.set_flow_control(_, _) +end + +return mavport diff --git a/libraries/AP_Scripting/tests/check.json b/libraries/AP_Scripting/tests/check.json new file mode 100644 index 00000000000000..899d55a5a559e9 --- /dev/null +++ b/libraries/AP_Scripting/tests/check.json @@ -0,0 +1,20 @@ +{ // lua-language-server config for checking + "$schema": "https://raw.githubusercontent.com/LuaLS/vscode-lua/master/setting/schema.json", + "runtime.version": "Lua 5.3", + "runtime.builtin": { + // Not all of the standard functionality is available + "coroutine": "disable", + "os": "disable", + "debug": "disable", + "ffi": "disable", + "jit": "disable", + "table.clear": "disable", + "table.new": "disable" + }, + "workspace": { + // These lua scripts are not for running on AP + "ignoreDir": ["Tools/CHDK-Scripts/*", "modules/*", "libraries/AP_Scripting/tests/luacheck.lua", "lua-language-server/*"], + // Dont use gitignore, it results in skipping checks for in progress scripts running in SITL + "useGitIgnore": false + } +} diff --git a/libraries/AP_Scripting/tests/docs.json b/libraries/AP_Scripting/tests/docs.json new file mode 100644 index 00000000000000..90b9fd5cbef339 --- /dev/null +++ b/libraries/AP_Scripting/tests/docs.json @@ -0,0 +1,22 @@ +{ // lua-language-server config for docs generation + "runtime.version": "Lua 5.3", + "runtime.builtin": { + "basic": "disable", + "bit": "disable", + "bit32": "disable", + "builtin": "disable", + "coroutine": "disable", + "debug": "disable", + "ffi": "disable", + "io": "disable", + "jit": "disable", + "math": "disable", + "os": "disable", + "package": "disable", + "string": "disable", + "table": "disable", + "table.clear": "disable", + "table.new": "disable", + "utf8": "disable" + } +} diff --git a/libraries/AP_Scripting/tests/docs_check.py b/libraries/AP_Scripting/tests/docs_check.py index a8bc1320dda21c..376bd9f99a4339 100644 --- a/libraries/AP_Scripting/tests/docs_check.py +++ b/libraries/AP_Scripting/tests/docs_check.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + ''' Reads two lua docs files and checks for differences @@ -6,14 +8,24 @@ AP_FLAKE8_CLEAN ''' -import optparse, sys +import optparse, sys, re class method(object): - def __init__(self, global_name, local_name, num_args, full_line): + def __init__(self, global_name, local_name, num_args, full_line, returns, params): self.global_name = global_name self.local_name = local_name self.num_args = num_args self.full_line = full_line + self.returns = returns + self.params = params + self.manual = False + for i in range(len(self.returns)): + if self.returns[i][0] == 'UNKNOWN': + self.manual = True + + for i in range(len(self.params)): + if self.params[i][0] == 'UNKNOWN': + self.manual = True def __str__(self): ret_str = "%s\n" % (self.full_line) @@ -22,20 +34,99 @@ def __str__(self): ret_str += "\tFunction: %s\n" % (self.local_name) else: ret_str += "\tGlobal: %s\n" % (self.global_name) - ret_str += "\tNum Args: %s\n\n" % (self.num_args) + ret_str += "\tNum Args: %s\n" % (self.num_args) + + ret_str += "\tParams:\n" + for param_type in self.params: + ret_str += "\t\t%s\n" % param_type + + ret_str += "\tReturns:\n" + for return_type in self.returns: + ret_str += "\t\t%s\n" % return_type + + ret_str +="\n" return ret_str + def type_compare(self, A, B): + if (((len(A) == 1) and (A[0] == 'UNKNOWN')) or + ((len(B) == 1) and (B[0] == 'UNKNOWN'))): + # UNKNOWN is a special case used for manual bindings + return True + + if len(A) != len(B): + return False + + for i in range(len(A)): + if A[i] != B[i]: + return False + + return True + + def types_compare(self, A, B): + if len(A) != len(B): + return False + + for i in range(len(A)): + if not self.type_compare(A[i], B[i]): + return False + + return True + + def check_types(self, other): + if not self.types_compare(self.returns, other.returns): + return False + + if not self.types_compare(self.params, other.params): + return False + + return True + def __eq__(self, other): return (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args == other.num_args) + def is_overload(self, other): + # this allows multiple function definitions with different params + white_list = [ + "Parameter" + ] + allow_override = other.manual or (self.global_name in white_list) + return allow_override and (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args != other.num_args) + +def get_return_type(line): + try: + match = re.findall(r"^---@return (\w+(\|(\w+))*)", line) + all_types = match[0][0] + return all_types.split("|") + + except: + raise Exception("Could not get return type in: %s" % line) + +def get_param_type(line): + try: + match = re.findall(r"^---@param (?:\w+\??|...) (\w+(\|(\w+))*)", line) + all_types = match[0][0] + return all_types.split("|") + + except: + raise Exception("Could not get param type in: %s" % line) + def parse_file(file_name): methods = [] + returns = [] + params = [] with open(file_name) as fp: while True: line = fp.readline() if not line: break + # Acuminate return and params to associate with next function + if line.startswith("---@return"): + returns.append(get_return_type(line)) + + if line.startswith("---@param"): + params.append(get_param_type(line)) + # only consider functions if not line.startswith("function"): continue @@ -57,13 +148,16 @@ def parse_file(file_name): # get arguments function_name, args = function_line.split("(",1) - args = args[0:args.find(")")-1] + args = args[0:args.find(")")] if len(args) == 0: num_args = 0 else: num_args = args.count(",") + 1 + if num_args != len(params): + raise Exception("Missing \"---@param\" for function: %s", line) + # get global/class name and function name local_name = "" if function_name.count(":") == 1: @@ -71,7 +165,9 @@ def parse_file(file_name): else: global_name = function_name - methods.append(method(global_name, local_name, num_args, line)) + methods.append(method(global_name, local_name, num_args, line, returns, params)) + returns = [] + params = [] return methods @@ -92,6 +188,15 @@ def compare(expected_file_name, got_file_name): print("Multiple definitions of:") print(meth) pass_check = False + + elif not meth.check_types(got): + print("Type error:") + print("Want:") + print(meth) + print("Got:") + print(got) + pass_check = False + found = True if not found: @@ -100,11 +205,21 @@ def compare(expected_file_name, got_file_name): pass_check = False + # White list of classes that are allowed unexpected definitions + white_list = [ + # "virtual" class to bypass need for nil check when getting a parameter value, Parameter_ud is used internally, Parameter_ud_const exists only in the docs. + "Parameter_ud_const" + ] + # make sure no unexpected methods are included for got in got_methods: + if got.global_name in white_list: + # Dont check if in the white list + continue + found = False for meth in expected_methods: - if got == meth: + if (got == meth) or got.is_overload(meth): found = True break if not found: diff --git a/libraries/AP_Scripting/tests/luacheck.lua b/libraries/AP_Scripting/tests/luacheck.lua index 2ae950e89f6ce9..c200da54b5d592 100644 --- a/libraries/AP_Scripting/tests/luacheck.lua +++ b/libraries/AP_Scripting/tests/luacheck.lua @@ -8,7 +8,7 @@ ignore = {"111", -- Setting an undefined global variable. "614"} -- Trailing whitespace in a comment. -- These lua scripts are not for running on AP -exclude_files = {"Tools/CHDK-Scripts/*", "modules/*", "libraries/AP_Scripting/tests/luacheck.lua"} +exclude_files = {"Tools/CHDK-Scripts/*", "modules/*", "libraries/AP_Scripting/tests/luacheck.lua", "lua-language-server/*"} -- Grab AP globals from docs file stds.ArduPilot = {} diff --git a/libraries/AP_Scripting/tests/math.lua b/libraries/AP_Scripting/tests/math.lua index 4cfeb4ffe4683e..e70d48ba66101a 100644 --- a/libraries/AP_Scripting/tests/math.lua +++ b/libraries/AP_Scripting/tests/math.lua @@ -33,6 +33,9 @@ -- luacheck: ignore 421 (Shadowing a local variable) -- luacheck: ignore 581 (Negation of a relational operator - operator can be flipped) +---@diagnostic disable: cast-local-type +---@diagnostic disable: undefined-global + gcs:send_text(6, "testing numbers and math lib") local minint = math.mininteger diff --git a/libraries/AP_Scripting/tests/mavlink_test.lua b/libraries/AP_Scripting/tests/mavlink_test.lua index cc2a062bdd116c..c03fe2af24ea88 100644 --- a/libraries/AP_Scripting/tests/mavlink_test.lua +++ b/libraries/AP_Scripting/tests/mavlink_test.lua @@ -1,3 +1,6 @@ +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: missing-parameter + local mavlink_msgs = require("mavlink/mavlink_msgs") local msg_map = {} diff --git a/libraries/AP_Scripting/tests/scripting_require_test_2.lua b/libraries/AP_Scripting/tests/scripting_require_test_2.lua new file mode 100644 index 00000000000000..f0bd9d270424f9 --- /dev/null +++ b/libraries/AP_Scripting/tests/scripting_require_test_2.lua @@ -0,0 +1,35 @@ +-- main require tests are in scripting_test.lua + +-- DO NOT EDIT!!!! it's very easy to make this accidentally pass even when the +-- original problem is still present!! we do some very careful work to check +-- that require works even when the function's first upvalue is not the script +-- environment. + +local loop_time = 500 -- number of ms between runs + +-- need to shadow gcs to make the upvalues right +local gcs = gcs -- luacheck: ignore + +local passes = 0 -- run both before and after scheduling + +local require_global = require("test/nested") + +local function update() + -- need to send before requiring to make the upvalues right + gcs:send_text(6, "testing") + local require_local = require("test/nested") -- should not crash + + -- validate we got the same object (object contents validated in main test) + if require_local == require_global then + passes = passes + 1 + else + gcs:send_text(0, "Failed: require returned different objects") + end + if passes >= 3 then + gcs:send_text(3, "Require test 2 passed") + end + + return update, loop_time +end + +return update() -- run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/tests/scripting_test.lua b/libraries/AP_Scripting/tests/scripting_test.lua index 4f794e5493b0ad..741d852c395e7d 100644 --- a/libraries/AP_Scripting/tests/scripting_test.lua +++ b/libraries/AP_Scripting/tests/scripting_test.lua @@ -35,6 +35,34 @@ function test_offset(ofs_e, ofs_n) return true end +function test_uint64() + local pass = true + + local zero = uint64_t() + local max = uint64_t(-1, -1) + + pass = pass and (zero - 1) == max + pass = pass and ~max == zero + pass = pass and max > zero + pass = pass and (((zero + 1) + 1.1) + uint32_t(1)) == uint64_t(0, 3) + pass = pass and tostring(zero) == "0" + pass = pass and (uint64_t(15) & uint64_t(130)) == uint32_t(2) + pass = pass and (uint64_t(1) | uint64_t(2)) == uint64_t(3) + pass = pass and (uint64_t(1) << 1) == uint64_t(2) + pass = pass and (uint64_t(16) >> 1) == uint64_t(8) + pass = pass and type(zero:tofloat()) == "number" + pass = pass and zero:tofloat() == 0 + + local high, low + high, low = zero:split() + pass = pass and high == uint32_t(0) and low == uint32_t(0) + + high, low = max:split() + pass = pass and high == uint32_t(-1) and low == uint32_t(-1) + + return pass +end + function update() local all_tests_passed = true local require_test_local = require('test/nested') @@ -53,6 +81,7 @@ function update() end -- each test should run then and it's result with the previous ones all_tests_passed = test_offset(500, 200) and all_tests_passed + all_tests_passed = test_uint64() and all_tests_passed if all_tests_passed then gcs:send_text(3, "Internal tests passed") diff --git a/libraries/AP_Scripting/tests/serial_loopback.lua b/libraries/AP_Scripting/tests/serial_loopback.lua new file mode 100644 index 00000000000000..9893c8f7d8e47f --- /dev/null +++ b/libraries/AP_Scripting/tests/serial_loopback.lua @@ -0,0 +1,36 @@ +local ser_driver = serial:find_serial(0) +local ser_device = serial:find_simulated_device(28, 0) + +if ser_driver == nil or ser_device == nil then + error("bad config") +end + +ser_driver:begin(115200) -- baud rate does not matter + +function test_driver_to_device() + local msg_send = "hello device" + local num_sent = 0 + for ci = 1,#msg_send do + num_sent = num_sent + ser_driver:write(msg_send:byte(ci, ci)):toint() + end + local msg_recv = ser_device:readstring(#msg_send) + if msg_send == msg_recv and num_sent == #msg_send then + gcs:send_text(6, "driver -> device good") + end +end + +function test_device_to_driver() + local msg_send = "hello driver" + local num_sent = ser_device:writestring(msg_send) + local msg_recv = ser_driver:readstring(#msg_send) + if msg_send == msg_recv and num_sent == #msg_send then + gcs:send_text(6, "device -> driver good") + end +end + +function update() + test_driver_to_device() + test_device_to_driver() +end + +return update() diff --git a/libraries/AP_Scripting/tests/strings.lua b/libraries/AP_Scripting/tests/strings.lua index 79fde4c4fb8c84..fb19ebcda5a89d 100644 --- a/libraries/AP_Scripting/tests/strings.lua +++ b/libraries/AP_Scripting/tests/strings.lua @@ -29,6 +29,11 @@ -- luacheck: ignore 581 (Negation of a relational operator - operator can be flipped) +---@diagnostic disable: param-type-mismatch +---@diagnostic disable: missing-parameter +---@diagnostic disable: undefined-global + + gcs:send_text(6, 'testing strings and string library') local maxi, mini = math.maxinteger, math.mininteger diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index f9a38712fe007f..3149209180b389 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -173,7 +173,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 0_PROTOCOL // @DisplayName: Console protocol selection // @Description: Control what protocol to use on the console. - // @Values: 1:MAVlink1, 2:MAVLink2 + // @Values: 1:MAVLink1, 2:MAVLink2 // @User: Standard // @RebootRequired: True AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2), @@ -502,14 +502,9 @@ void AP_SerialManager::init() state[i].protocol.set_and_save(SerialProtocol_Rangefinder); break; case SerialProtocol_Volz: - // Note baudrate is hardcoded to 115200 - 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; + // Note baudrate is hardcoded to 115200 + state[i].baud.set_and_default(AP_SERIALMANAGER_VOLZ_BAUD); // update baud param in case user looks at it + break; case SerialProtocol_Sbus1: 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(), @@ -546,6 +541,8 @@ void AP_SerialManager::init() case SerialProtocol_RCIN: if (!AP::RC().has_uart()) { AP::RC().add_uart(uart); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SERIAL%u_PROTOCOL: duplicate RCIN not permitted", i); } break; diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index c91330286a045b..1d8f74d69f0b22 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -86,6 +86,7 @@ class AP_SerialManager { // Reserving Serial Protocol 47 for SerialProtocol_IQ SerialProtocol_PPP = 48, SerialProtocol_IrisOrca = 49, + SerialProtocol_IBUS_Telem = 50, // i-BUS telemetry data, ie via sensor port of FS-iA6B SerialProtocol_NumProtocols // must be the last value }; @@ -175,6 +176,8 @@ class AP_SerialManager { */ class RegisteredPort : public AP_HAL::UARTDriver { public: + uint32_t bw_in_bytes_per_second() const override { return state.baudrate()/10; } + uint32_t get_baud_rate() const override { return state.baudrate(); } RegisteredPort *next; UARTState state; }; diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index fb25527a8ff7ff..22c2f871b3c1e9 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -19,7 +19,7 @@ */ #pragma once -#include +#include #include #include @@ -71,6 +71,9 @@ #define AP_SERIALMANAGER_CAN_D1_PORT_1 41 // CAN_D1_UC_S1_* #define AP_SERIALMANAGER_CAN_D2_PORT_1 51 // CAN_D2_UC_S1_* +// serial device simulation ports registered by AP_Scripting will use IDs starting at 61 for the first port +#define AP_SERIALMANAGER_SCR_PORT_1 61 // SCR_SDEV1_* + // console default baud rates and buffer sizes #ifdef DEFAULT_SERIAL0_BAUD #define AP_SERIALMANAGER_CONSOLE_BAUD DEFAULT_SERIAL0_BAUD @@ -111,8 +114,6 @@ #define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128 #define AP_SERIALMANAGER_VOLZ_BAUD 115 -#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128 #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128 #define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128 diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index 173d12c8f4079c..ed25eee43b4c30 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -117,7 +117,7 @@ void AP_SmartRTL::init() // check if memory allocation failed if (_path == nullptr || _prune.loops == nullptr || _simplify.stack == nullptr) { - log_action(SRTL_DEACTIVATED_INIT_FAILED); + log_action(Action::DEACTIVATED_INIT_FAILED); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: init failed"); free(_path); free(_prune.loops); @@ -150,7 +150,7 @@ bool AP_SmartRTL::pop_point(Vector3f& point) // get semaphore if (!_path_sem.take_nonblocking()) { - log_action(SRTL_POP_FAILED_NO_SEMAPHORE); + log_action(Action::POP_FAILED_NO_SEMAPHORE); return false; } @@ -180,7 +180,7 @@ bool AP_SmartRTL::peek_point(Vector3f& point) // get semaphore if (!_path_sem.take_nonblocking()) { - log_action(SRTL_PEEK_FAILED_NO_SEMAPHORE); + log_action(Action::PEEK_FAILED_NO_SEMAPHORE); return false; } @@ -268,12 +268,12 @@ void AP_SmartRTL::update(bool position_ok, const Vector3f& current_pos) _last_position_save_ms = now; } else if (AP_HAL::millis() - _last_position_save_ms > SMARTRTL_TIMEOUT) { // deactivate after timeout due to failure to save points to path (most likely due to buffer filling up) - deactivate(SRTL_DEACTIVATED_PATH_FULL_TIMEOUT, "buffer full"); + deactivate(Action::DEACTIVATED_PATH_FULL_TIMEOUT, "buffer full"); } } else { // check for timeout due to bad position if (AP_HAL::millis() - _last_good_position_ms > SMARTRTL_TIMEOUT) { - deactivate(SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT, "bad position"); + deactivate(Action::DEACTIVATED_BAD_POSITION_TIMEOUT, "bad position"); return; } } @@ -322,7 +322,7 @@ bool AP_SmartRTL::add_point(const Vector3f& point) { // get semaphore if (!_path_sem.take_nonblocking()) { - log_action(SRTL_ADD_FAILED_NO_SEMAPHORE, point); + log_action(Action::ADD_FAILED_NO_SEMAPHORE, point); return false; } @@ -338,13 +338,13 @@ bool AP_SmartRTL::add_point(const Vector3f& point) // check we have space in the path if (_path_points_count >= _path_points_max) { _path_sem.give(); - log_action(SRTL_ADD_FAILED_PATH_FULL, point); + log_action(Action::ADD_FAILED_PATH_FULL, point); return false; } // add point to path _path[_path_points_count++] = point; - log_action(SRTL_POINT_ADD, point); + log_action(Action::POINT_ADD, point); _path_sem.give(); return true; @@ -672,7 +672,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask() uint16_t removed = 0; for (uint16_t src = 1; src < _path_points_count; src++) { if (!_simplify.bitmask.get(src)) { - log_action(SRTL_POINT_SIMPLIFY, _path[src]); + log_action(Action::POINT_SIMPLIFY, _path[src]); removed++; } else { _path[dest] = _path[src]; @@ -687,7 +687,7 @@ void AP_SmartRTL::remove_points_by_simplify_bitmask() _simplify.path_points_completed = _simplify.path_points_count; } else { // this is an error that should never happen so deactivate - deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error"); + deactivate(Action::DEACTIVATED_PROGRAM_ERROR, "program error"); } _path_sem.give(); @@ -724,7 +724,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove) // shift points after the end of the loop down by the number of points in the loop uint16_t loop_num_points_to_remove = loop.end_index - loop.start_index; for (uint16_t dest = loop.start_index + 1; dest < _path_points_count - loop_num_points_to_remove; dest++) { - log_action(SRTL_POINT_PRUNE, _path[dest]); + log_action(Action::POINT_PRUNE, _path[dest]); _path[dest] = _path[dest + loop_num_points_to_remove]; } @@ -733,7 +733,7 @@ bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove) removed_points += loop_num_points_to_remove; } else { // this is an error that should never happen so deactivate - deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error"); + deactivate(Action::DEACTIVATED_PROGRAM_ERROR, "program error"); _path_sem.give(); // we return true so thorough_cleanup does not get stuck return true; @@ -862,7 +862,7 @@ AP_SmartRTL::dist_point AP_SmartRTL::segment_segment_dist(const Vector3f &p1, co } // de-activate SmartRTL, send warning to GCS and logger -void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) +void AP_SmartRTL::deactivate(Action action, const char *reason) { _active = false; log_action(action); @@ -871,7 +871,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) #if HAL_LOGGING_ENABLED // logging -void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const +void AP_SmartRTL::log_action(Action action, const Vector3f &point) const { if (!_example_mode) { AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point); diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.h b/libraries/AP_SmartRTL/AP_SmartRTL.h index 144762e512839d..d2c5b439e04c97 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.h +++ b/libraries/AP_SmartRTL/AP_SmartRTL.h @@ -41,6 +41,9 @@ class AP_SmartRTL { // get a point on the path const Vector3f& get_point(uint16_t index) const { return _path[index]; } + // add point to end of path. returns true on success, false on failure (due to failure to take the semaphore) + bool add_point(const Vector3f& point); + // get next point on the path to home, returns true on success bool pop_point(Vector3f& point); @@ -88,19 +91,19 @@ class AP_SmartRTL { private: // enums for logging latest actions - enum SRTL_Actions { - SRTL_POINT_ADD, - SRTL_POINT_PRUNE, - SRTL_POINT_SIMPLIFY, - SRTL_ADD_FAILED_NO_SEMAPHORE, - SRTL_ADD_FAILED_PATH_FULL, - SRTL_POP_FAILED_NO_SEMAPHORE, - SRTL_PEEK_FAILED_NO_SEMAPHORE, - SRTL_DEACTIVATED_INIT_FAILED, - SRTL_DEACTIVATED_BAD_POSITION, - SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT, - SRTL_DEACTIVATED_PATH_FULL_TIMEOUT, - SRTL_DEACTIVATED_PROGRAM_ERROR, + enum Action : uint8_t { + POINT_ADD = 0, + POINT_PRUNE = 1, + POINT_SIMPLIFY = 2, + ADD_FAILED_NO_SEMAPHORE = 3, + ADD_FAILED_PATH_FULL = 4, + POP_FAILED_NO_SEMAPHORE = 5, + PEEK_FAILED_NO_SEMAPHORE = 6, + DEACTIVATED_INIT_FAILED = 7, + // DEACTIVATED_BAD_POSITION = 8, unused, but historical + DEACTIVATED_BAD_POSITION_TIMEOUT = 9, + DEACTIVATED_PATH_FULL_TIMEOUT = 10, + DEACTIVATED_PROGRAM_ERROR = 11, }; // enum for SRTL_OPTIONS parameter @@ -109,9 +112,6 @@ class AP_SmartRTL { IgnorePilotYaw = (1U << 2), }; - // add point to end of path - bool add_point(const Vector3f& point); - // routine cleanup attempts to remove 10 points (see SMARTRTL_CLEANUP_POINT_MIN definition) by simplification or loop pruning void routine_cleanup(uint16_t path_points_count, uint16_t path_points_complete_limit); @@ -171,13 +171,13 @@ class AP_SmartRTL { static dist_point segment_segment_dist(const Vector3f& p1, const Vector3f& p2, const Vector3f& p3, const Vector3f& p4); // de-activate SmartRTL, send warning to GCS and logger - void deactivate(SRTL_Actions action, const char *reason); + void deactivate(Action action, const char *reason); #if HAL_LOGGING_ENABLED // logging - void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const; + void log_action(Action action, const Vector3f &point = Vector3f()) const; #else - void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const {} + void log_action(Action action, const Vector3f &point = Vector3f()) const {} #endif // parameters diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index bb51cd3948a10f..9fd24b35094c09 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -2,6 +2,7 @@ #if HAL_SOARING_ENABLED +#include #include #include #include @@ -432,15 +433,15 @@ void SoaringController::update_active_state(bool override_disable) switch (status) { case ActiveStatus::SOARING_DISABLED: // It's not enabled, but was enabled on the last loop. - gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Disabled."); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Soaring: Disabled."); set_throttle_suppressed(false); break; case ActiveStatus::MANUAL_MODE_CHANGE: // It's enabled, but wasn't on the last loop. - gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Enabled, manual mode changes."); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Soaring: Enabled, manual mode changes."); break; case ActiveStatus::AUTO_MODE_CHANGE: - gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Enabled, automatic mode changes."); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Soaring: Enabled, automatic mode changes."); break; } diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 4d13ef8e797d67..f9dd8b17c8073f 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -23,10 +23,10 @@ #include "Variometer.h" #include "SpeedToFly.h" -#define INITIAL_THERMAL_RADIUS 80.0 -#define INITIAL_STRENGTH_COVARIANCE 0.0049 -#define INITIAL_RADIUS_COVARIANCE 400.0 -#define INITIAL_POSITION_COVARIANCE 400.0 +static constexpr float INITIAL_THERMAL_RADIUS = 80.0; +static constexpr float INITIAL_STRENGTH_COVARIANCE = 0.0049; +static constexpr float INITIAL_RADIUS_COVARIANCE = 400.0; +static constexpr float INITIAL_POSITION_COVARIANCE = 400.0; class SoaringController { diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 712a6c3b4d5dcc..67e33fba03d8bc 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -4,6 +4,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. */ #include "Variometer.h" +#include #include Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) : diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index d5237b92dc81e4..4dea29fd05b90d 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -5,10 +5,11 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. */ #pragma once -#include #include #include +#include #include +#include class Variometer { diff --git a/libraries/AP_SurfaceDistance/AP_SurfaceDistance.cpp b/libraries/AP_SurfaceDistance/AP_SurfaceDistance.cpp new file mode 100644 index 00000000000000..af8ec0b42f0912 --- /dev/null +++ b/libraries/AP_SurfaceDistance/AP_SurfaceDistance.cpp @@ -0,0 +1,187 @@ +#include "AP_SurfaceDistance.h" + +#include + +#ifndef RANGEFINDER_TIMEOUT_MS + # define RANGEFINDER_TIMEOUT_MS 1000 // rangefinder filter reset if no updates from sensor in 1 second +#endif + +#if AP_RANGEFINDER_ENABLED + +#include +#include + +#ifndef RANGEFINDER_TILT_CORRECTION // by disable tilt correction for use of range finder data by EKF + # define RANGEFINDER_TILT_CORRECTION 1 +#endif + +#ifndef RANGEFINDER_GLITCH_NUM_SAMPLES + # define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading +#endif + +#ifndef RANGEFINDER_GLITCH_ALT_CM + # define RANGEFINDER_GLITCH_ALT_CM 200 // amount of rangefinder change to be considered a glitch +#endif + +#ifndef RANGEFINDER_HEALTH_MIN + # define RANGEFINDER_HEALTH_MIN 3 // number of good reads that indicates a healthy rangefinder +#endif + +void AP_SurfaceDistance::update() +{ + WITH_SEMAPHORE(sem); + + const RangeFinder *rangefinder = RangeFinder::get_singleton(); + if (rangefinder == nullptr) { + alt_healthy = false; + return; + } + +#if RANGEFINDER_TILT_CORRECTION == 1 + const float tilt_correction = MAX(0.707f, AP::ahrs().get_rotation_body_to_ned().c.z); +#else + const float tilt_correction = 1.0f; +#endif + + const uint32_t now = AP_HAL::millis(); + + // assemble bitmask assistance, definition is used to generate log documentation + enum class Surface_Distance_Status : uint8_t { + Enabled = 1U<<0, // true if rangefinder has been set to enable by vehicle + Unhealthy = 1U<<1, // true if rangefinder is considered unhealthy + Stale_Data = 1U<<2, // true if the last healthy rangefinder reading is no longer valid + Glitch_Detected = 1U<<3, // true if a measurement glitch detected + }; + + // reset status and add to the bitmask as we progress through the update + status = 0; + + // update enabled status + if (enabled) { + status |= (uint8_t)Surface_Distance_Status::Enabled; + } + + // update health + alt_healthy = (rangefinder->status_orient(rotation) == RangeFinder::Status::Good) && + (rangefinder->range_valid_count_orient(rotation) >= RANGEFINDER_HEALTH_MIN); + if (!alt_healthy) { + status |= (uint8_t)Surface_Distance_Status::Unhealthy; + } + + // tilt corrected but unfiltered, not glitch protected alt + alt_cm = tilt_correction * rangefinder->distance_cm_orient(rotation); + + // remember inertial alt to allow us to interpolate rangefinder + inertial_alt_cm = inertial_nav.get_position_z_up_cm(); + + // glitch handling. rangefinder readings more than RANGEFINDER_GLITCH_ALT_CM from the last good reading + // are considered a glitch and glitch_count becomes non-zero + // glitches clear after RANGEFINDER_GLITCH_NUM_SAMPLES samples in a row. + // glitch_cleared_ms is set so surface tracking (or other consumers) can trigger a target reset + const int32_t glitch_cm = alt_cm - alt_cm_glitch_protected; + bool reset_terrain_offset = false; + if (glitch_cm >= RANGEFINDER_GLITCH_ALT_CM) { + glitch_count = MAX(glitch_count+1, 1); + status |= (uint8_t)Surface_Distance_Status::Glitch_Detected; + } else if (glitch_cm <= -RANGEFINDER_GLITCH_ALT_CM) { + glitch_count = MIN(glitch_count-1, -1); + status |= (uint8_t)Surface_Distance_Status::Glitch_Detected; + } else { + glitch_count = 0; + alt_cm_glitch_protected = alt_cm; + } + if (abs(glitch_count) >= RANGEFINDER_GLITCH_NUM_SAMPLES) { + // clear glitch and record time so consumers (i.e. surface tracking) can reset their target altitudes + glitch_count = 0; + alt_cm_glitch_protected = alt_cm; + glitch_cleared_ms = now; + reset_terrain_offset = true; + } + + // filter rangefinder altitude + const bool timed_out = now - last_healthy_ms > RANGEFINDER_TIMEOUT_MS; + if (alt_healthy) { + if (timed_out) { + // reset filter if we haven't used it within the last second + alt_cm_filt.reset(alt_cm); + reset_terrain_offset = true; + status |= (uint8_t)Surface_Distance_Status::Stale_Data; + } else { + // TODO: When we apply this library in plane we will need to be able to set the filter freq + alt_cm_filt.apply(alt_cm, 0.05); + } + last_healthy_ms = now; + } + + // handle reset of terrain offset + if (reset_terrain_offset) { + if (rotation == ROTATION_PITCH_90) { + // upward facing + terrain_offset_cm = inertial_alt_cm + alt_cm; + } else { + // assume downward facing + terrain_offset_cm = inertial_alt_cm - alt_cm; + } + } +#if HAL_LOGGING_ENABLED + Log_Write(); +#endif +} + +/* + get inertially interpolated rangefinder height. Inertial height is + recorded whenever we update the rangefinder height, then we use the + difference between the inertial height at that time and the current + inertial height to give us interpolation of height from rangefinder + */ +bool AP_SurfaceDistance::get_rangefinder_height_interpolated_cm(int32_t& ret) const +{ + if (!enabled_and_healthy()) { + return false; + } + ret = alt_cm_filt.get(); + ret += inertial_nav.get_position_z_up_cm() - inertial_alt_cm; + return true; +} + +#if HAL_LOGGING_ENABLED +void AP_SurfaceDistance::Log_Write(void) const +{ + // @LoggerMessage: SURF + // @Vehicles: Copter + // @Description: Surface distance measurement + // @Field: TimeUS: Time since system startup + // @Field: I: Instance + // @FieldBitmaskEnum: St: Surface_Distance_Status + // @Field: D: Raw Distance + // @Field: FD: Filtered Distance + // @Field: TO: Terrain Offset + + //Write to data flash log + AP::logger().WriteStreaming("SURF", + "TimeUS,I,St,D,FD,TO", + "s#-mmm", + "F--000", + "QBBfff", + AP_HAL::micros64(), + instance, + status, + (float)alt_cm * 0.01, + (float)alt_cm_filt.get() * 0.01, + (float)terrain_offset_cm * 0.01 + ); +} +#endif // HAL_LOGGING_ENABLED + +#endif // AP_RANGEFINDER_ENABLED + +bool AP_SurfaceDistance::data_stale(void) +{ + WITH_SEMAPHORE(sem); + return (AP_HAL::millis() - last_healthy_ms) > RANGEFINDER_TIMEOUT_MS; +} + +bool AP_SurfaceDistance::enabled_and_healthy(void) const +{ + return enabled && alt_healthy; +} diff --git a/libraries/AP_SurfaceDistance/AP_SurfaceDistance.h b/libraries/AP_SurfaceDistance/AP_SurfaceDistance.h new file mode 100644 index 00000000000000..1b331a30810c10 --- /dev/null +++ b/libraries/AP_SurfaceDistance/AP_SurfaceDistance.h @@ -0,0 +1,51 @@ +#pragma once + +#include +#include +#include +#include + +class AP_SurfaceDistance { +public: + AP_SurfaceDistance(Rotation rot, const AP_InertialNav& inav, uint8_t i) : + instance(i), + inertial_nav(inav), + rotation(rot) + {}; + + void update(); + + // check if the last healthy range finder reading is too old to be considered valid + bool data_stale(void); + + // helper to check that rangefinder was last reported as enabled and healthy + bool enabled_and_healthy(void) const; + + // get inertially interpolated rangefinder height + bool get_rangefinder_height_interpolated_cm(int32_t& ret) const; + + bool enabled; // not to be confused with rangefinder enabled, this state is to be set by the vehicle. + bool alt_healthy; // true if we can trust the altitude from the rangefinder + int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder + float inertial_alt_cm; // inertial alt at time of last rangefinder sample + LowPassFilterFloat alt_cm_filt {0.5}; // altitude filter + int16_t alt_cm_glitch_protected; // last glitch protected altitude + int8_t glitch_count; // non-zero number indicates rangefinder is glitching + uint32_t glitch_cleared_ms; // system time glitch cleared + float terrain_offset_cm; // filtered terrain offset (e.g. terrain's height above EKF origin) + +private: +#if HAL_LOGGING_ENABLED + void Log_Write(void) const; +#endif + + // multi-thread access support + HAL_Semaphore sem; + + const uint8_t instance; + uint8_t status; + uint32_t last_healthy_ms; + + const AP_InertialNav& inertial_nav; + const Rotation rotation; +}; diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 604a21287f14db..69575aab7a8205 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -222,7 +222,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Param: TKOFF_IGAIN // @DisplayName: Controller integrator during takeoff - // @Description: This is the integrator gain on the control loop during takeoff. When set to 0 then TECS_INTEG_GAIN is used. Increase to increase the rate at which speed and height offsets are trimmed out. Typically values higher than TECS_INTEG_GAIN work best + // @Description: This is the integrator gain on the control loop during takeoff. Increase to increase the rate at which speed and height offsets are trimmed out. // @Range: 0.0 0.5 // @Increment: 0.02 // @User: Advanced @@ -328,7 +328,6 @@ void AP_TECS::update_50hz(void) _height_filter.dd_height = 0.0f; DT = 0.02f; // when first starting TECS, use most likely time constant _vdot_filter.reset(); - _takeoff_start_ms = 0; } _update_50hz_last_usec = now; @@ -415,7 +414,11 @@ void AP_TECS::_update_speed(float DT) if (aparm.stall_prevention) { // when stall prevention is active we raise the minimum // airspeed based on aerodynamic load factor - _TASmin *= _load_factor; + if (is_positive(aparm.airspeed_stall)) { + _TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*_load_factor); + } else { + _TASmin *= _load_factor; + } } if (_TASmax < _TASmin) { @@ -424,6 +427,9 @@ void AP_TECS::_update_speed(float DT) // Get measured airspeed or default to trim speed and constrain to range between min and max if // airspeed sensor data cannot be used + + // Equivalent airspeed + float _EAS; if (!use_airspeed || !_ahrs.airspeed_estimate(_EAS)) { // If no airspeed available use average of min and max _EAS = constrain_float(aparm.airspeed_cruise.get(), (float)aparm.airspeed_min.get(), (float)aparm.airspeed_max.get()); @@ -738,8 +744,8 @@ void AP_TECS::_update_throttle_with_airspeed(void) _throttle_dem = 0.0f; } 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. - const float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf)); + const float K_thr2STE = (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf); // This is the derivative of STEdot wrt throttle measured across the max allowed throttle range. + const float K_STE2Thr = 1 / (timeConstant() * K_thr2STE); // Calculate feed-forward throttle const float nomThr = aparm.throttle_cruise * 0.01f; @@ -749,7 +755,7 @@ void AP_TECS::_update_throttle_with_airspeed(void) // drag increase during turns. const 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); - const float ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf); + const float ff_throttle = nomThr + STEdot_dem / K_thr2STE; // Calculate PD + FF throttle float throttle_damp = _thrDamp; @@ -775,7 +781,6 @@ void AP_TECS::_update_throttle_with_airspeed(void) // 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 { _integTHR_state = constrain_float(_integTHR_state, integ_min, integ_max); } @@ -823,7 +828,12 @@ void AP_TECS::_update_throttle_with_airspeed(void) #endif } - // Constrain throttle demand and record clipping + constrain_throttle(); + +} + +// Constrain throttle demand and record clipping +void AP_TECS::constrain_throttle() { if (_throttle_dem > _THRmaxf) { _thr_clip_status = clipStatus::MAX; _throttle_dem = _THRmaxf; @@ -839,9 +849,7 @@ float AP_TECS::_get_i_gain(void) { float i_gain = _integGain; if (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) { - if (!is_zero(_integGain_takeoff)) { - i_gain = _integGain_takeoff; - } + i_gain = _integGain_takeoff; } else if (_flags.is_doing_auto_land) { if (!is_zero(_integGain_land)) { i_gain = _integGain_land; @@ -889,18 +897,6 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge, float pi _throttle_dem = nomThr; } - if (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF) { - const uint32_t now = AP_HAL::millis(); - if (_takeoff_start_ms == 0) { - _takeoff_start_ms = now; - } - const uint32_t dt = now - _takeoff_start_ms; - if (dt*0.001 < aparm.takeoff_throttle_max_t) { - _throttle_dem = _THRmaxf; - } - } else { - _takeoff_start_ms = 0; - } if (_flags.is_gliding) { _throttle_dem = 0.0f; return; @@ -914,6 +910,8 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge, float pi 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); _throttle_dem = _throttle_dem + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf); + + constrain_throttle(); } void AP_TECS::_detect_bad_descent(void) @@ -1084,17 +1082,17 @@ void AP_TECS::_update_pitch(void) // @Field: PEW: Potential energy weighting // @Field: KEW: Kinetic energy weighting // @Field: EBD: Energy balance demand - // @Field: EBE: Energy balance error + // @Field: EBE: Energy balance estimate // @Field: EBDD: Energy balance rate demand - // @Field: EBDE: Energy balance rate error + // @Field: EBDE: Energy balance rate estimate // @Field: EBDDT: Energy balance rate demand + Energy balance rate error*pitch_damping // @Field: Imin: Minimum integrator value // @Field: Imax: Maximum integrator value // @Field: I: Energy balance error integral // @Field: KI: Pitch demand kinetic energy integral - // @Field: pmin: Pitch min - // @Field: pmax: Pitch max - AP::logger().WriteStreaming("TEC2","TimeUS,PEW,KEW,EBD,EBE,EBDD,EBDE,EBDDT,Imin,Imax,I,KI,pmin,pmax", + // @Field: tmin: Throttle min + // @Field: tmax: Throttle max + AP::logger().WriteStreaming("TEC2","TimeUS,PEW,KEW,EBD,EBE,EBDD,EBDE,EBDDT,Imin,Imax,I,KI,tmin,tmax", "Qfffffffffffff", AP_HAL::micros64(), (double)SPE_weighting, @@ -1108,17 +1106,17 @@ void AP_TECS::_update_pitch(void) (double)integSEBdot_max, (double)_integSEBdot, (double)_integKE, - (double)_PITCHminf, - (double)_PITCHmaxf); + (double)_THRminf, + (double)_THRmaxf); } #endif } -void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) +void AP_TECS::_initialise_states(float hgt_afe) { + // Initialise states and variables if DT > 0.2 second or TECS is getting overriden or in climbout. _flags.reset = false; - // Initialise states and variables if DT > 0.2 second or in climbout if (_DT > 0.2f || _need_reset) { _SKE_weighting = 1.0f; _integTHR_state = 0.0f; @@ -1126,7 +1124,6 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _integKE = 0.0f; _last_throttle_dem = aparm.throttle_cruise * 0.01f; _last_pitch_dem = _ahrs.get_pitch(); - _hgt_afe = hgt_afe; _hgt_dem_in_prev = hgt_afe; _hgt_dem_lpf = hgt_afe; _hgt_dem_rate_ltd = hgt_afe; @@ -1136,7 +1133,6 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _DT = 0.02f; // when first starting TECS, use the most likely time constant _lag_comp_hgt_offset = 0.0f; _post_TO_hgt_offset = 0.0f; - _takeoff_start_ms = 0; _use_synthetic_airspeed_once = false; _flags.underspeed = false; @@ -1160,7 +1156,16 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _pitch_measured_lpf.reset(_ahrs.get_pitch()); } else if (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) { - _PITCHminf = 0.000174533f * ptchMinCO_cd; + + if (!_flag_throttle_forced) { + // Calculate the takeoff target height offset before _hgt_dem_in_raw gets reset below. + // Prevent the offset from becoming negative. + _post_TO_hgt_offset = MAX(MIN(_climb_rate_limit * _hgt_dem_tconst, _hgt_dem_in_raw - hgt_afe), 0); + } else { + // If throttle is externally forced, this mechanism of adding energy is unnecessary. + _post_TO_hgt_offset = 0; + } + _hgt_afe = hgt_afe; _hgt_dem_lpf = hgt_afe; _hgt_dem_rate_ltd = hgt_afe; @@ -1168,22 +1173,25 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _hgt_dem = hgt_afe; _hgt_dem_in_prev = hgt_afe; _hgt_dem_in_raw = hgt_afe; - _TAS_dem_adj = _TAS_dem; - _flags.reset = true; - _post_TO_hgt_offset = _climb_rate * _hgt_dem_tconst; _flags.underspeed = false; _flags.badDescent = false; - + _TAS_dem_adj = _TAS_dem; _max_climb_scaler = 1.0f; _max_sink_scaler = 1.0f; - _pitch_demand_lpf.reset(_ahrs.get_pitch()); _pitch_measured_lpf.reset(_ahrs.get_pitch()); + + + if (!_flag_have_reset_after_takeoff) { + _flags.reset = true; + _flag_have_reset_after_takeoff = true; + } } if (_flight_stage != AP_FixedWing::FlightStage::TAKEOFF && _flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) { // reset takeoff speed flag when not in takeoff _flags.reached_speed_takeoff = false; + _flag_have_reset_after_takeoff = false; } } @@ -1248,109 +1256,21 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, _hgt_dem_in = _hgt_dem_in_raw; } - if (aparm.takeoff_throttle_max != 0 && - (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING)) { - _THRmaxf = aparm.takeoff_throttle_max * 0.01f; - } else { - _THRmaxf = aparm.throttle_max * 0.01f; - } - _THRminf = aparm.throttle_min * 0.01f; - - // min of 1% throttle range to prevent a numerical error - _THRmaxf = MAX(_THRmaxf, _THRminf+0.01); - - // work out the maximum and minimum pitch - // if TECS_PITCH_{MAX,MIN} isn't set then use - // LIM_PITCH_{MAX,MIN}. Don't allow TECS_PITCH_{MAX,MIN} to be - // larger than LIM_PITCH_{MAX,MIN} - if (_pitch_max == 0) { - _PITCHmaxf = aparm.pitch_limit_max; - } else { - _PITCHmaxf = MIN(_pitch_max, aparm.pitch_limit_max); - } - - if (_pitch_min >= 0) { - _PITCHminf = aparm.pitch_limit_min; - } else { - _PITCHminf = MAX(_pitch_min, aparm.pitch_limit_min); - } - - // apply temporary pitch limit and clear - if (_pitch_max_limit < 90) { - _PITCHmaxf = constrain_float(_PITCHmaxf, -90, _pitch_max_limit); - _PITCHminf = constrain_float(_PITCHminf, -_pitch_max_limit, _PITCHmaxf); - _pitch_max_limit = 90; - } - - if (!_landing.is_on_approach()) { - // reset land pitch min when not landing - _land_pitch_min = _PITCHminf; - } - - // calculate the expected pitch angle from the demanded climb rate and airspeed fo ruse during approach and flare - if (_landing.is_flaring()) { - // smoothly move the min pitch to the required minimum at touchdown - float p; // 0 at start of flare, 1 at finish - if (!_flare_initialised) { - p = 0.0f; - } else if (_hgt_at_start_of_flare > _flare_holdoff_hgt) { - p = constrain_float((_hgt_at_start_of_flare - _hgt_afe) / _hgt_at_start_of_flare, 0.0f, 1.0f); - } else { - p = 1.0f; - } - const float pitch_limit_deg = (1.0f - p) * _pitch_min_at_flare_entry + p * 0.01f * _landing.get_pitch_cd(); - - // in flare use min pitch from LAND_PITCH_DEG - _PITCHminf = MAX(_PITCHminf, pitch_limit_deg); - - // and use max pitch from TECS_LAND_PMAX - if (_land_pitch_max != 0) { - // note that this allows a flare pitch outside the normal TECS auto limits - _PITCHmaxf = _land_pitch_max; - } - - // and allow zero throttle - _THRminf = 0; - } else if (_landing.is_on_approach()) { - _PITCHminf = MAX(_PITCHminf, aparm.pitch_limit_min); - _pitch_min_at_flare_entry = _PITCHminf; - _flare_initialised = false; - } else { - _flare_initialised = false; - } + // Update the throttle limits. + _update_throttle_limits(); - if (_landing.is_on_approach()) { - // don't allow the lower bound of pitch to decrease, nor allow - // it to increase rapidly. This prevents oscillation of pitch - // demand while in landing approach based on rapidly changing - // time to flare estimate - if (_land_pitch_min <= -90) { - _land_pitch_min = _PITCHminf; - } - const float flare_pitch_range = 20; - const float delta_per_loop = (flare_pitch_range/_landTimeConst) * _DT; - _PITCHminf = MIN(_PITCHminf, _land_pitch_min+delta_per_loop); - _land_pitch_min = MAX(_land_pitch_min, _PITCHminf); - _PITCHminf = MAX(_land_pitch_min, _PITCHminf); - } + _update_pitch_limits(ptchMinCO_cd); if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF || flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) { - if (!_flags.reached_speed_takeoff && _TAS_state >= _TAS_dem_adj) { + if (!_flags.reached_speed_takeoff && _TAS_state >= _TASmin && _TASmin > 0) { // we have reached our target speed in takeoff, allow for // normal throttle control _flags.reached_speed_takeoff = true; } } - // convert to radians - _PITCHmaxf = radians(_PITCHmaxf); - _PITCHminf = radians(_PITCHminf); - - // don't allow max pitch to go below min pitch - _PITCHmaxf = MAX(_PITCHmaxf, _PITCHminf); - // initialise selected states and variables if DT > 1 second or in climbout - _initialise_states(ptchMinCO_cd, hgt_afe); + _initialise_states(hgt_afe); // Calculate Specific Total Energy Rate Limits _update_STE_rate_lim(); @@ -1436,3 +1356,176 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, } #endif } + +// set minimum throttle override, [-1, -1] range +// it is applicable for one control cycle only +void AP_TECS::set_throttle_min(const float thr_min) { + // Don't change the limit if it is already covered. + if (thr_min > _THRminf_ext) { + _THRminf_ext = thr_min; + } +} + +// set minimum throttle override, [0, -1] range +// it is applicable for one control cycle only +void AP_TECS::set_throttle_max(const float thr_max) { + // Don't change the limit if it is already covered. + if (thr_max < _THRmaxf_ext) { + _THRmaxf_ext = thr_max; + } +} + +void AP_TECS::_update_throttle_limits() { + + // Configure max throttle; constrain to the external safety limits. + _THRmaxf = MIN(1.0f, _THRmaxf_ext); + // Configure min throttle; constrain to the external safety limits. + _THRminf = MAX(-1.0f, _THRminf_ext); + + // Allow a minimum of 1% throttle range, primarily to prevent TECS numerical errors. + const float thr_eps = 0.01; + if (fabsf(_THRminf-_THRmaxf) < thr_eps) { + _flag_throttle_forced = true; + if (_THRmaxf < 1) { + _THRmaxf = MAX(_THRmaxf, _THRminf + 0.01f); + } else { + _THRminf = MIN(_THRminf, _THRmaxf - 0.01f); + } + } else { + _flag_throttle_forced = false; + } + + // Reset the external throttle limits. + // Caller will have to reset them in the next iteration. + _THRminf_ext = -1.0f; + _THRmaxf_ext = 1.0f; +} + +void AP_TECS::set_pitch_min(const float pitch_min) { + // Don't change the limit if it is already covered. + if (pitch_min > _PITCHminf_ext) { + _PITCHminf_ext = pitch_min; + } +} + +void AP_TECS::set_pitch_max(const float pitch_max) { + // Don't change the limit if it is already covered. + if (pitch_max < _PITCHmaxf_ext) { + _PITCHmaxf_ext = pitch_max; + } +} + +void AP_TECS::_update_pitch_limits(const int32_t ptchMinCO_cd) { + // If TECS_PITCH_{MAX,MIN} isn't set then use LIM_PITCH_{MAX,MIN}. + // Don't allow TECS_PITCH_{MAX,MIN} to be larger than LIM_PITCH_{MAX,MIN}. + if (_pitch_max == 0) { + _PITCHmaxf = aparm.pitch_limit_max; + } else { + _PITCHmaxf = _pitch_max; + } + + if (_pitch_min == 0) { + _PITCHminf = aparm.pitch_limit_min; + } else { + _PITCHminf = _pitch_min; + } + + if (!_landing.is_on_approach()) { + // reset land pitch min when not landing + _land_pitch_min = _PITCHminf; + } + + // calculate the expected pitch angle from the demanded climb rate and airspeed for use during approach and flare + if (_landing.is_flaring()) { + // smoothly move the min pitch to the required minimum at touchdown + float p; // 0 at start of flare, 1 at finish + if (!_flare_initialised) { + p = 0.0f; + } else if (_hgt_at_start_of_flare > _flare_holdoff_hgt) { + p = constrain_float((_hgt_at_start_of_flare - _hgt_afe) / _hgt_at_start_of_flare, 0.0f, 1.0f); + } else { + p = 1.0f; + } + const float pitch_limit_deg = (1.0f - p) * _pitch_min_at_flare_entry + p * 0.01f * _landing.get_pitch_cd(); + + // in flare use min pitch from LAND_PITCH_DEG + _PITCHminf = MAX(_PITCHminf, pitch_limit_deg); + + // and use max pitch from TECS_LAND_PMAX + if (_land_pitch_max != 0) { + // note that this allows a flare pitch outside the normal TECS auto limits + _PITCHmaxf = _land_pitch_max; + } + } else if (_landing.is_on_approach()) { + _PITCHminf = MAX(_PITCHminf, aparm.pitch_limit_min); + _pitch_min_at_flare_entry = _PITCHminf; + _flare_initialised = false; + } else { + _flare_initialised = false; + } + + if (_landing.is_on_approach()) { + // don't allow the lower bound of pitch to decrease, nor allow + // it to increase rapidly. This prevents oscillation of pitch + // demand while in landing approach based on rapidly changing + // time to flare estimate + if (_land_pitch_min <= -90) { + _land_pitch_min = _PITCHminf; + } + const float flare_pitch_range = 20; + const float delta_per_loop = (flare_pitch_range/_landTimeConst) * _DT; + _PITCHminf = MIN(_PITCHminf, _land_pitch_min+delta_per_loop); + _land_pitch_min = MAX(_land_pitch_min, _PITCHminf); + _PITCHminf = MAX(_land_pitch_min, _PITCHminf); + } + + // Apply TAKEOFF minimum pitch + if (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF + || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) + { + _PITCHminf = CentiDegreesToRadians(ptchMinCO_cd); + } + + // Apply external limits. + _PITCHmaxf = MIN(_PITCHmaxf, _PITCHmaxf_ext); + _PITCHminf = MAX(_PITCHminf, _PITCHminf_ext); + + // Reset the external pitch limits. + _PITCHminf_ext = -90.0f; + _PITCHmaxf_ext = 90.0f; + + // convert to radians + _PITCHmaxf = radians(_PITCHmaxf); + _PITCHminf = radians(_PITCHminf); + + // don't allow max pitch to go below min pitch + _PITCHmaxf = MAX(_PITCHmaxf, _PITCHminf); +} + +void AP_TECS::offset_altitude(const float alt_offset) +{ + // Convention: When alt_offset is positive it means that the altitude of + // home has increased. Thus, the relative altitude of the vehicle has + // decreased. + // + // Assumption: This method is called more often and before + // `update_pitch_throttle()`. This is necessary to ensure that new height + // demands which incorporate the home change are compatible with the + // (now updated) internal height state. + + _flare_hgt_dem_ideal -= alt_offset; + _flare_hgt_dem_adj -= alt_offset; + _hgt_at_start_of_flare -= alt_offset; + _hgt_dem_in_prev -= alt_offset; + _hgt_dem_lpf -= alt_offset; + _hgt_dem_rate_ltd -= alt_offset; + _hgt_dem_prev -= alt_offset; + _height_filter.height -= alt_offset; + + // The following variables are updated anew in every call of + // `update_pitch_throttle()`. There's no need to update those. + // _hgt_dem + // _hgt_dem_in_raw + // _hgt_dem_in + // Energies +} \ No newline at end of file diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index fcd3fe97f9bfe7..4c4343b5ee950c 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -128,11 +128,21 @@ class AP_TECS { _flags.propulsion_failed = propulsion_failed; } + // set minimum throttle override, [-1, -1] range + // it is applicable for one control cycle only + void set_throttle_min(const float thr_min); - // set pitch max limit in degrees - void set_pitch_max_limit(int8_t pitch_limit) { - _pitch_max_limit = pitch_limit; - } + // set maximum throttle override, [0, -1] range + // it is applicable for one control cycle only + void set_throttle_max(const float thr_max); + + // set minimum pitch override, in degrees. + // it is applicable for one control cycle only + void set_pitch_min(const float pitch_min); + + // set maximum pitch override, in degrees. + // it is applicable for one control cycle only + void set_pitch_max(const float pitch_max); // force use of synthetic airspeed for one loop void use_synthetic_airspeed(void) { @@ -144,6 +154,9 @@ class AP_TECS { _need_reset = true; } + // Apply an altitude offset, to compensate for changes in home alt. + void offset_altitude(const float alt_offset); + // this supports the TECS_* user settable parameters static const struct AP_Param::GroupInfo var_info[]; @@ -261,9 +274,6 @@ class AP_TECS { float _vel_dot; float _vel_dot_lpf; - // Equivalent airspeed - float _EAS; - // True airspeed limits float _TASmax; float _TASmin; @@ -306,9 +316,6 @@ class AP_TECS { // Total energy rate filter state float _STEdotErrLast; - // time we started a takeoff - uint32_t _takeoff_start_ms; - struct flags { // Underspeed condition bool underspeed:1; @@ -360,6 +367,12 @@ class AP_TECS { // Maximum and minimum floating point throttle limits float _THRmaxf; float _THRminf; + // Maximum and minimum throttle safety limits, set externally, typically by servos.cpp:apply_throttle_limits() + float _THRmaxf_ext = 1.0f; + float _THRminf_ext = -1.0f; + // Maximum and minimum pitch limits, set externally, typically by the takeoff logic. + float _PITCHmaxf_ext = 90.0f; + float _PITCHminf_ext = -90.0f; // Maximum and minimum floating point pitch limits float _PITCHmaxf; @@ -418,6 +431,11 @@ class AP_TECS { // need to reset on next loop bool _need_reset; + // Flag if someone else drives throttle externally. + bool _flag_throttle_forced; + + // Checks if we reset at the beginning of takeoff. + bool _flag_have_reset_after_takeoff; float _SKE_weighting; @@ -458,6 +476,9 @@ class AP_TECS { // Update Demanded Throttle Non-Airspeed void _update_throttle_without_airspeed(int16_t throttle_nudge, float pitch_trim_deg); + // Constrain throttle demand and record clipping + void constrain_throttle(); + // get integral gain which is flight_stage dependent float _get_i_gain(void); @@ -468,7 +489,7 @@ class AP_TECS { void _update_pitch(void); // Initialise states and variables - void _initialise_states(int32_t ptchMinCO_cd, float hgt_afe); + void _initialise_states(float hgt_afe); // Calculate specific total energy rate limits void _update_STE_rate_lim(void); @@ -478,4 +499,10 @@ class AP_TECS { // current time constant float timeConstant(void) const; + + // Update the allowable throttle range. + void _update_throttle_limits(); + + // Update the allowable pitch range. + void _update_pitch_limits(const int32_t ptchMinCO_cd); }; diff --git a/libraries/AP_TempCalibration/AP_TempCalibration.cpp b/libraries/AP_TempCalibration/AP_TempCalibration.cpp index 574dc9258d0846..f9b6c07a5b0330 100644 --- a/libraries/AP_TempCalibration/AP_TempCalibration.cpp +++ b/libraries/AP_TempCalibration/AP_TempCalibration.cpp @@ -98,7 +98,7 @@ void AP_TempCalibration::setup_learning(void) learn_count = 200; learn_i = 0; delete [] learn_values; - learn_values = new float[learn_count]; + learn_values = NEW_NOTHROW float[learn_count]; if (learn_values == nullptr) { return; } diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp index 69ef84e41a6aca..8b0f75b6782eb0 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp @@ -19,7 +19,9 @@ #include +#ifndef AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED #define AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_ArduSub) || (AP_TEMPERATURE_SENSOR_ENABLED == 1))) +#endif #if !AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED @@ -30,6 +32,7 @@ #include "AP_TemperatureSensor_MAX31865.h" #include "AP_TemperatureSensor_Analog.h" #include "AP_TemperatureSensor_DroneCAN.h" +#include "AP_TemperatureSensor_MLX90614.h" #include #include @@ -40,12 +43,14 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = { // SKIP INDEX 0 +#if HAL_LOGGING_ENABLED // @Param: _LOG // @DisplayName: Logging // @Description: Enables temperature sensor logging - // @Values: 0:Disabled, 1:Enabled + // @Values: 0:Disabled, 1:Log all instances, 2: Log only instances with sensor source set to None // @User: Standard - AP_GROUPINFO("_LOG", 1, AP_TemperatureSensor, _log_flag, 0), + AP_GROUPINFO("_LOG", 1, AP_TemperatureSensor, _logging_type, 0), +#endif // SKIP Index 2-9 to be for parameters that apply to every sensor @@ -134,7 +139,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = { // @Group: 9_ // @Path: AP_TemperatureSensor_Analog.cpp - AP_SUBGROUPVARPTR(drivers[8], "9_", 26, AP_TemperatureSensor, backend_var_info[8]), + AP_SUBGROUPVARPTR(drivers[8], "9_", 27, AP_TemperatureSensor, backend_var_info[8]), #endif AP_GROUPEND @@ -174,32 +179,37 @@ void AP_TemperatureSensor::init() switch (get_type(instance)) { #if AP_TEMPERATURE_SENSOR_TSYS01_ENABLED case AP_TemperatureSensor_Params::Type::TSYS01: - drivers[instance] = new AP_TemperatureSensor_TSYS01(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_TSYS01(*this, _state[instance], _params[instance]); break; #endif #if AP_TEMPERATURE_SENSOR_MCP9600_ENABLED case AP_TemperatureSensor_Params::Type::MCP9600: - drivers[instance] = new AP_TemperatureSensor_MCP9600(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_MCP9600(*this, _state[instance], _params[instance]); break; #endif #if AP_TEMPERATURE_SENSOR_MAX31865_ENABLED case AP_TemperatureSensor_Params::Type::MAX31865: - drivers[instance] = new AP_TemperatureSensor_MAX31865(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_MAX31865(*this, _state[instance], _params[instance]); break; #endif #if AP_TEMPERATURE_SENSOR_TSYS03_ENABLED case AP_TemperatureSensor_Params::Type::TSYS03: - drivers[instance] = new AP_TemperatureSensor_TSYS03(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_TSYS03(*this, _state[instance], _params[instance]); break; #endif #if AP_TEMPERATURE_SENSOR_ANALOG_ENABLED case AP_TemperatureSensor_Params::Type::ANALOG: - drivers[instance] = new AP_TemperatureSensor_Analog(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_Analog(*this, _state[instance], _params[instance]); break; #endif #if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED case AP_TemperatureSensor_Params::Type::DRONECAN: - drivers[instance] = new AP_TemperatureSensor_DroneCAN(*this, _state[instance], _params[instance]); + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_DroneCAN(*this, _state[instance], _params[instance]); + break; +#endif +#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED + case AP_TemperatureSensor_Params::Type::MLX90614: + drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_MLX90614(*this, _state[instance], _params[instance]); break; #endif case AP_TemperatureSensor_Params::Type::NONE: @@ -239,7 +249,9 @@ void AP_TemperatureSensor::update() #if HAL_LOGGING_ENABLED const AP_Logger *logger = AP_Logger::get_singleton(); - if (logger != nullptr && _log_flag) { + const bool should_log = (_logging_type == LoggingType::All) || + ((_logging_type == LoggingType::SourceNone) && (_params[i].source == AP_TemperatureSensor_Params::Source::None)); + if (logger != nullptr && should_log) { drivers[i]->Log_Write_TEMP(); } #endif diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h index 1a9538d775b5ae..6ba94771afd636 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h @@ -27,6 +27,7 @@ class AP_TemperatureSensor_MCP9600; class AP_TemperatureSensor_MAX31865; class AP_TemperatureSensor_TSYS03; class AP_TemperatureSensor_Analog; +class AP_TemperatureSensor_MLX90614; class AP_TemperatureSensor { @@ -37,6 +38,7 @@ class AP_TemperatureSensor friend class AP_TemperatureSensor_TSYS03; friend class AP_TemperatureSensor_Analog; friend class AP_TemperatureSensor_DroneCAN; + friend class AP_TemperatureSensor_MLX90614; public: @@ -56,6 +58,7 @@ class AP_TemperatureSensor // Update the temperature for all temperature sensors void update(); + // return temperature from sensor - in degrees Celsius bool get_temperature(float &temp, const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const; bool healthy(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const; @@ -88,8 +91,14 @@ class AP_TemperatureSensor uint8_t _num_instances; // number of temperature sensors - // Parameters - AP_Int8 _log_flag; // log_flag: true if we should log all sensors data +#if HAL_LOGGING_ENABLED + enum class LoggingType : uint8_t { + All = 1, + SourceNone = 2, + }; + AP_Enum _logging_type; +#endif + }; namespace AP { diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp index e2871ca14615ee..91a7686f1d9582 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp @@ -26,36 +26,41 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Analog::var_info[] = { // @Param: PIN // @DisplayName: Temperature sensor analog voltage sensing pin - // @Description: Sets the analog input pin that should be used for temprature monitoring. + // @Description: Sets the analog input pin that should be used for temprature monitoring. Values for some autopilots are given as examples. Search wiki for "Analog pins". // @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1 // @User: Standard AP_GROUPINFO("PIN", 1, AP_TemperatureSensor_Analog, _pin, -1), // @Param: A0 // @DisplayName: Temperature sensor analog 0th polynomial coefficient - // @Description: a0 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // @Description: a0 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 AP_GROUPINFO("A0", 2, AP_TemperatureSensor_Analog, _a[0], 0), // @Param: A1 // @DisplayName: Temperature sensor analog 1st polynomial coefficient - // @Description: a1 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // @Description: a1 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 AP_GROUPINFO("A1", 3, AP_TemperatureSensor_Analog, _a[1], 0), // @Param: A2 // @DisplayName: Temperature sensor analog 2nd polynomial coefficient - // @Description: a2 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // @Description: a2 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 AP_GROUPINFO("A2", 4, AP_TemperatureSensor_Analog, _a[2], 0), // @Param: A3 // @DisplayName: Temperature sensor analog 3rd polynomial coefficient - // @Description: a3 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // @Description: a3 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 AP_GROUPINFO("A3", 5, AP_TemperatureSensor_Analog, _a[3], 0), // @Param: A4 // @DisplayName: Temperature sensor analog 4th polynomial coefficient - // @Description: a4 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // @Description: a4 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 AP_GROUPINFO("A4", 6, AP_TemperatureSensor_Analog, _a[4], 0), + // @Param: A5 + // @DisplayName: Temperature sensor analog 5th polynomial coefficient + // @Description: a5 in polynomial of form temperature in deg = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 + AP_GROUPINFO("A5", 7, AP_TemperatureSensor_Analog, _a[5], 0), + AP_GROUPEND }; @@ -81,7 +86,7 @@ void AP_TemperatureSensor_Analog::update() const float voltage = _analog_source->voltage_average_ratiometric(); // Evaluate polynomial - // temperature (deg) = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + // temperature (deg) = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + a5*voltage^5 float temp = 0.0; float poly = 1.0; for (uint8_t i = 0; i < ARRAY_SIZE(_a); i++) { diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h index a342c165332e9b..99c3ba4ed12002 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h @@ -35,10 +35,10 @@ class AP_TemperatureSensor_Analog : public AP_TemperatureSensor_Backend { AP_HAL::AnalogSource *_analog_source; // Pin used to measure voltage - AP_Int8 _pin; + AP_Int8 _pin; // Polynomial coefficients to calculate temperature from voltage - AP_Float _a[5]; + AP_Float _a[6]; }; diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.cpp index 0092939a06566b..172d10700e9fab 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.cpp @@ -53,15 +53,11 @@ AP_TemperatureSensor_DroneCAN::AP_TemperatureSensor_DroneCAN(AP_TemperatureSenso } // Subscript to incoming temperature messages -void AP_TemperatureSensor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +bool AP_TemperatureSensor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_dronecan == nullptr) { - return; - } + const auto driver_index = ap_dronecan->get_driver_index(); - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("temp_sub"); - } + return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, driver_index) != nullptr); } void AP_TemperatureSensor_DroneCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_device_Temperature &msg) diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h index fa2a3f086f0098..92b6d8ec310089 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h @@ -28,7 +28,7 @@ class AP_TemperatureSensor_DroneCAN : public AP_TemperatureSensor_Backend { public: AP_TemperatureSensor_DroneCAN(AP_TemperatureSensor &front, AP_TemperatureSensor::TemperatureSensor_State &state, AP_TemperatureSensor_Params ¶ms); - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static bool subscribe_msgs(AP_DroneCAN* ap_dronecan); // Don't do anything in update, but still need to override the pure virtual method. void update(void) override {}; diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp index c0c91382cee13d..d8be71f92ef775 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp @@ -47,7 +47,7 @@ static const uint8_t MCP9601_WHOAMI = 0x41; #define MCP9600_ADDR_LOW 0x60 // ADDR pin pulled low -#define MCP9600_ADDR_HIGH 0x66 // ADDR pin pulled high +#define MCP9600_ADDR_HIGH 0x67 // ADDR pin pulled high #define AP_TemperatureSensor_MCP9600_UPDATE_INTERVAL_MS 500 #define AP_TemperatureSensor_MCP9600_SCALE_FACTOR (0.0625f) @@ -56,10 +56,6 @@ static const uint8_t MCP9601_WHOAMI = 0x41; #define AP_TemperatureSensor_MCP9600_ADDR_DEFAULT MCP9600_ADDR_LOW #endif -#ifndef AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS -#define AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS 1 -#endif - #ifndef AP_TemperatureSensor_MCP9600_Filter #define AP_TemperatureSensor_MCP9600_Filter 2 // can be values 0 through 7 where 0 is no filtering (fast) and 7 is lots of smoothing (very very slow) #endif @@ -68,13 +64,6 @@ void AP_TemperatureSensor_MCP9600::init() { constexpr char name[] = "MCP9600"; -#if AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS - // I2C Address: Default to using MCP9600_ADDR_LOW if it's out of range - if ((_params.bus_address < MCP9600_ADDR_LOW) || ( _params.bus_address > MCP9600_ADDR_HIGH)) { - _params.bus_address.set(MCP9600_ADDR_LOW); - } -#endif - _dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address)); if (!_dev) { // device not found @@ -137,14 +126,14 @@ bool AP_TemperatureSensor_MCP9600::read_temperature(float &temperature) if ((data[0] & MCP9600_CMD_STATUS_UPDATE_READY) == 0) { return false; } - // clear update bit: - if (!_dev->write_register(0x04, data[0] & ~MCP9600_CMD_STATUS_UPDATE_READY)) { - return false; - } // read temperature: if (!_dev->read_registers(MCP9600_CMD_HOT_JUNCT_TEMP, data, 2)) { return false; } + // clear update bit: + if (!_dev->write_register(0x04, data[0] & ~MCP9600_CMD_STATUS_UPDATE_READY)) { + return false; + } // scale temperature: temperature = int16_t(UINT16_VALUE(data[0], data[1])) * AP_TemperatureSensor_MCP9600_SCALE_FACTOR; diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.cpp new file mode 100644 index 00000000000000..c718bc9d837efc --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.cpp @@ -0,0 +1,66 @@ +#include "AP_TemperatureSensor_config.h" + +#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED + +#include "AP_TemperatureSensor_MLX90614.h" + +#include +#include +#include + + +extern const AP_HAL::HAL &hal; + +#define MLX90614_I2CDEFAULTADDR 0x5A // Device default slave address +#define MLX90614_BROADCASTADDR 0 // Device broadcast slave address + +// RAM addresses +#define MLX90614_RAWIR1 0x04 // RAM reg - Raw temperature, source #1 +#define MLX90614_RAWIR2 0x05 // RAM reg - Raw temperature, source #2 +#define MLX90614_TA 0x06 // RAM reg - Linearized temperature, ambient +#define MLX90614_TOBJ1 0x07 // RAM reg - Linearized temperature, source #1 +#define MLX90614_TOBJ2 0x08 // RAM reg - Linearized temperature, source #2 + +void AP_TemperatureSensor_MLX90614::init() +{ + _params.bus_address.set_default(MLX90614_I2CDEFAULTADDR); + + _dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address)); + if (!_dev) { + return; + } + + WITH_SEMAPHORE(_dev->get_semaphore()); + + _dev->register_periodic_callback(50 * AP_USEC_PER_MSEC, + FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_MLX90614::_timer, void)); +} + + +void AP_TemperatureSensor_MLX90614::_timer() +{ + const uint16_t _crude_value = read_data(MLX90614_TA); + + if (_crude_value == 0) { + return; + } + + WITH_SEMAPHORE(_dev->get_semaphore()); + + // temp * 0.02 - 273.15 = degrees, temp * 0.02 is temperature in kelvin + const float tmp = KELVIN_TO_C(_crude_value * 0.02); + set_temperature(tmp); +} + + + +uint16_t AP_TemperatureSensor_MLX90614::read_data(uint8_t cmd) +{ + uint8_t val[3]; + + if (!_dev->transfer(&cmd, 1, val, 3)) { + return 0; + } + return UINT16_VALUE(val[1],val[0]); +} +#endif // AP_TEMPERATURE_SENSOR_MLX90614_ENABLED \ No newline at end of file diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.h new file mode 100644 index 00000000000000..f7c1d315a881af --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.h @@ -0,0 +1,24 @@ +#pragma once + +#include "AP_TemperatureSensor_Backend.h" + +#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED + + +class AP_TemperatureSensor_MLX90614 : public AP_TemperatureSensor_Backend { + using AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend; +public: + + void init(void) override; + + void update() override {}; + +private: + + // update the temperature, called at 20Hz + void _timer(void); + + uint16_t read_data(uint8_t cmd); + uint16_t read_eeprom(uint8_t address) {return read_data(address | 0x20);}; +}; +#endif // AP_TEMPERATURE_SENSOR_MLX90614_ENABLED \ No newline at end of file diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp index b1e15333d40f44..e5a73bcb0142ba 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp @@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = { // @Param: TYPE // @DisplayName: Temperature Sensor Type // @Description: Enables temperature sensors - // @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN + // @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN, 7:MLX90614 // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, (float)Type::NONE, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h index f8c551ee5f6dc3..ff3c00c8781757 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h @@ -34,6 +34,7 @@ class AP_TemperatureSensor_Params { TSYS03 = 4, ANALOG = 5, DRONECAN = 6, + MLX90614 = 7, }; // option to map to another system component diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h index 8b7cbf59e47677..7463d706c1f135 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h @@ -9,28 +9,36 @@ #ifndef AP_TEMPERATURE_SENSOR_ENABLED #if BOARD_FLASH_SIZE <= 1024 #define AP_TEMPERATURE_SENSOR_ENABLED 0 -#elif (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#elif BOARD_FLASH_SIZE > 2048 #define AP_TEMPERATURE_SENSOR_ENABLED 1 #else #define AP_TEMPERATURE_SENSOR_ENABLED 2 #endif #endif +#ifndef AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED +#define AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED AP_TEMPERATURE_SENSOR_ENABLED +#endif + #ifndef AP_TEMPERATURE_SENSOR_MAX31865_ENABLED - #define AP_TEMPERATURE_SENSOR_MAX31865_ENABLED AP_TEMPERATURE_SENSOR_ENABLED + #define AP_TEMPERATURE_SENSOR_MAX31865_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_TEMPERATURE_SENSOR_ANALOG_ENABLED - #define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED AP_TEMPERATURE_SENSOR_ENABLED + #define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED - #define AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED AP_TEMPERATURE_SENSOR_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS + #define AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS #endif #if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS #error AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS #endif +#ifndef AP_TEMPERATURE_SENSOR_MLX90614_ENABLED + #define AP_TEMPERATURE_SENSOR_MLX90614_ENABLED AP_TEMPERATURE_SENSOR_ENABLED +#endif + // maximum number of Temperature Sensors #ifndef AP_TEMPERATURE_SENSOR_MAX_INSTANCES #define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 3 diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index d2aab8bf1d8aba..79fc81a41f9a6f 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -77,7 +77,14 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Range: 0 50 // @User: Advanced AP_GROUPINFO("OFS_MAX", 4, AP_Terrain, offset_max, 30), - + + // @Param: CACHE_SZ + // @DisplayName: Terrain cache size + // @Description: The number of 32x28 cache blocks to keep in memory. Each block uses about 1800 bytes of memory + // @Range: 0 128 + // @User: Advanced + AP_GROUPINFO("CACHE_SZ", 5, AP_Terrain, config_cache_size, TERRAIN_GRID_BLOCK_CACHE_SIZE), + AP_GROUPEND }; @@ -147,19 +154,17 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected) } // hXY are the heights of the 4 surrounding grid points - int16_t h00, h01, h10, h11; - - h00 = grid.height[info.idx_x+0][info.idx_y+0]; - h01 = grid.height[info.idx_x+0][info.idx_y+1]; - h10 = grid.height[info.idx_x+1][info.idx_y+0]; - h11 = grid.height[info.idx_x+1][info.idx_y+1]; + const auto h00 = grid.height[info.idx_x+0][info.idx_y+0]; + const auto h01 = grid.height[info.idx_x+0][info.idx_y+1]; + const auto h10 = grid.height[info.idx_x+1][info.idx_y+0]; + const auto h11 = grid.height[info.idx_x+1][info.idx_y+1]; // do a simple dual linear interpolation. We could do something // fancier, but it probably isn't worth it as long as the // grid_spacing is kept small enough - float avg1 = (1.0f-info.frac_x) * h00 + info.frac_x * h10; - float avg2 = (1.0f-info.frac_x) * h01 + info.frac_x * h11; - float avg = (1.0f-info.frac_y) * avg1 + info.frac_y * avg2; + const float avg1 = (1.0f-info.frac_x) * h00 + info.frac_x * h10; + const float avg2 = (1.0f-info.frac_x) * h01 + info.frac_x * h11; + const float avg = (1.0f-info.frac_y) * avg1 + info.frac_y * avg2; height = avg; @@ -488,13 +493,13 @@ bool AP_Terrain::allocate(void) if (cache != nullptr) { return true; } - cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0])); + cache = (struct grid_cache *)calloc(config_cache_size, sizeof(cache[0])); if (cache == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); memory_alloc_failed = true; return false; } - cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE; + cache_size = config_cache_size; return true; } @@ -560,7 +565,7 @@ void AP_Terrain::update_reference_offset(void) if (!reference_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) { return; } - float adjustment = alt_cm*0.01 - height; + const 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", diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 8a6be4579db06c..b0cbe826ab761f 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -14,12 +14,7 @@ */ #pragma once -#include -#include - -#ifndef AP_TERRAIN_AVAILABLE -#define AP_TERRAIN_AVAILABLE AP_FILESYSTEM_FILE_READING_ENABLED -#endif +#include "AP_Terrain_config.h" #if AP_TERRAIN_AVAILABLE @@ -51,7 +46,9 @@ #define TERRAIN_GRID_BLOCK_SIZE_Y (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y) // number of grid_blocks in the LRU memory cache +#ifndef TERRAIN_GRID_BLOCK_CACHE_SIZE #define TERRAIN_GRID_BLOCK_CACHE_SIZE 12 +#endif // format of grid on disk #define TERRAIN_GRID_FORMAT_VERSION 1 @@ -106,15 +103,20 @@ class AP_Terrain { bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) const; +#if HAL_GCS_ENABLED // send any pending terrain request message bool send_cache_request(mavlink_channel_t chan); void send_request(mavlink_channel_t chan); // handle terrain data and reports from GCS + // send a terrain report for the current location, extrapolating height as we do for navigation: + void send_report(mavlink_channel_t chan); + // send a terrain report or Location loc void send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate); void handle_data(mavlink_channel_t chan, const mavlink_message_t &msg); void handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg); void handle_terrain_data(const mavlink_message_t &msg); +#endif /* find the terrain height in meters above sea level for a location @@ -316,11 +318,13 @@ class AP_Terrain { */ bool check_bitmap(const struct grid_block &grid, uint8_t idx_x, uint8_t idx_y); +#if HAL_GCS_ENABLED /* request any missing 4x4 grids from a block */ bool request_missing(mavlink_channel_t chan, struct grid_cache &gcache); bool request_missing(mavlink_channel_t chan, const struct grid_info &info); +#endif /* look for blocks that need to be read/written to disk @@ -371,6 +375,7 @@ class AP_Terrain { AP_Int16 grid_spacing; // meters between grid points AP_Int16 options; // option bits AP_Float offset_max; + AP_Int16 config_cache_size; enum class Options { DisableDownload = (1U<<0), @@ -391,8 +396,10 @@ class AP_Terrain { volatile enum DiskIoState disk_io_state; union grid_io_block disk_block; +#if HAL_GCS_ENABLED // last time we asked for more grids uint32_t last_request_time_ms[MAVLINK_COMM_NUM_BUFFERS]; +#endif static const uint64_t bitmap_mask = (((uint64_t)1U)<<(TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y)) - 1; diff --git a/libraries/AP_Terrain/AP_Terrain_config.h b/libraries/AP_Terrain/AP_Terrain_config.h new file mode 100644 index 00000000000000..30bc8b0b1fbb52 --- /dev/null +++ b/libraries/AP_Terrain/AP_Terrain_config.h @@ -0,0 +1,8 @@ +#pragma once + +#include +#include + +#ifndef AP_TERRAIN_AVAILABLE +#define AP_TERRAIN_AVAILABLE AP_FILESYSTEM_FILE_READING_ENABLED +#endif diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 30a2067c29b5db..e5e9f2ec25a1e1 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -32,14 +32,12 @@ extern const AP_HAL::HAL& hal; +#if HAL_GCS_ENABLED /* request any missing 4x4 grids from a block, given a grid_cache */ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcache) { -#if !HAL_GCS_ENABLED - return false; -#else struct grid_block &grid = gcache.grid; if (options.get() & uint16_t(Options::DisableDownload)) { @@ -75,7 +73,6 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac last_request_time_ms[chan] = AP_HAL::millis(); return true; -#endif } /* @@ -118,17 +115,12 @@ void AP_Terrain::send_request(mavlink_channel_t chan) Location loc; if (!AP::ahrs().get_location(loc)) { - // we don't know where we are. Send a report and request any cached blocks. + // we don't know where we are. Request any cached blocks. // this allows for download of mission items when we have no GPS lock - loc = {}; - send_terrain_report(chan, loc, true); send_cache_request(chan); return; } - // always send a terrain report - send_terrain_report(chan, loc, true); - // did we request recently? if (AP_HAL::millis() - last_request_time_ms[chan] < 2000) { // too soon to request again @@ -157,6 +149,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan) return; } } +#endif // HAL_GCS_ENABLED /* count bits in a uint64_t @@ -196,7 +189,8 @@ void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded) const } } -/* +#if HAL_GCS_ENABLED +/* handle terrain messages from GCS */ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &msg) @@ -208,6 +202,18 @@ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &ms } } +/* + send a TERRAIN_REPORT for the current location + */ +void AP_Terrain::send_report(mavlink_channel_t chan) +{ + Location loc; + if (!AP::ahrs().get_location(loc)) { + loc = {}; + } + + send_terrain_report(chan, loc, true); +} /* send a TERRAIN_REPORT for a location @@ -312,6 +318,7 @@ void AP_Terrain::handle_terrain_data(const mavlink_message_t &msg) // see if we need to schedule some disk IO update(); } +#endif // HAL_GCS_ENABLED #endif // AP_TERRAIN_AVAILABLE diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index af64699bc334f7..344e9e3d31068e 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -19,103 +19,25 @@ #include #include -#include -#include #include -#include - -#define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200 -#define TORQEEDO_PACKET_HEADER 0xAC // communication packet header -#define TORQEEDO_PACKET_FOOTER 0xAD // communication packet footer -#define TORQEEDO_PACKET_ESCAPE 0xAE // escape character for handling occurrences of header, footer and this escape bytes in original message -#define TORQEEDO_PACKET_ESCAPE_MASK 0x80 // byte after ESCAPE character should be XOR'd with this value -#define TORQEEDO_LOG_TRQD_INTERVAL_MS 5000// log TRQD message at this interval in milliseconds -#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS 100 // motor speed sent at 10hz if connected to motor -#define TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS 400 // motor status requested every 0.4sec if connected to motor -#define TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS 400 // motor param requested every 0.4sec if connected to motor -#define TORQEEDO_SEND_BATTERY_STATUS_REQUEST_INTERVAL_MS 400 // battery status requested every 0.4sec -#define TORQEEDO_BATT_TIMEOUT_MS 5000 // battery info timeouts after 5 seconds -#define TORQEEDO_REPLY_TIMEOUT_MS 25 // stop waiting for replies after 25ms -#define TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS 10000 // errors reported to user at no less than once every 10 seconds -#define TORQEEDO_MIN_RESET_INTERVAL_MS 5000 // minimum time between hard resets/wake -#define TORQEEDO_RESET_THROTTLE_HOLDDOWN_MS 6000 // throttle hold down time after reset/wake +#include "AP_Torqeedo_Backend.h" +#include "AP_Torqeedo_TQBus.h" extern const AP_HAL::HAL& hal; -// parameters const AP_Param::GroupInfo AP_Torqeedo::var_info[] = { - // @Param: TYPE - // @DisplayName: Torqeedo connection type - // @Description: Torqeedo connection type - // @Values: 0:Disabled, 1:Tiller, 2:Motor - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO_FLAGS("TYPE", 1, AP_Torqeedo, _type, (int8_t)ConnectionType::TYPE_DISABLED, AP_PARAM_FLAG_ENABLE), - - // @Param: ONOFF_PIN - // @DisplayName: Torqeedo ON/Off pin - // @Description: Pin number connected to Torqeedo's on/off pin. -1 to use serial port's RTS pin if available - // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("ONOFF_PIN", 2, AP_Torqeedo, _pin_onoff, -1), - - // @Param: DE_PIN - // @DisplayName: Torqeedo DE pin - // @Description: Pin number connected to RS485 to Serial converter's DE pin. -1 to use serial port's CTS pin if available - // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("DE_PIN", 3, AP_Torqeedo, _pin_de, -1), - - // @Param: OPTIONS - // @DisplayName: Torqeedo Options - // @Description: Torqeedo Options Bitmask - // @Bitmask: 0:Log,1:Send debug to GCS - // @User: Advanced - AP_GROUPINFO("OPTIONS", 4, AP_Torqeedo, _options, (int8_t)options::LOG), - - // @Param: POWER - // @DisplayName: Torqeedo Motor Power - // @Description: Torqeedo motor power. Only applied when using motor connection type (e.g. TRQD_TYPE=2) - // @Units: % - // @Range: 0 100 - // @Increment: 1 - // @User: Advanced - AP_GROUPINFO("POWER", 5, AP_Torqeedo, _motor_power, 100), + // 1 to 7 were used for parameters before frontend/backend split - // @Param: SLEW_TIME - // @DisplayName: Torqeedo Throttle Slew Time - // @Description: Torqeedo slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. Higher values cause a slower response, lower values cause a faster response. A value of zero disables the limit - // @Units: s - // @Range: 0 5 - // @Increment: 0.1 - // @User: Advanced - AP_GROUPINFO("SLEW_TIME", 6, AP_Torqeedo, _slew_time, 2.0), + // @Group: 1_ + // @Path: AP_Torqeedo_Params.cpp + AP_SUBGROUPINFO(_params[0], "1_", 8, AP_Torqeedo, AP_Torqeedo_Params), - // @Param: DIR_DELAY - // @DisplayName: Torqeedo Direction Change Delay - // @Description: Torqeedo direction change delay. Output will remain at zero for this many seconds when transitioning between forward and backwards rotation - // @Units: s - // @Range: 0 5 - // @Increment: 0.1 - // @User: Advanced - AP_GROUPINFO("DIR_DELAY", 7, AP_Torqeedo, _dir_delay, 1.0), - - // @Param: AUTO_RST - // @DisplayName: Torqeedo Auto Reset - // @Description: Torqeedo auto reset. If enabled, the motor will be reset if it is not healthy - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - AP_GROUPINFO("AUTO_RST", 8, AP_Torqeedo, _auto_reset, 1), - - // @Param: EXT_BATT - // @DisplayName: Torqeedo External Battery - // @Description: Torqeedo external battery. If enabled, battery status will be requested from the battery - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - AP_GROUPINFO("EXT_BATT", 9, AP_Torqeedo, _ext_batt, 0), +#if AP_TORQEEDO_MAX_INSTANCES > 1 + // @Group: 2_ + // @Path: AP_Torqeedo_Params.cpp + AP_SUBGROUPINFO(_params[1], "2_", 9, AP_Torqeedo, AP_Torqeedo_Params), +#endif AP_GROUPEND }; @@ -129,181 +51,87 @@ AP_Torqeedo::AP_Torqeedo() // initialise driver void AP_Torqeedo::init() { - // exit immediately if not enabled - if (!enabled()) { - return; + // check init has not been called before + for (uint8_t i = 1; i < AP_TORQEEDO_MAX_INSTANCES; i++) { + if (get_instance(i) != nullptr) { + return; + } } - // only init once - // Note: a race condition exists here if init is called multiple times quickly before thread_main has a chance to set _initialise - if (_initialised) { - return; + // create each instance + uint8_t instance; + for (instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + switch ((ConnectionType)_params[instance].type.get()) { + case ConnectionType::TYPE_DISABLED: + // do nothing + break; + case ConnectionType::TYPE_TILLER: + case ConnectionType::TYPE_MOTOR: + _backends[instance] = NEW_NOTHROW AP_Torqeedo_TQBus(_params[instance], instance); + break; + } } - // create background thread to process serial input and output - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Torqeedo::thread_main, void), "torqeedo", 2048, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { - return; + // init each instance, do it after all instances were created, so that they all know things + for (instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->init(); + } } } -// initialise serial port and gpio pins (run from background thread) -bool AP_Torqeedo::init_internals() +// returns true if at least one backend has been configured (e.g. TYPE param has been set) +bool AP_Torqeedo::enabled() const { - // find serial driver and initialise - const AP_SerialManager &serial_manager = AP::serialmanager(); - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Torqeedo, 0); - if (_uart == nullptr) { - return false; - } - _uart->begin(TORQEEDO_SERIAL_BAUD); - _uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); - _uart->set_unbuffered_writes(true); - - // if using tiller connection initialize on/off pin to OFF - if (_type == ConnectionType::TYPE_TILLER) { - if (_pin_onoff > -1) { - hal.gpio->pinMode(_pin_onoff, HAL_GPIO_OUTPUT); - hal.gpio->write(_pin_onoff, 0); - } else { - // use serial port's RTS pin - _uart->set_RTS_pin(false); + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + if (enabled(instance)) { + return true; } } - - // initialise RS485 DE pin (when high, allows send to motor) - if (_pin_de > -1) { - hal.gpio->pinMode(_pin_de, HAL_GPIO_OUTPUT); - hal.gpio->write(_pin_de, 0); - } else { - _uart->set_CTS_pin(false); - } - - return true; + return false; } -// returns true if the driver is enabled -bool AP_Torqeedo::enabled() const +// returns true if the instance has been configured (e.g. TYPE param has been set) +bool AP_Torqeedo::enabled(uint8_t instance) const { - switch ((ConnectionType)_type) { - case ConnectionType::TYPE_DISABLED: - return false; - case ConnectionType::TYPE_TILLER: - case ConnectionType::TYPE_MOTOR: - return true; + if (instance < AP_TORQEEDO_MAX_INSTANCES) { + switch ((ConnectionType)_params[instance].type.get()) { + case ConnectionType::TYPE_DISABLED: + return false; + case ConnectionType::TYPE_TILLER: + case ConnectionType::TYPE_MOTOR: + return true; + } } - return false; } -// consume incoming messages from motor, reply with latest motor speed -// runs in background thread -void AP_Torqeedo::thread_main() +// returns true if all backends are communicating with the motor +bool AP_Torqeedo::healthy() { - // initialisation - if (!init_internals()) { - return; - } - _initialised = true; - - while (true) { - // loop delay - hal.scheduler->delay_microseconds(100); - - // check if transmit pin should be unset - check_for_send_end(); - - // check for timeout waiting for reply - check_for_reply_timeout(); - - // parse incoming characters - uint32_t nbytes = MIN(_uart->available(), 1024U); - while (nbytes-- > 0) { - int16_t b = _uart->read(); - if (b >= 0 ) { - if (parse_byte((uint8_t)b)) { - // complete message received, parse it! - parse_message(); - // clear wait-for-reply because if we are waiting for a reply, this message must be it - set_reply_received(); - } + uint8_t num_backends = 0; + uint8_t num_healthy = 0; + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + auto *backend = get_instance(instance); + if (backend != nullptr) { + num_backends++; + if (backend->healthy()) { + num_healthy++; } } - - // send motor speed - bool log_update = false; - if (safe_to_send()) { - uint32_t now_ms = AP_HAL::millis(); - - // if connected to motor - if (_type == ConnectionType::TYPE_MOTOR) { - if (now_ms - _last_send_motor_ms > TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS) { - // send motor speed every 0.1sec - _send_motor_speed = true; - } else if (now_ms - _last_send_motor_status_request_ms > TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS) { - // send request for motor status - send_motor_msg_request(MotorMsgId::STATUS); - _last_send_motor_status_request_ms = now_ms; - } else if (now_ms - _last_send_motor_param_request_ms > TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS) { - // send request for motor params - send_motor_msg_request(MotorMsgId::PARAM); - _last_send_motor_param_request_ms = now_ms; - } - } - - // send motor speed - if (_send_motor_speed) { - // If no soft faults and not in hold-down period, set throttle - if ((now_ms - _last_reset_ms > TORQEEDO_RESET_THROTTLE_HOLDDOWN_MS) && - !(_display_system_state.flags.set_throttle_stop || _display_system_state.flags.temp_warning) && - !(_display_system_state.master_error_code > 0 && _display_system_state.master_error_code != 132)) { - send_motor_speed_cmd(); - } - else - // set throttle=0 after a reset for the hold-down period - // or if the motor is in a fault state that requires the throttle to be set to 0 - send_motor_speed_cmd(true); - - _send_motor_speed = false; - log_update = true; - } - // if not sending motor speed, send battery status request (if connected to external battery) - else if (_type == ConnectionType::TYPE_TILLER && _ext_batt) { - // send request for battery status - if (now_ms - _last_send_battery_status_request_ms > TORQEEDO_SEND_BATTERY_STATUS_REQUEST_INTERVAL_MS) { - send_battery_msg_request(BatteryMsgId::STATUS); - _last_send_battery_status_request_ms = now_ms; - } - } - } - - // if motor is not healthy and auto reset is enabled, - // toggle the on/off pin to try to hard wake or reset the motor - if (!motor_healthy() && _auto_reset) { - const uint32_t now_ms = AP_HAL::millis(); - // only reset if not reset recently (to avoid infinite reset loop) - if ((now_ms - _last_reset_ms > TORQEEDO_MIN_RESET_INTERVAL_MS)) { - press_on_off_button(); - _last_reset_ms = now_ms; - } - } - - // log high level status and motor speed - log_TRQD(log_update); } + + return ((num_backends > 0) && (num_healthy == num_backends)); } -// returns true if communicating with the motor -bool AP_Torqeedo::motor_healthy() +// returns true if instance is healthy +bool AP_Torqeedo::healthy(uint8_t instance) { - if (!_initialised) { + auto *backend = get_instance(instance); + if (backend == nullptr) { return false; } - { - // healthy if both receive and send have occurred in the last 3 seconds - WITH_SEMAPHORE(_last_motor_healthy_sem); - const uint32_t now_ms = AP_HAL::millis(); - return ((now_ms - _last_received_motor_ms < 3000) && (now_ms - _last_send_motor_ms < 3000)); - } + return backend->healthy(); } // run pre-arm check. returns false on failure and fills in failure_msg @@ -315,1071 +143,65 @@ bool AP_Torqeedo::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } - if (!_initialised) { - strncpy(failure_msg, "not initialised", failure_msg_len); - return false; - } - if (!motor_healthy()) { + if (!healthy()) { strncpy(failure_msg, "not healthy", failure_msg_len); return false; } return true; } -// 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 -{ - switch (code) { - case 2: - return "stator high temp"; - case 5: - return "propeller blocked"; - case 6: - return "motor low voltage"; - case 7: - return "motor high current"; - case 8: - return "pcb temp high"; - case 21: - return "tiller cal bad"; - case 22: - return "mag bad"; - case 23: - return "range incorrect"; - case 30: - return "motor comm error"; - case 32: - return "tiller comm error"; - case 33: - return "general comm error"; - case 34: - return "kill switch activated"; - case 41: - case 42: - return "charge voltage bad"; - case 43: - return "battery flat"; - case 45: - return "battery high current"; - case 46: - return "battery temp error"; - case 48: - return "charging temp error"; - case 70: - return "battery over/under temp during charge"; - case 71: - return "battery over/under temp during discharge"; - case 72: - return "battery FET overtemp"; - case 73: - return "battery overcurrent during discharge"; - case 74: - return "battery overcurrent during charge"; - case 75: - return "battery activating pyro switch"; - case 76: - return "battery undervoltage"; - case 77: - return "battery overvoltage during charging"; - case 78: - return "battery overcharge"; - case 79: - return "battery electronic fault"; - case 80: - return "battery deep discharging"; - case 81: - return "battery water sensor triggered"; - case 82: - return "charge imbalance between batteries"; - case 83: - return "battery software version error"; - case 84: - return "battery count does not match enumeration"; - case 85: - return "battery cell imbalance"; - } - - return nullptr; -} - -// report changes in error codes to user -void AP_Torqeedo::report_error_codes() +// clear motor errors +void AP_Torqeedo::clear_motor_error() { - // skip reporting if we have already reported status very recently - const uint32_t now_ms = AP_HAL::millis(); - - // skip reporting if no changes in flags and already reported within 10 seconds - const bool flags_changed = (_display_system_state_flags_prev.value != _display_system_state.flags.value) || - (_display_system_state_master_error_code_prev != _display_system_state.master_error_code) || - (_motor_status_prev.status_flags_value != _motor_status.status_flags_value) || - (_motor_status_prev.error_flags_value != _motor_status.error_flags_value); - if (!flags_changed && ((now_ms - _last_error_report_ms) < TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS)) { - return; - } - - // report display system errors - const char* msg_prefix = "Torqeedo:"; - (void)msg_prefix; // sometimes unused when HAL_GCS_ENABLED is false - if (_display_system_state.flags.set_throttle_stop) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); - } - if (_display_system_state.flags.temp_warning) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); - } - if (_display_system_state.flags.batt_nearly_empty) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix); - } - if (_display_system_state.master_error_code > 0 && _display_system_state.master_error_code != 132) { - const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); - if (error_string != nullptr) { - GCS_SEND_TEXT( - MAV_SEVERITY_CRITICAL, "%s err:%u %s", - msg_prefix, - _display_system_state.master_error_code, - error_string); - } else { - GCS_SEND_TEXT( - MAV_SEVERITY_CRITICAL, "%s err:%u", - msg_prefix, - _display_system_state.master_error_code); + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + auto *backend = get_instance(instance); + if (backend != nullptr) { + backend->clear_motor_error(); } } - - // report motor status errors - if (_motor_status.error_flags.overcurrent) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix); - } - if (_motor_status.error_flags.blocked) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix); - } - if (_motor_status.error_flags.overvoltage_static || _motor_status.error_flags.overvoltage_current) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix); - } - if (_motor_status.error_flags.undervoltage_static || _motor_status.error_flags.undervoltage_current) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix); - } - if (_motor_status.error_flags.overtemp_motor || _motor_status.error_flags.overtemp_pcb) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); - } - if (_motor_status.error_flags.timeout_rs485) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix); - } - if (_motor_status.error_flags.temp_sensor_error) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix); - } - if (_motor_status.error_flags.tilt) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix); - } - - // display OK if all errors cleared - const bool prev_errored = (_display_system_state_flags_prev.value != 0) || - (_display_system_state_master_error_code_prev != 0) || - (_motor_status_prev.error_flags_value != 0); - - const bool now_errored = (_display_system_state.flags.value != 0) || - (_display_system_state.master_error_code != 0) || - (_motor_status.error_flags_value != 0); - - if (!now_errored && prev_errored) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix); - } - - // record change in state and reporting time - _display_system_state_flags_prev.value = _display_system_state.flags.value; - _display_system_state_master_error_code_prev = _display_system_state.master_error_code; - _motor_status_prev = _motor_status; - _last_error_report_ms = now_ms; } // get latest battery status info. returns true on success and populates arguments -bool AP_Torqeedo::get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const +// instance is normally 0 or 1, if invalid instances are provided the first instance is used +bool AP_Torqeedo::get_batt_info(uint8_t instance, float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const { - - if (_ext_batt) { - // always use external battery info if selected - if ((AP_HAL::millis() - _battery_status.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { - voltage = _battery_status.voltage; - current_amps = _battery_status.current; - temp_C = _battery_status.temp_cell_pack; - pct_remaining = static_cast(_battery_status.capacity_pct); - return true; - } + // for invalid instances use the first instance + if (instance > AP_TORQEEDO_MAX_INSTANCES-1) { + instance = 0; } - else { - // use battery info from display_system_state if available (tiller connection) - if ((AP_HAL::millis() - _display_system_state.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { - voltage = _display_system_state.batt_voltage; - current_amps = _display_system_state.batt_current; - temp_C = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); - pct_remaining = _display_system_state.batt_charge_pct; - return true; - } - // use battery info from motor_param if available (motor connection) - if ((AP_HAL::millis() - _motor_param.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { - voltage = _motor_param.voltage; - current_amps = _motor_param.current; - temp_C = MAX(_motor_param.pcb_temp, _motor_param.stator_temp); - pct_remaining = 0; // motor does not know percent remaining - return true; - } + // return battery info for specified instance + auto *backend = get_instance(instance); + if (backend != nullptr) { + return backend->get_batt_info(voltage, current_amps, temp_C, pct_remaining); } - return false; } // get battery capacity. returns true on success and populates argument -bool AP_Torqeedo::get_batt_capacity_Ah(uint16_t &_hours) const -{ - if (_ext_batt) { - if (_battery_status.capacity <= 0.0) { - return false; - } - amp_hours = static_cast(_battery_status.capacity); - return true; - } - - if (_display_system_setup.batt_capacity == 0) { - return false; - } - amp_hours = _display_system_setup.batt_capacity; - return true; -} - -// process a single byte received on serial port -// return true if a complete message has been received (the message will be held in _received_buff) -bool AP_Torqeedo::parse_byte(uint8_t b) -{ - bool complete_msg_received = false; - - switch (_parse_state) { - case ParseState::WAITING_FOR_HEADER: - if (b == TORQEEDO_PACKET_HEADER) { - _parse_state = ParseState::WAITING_FOR_FOOTER; - } - _received_buff_len = 0; - _parse_escape_received = false; - break; - case ParseState::WAITING_FOR_FOOTER: - if (b == TORQEEDO_PACKET_FOOTER) { - _parse_state = ParseState::WAITING_FOR_HEADER; - - // check message length - if (_received_buff_len == 0) { - _parse_error_count++; - break; - } - - // check crc - const uint8_t crc_expected = crc8_maxim(_received_buff, _received_buff_len-1); - if (_received_buff[_received_buff_len-1] != crc_expected) { - _parse_error_count++; - break; - } - _parse_success_count++; - complete_msg_received = true; - } else { - // escape character handling - if (_parse_escape_received) { - b ^= TORQEEDO_PACKET_ESCAPE_MASK; - _parse_escape_received = false; - } else if (b == TORQEEDO_PACKET_ESCAPE) { - // escape character received, record this and ignore this byte - _parse_escape_received = true; - break; - } - // add to buffer - _received_buff[_received_buff_len] = b; - _received_buff_len++; - if (_received_buff_len > TORQEEDO_MESSAGE_LEN_MAX) { - // message too long - _parse_state = ParseState::WAITING_FOR_HEADER; - _parse_error_count++; - } - } - break; - } - - return complete_msg_received; -} - -// process message held in _received_buff -void AP_Torqeedo::parse_message() -{ - // message address (i.e. target of message) - const MsgAddress msg_addr = (MsgAddress)_received_buff[0]; - - // handle messages sent to "remote" (aka tiller) - if ((_type == ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::REMOTE1)) { - RemoteMsgId msg_id = (RemoteMsgId)_received_buff[1]; - if (msg_id == RemoteMsgId::REMOTE) { - // request received to send updated motor speed - _send_motor_speed = true; - - // record time of successful receive for health reporting - WITH_SEMAPHORE(_last_motor_healthy_sem); - _last_received_motor_ms = AP_HAL::millis(); - - } - return; - } - - // handle messages sent to Display - if ((_type == ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::DISPLAY)) { - DisplayMsgId msg_id = (DisplayMsgId)_received_buff[1]; - switch (msg_id) { - case DisplayMsgId::SYSTEM_STATE : - if (_received_buff_len == 30) { - // fill in _display_system_state - _display_system_state.flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); - _display_system_state.master_state = _received_buff[4]; // deprecated - _display_system_state.master_error_code = _received_buff[5]; - _display_system_state.motor_voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; - _display_system_state.motor_current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; - _display_system_state.motor_power = UINT16_VALUE(_received_buff[10], _received_buff[11]); - _display_system_state.motor_rpm = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]); - _display_system_state.motor_pcb_temp = _received_buff[14]; - _display_system_state.motor_stator_temp = _received_buff[15]; - _display_system_state.batt_charge_pct = _received_buff[16]; - _display_system_state.batt_voltage = UINT16_VALUE(_received_buff[17], _received_buff[18]) * 0.01; - _display_system_state.batt_current = UINT16_VALUE(_received_buff[19], _received_buff[20]) * 0.1; - _display_system_state.gps_speed = UINT16_VALUE(_received_buff[21], _received_buff[22]); - _display_system_state.range_miles = UINT16_VALUE(_received_buff[23], _received_buff[24]); - _display_system_state.range_minutes = UINT16_VALUE(_received_buff[25], _received_buff[26]); - _display_system_state.temp_sw = _received_buff[27]; - _display_system_state.temp_rp = _received_buff[28]; - _display_system_state.last_update_ms = AP_HAL::millis(); - - // update esc telem sent to ground station - const uint8_t esc_temp = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); - const uint8_t motor_temp = MAX(_display_system_state.motor_pcb_temp, _display_system_state.motor_stator_temp); - update_esc_telem(_display_system_state.motor_rpm, - _display_system_state.motor_voltage, - _display_system_state.motor_current, - esc_temp, - motor_temp); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRST - // @Description: Torqeedo System State - // @Field: TimeUS: Time since system startup - // @Field: F: Flags bitmask - // @Field: Err: Master error code - // @Field: MVolt: Motor voltage - // @Field: MCur: Motor current - // @Field: Pow: Motor power - // @Field: RPM: Motor RPM - // @Field: MTemp: Motor Temp (higher of pcb or stator) - // @Field: BPct: Battery charge percentage - // @Field: BVolt: Battery voltage - // @Field: BCur: Battery current - AP::logger().Write("TRST", "TimeUS,F,Err,MVolt,MCur,Pow,RPM,MTemp,BPct,BVolt,BCur", "QHBffHhBBff", - AP_HAL::micros64(), - _display_system_state.flags.value, - _display_system_state.master_error_code, - _display_system_state.motor_voltage, - _display_system_state.motor_current, - _display_system_state.motor_power, - _display_system_state.motor_rpm, - motor_temp, - _display_system_state.batt_charge_pct, - _display_system_state.batt_voltage, - _display_system_state.batt_current); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRST F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f", - (unsigned)_display_system_state.flags.value, - (unsigned)_display_system_state.master_error_code, - (double)_display_system_state.motor_voltage, - (double)_display_system_state.motor_current, - (unsigned)_display_system_state.motor_power, - (int)motor_temp, - (unsigned)_display_system_state.batt_charge_pct, - (double)_display_system_state.batt_voltage, - (double)_display_system_state.batt_current); - } - - // report any errors - report_error_codes(); - } else { - // unexpected length - _parse_error_count++; - } - break; - case DisplayMsgId::SYSTEM_SETUP: - if (_received_buff_len == 13) { - // fill in display system setup - _display_system_setup.flags = _received_buff[2]; - _display_system_setup.motor_type = _received_buff[3]; - _display_system_setup.motor_sw_version = UINT16_VALUE(_received_buff[4], _received_buff[5]); - _display_system_setup.batt_capacity = UINT16_VALUE(_received_buff[6], _received_buff[7]); - _display_system_setup.batt_charge_pct = _received_buff[8]; - _display_system_setup.batt_type = _received_buff[9]; - _display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRSE - // @Description: Torqeedo System Setup - // @Field: TimeUS: Time since system startup - // @Field: Flag: Flags - // @Field: MotType: Motor type - // @Field: MotVer: Motor software version - // @Field: BattCap: Battery capacity - // @Field: BattPct: Battery charge percentage - // @Field: BattType: Battery type - // @Field: SwVer: Master software version - AP::logger().Write("TRSE", "TimeUS,Flag,MotType,MotVer,BattCap,BattPct,BattType,SwVer", "QBBHHBBH", - AP_HAL::micros64(), - _display_system_setup.flags, - _display_system_setup.motor_type, - _display_system_setup.motor_sw_version, - _display_system_setup.batt_capacity, - _display_system_setup.batt_charge_pct, - _display_system_setup.batt_type, - _display_system_setup.master_sw_version); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRSE:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%", - (unsigned)_display_system_setup.master_sw_version, - (unsigned)_display_system_setup.flags, - (unsigned)_display_system_setup.motor_type, - (unsigned)_display_system_setup.motor_sw_version, - (unsigned)_display_system_setup.batt_type, - (unsigned)_display_system_setup.batt_capacity, - (unsigned)_display_system_setup.batt_charge_pct); - } - } else { - // unexpected length - _parse_error_count++; - } - break; - default: - // ignore message - break; - } - return; - } - - // handle reply from battery - // For now, only process battery messages if in tiller type mode to avoid changing - // code for motor type mode. This is because both reply to the bus master. - if ((_type == ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::BUS_MASTER)) { - // replies strangely do not return the msgid so we must have stored it - BatteryMsgId msg_id = (BatteryMsgId)_reply_msgid; - switch (msg_id) { - case BatteryMsgId::STATUS: - if (_received_buff_len == 29) { - _battery_status.status_flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); - _battery_status.warning_flags.value = UINT16_VALUE(_received_buff[4], _received_buff[5]); - _battery_status.error_flags.value = UINT16_VALUE(_received_buff[6], _received_buff[7]); - _battery_status.temp_cell_pack = (float)((int16_t)UINT16_VALUE(_received_buff[8], _received_buff[9])) * 0.1; - _battery_status.temp_pcb = (float)((int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11])) * 0.1; - _battery_status.voltage = (float)(UINT16_VALUE(_received_buff[12], _received_buff[13])) * 0.1; - _battery_status.current = -1.0 * (float)((int16_t)UINT16_VALUE(_received_buff[14], _received_buff[15])) * 0.1; - _battery_status.power = UINT16_VALUE(_received_buff[16], _received_buff[17]); - _battery_status.capacity = (float)(UINT16_VALUE(_received_buff[18], _received_buff[19])) * 0.1; - _battery_status.capacity_remaining = (float)(UINT16_VALUE(_received_buff[20], _received_buff[21])) * 0.1; - _battery_status.capacity_pct = UINT16_VALUE(_received_buff[22], _received_buff[23]); - _battery_status.running_time = UINT16_VALUE(_received_buff[24], _received_buff[25]); - _battery_status.water_detect = UINT16_VALUE(_received_buff[26], _received_buff[27]); - _battery_status.last_update_ms = AP_HAL::millis(); - -#if HAL_LOGGING_ENABLED - - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRBS - // @Description: Torqeedo Battery Status - // @Field: TimeUS: Time since system startup - // @Field: State: Battery status flags - // @Field: Warn: Battery warning flags - // @Field: Err: Battery error flags - // @Field: CTemp: Cell pack temp - // @Field: PTemp: PCB temp - // @Field: Volt: Battery voltage - // @Field: Cur: Battery current - // @Field: Pow: Battery power - // @Field: Cap: Battery capacity - // @Field: CapPct: Battery capacity percentage - // @Field: CapRem: Battery capacity remaining - // @Field: Water: Water detect - AP::logger().Write("TRBS", "TimeUS,State,Warn,Err,CTemp,PTemp,Volt,Cur,Pow,Cap,CapPct,CapRem,Water", "QHHHffffHfHfH", - AP_HAL::micros64(), - _battery_status.status_flags.value, - _battery_status.warning_flags.value, - _battery_status.error_flags.value, - _battery_status.temp_cell_pack, - _battery_status.temp_pcb, - _battery_status.voltage, - _battery_status.current, - _battery_status.power, - _battery_status.capacity, - _battery_status.capacity_pct, - _battery_status.capacity_remaining, - _battery_status.water_detect); - } - -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRBS S:%d W:%d E:%d V:%4.1f C:%4.1f P:%u Cap:%4.0f Rem:%u", - _battery_status.status_flags.value, - _battery_status.warning_flags.value, - _battery_status.error_flags.value, - (double)_battery_status.voltage, - (double)_battery_status.current, - (unsigned)_battery_status.power, - (double)_battery_status.capacity, - (unsigned)_battery_status.capacity_pct); - } - } - else { - // unexpected length - // _parse_error_count++; - // Lots of messages come addressed to the bus master, so we don't want to count these as errors - } - break; - - case BatteryMsgId::INFO: - // we do not process these replies - break; - - default: - // ignore unknown messages - break; - } - } - - // handle reply from motor - if ((_type == ConnectionType::TYPE_MOTOR) && (msg_addr == MsgAddress::BUS_MASTER)) { - // replies strangely do not return the msgid so we must have stored it - MotorMsgId msg_id = (MotorMsgId)_reply_msgid; - - // record time of successful receive for health reporting - WITH_SEMAPHORE(_last_motor_healthy_sem); - _last_received_motor_ms = AP_HAL::millis(); - - switch (msg_id) { - - case MotorMsgId::PARAM: - if (_received_buff_len == 15) { - _motor_param.rpm = (int16_t)UINT16_VALUE(_received_buff[2], _received_buff[3]); - _motor_param.power = UINT16_VALUE(_received_buff[4], _received_buff[5]); - _motor_param.voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; - _motor_param.current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; - _motor_param.pcb_temp = (int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11]) * 0.1; - _motor_param.stator_temp = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]) * 0.1; - _motor_param.last_update_ms = AP_HAL::millis(); - - // update esc telem sent to ground station - update_esc_telem(_motor_param.rpm, - _motor_param.voltage, - _motor_param.current, - _motor_param.pcb_temp, // esc temp - _motor_param.stator_temp); // motor temp - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRMP - // @Description: Torqeedo Motor Param - // @Field: TimeUS: Time since system startup - // @Field: RPM: Motor RPM - // @Field: Pow: Motor power - // @Field: Volt: Motor voltage - // @Field: Cur: Motor current - // @Field: ETemp: ESC Temp - // @Field: MTemp: Motor Temp - AP::logger().Write("TRMP", "TimeUS,RPM,Pow,Volt,Cur,ETemp,MTemp", "QhHffff", - AP_HAL::micros64(), - _motor_param.rpm, - _motor_param.power, - _motor_param.voltage, - _motor_param.current, - _motor_param.pcb_temp, - _motor_param.stator_temp); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRMP: rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f", - (int)_motor_param.rpm, - (unsigned)_motor_param.power, - (double)_motor_param.voltage, - (double)_motor_param.current, - (double)_motor_param.pcb_temp, - (double)_motor_param.stator_temp); - } - } else { - // unexpected length - _parse_error_count++; - } - break; - - case MotorMsgId::STATUS: - if (_received_buff_len == 6) { - _motor_status.status_flags_value = _received_buff[2]; - _motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRMS - // @Description: Torqeedo Motor Status - // @Field: TimeUS: Time since system startup - // @Field: State: Motor status flags - // @Field: Err: Motor error flags - AP::logger().Write("TRMS", "TimeUS,State,Err", "QBH", - AP_HAL::micros64(), - _motor_status.status_flags_value, - _motor_status.error_flags_value); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d", - _motor_status.status_flags_value, - _motor_status.error_flags_value); - } - - // report any errors - report_error_codes(); - } else { - // unexpected length - _parse_error_count++; - } - break; - - case MotorMsgId::INFO: - case MotorMsgId::DRIVE: - case MotorMsgId::CONFIG: - // we do not process these replies - break; - - default: - // ignore unknown messages - break; - } - } -} - -// set DE Serial CTS pin to enable sending commands to motor -void AP_Torqeedo::send_start() -{ - // set gpio pin or serial port's CTS pin - if (_pin_de > -1) { - hal.gpio->write(_pin_de, 1); - } else { - _uart->set_CTS_pin(true); - } -} - -// check for timeout after sending and unset pin if required -void AP_Torqeedo::check_for_send_end() -{ - if (_send_delay_us == 0) { - // not sending - return; - } - - if (AP_HAL::micros() - _send_start_us < _send_delay_us) { - // return if delay has not yet elapsed - return; - } - _send_delay_us = 0; - - // unset gpio or serial port's CTS pin - if (_pin_de > -1) { - hal.gpio->write(_pin_de, 0); - } else { - _uart->set_CTS_pin(false); - } -} - -// calculate delay require to allow bytes to be sent -uint32_t AP_Torqeedo::calc_send_delay_us(uint8_t num_bytes) -{ - // baud rate of 19200 bits/sec - // total number of bits = 10 x num_bytes - // Subtract 5 bits to stop transmission during the padding byte (but after its start bit - // convert from seconds to micros by multiplying by 1,000,000 - const uint32_t delay_us = 1e6 * ((num_bytes * 10) - 5) / TORQEEDO_SERIAL_BAUD; - return delay_us; -} - -// record msgid of message to wait for and set timer for timeout handling -void AP_Torqeedo::set_expected_reply_msgid(uint8_t msg_id) -{ - _reply_msgid = msg_id; - _reply_wait_start_us = AP_HAL::micros(); -} - -// check for timeout waiting for reply message -void AP_Torqeedo::check_for_reply_timeout() -{ - // return immediately if not waiting for reply - if (_reply_wait_start_us == 0) { - return; - } - if (AP_HAL::micros() - _reply_wait_start_us > (TORQEEDO_REPLY_TIMEOUT_MS * 1000)) { - _reply_wait_start_us = 0; - _parse_error_count++; - } -} - -// mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply -void AP_Torqeedo::set_reply_received() -{ - _reply_wait_start_us = 0; -} - -// send a message to the motor with the specified message contents -// msg_contents should not include the header, footer or CRC -// returns true on success -bool AP_Torqeedo::send_message(const uint8_t msg_contents[], uint8_t num_bytes) -{ - // buffer for outgoing message - uint8_t send_buff[TORQEEDO_MESSAGE_LEN_MAX]; - uint8_t send_buff_num_bytes = 0; - - // calculate crc - const uint8_t crc = crc8_maxim(msg_contents, num_bytes); - - // add header - send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_HEADER; - - // add contents - for (uint8_t i=0; i= ARRAY_SIZE(send_buff)) { - _parse_error_count++; - return false; - } - send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_FOOTER; - - // add padding byte - if (send_buff_num_bytes >= ARRAY_SIZE(send_buff)) { - _parse_error_count++; - return false; - } - send_buff[send_buff_num_bytes++] = 0xFF; - - // set send pin - send_start(); - - // write message - _uart->write(send_buff, send_buff_num_bytes); - - // record start and expected delay to send message - _send_start_us = AP_HAL::micros(); - _send_delay_us = calc_send_delay_us(send_buff_num_bytes); - - return true; -} - -// add a byte to a message buffer including adding the escape character (0xAE) if necessary -// this should only be used when adding the contents to the buffer, not the header and footer -// num_bytes is updated to the next free byte -bool AP_Torqeedo::add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const +// instance is normally 0 or 1, if invalid instances are provided the first instance is used +bool AP_Torqeedo::get_batt_capacity_Ah(uint8_t instance, uint16_t &_hours) const { - bool escape_required = (byte_to_add == TORQEEDO_PACKET_HEADER || - byte_to_add == TORQEEDO_PACKET_FOOTER || - byte_to_add == TORQEEDO_PACKET_ESCAPE); - - // check if we have enough space - if (num_bytes + (escape_required ? 2 : 1) >= msg_buff_size) { - return false; - } - - // add byte - if (escape_required) { - msg_buff[num_bytes++] = TORQEEDO_PACKET_ESCAPE; - msg_buff[num_bytes++] = byte_to_add ^ TORQEEDO_PACKET_ESCAPE_MASK; - } else { - msg_buff[num_bytes++] = byte_to_add; - } - return true; -} - -// Example "Remote (0x01)" reply message to allow tiller to control motor speed -// Byte Field Definition Example Value Comments -// --------------------------------------------------------------------------------- -// byte 0 Header 0xAC -// byte 1 TargetAddress 0x00 see MsgAddress enum -// byte 2 Message ID 0x00 only master populates this. replies have this set to zero -// byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid -// byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 -// byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) -// byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) -// byte 7 CRC-Maxim ---- CRC-Maxim value -// byte 8 Footer 0xAD -// -// example message when rotating tiller handle forwards: "AC 00 00 05 00 00 ED 95 AD" (+237) -// example message when rotating tiller handle backwards: "AC 00 00 05 00 FF AE 2C 0C AD" (-82) - -// send a motor speed command as a value from -1000 to +1000 -// value is taken directly from SRV_Channel -// for tiller connection this sends the "Remote (0x01)" message -// for motor connection this sends the "Motor Drive (0x82)" message -void AP_Torqeedo::send_motor_speed_cmd(bool set_zero_speed) -{ - // calculate desired motor speed - if (!hal.util->get_soft_armed() || set_zero_speed) { - _motor_speed_desired = 0; - } else { - // convert throttle output to motor output in range -1000 to +1000 - // ToDo: convert PWM output to motor output so that SERVOx_MIN, MAX and TRIM take effect - _motor_speed_desired = constrain_int16(SRV_Channels::get_output_norm(SRV_Channel::Aux_servo_function_t::k_throttle) * 1000.0, -1000, 1000); - } - - // updated limited motor speed - int16_t mot_speed_limited = calc_motor_speed_limited(_motor_speed_desired); - - // by default use tiller connection command - uint8_t mot_speed_cmd_buff[] = {(uint8_t)MsgAddress::BUS_MASTER, 0x0, 0x5, 0x0, HIGHBYTE(mot_speed_limited), LOWBYTE(mot_speed_limited)}; - - // update message if using motor connection - if (_type == ConnectionType::TYPE_MOTOR) { - const uint8_t motor_power = (uint8_t)constrain_int16(_motor_power, 0, 100); - mot_speed_cmd_buff[0] = (uint8_t)MsgAddress::MOTOR; - mot_speed_cmd_buff[1] = (uint8_t)MotorMsgId::DRIVE; - mot_speed_cmd_buff[2] = (mot_speed_limited == 0 ? 0 : 0x01) | (_motor_clear_error ? 0x04 : 0); // 1:enable motor, 2:fast off, 4:clear error - mot_speed_cmd_buff[3] = mot_speed_limited == 0 ? 0 : motor_power; // motor power from 0 to 100 - - // set expected reply message id - set_expected_reply_msgid((uint8_t)MotorMsgId::DRIVE); - - // reset motor clear error request - _motor_clear_error = false; + // for invalid instances use the first instance + if (instance > AP_TORQEEDO_MAX_INSTANCES-1) { + instance = 0; } - // send a message - if (send_message(mot_speed_cmd_buff, ARRAY_SIZE(mot_speed_cmd_buff))) { - // record time of send for health reporting - WITH_SEMAPHORE(_last_motor_healthy_sem); - _last_send_motor_ms = AP_HAL::millis(); + // return battery capacity from specified instance + auto *backend = get_instance(instance); + if (backend != nullptr) { + return backend->get_batt_capacity_Ah(amp_hours); } + return false; } -// send request to motor to reply with a particular message -// msg_id can be INFO, STATUS or PARAM -void AP_Torqeedo::send_motor_msg_request(MotorMsgId msg_id) -{ - // prepare message - uint8_t mot_status_request_buff[] = {(uint8_t)MsgAddress::MOTOR, (uint8_t)msg_id}; - - // record waiting for reply - set_expected_reply_msgid((uint8_t)msg_id); - - // send a message - send_message(mot_status_request_buff, ARRAY_SIZE(mot_status_request_buff)); -} - -// send request to battery to reply with a particular message -// msg_id can be STATUS -void AP_Torqeedo::send_battery_msg_request(BatteryMsgId msg_id) -{ - // prepare message - uint8_t batt_status_request_buff[] = {(uint8_t)MsgAddress::BATTERY, (uint8_t)msg_id}; - - // record waiting for reply - set_expected_reply_msgid((uint8_t)msg_id); - - // send a message - send_message(batt_status_request_buff, ARRAY_SIZE(batt_status_request_buff)); -} - -// calculate the limited motor speed that is sent to the motors -// desired_motor_speed argument and returned value are in the range -1000 to 1000 -int16_t AP_Torqeedo::calc_motor_speed_limited(int16_t desired_motor_speed) -{ - const uint32_t now_ms = AP_HAL::millis(); - - // update dir_limit flag for forward-reverse transition delay - const bool dir_delay_active = is_positive(_dir_delay); - if (!dir_delay_active) { - // allow movement in either direction - _dir_limit = 0; - } else { - // by default limit motor direction to previous iteration's direction - if (is_positive(_motor_speed_limited)) { - _dir_limit = 1; - } else if (is_negative(_motor_speed_limited)) { - _dir_limit = -1; - } else { - // motor speed is zero - if ((_motor_speed_zero_ms != 0) && ((now_ms - _motor_speed_zero_ms) > (_dir_delay * 1000))) { - // delay has passed so allow movement in either direction - _dir_limit = 0; - _motor_speed_zero_ms = 0; - } - } - } - - // calculate upper and lower limits for forward-reverse transition delay - int16_t lower_limit = -1000; - int16_t upper_limit = 1000; - if (_dir_limit < 0) { - upper_limit = 0; - } - if (_dir_limit > 0) { - lower_limit = 0; - } - - // calculate dt since last update - 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; - upper_limit = 0; - } - _motor_speed_limited_ms = now_ms; - - // apply slew limit - if (_slew_time > 0) { - const float chg_max = 1000.0 * dt / _slew_time; - _motor_speed_limited = constrain_float(desired_motor_speed, _motor_speed_limited - chg_max, _motor_speed_limited + chg_max); - } else { - // no slew limit - _motor_speed_limited = desired_motor_speed; - } - - // apply upper and lower limits - _motor_speed_limited = constrain_float(_motor_speed_limited, lower_limit, upper_limit); - - // record time motor speed becomes zero - if (is_zero(_motor_speed_limited)) { - if (_motor_speed_zero_ms == 0) { - _motor_speed_zero_ms = now_ms; - } - } else { - // clear timer - _motor_speed_zero_ms = 0; - } - - return (int16_t)_motor_speed_limited; -} - -// output logging and debug messages (if required) -// force_logging should be true if caller wants to ensure the latest status is logged -void AP_Torqeedo::log_TRQD(bool force_logging) -{ - // exit immediately if options are all unset - if (_options == 0) { - return; - } - - // return if not enough time has passed since last output - const uint32_t now_ms = AP_HAL::millis(); - if (!force_logging && (now_ms - _last_log_TRQD_ms < TORQEEDO_LOG_TRQD_INTERVAL_MS)) { - return; - } - _last_log_TRQD_ms = now_ms; - -#if HAL_LOGGING_ENABLED || HAL_GCS_ENABLED - const bool health = motor_healthy(); - int16_t actual_motor_speed = get_motor_speed_limited(); - -#if HAL_LOGGING_ENABLED - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRQD - // @Description: Torqeedo Status - // @Field: TimeUS: Time since system startup - // @Field: Health: Health - // @Field: DesMotSpeed: Desired Motor Speed (-1000 to 1000) - // @Field: MotSpeed: Motor Speed (-1000 to 1000) - // @Field: SuccCnt: Success Count - // @Field: ErrCnt: Error Count - AP::logger().Write("TRQD", "TimeUS,Health,DesMotSpeed,MotSpeed,SuccCnt,ErrCnt", "QBhhII", - AP_HAL::micros64(), - health, - _motor_speed_desired, - actual_motor_speed, - _parse_success_count, - _parse_error_count); - } -#endif - - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld", - (unsigned)health, - (int)_motor_speed_desired, - (int)actual_motor_speed, - (unsigned long)_parse_success_count, - (unsigned long)_parse_error_count); - } -#endif // HAL_LOGGING_ENABLED || HAL_GCS_ENABLED -} - -// send ESC telemetry -void AP_Torqeedo::update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC) -{ -#if HAL_WITH_ESC_TELEM - // find servo output channel - uint8_t telem_esc_index = 0; - IGNORE_RETURN(SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t::k_throttle, telem_esc_index)); - - // fill in telemetry data structure - AP_ESC_Telem_Backend::TelemetryData telem_dat {}; - telem_dat.temperature_cdeg = esc_tempC * 100; // temperature in centi-degrees - telem_dat.voltage = voltage; // voltage in volts - telem_dat.current = current_amps; // current in amps - telem_dat.motor_temp_cdeg = motor_tempC * 100; // motor temperature in centi-degrees - - // send telem and rpm data - update_telem_data(telem_esc_index, telem_dat, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | - AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | - AP_ESC_Telem_Backend::TelemetryType::CURRENT | - AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); - - update_rpm(telem_esc_index, rpm); -#endif -} - -// set the on/off pin to on momentarily to wake the motor or clear an error state -void AP_Torqeedo::press_on_off_button() +// return pointer to backend given an instance number +AP_Torqeedo_Backend *AP_Torqeedo::get_instance(uint8_t instance) const { - if (_type == ConnectionType::TYPE_TILLER) { - if (_pin_onoff > -1) { - hal.gpio->pinMode(_pin_onoff, HAL_GPIO_OUTPUT); - hal.gpio->write(_pin_onoff, 1); - hal.scheduler->delay(500); - hal.gpio->write(_pin_onoff, 0); - } else { - // use serial port's RTS pin to turn on battery - _uart->set_RTS_pin(true); - hal.scheduler->delay(500); - _uart->set_RTS_pin(false); - } - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Torqeedo: On/Off button pressed"); + if (instance < AP_TORQEEDO_MAX_INSTANCES) { + return _backends[instance]; } + return nullptr; } // get the AP_Torqeedo singleton @@ -1391,10 +213,11 @@ AP_Torqeedo *AP_Torqeedo::get_singleton() AP_Torqeedo *AP_Torqeedo::_singleton = nullptr; namespace AP { + AP_Torqeedo *torqeedo() { return AP_Torqeedo::get_singleton(); } -}; +} -#endif // HAL_TORQEEDO_ENABLED +#endif // HAL_TORQEEDO_ENABLED \ No newline at end of file diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.h b/libraries/AP_Torqeedo/AP_Torqeedo.h index df583cc39b66e4..9eb72af9e56dff 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.h +++ b/libraries/AP_Torqeedo/AP_Torqeedo.h @@ -15,32 +15,7 @@ /* This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol - which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW - - The autopilot should be connected either to the battery's tiller connector or directly to the motor - as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html - TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. - - Tiller connection: Autopilot <-> Battery (master) <-> Motor - Motor connection: Autopilot (master) <-> Motor - - Communication between the components is always initiated by the master with replies sent within 25ms - - Example "Remote (0x01)" reply message to allow tiller to control motor speed - Byte Field Definition Example Value Comments - --------------------------------------------------------------------------------- - byte 0 Header 0xAC - byte 1 TargetAddress 0x00 see MsgAddress enum - byte 2 Message ID 0x00 only master populates this. replies have this set to zero - byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid - byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 - byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) - byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) - byte 7 CRC-Maxim ---- CRC-Maxim value - byte 8 Footer 0xAD - - More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. - */ +*/ #pragma once @@ -48,90 +23,30 @@ #if HAL_TORQEEDO_ENABLED -#include #include +#include "AP_Torqeedo_Params.h" + +#define AP_TORQEEDO_MAX_INSTANCES 2 // maximum number of Torqeedo backends + +// declare backend classes +class AP_Torqeedo_Backend; +class AP_Torqeedo_TQBus; -#define TORQEEDO_MESSAGE_LEN_MAX 35 // messages are no more than 35 bytes +class AP_Torqeedo { + + // declare backends as friends + friend class AP_Torqeedo_Backend; + friend class AP_Torqeedo_TQBus; -class AP_Torqeedo : public AP_ESC_Telem_Backend { public: AP_Torqeedo(); + /* Do not allow copies */ CLASS_NO_COPY(AP_Torqeedo); + // get singleton instance static AP_Torqeedo* get_singleton(); - // initialise driver - void init(); - - // consume incoming messages from motor, reply with latest motor speed - // runs in background thread - void thread_main(); - - // returns true if communicating with the motor - bool motor_healthy(); - - // 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); - - // report changes in error codes to user - void report_error_codes(); - - // clear motor errors - void clear_motor_error() { _motor_clear_error = true; } - - // get latest battery status info. returns true on success and populates arguments - bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED; - bool get_batt_capacity_Ah(uint16_t &_hours) const; - - static const struct AP_Param::GroupInfo var_info[]; - -private: - - // message addresses - enum class MsgAddress : uint8_t { - BUS_MASTER = 0x00, - REMOTE1 = 0x14, - DISPLAY = 0x20, - MOTOR = 0x30, - BATTERY = 0x80 - }; - - // Remote specific message ids - enum class RemoteMsgId : uint8_t { - INFO = 0x00, - REMOTE = 0x01, - SETUP = 0x02 - }; - - // Display specific message ids - enum class DisplayMsgId : uint8_t { - INFO = 0x00, - SYSTEM_STATE = 0x41, - SYSTEM_SETUP = 0x42 - }; - - // Motor specific message ids - enum class MotorMsgId : uint8_t { - INFO = 0x00, - STATUS = 0x01, - PARAM = 0x03, - CONFIG = 0x04, - DRIVE = 0x82 - }; - - // Battery specific message ids - enum class BatteryMsgId : uint8_t { - INFO = 0x01, - STATUS = 0x04 - }; - - enum class ParseState { - WAITING_FOR_HEADER = 0, - WAITING_FOR_FOOTER, - }; - // TYPE parameter values enum class ConnectionType : uint8_t { TYPE_DISABLED = 0, @@ -140,320 +55,51 @@ class AP_Torqeedo : public AP_ESC_Telem_Backend { }; // OPTIONS parameter values - enum options { + enum class options { LOG = 1<<0, DEBUG_TO_GCS = 1<<1, }; - // initialise serial port and gpio pins (run from background thread) - // returns true on success - bool init_internals(); + // initialise driver + void init(); - // returns true if the driver is enabled + // returns true if at least one backend has been configured (e.g. TYPE param has been set) bool enabled() const; + bool enabled(uint8_t instance) const; - // process a single byte received on serial port - // return true if a complete message has been received (the message will be held in _received_buff) - bool parse_byte(uint8_t b); - - // process message held in _received_buff - void parse_message(); - - // returns true if it is safe to send a message - bool safe_to_send() const { return ((_send_delay_us == 0) && (_reply_wait_start_us == 0)); } - - // set pin to enable sending a message - void send_start(); - - // check for timeout after sending a message and unset pin if required - void check_for_send_end(); - - // calculate delay required to allow message to be completely sent - uint32_t calc_send_delay_us(uint8_t num_bytes); - - // record msgid of message to wait for and set timer for reply timeout handling - void set_expected_reply_msgid(uint8_t msg_id); - - // check for timeout waiting for reply - void check_for_reply_timeout(); - - // mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply - void set_reply_received(); - - // send a message to the motor with the specified message contents - // msg_contents should not include the header, footer or CRC - // returns true on success - bool send_message(const uint8_t msg_contents[], uint8_t num_bytes); - - // add a byte to a message buffer including adding the escape character (0xAE) if necessary - // this should only be used when adding the contents to the buffer, not the header and footer - // num_bytes is updated to the next free byte - bool add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const; - - // send a motor speed command as a value from -1000 to +1000 - // value is taken directly from SRV_Channel unless set_zero_speed is true - // (if set_zero_speed is true then the motor speed is set to zero) - void send_motor_speed_cmd(bool set_zero_speed = false); - - // send request to motor to reply with a particular message - // msg_id can be INFO, STATUS or PARAM - void send_motor_msg_request(MotorMsgId msg_id); - - // send request to battery to reply with a particular message - // msg_id can be STATUS - void send_battery_msg_request(BatteryMsgId msg_id); - - // calculate the limited motor speed that is sent to the motors - // desired_motor_speed argument and returned value are in the range -1000 to 1000 - int16_t calc_motor_speed_limited(int16_t desired_motor_speed); - int16_t get_motor_speed_limited() const { return (int16_t)_motor_speed_limited; } - - // log TRQD message which holds high level status and latest desired motors peed - // force_logging should be true to immediately write log bypassing timing check to avoid spamming - void log_TRQD(bool force_logging); - - // send ESC telemetry - void update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC); + // returns true if all backends are communicating with the motor + bool healthy(); + bool healthy(uint8_t instance); - // set the on/off pin to on momentarily to wake the motor or clear an error state - void press_on_off_button(); - - // parameters - AP_Enum _type; // connector type used (0:disabled, 1:tiller connector, 2: motor connector) - AP_Int8 _pin_onoff; // Pin number connected to Torqeedo's on/off pin. -1 to disable turning motor on/off from autopilot - AP_Int8 _pin_de; // Pin number connected to RS485 to Serial converter's DE pin. -1 to disable sending commands to motor - AP_Int16 _options; // options bitmask - AP_Int8 _motor_power; // motor power (0 ~ 100). only applied when using motor connection - AP_Float _slew_time; // slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. A value of zero disables the limit - AP_Float _dir_delay; // direction change delay. output will remain at zero for this many seconds when transitioning between forward and backwards rotation - AP_Int8 _auto_reset; // whether to auto reset the motor if it goes into an error state (0:disabled, 1:enabled) - AP_Int8 _ext_batt; // whether to use external battery (0:disabled, 1:enabled) - - // members - AP_HAL::UARTDriver *_uart; // serial port to communicate with motor - bool _initialised; // true once driver has been initialised - bool _send_motor_speed; // true if motor speed should be sent at next opportunity - int16_t _motor_speed_desired; // desired motor speed (set from within update method) - uint32_t _last_send_motor_ms; // system time (in millis) last motor speed command was sent (used for health reporting) - bool _motor_clear_error; // true if the motor error should be cleared (sent in "Drive" message) - uint32_t _send_start_us; // system time (in micros) when last message started being sent (used for timing to unset DE pin) - uint32_t _send_delay_us; // delay (in micros) to allow bytes to be sent after which pin can be unset. 0 if not delaying - - // motor speed limit variables - float _motor_speed_limited; // limited desired motor speed. this value is actually sent to the motor - uint32_t _motor_speed_limited_ms; // system time that _motor_speed_limited was last updated - int8_t _dir_limit; // acceptable directions for output to motor (+1 = positive OK, -1 = negative OK, 0 = either positive or negative OK) - uint32_t _motor_speed_zero_ms; // system time that _motor_speed_limited reached zero. 0 if currently not zero - - // health reporting - HAL_Semaphore _last_motor_healthy_sem;// semaphore protecting reading and updating of _last_send_motor_ms and _last_received_motor_ms - uint32_t _last_log_TRQD_ms; // system time (in millis) that TRQD was last logged - - // reset/wake - uint32_t _last_reset_ms; // system time (in millis) since hard reset/wake button was last pressed - - // message parsing members - ParseState _parse_state; // current state of parsing - bool _parse_escape_received; // true if the escape character has been received so we must XOR the next byte - uint32_t _parse_error_count; // total number of parsing errors (for reporting) - uint32_t _parse_success_count; // number of messages successfully parsed (for reporting) - uint8_t _received_buff[TORQEEDO_MESSAGE_LEN_MAX]; // characters received - uint8_t _received_buff_len; // number of characters received - uint32_t _last_received_motor_ms; // system time (in millis) that a motor message was successfully parsed (for health reporting) - - // reply message handling - uint8_t _reply_msgid; // replies expected msgid (reply often does not specify the msgid so we must record it) - uint32_t _reply_wait_start_us; // system time that we started waiting for a reply message - - // Display system state flags - typedef union PACKED { - struct { - uint8_t set_throttle_stop : 1; // 0, warning that user must set throttle to stop before motor can run - uint8_t setup_allowed : 1; // 1, remote is allowed to enter setup mode - uint8_t in_charge : 1; // 2, master is in charging state - uint8_t in_setup : 1; // 3, master is in setup state - uint8_t bank_available : 1; // 4 - uint8_t no_menu : 1; // 5 - uint8_t menu_off : 1; // 6 - uint8_t reserved7 : 1; // 7, unused - uint8_t temp_warning : 1; // 8, motor or battery temp warning - uint8_t batt_charge_valid : 1; // 9, battery charge valid - uint8_t batt_nearly_empty : 1; // 10, battery nearly empty - uint8_t batt_charging : 1; // 11, battery charging - uint8_t gps_searching : 1; // 12, gps searching for satellites - uint8_t gps_speed_valid : 1; // 13, gps speed is valid - uint8_t range_miles_valid : 1; // 14, range (in miles) is valid - uint8_t range_minutes_valid : 1; // 15, range (in minutes) is valid - }; - uint16_t value; - } DisplaySystemStateFlags; - - // Display system state - struct DisplaySystemState { - DisplaySystemStateFlags flags; // flags, see above for individual bit definitions - uint8_t master_state; // deprecated - uint8_t master_error_code; // error code (0=no error) - float motor_voltage; // motor voltage in volts - float motor_current; // motor current in amps - uint16_t motor_power; // motor power in watts - int16_t motor_rpm; // motor speed in rpm - uint8_t motor_pcb_temp; // motor pcb temp in C - uint8_t motor_stator_temp; // motor stator temp in C - uint8_t batt_charge_pct; // battery state of charge (0 to 100%) - float batt_voltage; // battery voltage in volts - float batt_current; // battery current in amps - uint16_t gps_speed; // gps speed in knots * 100 - uint16_t range_miles; // range in nautical miles * 10 - uint16_t range_minutes; // range in minutes (at current speed and current draw) - uint8_t temp_sw; // master PCB temp in C (close to motor power switches) - uint8_t temp_rp; // master PCB temp in C (close to reverse voltage protection) - uint32_t last_update_ms; // system time that system state was last updated - } _display_system_state; - - // Display system setup - struct DisplaySystemSetup { - uint8_t flags; // 0 : battery config valid, all other bits unused - uint8_t motor_type; // motor type (0 or 3:Unknown, 1:Ultralight, 2:Cruise2, 4:Cruise4, 5:Travel503, 6:Travel1003, 7:Cruise10kW) - uint16_t motor_sw_version; // motor software version - uint16_t batt_capacity; // battery capacity in amp hours - uint8_t batt_charge_pct; // battery state of charge (0 to 100%) - uint8_t batt_type; // battery type (0:lead acid, 1:Lithium) - uint16_t master_sw_version; // master software version - } _display_system_setup; + // 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); - // Motor status - struct MotorStatus { - union PACKED { - struct { - uint8_t temp_limit_motor : 1; // 0, motor speed limited due to motor temp - uint8_t temp_limit_pcb : 1; // 1, motor speed limited tue to PCB temp - uint8_t emergency_stop : 1; // 2, motor in emergency stop (must be cleared by master) - uint8_t running : 1; // 3, motor running - uint8_t power_limit : 1; // 4, motor power limited - uint8_t low_voltage_limit : 1; // 5, motor speed limited because of low voltage - uint8_t tilt : 1; // 6, motor is tilted - uint8_t reserved7 : 1; // 7, unused (always zero) - } status_flags; - uint8_t status_flags_value; - }; - union PACKED { - struct { - uint8_t overcurrent : 1; // 0, motor stopped because of overcurrent - uint8_t blocked : 1; // 1, motor stopped because it is blocked - uint8_t overvoltage_static : 1; // 2, motor stopped because voltage too high - uint8_t undervoltage_static : 1; // 3, motor stopped because voltage too low - uint8_t overvoltage_current : 1; // 4, motor stopped because voltage spiked high - uint8_t undervoltage_current: 1; // 5, motor stopped because voltage spiked low - uint8_t overtemp_motor : 1; // 6, motor stopped because stator temp too high - uint8_t overtemp_pcb : 1; // 7, motor stopped because pcb temp too high - uint8_t timeout_rs485 : 1; // 8, motor stopped because Drive message not received for too long - uint8_t temp_sensor_error : 1; // 9, motor temp sensor is defective (motor will not stop) - uint8_t tilt : 1; // 10, motor stopped because it was tilted - uint8_t unused11to15 : 5; // 11 ~ 15 (always zero) - } error_flags; - uint16_t error_flags_value; - }; - } _motor_status; - uint32_t _last_send_motor_status_request_ms; // system time (in milliseconds) that last motor status request was sent + // clear motor errors + void clear_motor_error(); - // Motor params - struct MotorParam { - int16_t rpm; // motor rpm - uint16_t power; // motor power consumption in Watts - float voltage; // motor voltage in volts - float current; // motor current in amps - float pcb_temp; // pcb temp in C - float stator_temp; // stator temp in C - uint32_t last_update_ms;// system time that above values were updated - } _motor_param; - uint32_t _last_send_motor_param_request_ms; // system time (in milliseconds) that last motor param request was sent + // get latest battery status info. returns true on success and populates arguments + // instance is normally 0 or 1, if invalid instances are provided the first instance is used + bool get_batt_info(uint8_t instance, float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED; + bool get_batt_capacity_Ah(uint8_t instance, uint16_t &_hours) const; - // Battery Status Flags - typedef union PACKED { - struct { - uint8_t discharge_channel : 1; // 0, discharge channel active - uint8_t charge_channel : 1; // 1, charge channel active - uint8_t ddch : 1; // 2, deep discharge - uint8_t eod : 1; // 3, end of discharge - uint8_t hi_stack : 1; // 4, battery on high side of serial connection - }; - uint16_t value; - } BatteryStatusFlags; + // parameter var table + static const struct AP_Param::GroupInfo var_info[]; - // Battery Warning Flags - typedef union PACKED { - struct { - uint8_t warn_batt_overcurrent : 1; // 0, discharge current too high - uint8_t warn_batt_overcomplicate : 1; // 1, cell temp too high - uint8_t warn_overtemp_fet : 1; // 2, pcb/fet temp too high - uint8_t warn_undertemp_cell : 1; // 3, cell temp too low - uint8_t warn_eod : 1; // 4, end of discharge - uint8_t warn_batt_off : 1; // 5, battery nearly empty - uint8_t warn_overcurrent_charge : 1; // 6, charge current too high - uint8_t warn_batt_overtemp_cell : 1; // 7, cell temp too high - uint8_t warn_batt_undertemp_cell : 1; // 8, cell temp too low - uint8_t warn_cells_unbalanced : 1; // 9, single voltage diff too big - }; - uint16_t value; - } BatteryWarningFlags; + // parameters for backends + AP_Torqeedo_Params _params[AP_TORQEEDO_MAX_INSTANCES]; - // Battery Error Flags - typedef union PACKED { - struct { - uint8_t err_batt_discharge_curr : 1; // 0, discharge current too high - uint8_t err_overtemp_cell : 1; // 1, cell temp too high - uint8_t err_overtemp_fet : 1; // 2, pcb/fet temp too high - uint8_t err_undertemp_cell : 1; // 3, cell temp too low - uint8_t err_eod : 1; // 4, end of discharge - uint8_t err_batt_off : 1; // 5, battery nearly empty - uint8_t err_overcurrent : 1; // 6, charge current too high - uint8_t err_overtemp_batt_cell : 1; // 7, cell temp too high - uint8_t err_undertemp_batt_cel : 1; // 8, cell temp too low - uint8_t err_overvoltage : 1; // 9, charge voltage too high - uint8_t err_overcharge : 1; // 10, overcharge - uint8_t err_second_protection : 1; // 11, second level protection was activated - uint8_t err_electronic_err : 1; // 12, general electronic error - uint8_t err_no_pyro_fuse : 1; // 13, pyrofuse connection lost - uint8_t err_leak_current : 1; // 14, water sensor - uint8_t err_ddch : 1; // 15, deep discharge - no charge - }; - uint16_t value; - } BatteryErrorFlags; +private: - // Battery status - struct BatteryStatus { - BatteryStatusFlags status_flags; // battery status flags - BatteryWarningFlags warning_flags; // battery warning flags - BatteryErrorFlags error_flags; // battery error flags - float temp_cell_pack; // max temp within cellpack (C) - float temp_pcb; // max temp on pcb/mosfet (C) - float voltage; // voltage cellpack (V) - float current; // battery current (A) - uint16_t power; // actual power (W) - float capacity; // learned max capacity (Ah) - float capacity_remaining; // remaining capacity (Ah) - uint16_t capacity_pct; // remaining capacity in percent (%) - uint16_t running_time; // remaining capacity in minutes (min) - uint16_t water_detect; // water detection (ADC value, 0=wet) - uint32_t last_update_ms; // system time that above values were updated - } _battery_status; - uint32_t _last_send_battery_status_request_ms; // system time (in milliseconds) that last battery status request was sent + // return pointer to backend given an instance number + AP_Torqeedo_Backend *get_instance(uint8_t instance) const; - // error reporting - DisplaySystemStateFlags _display_system_state_flags_prev; // backup of display system state flags - uint8_t _display_system_state_master_error_code_prev; // backup of display system state master_error_code - uint32_t _last_error_report_ms; // system time that flag changes were last reported (used to prevent spamming user) - MotorStatus _motor_status_prev; // backup of motor status static AP_Torqeedo *_singleton; - - // 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; + AP_Torqeedo_Backend *_backends[AP_TORQEEDO_MAX_INSTANCES]; // pointers to instantiated backends }; namespace AP { AP_Torqeedo *torqeedo(); }; -#endif // HAL_TORQEEDO_ENABLED +#endif // HAL_TORQEEDO_ENABLED \ No newline at end of file diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp new file mode 100644 index 00000000000000..243f7cab23e8bf --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp @@ -0,0 +1,31 @@ +/* + 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_Torqeedo_Backend.h" + +#if HAL_TORQEEDO_ENABLED + +#include +#include + +extern const AP_HAL::HAL& hal; + +// constructor +AP_Torqeedo_Backend::AP_Torqeedo_Backend(AP_Torqeedo_Params ¶ms, uint8_t instance) : + _params(params), + _instance(instance) +{} + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h new file mode 100644 index 00000000000000..fd56d0612aa91b --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h @@ -0,0 +1,84 @@ +/* + 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 . + */ + +/* + This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol + which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW + + The autopilot should be connected either to the battery's tiller connector or directly to the motor + as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html + TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. + + Tiller connection: Autopilot <-> Battery (master) <-> Motor + Motor connection: Autopilot (master) <-> Motor + + Communication between the components is always initiated by the master with replies sent within 25ms + + Example "Remote (0x01)" reply message to allow tiller to control motor speed + Byte Field Definition Example Value Comments + --------------------------------------------------------------------------------- + byte 0 Header 0xAC + byte 1 TargetAddress 0x00 see MsgAddress enum + byte 2 Message ID 0x00 only master populates this. replies have this set to zero + byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid + byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 + byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) + byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) + byte 7 CRC-Maxim ---- CRC-Maxim value + byte 8 Footer 0xAD + + More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. + */ + +#pragma once + +#include "AP_Torqeedo_config.h" + +#if HAL_TORQEEDO_ENABLED + +#include "AP_Torqeedo.h" +#include + +class AP_Torqeedo_Backend : public AP_ESC_Telem_Backend { +public: + AP_Torqeedo_Backend(AP_Torqeedo_Params ¶ms, uint8_t instance); + + // do not allow copies + CLASS_NO_COPY(AP_Torqeedo_Backend); + + // initialise driver + virtual void init() = 0; + + // returns true if communicating with the motor + virtual bool healthy() = 0; + + // clear motor errors + virtual void clear_motor_error() = 0; + + // get latest battery status info. returns true on success and populates arguments + virtual bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED = 0; + virtual bool get_batt_capacity_Ah(uint16_t &_hours) const = 0; + + protected: + + // parameter helper functions + AP_Torqeedo::ConnectionType get_type() const { return (AP_Torqeedo::ConnectionType)_params.type.get(); } + bool option_enabled(AP_Torqeedo::options opt) const { return ((uint16_t)_params.options.get() & (uint16_t)opt) != 0; } + + AP_Torqeedo_Params &_params; // parameters for this backend + uint8_t _instance; // this instance's number +}; + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp new file mode 100644 index 00000000000000..2ded30ca844a3d --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp @@ -0,0 +1,79 @@ +#include "AP_Torqeedo_Params.h" +#include + +// table of user settable parameters +const AP_Param::GroupInfo AP_Torqeedo_Params::var_info[] = { + + // @Param: TYPE + // @DisplayName: Torqeedo connection type + // @Description: Torqeedo connection type + // @Values: 0:Disabled, 1:Tiller, 2:Motor + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO_FLAGS("TYPE", 1, AP_Torqeedo_Params, type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: ONOFF_PIN + // @DisplayName: Torqeedo ON/Off pin + // @Description: Pin number connected to Torqeedo's on/off pin. -1 to use serial port's RTS pin if available + // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("ONOFF_PIN", 2, AP_Torqeedo_Params, pin_onoff, -1), + + // @Param: DE_PIN + // @DisplayName: Torqeedo DE pin + // @Description: Pin number connected to RS485 to Serial converter's DE pin. -1 to use serial port's CTS pin if available + // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("DE_PIN", 3, AP_Torqeedo_Params, pin_de, -1), + + // @Param: OPTIONS + // @DisplayName: Torqeedo Options + // @Description: Torqeedo Options Bitmask + // @Bitmask: 0:Log,1:Send debug to GCS + // @User: Advanced + AP_GROUPINFO("OPTIONS", 4, AP_Torqeedo_Params, options, 1), + + // @Param: POWER + // @DisplayName: Torqeedo Motor Power + // @Description: Torqeedo motor power. Only applied when using motor connection type (e.g. TRQD_TYPE=2) + // @Units: % + // @Range: 0 100 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("POWER", 5, AP_Torqeedo_Params, motor_power, 100), + + // @Param: SLEW_TIME + // @DisplayName: Torqeedo Throttle Slew Time + // @Description: Torqeedo slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. Higher values cause a slower response, lower values cause a faster response. A value of zero disables the limit + // @Units: s + // @Range: 0 5 + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("SLEW_TIME", 6, AP_Torqeedo_Params, slew_time, 2.0), + + // @Param: DIR_DELAY + // @DisplayName: Torqeedo Direction Change Delay + // @Description: Torqeedo direction change delay. Output will remain at zero for this many seconds when transitioning between forward and backwards rotation + // @Units: s + // @Range: 0 5 + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("DIR_DELAY", 7, AP_Torqeedo_Params, dir_delay, 1.0), + + // @Param: SERVO_FN + // @DisplayName: Torqeedo Servo Output Function + // @Description: Torqeedo Servo Output Function + // @Values: 70:Throttle,73:ThrottleLeft,74:ThrottleRight + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("SERVO_FN", 8, AP_Torqeedo_Params, servo_fn, (int16_t)SRV_Channel::k_throttle), + + AP_GROUPEND +}; + +AP_Torqeedo_Params::AP_Torqeedo_Params(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Params.h b/libraries/AP_Torqeedo/AP_Torqeedo_Params.h new file mode 100644 index 00000000000000..ffbee81491c6c2 --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Params.h @@ -0,0 +1,26 @@ +#pragma once + +#include +#include + +class AP_Torqeedo_Params { +public: + static const struct AP_Param::GroupInfo var_info[]; + + AP_Torqeedo_Params(void); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Torqeedo_Params); + + // parameters + AP_Int8 type; // connector type used (0:disabled, 1:tiller connector, 2:motor connector) + AP_Int8 pin_onoff; // Pin number connected to Torqeedo's on/off pin. -1 to disable turning motor on/off from autopilot + AP_Int8 pin_de; // Pin number connected to RS485 to Serial converter's DE pin. -1 to disable sending commands to motor + AP_Int16 options; // options bitmask + AP_Int8 motor_power; // motor power (0 ~ 100). only applied when using motor connection + AP_Float slew_time; // slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. A value of zero disables the limit + AP_Float dir_delay; // direction change delay. output will remain at zero for this many seconds when transitioning between forward and backwards rotation + AP_Int16 servo_fn; // servo output function number + AP_Int8 _auto_reset; // whether to auto reset the motor if it goes into an error state (0:disabled, 1:enabled) + AP_Int8 _ext_batt; // whether to use external battery (0:disabled, 1:enabled) +}; diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp new file mode 100644 index 00000000000000..a96ac825c620ab --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp @@ -0,0 +1,1287 @@ +/* + 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_Torqeedo_TQBus.h" + +#if HAL_TORQEEDO_ENABLED + +#include +#include +#include +#include +#include +#include +#include + +#define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200 +#define TORQEEDO_PACKET_HEADER 0xAC // communication packet header +#define TORQEEDO_PACKET_FOOTER 0xAD // communication packet footer +#define TORQEEDO_PACKET_ESCAPE 0xAE // escape character for handling occurrences of header, footer and this escape bytes in original message +#define TORQEEDO_PACKET_ESCAPE_MASK 0x80 // byte after ESCAPE character should be XOR'd with this value +#define TORQEEDO_LOG_TRQD_INTERVAL_MS 5000// log TRQD message at this interval in milliseconds +#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS 100 // motor speed sent at 10hz if connected to motor +#define TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS 400 // motor status requested every 0.4sec if connected to motor +#define TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS 400 // motor param requested every 0.4sec if connected to motor +#define TORQEEDO_SEND_BATTERY_STATUS_REQUEST_INTERVAL_MS 400 // battery status requested every 0.4sec +#define TORQEEDO_BATT_TIMEOUT_MS 5000 // battery info timeouts after 5 seconds +#define TORQEEDO_REPLY_TIMEOUT_MS 25 // stop waiting for replies after 25ms +#define TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS 10000 // errors reported to user at no less than once every 10 seconds +#define TORQEEDO_MIN_RESET_INTERVAL_MS 5000 // minimum time between hard resets/wake +#define TORQEEDO_RESET_THROTTLE_HOLDDOWN_MS 6000 // throttle hold down time after reset/wake + +extern const AP_HAL::HAL& hal; + +// initialise driver +void AP_Torqeedo_TQBus::init() +{ + // only init once + // Note: a race condition exists here if init is called multiple times quickly before thread_main has a chance to set _initialise + if (_initialised) { + return; + } + + // create background thread to process serial input and output + char thread_name[15]; + hal.util->snprintf(thread_name, sizeof(thread_name), "torqeedo%u", (unsigned)_instance); + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Torqeedo_TQBus::thread_main, void), thread_name, 2048, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { + return; + } +} + +// returns true if communicating with the motor +bool AP_Torqeedo_TQBus::healthy() +{ + if (!_initialised) { + return false; + } + { + // healthy if both receive and send have occurred in the last 3 seconds + WITH_SEMAPHORE(_last_healthy_sem); + const uint32_t now_ms = AP_HAL::millis(); + return ((now_ms - _last_received_ms < 3000) && (now_ms - _last_send_motor_ms < 3000)); + } +} + +// initialise serial port and gpio pins (run from background thread) +bool AP_Torqeedo_TQBus::init_internals() +{ + // find serial driver and initialise + const AP_SerialManager &serial_manager = AP::serialmanager(); + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Torqeedo, _instance); + if (_uart == nullptr) { + return false; + } + _uart->begin(TORQEEDO_SERIAL_BAUD); + _uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); + _uart->set_unbuffered_writes(true); + + // if using tiller connection set on/off pin for 0.5 sec to turn on battery + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) { + if (_params.pin_onoff > -1) { + hal.gpio->pinMode(_params.pin_onoff, HAL_GPIO_OUTPUT); + hal.gpio->write(_params.pin_onoff, 1); + hal.scheduler->delay(500); + hal.gpio->write(_params.pin_onoff, 0); + } else { + // use serial port's RTS pin to turn on battery + _uart->set_RTS_pin(true); + hal.scheduler->delay(500); + _uart->set_RTS_pin(false); + } + } + + // initialise RS485 DE pin (when high, allows send to motor) + if (_params.pin_de > -1) { + hal.gpio->pinMode(_params.pin_de, HAL_GPIO_OUTPUT); + hal.gpio->write(_params.pin_de, 0); + } else { + _uart->set_CTS_pin(false); + } + + return true; +} + +// consume incoming messages from motor, reply with latest motor speed +// runs in background thread +void AP_Torqeedo_TQBus::thread_main() +{ + // initialisation + if (!init_internals()) { + return; + } + _initialised = true; + + while (true) { + // 100 microsecond loop delay + hal.scheduler->delay_microseconds(100); + + // check if transmit pin should be unset + check_for_send_end(); + + // check for timeout waiting for reply + check_for_reply_timeout(); + + // parse incoming characters + uint32_t nbytes = MIN(_uart->available(), 1024U); + while (nbytes-- > 0) { + int16_t b = _uart->read(); + if (b >= 0 ) { + if (parse_byte((uint8_t)b)) { + // complete message received, parse it! + parse_message(); + // clear wait-for-reply because if we are waiting for a reply, this message must be it + set_reply_received(); + } + } + } + + // send motor speed + bool log_update = false; + if (safe_to_send()) { + uint32_t now_ms = AP_HAL::millis(); + + // if connected to motor + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) { + if (now_ms - _last_send_motor_ms > TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS) { + // send motor speed every 0.1sec + _send_motor_speed = true; + } else if (now_ms - _last_send_motor_status_request_ms > TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS) { + // send request for motor status + send_motor_msg_request(MotorMsgId::STATUS); + _last_send_motor_status_request_ms = now_ms; + } else if (now_ms - _last_send_motor_param_request_ms > TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS) { + // send request for motor params + send_motor_msg_request(MotorMsgId::PARAM); + _last_send_motor_param_request_ms = now_ms; + } + } + + // send motor speed + if (_send_motor_speed) { + // If no soft faults and not in hold-down period, set throttle + if ((now_ms - _last_reset_ms > TORQEEDO_RESET_THROTTLE_HOLDDOWN_MS) && + !(_display_system_state.flags.set_throttle_stop || _display_system_state.flags.temp_warning) && + !(_display_system_state.master_error_code > 0 && _display_system_state.master_error_code != 132)) { + send_motor_speed_cmd(); + } + else + // set throttle=0 after a reset for the hold-down period + // or if the motor is in a fault state that requires the throttle to be set to 0 + send_motor_speed_cmd(true); + + _send_motor_speed = false; + log_update = true; + } + // if not sending motor speed, send battery status request (if connected to external battery) + else if (_type == ConnectionType::TYPE_TILLER && _ext_batt) { + // send request for battery status + if (now_ms - _last_send_battery_status_request_ms > TORQEEDO_SEND_BATTERY_STATUS_REQUEST_INTERVAL_MS) { + send_battery_msg_request(BatteryMsgId::STATUS); + _last_send_battery_status_request_ms = now_ms; + } + } + } + + // if motor is not healthy and auto reset is enabled, + // toggle the on/off pin to try to hard wake or reset the motor + if (!motor_healthy() && _auto_reset) { + const uint32_t now_ms = AP_HAL::millis(); + // only reset if not reset recently (to avoid infinite reset loop) + if ((now_ms - _last_reset_ms > TORQEEDO_MIN_RESET_INTERVAL_MS)) { + press_on_off_button(); + _last_reset_ms = now_ms; + } + } + + // log high level status and motor speed + log_TRQD(log_update); + } +} + +// 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_TQBus::map_master_error_code_to_string(uint8_t code) const +{ + switch (code) { + case 2: + return "stator high temp"; + case 5: + return "propeller blocked"; + case 6: + return "motor low voltage"; + case 7: + return "motor high current"; + case 8: + return "pcb temp high"; + case 21: + return "tiller cal bad"; + case 22: + return "mag bad"; + case 23: + return "range incorrect"; + case 30: + return "motor comm error"; + case 32: + return "tiller comm error"; + case 33: + return "general comm error"; + case 34: + return "kill switch activated"; + case 41: + case 42: + return "charge voltage bad"; + case 43: + return "battery flat"; + case 45: + return "battery high current"; + case 46: + return "battery temp error"; + case 48: + return "charging temp error"; + case 70: + return "battery over/under temp during charge"; + case 71: + return "battery over/under temp during discharge"; + case 72: + return "battery FET overtemp"; + case 73: + return "battery overcurrent during discharge"; + case 74: + return "battery overcurrent during charge"; + case 75: + return "battery activating pyro switch"; + case 76: + return "battery undervoltage"; + case 77: + return "battery overvoltage during charging"; + case 78: + return "battery overcharge"; + case 79: + return "battery electronic fault"; + case 80: + return "battery deep discharging"; + case 81: + return "battery water sensor triggered"; + case 82: + return "charge imbalance between batteries"; + case 83: + return "battery software version error"; + case 84: + return "battery count does not match enumeration"; + case 85: + return "battery cell imbalance"; + } + + return nullptr; +} + +// report changes in error codes to user +void AP_Torqeedo_TQBus::report_error_codes() +{ + // skip reporting if we have already reported status very recently + const uint32_t now_ms = AP_HAL::millis(); + + // skip reporting if no changes in flags and already reported within 10 seconds + const bool flags_changed = (_display_system_state_flags_prev.value != _display_system_state.flags.value) || + (_display_system_state_master_error_code_prev != _display_system_state.master_error_code) || + (_motor_status_prev.status_flags_value != _motor_status.status_flags_value) || + (_motor_status_prev.error_flags_value != _motor_status.error_flags_value); + if (!flags_changed && ((now_ms - _last_error_report_ms) < TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS)) { + return; + } + + // report display system errors + const char* msg_prefix = "Torqeedo:"; + (void)msg_prefix; // sometimes unused when HAL_GCS_ENABLED is false + if (_display_system_state.flags.set_throttle_stop) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); + } + if (_display_system_state.flags.temp_warning) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); + } + if (_display_system_state.flags.batt_nearly_empty) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix); + } + if (_display_system_state.master_error_code > 0 && _display_system_state.master_error_code != 132) { + const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); + if (error_string != nullptr) { + GCS_SEND_TEXT( + MAV_SEVERITY_CRITICAL, "%s err:%u %s", + msg_prefix, + _display_system_state.master_error_code, + error_string); + } else { + GCS_SEND_TEXT( + MAV_SEVERITY_CRITICAL, "%s err:%u", + msg_prefix, + _display_system_state.master_error_code); + } + } + + // report motor status errors + if (_motor_status.error_flags.overcurrent) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix); + } + if (_motor_status.error_flags.blocked) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix); + } + if (_motor_status.error_flags.overvoltage_static || _motor_status.error_flags.overvoltage_current) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix); + } + if (_motor_status.error_flags.undervoltage_static || _motor_status.error_flags.undervoltage_current) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix); + } + if (_motor_status.error_flags.overtemp_motor || _motor_status.error_flags.overtemp_pcb) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); + } + if (_motor_status.error_flags.timeout_rs485) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix); + } + if (_motor_status.error_flags.temp_sensor_error) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix); + } + if (_motor_status.error_flags.tilt) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix); + } + + // display OK if all errors cleared + const bool prev_errored = (_display_system_state_flags_prev.value != 0) || + (_display_system_state_master_error_code_prev != 0) || + (_motor_status_prev.error_flags_value != 0); + + const bool now_errored = (_display_system_state.flags.value != 0) || + (_display_system_state.master_error_code != 0) || + (_motor_status.error_flags_value != 0); + + if (!now_errored && prev_errored) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix); + } + + // record change in state and reporting time + _display_system_state_flags_prev.value = _display_system_state.flags.value; + _display_system_state_master_error_code_prev = _display_system_state.master_error_code; + _motor_status_prev = _motor_status; + _last_error_report_ms = now_ms; +} + +// get latest battery status info. returns true on success and populates arguments +bool AP_Torqeedo_TQBus::get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const +{ + + if (_ext_batt) { + // always use external battery info if selected + if ((AP_HAL::millis() - _battery_status.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { + voltage = _battery_status.voltage; + current_amps = _battery_status.current; + temp_C = _battery_status.temp_cell_pack; + pct_remaining = static_cast(_battery_status.capacity_pct); + return true; + } + } + + // use battery info from display_system_state if available (tiller connection) + if ((AP_HAL::millis() - _display_system_state.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { + voltage = _display_system_state.batt_voltage; + current_amps = _display_system_state.batt_current; + temp_C = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); + pct_remaining = _display_system_state.batt_charge_pct; + return true; + } + + // use battery info from motor_param if available (motor connection) + if ((AP_HAL::millis() - _motor_param.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { + voltage = _motor_param.voltage; + current_amps = _motor_param.current; + temp_C = MAX(_motor_param.pcb_temp, _motor_param.stator_temp); + pct_remaining = 0; // motor does not know percent remaining + return true; + } + + return false; +} + +// get battery capacity. returns true on success and populates argument +bool AP_Torqeedo_TQBus::get_batt_capacity_Ah(uint16_t &_hours) const +{ + if (_ext_batt) { + if (_battery_status.capacity <= 0.0) { + return false; + } + amp_hours = static_cast(_battery_status.capacity); + return true; + } + + if (_display_system_setup.batt_capacity == 0) { + return false; + } + amp_hours = _display_system_setup.batt_capacity; + return true; +} + +// process a single byte received on serial port +// return true if a complete message has been received (the message will be held in _received_buff) +bool AP_Torqeedo_TQBus::parse_byte(uint8_t b) +{ + bool complete_msg_received = false; + + switch (_parse_state) { + case ParseState::WAITING_FOR_HEADER: + if (b == TORQEEDO_PACKET_HEADER) { + _parse_state = ParseState::WAITING_FOR_FOOTER; + } + _received_buff_len = 0; + _parse_escape_received = false; + break; + case ParseState::WAITING_FOR_FOOTER: + if (b == TORQEEDO_PACKET_FOOTER) { + _parse_state = ParseState::WAITING_FOR_HEADER; + + // check message length + if (_received_buff_len == 0) { + _parse_error_count++; + break; + } + + // check crc + const uint8_t crc_expected = crc8_maxim(_received_buff, _received_buff_len-1); + if (_received_buff[_received_buff_len-1] != crc_expected) { + _parse_error_count++; + break; + } + _parse_success_count++; + { + // record time of successful receive for health reporting + WITH_SEMAPHORE(_last_healthy_sem); + _last_received_ms = AP_HAL::millis(); + } + complete_msg_received = true; + } else { + // escape character handling + if (_parse_escape_received) { + b ^= TORQEEDO_PACKET_ESCAPE_MASK; + _parse_escape_received = false; + } else if (b == TORQEEDO_PACKET_ESCAPE) { + // escape character received, record this and ignore this byte + _parse_escape_received = true; + break; + } + // add to buffer + _received_buff[_received_buff_len] = b; + _received_buff_len++; + if (_received_buff_len > TORQEEDO_MESSAGE_LEN_MAX) { + // message too long + _parse_state = ParseState::WAITING_FOR_HEADER; + _parse_error_count++; + } + } + break; + } + + return complete_msg_received; +} + +// process message held in _received_buff +void AP_Torqeedo_TQBus::parse_message() +{ + // message address (i.e. target of message) + const MsgAddress msg_addr = (MsgAddress)_received_buff[0]; + + // handle messages sent to "remote" (aka tiller) + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::REMOTE1)) { + RemoteMsgId msg_id = (RemoteMsgId)_received_buff[1]; + if (msg_id == RemoteMsgId::REMOTE) { + // request received to send updated motor speed + _send_motor_speed = true; + } + return; + } + + // handle messages sent to Display + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::DISPLAY)) { + DisplayMsgId msg_id = (DisplayMsgId)_received_buff[1]; + switch (msg_id) { + case DisplayMsgId::SYSTEM_STATE : + if (_received_buff_len == 30) { + // fill in _display_system_state + _display_system_state.flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); + _display_system_state.master_state = _received_buff[4]; // deprecated + _display_system_state.master_error_code = _received_buff[5]; + _display_system_state.motor_voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; + _display_system_state.motor_current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; + _display_system_state.motor_power = UINT16_VALUE(_received_buff[10], _received_buff[11]); + _display_system_state.motor_rpm = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]); + _display_system_state.motor_pcb_temp = _received_buff[14]; + _display_system_state.motor_stator_temp = _received_buff[15]; + _display_system_state.batt_charge_pct = _received_buff[16]; + _display_system_state.batt_voltage = UINT16_VALUE(_received_buff[17], _received_buff[18]) * 0.01; + _display_system_state.batt_current = UINT16_VALUE(_received_buff[19], _received_buff[20]) * 0.1; + _display_system_state.gps_speed = UINT16_VALUE(_received_buff[21], _received_buff[22]); + _display_system_state.range_miles = UINT16_VALUE(_received_buff[23], _received_buff[24]); + _display_system_state.range_minutes = UINT16_VALUE(_received_buff[25], _received_buff[26]); + _display_system_state.temp_sw = _received_buff[27]; + _display_system_state.temp_rp = _received_buff[28]; + _display_system_state.last_update_ms = AP_HAL::millis(); + + // update esc telem sent to ground station + const uint8_t esc_temp = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); + const uint8_t motor_temp = MAX(_display_system_state.motor_pcb_temp, _display_system_state.motor_stator_temp); + update_esc_telem(_display_system_state.motor_rpm, + _display_system_state.motor_voltage, + _display_system_state.motor_current, + esc_temp, + motor_temp); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRST + // @Description: Torqeedo System State + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: F: Flags bitmask + // @Field: Err: Master error code + // @Field: MVolt: Motor voltage + // @Field: MCur: Motor current + // @Field: Pow: Motor power + // @Field: RPM: Motor RPM + // @Field: MTemp: Motor Temp (higher of pcb or stator) + // @Field: BPct: Battery charge percentage + // @Field: BVolt: Battery voltage + // @Field: BCur: Battery current + AP::logger().Write("TRST", "TimeUS,I,F,Err,MVolt,MCur,Pow,RPM,MTemp,BPct,BVolt,BCur", + "s#--vAWqO%vA", // units + "F---00000000", // multipliers + "QBHBffHhBBff", // formats + AP_HAL::micros64(), + _instance, + _display_system_state.flags.value, + _display_system_state.master_error_code, + _display_system_state.motor_voltage, + _display_system_state.motor_current, + _display_system_state.motor_power, + _display_system_state.motor_rpm, + motor_temp, + _display_system_state.batt_charge_pct, + _display_system_state.batt_voltage, + _display_system_state.batt_current); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRST i:%u, F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f", + (unsigned)_instance, + (unsigned)_display_system_state.flags.value, + (unsigned)_display_system_state.master_error_code, + (double)_display_system_state.motor_voltage, + (double)_display_system_state.motor_current, + (unsigned)_display_system_state.motor_power, + (int)motor_temp, + (unsigned)_display_system_state.batt_charge_pct, + (double)_display_system_state.batt_voltage, + (double)_display_system_state.batt_current); + } + + // report any errors + report_error_codes(); + } else { + // unexpected length + _parse_error_count++; + } + break; + case DisplayMsgId::SYSTEM_SETUP: + if (_received_buff_len == 13) { + // fill in display system setup + _display_system_setup.flags = _received_buff[2]; + _display_system_setup.motor_type = _received_buff[3]; + _display_system_setup.motor_sw_version = UINT16_VALUE(_received_buff[4], _received_buff[5]); + _display_system_setup.batt_capacity = UINT16_VALUE(_received_buff[6], _received_buff[7]); + _display_system_setup.batt_charge_pct = _received_buff[8]; + _display_system_setup.batt_type = _received_buff[9]; + _display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRSE + // @Description: Torqeedo System Setup + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: Flag: Flags + // @Field: MotType: Motor type + // @Field: MotVer: Motor software version + // @Field: BattCap: Battery capacity + // @Field: BattPct: Battery charge percentage + // @Field: BattType: Battery type + // @Field: SwVer: Master software version + AP::logger().Write("TRSE", "TimeUS,I,Flag,MotType,MotVer,BattCap,BattPct,BattType,SwVer", + "s#---a%--", // units + "F----00--", // multipliers + "QBBBHHBBH", // formats + AP_HAL::micros64(), + _instance, + _display_system_setup.flags, + _display_system_setup.motor_type, + _display_system_setup.motor_sw_version, + _display_system_setup.batt_capacity, + _display_system_setup.batt_charge_pct, + _display_system_setup.batt_type, + _display_system_setup.master_sw_version); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRSE i:%u v:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%", + (unsigned)_instance, + (unsigned)_display_system_setup.master_sw_version, + (unsigned)_display_system_setup.flags, + (unsigned)_display_system_setup.motor_type, + (unsigned)_display_system_setup.motor_sw_version, + (unsigned)_display_system_setup.batt_type, + (unsigned)_display_system_setup.batt_capacity, + (unsigned)_display_system_setup.batt_charge_pct); + } + } else { + // unexpected length + _parse_error_count++; + } + break; + default: + // ignore message + break; + } + return; + } + + // handle reply from battery + // For now, only process battery messages if in tiller type mode to avoid changing + // code for motor type mode. This is because both reply to the bus master. + if ((_type == AP_Torqeedo::ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::BUS_MASTER)) { + // replies strangely do not return the msgid so we must have stored it + BatteryMsgId msg_id = (BatteryMsgId)_reply_msgid; + switch (msg_id) { + case BatteryMsgId::STATUS: + if (_received_buff_len == 29) { + _battery_status.status_flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); + _battery_status.warning_flags.value = UINT16_VALUE(_received_buff[4], _received_buff[5]); + _battery_status.error_flags.value = UINT16_VALUE(_received_buff[6], _received_buff[7]); + _battery_status.temp_cell_pack = (float)((int16_t)UINT16_VALUE(_received_buff[8], _received_buff[9])) * 0.1; + _battery_status.temp_pcb = (float)((int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11])) * 0.1; + _battery_status.voltage = (float)(UINT16_VALUE(_received_buff[12], _received_buff[13])) * 0.1; + _battery_status.current = -1.0 * (float)((int16_t)UINT16_VALUE(_received_buff[14], _received_buff[15])) * 0.1; + _battery_status.power = UINT16_VALUE(_received_buff[16], _received_buff[17]); + _battery_status.capacity = (float)(UINT16_VALUE(_received_buff[18], _received_buff[19])) * 0.1; + _battery_status.capacity_remaining = (float)(UINT16_VALUE(_received_buff[20], _received_buff[21])) * 0.1; + _battery_status.capacity_pct = UINT16_VALUE(_received_buff[22], _received_buff[23]); + _battery_status.running_time = UINT16_VALUE(_received_buff[24], _received_buff[25]); + _battery_status.water_detect = UINT16_VALUE(_received_buff[26], _received_buff[27]); + _battery_status.last_update_ms = AP_HAL::millis(); + +#if HAL_LOGGING_ENABLED + + // log data + if ((_options & options::LOG) != 0) { + // @LoggerMessage: TRBS + // @Description: Torqeedo Battery Status + // @Field: TimeUS: Time since system startup + // @Field: State: Battery status flags + // @Field: Warn: Battery warning flags + // @Field: Err: Battery error flags + // @Field: CTemp: Cell pack temp + // @Field: PTemp: PCB temp + // @Field: Volt: Battery voltage + // @Field: Cur: Battery current + // @Field: Pow: Battery power + // @Field: Cap: Battery capacity + // @Field: CapPct: Battery capacity percentage + // @Field: CapRem: Battery capacity remaining + // @Field: Water: Water detect + AP::logger().Write("TRBS", "TimeUS,State,Warn,Err,CTemp,PTemp,Volt,Cur,Pow,Cap,CapPct,CapRem,Water", "QHHHffffHfHfH", + AP_HAL::micros64(), + _battery_status.status_flags.value, + _battery_status.warning_flags.value, + _battery_status.error_flags.value, + _battery_status.temp_cell_pack, + _battery_status.temp_pcb, + _battery_status.voltage, + _battery_status.current, + _battery_status.power, + _battery_status.capacity, + _battery_status.capacity_pct, + _battery_status.capacity_remaining, + _battery_status.water_detect); + } + +#endif + + // send to GCS + if ((_options & options::DEBUG_TO_GCS) != 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRBS S:%d W:%d E:%d V:%4.1f C:%4.1f P:%u Cap:%4.0f Rem:%u", + _battery_status.status_flags.value, + _battery_status.warning_flags.value, + _battery_status.error_flags.value, + (double)_battery_status.voltage, + (double)_battery_status.current, + (unsigned)_battery_status.power, + (double)_battery_status.capacity, + (unsigned)_battery_status.capacity_pct); + } + } + else { + // unexpected length + // _parse_error_count++; + // Lots of messages come addressed to the bus master, so we don't want to count these as errors + } + break; + + case BatteryMsgId::INFO: + // we do not process these replies + break; + + default: + // ignore unknown messages + break; + } + } + + // handle reply from motor + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) && (msg_addr == MsgAddress::BUS_MASTER)) { + // replies strangely do not return the msgid so we must have stored it + MotorMsgId msg_id = (MotorMsgId)_reply_msgid; + switch (msg_id) { + + case MotorMsgId::PARAM: + if (_received_buff_len == 15) { + _motor_param.rpm = (int16_t)UINT16_VALUE(_received_buff[2], _received_buff[3]); + _motor_param.power = UINT16_VALUE(_received_buff[4], _received_buff[5]); + _motor_param.voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; + _motor_param.current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; + _motor_param.pcb_temp = (int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11]) * 0.1; + _motor_param.stator_temp = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]) * 0.1; + _motor_param.last_update_ms = AP_HAL::millis(); + + // update esc telem sent to ground station + update_esc_telem(_motor_param.rpm, + _motor_param.voltage, + _motor_param.current, + _motor_param.pcb_temp, // esc temp + _motor_param.stator_temp); // motor temp + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRMP + // @Description: Torqeedo Motor Param + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: RPM: Motor RPM + // @Field: Pow: Motor power + // @Field: Volt: Motor voltage + // @Field: Cur: Motor current + // @Field: ETemp: ESC Temp + // @Field: MTemp: Motor Temp + AP::logger().Write("TRMP", "TimeUS,I,RPM,Pow,Volt,Cur,ETemp,MTemp", + "s#qWvAOO", // units + "F-000000", // multipliers + "QBhHffff", // formats + AP_HAL::micros64(), + _instance, + _motor_param.rpm, + _motor_param.power, + _motor_param.voltage, + _motor_param.current, + _motor_param.pcb_temp, + _motor_param.stator_temp); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRMP i:%u rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f", + (unsigned)_instance, + (int)_motor_param.rpm, + (unsigned)_motor_param.power, + (double)_motor_param.voltage, + (double)_motor_param.current, + (double)_motor_param.pcb_temp, + (double)_motor_param.stator_temp); + } + } else { + // unexpected length + _parse_error_count++; + } + break; + + case MotorMsgId::STATUS: + if (_received_buff_len == 6) { + _motor_status.status_flags_value = _received_buff[2]; + _motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRMS + // @Description: Torqeedo Motor Status + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: State: Motor status flags + // @Field: Err: Motor error flags + AP::logger().Write("TRMS", "TimeUS,I,State,Err", + "s#--", // units + "F---", // multipliers + "QBBH", // formats + AP_HAL::micros64(), + _instance, + _motor_status.status_flags_value, + _motor_status.error_flags_value); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS i:%u S:%d Err:%d", + (unsigned)_instance, + _motor_status.status_flags_value, + _motor_status.error_flags_value); + } + + // report any errors + report_error_codes(); + } else { + // unexpected length + _parse_error_count++; + } + break; + + case MotorMsgId::INFO: + case MotorMsgId::DRIVE: + case MotorMsgId::CONFIG: + // we do not process these replies + break; + + default: + // ignore unknown messages + break; + } + } +} + +// set DE Serial CTS pin to enable sending commands to motor +void AP_Torqeedo_TQBus::send_start() +{ + // set gpio pin or serial port's CTS pin + if (_params.pin_de > -1) { + hal.gpio->write(_params.pin_de, 1); + } else { + _uart->set_CTS_pin(true); + } +} + +// check for timeout after sending and unset pin if required +void AP_Torqeedo_TQBus::check_for_send_end() +{ + if (_send_delay_us == 0) { + // not sending + return; + } + + if (AP_HAL::micros() - _send_start_us < _send_delay_us) { + // return if delay has not yet elapsed + return; + } + _send_delay_us = 0; + + // unset gpio or serial port's CTS pin + if (_params.pin_de > -1) { + hal.gpio->write(_params.pin_de, 0); + } else { + _uart->set_CTS_pin(false); + } +} + +// calculate delay require to allow bytes to be sent +uint32_t AP_Torqeedo_TQBus::calc_send_delay_us(uint8_t num_bytes) +{ + // baud rate of 19200 bits/sec + // total number of bits = 10 x num_bytes + // Subtract 5 bits to stop transmission during the padding byte (but after its start bit) + // convert from seconds to micros by multiplying by 1,000,000 + // plus additional 300us safety margin + const uint32_t delay_us = 1e6 * ((num_bytes * 10) - 5) / TORQEEDO_SERIAL_BAUD; + return delay_us; +} + +// record msgid of message to wait for and set timer for timeout handling +void AP_Torqeedo_TQBus::set_expected_reply_msgid(uint8_t msg_id) +{ + _reply_msgid = msg_id; + _reply_wait_start_us = AP_HAL::micros(); +} + +// check for timeout waiting for reply message +void AP_Torqeedo_TQBus::check_for_reply_timeout() +{ + // return immediately if not waiting for reply + if (_reply_wait_start_us == 0) { + return; + } + if (AP_HAL::micros() - _reply_wait_start_us > (TORQEEDO_REPLY_TIMEOUT_MS * 1000)) { + _reply_wait_start_us = 0; + _parse_error_count++; + } +} + +// mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply +void AP_Torqeedo_TQBus::set_reply_received() +{ + _reply_wait_start_us = 0; +} + +// send a message to the motor with the specified message contents +// msg_contents should not include the header, footer or CRC +// returns true on success +bool AP_Torqeedo_TQBus::send_message(const uint8_t msg_contents[], uint8_t num_bytes) +{ + // buffer for outgoing message + uint8_t send_buff[TORQEEDO_MESSAGE_LEN_MAX]; + uint8_t send_buff_num_bytes = 0; + + // calculate crc + const uint8_t crc = crc8_maxim(msg_contents, num_bytes); + + // add header + send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_HEADER; + + // add contents + for (uint8_t i=0; i= ARRAY_SIZE(send_buff)) { + _parse_error_count++; + return false; + } + send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_FOOTER; + + // set send pin + send_start(); + + // write message + _uart->write(send_buff, send_buff_num_bytes); + + // record start and expected delay to send message + _send_start_us = AP_HAL::micros(); + _send_delay_us = calc_send_delay_us(send_buff_num_bytes); + + return true; +} + +// add a byte to a message buffer including adding the escape character (0xAE) if necessary +// this should only be used when adding the contents to the buffer, not the header and footer +// num_bytes is updated to the next free byte +bool AP_Torqeedo_TQBus::add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const +{ + bool escape_required = (byte_to_add == TORQEEDO_PACKET_HEADER || + byte_to_add == TORQEEDO_PACKET_FOOTER || + byte_to_add == TORQEEDO_PACKET_ESCAPE); + + // check if we have enough space + if (num_bytes + (escape_required ? 2 : 1) >= msg_buff_size) { + return false; + } + + // add byte + if (escape_required) { + msg_buff[num_bytes++] = TORQEEDO_PACKET_ESCAPE; + msg_buff[num_bytes++] = byte_to_add ^ TORQEEDO_PACKET_ESCAPE_MASK; + } else { + msg_buff[num_bytes++] = byte_to_add; + } + return true; +} + +// Example "Remote (0x01)" reply message to allow tiller to control motor speed +// Byte Field Definition Example Value Comments +// --------------------------------------------------------------------------------- +// byte 0 Header 0xAC +// byte 1 TargetAddress 0x00 see MsgAddress enum +// byte 2 Message ID 0x00 only master populates this. replies have this set to zero +// byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid +// byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 +// byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) +// byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) +// byte 7 CRC-Maxim ---- CRC-Maxim value +// byte 8 Footer 0xAD +// +// example message when rotating tiller handle forwards: "AC 00 00 05 00 00 ED 95 AD" (+237) +// example message when rotating tiller handle backwards: "AC 00 00 05 00 FF AE 2C 0C AD" (-82) + +// send a motor speed command as a value from -1000 to +1000 +// value is taken directly from SRV_Channel +// for tiller connection this sends the "Remote (0x01)" message +// for motor connection this sends the "Motor Drive (0x82)" message +void AP_Torqeedo_TQBus::send_motor_speed_cmd() +{ + // calculate desired motor speed + if (!hal.util->get_soft_armed()) { + _motor_speed_desired = 0; + } else { + // convert throttle output to motor output in range -1000 to +1000 + // ToDo: convert PWM output to motor output so that SERVOx_MIN, MAX and TRIM take effect + _motor_speed_desired = constrain_int16(SRV_Channels::get_output_norm((SRV_Channel::Aux_servo_function_t)_params.servo_fn.get()) * 1000.0, -1000, 1000); + } + + // updated limited motor speed + int16_t mot_speed_limited = calc_motor_speed_limited(_motor_speed_desired); + + // by default use tiller connection command + uint8_t mot_speed_cmd_buff[] = {(uint8_t)MsgAddress::BUS_MASTER, 0x0, 0x5, 0x0, HIGHBYTE(mot_speed_limited), LOWBYTE(mot_speed_limited)}; + + // update message if using motor connection + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) { + const uint8_t motor_power = (uint8_t)constrain_int16(_params.motor_power, 0, 100); + mot_speed_cmd_buff[0] = (uint8_t)MsgAddress::MOTOR; + mot_speed_cmd_buff[1] = (uint8_t)MotorMsgId::DRIVE; + mot_speed_cmd_buff[2] = (mot_speed_limited == 0 ? 0 : 0x01) | (_motor_clear_error ? 0x04 : 0); // 1:enable motor, 2:fast off, 4:clear error + mot_speed_cmd_buff[3] = mot_speed_limited == 0 ? 0 : motor_power; // motor power from 0 to 100 + + // set expected reply message id + set_expected_reply_msgid((uint8_t)MotorMsgId::DRIVE); + + // reset motor clear error request + _motor_clear_error = false; + } + + // send a message + if (send_message(mot_speed_cmd_buff, ARRAY_SIZE(mot_speed_cmd_buff))) { + // record time of send for health reporting + WITH_SEMAPHORE(_last_healthy_sem); + _last_send_motor_ms = AP_HAL::millis(); + } +} + +// send request to motor to reply with a particular message +// msg_id can be INFO, STATUS or PARAM +void AP_Torqeedo_TQBus::send_motor_msg_request(MotorMsgId msg_id) +{ + // prepare message + uint8_t mot_status_request_buff[] = {(uint8_t)MsgAddress::MOTOR, (uint8_t)msg_id}; + + // send a message + if (send_message(mot_status_request_buff, ARRAY_SIZE(mot_status_request_buff))) { + // record waiting for reply + set_expected_reply_msgid((uint8_t)msg_id); + } +} + +// send request to battery to reply with a particular message +// msg_id can be STATUS +void AP_Torqeedo_TQBus::send_battery_msg_request(BatteryMsgId msg_id) +{ + // prepare message + uint8_t batt_status_request_buff[] = {(uint8_t)MsgAddress::BATTERY, (uint8_t)msg_id}; + + // record waiting for reply + set_expected_reply_msgid((uint8_t)msg_id); + + // send a message + send_message(batt_status_request_buff, ARRAY_SIZE(batt_status_request_buff)); +} + +// calculate the limited motor speed that is sent to the motors +// desired_motor_speed argument and returned value are in the range -1000 to 1000 +int16_t AP_Torqeedo_TQBus::calc_motor_speed_limited(int16_t desired_motor_speed) +{ + const uint32_t now_ms = AP_HAL::millis(); + + // update dir_limit flag for forward-reverse transition delay + const bool dir_delay_active = is_positive(_params.dir_delay); + if (!dir_delay_active) { + // allow movement in either direction + _dir_limit = 0; + } else { + // by default limit motor direction to previous iteration's direction + if (is_positive(_motor_speed_limited)) { + _dir_limit = 1; + } else if (is_negative(_motor_speed_limited)) { + _dir_limit = -1; + } else { + // motor speed is zero + if ((_motor_speed_zero_ms != 0) && ((now_ms - _motor_speed_zero_ms) > (_params.dir_delay * 1000))) { + // delay has passed so allow movement in either direction + _dir_limit = 0; + _motor_speed_zero_ms = 0; + } + } + } + + // calculate upper and lower limits for forward-reverse transition delay + int16_t lower_limit = -1000; + int16_t upper_limit = 1000; + if (_dir_limit < 0) { + upper_limit = 0; + } + if (_dir_limit > 0) { + lower_limit = 0; + } + + // calculate dt since last update + 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; + upper_limit = 0; + } + _motor_speed_limited_ms = now_ms; + + // apply slew limit + if (_params.slew_time > 0) { + const float chg_max = 1000.0 * dt / _params.slew_time; + _motor_speed_limited = constrain_float(desired_motor_speed, _motor_speed_limited - chg_max, _motor_speed_limited + chg_max); + } else { + // no slew limit + _motor_speed_limited = desired_motor_speed; + } + + // apply upper and lower limits + _motor_speed_limited = constrain_float(_motor_speed_limited, lower_limit, upper_limit); + + // record time motor speed becomes zero + if (is_zero(_motor_speed_limited)) { + if (_motor_speed_zero_ms == 0) { + _motor_speed_zero_ms = now_ms; + } + } else { + // clear timer + _motor_speed_zero_ms = 0; + } + + return (int16_t)_motor_speed_limited; +} + +// set the on/off pin to on momentarily to wake the motor or clear an error state +void AP_Torqeedo_TQBus::press_on_off_button() +{ + if (_type == AP_Torqeedo::ConnectionType::TYPE_TILLER) { + if (_pin_onoff > -1) { + hal.gpio->pinMode(_pin_onoff, HAL_GPIO_OUTPUT); + hal.gpio->write(_pin_onoff, 1); + hal.scheduler->delay(500); + hal.gpio->write(_pin_onoff, 0); + } else { + // use serial port's RTS pin to turn on battery + _uart->set_RTS_pin(true); + hal.scheduler->delay(500); + _uart->set_RTS_pin(false); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Torqeedo: On/Off button pressed"); + } +} + +// output logging and debug messages (if required) +// force_logging should be true if caller wants to ensure the latest status is logged +void AP_Torqeedo_TQBus::log_TRQD(bool force_logging) +{ + // exit immediately if logging and debug options are not set + if (!option_enabled(AP_Torqeedo::options::LOG) && option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + return; + } + + // return if not enough time has passed since last output + const uint32_t now_ms = AP_HAL::millis(); + if (!force_logging && (now_ms - _last_log_TRQD_ms < TORQEEDO_LOG_TRQD_INTERVAL_MS)) { + return; + } + _last_log_TRQD_ms = now_ms; + +#if HAL_LOGGING_ENABLED || HAL_GCS_ENABLED + const bool health = healthy(); + int16_t actual_motor_speed = get_motor_speed_limited(); + +#if HAL_LOGGING_ENABLED + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRQD + // @Description: Torqeedo Status + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: Health: Health + // @Field: DesMotSpeed: Desired Motor Speed (-1000 to 1000) + // @Field: MotSpeed: Motor Speed (-1000 to 1000) + // @Field: SuccCnt: Success Count + // @Field: ErrCnt: Error Count + AP::logger().Write("TRQD", "TimeUS,I,Health,DesMotSpeed,MotSpeed,SuccCnt,ErrCnt", + "s#-----", // units + "F------", // multipliers + "QBBhhII", // formats + AP_HAL::micros64(), + _instance, + health, + _motor_speed_desired, + actual_motor_speed, + _parse_success_count, + _parse_error_count); + } +#endif + + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD i:%u h:%u dspd:%d spd:%d succ:%ld err:%ld", + (unsigned)_instance, + (unsigned)health, + (int)_motor_speed_desired, + (int)actual_motor_speed, + (unsigned long)_parse_success_count, + (unsigned long)_parse_error_count); + } +#endif // HAL_LOGGING_ENABLED || HAL_GCS_ENABLED +} + +// send ESC telemetry +void AP_Torqeedo_TQBus::update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC) +{ +#if HAL_WITH_ESC_TELEM + // find servo output channel + uint8_t telem_esc_index = 0; + IGNORE_RETURN(SRV_Channels::find_channel((SRV_Channel::Aux_servo_function_t)_params.servo_fn.get(), telem_esc_index)); + + // fill in telemetry data structure + AP_ESC_Telem_Backend::TelemetryData telem_dat {}; + telem_dat.temperature_cdeg = esc_tempC * 100; // temperature in centi-degrees + telem_dat.voltage = voltage; // voltage in volts + telem_dat.current = current_amps; // current in amps + telem_dat.motor_temp_cdeg = motor_tempC * 100; // motor temperature in centi-degrees + + // send telem and rpm data + update_telem_data(telem_esc_index, telem_dat, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | + AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | + AP_ESC_Telem_Backend::TelemetryType::CURRENT | + AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); + + update_rpm(telem_esc_index, rpm); +#endif +} + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h new file mode 100644 index 00000000000000..06595a51fbd85d --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h @@ -0,0 +1,420 @@ +/* + 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 . + */ + +/* + This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol + which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW + + The autopilot should be connected either to the battery's tiller connector or directly to the motor + as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html + TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. + + Tiller connection: Autopilot <-> Battery (master) <-> Motor + Motor connection: Autopilot (master) <-> Motor + + Communication between the components is always initiated by the master with replies sent within 25ms + + Example "Remote (0x01)" reply message to allow tiller to control motor speed + Byte Field Definition Example Value Comments + --------------------------------------------------------------------------------- + byte 0 Header 0xAC + byte 1 TargetAddress 0x00 see MsgAddress enum + byte 2 Message ID 0x00 only master populates this. replies have this set to zero + byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid + byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 + byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) + byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) + byte 7 CRC-Maxim ---- CRC-Maxim value + byte 8 Footer 0xAD + + More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. + */ + +#pragma once + +#include "AP_Torqeedo_config.h" + +#if HAL_TORQEEDO_ENABLED + +#include "AP_Torqeedo_Backend.h" + +#define TORQEEDO_MESSAGE_LEN_MAX 35 // messages are no more than 35 bytes + +class AP_Torqeedo_TQBus : public AP_Torqeedo_Backend { +public: + + // constructor + using AP_Torqeedo_Backend::AP_Torqeedo_Backend; + + CLASS_NO_COPY(AP_Torqeedo_TQBus); + + // initialise driver + void init() override; + + // returns true if communicating with the motor + bool healthy() override; + + // clear motor errors + void clear_motor_error() override { _motor_clear_error = true; } + + // get latest battery status info. returns true on success and populates arguments + bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const override; + bool get_batt_capacity_Ah(uint16_t &_hours) const override; + +private: + + // consume incoming messages from motor, reply with latest motor speed + // runs in background thread + void thread_main(); + + // report changes in error codes to user + void report_error_codes(); + + // message addresses + enum class MsgAddress : uint8_t { + BUS_MASTER = 0x00, + REMOTE1 = 0x14, + DISPLAY = 0x20, + MOTOR = 0x30, + BATTERY = 0x80 + }; + + // Remote specific message ids + enum class RemoteMsgId : uint8_t { + INFO = 0x00, + REMOTE = 0x01, + SETUP = 0x02 + }; + + // Display specific message ids + enum class DisplayMsgId : uint8_t { + INFO = 0x00, + SYSTEM_STATE = 0x41, + SYSTEM_SETUP = 0x42 + }; + + // Motor specific message ids + enum class MotorMsgId : uint8_t { + INFO = 0x00, + STATUS = 0x01, + PARAM = 0x03, + CONFIG = 0x04, + DRIVE = 0x82 + }; + + // Battery specific message ids + enum class BatteryMsgId : uint8_t { + INFO = 0x01, + STATUS = 0x04 + }; + + enum class ParseState { + WAITING_FOR_HEADER = 0, + WAITING_FOR_FOOTER, + }; + + // initialise serial port and gpio pins (run from background thread) + // returns true on success + bool init_internals(); + + // process a single byte received on serial port + // return true if a complete message has been received (the message will be held in _received_buff) + bool parse_byte(uint8_t b); + + // process message held in _received_buff + void parse_message(); + + // returns true if it is safe to send a message + bool safe_to_send() const { return ((_send_delay_us == 0) && (_reply_wait_start_us == 0)); } + + // set pin to enable sending a message + void send_start(); + + // check for timeout after sending a message and unset pin if required + void check_for_send_end(); + + // calculate delay required to allow message to be completely sent + uint32_t calc_send_delay_us(uint8_t num_bytes); + + // record msgid of message to wait for and set timer for reply timeout handling + void set_expected_reply_msgid(uint8_t msg_id); + + // check for timeout waiting for reply + void check_for_reply_timeout(); + + // mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply + void set_reply_received(); + + // send a message to the motor with the specified message contents + // msg_contents should not include the header, footer or CRC + // returns true on success + bool send_message(const uint8_t msg_contents[], uint8_t num_bytes); + + // add a byte to a message buffer including adding the escape character (0xAE) if necessary + // this should only be used when adding the contents to the buffer, not the header and footer + // num_bytes is updated to the next free byte + bool add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const; + + // send a motor speed command as a value from -1000 to +1000 + // value is taken directly from SRV_Channel unless set_zero_speed is true + // (if set_zero_speed is true then the motor speed is set to zero) + void send_motor_speed_cmd(bool set_zero_speed = false); + + // send request to motor to reply with a particular message + // msg_id can be INFO, STATUS or PARAM + void send_motor_msg_request(MotorMsgId msg_id); + + // send request to battery to reply with a particular message + // msg_id can be STATUS + void send_battery_msg_request(BatteryMsgId msg_id); + + // calculate the limited motor speed that is sent to the motors + // desired_motor_speed argument and returned value are in the range -1000 to 1000 + int16_t calc_motor_speed_limited(int16_t desired_motor_speed); + int16_t get_motor_speed_limited() const { return (int16_t)_motor_speed_limited; } + + // log TRQD message which holds high level status and latest desired motors peed + // force_logging should be true to immediately write log bypassing timing check to avoid spamming + void log_TRQD(bool force_logging); + + // send ESC telemetry + void update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC); + + // set the on/off pin to on momentarily to wake the motor or clear an error state + void press_on_off_button(); + + // members + AP_HAL::UARTDriver *_uart; // serial port to communicate with motor + bool _initialised; // true once driver has been initialised + bool _send_motor_speed; // true if motor speed should be sent at next opportunity + int16_t _motor_speed_desired; // desired motor speed (set from within update method) + uint32_t _last_send_motor_ms; // system time (in millis) last motor speed command was sent (used for health reporting) + bool _motor_clear_error; // true if the motor error should be cleared (sent in "Drive" message) + uint32_t _send_start_us; // system time (in micros) when last message started being sent (used for timing to unset DE pin) + uint32_t _send_delay_us; // delay (in micros) to allow bytes to be sent after which pin can be unset. 0 if not delaying + + // motor speed limit variables + float _motor_speed_limited; // limited desired motor speed. this value is actually sent to the motor + uint32_t _motor_speed_limited_ms; // system time that _motor_speed_limited was last updated + int8_t _dir_limit; // acceptable directions for output to motor (+1 = positive OK, -1 = negative OK, 0 = either positive or negative OK) + uint32_t _motor_speed_zero_ms; // system time that _motor_speed_limited reached zero. 0 if currently not zero + + // health reporting + HAL_Semaphore _last_healthy_sem;// semaphore protecting reading and updating of _last_send_motor_ms and _last_received_ms + uint32_t _last_log_TRQD_ms; // system time (in millis) that TRQD was last logged + + // reset/wake + uint32_t _last_reset_ms; // system time (in millis) since hard reset/wake button was last pressed + + // message parsing members + ParseState _parse_state; // current state of parsing + bool _parse_escape_received; // true if the escape character has been received so we must XOR the next byte + uint32_t _parse_error_count; // total number of parsing errors (for reporting) + uint32_t _parse_success_count; // number of messages successfully parsed (for reporting) + uint8_t _received_buff[TORQEEDO_MESSAGE_LEN_MAX]; // characters received + uint8_t _received_buff_len; // number of characters received + uint32_t _last_received_ms; // system time (in millis) that a message was successfully parsed (for health reporting) + + // reply message handling + uint8_t _reply_msgid; // replies expected msgid (reply often does not specify the msgid so we must record it) + uint32_t _reply_wait_start_us; // system time (in micros) that we started waiting for a reply message + + // Display system state flags + typedef union PACKED { + struct { + uint8_t set_throttle_stop : 1; // 0, warning that user must set throttle to stop before motor can run + uint8_t setup_allowed : 1; // 1, remote is allowed to enter setup mode + uint8_t in_charge : 1; // 2, master is in charging state + uint8_t in_setup : 1; // 3, master is in setup state + uint8_t bank_available : 1; // 4 + uint8_t no_menu : 1; // 5 + uint8_t menu_off : 1; // 6 + uint8_t reserved7 : 1; // 7, unused + uint8_t temp_warning : 1; // 8, motor or battery temp warning + uint8_t batt_charge_valid : 1; // 9, battery charge valid + uint8_t batt_nearly_empty : 1; // 10, battery nearly empty + uint8_t batt_charging : 1; // 11, battery charging + uint8_t gps_searching : 1; // 12, gps searching for satellites + uint8_t gps_speed_valid : 1; // 13, gps speed is valid + uint8_t range_miles_valid : 1; // 14, range (in miles) is valid + uint8_t range_minutes_valid : 1; // 15, range (in minutes) is valid + }; + uint16_t value; + } DisplaySystemStateFlags; + + // Display system state + struct DisplaySystemState { + DisplaySystemStateFlags flags; // flags, see above for individual bit definitions + uint8_t master_state; // deprecated + uint8_t master_error_code; // error code (0=no error) + float motor_voltage; // motor voltage in volts + float motor_current; // motor current in amps + uint16_t motor_power; // motor power in watts + int16_t motor_rpm; // motor speed in rpm + uint8_t motor_pcb_temp; // motor pcb temp in C + uint8_t motor_stator_temp; // motor stator temp in C + uint8_t batt_charge_pct; // battery state of charge (0 to 100%) + float batt_voltage; // battery voltage in volts + float batt_current; // battery current in amps + uint16_t gps_speed; // gps speed in knots * 100 + uint16_t range_miles; // range in nautical miles * 10 + uint16_t range_minutes; // range in minutes (at current speed and current draw) + uint8_t temp_sw; // master PCB temp in C (close to motor power switches) + uint8_t temp_rp; // master PCB temp in C (close to reverse voltage protection) + uint32_t last_update_ms; // system time that system state was last updated + } _display_system_state; + + // Display system setup + struct DisplaySystemSetup { + uint8_t flags; // 0 : battery config valid, all other bits unused + uint8_t motor_type; // motor type (0 or 3:Unknown, 1:Ultralight, 2:Cruise2, 4:Cruise4, 5:Travel503, 6:Travel1003, 7:Cruise10kW) + uint16_t motor_sw_version; // motor software version + uint16_t batt_capacity; // battery capacity in amp hours + uint8_t batt_charge_pct; // battery state of charge (0 to 100%) + uint8_t batt_type; // battery type (0:lead acid, 1:Lithium) + uint16_t master_sw_version; // master software version + } _display_system_setup; + + // Motor status + struct MotorStatus { + union PACKED { + struct { + uint8_t temp_limit_motor : 1; // 0, motor speed limited due to motor temp + uint8_t temp_limit_pcb : 1; // 1, motor speed limited tue to PCB temp + uint8_t emergency_stop : 1; // 2, motor in emergency stop (must be cleared by master) + uint8_t running : 1; // 3, motor running + uint8_t power_limit : 1; // 4, motor power limited + uint8_t low_voltage_limit : 1; // 5, motor speed limited because of low voltage + uint8_t tilt : 1; // 6, motor is tilted + uint8_t reserved7 : 1; // 7, unused (always zero) + } status_flags; + uint8_t status_flags_value; + }; + union PACKED { + struct { + uint8_t overcurrent : 1; // 0, motor stopped because of overcurrent + uint8_t blocked : 1; // 1, motor stopped because it is blocked + uint8_t overvoltage_static : 1; // 2, motor stopped because voltage too high + uint8_t undervoltage_static : 1; // 3, motor stopped because voltage too low + uint8_t overvoltage_current : 1; // 4, motor stopped because voltage spiked high + uint8_t undervoltage_current: 1; // 5, motor stopped because voltage spiked low + uint8_t overtemp_motor : 1; // 6, motor stopped because stator temp too high + uint8_t overtemp_pcb : 1; // 7, motor stopped because pcb temp too high + uint8_t timeout_rs485 : 1; // 8, motor stopped because Drive message not received for too long + uint8_t temp_sensor_error : 1; // 9, motor temp sensor is defective (motor will not stop) + uint8_t tilt : 1; // 10, motor stopped because it was tilted + uint8_t unused11to15 : 5; // 11 ~ 15 (always zero) + } error_flags; + uint16_t error_flags_value; + }; + } _motor_status; + uint32_t _last_send_motor_status_request_ms; // system time (in milliseconds) that last motor status request was sent + + // Motor params + struct MotorParam { + int16_t rpm; // motor rpm + uint16_t power; // motor power consumption in Watts + float voltage; // motor voltage in volts + float current; // motor current in amps + float pcb_temp; // pcb temp in C + float stator_temp; // stator temp in C + uint32_t last_update_ms;// system time that above values were updated + } _motor_param; + uint32_t _last_send_motor_param_request_ms; // system time (in milliseconds) that last motor param request was sent + + // Battery Status Flags + typedef union PACKED { + struct { + uint8_t discharge_channel : 1; // 0, discharge channel active + uint8_t charge_channel : 1; // 1, charge channel active + uint8_t ddch : 1; // 2, deep discharge + uint8_t eod : 1; // 3, end of discharge + uint8_t hi_stack : 1; // 4, battery on high side of serial connection + }; + uint16_t value; + } BatteryStatusFlags; + + // Battery Warning Flags + typedef union PACKED { + struct { + uint8_t warn_batt_overcurrent : 1; // 0, discharge current too high + uint8_t warn_batt_overcomplicate : 1; // 1, cell temp too high + uint8_t warn_overtemp_fet : 1; // 2, pcb/fet temp too high + uint8_t warn_undertemp_cell : 1; // 3, cell temp too low + uint8_t warn_eod : 1; // 4, end of discharge + uint8_t warn_batt_off : 1; // 5, battery nearly empty + uint8_t warn_overcurrent_charge : 1; // 6, charge current too high + uint8_t warn_batt_overtemp_cell : 1; // 7, cell temp too high + uint8_t warn_batt_undertemp_cell : 1; // 8, cell temp too low + uint8_t warn_cells_unbalanced : 1; // 9, single voltage diff too big + }; + uint16_t value; + } BatteryWarningFlags; + + // Battery Error Flags + typedef union PACKED { + struct { + uint8_t err_batt_discharge_curr : 1; // 0, discharge current too high + uint8_t err_overtemp_cell : 1; // 1, cell temp too high + uint8_t err_overtemp_fet : 1; // 2, pcb/fet temp too high + uint8_t err_undertemp_cell : 1; // 3, cell temp too low + uint8_t err_eod : 1; // 4, end of discharge + uint8_t err_batt_off : 1; // 5, battery nearly empty + uint8_t err_overcurrent : 1; // 6, charge current too high + uint8_t err_overtemp_batt_cell : 1; // 7, cell temp too high + uint8_t err_undertemp_batt_cel : 1; // 8, cell temp too low + uint8_t err_overvoltage : 1; // 9, charge voltage too high + uint8_t err_overcharge : 1; // 10, overcharge + uint8_t err_second_protection : 1; // 11, second level protection was activated + uint8_t err_electronic_err : 1; // 12, general electronic error + uint8_t err_no_pyro_fuse : 1; // 13, pyrofuse connection lost + uint8_t err_leak_current : 1; // 14, water sensor + uint8_t err_ddch : 1; // 15, deep discharge - no charge + }; + uint16_t value; + } BatteryErrorFlags; + + // Battery status + struct BatteryStatus { + BatteryStatusFlags status_flags; // battery status flags + BatteryWarningFlags warning_flags; // battery warning flags + BatteryErrorFlags error_flags; // battery error flags + float temp_cell_pack; // max temp within cellpack (C) + float temp_pcb; // max temp on pcb/mosfet (C) + float voltage; // voltage cellpack (V) + float current; // battery current (A) + uint16_t power; // actual power (W) + float capacity; // learned max capacity (Ah) + float capacity_remaining; // remaining capacity (Ah) + uint16_t capacity_pct; // remaining capacity in percent (%) + uint16_t running_time; // remaining capacity in minutes (min) + uint16_t water_detect; // water detection (ADC value, 0=wet) + uint32_t last_update_ms; // system time that above values were updated + } _battery_status; + uint32_t _last_send_battery_status_request_ms; // system time (in milliseconds) that last battery status request was sent + + // error reporting + DisplaySystemStateFlags _display_system_state_flags_prev; // backup of display system state flags + uint8_t _display_system_state_master_error_code_prev; // backup of display system state master_error_code + uint32_t _last_error_report_ms; // system time that flag changes were last reported (used to prevent spamming user) + MotorStatus _motor_status_prev; // backup of motor status + + // 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; +}; + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Vehicle/AP_FixedWing.h b/libraries/AP_Vehicle/AP_FixedWing.h index 7aee38d5c5b35d..8135a7d1603520 100644 --- a/libraries/AP_Vehicle/AP_FixedWing.h +++ b/libraries/AP_Vehicle/AP_FixedWing.h @@ -11,9 +11,13 @@ struct AP_FixedWing { AP_Int8 throttle_slewrate; AP_Int8 throttle_cruise; AP_Int8 takeoff_throttle_max; + AP_Int8 takeoff_throttle_min; + AP_Int8 takeoff_throttle_idle; + AP_Int32 takeoff_options; AP_Int16 airspeed_min; AP_Int16 airspeed_max; AP_Float airspeed_cruise; + AP_Float airspeed_stall; AP_Float min_groundspeed; AP_Int8 crash_detection_enable; AP_Float roll_limit; @@ -48,4 +52,9 @@ struct AP_FixedWing { LAND = 4, ABORT_LANDING = 7 }; + + // Bitfields of TKOFF_OPTIONS + enum class TakeoffOption { + THROTTLE_RANGE = (1U << 0), // Unset: Max throttle. Set: Throttle range. + }; }; diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 829383dd310e48..3005e40d3adcbc 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -223,6 +223,7 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { are too deep in the parameter tree */ +#if AP_NETWORKING_REGISTER_PORT_ENABLED #if AP_NETWORKING_NUM_PORTS > 0 // @Group: NET_P1_ // @Path: ../AP_Networking/AP_Networking_port.cpp @@ -246,6 +247,7 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { // @Path: ../AP_Networking/AP_Networking_port.cpp AP_SUBGROUPINFO(networking.ports[3], "NET_P4_", 25, AP_Vehicle, AP_Networking::Port), #endif +#endif // AP_NETWORKING_REGISTER_PORT_ENABLED #endif // AP_NETWORKING_ENABLED #if AP_FILTER_ENABLED @@ -367,9 +369,19 @@ void AP_Vehicle::setup() networking.init(); #endif +#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_SERIALDEVICE_ENABLED + // must be done now so ports are registered and drivers get set up properly + // (in particular mavlink which checks during init_ardupilot()) + scripting.init_serialdevice_ports(); +#endif +#endif + +#if AP_SCHEDULER_ENABLED // Register scheduler_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay hal.scheduler->register_delay_callback(scheduler_delay_callback, 5); +#endif #if HAL_MSP_ENABLED // call MSP init before init_ardupilot to allow for MSP sensors @@ -426,12 +438,16 @@ void AP_Vehicle::setup() #if AP_SRV_CHANNELS_ENABLED - SRV_Channels::init(); + AP::srv().init(); #endif // gyro FFT needs to be initialized really late #if HAL_GYROFFT_ENABLED +#if AP_SCHEDULER_ENABLED gyro_fft.init(AP::scheduler().get_loop_rate_hz()); +#else + gyro_fft.init(1000); +#endif #endif #if HAL_RUNCAM_ENABLED runcam.init(); @@ -516,12 +532,21 @@ void AP_Vehicle::setup() GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Failed to Initialize", AP_DDS_Client::msg_prefix); } #endif + +#if AP_IBUS_TELEM_ENABLED + ibus_telem.init(); +#endif } void AP_Vehicle::loop() { +#if AP_SCHEDULER_ENABLED scheduler.loop(); G_Dt = scheduler.get_loop_period_s(); +#else + hal.scheduler->delay(1); + G_Dt = 0.001; +#endif if (!done_safety_init) { /* @@ -548,6 +573,7 @@ void AP_Vehicle::loop() } } +#if AP_SCHEDULER_ENABLED /* scheduler table - all regular tasks apart from the fast_loop() should be listed here. @@ -708,6 +734,7 @@ void AP_Vehicle::scheduler_delay_callback() logger.EnableWrites(true); #endif } +#endif // AP_SCHEDULER_ENABLED // if there's been a watchdog reset, notify the world via a statustext: void AP_Vehicle::send_watchdog_reset_statustext() @@ -751,21 +778,43 @@ bool AP_Vehicle::is_crashed() const // 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) +#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(); -#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +#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; + if (motors == nullptr) { + notch.update_freq_hz(0); + return; + } + const float motors_throttle = MAX(0,motors->get_throttle_out()); + // set the harmonic notch filter frequency scaled on measured frequency + if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { + float notches[INS_MAX_NOTCHES]; + uint8_t motor_num = 0; + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + float motor_throttle = 0; + if (motors->get_thrust(i, motor_throttle)) { + notches[motor_num] = ref_freq * sqrtf(MAX(0, motor_throttle) / ref); + motor_num++; + } + if (motor_num >= INS_MAX_NOTCHES) { + break; + } + } + notch.update_frequencies_hz(motor_num, notches); + } else #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 * sqrtf(MAX(0,motors_throttle) / ref); - float throttle_freq = ref_freq * sqrtf(MAX(0,motors_throttle) / ref); + notch.update_freq_hz(throttle_freq); + } - notch.update_freq_hz(throttle_freq); #endif } @@ -1070,7 +1119,7 @@ void AP_Vehicle::check_motor_noise() #if AP_DDS_ENABLED bool AP_Vehicle::init_dds_client() { - dds_client = new AP_DDS_Client(); + dds_client = NEW_NOTHROW AP_DDS_Client(); if (dds_client == nullptr) { return false; } diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 0ea6a802ca665e..f56262e0c33116 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -80,6 +80,8 @@ #include #endif +#include + class AP_DDS_Client; class AP_Vehicle : public AP_HAL::HAL::Callbacks { @@ -127,10 +129,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // parameters for example. void notify_no_such_mode(uint8_t mode_number); +#if AP_SCHEDULER_ENABLED void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks); // implementations *MUST* fill in all passed-in fields or we get // Valgrind errors -#if AP_SCHEDULER_ENABLED virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0; #endif @@ -169,21 +171,23 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // returns true if the vehicle has crashed virtual bool is_crashed() const; -#if AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED + // Method to takeoff for use by external control + virtual bool start_takeoff(const float alt) { return false; } // Method to control vehicle position for use by external control virtual bool set_target_location(const Location& target_loc) { return false; } -#endif // AP_EXTERNAL_CONTROL_ENABLED +#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED #if AP_SCRIPTING_ENABLED /* methods to control vehicle for use by scripting */ - virtual bool start_takeoff(float alt) { return false; } virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; } virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; } virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; } virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; } virtual bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; } virtual 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) { return false; } + virtual bool set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) { return false; } // command throttle percentage and roll, pitch, yaw target // rates. For use with scripting controllers @@ -221,7 +225,11 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // allow for landing descent rate to be overridden by a script, may be -ve to climb virtual bool set_land_descent_rate(float descent_rate) { return false; } - + + // Allow for scripting to have control over the crosstracking when exiting and resuming missions or guided flight + // It's up to the Lua script to ensure the provided location makes sense + virtual bool set_crosstrack_start(const Location &new_start_location) { return false; } + // control outputs enumeration enum class ControlOutput { Roll = 1, @@ -239,6 +247,12 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // returns true on success and control_value is set to a value in the range -1 to +1 virtual bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) { return false; } + // Register a custom mode with given number and names, return a structure which the script can edit + struct custom_mode_state { + bool allow_entry; + }; + virtual custom_mode_state* register_custom_mode(const uint8_t number, const char* full_name, const char* short_name) { return nullptr; } + #endif // AP_SCRIPTING_ENABLED // returns true if vehicle is in the process of landing @@ -310,8 +324,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_CANManager can_mgr; #endif +#if AP_SCHEDULER_ENABLED // main loop scheduler AP_Scheduler scheduler; +#endif // IMU variables // Integration time; time last loop took to run @@ -331,7 +347,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #if HAL_BUTTON_ENABLED AP_Button button; #endif +#if AP_RANGEFINDER_ENABLED RangeFinder rangefinder; +#endif #if HAL_LOGGING_ENABLED AP_Logger logger; @@ -346,6 +364,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_Gripper gripper; #endif +#if AP_IBUS_TELEM_ENABLED + AP_IBus_Telem ibus_telem; +#endif + #if AP_RSSI_ENABLED AP_RSSI rssi; #endif @@ -461,7 +483,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif static const struct AP_Param::GroupInfo var_info[]; +#if AP_SCHEDULER_ENABLED static const struct AP_Scheduler::Task scheduler_tasks[]; +#endif #if OSD_ENABLED void publish_osd_info(); @@ -495,8 +519,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { private: +#if AP_SCHEDULER_ENABLED // delay() callback that processing MAVLink packets static void scheduler_delay_callback(); +#endif // if there's been a watchdog reset, notify the world via a // statustext: diff --git a/libraries/AP_Vehicle/AP_Vehicle_Type.h b/libraries/AP_Vehicle/AP_Vehicle_Type.h index 0bc298658f8c8b..3636f2364983c1 100644 --- a/libraries/AP_Vehicle/AP_Vehicle_Type.h +++ b/libraries/AP_Vehicle/AP_Vehicle_Type.h @@ -19,6 +19,7 @@ Also note that code needs to support other APM_BUILD_DIRECTORY values for example sketches */ +// @LoggerEnum: APM_BUILD #define APM_BUILD_Rover 1 #define APM_BUILD_ArduCopter 2 #define APM_BUILD_ArduPlane 3 @@ -32,6 +33,7 @@ #define APM_BUILD_AP_Bootloader 11 #define APM_BUILD_Blimp 12 #define APM_BUILD_Heli 13 +// @LoggerEnumEnd #ifdef APM_BUILD_DIRECTORY /* diff --git a/libraries/AP_Vehicle/ModeReason.h b/libraries/AP_Vehicle/ModeReason.h index d1e124426f28e7..a1936d8e455bf0 100644 --- a/libraries/AP_Vehicle/ModeReason.h +++ b/libraries/AP_Vehicle/ModeReason.h @@ -70,4 +70,5 @@ enum class ModeReason : uint8_t { DEADRECKON_FAILSAFE = 50, MODE_TAKEOFF_FAILSAFE = 51, DDS_COMMAND = 52, + AUX_FUNCTION = 53, }; diff --git a/libraries/AP_VideoTX/AP_SmartAudio.cpp b/libraries/AP_VideoTX/AP_SmartAudio.cpp index f95bca0614c60e..ef396c345b9189 100644 --- a/libraries/AP_VideoTX/AP_SmartAudio.cpp +++ b/libraries/AP_VideoTX/AP_SmartAudio.cpp @@ -62,6 +62,8 @@ bool AP_SmartAudio::init() return false; } + AP::vtx().set_provider_enabled(AP_VideoTX::VTXType::SmartAudio); + return true; } return false; diff --git a/libraries/AP_VideoTX/AP_Tramp.cpp b/libraries/AP_VideoTX/AP_Tramp.cpp index 74581b09d333db..afe6f07ac7bc24 100644 --- a/libraries/AP_VideoTX/AP_Tramp.cpp +++ b/libraries/AP_VideoTX/AP_Tramp.cpp @@ -77,12 +77,17 @@ void AP_Tramp::send_command(uint8_t cmd, uint16_t param) port->write(request_buffer, TRAMP_BUF_SIZE); port->flush(); + _packets_sent++; + debug("send command '%c': %u", cmd, param); } // Process response and return code if valid else 0 char AP_Tramp::handle_response(void) { + _packets_rcvd++; + _packets_sent = _packets_rcvd; + const uint8_t respCode = response_buffer[1]; switch (respCode) { @@ -135,9 +140,11 @@ char AP_Tramp::handle_response(void) vtx.announce_vtx_settings(); } - debug("device config: freq: %u, power: %u, pitmode: %u", - unsigned(freq), unsigned(power), unsigned(pit_mode)); + debug("device config: freq: %u, cfg pwr: %umw, act pwr: %umw, pitmode: %u", + unsigned(freq), unsigned(power), unsigned(cur_act_power), unsigned(pit_mode)); + // update the "_configuration_finished" flag, otherwise OSD item VTX_POWER blinks forever + vtx.set_configuration_finished(!update_pending); return 'v'; } @@ -162,6 +169,7 @@ char AP_Tramp::handle_response(void) // Reset receiver state machine void AP_Tramp::reset_receiver(void) { + port->discard_input(); receive_state = ReceiveState::S_WAIT_LEN; receive_pos = 0; } @@ -316,6 +324,9 @@ void AP_Tramp::process_requests() // 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) { + + update_baud_rate(); + // Min request period exceeded, issue another query send_query('v'); @@ -332,12 +343,14 @@ void AP_Tramp::process_requests() AP_VideoTX& vtx = AP::vtx(); // Config retries remain and min request period exceeded, check freq if (!is_race_lock_enabled() && vtx.update_frequency()) { + debug("Updating frequency to %uMhz", vtx.get_configured_frequency_mhz()); // 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()) { + debug("Updating power to %umw\n", vtx.get_configured_power_mw()); // Power can be and needs to be updated, issue request send_command('P', vtx.get_configured_power_mw()); @@ -477,6 +490,35 @@ void AP_Tramp::update() process_requests(); } +// we missed a response too many times - update the baud rate in case the temperature has increased +void AP_Tramp::update_baud_rate() +{ + // on my Unify Pro32 the VTX will respond immediately on power up to a settings request, so 5 packets is easily more than enough + // we want to bias autobaud to only frequency hop when the current frequency is clearly exhausted, but after that hop quickly + // on a Foxeer Reaper Infinity the actual response baudrate is more like 9400, so auto-bauding down in the first instance. + if (_packets_sent - _packets_rcvd < 5) { + return; + } + + if (_smartbaud_direction == AutobaudDirection::UP + && _smartbaud == VTX_TRAMP_SMARTBAUD_MAX) { + _smartbaud_direction = AutobaudDirection::DOWN; + } else if (_smartbaud_direction == AutobaudDirection::DOWN + && _smartbaud == VTX_TRAMP_SMARTBAUD_MIN) { + _smartbaud_direction = AutobaudDirection::UP; + } + + _smartbaud += VTX_TRAMP_SMARTBAUD_STEP * int32_t(_smartbaud_direction); + + debug("autobaud: %d", int(_smartbaud)); + + port->discard_input(); + port->begin(_smartbaud); + + _packets_sent = _packets_rcvd = 0; +} + + bool AP_Tramp::init(void) { if (AP::vtx().get_enabled() == 0) { @@ -495,6 +537,8 @@ bool AP_Tramp::init(void) port->begin(AP_TRAMP_UART_BAUD, AP_TRAMP_UART_BUFSIZE_RX, AP_TRAMP_UART_BUFSIZE_TX); debug("port opened"); + AP::vtx().set_provider_enabled(AP_VideoTX::VTXType::Tramp); + return true; } return false; diff --git a/libraries/AP_VideoTX/AP_Tramp.h b/libraries/AP_VideoTX/AP_Tramp.h index 7d812cb3a5938f..bec93826770a14 100644 --- a/libraries/AP_VideoTX/AP_Tramp.h +++ b/libraries/AP_VideoTX/AP_Tramp.h @@ -38,6 +38,11 @@ // Race lock - settings can't be changed #define TRAMP_CONTROL_RACE_LOCK (0x01) +#define VTX_TRAMP_UART_BAUD 9600 +#define VTX_TRAMP_SMARTBAUD_MIN 9120 // -5% +#define VTX_TRAMP_SMARTBAUD_MAX 10080 // +5% +#define VTX_TRAMP_SMARTBAUD_STEP 120 + class AP_Tramp { public: @@ -73,6 +78,8 @@ class AP_Tramp void set_frequency(uint16_t freq); void set_power(uint16_t power); void set_pit_mode(uint8_t onoff); + // change baud automatically when request-response fails many times + void update_baud_rate(); // serial interface AP_HAL::UARTDriver *port; // UART used to send data to Tramp VTX @@ -115,6 +122,17 @@ class AP_Tramp int16_t cur_temp; uint8_t cur_control_mode; + // statistics + uint16_t _packets_sent; + uint16_t _packets_rcvd; + + // value for current baud adjust + int32_t _smartbaud = VTX_TRAMP_UART_BAUD; + enum class AutobaudDirection { + UP = 1, + DOWN = -1 + } _smartbaud_direction = AutobaudDirection::DOWN; + // Retry count uint8_t retry_count = VTX_TRAMP_MAX_RETRIES; diff --git a/libraries/AP_VideoTX/AP_VideoTX.cpp b/libraries/AP_VideoTX/AP_VideoTX.cpp index 2ccbe27996e17a..3f50914c16da2f 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.cpp +++ b/libraries/AP_VideoTX/AP_VideoTX.cpp @@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_VideoTX::var_info[] = { // @DisplayName: Video Transmitter Band // @Description: Video Transmitter Band // @User: Standard - // @Values: 0:Band A,1:Band B,2:Band E,3:Airwave,4:RaceBand,5:Low RaceBand,6:1G3 Band A,7:1G3 Band B,8:Band X + // @Values: 0:Band A,1:Band B,2:Band E,3:Airwave,4:RaceBand,5:Low RaceBand,6:1G3 Band A,7:1G3 Band B,8:Band X,9:3G3 Band A,10:3G3 Band B AP_GROUPINFO("BAND", 4, AP_VideoTX, _band, 0), // @Param: FREQ @@ -87,7 +87,7 @@ const AP_Param::GroupInfo AP_VideoTX::var_info[] = { extern const AP_HAL::HAL& hal; -const char * AP_VideoTX::band_names[] = {"A","B","E","F","R","L","1G3_A","1G3_B","X"}; +const char * AP_VideoTX::band_names[] = {"A","B","E","F","R","L","1G3_A","1G3_B","X","3G3_A","3G3_B"}; const uint16_t AP_VideoTX::VIDEO_CHANNELS[AP_VideoTX::MAX_BANDS][VTX_MAX_CHANNELS] = { @@ -99,7 +99,9 @@ const uint16_t AP_VideoTX::VIDEO_CHANNELS[AP_VideoTX::MAX_BANDS][VTX_MAX_CHANNEL { 5621, 5584, 5547, 5510, 5473, 5436, 5399, 5362}, /* LO Race */ { 1080, 1120, 1160, 1200, 1240, 1280, 1320, 1360}, /* Band 1G3_A */ { 1080, 1120, 1160, 1200, 1258, 1280, 1320, 1360}, /* Band 1G3_B */ - { 4990, 5020, 5050, 5080, 5110, 5140, 5170, 5200} /* Band X */ + { 4990, 5020, 5050, 5080, 5110, 5140, 5170, 5200}, /* Band X */ + { 3330, 3350, 3370, 3390, 3410, 3430, 3450, 3470}, /* Band 3G3_A */ + { 3170, 3190, 3210, 3230, 3250, 3270, 3290, 3310} /* Band 3G3_B */ }; // mapping of power level to milliwatt to dbm @@ -113,7 +115,7 @@ AP_VideoTX::PowerLevel AP_VideoTX::_power_levels[VTX_MAX_POWER_LEVELS] = { { 1, 200, 23, 16 }, { 0x12, 400, 26, 0xFF }, // only in SA 2.1 { 2, 500, 27, 25 }, - //{ 0x13, 600, 28, 0xFF }, + { 0x12, 600, 28, 0xFF }, // Tramp lies above power levels and always returns 25/100/200/400/600 { 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 @@ -342,13 +344,6 @@ void AP_VideoTX::update(void) return; } -#if HAL_CRSF_TELEM_ENABLED - AP_CRSF_Telem* crsf = AP::crsf_telem(); - - if (crsf != nullptr) { - crsf->update(); - } -#endif // 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)) { diff --git a/libraries/AP_VideoTX/AP_VideoTX.h b/libraries/AP_VideoTX/AP_VideoTX.h index a1321fb096a088..b544154abf6ef6 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.h +++ b/libraries/AP_VideoTX/AP_VideoTX.h @@ -21,7 +21,7 @@ #include #define VTX_MAX_CHANNELS 8 -#define VTX_MAX_POWER_LEVELS 9 +#define VTX_MAX_POWER_LEVELS 10 class AP_VideoTX { public: @@ -65,6 +65,8 @@ class AP_VideoTX { BAND_1G3_A, BAND_1G3_B, BAND_X, + BAND_3G3_A, + BAND_3G3_B, MAX_BANDS }; @@ -74,6 +76,12 @@ class AP_VideoTX { Inactive }; + enum VTXType { + CRSF = 1U<<0, + SmartAudio = 1U<<1, + Tramp = 1U<<2 + }; + struct PowerLevel { uint8_t level; uint16_t mw; @@ -164,6 +172,10 @@ class AP_VideoTX { void set_configuration_finished(bool configuration_finished) { _configuration_finished = configuration_finished; } bool is_configuration_finished() { return _configuration_finished; } + // manage VTX backends + bool is_provider_enabled(VTXType type) const { return (_types & type) != 0; } + void set_provider_enabled(VTXType type) { _types |= type; } + static AP_VideoTX *singleton; private: @@ -197,6 +209,9 @@ class AP_VideoTX { bool _defaults_set; // true when configuration have been applied successfully to the VTX bool _configuration_finished; + + // types of VTX providers + uint8_t _types; }; namespace AP { diff --git a/libraries/AP_VideoTX/AP_VideoTX_config.h b/libraries/AP_VideoTX/AP_VideoTX_config.h index c95b1a151ce094..c65141c5e6a38e 100644 --- a/libraries/AP_VideoTX/AP_VideoTX_config.h +++ b/libraries/AP_VideoTX/AP_VideoTX_config.h @@ -1,7 +1,7 @@ #pragma once #include -#include +#include #ifndef AP_VIDEOTX_ENABLED #define AP_VIDEOTX_ENABLED 1 diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.cpp b/libraries/AP_VisualOdom/AP_VisualOdom.cpp index 35c97d4875ce9c..c457627a4176bb 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom.cpp @@ -138,13 +138,13 @@ void AP_VisualOdom::init() break; #if AP_VISUALODOM_MAV_ENABLED case VisualOdom_Type::MAV: - _driver = new AP_VisualOdom_MAV(*this); + _driver = NEW_NOTHROW AP_VisualOdom_MAV(*this); break; #endif #if AP_VISUALODOM_INTELT265_ENABLED case VisualOdom_Type::IntelT265: case VisualOdom_Type::VOXL: - _driver = new AP_VisualOdom_IntelT265(*this); + _driver = NEW_NOTHROW AP_VisualOdom_IntelT265(*this); break; #endif } diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp index c26bd38b715f10..744fac017b5147 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp @@ -192,7 +192,7 @@ void AP_VisualOdom_IntelT265::align_yaw(const Vector3f &position, const Quaterni // trim yaw by difference between ahrs and sensor yaw const float yaw_trim_orig = _yaw_trim; _yaw_trim = wrap_2PI(yaw_rad - sens_yaw); - gcs().send_text(MAV_SEVERITY_INFO, "VisOdom: yaw shifted %d to %d deg", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VisOdom: yaw shifted %d to %d deg", (int)degrees(_yaw_trim - yaw_trim_orig), (int)wrap_360(degrees(sens_yaw + _yaw_trim))); @@ -349,7 +349,7 @@ void AP_VisualOdom_IntelT265::handle_voxl_camera_reset_jump(const Vector3f &sens } // warng user of reset - gcs().send_text(MAV_SEVERITY_WARNING, "VisOdom: reset"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "VisOdom: reset"); // align sensor yaw to match current yaw estimate align_yaw_to_ahrs(sensor_pos, sensor_att); diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp index fdd788b42972c1..4dac4792b3bc31 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp @@ -12,6 +12,22 @@ #include #include +#include + +#include + +// Extended Position Data Format defines -100 as 0x0080 decimal 128, we map this to a PWM of 1000 (if range is default) +#define PWM_POSITION_MIN 1000 +#define ANGLE_POSITION_MIN -100.0 +#define EXTENDED_POSITION_MIN 0x0080 + +// Extended Position Data Format defines +100 as 0x0F80 decimal 3968, we map this to a PWM of 2000 (if range is default) +#define PWM_POSITION_MAX 2000 +#define ANGLE_POSITION_MAX 100.0 +#define EXTENDED_POSITION_MAX 0x0F80 + +#define UART_BUFSIZE_RX 128 +#define UART_BUFSIZE_TX 128 extern const AP_HAL::HAL& hal; @@ -23,6 +39,12 @@ const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = { // @User: Standard AP_GROUPINFO("MASK", 1, AP_Volz_Protocol, bitmask, 0), + // @Param: RANGE + // @DisplayName: Range of travel + // @Description: Range to map between 1000 and 2000 PWM. Default value of 200 gives full +-100 deg range of extended position command. This results in 0.2 deg movement per US change in PWM. If the full range is not needed it can be reduced to increase resolution. 40 deg range gives 0.04 deg movement per US change in PWM, this is higher resolution than possible with the VOLZ protocol so further reduction in range will not improve resolution. Reduced range does allow PWMs outside the 1000 to 2000 range, with 40 deg range 750 PWM results in a angle of -30 deg, 2250 would be +30 deg. This is still limited by the 200 deg maximum range of the actuator. + // @Units: deg + AP_GROUPINFO("RANGE", 2, AP_Volz_Protocol, range, 200), + AP_GROUPEND }; @@ -35,89 +57,382 @@ AP_Volz_Protocol::AP_Volz_Protocol(void) void AP_Volz_Protocol::init(void) { - AP_SerialManager &serial_manager = AP::serialmanager(); + if (uint32_t(bitmask.get()) == 0) { + // No servos enabled + return; + } + + const AP_SerialManager &serial_manager = AP::serialmanager(); port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Volz,0); - update_volz_bitmask(bitmask); + if (port == nullptr) { + // No port configured + return; + } + + // Create thread to handle output + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Volz_Protocol::loop, void), + "Volz", + 1024, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { + AP_BoardConfig::allocation_error("Volz thread"); + } } -void AP_Volz_Protocol::update() +#if HAL_LOGGING_ENABLED +// Request telem data, cycling through each servo and telem item +void AP_Volz_Protocol::request_telem() { - if (!initialised) { - initialised = true; - init(); + // Request the queued item, making sure the servo is enabled + if ((uint32_t(bitmask.get()) & (1U<set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_RTS_DE); + port->begin(baudrate, UART_BUFSIZE_RX, UART_BUFSIZE_TX); + port->set_unbuffered_writes(true); + + // Calculate the amount of time it should take to send a command + // Multiply by 10 to convert from bit rate to byte rate (8 data bits + start and stop bits) + // B/s to s/B, 1000000 converts to microseconds, multiply by number of bytes + // 6 bytes at 11520 bytes per second takes 520 us + const uint16_t send_us = (sizeof(CMD) * 1000000 * 10) / baudrate; + + // receive packet is same length as sent, double to allow some time for the servo respond + const uint16_t receive_us = send_us * 2; + + // This gives a total time of 1560us, message rate of 641 Hz. + // One servo at 641Hz, two at 320.5 each, three at 213.7 each ect... + // Note that we send a telem request every time servo sending is complete. This is like a extra servo. + // So for a single servo position commands are at 320.5Hz and telem at 320.5Hz. + + while (port != nullptr) { + + // Wait the expected amount of time for the send and receive to complete so we don't step on the response + hal.scheduler->delay_microseconds(send_us + receive_us); + + while (port->txspace() < sizeof(CMD)) { + // Wait until there is enough space to transmit a full command + hal.scheduler->delay_microseconds(100); + } + +#if HAL_LOGGING_ENABLED + // Send a command for each servo, then one telem request + const uint8_t num_servos = __builtin_popcount(bitmask.get()); + if (sent_count < num_servos) { + send_position_cmd(); + sent_count++; + + } else { + request_telem(); + sent_count = 0; + } + + { + // Read in telem data if available + WITH_SEMAPHORE(telem.sem); + read_telem(); + } + +#else // No logging, send only + send_position_cmd(); +#endif } +} - if (last_used_bitmask != uint32_t(bitmask.get())) { - update_volz_bitmask(bitmask); +// Send postion commands from PWM, cycle through each servo +void AP_Volz_Protocol::send_position_cmd() +{ + + // loop for all channels + for (uint8_t i=0; itxspace() < VOLZ_DATA_FRAME_SIZE) { +#if HAL_LOGGING_ENABLED +void AP_Volz_Protocol::process_response(const CMD &cmd) +{ + // Convert to 0 indexed + const uint8_t index = cmd.actuator_id - 1; + if (index >= ARRAY_SIZE(telem.data)) { + // Invalid ID return; } - last_volz_update_time = now; + switch (cmd.ID) { + case CMD_ID::EXTENDED_POSITION_RESPONSE: + // Map back to angle + telem.data[index].angle = linear_interpolate(ANGLE_POSITION_MIN, ANGLE_POSITION_MAX, UINT16_VALUE(cmd.arg1, cmd.arg2), EXTENDED_POSITION_MIN, EXTENDED_POSITION_MAX); + break; + + case CMD_ID::CURRENT_RESPONSE: + // Current is reported in 20mA increments (0.02A) + telem.data[index].primary_current = cmd.arg1 * 0.02; + telem.data[index].secondary_current = cmd.arg2 * 0.02; + break; + + case CMD_ID::VOLTAGE_RESPONSE: + // Voltage is reported in 200mv increments (0.2v) + telem.data[index].primary_voltage = cmd.arg1 * 0.2; + telem.data[index].secondary_voltage = cmd.arg2 * 0.2; + break; + + case CMD_ID::TEMPERATURE_RESPONSE: + // Temperature is reported relative to -50 deg C + telem.data[index].motor_temp_deg = -50 + cmd.arg1; + telem.data[index].pcb_temp_deg = -50 + cmd.arg2; + break; + + default: + // This should never happen + return; + } - uint8_t i; - uint16_t value; + telem.data[index].last_response_ms = AP_HAL::millis(); +} - // loop for all channels - for (i=0; iget_output_pwm() < VOLZ_PWM_POSITION_MIN) { - value = 0; - } else { - value = c->get_output_pwm() - VOLZ_PWM_POSITION_MIN; + return false; +} + +void AP_Volz_Protocol::read_telem() +{ + // Try and read data a few times, this could be a while loop, using a for loop gives a upper bound to run time + for (uint8_t attempts = 0; attempts < sizeof(telem.cmd_buffer) * 4; attempts++) { + + uint32_t n = port->available(); + if (n == 0) { + // No data available + return; + } + if (telem.buffer_offset < sizeof(telem.cmd_buffer)) { + // Read enough bytes to fill buffer + ssize_t nread = port->read(&telem.cmd_buffer.data[telem.buffer_offset], MIN(n, unsigned(sizeof(telem.cmd_buffer)-telem.buffer_offset))); + if (nread <= 0) { + // Read failed + return; } + telem.buffer_offset += nread; + } - // scale the PWM value to Volz value - value = value * VOLZ_SCALE_VALUE / (VOLZ_PWM_POSITION_MAX - VOLZ_PWM_POSITION_MIN); - value = value + VOLZ_EXTENDED_POSITION_MIN; + // Check for valid response start byte + if (!is_response(telem.cmd_buffer.data[0])) { - // make sure value stays in range - if (value > VOLZ_EXTENDED_POSITION_MAX) { - value = VOLZ_EXTENDED_POSITION_MAX; + // Search for a valid response start byte + uint8_t cmd_start; + for (cmd_start = 1; cmd_start < telem.buffer_offset; cmd_start++) { + if (is_response(telem.cmd_buffer.data[cmd_start])) { + // Found one + break; + } } - // prepare Volz protocol data. - uint8_t data[VOLZ_DATA_FRAME_SIZE]; + // Shift buffer to put start on valid byte, or if no valid byte was found clear + const uint8_t n_move = telem.buffer_offset - cmd_start; + if (n_move > 0) { + // No need to move 0 bytes + memmove(&telem.cmd_buffer.data[0], &telem.cmd_buffer.data[cmd_start], n_move); + } + telem.buffer_offset = 0; - data[0] = VOLZ_SET_EXTENDED_POSITION_CMD; - data[1] = i + 1; // send actuator id as 1 based index so ch1 will have id 1, ch2 will have id 2 .... - data[2] = HIGHBYTE(value); - data[3] = LOWBYTE(value); + // Since the buffer is the same length as a full command, we can never get a valid packet after shifting + // Always need to read in some more data + continue; + } - send_command(data); + if (telem.buffer_offset < sizeof(telem.cmd_buffer)) { + // Not enough data to make up packet + continue; } + + // Have valid ID and enough data, check crc + if (UINT16_VALUE(telem.cmd_buffer.crc1, telem.cmd_buffer.crc2) != calculate_crc(telem.cmd_buffer)) { + // Probably lost sync shift by one and try again + memmove(&telem.cmd_buffer.data[0], &telem.cmd_buffer.data[1], telem.buffer_offset - 1); + telem.buffer_offset -= 1; + continue; + } + + // Valid packet passed crc check + process_response(telem.cmd_buffer); + + // zero offset and continue + telem.buffer_offset = 0; } + + // Used up all attempts without running out of data. + // Really should not end up here } +#endif // HAL_LOGGING_ENABLED -// calculate CRC for volz serial protocol and send the data. -void AP_Volz_Protocol::send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]) +// Called each time the servo outputs are sent +void AP_Volz_Protocol::update() +{ + if (!initialised) { + // One time setup + initialised = true; + init(); + } + + if (port == nullptr) { + // no point if we don't have a valid port + return; + } + + // take semaphore and loop for all channels + for (uint8_t i=0; iget_output_pwm(); + servo_pwm[i] = (pwm == 0) ? c->get_trim() : pwm; + } + +#if HAL_LOGGING_ENABLED + // take semaphore and log all channels at 5 Hz + const uint32_t now_ms = AP_HAL::millis(); + if ((now_ms - telem.last_log_ms) > 200) { + telem.last_log_ms = now_ms; + + WITH_SEMAPHORE(telem.sem); + for (uint8_t i=0; i 5000)) { + // Never seen telem, or not had a response for more than 5 seconds + continue; + } + + // @LoggerMessage: VOLZ + // @Description: Volz servo data + // @Field: TimeUS: Time since system startup + // @Field: I: Instance + // @Field: Dang: desired angle + // @Field: ang: reported angle + // @Field: pc: primary supply current + // @Field: sc: secondary supply current + // @Field: pv: primary supply voltage + // @Field: sv: secondary supply voltage + // @Field: mt: motor temperature + // @Field: pt: pcb temperature + AP::logger().WriteStreaming("VOLZ", + "TimeUS,I,Dang,ang,pc,sc,pv,sv,mt,pt", + "s#ddAAvvOO", + "F000000000", + "QBffffffhh", + AP_HAL::micros64(), + i + 1, // convert to 1 indexed to match actuator IDs and SERVOx numbering + telem.data[i].desired_angle, + telem.data[i].angle, + telem.data[i].primary_current, + telem.data[i].secondary_current, + telem.data[i].primary_voltage, + telem.data[i].secondary_voltage, + telem.data[i].motor_temp_deg, + telem.data[i].pcb_temp_deg + ); + } + } +#endif // HAL_LOGGING_ENABLED +} + +// Return the crc for a given command packet +uint16_t AP_Volz_Protocol::calculate_crc(const CMD &cmd) const { - uint8_t i,j; uint16_t crc = 0xFFFF; // calculate Volz CRC value according to protocol definition - for(i=0; i<4; i++) { + for(uint8_t i=0; i<4; i++) { // take input data into message that will be transmitted. - crc = ((data[i] << 8) ^ crc); - - for(j=0; j<8; j++) { + crc = (cmd.data[i] << 8) ^ crc; + for(uint8_t j=0; j<8; j++) { if (crc & 0x8000) { crc = (crc << 1) ^ 0x8005; } else { @@ -126,38 +441,18 @@ void AP_Volz_Protocol::send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]) } } - // add CRC result to the message - data[4] = HIGHBYTE(crc); - data[5] = LOWBYTE(crc); - port->write(data, VOLZ_DATA_FRAME_SIZE); + return crc; } -void AP_Volz_Protocol::update_volz_bitmask(uint32_t new_bitmask) +// calculate CRC for volz serial protocol and send the data. +void AP_Volz_Protocol::send_command(CMD &cmd) { - uint8_t count = 0; - last_used_bitmask = new_bitmask; + const uint16_t crc = calculate_crc(cmd); - for (uint8_t i=0; iwrite(cmd.data, sizeof(cmd)); } #endif // AP_VOLZ_ENABLED diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h index c4f5705bd0db44..f14df3023090d0 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h @@ -43,18 +43,9 @@ #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 -#define VOLZ_DATA_FRAME_SIZE 6 - -#define VOLZ_EXTENDED_POSITION_MIN 0x0080 // Extended Position Data Format defines -100 as 0x0080 decimal 128 -#define VOLZ_EXTENDED_POSITION_CENTER 0x0800 // Extended Position Data Format defines 0 as 0x0800 - decimal 2048 -#define VOLZ_EXTENDED_POSITION_MAX 0x0F80 // Extended Position Data Format defines +100 as 0x0F80 decimal 3968 -> full range decimal 3840 - -#define VOLZ_PWM_POSITION_MIN 1000 -#define VOLZ_PWM_POSITION_MAX 2000 class AP_Volz_Protocol { public: @@ -64,22 +55,98 @@ class AP_Volz_Protocol { CLASS_NO_COPY(AP_Volz_Protocol); static const struct AP_Param::GroupInfo var_info[]; - + void update(); private: + + // Command and response IDs + enum class CMD_ID : uint8_t { + SET_EXTENDED_POSITION = 0xDC, + EXTENDED_POSITION_RESPONSE = 0x2C, + READ_CURRENT = 0xB0, + CURRENT_RESPONSE = 0x30, + READ_VOLTAGE = 0xB1, + VOLTAGE_RESPONSE = 0x31, + READ_TEMPERATURE = 0xC0, + TEMPERATURE_RESPONSE = 0x10, + }; + + // Command frame + union CMD { + struct PACKED { + CMD_ID ID; + uint8_t actuator_id; // actuator send to or receiving from + uint8_t arg1; // CMD dependant argument 1 + uint8_t arg2; // CMD dependant argument 2 + uint8_t crc1; + uint8_t crc2; + }; + uint8_t data[6]; + }; + AP_HAL::UARTDriver *port; - + + // Loop in thread to output to uart + void loop(); + uint8_t sent_count; + void init(void); - void send_command(uint8_t data[VOLZ_DATA_FRAME_SIZE]); - void update_volz_bitmask(uint32_t new_bitmask); - uint32_t last_volz_update_time; - uint32_t volz_time_frame_micros; - uint32_t last_used_bitmask; + // Return the crc for a given command packet + uint16_t calculate_crc(const CMD &cmd) const; + + // calculate CRC for volz serial protocol and send the data. + void send_command(CMD &cmd); + + // Incoming PWM commands from the servo lib + uint16_t servo_pwm[NUM_SERVO_CHANNELS]; + + // Send postion commands from PWM, cycle through each servo + void send_position_cmd(); + uint8_t last_sent_index; AP_Int32 bitmask; + AP_Int16 range; bool initialised; + +#if HAL_LOGGING_ENABLED + // Request telem data, cycling through each servo and telem item + void request_telem(); + + // Return true if the given ID is a valid response + bool is_response(uint8_t ID) const; + + // Reading of telem packets + void read_telem(); + void process_response(const CMD &cmd); + + struct { + CMD_ID types[3] { + CMD_ID::READ_CURRENT, + CMD_ID::READ_VOLTAGE, + CMD_ID::READ_TEMPERATURE, + }; + uint8_t actuator_id; + uint8_t request_type; + HAL_Semaphore sem; + CMD cmd_buffer; + uint8_t buffer_offset; + struct { + uint32_t last_response_ms; + float desired_angle; + float angle; + float primary_current; + float secondary_current; + float primary_voltage; + float secondary_voltage; + int16_t motor_temp_deg; + int16_t pcb_temp_deg; + } data[NUM_SERVO_CHANNELS]; + uint32_t last_log_ms; + } telem; +#endif + }; #endif // AP_VOLZ_PROTOCOL diff --git a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp index 610a7cd8e2bd7e..fffe1ae9a51d64 100644 --- a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp @@ -168,13 +168,13 @@ void AP_WheelEncoder::init(void) case WheelEncoder_TYPE_QUADRATURE: #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - drivers[i] = new AP_WheelEncoder_Quadrature(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_WheelEncoder_Quadrature(*this, i, state[i]); #endif break; case WheelEncoder_TYPE_SITL_QUADRATURE: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - drivers[i] = new AP_WheelEncoder_SITL_Quadrature(*this, i, state[i]); + drivers[i] = NEW_NOTHROW AP_WheelEncoder_SITL_Quadrature(*this, i, state[i]); #endif break; diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.h b/libraries/AP_WheelEncoder/AP_WheelRateControl.h index f62d981bfb6863..2ce4597360cb42 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.h +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.h @@ -29,7 +29,6 @@ #define AP_WHEEL_RATE_CONTROL_IMAX 1.00f #define AP_WHEEL_RATE_CONTROL_D 0.01f #define AP_WHEEL_RATE_CONTROL_FILT 0.00f -#define AP_WHEEL_RATE_CONTROL_DT 0.02f #define AP_WHEEL_RATE_CONTROL_TIMEOUT_MS 200 class AP_WheelRateControl { @@ -61,8 +60,22 @@ class AP_WheelRateControl { // parameters AP_Int8 _enabled; // top level enable/disable control AP_Float _rate_max; // wheel maximum rotation rate in rad/s - AC_PID _rate_pid0{AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT}; - AC_PID _rate_pid1{AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT}; + + const AC_PID::Defaults rate_pid_defaults { + .p = AP_WHEEL_RATE_CONTROL_P, + .i = AP_WHEEL_RATE_CONTROL_I, + .d = AP_WHEEL_RATE_CONTROL_D, + .ff = AP_WHEEL_RATE_CONTROL_FF, + .imax = AP_WHEEL_RATE_CONTROL_IMAX, + .filt_T_hz = AP_WHEEL_RATE_CONTROL_FILT, + .filt_E_hz = AP_WHEEL_RATE_CONTROL_FILT, + .filt_D_hz = AP_WHEEL_RATE_CONTROL_FILT, + .srmax = 0, + .srtau = 1.0 + }; + + AC_PID _rate_pid0{rate_pid_defaults}; + AC_PID _rate_pid1{rate_pid_defaults}; // limit flags struct AP_MotorsUGV_limit { diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index 5738fdfea957b0..613679ceec5f7f 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -78,12 +78,16 @@ void AP_Winch::init() switch ((WinchType)config.type.get()) { case WinchType::NONE: break; +#if AP_WINCH_PWM_ENABLED case WinchType::PWM: - backend = new AP_Winch_PWM(config); + backend = NEW_NOTHROW AP_Winch_PWM(config); break; +#endif +#if AP_WINCH_DAIWA_ENABLED case WinchType::DAIWA: - backend = new AP_Winch_Daiwa(config); + backend = NEW_NOTHROW AP_Winch_Daiwa(config); break; +#endif default: break; } diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index 7d336a41c570c2..9d417713b64cb2 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -209,23 +209,23 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) #if AP_WINDVANE_HOME_ENABLED case WindVaneType::WINDVANE_HOME_HEADING: case WindVaneType::WINDVANE_PWM_PIN: - _direction_driver = new AP_WindVane_Home(*this); + _direction_driver = NEW_NOTHROW AP_WindVane_Home(*this); break; #endif #if AP_WINDVANE_ANALOG_ENABLED case WindVaneType::WINDVANE_ANALOG_PIN: - _direction_driver = new AP_WindVane_Analog(*this); + _direction_driver = NEW_NOTHROW AP_WindVane_Analog(*this); break; #endif #if AP_WINDVANE_SIM_ENABLED case WindVaneType::WINDVANE_SITL_TRUE: case WindVaneType::WINDVANE_SITL_APPARENT: - _direction_driver = new AP_WindVane_SITL(*this); + _direction_driver = NEW_NOTHROW AP_WindVane_SITL(*this); break; #endif #if AP_WINDVANE_NMEA_ENABLED case WindVaneType::WINDVANE_NMEA: - _direction_driver = new AP_WindVane_NMEA(*this); + _direction_driver = NEW_NOTHROW AP_WindVane_NMEA(*this); _direction_driver->init(serial_manager); break; #endif @@ -237,12 +237,12 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) break; #if AP_WINDVANE_AIRSPEED_ENABLED case Speed_type::WINDSPEED_AIRSPEED: - _speed_driver = new AP_WindVane_Airspeed(*this); + _speed_driver = NEW_NOTHROW AP_WindVane_Airspeed(*this); break; #endif #if AP_WINDVANE_MODERNDEVICE_ENABLED case Speed_type::WINDVANE_WIND_SENSOR_REV_P: - _speed_driver = new AP_WindVane_ModernDevice(*this); + _speed_driver = NEW_NOTHROW AP_WindVane_ModernDevice(*this); break; #endif #if AP_WINDVANE_SIM_ENABLED @@ -250,7 +250,7 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) case Speed_type::WINDSPEED_SITL_APPARENT: // single driver does both speed and direction if (_direction_type != _speed_sensor_type) { - _speed_driver = new AP_WindVane_SITL(*this); + _speed_driver = NEW_NOTHROW AP_WindVane_SITL(*this); } else { _speed_driver = _direction_driver; } @@ -260,7 +260,7 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) case Speed_type::WINDSPEED_NMEA: // single driver does both speed and direction if (_direction_type != WindVaneType::WINDVANE_NMEA) { - _speed_driver = new AP_WindVane_NMEA(*this); + _speed_driver = NEW_NOTHROW AP_WindVane_NMEA(*this); _speed_driver->init(serial_manager); } else { _speed_driver = _direction_driver; @@ -269,7 +269,7 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) #endif // AP_WINDVANE_NMEA_ENABLED #if AP_WINDVANE_RPM_ENABLED case Speed_type::WINDSPEED_RPM: - _speed_driver = new AP_WindVane_RPM(*this); + _speed_driver = NEW_NOTHROW AP_WindVane_RPM(*this); break; #endif } diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index b211384e1cb9d2..4b63101d5f5bb2 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -33,7 +33,7 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = { // @Values: 0:Normal,1:OneShot,2:OneShot125,3:BrushedWithRelay,4:BrushedBiPolar,5:DShot150,6:DShot300,7:DShot600,8:DShot1200 // @User: Advanced // @RebootRequired: True - AP_GROUPINFO("PWM_TYPE", 1, AP_MotorsUGV, _pwm_type, PWM_TYPE_NORMAL), + AP_GROUPINFO("PWM_TYPE", 1, AP_MotorsUGV, _pwm_type, PWMType::NORMAL), // @Param: PWM_FREQ // @DisplayName: Motor Output PWM freq for brushed motors @@ -149,7 +149,7 @@ void AP_MotorsUGV::init(uint8_t frtype) bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t &index3, int8_t &index4) const { - if (_pwm_type != PWM_TYPE_BRUSHED_WITH_RELAY) { + if (_pwm_type != PWMType::BRUSHED_WITH_RELAY) { // Relays only used if PWM type is set to brushed with relay return false; } @@ -177,7 +177,7 @@ bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t // setup output in case of main CPU failure void AP_MotorsUGV::setup_safety_output() { - if (_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) { + if (_pwm_type == PWMType::BRUSHED_WITH_RELAY) { // set trim to min to set duty cycle range (0 - 100%) to servo range // ignore servo revese flag, it is used by the relay SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttle, true); @@ -340,10 +340,11 @@ void AP_MotorsUGV::output(bool armed, float ground_speed, float dt) output_sail(); // send values to the PWM timers for output + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - SRV_Channels::push(); + srv.push(); } // test steering or throttle output as a percentage of the total (range -100 to +100) @@ -408,10 +409,11 @@ bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct) case MOTOR_TEST_LAST: return false; } + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - SRV_Channels::push(); + srv.push(); return true; } @@ -474,10 +476,11 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm) default: return false; } + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - SRV_Channels::push(); + srv.push(); return true; } @@ -529,7 +532,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const // Check relays are configured for brushed with relay outputs #if AP_RELAY_ENABLED AP_Relay*relay = AP::relay(); - if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) { + if ((_pwm_type == PWMType::BRUSHED_WITH_RELAY) && (relay != nullptr)) { // If a output is configured its relay must be enabled struct RelayTable { bool output_assigned; @@ -546,7 +549,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const for (uint8_t i=0; ienabled(relay_table[i].fun)) { if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: relay function %u unassigned", uint8_t(relay_table[i].fun)); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: relay function %u unassigned", uint8_t(relay_table[i].fun)); } return false; } @@ -581,27 +584,27 @@ void AP_MotorsUGV::setup_pwm_type() } switch (_pwm_type) { - case PWM_TYPE_ONESHOT: + case PWMType::ONESHOT: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); break; - case PWM_TYPE_ONESHOT125: + case PWMType::ONESHOT125: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125); break; - case PWM_TYPE_BRUSHED_WITH_RELAY: - case PWM_TYPE_BRUSHED_BIPOLAR: + case PWMType::BRUSHED_WITH_RELAY: + case PWMType::BRUSHED_BIPOLAR: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED); hal.rcout->set_freq(_motor_mask, uint16_t(_pwm_freq * 1000)); break; - case PWM_TYPE_DSHOT150: + case PWMType::DSHOT150: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150); break; - case PWM_TYPE_DSHOT300: + case PWMType::DSHOT300: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300); break; - case PWM_TYPE_DSHOT600: + case PWMType::DSHOT600: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600); break; - case PWM_TYPE_DSHOT1200: + case PWMType::DSHOT1200: hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200); break; default: @@ -647,6 +650,13 @@ void AP_MotorsUGV::setup_omni() add_omni_motor(2, 0.0f, -1.0f, 1.0f); add_omni_motor(3, 1.0f, 0.0f, 0.0f); break; + + case FRAME_TYPE_OMNI3MECANUM: + _motors_num = 3; + add_omni_motor(0, -1.0f, 1.0f, -0.26795f); + add_omni_motor(1, 0.73205f, 1.0f, -0.73205f); + add_omni_motor(2, 0.26795f, 1.0f, 1.0f); + break; } } @@ -981,7 +991,7 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f // set relay if necessary #if AP_RELAY_ENABLED AP_Relay*relay = AP::relay(); - if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) { + if ((_pwm_type == PWMType::BRUSHED_WITH_RELAY) && (relay != nullptr)) { // find the output channel, if not found return const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function); @@ -1146,17 +1156,17 @@ bool AP_MotorsUGV::active() const bool AP_MotorsUGV::is_digital_pwm_type() const { switch (_pwm_type) { - case PWM_TYPE_DSHOT150: - case PWM_TYPE_DSHOT300: - case PWM_TYPE_DSHOT600: - case PWM_TYPE_DSHOT1200: - return true; - case PWM_TYPE_NORMAL: - case PWM_TYPE_ONESHOT: - case PWM_TYPE_ONESHOT125: - case PWM_TYPE_BRUSHED_WITH_RELAY: - case PWM_TYPE_BRUSHED_BIPOLAR: - break; + case PWMType::DSHOT150: + case PWMType::DSHOT300: + case PWMType::DSHOT600: + case PWMType::DSHOT1200: + return true; + case PWMType::NORMAL: + case PWMType::ONESHOT: + case PWMType::ONESHOT125: + case PWMType::BRUSHED_WITH_RELAY: + case PWMType::BRUSHED_BIPOLAR: + break; } return false; } diff --git a/libraries/AR_Motors/AP_MotorsUGV.h b/libraries/AR_Motors/AP_MotorsUGV.h index 42c2df5377ae98..45df9fe2b526a2 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.h +++ b/libraries/AR_Motors/AP_MotorsUGV.h @@ -27,6 +27,7 @@ class AP_MotorsUGV { FRAME_TYPE_OMNI3 = 1, FRAME_TYPE_OMNIX = 2, FRAME_TYPE_OMNIPLUS = 3, + FRAME_TYPE_OMNI3MECANUM = 4, }; // initialise motors @@ -130,16 +131,16 @@ class AP_MotorsUGV { private: - enum pwm_type { - PWM_TYPE_NORMAL = 0, - PWM_TYPE_ONESHOT = 1, - PWM_TYPE_ONESHOT125 = 2, - PWM_TYPE_BRUSHED_WITH_RELAY = 3, - PWM_TYPE_BRUSHED_BIPOLAR = 4, - PWM_TYPE_DSHOT150 = 5, - PWM_TYPE_DSHOT300 = 6, - PWM_TYPE_DSHOT600 = 7, - PWM_TYPE_DSHOT1200 = 8 + enum PWMType { + NORMAL = 0, + ONESHOT = 1, + ONESHOT125 = 2, + BRUSHED_WITH_RELAY = 3, + BRUSHED_BIPOLAR = 4, + DSHOT150 = 5, + DSHOT300 = 6, + DSHOT600 = 7, + DSHOT1200 = 8 }; // sanity check parameters diff --git a/libraries/AR_WPNav/AR_WPNav.cpp b/libraries/AR_WPNav/AR_WPNav.cpp index d87837ffa01b70..cd39be26b71238 100644 --- a/libraries/AR_WPNav/AR_WPNav.cpp +++ b/libraries/AR_WPNav/AR_WPNav.cpp @@ -88,9 +88,9 @@ const AP_Param::GroupInfo AR_WPNav::var_info[] = { }; AR_WPNav::AR_WPNav(AR_AttitudeControl& atc, AR_PosControl &pos_control) : + _pivot(atc), _atc(atc), - _pos_control(pos_control), - _pivot(atc) + _pos_control(pos_control) { AP_Param::setup_object_defaults(this, var_info); } diff --git a/libraries/Filter/AP_Filter.cpp b/libraries/Filter/AP_Filter.cpp index 3e2763141ac18c..072e0513c9d011 100644 --- a/libraries/Filter/AP_Filter.cpp +++ b/libraries/Filter/AP_Filter.cpp @@ -117,7 +117,7 @@ void AP_Filters::update() break; case AP_Filter::FilterType::FILTER_NOTCH: if (filters[i] == nullptr) { - filters[i] = new AP_NotchFilter_params(); + filters[i] = NEW_NOTHROW AP_NotchFilter_params(); backend_var_info[i] = AP_NotchFilter_params::var_info; update = true; } diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index a710de35daa7c3..c98a50eeac4ea0 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -125,7 +125,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { // @Param: OPTS // @DisplayName: Harmonic Notch Filter options // @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. Multi-Source 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:Multi-Source,2:Update at loop rate,3:EnableOnAllIMUs,4:Triple notch, 5:Use min freq on RPM failure + // @Bitmask: 0:Double notch,1:Multi-Source,2:Update at loop rate,3:EnableOnAllIMUs,4:Triple notch, 5:Use min freq on RPM source failure // @User: Advanced // @RebootRequired: True AP_GROUPINFO("OPTS", 8, HarmonicNotchFilterParams, _options, 0), @@ -191,6 +191,11 @@ void HarmonicNotchFilter::init(float sample_freq_hz, HarmonicNotchFilterParam NotchFilter::calculate_A_and_Q(center_freq_hz, bandwidth_hz / _composite_notches, attenuation_dB, _A, _Q); _initialised = true; + + // ensure static notches are allocated and working + if (params->tracking_mode() == HarmonicNotchDynamicMode::Fixed) { + update(center_freq_hz); + } } /* @@ -205,7 +210,7 @@ void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint32_t harm _harmonics = harmonics; if (_num_filters > 0) { - _filters = new NotchFilter[_num_filters]; + _filters = NEW_NOTHROW NotchFilter[_num_filters]; if (_filters == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Failed to allocate %u bytes for notch filter", (unsigned int)(_num_filters * sizeof(NotchFilter))); _num_filters = 0; @@ -231,7 +236,7 @@ void HarmonicNotchFilter::expand_filter_count(uint16_t total_notches) note that we rely on the semaphore in AP_InertialSensor_Backend.cpp to make this thread safe */ - auto filters = new NotchFilter[total_notches]; + auto filters = NEW_NOTHROW NotchFilter[total_notches]; if (filters == nullptr) { _alloc_has_failed = true; return; @@ -515,7 +520,7 @@ HarmonicNotchFilterParams::HarmonicNotchFilterParams(void) void HarmonicNotchFilterParams::init() { - _harmonics.convert_parameter_width(AP_PARAM_INT8); + _harmonics.convert_bitmask_parameter_width(AP_PARAM_INT8); } /* diff --git a/libraries/Filter/LowPassFilter.cpp b/libraries/Filter/LowPassFilter.cpp index e4f741b93431df..d18cdd00b4d0fc 100644 --- a/libraries/Filter/LowPassFilter.cpp +++ b/libraries/Filter/LowPassFilter.cpp @@ -1,8 +1,6 @@ // /// @file LowPassFilter.cpp -/// @brief A class to implement a low pass filter without losing precision even for int types -/// the downside being that it's a little slower as it internally uses a float -/// and it consumes an extra 4 bytes of memory to hold the constant gain +/// @brief A class to implement a low pass filter #ifndef HAL_DEBUG_BUILD #define AP_INLINE_VECTOR_OPS @@ -12,134 +10,121 @@ #include //////////////////////////////////////////////////////////////////////////////////////////// -// DigitalLPF +// DigitalLPF, base class //////////////////////////////////////////////////////////////////////////////////////////// template DigitalLPF::DigitalLPF() { // built in initialization - _output = T(); + output = T(); } // 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 (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; +T DigitalLPF::_apply(const T &sample, const float &alpha) { + output += (sample - output) * alpha; if (!initialised) { initialised = true; - _output = sample; - } - return _output; -} - -template -T DigitalLPF::apply(const T &sample) { - _output += (sample - _output) * alpha; - if (!initialised) { - initialised = true; - _output = sample; - } - return _output; -} - -template -void DigitalLPF::compute_alpha(float sample_freq, float cutoff_freq) { - if (sample_freq <= 0) { - alpha = 1; - } else { - alpha = calc_lowpass_alpha_dt(1.0/sample_freq, cutoff_freq); + output = sample; } + return output; } // get latest filtered value from filter (equal to the value returned by latest call to apply method) template const T &DigitalLPF::get() const { - return _output; + return output; } +// Reset filter to given value template -void DigitalLPF::reset(T value) { - _output = value; +void DigitalLPF::reset(const T &value) { + output = value; initialised = true; } - -//////////////////////////////////////////////////////////////////////////////////////////// -// LowPassFilter -//////////////////////////////////////////////////////////////////////////////////////////// -// constructors +// Set reset flag such that the filter will be reset to the next value applied template -LowPassFilter::LowPassFilter() : - _cutoff_freq(0.0f) {} +void DigitalLPF::reset() { + initialised = false; +} -template -LowPassFilter::LowPassFilter(float cutoff_freq) : - _cutoff_freq(cutoff_freq) {} +template class DigitalLPF; +template class DigitalLPF; +template class DigitalLPF; +//////////////////////////////////////////////////////////////////////////////////////////// +// Low pass filter with constant time step +//////////////////////////////////////////////////////////////////////////////////////////// + +// constructor template -LowPassFilter::LowPassFilter(float sample_freq, float cutoff_freq) +LowPassFilterConstDt::LowPassFilterConstDt(const float &sample_freq, const float &new_cutoff_freq) { - set_cutoff_frequency(sample_freq, cutoff_freq); + set_cutoff_frequency(sample_freq, new_cutoff_freq); } // change parameters template -void LowPassFilter::set_cutoff_frequency(float cutoff_freq) { - _cutoff_freq = cutoff_freq; +void LowPassFilterConstDt::set_cutoff_frequency(const float &sample_freq, const float &new_cutoff_freq) { + cutoff_freq = new_cutoff_freq; + + if (sample_freq <= 0) { + alpha = 1; + } else { + alpha = calc_lowpass_alpha_dt(1.0/sample_freq, cutoff_freq); + } } +// return the cutoff frequency template -void LowPassFilter::set_cutoff_frequency(float sample_freq, float cutoff_freq) { - _cutoff_freq = cutoff_freq; - _filter.compute_alpha(sample_freq, cutoff_freq); +float LowPassFilterConstDt::get_cutoff_freq(void) const { + return cutoff_freq; } -// return the cutoff frequency +// add a new raw value to the filter, retrieve the filtered result template -float LowPassFilter::get_cutoff_freq(void) const { - return _cutoff_freq; +T LowPassFilterConstDt::apply(const T &sample) { + return this->_apply(sample, alpha); } +template class LowPassFilterConstDt; +template class LowPassFilterConstDt; +template class LowPassFilterConstDt; + +//////////////////////////////////////////////////////////////////////////////////////////// +// Low pass filter with variable time step +//////////////////////////////////////////////////////////////////////////////////////////// + template -T LowPassFilter::apply(T sample, float dt) { - return _filter.apply(sample, _cutoff_freq, dt); +LowPassFilter::LowPassFilter(const float &new_cutoff_freq) +{ + set_cutoff_frequency(new_cutoff_freq); } +// change parameters template -T LowPassFilter::apply(T sample) { - return _filter.apply(sample); +void LowPassFilter::set_cutoff_frequency(const float &new_cutoff_freq) { + cutoff_freq = new_cutoff_freq; } +// return the cutoff frequency template -const T &LowPassFilter::get() const { - return _filter.get(); +float LowPassFilter::get_cutoff_freq() const { + return cutoff_freq; } +// add a new raw value to the filter, retrieve the filtered result template -void LowPassFilter::reset(T value) { - _filter.reset(value); +T LowPassFilter::apply(const T &sample, const float &dt) { + const float alpha = calc_lowpass_alpha_dt(dt, cutoff_freq); + return this->_apply(sample, alpha); } /* * Make an instances * Otherwise we have to move the constructor implementations to the header file :P */ -template class LowPassFilter; -template class LowPassFilter; template class LowPassFilter; template class LowPassFilter; template class LowPassFilter; diff --git a/libraries/Filter/LowPassFilter.h b/libraries/Filter/LowPassFilter.h index 497d0ddf976e7f..3106bc14aeabf4 100644 --- a/libraries/Filter/LowPassFilter.h +++ b/libraries/Filter/LowPassFilter.h @@ -15,14 +15,12 @@ // /// @file LowPassFilter.h -/// @brief A class to implement a low pass filter without losing precision even for int types -/// the downside being that it's a little slower as it internally uses a float -/// and it consumes an extra 4 bytes of memory to hold the constant gain +/// @brief A class to implement a low pass filter. /* - Note that this filter can be used in 2 ways: + Two classes are provided: - 1) providing dt on every sample, and calling apply like this: + LowPassFilter: providing dt on every sample, and calling apply like this: // call once filter.set_cutoff_frequency(frequency_hz); @@ -30,7 +28,7 @@ // then on each sample output = filter.apply(sample, dt); - 2) providing a sample freq and cutoff_freq once at start + LowPassFilterConstDt: providing a sample freq and cutoff_freq once at start // call once filter.set_cutoff_frequency(sample_freq, frequency_hz); @@ -45,79 +43,89 @@ #pragma once #include -#include "FilterClass.h" // DigitalLPF implements the filter math template class DigitalLPF { public: + + // constructor DigitalLPF(); - // add a new raw value to the filter, retrieve the filtered result - T apply(const T &sample, float cutoff_freq, float dt); - T apply(const T &sample); CLASS_NO_COPY(DigitalLPF); - void compute_alpha(float sample_freq, float cutoff_freq); - // get latest filtered value from filter (equal to the value returned by latest call to apply method) const T &get() const; - void reset(T value); - void reset() { - initialised = false; - } + + // Reset filter to given value + void reset(const T &value); + + // Set reset flag such that the filter will be reset to the next value applied + void reset(); + +protected: + // add a new raw value to the filter, retrieve the filtered result + T _apply(const T &sample, const float &alpha); private: - T _output; - float alpha = 1.0f; + T output; bool initialised; }; -// LPF base class +// Low pass filter with constant time step template -class LowPassFilter { +class LowPassFilterConstDt : public DigitalLPF { public: - LowPassFilter(); - LowPassFilter(float cutoff_freq); - LowPassFilter(float sample_freq, float cutoff_freq); - CLASS_NO_COPY(LowPassFilter); + // constructors + LowPassFilterConstDt() {}; + LowPassFilterConstDt(const float &sample_freq, const float &cutoff_freq); + + CLASS_NO_COPY(LowPassFilterConstDt); // change parameters - void set_cutoff_frequency(float cutoff_freq); - void set_cutoff_frequency(float sample_freq, float cutoff_freq); + void set_cutoff_frequency(const float &sample_freq, const float &cutoff_freq); // return the cutoff frequency - float get_cutoff_freq(void) const; - T apply(T sample, float dt); - T apply(T sample); - const T &get() const; - void reset(T value); - void reset(void) { _filter.reset(); } + float get_cutoff_freq() const; -protected: - float _cutoff_freq; + // add a new raw value to the filter, retrieve the filtered result + T apply(const T &sample); private: - DigitalLPF _filter; + float cutoff_freq; + float alpha; }; -// Uncomment this, if you decide to remove the instantiations in the implementation file -/* -template -LowPassFilter::LowPassFilter() : _cutoff_freq(0.0f) { - -} -// constructor +typedef LowPassFilterConstDt LowPassFilterConstDtFloat; +typedef LowPassFilterConstDt LowPassFilterConstDtVector2f; +typedef LowPassFilterConstDt LowPassFilterConstDtVector3f; + +// Low pass filter with variable time step template -LowPassFilter::LowPassFilter(float cutoff_freq) : _cutoff_freq(cutoff_freq) { - -} -*/ +class LowPassFilter : public DigitalLPF { +public: + + // constructors + LowPassFilter() {}; + LowPassFilter(const float &cutoff_freq); + + CLASS_NO_COPY(LowPassFilter); + + // change parameters + void set_cutoff_frequency(const float &cutoff_freq); + + // return the cutoff frequency + float get_cutoff_freq() const; + + // add a new raw value to the filter, retrieve the filtered result + T apply(const T &sample, const float &dt); + +private: + float cutoff_freq; +}; // typedefs for compatibility -typedef LowPassFilter LowPassFilterInt; -typedef LowPassFilter LowPassFilterLong; typedef LowPassFilter LowPassFilterFloat; typedef LowPassFilter LowPassFilterVector2f; typedef LowPassFilter LowPassFilterVector3f; diff --git a/libraries/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index dbbec6f80a802b..29a531ef009f66 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -19,6 +19,7 @@ #endif #include "NotchFilter.h" +#include const static float NOTCH_MAX_SLEW = 0.05f; const static float NOTCH_MAX_SLEW_LOWER = 1.0f - NOTCH_MAX_SLEW; @@ -45,13 +46,11 @@ template void NotchFilter::init(float sample_freq_hz, float center_freq_hz, float bandwidth_hz, float attenuation_dB) { // check center frequency is in the allowable range + initialised = false; 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 { - initialised = false; } } @@ -135,6 +134,15 @@ void NotchFilter::reset() need_reset = true; } +#if HAL_LOGGING_ENABLED +// return the frequency to log for the notch +template +float NotchFilter::logging_frequency() const +{ + return initialised ? _center_freq_hz : AP::logger().quiet_nanf(); +} +#endif + /* instantiate template classes */ diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index 9f2e49c66acb6e..811f7800fccf5a 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -49,9 +49,7 @@ class NotchFilter { } // return the frequency to log for the notch - float logging_frequency(void) const { - return initialised?_center_freq_hz:0; - } + float logging_frequency(void) const; protected: diff --git a/libraries/Filter/examples/TransferFunctionCheck/FilterTest.m b/libraries/Filter/examples/TransferFunctionCheck/FilterTest.m index bef9f6e0cb80e7..73520f35b93e16 100644 --- a/libraries/Filter/examples/TransferFunctionCheck/FilterTest.m +++ b/libraries/Filter/examples/TransferFunctionCheck/FilterTest.m @@ -5,7 +5,7 @@ % File generated by the TransferFunctionCheck example filename = "test.csv"; -% There are some anoying warnings for text parsing and matrix solve +% There are some annoying warnings for text parsing and matrix solve warning('off','MATLAB:rankDeficientMatrix'); warning('off','MATLAB:table:ModifiedAndSavedVarnames'); @@ -21,6 +21,10 @@ % Try and work out types filters = {}; +filter_index = find(startsWith(lines,"LowPassFilterConstDtFloat")); +for i = 1:numel(filter_index) + filters{end+1} = parse_low_pass(lines, filter_index(i)); %#ok +end filter_index = find(startsWith(lines,"LowPassFilterFloat")); for i = 1:numel(filter_index) filters{end+1} = parse_low_pass(lines, filter_index(i)); %#ok @@ -102,7 +106,7 @@ end -% Caculalte using transfer function +% Calculate using transfer function Z = exp(1i*pi*(freq/(sample_freq*0.5))); for i = numel(filters):-1:1 @@ -113,7 +117,7 @@ % multiply all transfer functions together H_all = prod(H,2); -% Extract anmpitude and phase from transfer function +% Extract amplitude and phase from transfer function calc_amplitude = abs(H_all); calc_phase = atan2d(imag(H_all),real(H_all)); @@ -142,8 +146,9 @@ ylabel('phase') function ret = parse_low_pass(lines, start_index) - if ~startsWith(lines(start_index),"LowPassFilterFloat") - error("Expecting LowPassFilterFloat") + found = startsWith(lines(start_index),"LowPassFilterFloat") || startsWith(lines(start_index),"LowPassFilterConstDtFloat"); + if ~found + error("Expecting LowPassFilterConstDtFloat or LowPassFilterFloat") end % Next line gives sample rate and cutoff diff --git a/libraries/Filter/examples/TransferFunctionCheck/TransferFunctionCheck.cpp b/libraries/Filter/examples/TransferFunctionCheck/TransferFunctionCheck.cpp index 320f0b44562a41..16d310914bbcbe 100644 --- a/libraries/Filter/examples/TransferFunctionCheck/TransferFunctionCheck.cpp +++ b/libraries/Filter/examples/TransferFunctionCheck/TransferFunctionCheck.cpp @@ -16,20 +16,20 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // Some helper classes to allow accessing protected variables, also useful for adding type specific prints -class LowPassHelper : public LowPassFilterFloat { +class LowPassConstDtHelper : public LowPassFilterConstDtFloat { public: - using LowPassFilterFloat::LowPassFilterFloat; + using LowPassFilterConstDtFloat::LowPassFilterConstDtFloat; - void set_cutoff_frequency_override(float sample_freq, float cutoff_freq) { + void set_cutoff_frequency_override(float sample_freq, float new_cutoff_freq) { // Stash the sample rate so we can use it later _sample_freq = sample_freq; - set_cutoff_frequency(sample_freq, cutoff_freq); + set_cutoff_frequency(sample_freq, new_cutoff_freq); } // Were really cheating here and using the same method as the filter to get the coefficient // rather than pulling the coefficient directly void print_transfer_function() { - hal.console->printf("LowPassFilterFloat\n"); + hal.console->printf("LowPassFilterConstDtFloat\n"); hal.console->printf("Sample rate: %.9f Hz, Cutoff: %.9f Hz\n", _sample_freq, get_cutoff_freq()); hal.console->printf("Low pass filter in the form: H(z) = a/(1-(1-a)*z^-1)\n"); hal.console->printf("a: %.9f\n", calc_lowpass_alpha_dt(1.0/_sample_freq, get_cutoff_freq())); @@ -39,6 +39,33 @@ class LowPassHelper : public LowPassFilterFloat { float _sample_freq; }; +class LowPassHelper : public LowPassFilterFloat { +public: + using LowPassFilterFloat::LowPassFilterFloat; + + void set_cutoff_frequency_override(float sample_freq, float new_cutoff_freq) { + // Stash the DT so we can use it later + _DT = 1.0 / sample_freq; + set_cutoff_frequency(new_cutoff_freq); + } + + // Were really cheating here and using the same method as the filter to get the coefficient + // rather than pulling the coefficient directly + void print_transfer_function() { + hal.console->printf("LowPassFilterFloat\n"); + hal.console->printf("Sample rate: %.9f Hz, Cutoff: %.9f Hz\n", 1.0 / _DT, get_cutoff_freq()); + hal.console->printf("Low pass filter in the form: H(z) = a/(1-(1-a)*z^-1)\n"); + hal.console->printf("a: %.9f\n", calc_lowpass_alpha_dt(_DT, get_cutoff_freq())); + } + + float apply_override(const float sample) { + return apply(sample, _DT); + } + +private: + float _DT; +}; + class LowPass2pHelper : public LowPassFilter2pFloat { public: using LowPassFilter2pFloat::LowPassFilter2pFloat; @@ -67,12 +94,14 @@ class NotchHelper : public NotchFilterFloat { // create an instance each filter to test +LowPassConstDtHelper lowpassConstDt; LowPassHelper lowpass; LowPass2pHelper biquad; NotchHelper notch; NotchHelper notch2; enum class filter_type { + LowPassConstDT, LowPass, Biquad, Notch, @@ -97,7 +126,7 @@ void setup() const float sample_rate = 1000; const float target_freq = 50; - type = filter_type::Combination; + type = filter_type::LowPassConstDT; // Run 1000 time steps at each frequency const uint16_t num_samples = 1000; @@ -108,6 +137,11 @@ void setup() // Print transfer function of filter under test hal.console->printf("\n"); switch (type) { + case filter_type::LowPassConstDT: + lowpassConstDt.set_cutoff_frequency_override(sample_rate, target_freq); + lowpassConstDt.print_transfer_function(); + break; + case filter_type::LowPass: lowpass.set_cutoff_frequency_override(sample_rate, target_freq); lowpass.print_transfer_function(); @@ -147,6 +181,7 @@ void setup() void reset_all() { + lowpassConstDt.reset(0.0); lowpass.reset(0.0); biquad.reset(0.0); notch.reset(); @@ -156,8 +191,11 @@ void reset_all() float apply_to_filter_under_test(float input) { switch (type) { + case filter_type::LowPassConstDT: + return lowpassConstDt.apply(input); + case filter_type::LowPass: - return lowpass.apply(input); + return lowpass.apply_override(input); case filter_type::Biquad: return biquad.apply(input); @@ -195,6 +233,9 @@ void sweep(uint16_t num_samples, uint16_t max_freq, float sample_rate) hal.console->printf(", %+.9f", output); } hal.console->printf("\n"); + + // Try not to overflow the print buffer + hal.scheduler->delay(100); } } diff --git a/libraries/Filter/tests/plot_harmonictest5.gnu b/libraries/Filter/tests/plot_harmonictest5.gnu new file mode 100755 index 00000000000000..4de8b27b730a38 --- /dev/null +++ b/libraries/Filter/tests/plot_harmonictest5.gnu @@ -0,0 +1,13 @@ +#!/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 "Attenuation(dB)" +set ylabel "PhaseLag(deg)" +set key left bottom +set yrange [0:60] +plot "harmonicnotch_test5.csv" using 1:2, "harmonicnotch_test5.csv" using 1:3, "harmonicnotch_test5.csv" using 1:4, "harmonicnotch_test5.csv" using 1:5, "harmonicnotch_test5.csv" using 1:6 + diff --git a/libraries/Filter/tests/test_notchfilter.cpp b/libraries/Filter/tests/test_notchfilter.cpp index a13c9aeae161a2..ce6d6ffa3a4b6c 100644 --- a/libraries/Filter/tests/test_notchfilter.cpp +++ b/libraries/Filter/tests/test_notchfilter.cpp @@ -186,8 +186,8 @@ static void test_one_filter(float base_freq, float attenuation_dB, double last_in; double last_out; double v_max; - uint32_t last_crossing; - uint32_t total_lag_samples; + double last_crossing; + double 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); @@ -218,10 +218,16 @@ static void test_one_filter(float base_freq, float attenuation_dB, integral.v_max = MAX(integral.v_max, v); } if (sample >= 0 && integral.last_in < 0) { - integral.last_crossing = s; + // Always interpolating the value at 0.0 + // crossing happened some fraction before the current sample + // result in the range -1.0 to 0.0 + // linear interpolation: ((0.0 - last_in) / (sample - last_in)) - 1.0 is the same as: + // sample / (last_in - sample) + integral.last_crossing = (double)s + (sample / (integral.last_in - sample)); } - if (v >= 0 && integral.last_out < 0 && integral.last_crossing != 0) { - integral.total_lag_samples += s - integral.last_crossing; + if (v >= 0 && integral.last_out < 0 && integral.last_crossing > 0) { + const double crossing = (double)s + (v / (integral.last_out - v)); + integral.total_lag_samples += crossing - integral.last_crossing; integral.lag_count++; } integral.last_in = sample; @@ -325,4 +331,36 @@ TEST(NotchFilterTest, HarmonicNotchTest4) fclose(f); } +/* + show phase lag versus attenuation + */ +TEST(NotchFilterTest, HarmonicNotchTest5) +{ + const float min_attenuation = 0; + const float max_attenuation = 50; + const uint16_t steps = 200; + + const char *csv_file = "harmonicnotch_test5.csv"; + FILE *f = fopen(csv_file, "w"); + fprintf(f, "Attenuation(dB),Lag(10Hz),Lag(20Hz),Lag(30Hz),Lag(40Hz),Lag(50Hz),Lag(60Hz),Lag(70Hz)\n"); + + for (uint16_t i=0; ihandle_command_int_packet(packet, msg); +} +#endif // AP_SCRIPTING_ENABLED + #endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index abcdf00cbdfc0c..649a12a6ad6337 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -27,6 +27,7 @@ #include #include #include +#include #include "ap_message.h" @@ -266,6 +267,9 @@ class GCS_MAVLINK // accessor for uart AP_HAL::UARTDriver *get_uart() { return _port; } + // cap the MAVLink message rate. It can't be greater than 0.8 * SCHED_LOOP_RATE + uint16_t cap_message_interval(uint16_t interval_ms) const; + virtual uint8_t sysid_my_gcs() const = 0; virtual bool sysid_enforce() const { return false; } @@ -319,6 +323,7 @@ class GCS_MAVLINK return last_radio_status.remrssi_ms; } static float telemetry_radio_rssi(); // 0==no signal, 1==full signal + static bool last_txbuf_is_greater(uint8_t txbuf_limit); // mission item index to be sent on queued msg, delayed or not uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE; @@ -353,11 +358,18 @@ class GCS_MAVLINK void send_rc_channels() const; void send_rc_channels_raw() const; void send_raw_imu(); + void send_highres_imu(); void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)); void send_scaled_pressure(); void send_scaled_pressure2(); virtual void send_scaled_pressure3(); // allow sub to override this +#if AP_AIRSPEED_ENABLED + // Send per instance airspeed message + // last index is used to rotate through sensors + void send_airspeed(); + uint8_t last_airspeed_idx; +#endif void send_simstate() const; void send_sim_state() const; void send_ahrs(); @@ -400,6 +412,10 @@ class GCS_MAVLINK void send_uavionix_adsb_out_status() const; void send_autopilot_state_for_gimbal_device() const; + // Send the mode with the given index (not mode number!) return the total number of modes + // Index starts at 1 + virtual uint8_t send_available_mode(uint8_t index) const = 0; + // lock a channel, preventing use by MAVLink void lock(bool _lock) { _locked = _lock; @@ -481,7 +497,6 @@ class GCS_MAVLINK virtual uint64_t capabilities() const; uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; } - uint8_t get_last_txbuf() const { return last_txbuf; } MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us); @@ -522,12 +537,15 @@ class GCS_MAVLINK void handle_set_mode(const mavlink_message_t &msg); void handle_command_int(const mavlink_message_t &msg); - MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_int_external_wind_estimate(const mavlink_command_int_t &packet); +#if AP_HOME_ENABLED + MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); bool set_home_to_current_location(bool lock); bool set_home(const Location& loc, bool lock); +#endif #if AP_ARMING_ENABLED virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet); @@ -729,7 +747,7 @@ class GCS_MAVLINK #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; + static constexpr const float magic_force_arm_disarm_value = 21196.0f; void manual_override(class RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false); @@ -768,6 +786,7 @@ class GCS_MAVLINK uint32_t remrssi_ms; uint8_t rssi; uint32_t received_ms; // time RADIO_STATUS received + uint8_t txbuf = 100; } last_radio_status; enum class Flags { @@ -813,8 +832,6 @@ class GCS_MAVLINK // number of extra ms to add to slow things down for the radio uint16_t stream_slowdown_ms; - // last reported radio buffer percent available - uint8_t last_txbuf = 100; // outbound ("deferred message") queue. @@ -1113,6 +1130,17 @@ class GCS_MAVLINK // true if we should NOT do MAVLink on this port (usually because // someone's doing SERIAL_CONTROL over mavlink) bool _locked; + + // Handling of AVAILABLE_MODES + struct { + bool should_send; + // Note these start at 1 + uint8_t requested_index; + uint8_t next_index; + } available_modes; + bool send_available_modes(); + bool send_available_mode_monitor(); + }; /// @class GCS @@ -1269,6 +1297,16 @@ class GCS virtual uint8_t sysid_this_mav() const = 0; +#if AP_SCRIPTING_ENABLED + // lua access to command_int + MAV_RESULT lua_command_int_packet(const mavlink_command_int_t &packet); +#endif + + // Sequence number should be incremented when available modes changes + // Sent in AVAILABLE_MODES_MONITOR msg + uint8_t get_available_modes_sequence() const { return available_modes_sequence; } + void available_modes_changed() { available_modes_sequence += 1; } + protected: virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, @@ -1332,6 +1370,8 @@ class GCS uint32_t last_port1_data_ms; uint32_t baud1; uint32_t baud2; + uint8_t parity1; + uint8_t parity2; uint8_t timeout_s; HAL_Semaphore sem; } _passthru; @@ -1344,6 +1384,10 @@ class GCS // GCS::update_send is called so we don't starve later links of // time in which they are permitted to send messages. uint8_t first_backend_to_send; + + // Sequence number should be incremented when available modes changes + // Sent in AVAILABLE_MODES_MONITOR msg + uint8_t available_modes_sequence; }; GCS &gcs(); @@ -1398,4 +1442,3 @@ enum MAV_SEVERITY #define AP_HAVE_GCS_SEND_TEXT 0 #endif // HAL_GCS_ENABLED - diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fe29ac468e513a..e670339e7b756b 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -77,7 +77,7 @@ #include -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED #include #include #endif @@ -225,6 +225,20 @@ void GCS_MAVLINK::send_power_status(void) hal.analogin->power_status_flags()); } +#if AP_SCHEDULER_ENABLED +// cap the MAVLink message rate. It can't be greater than 0.8 * SCHED_LOOP_RATE +uint16_t GCS_MAVLINK::cap_message_interval(uint16_t interval_ms) const +{ + if (interval_ms == 0) { + return 0; + } + if (interval_ms*800 < AP::scheduler().get_loop_period_us()) { + return AP::scheduler().get_loop_period_us()/800.0f; + } + return interval_ms; +} +#endif + #if HAL_WITH_MCU_MONITORING // report MCU voltage/temperature status void GCS_MAVLINK::send_mcu_status(void) @@ -377,7 +391,10 @@ bool GCS_MAVLINK::send_battery_status() for(uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) { const uint8_t battery_id = (last_battery_status_idx + 1) % AP_BATT_MONITOR_MAX_INSTANCES; - if (battery.get_type(battery_id) != AP_BattMonitor::Type::NONE) { + const auto configured_type = battery.configured_type(battery_id); + if (configured_type != AP_BattMonitor::Type::NONE && + configured_type == battery.allocated_type(battery_id) && + !battery.option_is_set(battery_id, AP_BattMonitor_Params::Options::InternalUseOnly)) { CHECK_PAYLOAD_SIZE(BATTERY_STATUS); send_battery_status(battery_id); last_battery_status_idx = battery_id; @@ -833,6 +850,15 @@ float GCS_MAVLINK::telemetry_radio_rssi() return last_radio_status.rssi/254.0f; } +bool GCS_MAVLINK::last_txbuf_is_greater(uint8_t txbuf_limit) +{ + if (AP_HAL::millis() - last_radio_status.received_ms > 5000) { + // stale report + return true; + } + return last_radio_status.txbuf > txbuf_limit; +} + void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg) { mavlink_radio_t packet; @@ -849,7 +875,7 @@ void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg) last_radio_status.remrssi_ms = now; } - last_txbuf = packet.txbuf; + last_radio_status.txbuf = packet.txbuf; // use the state of the transmit buffer in the radio to // control the stream rate, giving us adaptive software @@ -991,21 +1017,30 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_MISSION_CURRENT, MSG_CURRENT_WAYPOINT}, { MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, MSG_SERVO_OUTPUT_RAW}, { MAVLINK_MSG_ID_RC_CHANNELS, MSG_RC_CHANNELS}, +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED { MAVLINK_MSG_ID_RC_CHANNELS_RAW, MSG_RC_CHANNELS_RAW}, +#endif { MAVLINK_MSG_ID_RAW_IMU, MSG_RAW_IMU}, { MAVLINK_MSG_ID_SCALED_IMU, MSG_SCALED_IMU}, { MAVLINK_MSG_ID_SCALED_IMU2, MSG_SCALED_IMU2}, { MAVLINK_MSG_ID_SCALED_IMU3, MSG_SCALED_IMU3}, +#if AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED + { MAVLINK_MSG_ID_HIGHRES_IMU, MSG_HIGHRES_IMU}, +#endif { MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE}, { MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2}, { MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3}, -#if AP_GPS_ENABLED +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED { MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW}, +#endif +#if AP_GPS_GPS_RTK_SENDING_ENABLED { MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK}, -#if GPS_MAX_RECEIVERS > 1 +#endif +#if AP_GPS_GPS2_RAW_SENDING_ENABLED { MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW}, - { MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK}, #endif +#if AP_GPS_GPS2_RTK_SENDING_ENABLED + { 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}, @@ -1032,8 +1067,10 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_RANGEFINDER, MSG_RANGEFINDER}, #endif { MAVLINK_MSG_ID_DISTANCE_SENSOR, MSG_DISTANCE_SENSOR}, - // request also does report: - { MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN}, +#if AP_TERRAIN_AVAILABLE + { MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN_REQUEST}, + { MAVLINK_MSG_ID_TERRAIN_REPORT, MSG_TERRAIN_REPORT}, +#endif #if AP_MAVLINK_BATTERY2_ENABLED { MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2}, #endif @@ -1043,7 +1080,13 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS}, { MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS}, { MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS}, -#endif +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + { MAVLINK_MSG_ID_CAMERA_THERMAL_RANGE, MSG_CAMERA_THERMAL_RANGE}, +#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + { MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, MSG_VIDEO_STREAM_INFORMATION}, +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED +#endif // AP_CAMERA_ENABLED #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}, @@ -1106,6 +1149,11 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED { MAVLINK_MSG_ID_RELAY_STATUS, MSG_RELAY_STATUS}, #endif +#if AP_AIRSPEED_ENABLED + { MAVLINK_MSG_ID_AIRSPEED, MSG_AIRSPEED}, +#endif + { MAVLINK_MSG_ID_AVAILABLE_MODES, MSG_AVAILABLE_MODES}, + { MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR, MSG_AVAILABLE_MODES_MONITOR}, }; for (uint8_t i=0; ipersistent_data.last_mavlink_msgid = msg.msgid; packetReceived(status, msg); parsed_packet = true; gcs_alternative_active[chan] = false; alternative.last_mavlink_ms = now_ms; hal.util->persistent_data.last_mavlink_msgid = 0; + + } +#if AP_SCRIPTING_ENABLED + else if (framing == MAVLINK_FRAMING_BAD_CRC) { + // This may be a valid message that we don't know the crc extra for, pass it to scripting which might + AP_Scripting *scripting = AP_Scripting::get_singleton(); + if (scripting != nullptr) { + scripting->handle_message(msg, chan); + } } +#endif // AP_SCRIPTING_ENABLED if (parsed_packet || i % 100 == 0) { // make sure we don't spend too much time parsing mavlink messages @@ -1885,7 +1940,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) if (uint16_t(now16_ms - try_send_message_stats.statustext_last_sent_ms) > 10000U) { if (try_send_message_stats.longest_time_us) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): ap_msg=%u took %uus to send", chan, try_send_message_stats.longest_id, @@ -1894,42 +1949,42 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) } if (try_send_message_stats.no_space_for_message && (is_active() || is_streaming())) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): out-of-space: %u", chan, try_send_message_stats.no_space_for_message); try_send_message_stats.no_space_for_message = 0; } if (try_send_message_stats.out_of_time) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): out-of-time=%u", chan, try_send_message_stats.out_of_time); try_send_message_stats.out_of_time = 0; } if (max_slowdown_ms) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): max slowdown=%u", chan, max_slowdown_ms); max_slowdown_ms = 0; } if (try_send_message_stats.behind) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): behind=%u", chan, try_send_message_stats.behind); try_send_message_stats.behind = 0; } if (try_send_message_stats.fnbts_maxtime) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): fnbts_maxtime=%uus", chan, try_send_message_stats.fnbts_maxtime); try_send_message_stats.fnbts_maxtime = 0; } if (try_send_message_stats.max_retry_deferred_body_us) { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GCS.chan(%u): retry_body_maxtime=%uus (%u)", chan, try_send_message_stats.max_retry_deferred_body_us, @@ -1939,7 +1994,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) } for (uint8_t i=0; i= 1) { + const Vector3f field = compass.get_field() * 1000.0f; + reply.xmag = field.x; // convert to gauss + reply.ymag = field.y; + reply.zmag = field.z; + reply.fields_updated |= (HIGHRES_IMU_UPDATED_XMAG | HIGHRES_IMU_UPDATED_YMAG | HIGHRES_IMU_UPDATED_ZMAG); + } +#endif + +#if AP_BARO_ENABLED + const AP_Baro &barometer = AP::baro(); + reply.abs_pressure = barometer.get_pressure() * 0.01f; + reply.temperature = barometer.get_temperature(); + reply.pressure_alt = barometer.get_altitude_AMSL(); + reply.diff_pressure = reply.abs_pressure - barometer.get_ground_pressure() * 0.01f; + reply.fields_updated |= (HIGHRES_IMU_UPDATED_ABS_PRESSURE | HIGHRES_IMU_UPDATED_DIFF_PRESSURE | + HIGHRES_IMU_UPDATED_PRESSURE_ALT | HIGHRES_IMU_UPDATED_TEMPERATURE); +#endif + static const uint16_t all_flags = (HIGHRES_IMU_UPDATED_XACC | HIGHRES_IMU_UPDATED_YACC | HIGHRES_IMU_UPDATED_ZACC | + HIGHRES_IMU_UPDATED_XGYRO | HIGHRES_IMU_UPDATED_YGYRO | HIGHRES_IMU_UPDATED_ZGYRO | + HIGHRES_IMU_UPDATED_XMAG | HIGHRES_IMU_UPDATED_YMAG | HIGHRES_IMU_UPDATED_ZMAG | + HIGHRES_IMU_UPDATED_ABS_PRESSURE | HIGHRES_IMU_UPDATED_DIFF_PRESSURE | + HIGHRES_IMU_UPDATED_PRESSURE_ALT | HIGHRES_IMU_UPDATED_TEMPERATURE); + if (reply.fields_updated == all_flags) { + reply.fields_updated |= HIGHRES_IMU_UPDATED_ALL; + } + + mavlink_msg_highres_imu_send_struct(chan, &reply); +} +#endif // AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED + void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature)) { #if AP_INERTIALSENSOR_ENABLED @@ -2228,6 +2362,60 @@ void GCS_MAVLINK::send_scaled_pressure3() send_scaled_pressure_instance(2, mavlink_msg_scaled_pressure3_send); } +#if AP_AIRSPEED_ENABLED +void GCS_MAVLINK::send_airspeed() +{ + AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); + if (airspeed == nullptr) { + return; + } + + for (uint8_t i=0; ienabled(index)) { + continue; + } + + float temperature_float; + int16_t temperature = INT16_MAX; + if (airspeed->get_temperature(index, temperature_float)) { + temperature = int16_t(temperature_float * 100); + } + + uint8_t flags = 0; + // Set unhealthy flag + if (!airspeed->healthy(index)) { + flags |= 1U << AIRSPEED_SENSOR_FLAGS::AIRSPEED_SENSOR_UNHEALTHY; + } + +#if AP_AHRS_ENABLED + // Set using flag if the AHRS is using this sensor + const AP_AHRS &ahrs = AP::ahrs(); + if (ahrs.using_airspeed_sensor() && (ahrs.get_active_airspeed_index() == index)) { + flags |= 1U << AIRSPEED_SENSOR_FLAGS::AIRSPEED_SENSOR_USING; + } +#endif + + // Assemble message and send + const mavlink_airspeed_t msg { + airspeed : airspeed->get_airspeed(index), + raw_press : airspeed->get_differential_pressure(index), + temperature : temperature, + id : index, + flags : flags + }; + + mavlink_msg_airspeed_send_struct(chan, &msg); + + // Only send one msg per call + last_airspeed_idx = index; + return; + } + +} +#endif // AP_AIRSPEED_ENABLED + #if AP_AHRS_ENABLED void GCS_MAVLINK::send_ahrs() { @@ -2471,19 +2659,19 @@ void GCS::update_send() #if AP_MISSION_ENABLED AP_Mission *mission = AP::mission(); if (mission != nullptr) { - missionitemprotocols[MAV_MISSION_TYPE_MISSION] = new MissionItemProtocol_Waypoints(*mission); + missionitemprotocols[MAV_MISSION_TYPE_MISSION] = NEW_NOTHROW MissionItemProtocol_Waypoints(*mission); } #endif #if HAL_RALLY_ENABLED AP_Rally *rally = AP::rally(); if (rally != nullptr) { - missionitemprotocols[MAV_MISSION_TYPE_RALLY] = new MissionItemProtocol_Rally(*rally); + missionitemprotocols[MAV_MISSION_TYPE_RALLY] = NEW_NOTHROW MissionItemProtocol_Rally(*rally); } #endif #if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence != nullptr) { - missionitemprotocols[MAV_MISSION_TYPE_FENCE] = new MissionItemProtocol_Fence(*fence); + missionitemprotocols[MAV_MISSION_TYPE_FENCE] = NEW_NOTHROW MissionItemProtocol_Fence(*fence); } #endif } @@ -2585,7 +2773,7 @@ void GCS::setup_uarts() #if AP_FRSKY_TELEM_ENABLED if (frsky == nullptr) { - frsky = new AP_Frsky_Telem(); + frsky = NEW_NOTHROW AP_Frsky_Telem(); if (frsky == nullptr || !frsky->init()) { delete frsky; frsky = nullptr; @@ -2933,6 +3121,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_int_t &packet) { + if (!is_zero(packet.param3)) { + return MAV_RESULT_DENIED; + } return set_message_interval((uint32_t)packet.param1, (int32_t)packet.param2); } @@ -2940,7 +3131,7 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u { const ap_message id = mavlink_id_to_ap_message_id(msg_id); if (id == MSG_LAST) { - gcs().send_text(MAV_SEVERITY_INFO, "No ap_message for mavlink id (%u)", (unsigned int)msg_id); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "No ap_message for mavlink id (%u)", (unsigned int)msg_id); return MAV_RESULT_DENIED; } @@ -2968,6 +3159,12 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u } else { interval_ms = interval_us / 1000; } +#if AP_SCHEDULER_ENABLED + if (interval_ms != 0 && cap_message_interval(interval_ms) > interval_ms) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Requested rate for message ID %u too fast. Increase SCHED_LOOP_RATE", (unsigned int)msg_id); + return MAV_RESULT_DENIED; + } +#endif if (set_ap_message_interval(id, interval_ms)) { return MAV_RESULT_ACCEPTED; } @@ -3008,6 +3205,22 @@ MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_int if (id == MSG_LAST) { return MAV_RESULT_FAILED; } + + switch(id) { + case MSG_AVAILABLE_MODES: + available_modes.should_send = true; + available_modes.next_index = 1; + available_modes.requested_index = (uint8_t)packet.param2; + + // After the first request sequnece is streamed in the AVAILABLE_MODES_MONITOR message + // This allows the GCS to re-request modes if there is a change + set_ap_message_interval(MSG_AVAILABLE_MODES_MONITOR, 5000); + break; + + default: + break; + } + send_message(id); return MAV_RESULT_ACCEPTED; } @@ -3053,17 +3266,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_comman } uint16_t interval_ms = 0; - if (!get_ap_message_interval(id, interval_ms)) { + if (!get_ap_message_interval(id, interval_ms) || interval_ms == 0) { // not streaming this message at the moment... mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled return MAV_RESULT_ACCEPTED; } - if (interval_ms == 0) { - mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled - return MAV_RESULT_ACCEPTED; - } - mavlink_msg_message_interval_send(chan, mavlink_id, interval_ms * 1000); return MAV_RESULT_ACCEPTED; } @@ -3428,7 +3636,7 @@ void GCS_MAVLINK::handle_timesync(const mavlink_message_t &msg) return; } #if 0 - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "timesync response sysid=%u (latency=%fms)", msg.sysid, round_trip_time_us*0.001f); @@ -3617,7 +3825,7 @@ void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t &msg) */ void GCS_MAVLINK::handle_data_packet(const mavlink_message_t &msg) { -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED mavlink_data96_t m; mavlink_msg_data96_decode(&msg, &m); switch (m.type) { @@ -4070,6 +4278,7 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) #if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT case MAVLINK_MSG_ID_FENCE_POINT: case MAVLINK_MSG_ID_FENCE_FETCH_POINT: + send_received_message_deprecation_warning("FENCE_FETCH_POINT"); handle_fence_message(msg); break; #endif @@ -4114,7 +4323,6 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) #if AP_GPS_ENABLED case MAVLINK_MSG_ID_GPS_RTCM_DATA: case MAVLINK_MSG_ID_GPS_INPUT: - case MAVLINK_MSG_ID_HIL_GPS: case MAVLINK_MSG_ID_GPS_INJECT_DATA: AP::gps().handle_msg(chan, msg); break; @@ -4147,6 +4355,7 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) #if AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED case MAVLINK_MSG_ID_RALLY_POINT: case MAVLINK_MSG_ID_RALLY_FETCH_POINT: + send_received_message_deprecation_warning("RALLY_FETCH_POINT"); handle_common_rally_message(msg); break; #endif @@ -4444,7 +4653,7 @@ void GCS_MAVLINK::send_sim_state() const MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_int_t &packet) { if (packet.x != 290876) { - gcs().send_text(MAV_SEVERITY_INFO, "Magic not set"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Magic not set"); return MAV_RESULT_FAILED; } @@ -4455,7 +4664,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_in return MAV_RESULT_ACCEPTED; #if AP_SIGNED_FIRMWARE case AP_HAL::Util::FlashBootloader::NOT_SIGNED: - gcs().send_text(MAV_SEVERITY_ERROR, "Bootloader not signed"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader not signed"); break; #endif default: @@ -4469,9 +4678,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_in MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg) { // fast barometer calibration - gcs().send_text(MAV_SEVERITY_INFO, "Updating barometer calibration"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Updating barometer calibration"); AP::baro().update_calibration(); - gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer calibration complete"); #if AP_AIRSPEED_ENABLED @@ -4565,7 +4774,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma { if (hal.util->get_soft_armed()) { // *preflight*, remember? - gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow calibration"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow calibration"); return MAV_RESULT_FAILED; } // now call subclass methods: @@ -4715,7 +4924,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_ uint32_t source_set = uint32_t(packet.param1); if ((source_set >= 1) && (source_set <= 3)) { // mavlink command uses range 1 to 3 while ahrs interface accepts 0 to 2 - AP::ahrs().set_posvelyaw_source_set(source_set-1); + AP::ahrs().set_posvelyaw_source_set((AP_NavEKF_Source::SourceSetSelection)(source_set-1)); return MAV_RESULT_ACCEPTED; } return MAV_RESULT_DENIED; @@ -4824,7 +5033,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman return MAV_RESULT_ACCEPTED; } // run pre_arm_checks and arm_checks and display failures - const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value); + const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value) && !is_equal(packet.param2,magic_force_arm_disarm_value); if (AP::arming().arm(AP_Arming::Method::MAVLINK, do_arming_checks)) { return MAV_RESULT_ACCEPTED; } @@ -4834,7 +5043,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman if (!AP::arming().is_armed()) { return MAV_RESULT_ACCEPTED; } - const bool forced = is_equal(packet.param2, magic_force_disarm_value); + const bool forced = is_equal(packet.param2, magic_force_arm_disarm_value); // note disarm()'s second parameter is "do_disarm_checks" if (AP::arming().disarm(AP_Arming::Method::MAVLINK, !forced)) { return MAV_RESULT_ACCEPTED; @@ -4866,7 +5075,7 @@ bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Locat out.lat = in.x; out.lng = in.y; - out.set_alt_cm(int32_t(in.z * 100), frame); + out.set_alt_m(in.z, frame); return true; } @@ -5057,6 +5266,7 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg) } +#if AP_HOME_ENABLED bool GCS_MAVLINK::set_home_to_current_location(bool _lock) { #if AP_VEHICLE_ENABLED @@ -5073,7 +5283,9 @@ bool GCS_MAVLINK::set_home(const Location& loc, bool _lock) { return false; #endif } +#endif // AP_HOME_ENABLED +#if AP_HOME_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet) { if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) { @@ -5096,6 +5308,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t & } return MAV_RESULT_ACCEPTED; } +#endif // AP_HOME_ENABLED #if AP_AHRS_POSITION_RESET_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavlink_command_int_t &packet) @@ -5127,6 +5340,21 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavl } #endif // AP_AHRS_POSITION_RESET_ENABLED +#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED +MAV_RESULT GCS_MAVLINK::handle_command_int_external_wind_estimate(const mavlink_command_int_t &packet) +{ + if (packet.param1 < 0) { + return MAV_RESULT_DENIED; + } + if (packet.param3 < 0 || packet.param3 > 360) { + return MAV_RESULT_DENIED; + } + + AP::ahrs().set_external_wind_estimate(packet.param1, packet.param3); + return MAV_RESULT_ACCEPTED; +} +#endif // AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED + MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const mavlink_command_int_t &packet) { // be aware that this method is called for both MAV_CMD_DO_SET_ROI @@ -5279,7 +5507,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p #endif case MAV_CMD_DO_SET_ROI_NONE: { - const Location zero_loc = Location(); + const Location zero_loc; return handle_command_do_set_roi(zero_loc); } @@ -5300,12 +5528,19 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p send_banner(); return MAV_RESULT_ACCEPTED; +#if AP_HOME_ENABLED case MAV_CMD_DO_SET_HOME: return handle_command_do_set_home(packet); +#endif + #if AP_AHRS_POSITION_RESET_ENABLED case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: return handle_command_int_external_position_estimate(packet); #endif +#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED + case MAV_CMD_EXTERNAL_WIND_ESTIMATE: + return handle_command_int_external_wind_estimate(packet); +#endif #if AP_ARMING_ENABLED case MAV_CMD_COMPONENT_ARM_DISARM: return handle_command_component_arm_disarm(packet); @@ -5874,6 +6109,51 @@ void GCS_MAVLINK::send_received_message_deprecation_warning(const char * message send_text(MAV_SEVERITY_INFO, "Received message (%s) is deprecated", message); } +bool GCS_MAVLINK::send_available_modes() +{ + if (!available_modes.should_send) { + // must only return false if out of space + return true; + } + + CHECK_PAYLOAD_SIZE(AVAILABLE_MODES); + + // Zero is a special case for send all. + const bool send_all = available_modes.requested_index == 0; + uint8_t request_index; + if (!send_all) { + // Single request + request_index = available_modes.requested_index; + available_modes.should_send = false; + + } else { + // Request all modes + request_index = available_modes.next_index; + available_modes.next_index += 1; + } + + const uint8_t mode_count = send_available_mode(request_index); + + if (send_all && (available_modes.next_index > mode_count)) { + // Sending all and just sent the last + available_modes.should_send = false; + } + + return true; +} + +bool GCS_MAVLINK::send_available_mode_monitor() +{ + CHECK_PAYLOAD_SIZE(AVAILABLE_MODES_MONITOR); + + mavlink_msg_available_modes_monitor_send( + chan, + gcs().get_available_modes_sequence() + ); + + return true; +} + bool GCS_MAVLINK::try_send_message(const enum ap_message id) { bool ret = true; @@ -5994,85 +6274,57 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) #if AP_CAMERA_ENABLED case MSG_CAMERA_FEEDBACK: - { - AP_Camera *camera = AP::camera(); - if (camera == nullptr) { - break; - } - CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK); - camera->send_feedback(chan); - } - break; case MSG_CAMERA_INFORMATION: - { - AP_Camera *camera = AP::camera(); - if (camera == nullptr) { - break; - } - CHECK_PAYLOAD_SIZE(CAMERA_INFORMATION); - camera->send_camera_information(chan); - } - break; case MSG_CAMERA_SETTINGS: - { - AP_Camera *camera = AP::camera(); - if (camera == nullptr) { - break; - } - CHECK_PAYLOAD_SIZE(CAMERA_SETTINGS); - camera->send_camera_settings(chan); - } - break; #if AP_CAMERA_SEND_FOV_STATUS_ENABLED case MSG_CAMERA_FOV_STATUS: - { - AP_Camera *camera = AP::camera(); - if (camera == nullptr) { - break; - } - CHECK_PAYLOAD_SIZE(CAMERA_FOV_STATUS); - camera->send_camera_fov_status(chan); - } - break; #endif case MSG_CAMERA_CAPTURE_STATUS: +#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED + case MSG_CAMERA_THERMAL_RANGE: +#endif +#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED + case MSG_VIDEO_STREAM_INFORMATION: +#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED { AP_Camera *camera = AP::camera(); if (camera == nullptr) { break; } - CHECK_PAYLOAD_SIZE(CAMERA_CAPTURE_STATUS); - camera->send_camera_capture_status(chan); + return camera->send_mavlink_message(*this, id); } - break; -#endif +#endif // AP_CAMERA_ENABLED case MSG_SYSTEM_TIME: CHECK_PAYLOAD_SIZE(SYSTEM_TIME); send_system_time(); break; -#if AP_GPS_ENABLED + +#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED case MSG_GPS_RAW: CHECK_PAYLOAD_SIZE(GPS_RAW_INT); AP::gps().send_mavlink_gps_raw(chan); break; +#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED +#if AP_GPS_GPS_RTK_SENDING_ENABLED case MSG_GPS_RTK: CHECK_PAYLOAD_SIZE(GPS_RTK); AP::gps().send_mavlink_gps_rtk(chan, 0); break; -#if GPS_MAX_RECEIVERS > 1 +#endif // AP_GPS_GPS_RTK_SENDING_ENABLED +#if AP_GPS_GPS2_RAW_SENDING_ENABLED case MSG_GPS2_RAW: CHECK_PAYLOAD_SIZE(GPS2_RAW); AP::gps().send_mavlink_gps2_raw(chan); break; -#endif -#if GPS_MAX_RECEIVERS > 1 +#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED +#if AP_GPS_GPS2_RTK_SENDING_ENABLED case MSG_GPS2_RTK: CHECK_PAYLOAD_SIZE(GPS2_RTK); AP::gps().send_mavlink_gps_rtk(chan, 1); break; -#endif -#endif // AP_GPS_ENABLED +#endif // AP_GPS_GPS2_RTK_SENDING_ENABLED + #if AP_AHRS_ENABLED case MSG_LOCAL_POSITION: CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED); @@ -6139,10 +6391,13 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_rc_channels(); break; +#if AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED case MSG_RC_CHANNELS_RAW: CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW); send_rc_channels_raw(); break; +#endif // AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED + #endif case MSG_RAW_IMU: @@ -6164,6 +6419,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(SCALED_IMU3); send_scaled_imu(2, mavlink_msg_scaled_imu3_send); break; +#if AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED + case MSG_HIGHRES_IMU: + CHECK_PAYLOAD_SIZE(HIGHRES_IMU); + send_highres_imu(); + break; +#endif case MSG_SCALED_PRESSURE: CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); @@ -6180,6 +6441,13 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_scaled_pressure3(); break; +#if AP_AIRSPEED_ENABLED + case MSG_AIRSPEED: + CHECK_PAYLOAD_SIZE(AIRSPEED); + send_airspeed(); + break; +#endif + case MSG_SERVO_OUTPUT_RAW: CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); send_servo_output_raw(); @@ -6316,13 +6584,21 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif + case MSG_AVAILABLE_MODES: + ret = send_available_modes(); + break; + + case MSG_AVAILABLE_MODES_MONITOR: + ret = send_available_mode_monitor(); + break; + default: // try_send_message must always at some stage return true for // a message, or we will attempt to infinitely retry the // message as part of send_message. // This message will be sent out at the same rate as the // unknown message, so should be safe. - gcs().send_text(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("Sending unknown ap_message %u", id); #endif @@ -6369,7 +6645,7 @@ DefaultIntervalsFromFiles::DefaultIntervalsFromFiles(uint16_t max_num) if (max_num == 0) { return; } - _intervals = new from_file_default_interval[max_num]; + _intervals = NEW_NOTHROW from_file_default_interval[max_num]; _max_intervals = max_num; } @@ -6493,7 +6769,7 @@ void GCS_MAVLINK::initialise_message_intervals_from_config_files() } // first over-allocate: - DefaultIntervalsFromFiles *overallocated = new DefaultIntervalsFromFiles(128); + DefaultIntervalsFromFiles *overallocated = NEW_NOTHROW DefaultIntervalsFromFiles(128); if (overallocated == nullptr) { return; } @@ -6511,7 +6787,7 @@ void GCS_MAVLINK::initialise_message_intervals_from_config_files() delete overallocated; overallocated = nullptr; - default_intervals_from_files = new DefaultIntervalsFromFiles(num_required); + default_intervals_from_files = NEW_NOTHROW DefaultIntervalsFromFiles(num_required); if (default_intervals_from_files == nullptr) { return; } @@ -6656,6 +6932,7 @@ void GCS::update_passthru(void) WITH_SEMAPHORE(_passthru.sem); uint32_t now = AP_HAL::millis(); uint32_t baud1, baud2; + uint8_t parity1 = 0, parity2 = 0; bool enabled = AP::serialmanager().get_passthru(_passthru.port1, _passthru.port2, _passthru.timeout_s, baud1, baud2); if (enabled && !_passthru.enabled) { @@ -6665,7 +6942,9 @@ void GCS::update_passthru(void) _passthru.last_port1_data_ms = now; _passthru.baud1 = baud1; _passthru.baud2 = baud2; - gcs().send_text(MAV_SEVERITY_INFO, "Passthru enabled"); + _passthru.parity1 = parity1 = _passthru.port1->get_parity(); + _passthru.parity2 = parity2 = _passthru.port2->get_parity(); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru enabled"); if (!_passthru.timer_installed) { _passthru.timer_installed = true; hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&GCS::passthru_timer, void)); @@ -6683,7 +6962,14 @@ void GCS::update_passthru(void) _passthru.port2->end(); _passthru.port2->begin(baud2); } - gcs().send_text(MAV_SEVERITY_INFO, "Passthru disabled"); + // Restore original parity + if (_passthru.parity1 != parity1) { + _passthru.port1->configure_parity(parity1); + } + if (_passthru.parity2 != parity2) { + _passthru.port2->configure_parity(parity2); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru disabled"); } else if (enabled && _passthru.timeout_s && now - _passthru.last_port1_data_ms > uint32_t(_passthru.timeout_s)*1000U) { @@ -6701,12 +6987,19 @@ void GCS::update_passthru(void) _passthru.port2->end(); _passthru.port2->begin(baud2); } - gcs().send_text(MAV_SEVERITY_INFO, "Passthru timed out"); + // Restore original parity + if (_passthru.parity1 != parity1) { + _passthru.port1->configure_parity(parity1); + } + if (_passthru.parity2 != parity2) { + _passthru.port2->configure_parity(parity2); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Passthru timed out"); } } /* - called at 1kHz to handle pass-thru between SERIA0_PASSTHRU port and hal.console + called at 1kHz to handle pass-thru between SERIAL_PASS1 and SERIAL_PASS2 ports */ void GCS::passthru_timer(void) { @@ -6719,7 +7012,7 @@ void GCS::passthru_timer(void) if (_passthru.start_ms != 0) { uint32_t now = AP_HAL::millis(); if (now - _passthru.start_ms < 1000) { - // delay for 1s so the reply for the SERIAL0_PASSTHRU param set can be seen by GCS + // delay for 1s so the reply for the SERIAL_PASS2 param set can be seen by GCS return; } _passthru.start_ms = 0; @@ -6733,32 +7026,48 @@ void GCS::passthru_timer(void) _passthru.port1->lock_port(lock_key, lock_key); _passthru.port2->lock_port(lock_key, lock_key); - // Check for requested Baud rates over USB + // Check for requested Baud rates and parity over USB uint32_t baud = _passthru.port1->get_usb_baud(); - if (_passthru.baud2 != baud && baud != 0) { - _passthru.baud2 = baud; - _passthru.port2->end(); - _passthru.port2->begin_locked(baud, 0, 0, lock_key); + uint8_t parity = _passthru.port1->get_usb_parity(); + if (baud != 0) { // port1 is USB + if (_passthru.baud2 != baud) { + _passthru.baud2 = baud; + _passthru.port2->end(); + _passthru.port2->begin_locked(baud, 0, 0, lock_key); + } + + if (_passthru.parity2 != parity) { + _passthru.parity2 = parity; + _passthru.port2->configure_parity(parity); + } } baud = _passthru.port2->get_usb_baud(); - if (_passthru.baud1 != baud && baud != 0) { - _passthru.baud1 = baud; - _passthru.port1->end(); - _passthru.port1->begin_locked(baud, 0, 0, lock_key); + parity = _passthru.port2->get_usb_parity(); + if (baud != 0) { // port2 is USB + if (_passthru.baud1 != baud) { + _passthru.baud1 = baud; + _passthru.port1->end(); + _passthru.port1->begin_locked(baud, 0, 0, lock_key); + } + + if (_passthru.parity1 != parity) { + _passthru.parity1 = parity; + _passthru.port1->configure_parity(parity); + } } uint8_t buf[64]; // read from port1, and write to port2 - int16_t nbytes = _passthru.port1->read_locked(buf, sizeof(buf), lock_key); + int16_t nbytes = _passthru.port1->read_locked(buf, MIN(sizeof(buf),_passthru.port2->txspace()), lock_key); if (nbytes > 0) { _passthru.last_port1_data_ms = AP_HAL::millis(); _passthru.port2->write_locked(buf, nbytes, lock_key); } // read from port2, and write to port1 - nbytes = _passthru.port2->read_locked(buf, sizeof(buf), lock_key); + nbytes = _passthru.port2->read_locked(buf, MIN(sizeof(buf),_passthru.port1->txspace()), lock_key); if (nbytes > 0) { _passthru.port1->write_locked(buf, nbytes, lock_key); } @@ -6781,7 +7090,7 @@ bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const MAV_FRAME return true; default: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - gcs().send_text(MAV_SEVERITY_INFO, "Unknown mavlink coordinate frame %u", coordinate_frame); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown mavlink coordinate frame %u", coordinate_frame); #endif return false; } diff --git a/libraries/GCS_MAVLink/GCS_Dummy.h b/libraries/GCS_MAVLink/GCS_Dummy.h index 723f927dcdef69..17e74ee0ba7ed1 100644 --- a/libraries/GCS_MAVLink/GCS_Dummy.h +++ b/libraries/GCS_MAVLink/GCS_Dummy.h @@ -35,6 +35,7 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK void send_nav_controller_output() const override {}; void send_pid_tuning() override {}; + uint8_t send_available_mode(uint8_t index) const override { return 0; } }; /* @@ -55,7 +56,7 @@ class GCS_Dummy : public GCS GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Dummy(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Dummy(params, uart); } private: diff --git a/libraries/GCS_MAVLink/GCS_FTP.cpp b/libraries/GCS_MAVLink/GCS_FTP.cpp index 10725ad586a236..0430dc2f3b124d 100644 --- a/libraries/GCS_MAVLink/GCS_FTP.cpp +++ b/libraries/GCS_MAVLink/GCS_FTP.cpp @@ -48,7 +48,7 @@ bool GCS_MAVLINK::ftp_init(void) { return true; } - ftp.requests = new ObjectBuffer(5); + ftp.requests = NEW_NOTHROW ObjectBuffer(5); if (ftp.requests == nullptr || ftp.requests->get_size() == 0) { goto failed; } @@ -63,7 +63,7 @@ bool GCS_MAVLINK::ftp_init(void) { failed: delete ftp.requests; ftp.requests = nullptr; - gcs().send_text(MAV_SEVERITY_WARNING, "failed to initialize MAVFTP"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "failed to initialize MAVFTP"); return false; } @@ -97,12 +97,8 @@ void GCS_MAVLINK::handle_file_transfer_protocol(const mavlink_message_t &msg) { 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<delay(2); } + + if (reply.req_opcode == FTP_OP::TerminateSession) { + ftp.last_send_ms = 0; + } + /* + provide same banner we would give with old param download + Do this after send_ftp_reply() to get the first FTP response out sooner + on slow links to avoid GCS timeout. The slowdown of normal streams in + get_reschedule_interval_ms() should help for subsequent responses. + */ + if (ftp.need_banner_send_mask & (1U<(request.opcode)); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Unsupported FTP: %d", static_cast(request.opcode)); ftp_error(reply, FTP_ERROR::Fail); break; } @@ -581,16 +588,23 @@ 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) { +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE const bool is_file = entry->d_type == DT_REG || entry->d_type == DT_LNK; +#else + // assume true initially, then handle below + const bool is_file = true; +#endif if (space < 3) { return -1; } dest[0] = 0; +#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE if (!is_file && entry->d_type != DT_DIR) { return -1; // this just forces it so we can't send this back, it's easier then sending skips to a GCS } +#endif if (is_file) { #ifdef MAX_NAME_LEN @@ -605,6 +619,12 @@ int GCS_MAVLINK::gen_dir_entry(char *dest, size_t space, const char *path, const if (AP::FS().stat(full_path, &st)) { return -1; } + +#if !AP_FILESYSTEM_HAVE_DIRENT_DTYPE + if (S_ISDIR(st.st_mode)) { + return hal.util->snprintf(dest, space, "D%s%c", entry->d_name, (char)0); + } +#endif return hal.util->snprintf(dest, space, "F%s\t%u%c", entry->d_name, (unsigned)st.st_size, (char)0); } else { return hal.util->snprintf(dest, space, "D%s%c", entry->d_name, (char)0); diff --git a/libraries/GCS_MAVLink/GCS_Fence.cpp b/libraries/GCS_MAVLink/GCS_Fence.cpp index d6dad1a76990c9..b3bfb78a37194f 100644 --- a/libraries/GCS_MAVLink/GCS_Fence.cpp +++ b/libraries/GCS_MAVLink/GCS_Fence.cpp @@ -16,20 +16,24 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_int return MAV_RESULT_UNSUPPORTED; } - switch ((uint16_t)packet.param1) { - case 0: // disable fence - fence->enable(false); + uint8_t fences = AC_FENCE_ALL_FENCES; + if (uint8_t(packet.param2)) { + fences = uint8_t(packet.param2); + } + + switch (AC_Fence::MavlinkFenceActions(packet.param1)) { + case AC_Fence::MavlinkFenceActions::DISABLE_FENCE: + fence->enable(false, fences); return MAV_RESULT_ACCEPTED; - case 1: // enable fence - if (!fence->present()) - { + case AC_Fence::MavlinkFenceActions::ENABLE_FENCE: + if (!(fence->present() & fences)) { return MAV_RESULT_FAILED; } - - fence->enable(true); + + fence->enable(true, fences); return MAV_RESULT_ACCEPTED; - case 2: // disable fence floor only - fence->disable_floor(); + case AC_Fence::MavlinkFenceActions::DISABLE_ALT_MIN_FENCE: + fence->enable(false, AC_FENCE_TYPE_ALT_MIN); return MAV_RESULT_ACCEPTED; default: return MAV_RESULT_FAILED; @@ -82,7 +86,7 @@ void GCS_MAVLINK::send_fence_status() const mavlink_breach_type = FENCE_BREACH_BOUNDARY; } - // report on Avoidance liminting + // report on Avoidance limiting uint8_t breach_mitigation = FENCE_MITIGATE_UNKNOWN; #if AP_AVOIDANCE_ENABLED && !APM_BUILD_TYPE(APM_BUILD_ArduPlane) const AC_Avoid* avoid = AC_Avoid::get_singleton(); diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 36e0cd3fb0851b..b59ba9d93c3119 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -15,9 +15,9 @@ #define MAVLINK_START_UART_SEND(chan, size) comm_send_lock(chan, size) #define MAVLINK_END_UART_SEND(chan, size) comm_send_unlock(chan) -#if AP_NETWORKING_ENABLED -// allow 7 telemetry ports with networking -#define MAVLINK_COMM_NUM_BUFFERS 7 +#if BOARD_FLASH_SIZE > 1024 +// allow 8 telemetry ports, allowing for extra networking or CAN ports +#define MAVLINK_COMM_NUM_BUFFERS 8 #else // allow five telemetry ports #define MAVLINK_COMM_NUM_BUFFERS 5 diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index a4c8c1df5182cb..5d73e8a646b095 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -75,7 +75,7 @@ GCS_MAVLINK::queued_param_send() } count -= async_replies_sent_count; - while (count && _queued_parameter != nullptr && get_last_txbuf() > 50) { + while (count && _queued_parameter != nullptr && last_txbuf_is_greater(33)) { char param_name[AP_MAX_NAME_SIZE]; _queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true); @@ -108,7 +108,7 @@ bool GCS_MAVLINK::have_flow_control(void) return false; } - if (_port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) { + if (_port->flow_control_enabled()) { return true; } @@ -290,7 +290,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg) } if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) { - gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param write denied (%s)", key); // send the readonly value send_parameter_value(key, var_type, old_value); return; diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index 394d669a9cb97d..891eaddec10ffa 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -80,7 +80,7 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg) const mavlink_setup_signing_t packet; mavlink_msg_setup_signing_decode(&msg, &packet); - struct SigningKey key; + struct SigningKey key {}; key.magic = SIGNING_KEY_MAGIC; key.timestamp = packet.initial_timestamp; memcpy(key.secret_key, packet.secret_key, 32); diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 64877c10649dd4..8a297bb003f1ec 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -3,6 +3,7 @@ #include #include #include +#include #ifndef HAL_GCS_ENABLED #define HAL_GCS_ENABLED 1 @@ -12,9 +13,12 @@ #define HAL_MAVLINK_BINDINGS_ENABLED HAL_GCS_ENABLED #endif +// CODE_REMOVAL // BATTERY2 is slated to be removed: +// ArduPilot 4.6 stops compiling support in +// ArduPilot 4.7 removes the code entirely #ifndef AP_MAVLINK_BATTERY2_ENABLED -#define AP_MAVLINK_BATTERY2_ENABLED 1 +#define AP_MAVLINK_BATTERY2_ENABLED 0 #endif #ifndef HAL_HIGH_LATENCY2_ENABLED @@ -36,6 +40,10 @@ #define AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED 1 #endif +#ifndef AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED +#define AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED 1 +#endif + // handling of MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES is slated to be // removed; the message can be requested with MAV_CMD_REQUEST_MESSAGE #ifndef AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED @@ -55,16 +63,24 @@ #define AP_MAVLINK_FAILURE_CREATION_ENABLED 1 #endif +// CODE_REMOVAL +// ArduPilot 4.6 sends deprecation warnings for RALLY_POINT/RALLY_FETCH_POINT +// ArduPilot 4.7 stops compiling them in by default +// ArduPilot 4.8 removes the code entirely #ifndef AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED -#define AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED HAL_GCS_ENABLED && HAL_RALLY_ENABLED +#define AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED 0 #endif +// CODE_REMOVAL +// ArduPilot 4.5 sends deprecation warnings for MOUNT_CONTROL/MOUNT_CONFIGURE +// ArduPilot 4.6 stops compiling them in +// ArduPilot 4.7 removes the code entirely #ifndef AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED -#define AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED HAL_GCS_ENABLED +#define AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED 0 #endif #ifndef AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED -#define AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED HAL_GCS_ENABLED +#define AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED 0 #endif // this is for both read and write messages: @@ -102,3 +118,15 @@ #ifndef AP_MAVLINK_COMMAND_LONG_ENABLED #define AP_MAVLINK_COMMAND_LONG_ENABLED 1 #endif + +#ifndef AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED +#define AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED (BOARD_FLASH_SIZE > 1024) && AP_INERTIALSENSOR_ENABLED +#endif + +#ifndef AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED +#define AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED (BOARD_FLASH_SIZE > 1024) +#endif + +#ifndef AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED +#define AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED HAL_GCS_ENABLED +#endif diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 0c60dcb4e27bc1..e0a2b3fa09366a 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -74,12 +74,6 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg) AP::gps().lock_port(1, exclusive); break; #endif // AP_GPS_ENABLED - case SERIAL_CONTROL_DEV_SHELL: - stream = hal.util->get_shell_stream(); - if (stream == nullptr) { - return; - } - break; case SERIAL_CONTROL_SERIAL0 ... SERIAL_CONTROL_SERIAL9: { // direct access to a SERIALn port stream = port = AP::serialmanager().get_serial_by_id(packet.device - SERIAL_CONTROL_SERIAL0); diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index bd051591579b46..c66ad8697597f7 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -101,7 +101,7 @@ bool MAVLink_routing::check_and_forward(GCS_MAVLINK &in_link, const mavlink_mess // of mavlink messages to a private channel (Solo Gimbal case) if (!gopro_status_check && (msg.msgid == MAVLINK_MSG_ID_GOPRO_HEARTBEAT)) { gopro_status_check = true; - gcs().send_text(MAV_SEVERITY_NOTICE, "GoPro in Solo gimbal detected"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "GoPro in Solo gimbal detected"); } #endif // HAL_SOLO_GIMBAL_ENABLED @@ -199,7 +199,7 @@ bool MAVLink_routing::check_and_forward(GCS_MAVLINK &in_link, const mavlink_mess #if ROUTING_DEBUG ::printf("fwd msg %u from chan %u on chan %u sysid=%d compid=%d\n", msg.msgid, - (unsigned)in_link->get_chan(), + (unsigned)in_link.get_chan(), (unsigned)routes[i].channel, (int)target_system, (int)target_component); diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index d29faaa7f6e8a9..5667578ad064e7 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -33,7 +33,7 @@ void MissionItemProtocol::handle_mission_clear_all(const GCS_MAVLINK &_link, const mavlink_message_t &msg) { bool success = true; - success = success && !receiving; + success = success && cancel_upload(_link, msg); success = success && clear_all_items(); send_mission_ack(_link, msg, success ? MAV_MISSION_ACCEPTED : MAV_MISSION_ERROR); } @@ -47,20 +47,15 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con if (!_link.sending_mavlink1()) { return true; } - gcs().send_text(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer"); send_mission_ack(_link, msg, MAV_MISSION_UNSUPPORTED); return false; } -void MissionItemProtocol::handle_mission_count( - GCS_MAVLINK &_link, - const mavlink_mission_count_t &packet, - const mavlink_message_t &msg) +// returns true if we are either not receiving, or we successfully +// cancelled an existing upload: +bool MissionItemProtocol::cancel_upload(const GCS_MAVLINK &_link, const mavlink_message_t &msg) { - if (!mavlink2_requirement_met(_link, msg)) { - return; - } - if (receiving) { // someone is already uploading a mission. If we are // receiving from someone then we will allow them to restart - @@ -68,11 +63,29 @@ void MissionItemProtocol::handle_mission_count( if (msg.sysid != dest_sysid || msg.compid != dest_compid) { // reject another upload until send_mission_ack(_link, msg, MAV_MISSION_DENIED); - return; + return false; } // the upload count may have changed; free resources and // allocate them again: free_upload_resources(); + receiving = false; + link = nullptr; + } + + return true; +} + +void MissionItemProtocol::handle_mission_count( + GCS_MAVLINK &_link, + const mavlink_mission_count_t &packet, + const mavlink_message_t &msg) +{ + if (!mavlink2_requirement_met(_link, msg)) { + return; + } + + if (!cancel_upload(_link, msg)) { + return; } if (packet.count > max_items()) { @@ -197,7 +210,7 @@ void MissionItemProtocol::handle_mission_request(GCS_MAVLINK &_link, if (!mission_request_warning_sent) { mission_request_warning_sent = true; - gcs().send_text(MAV_SEVERITY_WARNING, "got MISSION_REQUEST; use MISSION_REQUEST_INT!"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "got MISSION_REQUEST; use MISSION_REQUEST_INT!"); } // buffer space is checked by send_message @@ -211,19 +224,32 @@ void MissionItemProtocol::send_mission_item_warning() return; } mission_item_warning_sent = true; - gcs().send_text(MAV_SEVERITY_WARNING, "got MISSION_ITEM; GCS should send MISSION_ITEM_INT"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "got MISSION_ITEM; GCS should send MISSION_ITEM_INT"); } void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link, const mavlink_message_t &msg, const mavlink_mission_write_partial_list_t &packet) { + if (!mavlink2_requirement_met(_link, msg)) { + return; + } + + if (receiving) { + // someone is already uploading a mission. Deny ability to + // write a partial list here as they might be trying to + // overwrite a subset of the waypoints which the current + // transfer is uploading, and that may lead to storing a whole + // bunch of empty items. + send_mission_ack(_link, msg, MAV_MISSION_DENIED); + return; + } // start waypoint receiving if ((unsigned)packet.start_index > item_count() || (unsigned)packet.end_index > item_count() || packet.end_index < packet.start_index) { - gcs().send_text(MAV_SEVERITY_WARNING,"Flight plan update rejected"); // FIXME: Remove this anytime after 2020-01-22 + GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"Flight plan update rejected"); // FIXME: Remove this anytime after 2020-01-22 send_mission_ack(_link, msg, MAV_MISSION_ERROR); return; } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.h b/libraries/GCS_MAVLink/MissionItemProtocol.h index a7df605a428ec9..37f37fd5597165 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.h +++ b/libraries/GCS_MAVLink/MissionItemProtocol.h @@ -79,6 +79,10 @@ class MissionItemProtocol private: + // returns true if we are either not receiving, or we successfully + // cancelled an existing upload: + bool cancel_upload(const GCS_MAVLINK &_link, const mavlink_message_t &msg); + virtual void truncate(const mavlink_mission_count_t &packet) = 0; uint16_t request_i; // request index diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index 3d8cd593d02ee7..fdb3d11e6c9791 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -19,7 +19,7 @@ bool MissionItemProtocol_Fence::get_item_as_mission_item(uint16_t seq, if (fence == nullptr) { return false; } - const uint8_t num_stored_items = fence->polyfence().num_stored_items(); + const auto num_stored_items = fence->polyfence().num_stored_items(); if (seq > num_stored_items) { return false; } @@ -66,6 +66,7 @@ bool MissionItemProtocol_Fence::get_item_as_mission_item(uint16_t seq, ret_packet.x = fenceitem.loc.x; ret_packet.y = fenceitem.loc.y; ret_packet.z = 0; + ret_packet.mission_type = MAV_MISSION_TYPE_FENCE; return true; } @@ -75,7 +76,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, const mavlink_mission_request_int_t &packet, mavlink_mission_item_int_t &ret_packet) { - const uint8_t num_stored_items = _fence.polyfence().num_stored_items(); + const auto num_stored_items = _fence.polyfence().num_stored_items(); if (packet.seq > num_stored_items) { return MAV_MISSION_INVALID_SEQUENCE; } @@ -109,10 +110,16 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_Pol switch (mission_item_int.command) { case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION: ret.type = AC_PolyFenceType::POLYGON_INCLUSION; + if (mission_item_int.param1 > 255) { + return MAV_MISSION_INVALID_PARAM1; + } ret.vertex_count = mission_item_int.param1; break; case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION: ret.type = AC_PolyFenceType::POLYGON_EXCLUSION; + if (mission_item_int.param1 > 255) { + return MAV_MISSION_INVALID_PARAM1; + } ret.vertex_count = mission_item_int.param1; break; case MAV_CMD_NAV_FENCE_RETURN_POINT: @@ -218,11 +225,11 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_receive_resources(const u return MAV_MISSION_ERROR; } - const uint16_t allocation_size = count * sizeof(AC_PolyFenceItem); + const uint32_t allocation_size = count * sizeof(AC_PolyFenceItem); if (allocation_size != 0) { _new_items = (AC_PolyFenceItem*)malloc(allocation_size); if (_new_items == nullptr) { - gcs().send_text(MAV_SEVERITY_WARNING, "Out of memory for upload"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Out of memory for upload"); return MAV_MISSION_ERROR; } } @@ -233,7 +240,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_NOTHROW uint8_t[(_item_count+7)/8]; if (_updated_mask == nullptr) { return MAV_MISSION_ERROR; } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp index ee33e55188e35c..ca33979c3e2cfd 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp @@ -143,6 +143,7 @@ bool MissionItemProtocol_Rally::get_item_as_mission_item(uint16_t seq, ret_packet.x = rallypoint.lat; ret_packet.y = rallypoint.lng; ret_packet.z = rallypoint.alt; + ret_packet.mission_type = MAV_MISSION_TYPE_RALLY; return true; } diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 42724b12a2548c..d55a29a31db2ed 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -6,6 +6,8 @@ #pragma once +#include "GCS_config.h" + #include enum ap_message : uint8_t { @@ -50,16 +52,19 @@ enum ap_message : uint8_t { MSG_WIND, MSG_RANGEFINDER, MSG_DISTANCE_SENSOR, - MSG_TERRAIN, + MSG_TERRAIN_REQUEST, + MSG_TERRAIN_REPORT, MSG_BATTERY2, MSG_CAMERA_FEEDBACK, MSG_CAMERA_INFORMATION, MSG_CAMERA_SETTINGS, MSG_CAMERA_FOV_STATUS, MSG_CAMERA_CAPTURE_STATUS, + MSG_CAMERA_THERMAL_RANGE, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_STATUS, + MSG_VIDEO_STREAM_INFORMATION, MSG_OPTICAL_FLOW, MSG_MAG_CAL_PROGRESS, MSG_MAG_CAL_REPORT, @@ -94,5 +99,11 @@ enum ap_message : uint8_t { MSG_HYGROMETER, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_RELAY_STATUS, +#if AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED + MSG_HIGHRES_IMU, +#endif + MSG_AIRSPEED, + MSG_AVAILABLE_MODES, + MSG_AVAILABLE_MODES_MONITOR, MSG_LAST // MSG_LAST must be the last entry in this enum }; diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 04a96b0b5b9424..1d4c7cc77fd0ca 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -59,6 +59,7 @@ extern const AP_HAL::HAL& hal; #include #include #include +#include #define SWITCH_DEBOUNCE_TIME_MS 200 const AP_Param::GroupInfo RC_Channel::var_info[] = { @@ -191,7 +192,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 87:Crow Select // @Values{Plane}: 88:Soaring Enable // @Values{Plane}: 89:Landing Flare - // @Values{Copter, Rover, Plane, Blimp}: 90:EKF Pos Source + // @Values{Copter, Rover, Plane, Blimp}: 90:EKF Source Set // @Values{Plane}: 91:Airspeed Ratio Calibration // @Values{Plane}: 92:FBWA Mode // @Values{Copter, Rover, Plane}: 94:VTX Power @@ -209,6 +210,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter}: 109:use Custom Controller // @Values{Copter, Rover, Plane, Blimp}: 110:KillIMU3 // @Values{Copter,Plane,Rover,Blimp,Sub,Tracker}: 112:SwitchExternalAHRS + // @Values{Copter, Rover, Plane}: 113:Retract Mount2 // @Values{Plane}: 150:CRUISE Mode // @Values{Copter}: 151:TURTLE Mode // @Values{Copter}: 152:SIMPLE heading reset @@ -238,6 +240,8 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable // @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable // @Values{Copter}: 178:FlightMode Pause/Resume + // @Values{Plane}: 179:ICEngine start / stop + // @Values{Copter, Plane}: 180:Test autotuned gains after tune is complete // @Values{Rover}: 201:Roll // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail @@ -246,6 +250,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 210:Airbrakes // @Values{Rover}: 211:Walking Height // @Values{Copter, Rover, Plane}: 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw + // @Values{Copter}: 219:Transmitter Tuning // @Values{Copter, Rover, Plane}: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 // @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), @@ -624,28 +629,53 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos // init channel options switch (ch_option) { // the following functions do not need to be initialised: +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARMDISARM_AIRMODE: +#endif +#if AP_BATTERY_ENABLED case AUX_FUNC::BATTERY_MPPT_ENABLE: +#endif +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_TRIGGER: +#endif +#if AP_MISSION_ENABLED case AUX_FUNC::CLEAR_WP: +#endif case AUX_FUNC::COMPASS_LEARN: +#if AP_ARMING_ENABLED case AUX_FUNC::DISARM: +#endif case AUX_FUNC::DO_NOTHING: +#if AP_LANDINGGEAR_ENABLED case AUX_FUNC::LANDING_GEAR: +#endif case AUX_FUNC::LOST_VEHICLE_SOUND: +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED case AUX_FUNC::RELAY: case AUX_FUNC::RELAY2: case AUX_FUNC::RELAY3: case AUX_FUNC::RELAY4: case AUX_FUNC::RELAY5: case AUX_FUNC::RELAY6: +#endif +#if HAL_VISUALODOM_ENABLED case AUX_FUNC::VISODOM_ALIGN: +#endif +#if AP_AHRS_ENABLED case AUX_FUNC::EKF_LANE_SWITCH: case AUX_FUNC::EKF_YAW_RESET: +#endif +#if HAL_GENERATOR_ENABLED case AUX_FUNC::GENERATOR: // don't turn generator on or off initially - case AUX_FUNC::EKF_POS_SOURCE: +#endif +#if AP_AHRS_ENABLED + case AUX_FUNC::EKF_SOURCE_SET: +#endif +#if HAL_TORQEEDO_ENABLED case AUX_FUNC::TORQEEDO_CLEAR_ERR: +#endif +#if AP_SCRIPTING_ENABLED case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_3: @@ -654,33 +684,50 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::SCRIPTING_6: case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_8: +#endif #if AP_VIDEOTX_ENABLED case AUX_FUNC::VTX_POWER: #endif +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED case AUX_FUNC::OPTFLOW_CAL: +#endif case AUX_FUNC::TURBINE_START: +#if HAL_MOUNT_ENABLED 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: +#endif +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_STARTER: +#endif +#if COMPASS_CAL_ENABLED case AUX_FUNC::MAG_CAL: +#endif +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_IMAGE_TRACKING: +#endif +#if HAL_MOUNT_ENABLED case AUX_FUNC::MOUNT_LRF_ENABLE: - break; - - // not really aux functions: +#endif +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_THROTTLE: +#endif break; + #if HAL_ADSB_ENABLED case AUX_FUNC::AVOID_ADSB: #endif case AUX_FUNC::AVOID_PROXIMITY: +#if AP_FENCE_ENABLED case AUX_FUNC::FENCE: +#endif +#if AP_GPS_ENABLED case AUX_FUNC::GPS_DISABLE: case AUX_FUNC::GPS_DISABLE_YAW: +#endif #if AP_GRIPPER_ENABLED case AUX_FUNC::GRIPPER: #endif @@ -689,28 +736,43 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos case AUX_FUNC::KILL_IMU2: case AUX_FUNC::KILL_IMU3: #endif +#if AP_MISSION_ENABLED case AUX_FUNC::MISSION_RESET: +#endif case AUX_FUNC::MOTOR_ESTOP: case AUX_FUNC::RC_OVERRIDE_ENABLE: +#if HAL_RUNCAM_ENABLED case AUX_FUNC::RUNCAM_CONTROL: case AUX_FUNC::RUNCAM_OSD_CONTROL: +#endif +#if HAL_SPRAYER_ENABLED case AUX_FUNC::SPRAYER: +#endif +#if AP_AIRSPEED_ENABLED case AUX_FUNC::DISABLE_AIRSPEED_USE: +#endif case AUX_FUNC::FFT_NOTCH_TUNE: #if HAL_MOUNT_ENABLED case AUX_FUNC::RETRACT_MOUNT1: + case AUX_FUNC::RETRACT_MOUNT2: case AUX_FUNC::MOUNT_LOCK: #endif +#if HAL_LOGGING_ENABLED case AUX_FUNC::LOG_PAUSE: +#endif case AUX_FUNC::ARM_EMERGENCY_STOP: +#if AP_CAMERA_ENABLED case AUX_FUNC::CAMERA_REC_VIDEO: case AUX_FUNC::CAMERA_ZOOM: case AUX_FUNC::CAMERA_MANUAL_FOCUS: case AUX_FUNC::CAMERA_AUTO_FOCUS: case AUX_FUNC::CAMERA_LENS: +#endif +#if AP_AHRS_ENABLED case AUX_FUNC::AHRS_TYPE: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; +#endif default: GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n", (unsigned)(this->ch_in+1), (unsigned)ch_option); @@ -725,58 +787,111 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const RC_Channel::LookupTable RC_Channel::lookuptable[] = { +#if AP_MISSION_ENABLED { AUX_FUNC::SAVE_WP,"SaveWaypoint"}, +#endif +#if AP_CAMERA_ENABLED { AUX_FUNC::CAMERA_TRIGGER,"CameraTrigger"}, +#endif +#if AP_RANGEFINDER_ENABLED { AUX_FUNC::RANGEFINDER,"Rangefinder"}, +#endif +#if AP_FENCE_ENABLED { AUX_FUNC::FENCE,"Fence"}, +#endif +#if HAL_SPRAYER_ENABLED { AUX_FUNC::SPRAYER,"Sprayer"}, +#endif +#if HAL_PARACHUTE_ENABLED { AUX_FUNC::PARACHUTE_ENABLE,"ParachuteEnable"}, { AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"}, { AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"}, +#endif +#if AP_MISSION_ENABLED { AUX_FUNC::MISSION_RESET,"MissionReset"}, +#endif +#if HAL_MOUNT_ENABLED { AUX_FUNC::RETRACT_MOUNT1,"RetractMount1"}, + { AUX_FUNC::RETRACT_MOUNT2,"RetractMount2"}, +#endif +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY,"Relay1"}, +#endif { AUX_FUNC::MOTOR_ESTOP,"MotorEStop"}, { AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"}, +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY2,"Relay2"}, { AUX_FUNC::RELAY3,"Relay3"}, { AUX_FUNC::RELAY4,"Relay4"}, +#endif { AUX_FUNC::PRECISION_LOITER,"PrecisionLoiter"}, { AUX_FUNC::AVOID_PROXIMITY,"AvoidProximity"}, +#if AP_WINCH_ENABLED { AUX_FUNC::WINCH_ENABLE,"WinchEnable"}, { AUX_FUNC::WINCH_CONTROL,"WinchControl"}, +#endif +#if AP_MISSION_ENABLED { AUX_FUNC::CLEAR_WP,"ClearWaypoint"}, +#endif { AUX_FUNC::COMPASS_LEARN,"CompassLearn"}, { AUX_FUNC::SAILBOAT_TACK,"SailboatTack"}, +#if AP_GPS_ENABLED { AUX_FUNC::GPS_DISABLE,"GPSDisable"}, { AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"}, +#endif +#if AP_AIRSPEED_ENABLED { AUX_FUNC::DISABLE_AIRSPEED_USE,"DisableAirspeedUse"}, +#endif +#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED { AUX_FUNC::RELAY5,"Relay5"}, { AUX_FUNC::RELAY6,"Relay6"}, +#endif { AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"}, { AUX_FUNC::SURFACE_TRACKING,"SurfaceTracking"}, +#if HAL_RUNCAM_ENABLED { AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"}, { AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"}, +#endif +#if HAL_VISUALODOM_ENABLED { AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"}, +#endif { AUX_FUNC::AIRMODE, "AirMode"}, +#if AP_CAMERA_ENABLED { AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"}, +#endif +#if HAL_GENERATOR_ENABLED { AUX_FUNC::GENERATOR,"Generator"}, +#endif +#if AP_BATTERY_ENABLED { AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"}, +#endif +#if AP_AIRSPEED_AUTOCAL_ENABLE { AUX_FUNC::ARSPD_CALIBRATE,"Calibrate Airspeed"}, +#endif +#if HAL_TORQEEDO_ENABLED { AUX_FUNC::TORQEEDO_CLEAR_ERR, "Torqeedo Clear Err"}, +#endif { 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"}, +#if HAL_MOUNT_ENABLED { AUX_FUNC::MOUNT_LOCK, "MountLock"}, +#endif +#if HAL_LOGGING_ENABLED { AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"}, +#endif +#if AP_CAMERA_ENABLED { 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"}, { AUX_FUNC::CAMERA_IMAGE_TRACKING, "Camera Image Tracking"}, { AUX_FUNC::CAMERA_LENS, "Camera Lens"}, +#endif +#if HAL_MOUNT_ENABLED { AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"}, +#endif }; /* lookup the announcement for switch change */ @@ -866,10 +981,14 @@ bool RC_Channel::read_aux() bool RC_Channel::init_position_on_first_radio_read(AUX_FUNC func) const { switch (func) { +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM: case AUX_FUNC::ARM_EMERGENCY_STOP: +#endif +#if HAL_PARACHUTE_ENABLED case AUX_FUNC::PARACHUTE_RELEASE: +#endif // we do not want to process return true; @@ -1049,9 +1168,9 @@ bool RC_Channel::do_aux_function_camera_lens(const AuxSwitchPos ch_flag) } #endif // AP_CAMERA_ENABLED +#if HAL_RUNCAM_ENABLED void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) { -#if HAL_RUNCAM_ENABLED AP_RunCam *runcam = AP::runcam(); if (runcam == nullptr) { return; @@ -1068,12 +1187,10 @@ void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) runcam->stop_recording(); break; } -#endif } void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) { -#if HAL_RUNCAM_ENABLED AP_RunCam *runcam = AP::runcam(); if (runcam == nullptr) { return; @@ -1088,8 +1205,8 @@ void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) runcam->exit_osd(); break; } -#endif } +#endif #if AP_FENCE_ENABLED // enable or disable the fence @@ -1100,7 +1217,7 @@ void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag) return; } - fence->enable(ch_flag == AuxSwitchPos::HIGH); + fence->enable_configured(ch_flag == AuxSwitchPos::HIGH); } #endif @@ -1248,6 +1365,34 @@ void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag) #endif } +/** + * Perform the RETRACT_MOUNT 1/2 process. + * + * @param [in] ch_flag Position of the switch. HIGH, MIDDLE and LOW. + * @param [in] instance 0: RETRACT MOUNT 1
+ * 1: RETRACT MOUNT 2 +*/ +#if HAL_MOUNT_ENABLED +void RC_Channel::do_aux_function_retract_mount(const AuxSwitchPos ch_flag, const uint8_t instance) +{ + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + return; + } + switch (ch_flag) { + case AuxSwitchPos::HIGH: + mount->set_mode(instance,MAV_MOUNT_MODE_RETRACT); + break; + case AuxSwitchPos::MIDDLE: + // nothing + break; + case AuxSwitchPos::LOW: + mount->set_mode_to_default(instance); + break; + } +} +#endif // HAL_MOUNT_ENABLED + bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) { #if AP_SCRIPTING_ENABLED @@ -1328,6 +1473,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; #endif // AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED +#if HAL_RUNCAM_ENABLED case AUX_FUNC::RUNCAM_CONTROL: do_aux_function_runcam_control(ch_flag); break; @@ -1335,13 +1481,16 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::RUNCAM_OSD_CONTROL: do_aux_function_runcam_osd_control(ch_flag); break; +#endif +#if AP_MISSION_ENABLED case AUX_FUNC::CLEAR_WP: do_aux_function_clear_wp(ch_flag); break; case AUX_FUNC::MISSION_RESET: do_aux_function_mission_reset(ch_flag); break; +#endif #if HAL_ADSB_ENABLED case AUX_FUNC::AVOID_ADSB: @@ -1377,6 +1526,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch do_aux_function_lost_vehicle_sound(ch_flag); break; +#if AP_ARMING_ENABLED case AUX_FUNC::ARMDISARM: do_aux_function_armdisarm(ch_flag); break; @@ -1386,6 +1536,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch AP::arming().disarm(AP_Arming::Method::AUXSWITCH); } break; +#endif case AUX_FUNC::COMPASS_LEARN: if (ch_flag == AuxSwitchPos::HIGH) { @@ -1415,6 +1566,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch } #endif +#if AP_GPS_ENABLED case AUX_FUNC::GPS_DISABLE: AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH); #if HAL_EXTERNAL_AHRS_ENABLED @@ -1425,6 +1577,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::GPS_DISABLE_YAW: AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH); break; +#endif // AP_GPS_ENABLED #if AP_AIRSPEED_ENABLED case AUX_FUNC::DISABLE_AIRSPEED_USE: { @@ -1473,24 +1626,24 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; #endif - case AUX_FUNC::EKF_POS_SOURCE: { - uint8_t source_set = 0; + case AUX_FUNC::EKF_SOURCE_SET: { + AP_NavEKF_Source::SourceSetSelection source_set = AP_NavEKF_Source::SourceSetSelection::PRIMARY; switch (ch_flag) { case AuxSwitchPos::LOW: // low switches to primary source - source_set = 0; + source_set = AP_NavEKF_Source::SourceSetSelection::PRIMARY; break; case AuxSwitchPos::MIDDLE: // middle switches to secondary source - source_set = 1; + source_set = AP_NavEKF_Source::SourceSetSelection::SECONDARY; break; case AuxSwitchPos::HIGH: // high switches to tertiary source - source_set = 2; + source_set = AP_NavEKF_Source::SourceSetSelection::TERTIARY; break; } AP::ahrs().set_posvelyaw_source_set(source_set); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Using EKF Source Set %u", source_set+1); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Using EKF Source Set %u", uint8_t(source_set)+1); break; } @@ -1570,24 +1723,13 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch #endif // AP_CAMERA_ENABLED #if HAL_MOUNT_ENABLED - case AUX_FUNC::RETRACT_MOUNT1: { - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - break; - } - switch (ch_flag) { - case AuxSwitchPos::HIGH: - mount->set_mode(0,MAV_MOUNT_MODE_RETRACT); - break; - case AuxSwitchPos::MIDDLE: - // nothing - break; - case AuxSwitchPos::LOW: - mount->set_mode_to_default(0); - break; - } + case AUX_FUNC::RETRACT_MOUNT1: + do_aux_function_retract_mount(ch_flag, 0); + break; + + case AUX_FUNC::RETRACT_MOUNT2: + do_aux_function_retract_mount(ch_flag, 1); break; - } case AUX_FUNC::MOUNT_LOCK: { AP_Mount *mount = AP::mount(); @@ -1671,6 +1813,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch break; } +#if AP_AHRS_ENABLED case AUX_FUNC::EKF_LANE_SWITCH: // used to test emergency lane switch AP::ahrs().check_lane_switch(); @@ -1687,7 +1830,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch #endif break; } - +#endif // AP_AHRS_ENABLED #if HAL_TORQEEDO_ENABLED // clear torqeedo error @@ -1703,12 +1846,15 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch #endif // do nothing for these functions +#if HAL_MOUNT_ENABLED 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: +#endif +#if AP_SCRIPTING_ENABLED case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_3: @@ -1717,12 +1863,15 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch case AUX_FUNC::SCRIPTING_6: case AUX_FUNC::SCRIPTING_7: case AUX_FUNC::SCRIPTING_8: +#endif break; +#if HAL_GENERATOR_ENABLED case AUX_FUNC::LOWEHEISER_THROTTLE: case AUX_FUNC::LOWEHEISER_STARTER: // monitored by the library itself break; +#endif default: GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option); @@ -1772,14 +1921,6 @@ RC_Channel::AuxSwitchPos RC_Channel::get_aux_switch_pos() const return position; } -// return switch position value as LOW, MIDDLE, HIGH -// if reading the switch fails then it returns LOW -RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) const -{ - const RC_Channel* chan = rc().channel(rcmapchan-1); - return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW; -} - RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::AUX_FUNC option) { for (uint8_t i=0; i used_auxsw_options; for (uint8_t i=0; ioption.get(); - if (option >= sizeof(auxsw_option_counts)) { + if (option == (uint16_t)RC_Channel::AUX_FUNC::DO_NOTHING) { continue; } - auxsw_option_counts[option]++; - } - - for (uint16_t i=0; i= used_auxsw_options.size()) { continue; } - if (auxsw_option_counts[i] > 1) { + if (used_auxsw_options.get(option)) { return true; } + used_auxsw_options.set(option); } return false; } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 2d8d1ab850a2ba..7194fa092b80e3 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -26,6 +26,12 @@ class RC_Channel { RANGE = 1, }; + // ch returns the radio channel be read, starting at 1. so + // typically Roll=1, Pitch=2, throttle=3, yaw=4. If this returns + // 0 then this is the dummy object which means that one of roll, + // pitch, yaw or throttle has not been configured correctly. + uint8_t ch() const { return ch_in + 1; } + // setup the control preferences void set_range(uint16_t high); uint16_t get_range() const { return high_in; } @@ -119,7 +125,7 @@ class RC_Channel { ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited SPRAYER = 15, // enable/disable the crop sprayer AUTO = 16, // change to auto flight mode - AUTOTUNE = 17, // auto tune + AUTOTUNE_MODE = 17, // auto tune LAND = 18, // change to LAND flight mode GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on PARACHUTE_ENABLE = 21, // Parachute enable/disable @@ -191,7 +197,7 @@ class RC_Channel { CROW_SELECT = 87, // select CROW mode for diff spoilers;high disables,mid forces progressive SOARING = 88, // three-position switch to set soaring mode LANDING_FLARE = 89, // force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up - EKF_POS_SOURCE = 90, // change EKF position source between primary, secondary and tertiary sources + EKF_SOURCE_SET = 90, // change EKF data source set between primary, secondary and tertiary ARSPD_CALIBRATE= 91, // calibrate airspeed ratio FBWA = 92, // Fly-By-Wire-A RELOCATE_MISSION = 93, // used in separate branch MISSION_RELATIVE @@ -217,6 +223,7 @@ class RC_Channel { KILL_IMU3 = 110, // disable third IMU (for IMU failure testing) LOWEHEISER_STARTER = 111, // allows for manually running starter AHRS_TYPE = 112, // change AHRS_EKF_TYPE + RETRACT_MOUNT2 = 113, // Retract Mount2 // 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 @@ -251,6 +258,9 @@ class RC_Channel { VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint + ICE_START_STOP = 179, // AP_ICEngine start stop + AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains + QUICKTUNE = 181, //quicktune 3 position switch // inputs from 200 will eventually used to replace RCMAP @@ -270,6 +280,7 @@ class RC_Channel { MOUNT2_PITCH = 216, // mount3 pitch input MOUNT2_YAW = 217, // mount4 yaw input LOWEHEISER_THROTTLE= 218, // allows for throttle on slider + TRANSMITTER_TUNING = 219, // use a transmitter knob or slider for in-flight tuning // inputs 248-249 are reserved for the Skybrush fork at // https://github.com/skybrush-io/ardupilot @@ -362,6 +373,7 @@ class RC_Channel { 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); + void do_aux_function_retract_mount(const AuxSwitchPos ch_flag, const uint8_t instance); typedef int8_t modeswitch_pos_t; virtual void mode_switch_changed(modeswitch_pos_t new_pos) { @@ -493,7 +505,6 @@ class RC_Channels { class RC_Channel *find_channel_for_option(const RC_Channel::AUX_FUNC option); bool duplicate_options_exist(); - RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const; void convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option); void init_aux_all(); @@ -607,6 +618,12 @@ class RC_Channels { // get failsafe timeout in milliseconds uint32_t get_fs_timeout_ms() const { return MAX(_fs_timeout * 1000, 100); } + // methods which return RC input channels used for various axes. + RC_Channel &get_roll_channel(); + RC_Channel &get_pitch_channel(); + RC_Channel &get_yaw_channel(); + RC_Channel &get_throttle_channel(); + protected: void new_override_received() { @@ -648,6 +665,9 @@ class RC_Channels { void set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos); #endif + + RC_Channel &get_rcmap_channel_nonnull(uint8_t rcmap_number); + RC_Channel dummy_rcchannel; }; RC_Channels &rc(); diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 9ec73c5dab365e..cd32cf938ba3bd 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -30,6 +30,7 @@ extern const AP_HAL::HAL& hal; #include #include +#include #include "RC_Channel.h" @@ -307,6 +308,39 @@ void RC_Channels::set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwi } #endif // AP_SCRIPTING_ENABLED +#if AP_RCMAPPER_ENABLED +// these methods return an RC_Channel pointers based on values from +// AP_::rcmap(). The return value is guaranteed to be not-null to +// allow use of the pointer without checking it for null-ness. If an +// invalid option has been chosen somehow then the returned channel +// will be a dummy channel. +RC_Channel &RC_Channels::get_rcmap_channel_nonnull(uint8_t rcmap_number) +{ + RC_Channel *ret = RC_Channels::rc_channel(rcmap_number-1); + if (ret != nullptr) { + return *ret; + } + return dummy_rcchannel; +} +RC_Channel &RC_Channels::get_roll_channel() +{ + return get_rcmap_channel_nonnull(AP::rcmap()->roll()); +}; +RC_Channel &RC_Channels::get_pitch_channel() +{ + return get_rcmap_channel_nonnull(AP::rcmap()->pitch()); +}; +RC_Channel &RC_Channels::get_throttle_channel() +{ + return get_rcmap_channel_nonnull(AP::rcmap()->throttle()); +}; +RC_Channel &RC_Channels::get_yaw_channel() +{ + return get_rcmap_channel_nonnull(AP::rcmap()->yaw()); +}; +#endif // AP_RCMAPPER_ENABLED + + // singleton instance RC_Channels *RC_Channels::_singleton; diff --git a/libraries/SITL/SIM_ADSB_Sagetech_MXS.h b/libraries/SITL/SIM_ADSB_Sagetech_MXS.h index 67e4fbda92f6c2..18eba0f4dbd57e 100644 --- a/libraries/SITL/SIM_ADSB_Sagetech_MXS.h +++ b/libraries/SITL/SIM_ADSB_Sagetech_MXS.h @@ -70,9 +70,9 @@ class ADSB_Sagetech_MXS : public ADSB_Device { class PACKED PackedMessage { public: PackedMessage(T _msg, MsgType _msgtype, uint8_t _msgid) : - msg{_msg}, msgtype{_msgtype}, - msgid{_msgid} + msgid{_msgid}, + msg{_msg} { update_checksum(); } diff --git a/libraries/SITL/SIM_AirSim.cpp b/libraries/SITL/SIM_AirSim.cpp index abba54027dbf23..989da084200e5f 100644 --- a/libraries/SITL/SIM_AirSim.cpp +++ b/libraries/SITL/SIM_AirSim.cpp @@ -55,12 +55,14 @@ AirSim::AirSim(const char *frame_str) : */ void AirSim::set_interface_ports(const char* address, const int port_in, const int port_out) { - if (!sock.bind("0.0.0.0", port_in)) { + static const char *port_in_addr = "0.0.0.0"; + + if (!sock.bind(port_in_addr, port_in)) { printf("Unable to bind Airsim sensor_in socket at port %u - Error: %s\n", port_in, strerror(errno)); return; } - printf("Bind SITL sensor input at %s:%u\n", "127.0.0.1", port_in); + printf("Bind SITL sensor input at %s:%u\n", port_in_addr, port_in); sock.set_blocking(false); sock.reuseaddress(); diff --git a/libraries/SITL/SIM_AirSim.h b/libraries/SITL/SIM_AirSim.h index 1e9b75c0e648ae..151a4fcb326edd 100644 --- a/libraries/SITL/SIM_AirSim.h +++ b/libraries/SITL/SIM_AirSim.h @@ -44,7 +44,7 @@ class AirSim : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new AirSim(frame_str); + return NEW_NOTHROW AirSim(frame_str); } /* Create and set in/out socket for Airsim simulator */ diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 2790c692e747b5..c0469abc7cf20a 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -22,12 +22,6 @@ #include #include -#if defined(__CYGWIN__) || defined(__CYGWIN64__) -#include -#include -#include -#endif - #include #include #include @@ -37,11 +31,19 @@ #include #include #include +#include +#include +#include using namespace SITL; extern const AP_HAL::HAL& hal; +// the SITL HAL can add information about pausing the simulation and its effect on the UART. Not present when we're compiling for simulation-on-hardware +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +extern const HAL_SITL& hal_sitl; +#endif + /* parent class for all simulator types */ @@ -176,16 +178,18 @@ void Aircraft::update_position(void) pos_home.x, pos_home.y, pos_home.z); #endif - uint32_t now = AP_HAL::millis(); - if (now - last_one_hz_ms >= 1000) { - // shift origin of position at 1Hz to current location - // this prevents sperical errors building up in the GPS data - last_one_hz_ms = now; - Vector2d diffNE = origin.get_distance_NE_double(location); - position.xy() -= diffNE; - smoothing.position.xy() -= diffNE; - origin.lat = location.lat; - origin.lng = location.lng; + if (!disable_origin_movement) { + uint32_t now = AP_HAL::millis(); + if (now - last_one_hz_ms >= 1000) { + // shift origin of position at 1Hz to current location + // this prevents spherical errors building up in the GPS data + last_one_hz_ms = now; + Vector2d diffNE = origin.get_distance_NE_double(location); + position.xy() -= diffNE; + smoothing.position.xy() -= diffNE; + origin.lat = location.lat; + origin.lng = location.lng; + } } } @@ -455,6 +459,14 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) } #if HAL_LOGGING_ENABLED +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + // the SITL HAL can add information about pausing the simulation + // and its effect on the UART. Not present when we're compiling + // for simulation-on-hardware + const uint32_t full_count = hal_sitl.get_uart_output_full_queue_count(); +#else + const uint32_t full_count = 0; +#endif // for EKF comparison log relhome pos and velocity at loop rate static uint16_t last_ticks; uint16_t ticks = AP::scheduler().ticks(); @@ -471,31 +483,45 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) // @Field: VD: Velocity down // @Field: As: Airspeed // @Field: ASpdU: Achieved simulation speedup value +// @Field: UFC: Number of times simulation paused for serial0 output Vector3d pos = get_position_relhome(); Vector3f vel = get_velocity_ef(); - AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU", - "Qdddfffff", - AP_HAL::micros64(), - pos.x, pos.y, pos.z, - vel.x, vel.y, vel.z, - airspeed_pitot, - achieved_rate_hz/rate_hz); + AP::logger().WriteStreaming( + "SIM2", + "TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU,UFC", + "QdddfffffI", + AP_HAL::micros64(), + pos.x, pos.y, pos.z, + vel.x, vel.y, vel.z, + airspeed_pitot, + achieved_rate_hz/rate_hz, + full_count + ); } #endif } -// returns perpendicular height to surface downward-facing rangefinder -// is bouncing off: +/* + rover and copter have special handling for horizontal rangefinders + as distance to obstacles - this takes effect for yaw-only + orientations + */ +#define SITL_RANGEFINDER_AS_OBJECT_SENSOR (APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_Rover)) +#define SITL_RANGEFINDER_IS_YAW_ONLY(orientation) (orientation <= ROTATION_YAW_315) + +// returns perpendicular height to surface rangefinder is bouncing off float Aircraft::perpendicular_distance_to_rangefinder_surface() const { - switch ((Rotation)sitl->sonar_rot.get()) { - case Rotation::ROTATION_PITCH_270: - return sitl->state.height_agl; - case ROTATION_NONE ... ROTATION_YAW_315: +#if SITL_RANGEFINDER_AS_OBJECT_SENSOR + const auto orientation = (Rotation)sitl->sonar_rot.get(); + if (SITL_RANGEFINDER_IS_YAW_ONLY(orientation)) { + // assume these are avoidance sensors return sitl->measure_distance_at_angle_bf(location, sitl->sonar_rot.get()*45); - default: - AP_BoardConfig::config_error("Bad simulated sonar rotation"); } +#endif + + // default is ground sensing rangefinders + return sitl->state.height_agl; } float Aircraft::rangefinder_range() const @@ -527,11 +553,6 @@ float Aircraft::rangefinder_range() const } } - if (fabs(roll) >= 90.0 || fabs(pitch) >= 90.0) { - // not going to hit the ground.... - return INFINITY; - } - float altitude = perpendicular_distance_to_rangefinder_surface(); // sensor position offset in body frame @@ -549,8 +570,41 @@ float Aircraft::rangefinder_range() const altitude -= relPosSensorEF.z; } - // adjust for apparent altitude with roll - altitude /= cosf(radians(roll)) * cosf(radians(pitch)); + const auto orientation = (Rotation)sitl->sonar_rot.get(); +#if SITL_RANGEFINDER_AS_OBJECT_SENSOR + /* + rover and copter using SITL rangefinders as obstacle sensors + */ + if (SITL_RANGEFINDER_IS_YAW_ONLY(orientation)) { + if (fabs(roll) >= 90.0 || fabs(pitch) >= 90.0) { + // not going to hit the ground.... + return INFINITY; + } + altitude /= cosf(radians(roll)) * cosf(radians(pitch)); + } else +#endif + { + // adjust for rotation based on orientation of the sensor + Matrix3f rotmat; + sitl->state.quaternion.rotation_matrix(rotmat); + Vector3f v{1, 0, 0}; + v.rotate(orientation); + v = rotmat * v; + + if (!is_positive(v.z)) { + return INFINITY; + } + altitude /= v.z; + + // this is awful, but there are drawbacks to assuming an + // infinite plane. If we don't do this here then we end up + // with a ridiculous rangefinder range, and that can cause + // floating point exceptions when we return a distance in cm + // from the AP_RangeFinder_SITL. + if (altitude > 100000) { + return INFINITY; + } + } // Add some noise on reading altitude += sitl->sonar_noise * rand_float(); @@ -558,18 +612,21 @@ float Aircraft::rangefinder_range() const return altitude; } +#if defined(__CYGWIN__) || defined(__CYGWIN64__) +extern "C" { uint32_t timeGetTime(); } +#endif // 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__) - static DWORD tPrev; + static uint32_t tPrev; static uint64_t last_ret_us; if (tPrev == 0) { tPrev = timeGetTime(); return 0; } - DWORD now = timeGetTime(); + uint32_t now = timeGetTime(); last_ret_us += (uint64_t)((now - tPrev)*1000UL); tPrev = now; return last_ret_us; @@ -619,8 +676,18 @@ void Aircraft::update_model(const struct sitl_input &input) */ void Aircraft::update_dynamics(const Vector3f &rot_accel) { + // update eas2tas and air density +#if AP_AHRS_ENABLED + eas2tas = AP::ahrs().get_EAS2TAS(); +#endif + air_density = SSL_AIR_DENSITY / sq(eas2tas); + const float delta_time = frame_time_us * 1.0e-6f; + // update eas2tas and air density + eas2tas = AP_Baro::get_EAS2TAS_for_alt_amsl(location.alt*0.01); + air_density = AP_Baro::get_air_density_for_alt_amsl(location.alt*0.01); + // update rotational rates in body frame gyro += rot_accel * delta_time; @@ -628,6 +695,12 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f)); gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f)); + // limit body accel to 64G + const float accel_limit = 64*GRAVITY_MSS; + accel_body.x = constrain_float(accel_body.x, -accel_limit, accel_limit); + accel_body.y = constrain_float(accel_body.y, -accel_limit, accel_limit); + accel_body.z = constrain_float(accel_body.z, -accel_limit, accel_limit); + // update attitude dcm.rotate(gyro * delta_time); dcm.normalize(); @@ -659,10 +732,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) velocity_air_bf = dcm.transposed() * velocity_air_ef; // airspeed - airspeed = velocity_air_ef.length(); - - // airspeed as seen by a fwd pitot tube (limited to 120m/s) - airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f); + update_eas_airspeed(); // constrain height to the ground if (on_ground()) { @@ -675,7 +745,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) // get speed of ground movement (for ship takeoff/landing) float yaw_rate = 0; #if AP_SIM_SHIP_ENABLED - const Vector2f ship_movement = sitl->shipsim.get_ground_speed_adjustment(location, yaw_rate); + const Vector2f ship_movement = sitl->models.shipsim.get_ground_speed_adjustment(location, yaw_rate); const Vector3f gnd_movement(ship_movement.x, ship_movement.y, 0); #else const Vector3f gnd_movement; @@ -764,6 +834,11 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) } } + // update slung payload +#if AP_SIM_SLUNGPAYLOAD_ENABLED + sitl->models.slung_payload_sim.update(get_position_relhome(), velocity_ef, accel_earth, wind_ef); +#endif + // allow for changes in physics step adjust_frame_time(constrain_float(sitl->loop_rate_hz, rate_hz-1, rate_hz+1)); } @@ -896,34 +971,13 @@ void Aircraft::smooth_sensors(void) smoothing.last_update_us = now; } -/* - return a filtered servo input as a value from -1 to 1 - servo is assumed to be 1000 to 2000, trim at 1500 - */ -float Aircraft::filtered_idx(float v, uint8_t idx) -{ - if (sitl->servo_speed <= 0) { - return v; - } - const float cutoff = 1.0f / (2 * M_PI * sitl->servo_speed); - servo_filter[idx].set_cutoff_frequency(cutoff); - - if (idx >= ARRAY_SIZE(servo_filter)) { - AP_HAL::panic("Attempt to filter invalid servo at offset %u", (unsigned)idx); - } - - return servo_filter[idx].apply(v, frame_time_us * 1.0e-6f); -} - - /* return a filtered servo input as a value from -1 to 1 servo is assumed to be 1000 to 2000, trim at 1500 */ float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx) { - const float v = (input.servos[idx] - 1500)/500.0f; - return filtered_idx(v, idx); + return servo_filter[idx].filter_angle(input.servos[idx], frame_time_us * 1.0e-6); } /* @@ -932,8 +986,14 @@ float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx */ float Aircraft::filtered_servo_range(const struct sitl_input &input, uint8_t idx) { - const float v = (input.servos[idx] - 1000)/1000.0f; - return filtered_idx(v, idx); + return servo_filter[idx].filter_range(input.servos[idx], frame_time_us * 1.0e-6); +} + +// setup filtering for servo +void Aircraft::filtered_servo_setup(uint8_t idx, uint16_t pwm_min, uint16_t pwm_max, float deflection_deg) +{ + servo_filter[idx].set_pwm_range(pwm_min, pwm_max); + servo_filter[idx].set_deflection(deflection_deg); } // extrapolate sensors by a given delta time in seconds @@ -956,6 +1016,45 @@ void Aircraft::extrapolate_sensors(float delta_time) velocity_air_bf = dcm.transposed() * velocity_air_ef; } +bool Aircraft::Clamp::clamped(Aircraft &aircraft, const struct sitl_input &input) +{ + const auto clamp_ch = AP::sitl()->clamp_ch; + if (clamp_ch < 1) { + return false; + } + const uint32_t clamp_idx = clamp_ch - 1; + if (clamp_idx > ARRAY_SIZE(input.servos)) { + return false; + } + const uint16_t servo_pos = input.servos[clamp_idx]; + bool new_clamped = currently_clamped; + if (servo_pos < 1200) { + if (currently_clamped) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SITL: Clamp: released vehicle"); + new_clamped = false; + } + grab_attempted = false; + } else { + // re-clamp if < 10cm from home + if (servo_pos > 1800 && !grab_attempted) { + const Vector3d pos = aircraft.get_position_relhome(); + const float distance_from_home = pos.length(); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SITL: Clamp: dist=%f", distance_from_home); + if (distance_from_home < 0.5) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SITL: Clamp: grabbed vehicle"); + new_clamped = true; + } else if (!grab_attempted) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SITL: Clamp: missed vehicle"); + } + grab_attempted = true; + } + } + + currently_clamped = new_clamped; + + return currently_clamped; +} + void Aircraft::update_external_payload(const struct sitl_input &input) { external_payload_mass = 0; @@ -968,6 +1067,9 @@ void Aircraft::update_external_payload(const struct sitl_input &input) { const float range = rangefinder_range(); + if (!isinf(range) && range > 100000) { + AP_HAL::panic("Bad rangefinder calculation"); + } for (uint8_t i=0; ishipsim.update(); + sitl->models.shipsim.update(); #endif // update IntelligentEnergy 2.4kW generator @@ -1037,6 +1139,19 @@ void Aircraft::update_external_payload(const struct sitl_input &input) dronecan->update(); } #endif + +#if AP_SIM_GPIO_LED_1_ENABLED + sim_led1.update(*this); +#endif +#if AP_SIM_GPIO_LED_2_ENABLED + sim_led2.update(*this); +#endif +#if AP_SIM_GPIO_LED_3_ENABLED + sim_led3.update(*this); +#endif +#if AP_SIM_GPIO_LED_RGB_ENABLED + sim_ledrgb.update(*this); +#endif } void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel) @@ -1158,6 +1273,19 @@ void Aircraft::add_twist_forces(Vector3f &rot_accel) } } +#if AP_SIM_SLUNGPAYLOAD_ENABLED +// add body-frame force due to slung payload +void Aircraft::add_slungpayload_forces(Vector3f &body_accel) +{ + Vector3f forces_ef; + sitl->models.slung_payload_sim.get_forces_on_vehicle(forces_ef); + + // convert ef forces to body-frame accelerations (acceleration = force / mass) + const Vector3f accel_bf = dcm.transposed() * forces_ef / mass; + body_accel += accel_bf; +} +#endif + /* get position relative to home */ @@ -1167,3 +1295,37 @@ Vector3d Aircraft::get_position_relhome() const pos.xy() += home.get_distance_NE_double(origin); return pos; } + +// get air density in kg/m^3 +float Aircraft::get_air_density(float alt_amsl) const +{ + return AP_Baro::get_air_density_for_alt_amsl(alt_amsl); +} + +/* + update EAS airspeed and pitot speed + */ +void Aircraft::update_eas_airspeed() +{ + airspeed = velocity_air_ef.length() / eas2tas; + + /* + airspeed as seen by a fwd pitot tube (limited to 120m/s) + */ + airspeed_pitot = airspeed; + + // calculate angle between the local flow vector and a pitot tube aligned with the X body axis + const float pitot_aoa = atan2f(sqrtf(sq(velocity_air_bf.y) + sq(velocity_air_bf.z)), velocity_air_bf.x); + + /* + assume the pitot can correctly capture airspeed up to 20 degrees off the nose + and follows a cose law outside that range + */ + const float max_pitot_aoa = radians(20); + if (pitot_aoa > radians(90)) { + airspeed_pitot = 0; + } else if (pitot_aoa > max_pitot_aoa) { + const float gain_factor = M_PI_2 / (radians(90) - max_pitot_aoa); + airspeed_pitot *= cosf((pitot_aoa - max_pitot_aoa) * gain_factor); + } +} diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 1d79437e9065d2..e84a078ac8fafc 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -37,6 +37,11 @@ #include "SIM_Battery.h" #include #include "SIM_JSON_Master.h" +#include "ServoModel.h" +#include "SIM_GPIO_LED_1.h" +#include "SIM_GPIO_LED_2.h" +#include "SIM_GPIO_LED_3.h" +#include "SIM_GPIO_LED_RGB.h" namespace SITL { @@ -102,6 +107,7 @@ class Aircraft { return velocity_ef; } + // return TAS airspeed in earth frame const Vector3f &get_velocity_air_ef(void) const { return velocity_air_ef; } @@ -128,6 +134,9 @@ class Aircraft { // get position relative to home Vector3d get_position_relhome() const; + // get air density in kg/m^3 + float get_air_density(float alt_amsl) const; + // distance the rangefinder is perceiving float rangefinder_range() const; @@ -176,15 +185,15 @@ class Aircraft { Vector3f gyro; // rad/s Vector3f velocity_ef; // m/s, earth frame Vector3f wind_ef; // m/s, earth frame - Vector3f velocity_air_ef; // velocity relative to airmass, earth frame + Vector3f velocity_air_ef; // velocity relative to airmass, earth frame (true airspeed) Vector3f velocity_air_bf; // velocity relative to airmass, body frame Vector3d position; // meters, NED from origin float mass; // kg float external_payload_mass; // kg Vector3f accel_body{0.0f, 0.0f, -GRAVITY_MSS}; // m/s/s NED, body frame - float airspeed; // m/s, apparent airspeed - float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube - float battery_voltage = 0.0f; + float airspeed; // m/s, EAS airspeed + float airspeed_pitot; // m/s, EAS airspeed, as seen by fwd pitot tube + float battery_voltage; float battery_current; float local_ground_level; // ground level at local position bool lock_step_scheduled; @@ -241,6 +250,8 @@ class Aircraft { bool use_time_sync = true; float last_speedup = -1.0f; const char *config_ = ""; + float eas2tas = 1.0; + float air_density = SSL_AIR_DENSITY; // allow for AHRS_ORIENTATION AP_Int8 *ahrs_orientation; @@ -257,6 +268,7 @@ class Aircraft { } ground_behavior; bool use_smoothing; + bool disable_origin_movement; float ground_height_difference() const; @@ -297,9 +309,9 @@ class Aircraft { void update_wind(const struct sitl_input &input); // return filtered servo input as -1 to 1 range - float filtered_idx(float v, uint8_t idx); float filtered_servo_angle(const struct sitl_input &input, uint8_t idx); float filtered_servo_range(const struct sitl_input &input, uint8_t idx); + void filtered_servo_setup(uint8_t idx, uint16_t pwm_min, uint16_t pwm_max, float deflection_deg); // extrapolate sensors by a given delta time in seconds void extrapolate_sensors(float delta_time); @@ -310,9 +322,26 @@ class Aircraft { void add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel); void add_twist_forces(Vector3f &rot_accel); +#if AP_SIM_SLUNGPAYLOAD_ENABLED + // add body-frame force due to slung payload + void add_slungpayload_forces(Vector3f &body_accel); +#endif + // get local thermal updraft float get_local_updraft(const Vector3d ¤tPos); + // update EAS speeds + void update_eas_airspeed(); + + // clamp support + class Clamp { + public: + bool clamped(class Aircraft&, const struct sitl_input &input); // true if the vehicle is currently clamped down + private: + bool currently_clamped; + bool grab_attempted; // avoid warning multiple times about missed grab + } clamp; + private: uint64_t last_time_us; uint32_t frame_counter; @@ -333,7 +362,7 @@ class Aircraft { Location location; } smoothing; - LowPassFilterFloat servo_filter[5]; + ServoModel servo_filter[16]; Buzzer *buzzer; Sprayer *sprayer; @@ -352,6 +381,21 @@ class Aircraft { #if AP_TEST_DRONECAN_DRIVERS DroneCANDevice *dronecan; #endif + + +#if AP_SIM_GPIO_LED_1_ENABLED + GPIO_LED_1 sim_led1{8}; // pin to match sitl.h +#endif +#if AP_SIM_GPIO_LED_2_ENABLED + GPIO_LED_2 sim_led2{13, 14}; // pins to match sitl.h +#endif +#if AP_SIM_GPIO_LED_3_ENABLED + GPIO_LED_3 sim_led3{13, 14, 15}; // pins to match sitl.h +#endif +#if AP_SIM_GPIO_LED_RGB_ENABLED + GPIO_LED_RGB sim_ledrgb{8, 9, 10}; // pins to match sitl.h +#endif + }; } // namespace SITL diff --git a/libraries/SITL/SIM_Airspeed_DLVR.cpp b/libraries/SITL/SIM_Airspeed_DLVR.cpp index 4cae7047a4ab6b..265185fae44562 100644 --- a/libraries/SITL/SIM_Airspeed_DLVR.cpp +++ b/libraries/SITL/SIM_Airspeed_DLVR.cpp @@ -65,9 +65,6 @@ void SITL::Airspeed_DLVR::update(const class Aircraft &aircraft) float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - 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; + temperature = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); } diff --git a/libraries/SITL/SIM_BalanceBot.h b/libraries/SITL/SIM_BalanceBot.h index be7e88ebb82eef..705edfd3b4a934 100644 --- a/libraries/SITL/SIM_BalanceBot.h +++ b/libraries/SITL/SIM_BalanceBot.h @@ -31,7 +31,7 @@ class BalanceBot : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new BalanceBot(frame_str); + return NEW_NOTHROW BalanceBot(frame_str); } private: diff --git a/libraries/SITL/SIM_Balloon.cpp b/libraries/SITL/SIM_Balloon.cpp index 77eca0b1ab936f..218610be8b465e 100644 --- a/libraries/SITL/SIM_Balloon.cpp +++ b/libraries/SITL/SIM_Balloon.cpp @@ -50,7 +50,7 @@ void Balloon::update(const struct sitl_input &input) Vector3f rot_accel = -gyro * radians(400) / terminal_rotation_rate; // air resistance - Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity); + Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity) / eas2tas; float lift_accel = 0; if (!burst && released) { diff --git a/libraries/SITL/SIM_Balloon.h b/libraries/SITL/SIM_Balloon.h index 081bb36be3a1fb..77e0d1820722da 100644 --- a/libraries/SITL/SIM_Balloon.h +++ b/libraries/SITL/SIM_Balloon.h @@ -34,7 +34,7 @@ class Balloon : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Balloon(frame_str); + return NEW_NOTHROW Balloon(frame_str); } private: diff --git a/libraries/SITL/SIM_Battery.cpp b/libraries/SITL/SIM_Battery.cpp index d5a7219c36d77d..4c94bd305140b1 100644 --- a/libraries/SITL/SIM_Battery.cpp +++ b/libraries/SITL/SIM_Battery.cpp @@ -149,7 +149,7 @@ void Battery::set_current(float current) voltage = get_resting_voltage(100 * remaining_Ah / capacity_Ah) - voltage_delta; } - voltage_filter.apply(voltage); + voltage_filter.apply(voltage, dt); { const uint64_t temperature_dt = now - temperature.last_update_micros; diff --git a/libraries/SITL/SIM_Blimp.h b/libraries/SITL/SIM_Blimp.h index 1cdfc504df2c82..0a01cd3a743290 100644 --- a/libraries/SITL/SIM_Blimp.h +++ b/libraries/SITL/SIM_Blimp.h @@ -51,7 +51,7 @@ class Blimp : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Blimp(frame_str); + return NEW_NOTHROW Blimp(frame_str); } protected: diff --git a/libraries/SITL/SIM_Buzzer.cpp b/libraries/SITL/SIM_Buzzer.cpp index 0cd154505217fd..3e7a1b05e23167 100644 --- a/libraries/SITL/SIM_Buzzer.cpp +++ b/libraries/SITL/SIM_Buzzer.cpp @@ -102,19 +102,19 @@ void Buzzer::update(const struct sitl_input &input) const uint32_t now = AP_HAL::millis(); if (on) { if (!was_on) { - gcs().send_text(MAV_SEVERITY_WARNING, "%u: Buzzer on", now); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%u: Buzzer on", now); on_time = now; was_on = true; xdemoSound.play(); } if (now - on_time > duration_ms/2) { - gcs().send_text(MAV_SEVERITY_WARNING, "%u: Buzzer on again", now); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%u: Buzzer on again", now); on_time = now; xdemoSound.play(); } } else { if (was_on) { - gcs().send_text(MAV_SEVERITY_WARNING, "%u: Buzzer off", now); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%u: Buzzer off", now); xdemoSound.stop(); was_on = false; } diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index b3a5699f99156e..47e91ed020fa9d 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -44,7 +44,7 @@ class CRRCSim : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new CRRCSim(frame_str); + return NEW_NOTHROW CRRCSim(frame_str); } private: diff --git a/libraries/SITL/SIM_Calibration.h b/libraries/SITL/SIM_Calibration.h index f2ded133fb3376..a60d31826df3f2 100644 --- a/libraries/SITL/SIM_Calibration.h +++ b/libraries/SITL/SIM_Calibration.h @@ -69,7 +69,7 @@ class Calibration : public Aircraft { void update(const struct sitl_input &input) override; static Aircraft *create(const char *frame_str) { - return new Calibration(frame_str); + return NEW_NOTHROW Calibration(frame_str); } private: diff --git a/libraries/SITL/SIM_DroneCANDevice.cpp b/libraries/SITL/SIM_DroneCANDevice.cpp index 598a53a0dadeb9..de7d43c451d7e9 100644 --- a/libraries/SITL/SIM_DroneCANDevice.cpp +++ b/libraries/SITL/SIM_DroneCANDevice.cpp @@ -92,11 +92,10 @@ void DroneCANDevice::update_baro() { } #if !APM_BUILD_TYPE(APM_BUILD_ArduSub) - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - float p = SSL_AIR_PRESSURE * delta; - float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + float p, t_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, t_K); + float T = KELVIN_TO_C(t_K); AP_Baro_SITL::temperature_adjustment(p, T); T = C_TO_KELVIN(T); @@ -131,11 +130,8 @@ void DroneCANDevice::update_airspeed() { // this was mostly swiped from SIM_Airspeed_DLVR: const float sim_alt = AP::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 - msg.static_air_temperature = SSL_AIR_TEMPERATURE * theta + 25.0; + msg.static_air_temperature = C_TO_KELVIN(AP_Baro::get_temperatureC_for_alt_amsl(sim_alt)); static Canard::Publisher raw_air_pub{CanardInterface::get_test_iface()}; raw_air_pub.broadcast(msg); diff --git a/libraries/SITL/SIM_EFI_Hirth.cpp b/libraries/SITL/SIM_EFI_Hirth.cpp index 2dbafba610b01a..994bdae423a1f1 100644 --- a/libraries/SITL/SIM_EFI_Hirth.cpp +++ b/libraries/SITL/SIM_EFI_Hirth.cpp @@ -61,13 +61,17 @@ void EFI_Hirth::update_receive() if (received_packet_code == PacketCode::SetValues) { // do this synchronously for now handle_set_values(); - } else { + } else if (uint8_t(received_packet_code) == 0x04 || + uint8_t(received_packet_code) == 0x0B || + uint8_t(received_packet_code) == 0x0D) { assert_receive_size(3); if (requested_data_record.time_ms != 0) { AP_HAL::panic("Requesting too fast?"); } requested_data_record.code = received_packet_code; requested_data_record.time_ms = AP_HAL::millis(); + } else { + AP_HAL::panic("Invalid packet code"); } } else { AP_HAL::panic("checksum failed"); @@ -90,6 +94,14 @@ void EFI_Hirth::handle_set_values() assert_receive_size(23); static_assert(sizeof(settings) == 20, "correct number of bytes in settings"); memcpy((void*)&settings, &receive_buf[2], sizeof(settings)); + + // send ACK for set-values + constexpr uint8_t set_values_ack[] { + 3, // length + uint8_t(PacketCode::SetValues), // code + 3 + uint8_t(PacketCode::SetValues) + }; + write_to_autopilot((const char*)set_values_ack, sizeof(set_values_ack)); } void EFI_Hirth::update_send() diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.cpp b/libraries/SITL/SIM_EFI_MegaSquirt.cpp index 2935024ce0b0aa..2a5e7152be8a1c 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.cpp +++ b/libraries/SITL/SIM_EFI_MegaSquirt.cpp @@ -107,7 +107,7 @@ void EFI_MegaSquirt::update() if (crc == crc2) { send_table(); } else { - printf("BAD EFI CRC: 0x%08x 0x%08x\n", crc, crc2); + printf("BAD EFI CRC: 0x%08x 0x%08x\n", (unsigned int)crc, (unsigned int)crc2); } ofs = 0; } diff --git a/libraries/SITL/SIM_ELRS.cpp b/libraries/SITL/SIM_ELRS.cpp new file mode 100644 index 00000000000000..687079289bdb78 --- /dev/null +++ b/libraries/SITL/SIM_ELRS.cpp @@ -0,0 +1,165 @@ +#include + +// Only support ELRS simulation in SITL (not Sim on Hardware) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#include "SIM_ELRS.h" +#include + +#include +#include + +#include "include/mavlink/v2.0/all/mavlink.h" + +// Example command: -A --serial2=sim:ELRS +// TCP connection will be started on normal AP port eg 5763 for serial 2 + +// Baud rate must be set correctly +// param set SERIAL2_BAUD 460 + +using namespace SITL; + +ELRS::ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state) : + // Mirror typical ELRS UART buffer sizes + SerialDevice::SerialDevice(64, 128), + // Mirror MAVLink buffer sizes + mavlinkInputBuffer(2048), + mavlinkOutputBuffer(2048), + // 255 is typically used by the GCS, for RC override to work in ArduPilot `SYSID_MYGCS` must be set to this value (255 is the default) + this_system_id(255), + // Strictly this is not a valid source component ID + this_component_id(MAV_COMPONENT::MAV_COMP_ID_ALL), + // Typical setup is about 500 B /s + input_data_rate(500), + output_data_rate(500), + target_address("127.0.0.1"), + target_port(5761 + portNumber) +{ + + // Setup TCP server + listener.reuseaddress(); + listener.bind(target_address, target_port); + listener.listen(1); + listener.set_blocking(false); + +} + +void ELRS::update() +{ + // Connect to incoming TCP + if (sock == nullptr) { + sock = listener.accept(0); + if (sock != nullptr) { + sock->set_blocking(false); + sock->reuseaddress(); + ::printf("ELRS connected to %s:%u\n", target_address, (unsigned)target_port); + } + } + if (sock == nullptr) { + return; + } + + // Read from AP into radio + const uint32_t input_space = mavlinkInputBuffer.space(); + if (input_space > 0) { + uint8_t buf[input_space]; + ssize_t len = read_from_autopilot((char*)buf, input_space); + mavlinkInputBuffer.write(buf, len); + } + + // Send from radio to GCS + const uint32_t send_bytes = input_limit.max_bytes(input_data_rate); + if (send_bytes > 0) { + uint8_t buf[send_bytes]; + const uint32_t len = mavlinkInputBuffer.read(buf, send_bytes); + if (len > 0) { + sock->send(buf, len); + } + } + + // Incoming data from GCS to radio + const uint32_t receive_bytes = output_limit.max_bytes(output_data_rate); + if (receive_bytes > 0) { + uint8_t buf[receive_bytes]; + const ssize_t len = sock->recv(buf, receive_bytes, 1); + if (len > 0) { + mavlinkOutputBuffer.write(buf, len); + } else if (len == 0) { + // EOF, go back to waiting for a new connection + delete sock; + sock = nullptr; + } + } + + // Write from radio to AP + sendQueuedData(); +} + +// Function to behave like MAVLink libs `mavlink_parse_char` but use local buffer +uint8_t ELRS::mavlink_parse_char_helper(uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + uint8_t msg_received = mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status, c, r_message, r_mavlink_status); + if ((msg_received == MAVLINK_FRAMING_BAD_CRC) || (msg_received == MAVLINK_FRAMING_BAD_SIGNATURE)) { + return 0; + } + return msg_received; +} + +// Send incoming data to AP, this is a re-implementation of the ELRS function found here: +// https://github.com/ExpressLRS/ExpressLRS/blob/0d31863f34ca16a036e94a9c2a56038ae56c7f9e/src/src/rx-serial/SerialMavlink.cpp#L78 +void ELRS::sendQueuedData() +{ + + // Send radio messages at 100Hz + const uint32_t now = AP_HAL::millis(); + if ((now - lastSentFlowCtrl) > 10) { + lastSentFlowCtrl = now; + + // Space remaining as a percentage. + const uint8_t percentage_remaining = (mavlinkInputBuffer.space() * 100) / mavlinkInputBuffer.get_size(); + + // Populate radio status packet + const mavlink_radio_status_t radio_status { + rxerrors: 0, + fixed: 0, + rssi: UINT8_MAX, // Unknown + remrssi: UINT8_MAX, // Unknown + txbuf: percentage_remaining, + noise: UINT8_MAX, // Unknown + remnoise: UINT8_MAX, // Unknown + }; + + uint8_t buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES]; + mavlink_message_t msg; + mavlink_msg_radio_status_encode(this_system_id, this_component_id, &msg, &radio_status); + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + write_to_autopilot((char*)buf, len); + } + + // Read one byte at a time until were done + while (true) { + uint8_t c; + if (!mavlinkOutputBuffer.read_byte(&c)) { + break; + } + + mavlink_message_t msg; + mavlink_status_t status; + + // Try parse a mavlink message + if (mavlink_parse_char_helper(c, &msg, &status)) { + // Message decoded successfully + + // Forward message to the UART + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + uint16_t written = write_to_autopilot((char*)buf, len); + if ((written != uint16_t(-1)) && (len != written)) { + ::fprintf(stderr, "Failed to write full msg, wanted %u achieved %u (msg id: %u)\n", len, written, msg.msgid); + } + } + } + +} + +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/SITL/SIM_ELRS.h b/libraries/SITL/SIM_ELRS.h new file mode 100644 index 00000000000000..cd0460a1bae558 --- /dev/null +++ b/libraries/SITL/SIM_ELRS.h @@ -0,0 +1,51 @@ +#pragma once + +#include +#include "SIM_SerialDevice.h" +#include +#include + +namespace SITL { + +class ELRS : public SerialDevice { +public: + ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state); + + uint32_t device_baud() const override { return 460800; } + + void update(); + +private: + void sendQueuedData(); + + struct { + mavlink_message_t rxmsg; + mavlink_status_t status; + } mavlink; + + uint8_t mavlink_parse_char_helper(uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + + ByteBuffer mavlinkInputBuffer; + ByteBuffer mavlinkOutputBuffer; + + DataRateLimit input_limit; + DataRateLimit output_limit; + + uint32_t lastSentFlowCtrl; + + const uint8_t this_system_id; + const uint8_t this_component_id; + + // Air data rate limits in bytes per second + const float input_data_rate; + const float output_data_rate; + + // Sockets for communicating with GCS + SocketAPM_native listener {false}; + SocketAPM_native *sock = nullptr; + const char *target_address; + const uint16_t target_port; + +}; + +} diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index d60793c006dc6a..0e1a947449e6bb 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -18,7 +18,7 @@ #include "SIM_FlightAxis.h" -#if HAL_SIM_FLIGHTAXIS_ENABLED +#if AP_SIM_FLIGHTAXIS_ENABLED #include #include @@ -36,6 +36,19 @@ extern const AP_HAL::HAL& hal; using namespace SITL; +const AP_Param::GroupInfo FlightAxis::var_info[] = { + // @Param: OPTS + // @DisplayName: FlightAxis options + // @Description: Bitmask of FlightAxis options + // @Bitmask: 0: Reset position on startup + // @Bitmask: 1: Swap first 4 and last 4 servos (for quadplane testing) + // @Bitmask: 2: Demix heli servos and send roll/pitch/collective/yaw + // @Bitmask: 3: Don't print frame rate stats + // @User: Advanced + AP_GROUPINFO("OPTS", 1, FlightAxis, _options, uint32_t(Option::ResetPosition)), + AP_GROUPEND +}; + /* we use a thread for socket creation to reduce the impact of socket creation latency. These condition variables are used to synchronise @@ -108,10 +121,18 @@ static double timestamp_sec() FlightAxis::FlightAxis(const char *frame_str) : Aircraft(frame_str) { + AP::sitl()->models.flightaxis_ptr = this; + AP_Param::setup_object_defaults(this, var_info); + use_time_sync = false; rate_hz = 250 / target_speedup; - heli_demix = strstr(frame_str, "helidemix") != nullptr; - rev4_servos = strstr(frame_str, "rev4") != nullptr; + if(strstr(frame_str, "helidemix") != nullptr) { + _options.set(_options | uint32_t(Option::HeliDemix)); + } + if(strstr(frame_str, "rev4") != nullptr) { + _options.set(_options | uint32_t(Option::Rev4Servos)); + } + const char *colon = strchr(frame_str, ':'); if (colon) { controller_ip = colon+1; @@ -284,6 +305,15 @@ void FlightAxis::exchange_data(const struct sitl_input &input) )"); soap_request_end(1000); + if(option_is_set(Option::ResetPosition)) { + soap_request_start("ResetAircraft", R"( + + +12 + +)"); + soap_request_end(1000); + } soap_request_start("InjectUAVControllerInterface", R"( @@ -301,7 +331,7 @@ void FlightAxis::exchange_data(const struct sitl_input &input) scaled_servos[i] = (input.servos[i] - 1000) / 1000.0f; } - if (rev4_servos) { + if (option_is_set(Option::Rev4Servos)) { // swap first 4 and last 4 servos, for quadplane testing float saved[4]; memcpy(saved, &scaled_servos[0], sizeof(saved)); @@ -309,7 +339,7 @@ void FlightAxis::exchange_data(const struct sitl_input &input) memcpy(&scaled_servos[4], saved, sizeof(saved)); } - if (heli_demix) { + if (option_is_set(Option::HeliDemix)) { // FlightAxis expects "roll/pitch/collective/yaw" input float swash1 = scaled_servos[0]; float swash2 = scaled_servos[1]; @@ -574,8 +604,10 @@ void FlightAxis::report_FPS(void) uint64_t frames = socket_frame_counter - last_socket_frame_counter; last_socket_frame_counter = socket_frame_counter; double dt = state.m_currentPhysicsTime_SEC - last_frame_count_s; - printf("%.2f/%.2f FPS avg=%.2f glitches=%u\n", - frames / dt, 1000 / dt, 1.0/average_frame_time_s, unsigned(glitch_count)); + if(!option_is_set(Option::SilenceFPS)) { + printf("%.2f/%.2f FPS avg=%.2f glitches=%u\n", + frames / dt, 1000 / dt, 1.0/average_frame_time_s, unsigned(glitch_count)); + } } else { printf("Initial position %f %f %f\n", position.x, position.y, position.z); } @@ -592,7 +624,7 @@ void FlightAxis::socket_creator(void) pthread_cond_wait(&sockcond2, &sockmtx); } pthread_mutex_unlock(&sockmtx); - auto *sck = new SocketAPM_native(false); + auto *sck = NEW_NOTHROW SocketAPM_native(false); if (sck == nullptr) { usleep(500); continue; @@ -615,4 +647,4 @@ void FlightAxis::socket_creator(void) } } -#endif // HAL_SIM_FLIGHTAXIS_ENABLED +#endif // AP_SIM_FLIGHTAXIS_ENABLED diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index 0567997e1fee5f..276a2aa69c20d3 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -19,12 +19,9 @@ #pragma once #include +#include "SIM_config.h" -#ifndef HAL_SIM_FLIGHTAXIS_ENABLED -#define HAL_SIM_FLIGHTAXIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) -#endif - -#if HAL_SIM_FLIGHTAXIS_ENABLED +#if AP_SIM_FLIGHTAXIS_ENABLED #include @@ -39,12 +36,14 @@ class FlightAxis : public Aircraft { public: FlightAxis(const char *frame_str); + static const struct AP_Param::GroupInfo var_info[]; + /* update model by one time step */ void update(const struct sitl_input &input) override; /* static object creator */ static Aircraft *create(const char *frame_str) { - return new FlightAxis(frame_str); + return NEW_NOTHROW FlightAxis(frame_str); } struct state { @@ -175,12 +174,24 @@ class FlightAxis : public Aircraft { struct sitl_input last_input; + AP_Int32 _options; + + enum class Option : uint32_t{ + ResetPosition = (1U<<0), + Rev4Servos = (1U<<1), + HeliDemix = (1U<<2), + SilenceFPS = (1U<<3), + }; + + // return true if an option is set + bool option_is_set(Option option) const { + return (uint32_t(option) & uint32_t(_options)) != 0; + } + double average_frame_time_s; double extrapolated_s; double initial_time_s; double last_time_s; - bool heli_demix; - bool rev4_servos; bool controller_started; uint32_t glitch_count; uint64_t frame_counter; @@ -204,4 +215,4 @@ class FlightAxis : public Aircraft { } // namespace SITL -#endif // HAL_SIM_FLIGHTAXIS_ENABLED +#endif // AP_SIM_FLIGHTAXIS_ENABLED diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index 0f9bc5fb6260c4..d5435047f95fb9 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -323,12 +323,7 @@ static Frame supported_frames[] = // get air density in kg/m^3 float Frame::get_air_density(float alt_amsl) const { - float sigma, delta, theta; - - AP_Baro::SimpleAtmosphere(alt_amsl * 0.001f, sigma, delta, theta); - - const float air_pressure = SSL_AIR_PRESSURE * delta; - return air_pressure / (ISA_GAS_CONSTANT * (C_TO_KELVIN(model.refTempC))); + return AP_Baro::get_air_density_for_alt_amsl(alt_amsl); } /* diff --git a/libraries/SITL/SIM_GPIO_LED_1.cpp b/libraries/SITL/SIM_GPIO_LED_1.cpp new file mode 100644 index 00000000000000..5ae8a40ef4d3da --- /dev/null +++ b/libraries/SITL/SIM_GPIO_LED_1.cpp @@ -0,0 +1,31 @@ +#include "SIM_config.h" + +#if AP_SIM_GPIO_LED_1_ENABLED + +#include "SIM_GPIO_LED_1.h" + +#include + +using namespace SITL; + +void GPIO_LED_1::init() +{ + leds.init(); +} + +void GPIO_LED_1::update(const class Aircraft &aircraft) +{ + if (!init_done) { + init(); + init_done = true; + } + + const uint16_t pin_mask = AP::sitl()->pin_mask.get(); + const bool new_led_states[1] { + ((pin_mask & uint16_t((1U<::LEDColour colours[1] { + SIM_LED_n<1>::LEDColour::RED, + }; + + SIM_LED_n<1> leds{"GPIO_LED_1", colours}; + + uint8_t LED_A_PIN; +}; + +} // namespace SITL + +#endif // AP_SIM_GPIO_LED_2_ENABLED diff --git a/libraries/SITL/SIM_GPIO_LED_2.cpp b/libraries/SITL/SIM_GPIO_LED_2.cpp new file mode 100644 index 00000000000000..429e3d88753a51 --- /dev/null +++ b/libraries/SITL/SIM_GPIO_LED_2.cpp @@ -0,0 +1,32 @@ +#include "SIM_config.h" + +#if AP_SIM_GPIO_LED_2_ENABLED + +#include "SIM_GPIO_LED_2.h" + +#include + +using namespace SITL; + +void GPIO_LED_2::init() +{ + leds.init(); +} + +void GPIO_LED_2::update(const class Aircraft &aircraft) +{ + if (!init_done) { + init(); + init_done = true; + } + + const uint16_t pin_mask = AP::sitl()->pin_mask.get(); + const bool new_led_states[2] { + ((pin_mask & uint16_t((1U<::LEDColour colours[2] { + SIM_LED_n<2>::LEDColour::RED, + SIM_LED_n<2>::LEDColour::BLUE, + }; + + SIM_LED_n<2> leds{"GPIO_LED_2", colours}; + + uint8_t LED_A_PIN; + uint8_t LED_B_PIN; +}; + +} // namespace SITL + +#endif // AP_SIM_GPIO_LED_2_ENABLED diff --git a/libraries/SITL/SIM_GPIO_LED_3.cpp b/libraries/SITL/SIM_GPIO_LED_3.cpp new file mode 100644 index 00000000000000..d078f30d30bf6a --- /dev/null +++ b/libraries/SITL/SIM_GPIO_LED_3.cpp @@ -0,0 +1,33 @@ +#include "SIM_config.h" + +#if AP_SIM_GPIO_LED_3_ENABLED + +#include "SIM_GPIO_LED_3.h" + +#include + +using namespace SITL; + +void GPIO_LED_3::init() +{ + leds.init(); +} + +void GPIO_LED_3::update(const class Aircraft &aircraft) +{ + if (!init_done) { + init(); + init_done = true; + } + + const uint16_t pin_mask = AP::sitl()->pin_mask.get(); + const bool new_led_states[3] { + ((pin_mask & uint16_t((1U<::LEDColour colours[3] { + SIM_LED_n<3>::LEDColour::RED, + SIM_LED_n<3>::LEDColour::BLUE, + SIM_LED_n<3>::LEDColour::YELLOW, + }; + + SIM_LED_n<3> leds{"GPIO_LED_3", colours}; + + uint8_t LED_A_PIN; + uint8_t LED_B_PIN; + uint8_t LED_C_PIN; +}; + +} // namespace SITL + +#endif // AP_SIM_GPIO_LED_3_ENABLED diff --git a/libraries/SITL/SIM_GPIO_LED_RGB.cpp b/libraries/SITL/SIM_GPIO_LED_RGB.cpp new file mode 100644 index 00000000000000..940240c6c4b67e --- /dev/null +++ b/libraries/SITL/SIM_GPIO_LED_RGB.cpp @@ -0,0 +1,38 @@ +#include "SIM_config.h" + +#if AP_SIM_GPIO_LED_RGB_ENABLED + +#include "SIM_GPIO_LED_RGB.h" + +#include + +using namespace SITL; + +void GPIO_LED_RGB::init() +{ + leds.init(); + rgbled.init(); +} + +void GPIO_LED_RGB::update(const class Aircraft &aircraft) +{ + if (!init_done) { + init(); + init_done = true; + } + + const uint16_t pin_mask = AP::sitl()->pin_mask.get(); + + const bool red = ((pin_mask & uint16_t((1U<::LEDColour colours[3] { + SIM_LED_n<3>::LEDColour::RED, + SIM_LED_n<3>::LEDColour::GREEN, + SIM_LED_n<3>::LEDColour::BLUE, + }; + + SIM_LED_n<3> leds{"GPIO_LED_RGB", colours}; + SIM_RGBLED rgbled{"GPIO_LED_RGB Mixed"}; + + uint8_t LED_RED_PIN; + uint8_t LED_GREEN_PIN; + uint8_t LED_BLUE_PIN; +}; + +} // namespace SITL + +#endif // AP_SIM_GPIO_LED_RGB_ENABLED diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 38735248d97e2d..6ca425a5ea6966 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -11,6 +11,7 @@ #if HAL_SIM_GPS_ENABLED #include +#include #include #include @@ -25,9 +26,125 @@ #include "SIM_GPS_SBP2.h" #include "SIM_GPS_SBP.h" #include "SIM_GPS_UBLOX.h" +#include "SIM_GPS_SBF.h" #include +namespace SITL { +// user settable parameters for GNSS sensors +const AP_Param::GroupInfo SIM::GPSParms::var_info[] = { + + // @Param: ENABLE + // @DisplayName: GPS enable + // @Description: Enable simulated GPS + // @Values: 0:Disable, 1:Enable + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLE", 1, GPSParms, enabled, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: LAG_MS + // @DisplayName: GPS Lag + // @Description: GPS lag + // @Units: ms + // @User: Advanced + AP_GROUPINFO("LAG_MS", 2, GPSParms, delay_ms, 100), + + // @Param: TYPE + // @DisplayName: GPS type + // @Description: Sets the type of simulation used for GPS + // @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP2, 11:Trimble, 19:MSP + // @User: Advanced + AP_GROUPINFO("TYPE", 3, GPSParms, type, GPS::Type::UBLOX), + + // @Param: BYTELOS + // @DisplayName: GPS Byteloss + // @Description: Percent of bytes lost from GPS + // @Units: % + // @User: Advanced + AP_GROUPINFO("BYTELOS", 4, GPSParms, byteloss, 0), + + // @Param: NUMSATS + // @DisplayName: GPS Num Satellites + // @Description: Number of satellites GPS has in view + AP_GROUPINFO("NUMSATS", 5, GPSParms, numsats, 10), + + // @Param: GLTCH + // @DisplayName: GPS Glitch + // @Description: Glitch offsets of simulated GPS sensor + // @Vector3Parameter: 1 + // @User: Advanced + AP_GROUPINFO("GLTCH", 6, GPSParms, glitch, 0), + + // @Param: HZ + // @DisplayName: GPS Hz + // @Description: GPS Update rate + // @Units: Hz + AP_GROUPINFO("HZ", 7, GPSParms, hertz, 5), + + // @Param: DRFTALT + // @DisplayName: GPS Altitude Drift + // @Description: GPS altitude drift error + // @Units: m + // @User: Advanced + AP_GROUPINFO("DRFTALT", 8, GPSParms, drift_alt, 0), + + // @Param: POS + // @DisplayName: GPS Position + // @Description: GPS antenna phase center position relative to the body frame origin + // @Units: m + // @Vector3Parameter: 1 + AP_GROUPINFO("POS", 9, GPSParms, pos_offset, 0), + + // @Param: NOISE + // @DisplayName: GPS Noise + // @Description: Amplitude of the GPS altitude error + // @Units: m + // @User: Advanced + AP_GROUPINFO("NOISE", 10, GPSParms, noise, 0), + + // @Param: LCKTIME + // @DisplayName: GPS Lock Time + // @Description: Delay in seconds before GPS acquires lock + // @Units: s + // @User: Advanced + AP_GROUPINFO("LCKTIME", 11, GPSParms, lock_time, 0), + + // @Param: ALT_OFS + // @DisplayName: GPS Altitude Offset + // @Description: GPS Altitude Error + // @Units: m + AP_GROUPINFO("ALT_OFS", 12, GPSParms, alt_offset, 0), + + // @Param: HDG + // @DisplayName: GPS Heading + // @Description: Enable GPS output of NMEA heading HDT sentence or UBLOX_RELPOSNED + // @Values: 0:Disabled, 1:Emit HDT, 2:Emit THS, 3:KSXT, 4:Be Moving Baseline Base + // @User: Advanced + AP_GROUPINFO("HDG", 13, GPSParms, hdg_enabled, SIM::GPS_HEADING_NONE), + + // @Param: ACC + // @DisplayName: GPS Accuracy + // @Description: GPS Accuracy + // @User: Advanced + AP_GROUPINFO("ACC", 14, GPSParms, accuracy, 0.3), + + // @Param: VERR + // @DisplayName: GPS Velocity Error + // @Description: GPS Velocity Error Offsets in NED + // @Vector3Parameter: 1 + // @User: Advanced + AP_GROUPINFO("VERR", 15, GPSParms, vel_err, 0), + + // @Param: JAM + // @DisplayName: GPS jamming enable + // @Description: Enable simulated GPS jamming + // @User: Advanced + // @Values: 0:Disabled, 1:Enabled + AP_GROUPINFO("JAM", 16, GPSParms, jam, 0), + + AP_GROUPEND +}; +} + // the number of GPS leap seconds - copied from AP_GPS.h #define GPS_LEAPSECONDS_MILLIS 18000ULL @@ -36,11 +153,18 @@ extern const AP_HAL::HAL& hal; using namespace SITL; // ensure the backend we have allocated matches the one that's configured: -GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) - : front{_front}, - instance{_instance} +GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) : + instance{_instance}, + front{_front} { _sitl = AP::sitl(); + +#if HAL_SIM_GPS_ENABLED && AP_SIM_MAX_GPS_SENSORS > 0 + // default the first backend to enabled: + if (_instance == 0 && !_sitl->gps[0].enabled.configured()) { + _sitl->gps[0].enabled.set(1); + } +#endif } ssize_t GPS_Backend::write_to_autopilot(const char *p, size_t size) const @@ -76,11 +200,11 @@ ssize_t GPS::write_to_autopilot(const char *p, size_t size) const // the first will start sending back 3 satellites, the second just // stops responding when disabled. This is not necessarily a good // thing. - if (instance == 1 && _sitl->gps_disable[instance]) { + if (instance == 1 && !_sitl->gps[instance].enabled) { return -1; } - const float byteloss = _sitl->gps_byteloss[instance]; + const float byteloss = _sitl->gps[instance].byteloss; // shortcut if we're not doing byteloss: if (!is_positive(byteloss)) { @@ -215,7 +339,7 @@ GPS_Backend::GPS_TOW GPS_Backend::gps_time() void GPS::check_backend_allocation() { - const Type configured_type = Type(_sitl->gps_type[instance].get()); + const Type configured_type = Type(_sitl->gps[instance].type.get()); if (allocated_type == configured_type) { return; } @@ -234,49 +358,55 @@ void GPS::check_backend_allocation() #if AP_SIM_GPS_UBLOX_ENABLED case Type::UBLOX: - backend = new GPS_UBlox(*this, instance); + backend = NEW_NOTHROW GPS_UBlox(*this, instance); break; #endif #if AP_SIM_GPS_NMEA_ENABLED case Type::NMEA: - backend = new GPS_NMEA(*this, instance); + backend = NEW_NOTHROW GPS_NMEA(*this, instance); break; #endif #if AP_SIM_GPS_SBP_ENABLED case Type::SBP: - backend = new GPS_SBP(*this, instance); + backend = NEW_NOTHROW GPS_SBP(*this, instance); break; #endif #if AP_SIM_GPS_SBP2_ENABLED case Type::SBP2: - backend = new GPS_SBP2(*this, instance); + backend = NEW_NOTHROW GPS_SBP2(*this, instance); break; #endif #if AP_SIM_GPS_NOVA_ENABLED case Type::NOVA: - backend = new GPS_NOVA(*this, instance); + backend = NEW_NOTHROW GPS_NOVA(*this, instance); break; #endif #if AP_SIM_GPS_MSP_ENABLED case Type::MSP: - backend = new GPS_MSP(*this, instance); + backend = NEW_NOTHROW GPS_MSP(*this, instance); + break; +#endif + +#if AP_SIM_GPS_SBF_ENABLED + case Type::SBF: + backend = NEW_NOTHROW GPS_SBF(*this, instance); break; #endif #if AP_SIM_GPS_TRIMBLE_ENABLED case Type::TRIMBLE: - backend = new GPS_Trimble(*this, instance); + backend = NEW_NOTHROW GPS_Trimble(*this, instance); break; #endif #if AP_SIM_GPS_FILE_ENABLED case Type::FILE: - backend = new GPS_FILE(*this, instance); + backend = NEW_NOTHROW GPS_FILE(*this, instance); break; #endif }; @@ -320,7 +450,7 @@ void GPS::update() //Capture current position as basestation location for if (!_gps_has_basestation_position && - now_ms >= _sitl->gps_lock_time[0]*1000UL) { + now_ms >= _sitl->gps[0].lock_time*1000UL) { _gps_basestation_data.latitude = latitude; _gps_basestation_data.longitude = longitude; _gps_basestation_data.altitude = altitude; @@ -330,15 +460,15 @@ void GPS::update() _gps_has_basestation_position = true; } - const uint8_t idx = instance; // alias to avoid code churn + const auto ¶ms = _sitl->gps[instance]; struct GPS_Data d {}; // simulate delayed lock times - bool have_lock = (!_sitl->gps_disable[idx] && now_ms >= _sitl->gps_lock_time[idx]*1000UL); + bool have_lock = (params.enabled && now_ms >= params.lock_time*1000UL); // Only let physics run and GPS write at configured GPS rate (default 5Hz). - if ((now_ms - last_write_update_ms) < (uint32_t)(1000/_sitl->gps_hertz[instance])) { + if ((now_ms - last_write_update_ms) < (uint32_t)(1000/params.hertz)) { // Reading runs every iteration. // Beware- physics don't update every iteration with this approach. // Currently, none of the drivers rely on quickly updated physics. @@ -348,6 +478,7 @@ void GPS::update() last_write_update_ms = now_ms; + d.num_sats = params.numsats; d.latitude = latitude; d.longitude = longitude; d.yaw_deg = _sitl->state.yawDeg; @@ -355,23 +486,29 @@ void GPS::update() d.pitch_deg = _sitl->state.pitchDeg; // add an altitude error controlled by a slow sine wave - d.altitude = altitude + _sitl->gps_noise[idx] * sinf(now_ms * 0.0005f) + _sitl->gps_alt_offset[idx]; + d.altitude = altitude + params.noise * sinf(now_ms * 0.0005f) + params.alt_offset; // Add offset to c.g. velocity to get velocity at antenna and add simulated error - Vector3f velErrorNED = _sitl->gps_vel_err[idx]; + Vector3f velErrorNED = params.vel_err; d.speedN = speedN + (velErrorNED.x * rand_float()); d.speedE = speedE + (velErrorNED.y * rand_float()); d.speedD = speedD + (velErrorNED.z * rand_float()); + d.have_lock = have_lock; - if (_sitl->gps_drift_alt[idx] > 0) { + // fill in accuracies + d.horizontal_acc = params.accuracy; + d.vertical_acc = params.accuracy; + d.speed_acc = params.vel_err.get().xy().length(); + + if (params.drift_alt > 0) { // add slow altitude drift controlled by a slow sine wave - d.altitude += _sitl->gps_drift_alt[idx]*sinf(now_ms*0.001f*0.02f); + d.altitude += params.drift_alt*sinf(now_ms*0.001f*0.02f); } // correct the latitude, longitude, height and NED velocity for the offset between // the vehicle c.g. and GPS antenna - Vector3f posRelOffsetBF = _sitl->gps_pos_offset[idx]; + Vector3f posRelOffsetBF = params.pos_offset; if (!posRelOffsetBF.is_zero()) { // get a rotation matrix following DCM conventions (body to earth) Matrix3f rotmat; @@ -403,18 +540,18 @@ void GPS::update() // get delayed data d.timestamp_ms = now_ms; - d = interpolate_data(d, _sitl->gps_delay_ms[instance]); + d = interpolate_data(d, params.delay_ms); // Applying GPS glitch // Using first gps glitch - Vector3f glitch_offsets = _sitl->gps_glitch[idx]; + Vector3f glitch_offsets = params.glitch; d.latitude += glitch_offsets.x; d.longitude += glitch_offsets.y; d.altitude += glitch_offsets.z; - if (_sitl->gps_jam[idx] == 1) { - simulate_jamming(d); - } + if (params.jam == 1) { + simulate_jamming(d); + } backend->publish(&d); } @@ -462,10 +599,9 @@ GPS_Data GPS::interpolate_data(const GPS_Data &d, uint32_t delay_ms) return _gps_history[N-1]; } -float GPS_Data::heading() const +float GPS_Data::ground_track_rad() const { - const auto velocity = Vector2d{speedE, speedN}; - return velocity.angle(); + return atan2f(speedE, speedN); } float GPS_Data::speed_2d() const diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index f92375f55844a4..1bdb583d0e59d5 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -27,6 +27,7 @@ param set SERIAL5_PROTOCOL 5 #if HAL_SIM_GPS_ENABLED +#include #include "SIM_SerialDevice.h" namespace SITL { @@ -49,8 +50,9 @@ struct GPS_Data { float speed_acc; uint8_t num_sats; - // Get heading [rad], where 0 = North in WGS-84 coordinate system - float heading() const WARN_IF_UNUSED; + // Get course over ground [rad], where 0 = North in WGS-84 coordinate system. + // Calculated from 2D velocity. + float ground_track_rad() const WARN_IF_UNUSED; // Get 2D speed [m/s] in WGS-84 coordinate system float speed_2d() const WARN_IF_UNUSED; @@ -119,6 +121,9 @@ class GPS : public SerialDevice { #if AP_SIM_GPS_SBP2_ENABLED SBP2 = 9, #endif +#if AP_SIM_GPS_SBF_ENABLED + SBF = 10, //matches GPS_TYPE +#endif #if AP_SIM_GPS_TRIMBLE_ENABLED TRIMBLE = 11, // matches GPS1_TYPE #endif diff --git a/libraries/SITL/SIM_GPS_FILE.cpp b/libraries/SITL/SIM_GPS_FILE.cpp index 60868d4355cb6a..94a970960bcc81 100644 --- a/libraries/SITL/SIM_GPS_FILE.cpp +++ b/libraries/SITL/SIM_GPS_FILE.cpp @@ -50,7 +50,7 @@ void GPS_FILE::publish(const GPS_Data *d) ::lseek(fd[instance], -sizeof(header), SEEK_CUR); return; } - buf = new uint8_t[header.n]; + buf = NEW_NOTHROW 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; diff --git a/libraries/SITL/SIM_GPS_MSP.cpp b/libraries/SITL/SIM_GPS_MSP.cpp index 2bf9db476f0bc0..66bde9c22ce6ef 100644 --- a/libraries/SITL/SIM_GPS_MSP.cpp +++ b/libraries/SITL/SIM_GPS_MSP.cpp @@ -7,6 +7,7 @@ #include #include +#include using namespace SITL; @@ -62,9 +63,9 @@ void GPS_MSP::publish(const GPS_Data *d) msp_gps.gps_week = t.week; msp_gps.ms_tow = t.ms; msp_gps.fix_type = d->have_lock?3:0; - msp_gps.satellites_in_view = d->have_lock ? _sitl->gps_numsats[instance] : 3; - msp_gps.horizontal_pos_accuracy = _sitl->gps_accuracy[instance]*100; - msp_gps.vertical_pos_accuracy = _sitl->gps_accuracy[instance]*100; + msp_gps.satellites_in_view = d->have_lock ? d->num_sats : 3; + msp_gps.horizontal_pos_accuracy = d->horizontal_acc*100; + msp_gps.vertical_pos_accuracy = d->vertical_acc*100; msp_gps.horizontal_vel_accuracy = 30; msp_gps.hdop = 100; msp_gps.longitude = d->longitude * 1.0e7; diff --git a/libraries/SITL/SIM_GPS_NMEA.cpp b/libraries/SITL/SIM_GPS_NMEA.cpp index c4b16b89da44fd..a4e19fb40b4688 100644 --- a/libraries/SITL/SIM_GPS_NMEA.cpp +++ b/libraries/SITL/SIM_GPS_NMEA.cpp @@ -9,6 +9,7 @@ #include #include +#include extern const AP_HAL::HAL& hal; @@ -73,19 +74,19 @@ void GPS_NMEA::publish(const GPS_Data *d) lat_string, lng_string, d->have_lock?1:0, - d->have_lock?_sitl->gps_numsats[instance]:3, + d->have_lock?d->num_sats:3, 1.2, d->altitude); const float speed_mps = d->speed_2d(); const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; - const auto heading_rad = d->heading(); + const auto ground_track_deg = degrees(d->ground_track_rad()); //$GPVTG,133.18,T,120.79,M,0.11,N,0.20,K,A*24 nmea_printf("$GPVTG,%.2f,T,%.2f,M,%.2f,N,%.2f,K,A", tstring, - heading_rad, - heading_rad, + ground_track_deg, + ground_track_deg, speed_knots, speed_knots * KNOTS_TO_METERS_PER_SECOND * 3.6); @@ -95,15 +96,15 @@ void GPS_NMEA::publish(const GPS_Data *d) lat_string, lng_string, speed_knots, - heading_rad, + ground_track_deg, dstring); - if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) { + if (_sitl->gps[instance].hdg_enabled == SITL::SIM::GPS_HEADING_HDT) { nmea_printf("$GPHDT,%.2f,T", d->yaw_deg); } - else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_THS) { + else if (_sitl->gps[instance].hdg_enabled == SITL::SIM::GPS_HEADING_THS) { nmea_printf("$GPTHS,%.2f,%c,T", d->yaw_deg, d->have_lock ? 'A' : 'V'); - } else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_KSXT) { + } else if (_sitl->gps[instance].hdg_enabled == SITL::SIM::GPS_HEADING_KSXT) { // Unicore support // $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 nmea_printf("$KSXT,%04u%02u%02u%02u%02u%02u.%02u,%.8f,%.8f,%.4f,%.2f,%.2f,%.2f,%.2f,%.3f,%u,%u,%u,%u,,,,%.3f,%.3f,%.3f,,", @@ -112,13 +113,13 @@ void GPS_NMEA::publish(const GPS_Data *d) d->altitude, wrap_360(d->yaw_deg), d->pitch_deg, - heading_rad, + ground_track_deg, speed_mps, d->roll_deg, d->have_lock?1:0, // 2=rtkfloat 3=rtkfixed, 3, // fixed rtk yaw solution, - d->have_lock?_sitl->gps_numsats[instance]:3, - d->have_lock?_sitl->gps_numsats[instance]:3, + d->have_lock?d->num_sats:3, + d->have_lock?d->num_sats:3, d->speedE * 3.6, d->speedN * 3.6, -d->speedD * 3.6); diff --git a/libraries/SITL/SIM_GPS_NOVA.cpp b/libraries/SITL/SIM_GPS_NOVA.cpp index cd4608b7f0b91d..808d6b19cc3caa 100644 --- a/libraries/SITL/SIM_GPS_NOVA.cpp +++ b/libraries/SITL/SIM_GPS_NOVA.cpp @@ -129,7 +129,7 @@ void GPS_NOVA::publish(const GPS_Data *d) bestpos.lat = d->latitude; bestpos.lng = d->longitude; bestpos.hgt = d->altitude; - bestpos.svsused = d->have_lock ? _sitl->gps_numsats[instance] : 3; + bestpos.svsused = d->have_lock ? d->num_sats : 3; bestpos.latsdev=0.2; bestpos.lngsdev=0.2; bestpos.hgtsdev=0.2; @@ -142,36 +142,12 @@ void GPS_NOVA::publish(const GPS_Data *d) void GPS_NOVA::nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen) { write_to_autopilot((char*)header, headerlength); -write_to_autopilot((char*)payload, payloadlen); + write_to_autopilot((char*)payload, payloadlen); - uint32_t crc = CalculateBlockCRC32(headerlength, header, (uint32_t)0); - crc = CalculateBlockCRC32(payloadlen, payload, crc); + uint32_t crc = crc_crc32((uint32_t)0, header, headerlength); + crc = crc_crc32(crc, payload, payloadlen); write_to_autopilot((char*)&crc, 4); } -#define CRC32_POLYNOMIAL 0xEDB88320L -uint32_t GPS_NOVA::CRC32Value(uint32_t icrc) -{ - int i; - uint32_t crc = icrc; - for ( i = 8 ; i > 0; i-- ) - { - if ( crc & 1 ) - crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL; - else - crc >>= 1; - } - return crc; -} - -uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) -{ - while ( length-- != 0 ) - { - crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff)); - } - return( crc ); -} - #endif // AP_SIM_GPS_NOVA_ENABLED diff --git a/libraries/SITL/SIM_GPS_NOVA.h b/libraries/SITL/SIM_GPS_NOVA.h index 4df22b32d8dc9a..0801dd9533adbb 100644 --- a/libraries/SITL/SIM_GPS_NOVA.h +++ b/libraries/SITL/SIM_GPS_NOVA.h @@ -21,8 +21,6 @@ class GPS_NOVA : public GPS_Backend { private: void nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen); - uint32_t CRC32Value(uint32_t icrc); - uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc); }; }; diff --git a/libraries/SITL/SIM_GPS_SBF.cpp b/libraries/SITL/SIM_GPS_SBF.cpp new file mode 100644 index 00000000000000..5df55017560dbe --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBF.cpp @@ -0,0 +1,184 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_SBF_ENABLED + +#include "SIM_GPS_SBF.h" + +#include +#include + +using namespace SITL; + +static const uint16_t CRC16_LOOK_UP[256] = { + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, 0x8108, 0x9129, + 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, 0x1231, 0x0210, 0x3273, 0x2252, + 0x52b5, 0x4294, 0x72f7, 0x62d6, 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, + 0xf3ff, 0xe3de, 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, + 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, 0x3653, 0x2672, + 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, 0xb75b, 0xa77a, 0x9719, 0x8738, + 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, + 0x2802, 0x3823, 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, + 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, 0xdbfd, 0xcbdc, + 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, + 0x2c22, 0x3c03, 0x0c60, 0x1c41, 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, + 0x8d68, 0x9d49, 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, + 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, 0x9188, 0x81a9, + 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, 0x1080, 0x00a1, 0x30c2, 0x20e3, + 0x5004, 0x4025, 0x7046, 0x6067, 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, + 0xe37f, 0xf35e, 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, 0x34e2, 0x24c3, + 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 0xa7db, 0xb7fa, 0x8799, 0x97b8, + 0xe75f, 0xf77e, 0xc71d, 0xd73c, 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, + 0x4615, 0x5634, 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, 0xcb7d, 0xdb5c, + 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, 0x4a75, 0x5a54, 0x6a37, 0x7a16, + 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, + 0x9de8, 0x8dc9, 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, + 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, 0x6e17, 0x7e36, + 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 +}; + +void GPS_SBF::send_sbf(uint16_t msgid, uint8_t *buf, uint16_t size) +{ + if ((size % 4) != 0) { + AP_HAL::panic("Invalid SBF packet length"); + } + + //HEADER + const uint8_t PREAMBLE1 = 0x24; + const uint8_t PREAMBLE2 = 0x40; + uint8_t hdr[8]; + uint16_t crc = 0; + hdr[0] = PREAMBLE1; + hdr[1] = PREAMBLE2; + hdr[4] = msgid & 0xFF; + hdr[5] = (msgid >> 8) & 0xFF; + hdr[6] = (size+8) & 0xFF; + hdr[7] = ((size+8) >> 8) & 0xFF; + for (uint8_t i = 4; i<8; i++) { + crc = (crc << 8) ^ CRC16_LOOK_UP[uint8_t((crc >> 8) ^ hdr[i])]; //include id and length + } + for (uint16_t i = 0; i> 8) ^ buf[i])]; + } + hdr[2] = crc & 0xFF; + hdr[3] = (crc >> 8) & 0xFF; + + write_to_autopilot((char*)hdr, sizeof(hdr)); + write_to_autopilot((char*)buf, size); +} + +void GPS_SBF::publish(const GPS_Data *d) { + publish_PVTGeodetic(d); + publish_DOP(d); +} + +// public PVTGeodetic message, ID 4007 +void GPS_SBF::publish_PVTGeodetic(const GPS_Data *d) +{ + const double DNU_DOUBLE = -2e10; + const float DNU_FLOAT = -2e10; + const uint8_t DNU_UINT8 = 255; + const uint16_t DNU_UINT16 = 65535; + + struct PACKED timestamp_t { + uint32_t tow; + uint16_t wnc; + }; + + struct PACKED sbf_pvtGeod_t + { + timestamp_t time_stamp; + uint8_t mode; + uint8_t error; + double latitude; + double longitude; + double height; + float undulation; + float vn; + float ve; + float vu; + float cog; + double rxclkbias; + float rxclkdrift; + uint8_t timesystem; + uint8_t datum; + uint8_t nrsv; + uint8_t wacorrinfo; + uint16_t referenceid; + uint16_t meancorrage; + uint64_t signalinfo; + uint8_t alertflag; + uint8_t __PADDING__[3]; // packets must be zero-mod-4 + } pvtGeod_buf {} ; + assert_storage_size assert_storage_size_pvt_Geod_buf; + (void)assert_storage_size_pvt_Geod_buf; + + const uint16_t PVTGEO_0_MSG_ID = 0x0FA7; + + const auto gps_tow = gps_time(); + pvtGeod_buf.time_stamp.tow = gps_tow.ms; + pvtGeod_buf.time_stamp.wnc = gps_tow.week; + + pvtGeod_buf.mode = 4; //Mode: default to rtk fixed + pvtGeod_buf.error= 0; //Error: no error + pvtGeod_buf.latitude = radians(_sitl->state.latitude); + pvtGeod_buf.longitude = radians(_sitl->state.longitude); + pvtGeod_buf.height = d->altitude; + pvtGeod_buf.undulation = DNU_DOUBLE; + pvtGeod_buf.vn = d->speedN; + pvtGeod_buf.ve = d->speedE; + pvtGeod_buf.vu = -d->speedD; + pvtGeod_buf.cog = degrees(d->ground_track_rad()); + pvtGeod_buf.rxclkbias = DNU_DOUBLE; + pvtGeod_buf.rxclkdrift = DNU_FLOAT; + pvtGeod_buf.timesystem = DNU_UINT8; + pvtGeod_buf.datum = DNU_UINT8; + pvtGeod_buf.nrsv = d->num_sats; + pvtGeod_buf.wacorrinfo = 0; //default value + pvtGeod_buf.referenceid = DNU_UINT16; + pvtGeod_buf.meancorrage = DNU_UINT16; + pvtGeod_buf.signalinfo = 0; + pvtGeod_buf.alertflag = 0; + + send_sbf(PVTGEO_0_MSG_ID, (uint8_t*)&pvtGeod_buf, sizeof(pvtGeod_buf)); +} + +// public DOP message, ID 4001 +void GPS_SBF::publish_DOP(const GPS_Data *d) +{ + struct PACKED timestamp_t { + uint32_t tow; + uint16_t wnc; + }; + + const auto gps_tow = gps_time(); + + // swiped from the driver: + const struct PACKED { + timestamp_t time_stamp; + uint8_t NrSV; + uint8_t Reserved; + uint16_t PDOP; + uint16_t TDOP; + uint16_t HDOP; + uint16_t VDOP; + float HPL; + float VPL; + // uint8_t __PADDING__[2]; + } packet { + { gps_tow.ms, gps_tow.week }, // timestamp + 17, // NrSV + 0, // reserved + 1, // PDOP + 1, // TDOP + 1, // HDOP + 1, // VDOP + 1.0, // HPL + 1.0 // VPL + }; + + send_sbf(4001, (uint8_t*)&packet, sizeof(packet)); +} + +#endif //AP_SIM_GPS_SBF_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBF.h b/libraries/SITL/SIM_GPS_SBF.h new file mode 100644 index 00000000000000..9985213f385001 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBF.h @@ -0,0 +1,29 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_SBF_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_SBF : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_SBF); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; + +private: + + void send_sbf(uint16_t msgid, uint8_t *buf, uint16_t buf_size); + void publish_PVTGeodetic(const GPS_Data *d); + void publish_DOP(const GPS_Data *d); + +}; + +}; + +#endif // AP_SIM_GPS_SBF_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP.cpp b/libraries/SITL/SIM_GPS_SBP.cpp index b3b8e77d890711..a3b11f2e873f95 100644 --- a/libraries/SITL/SIM_GPS_SBP.cpp +++ b/libraries/SITL/SIM_GPS_SBP.cpp @@ -77,9 +77,9 @@ void GPS_SBP::publish(const GPS_Data *d) pos.lon = d->longitude; pos.lat= d->latitude; pos.height = d->altitude; - pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + pos.h_accuracy = d->horizontal_acc*1000; + pos.v_accuracy = d->vertical_acc*1000; + pos.n_sats = d->have_lock ? d->num_sats : 3; // Send single point position solution pos.flags = 0; @@ -94,7 +94,7 @@ void GPS_SBP::publish(const GPS_Data *d) velned.d = 1e3 * d->speedD; velned.h_accuracy = 5e3; velned.v_accuracy = 5e3; - velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + velned.n_sats = d->have_lock ? d->num_sats : 3; velned.flags = 0; sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); @@ -111,6 +111,7 @@ void GPS_SBP::publish(const GPS_Data *d) sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), (uint8_t*)&dops); + hb = {}; hb.protocol_major = 0; //Sends protocol version 0 sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), (uint8_t*)&hb); diff --git a/libraries/SITL/SIM_GPS_SBP2.cpp b/libraries/SITL/SIM_GPS_SBP2.cpp index 1596d330af6fae..f7b33361f36598 100644 --- a/libraries/SITL/SIM_GPS_SBP2.cpp +++ b/libraries/SITL/SIM_GPS_SBP2.cpp @@ -77,9 +77,9 @@ void GPS_SBP2::publish(const GPS_Data *d) pos.lon = d->longitude; pos.lat= d->latitude; pos.height = d->altitude; - pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + pos.h_accuracy = d->horizontal_acc*1000; + pos.v_accuracy = d->vertical_acc*1000; + pos.n_sats = d->have_lock ? d->num_sats : 3; // Send single point position solution pos.flags = 1; @@ -92,9 +92,9 @@ void GPS_SBP2::publish(const GPS_Data *d) velned.n = 1e3 * d->speedN; velned.e = 1e3 * d->speedE; velned.d = 1e3 * d->speedD; - velned.h_accuracy = 5e3; - velned.v_accuracy = 5e3; - velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + velned.h_accuracy = 1e3 * 0.5; + velned.v_accuracy = 1e3 * 0.5; + velned.n_sats = d->have_lock ? d->num_sats : 3; velned.flags = 1; sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); @@ -111,6 +111,7 @@ void GPS_SBP2::publish(const GPS_Data *d) sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), (uint8_t*)&dops); + hb = {}; hb.protocol_major = 2; //Sends protocol version 2.0 sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), (uint8_t*)&hb); diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index 1e1726b33376ba..4e5883ef45d8e7 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -93,7 +93,7 @@ void GPS_Trimble::publish(const GPS_Data *d) GSOF_POS_TIME_LEN, htobe32(gps_tow.ms), htobe16(gps_tow.week), - d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), + d->have_lock ? d->num_sats : uint8_t(3), pos_flags_1, pos_flags_2, bootcount @@ -175,7 +175,7 @@ void GPS_Trimble::publish(const GPS_Data *d) GSOF_VEL_LEN, vel_flags, gsof_pack_float(d->speed_2d()), - gsof_pack_float(d->heading()), + gsof_pack_float(d->ground_track_rad()), // Trimble API has ambiguous direction here. // Intentionally narrow from double. gsof_pack_float(static_cast(d->speedD)) diff --git a/libraries/SITL/SIM_GPS_UBLOX.cpp b/libraries/SITL/SIM_GPS_UBLOX.cpp index 5d743cbfe9b3a3..3f3ef5da683b80 100644 --- a/libraries/SITL/SIM_GPS_UBLOX.cpp +++ b/libraries/SITL/SIM_GPS_UBLOX.cpp @@ -35,6 +35,47 @@ void GPS_UBlox::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) write_to_autopilot((char*)chk, sizeof(chk)); } +void GPS_UBlox::update_relposned(ubx_nav_relposned &relposned, uint32_t tow_ms, float yaw_deg) +{ + Vector3f ant1_pos { NaNf, NaNf, NaNf }; + + // find our partner: + for (uint8_t i=0; igps); i++) { + if (i == instance) { + // this shouldn't matter as our heading type should never be base + continue; + } + if (_sitl->gps[i].hdg_enabled != SITL::SIM::GPS_HEADING_BASE) { + continue; + } + ant1_pos = _sitl->gps[i].pos_offset.get(); + break; + } + if (ant1_pos.is_nan()) { + return; + } + + const Vector3f ant2_pos = _sitl->gps[instance].pos_offset.get(); + Vector3f rel_antenna_pos = ant2_pos - ant1_pos; + Matrix3f rot; + // project attitude back using gyros to get antenna orientation at time of GPS sample + Vector3f gyro(radians(_sitl->state.rollRate), + radians(_sitl->state.pitchRate), + radians(_sitl->state.yawRate)); + rot.from_euler(radians(_sitl->state.rollDeg), radians(_sitl->state.pitchDeg), radians(yaw_deg)); + const float lag = _sitl->gps[instance].delay_ms * 0.001; + rot.rotate(gyro * (-lag)); + rel_antenna_pos = rot * rel_antenna_pos; + relposned.version = 1; + relposned.iTOW = tow_ms; + relposned.relPosN = rel_antenna_pos.x * 100; + relposned.relPosE = rel_antenna_pos.y * 100; + relposned.relPosD = rel_antenna_pos.z * 100; + relposned.relPosLength = rel_antenna_pos.length() * 100; + relposned.relPosHeading = degrees(Vector2f(rel_antenna_pos.x, rel_antenna_pos.y).angle()) * 1.0e5; + relposned.flags = gnssFixOK | diffSoln | carrSolnFixed | isMoving | relPosValid | relPosHeadingValid; +} + /* send a new set of GPS UBLOX packets */ @@ -139,44 +180,7 @@ void GPS_UBlox::publish(const GPS_Data *d) int32_t prRes; } sv[SV_COUNT]; } svinfo {}; - enum RELPOSNED { - gnssFixOK = 1U << 0, - diffSoln = 1U << 1, - relPosValid = 1U << 2, - carrSolnFloat = 1U << 3, - - carrSolnFixed = 1U << 4, - isMoving = 1U << 5, - refPosMiss = 1U << 6, - refObsMiss = 1U << 7, - - relPosHeadingValid = 1U << 8, - relPosNormalized = 1U << 9 - }; - struct PACKED ubx_nav_relposned { - uint8_t version; - uint8_t reserved1; - uint16_t refStationId; - uint32_t iTOW; - int32_t relPosN; - int32_t relPosE; - int32_t relPosD; - int32_t relPosLength; - int32_t relPosHeading; - uint8_t reserved2[4]; - int8_t relPosHPN; - int8_t relPosHPE; - int8_t relPosHPD; - int8_t relPosHPLength; - uint32_t accN; - uint32_t accE; - uint32_t accD; - uint32_t accLength; - uint32_t accHeading; - uint8_t reserved3[4]; - uint32_t flags; - } relposned {}; - + ubx_nav_relposned relposned {}; const uint8_t MSG_POSLLH = 0x2; const uint8_t MSG_STATUS = 0x3; const uint8_t MSG_DOP = 0x4; @@ -195,8 +199,8 @@ void GPS_UBlox::publish(const GPS_Data *d) pos.latitude = d->latitude * 1.0e7; pos.altitude_ellipsoid = d->altitude * 1000.0f; pos.altitude_msl = d->altitude * 1000.0f; - pos.horizontal_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.vertical_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.horizontal_accuracy = d->horizontal_acc*1000; + pos.vertical_accuracy = d->vertical_acc*1000; status.time = gps_tow.ms; status.fix_type = d->have_lock?3:0; @@ -216,13 +220,13 @@ void GPS_UBlox::publish(const GPS_Data *d) if (velned.heading_2d < 0.0f) { velned.heading_2d += 360.0f * 100000.0f; } - velned.speed_accuracy = 40; + velned.speed_accuracy = d->speed_acc * 100; // m/s -> cm/s velned.heading_accuracy = 4; memset(&sol, 0, sizeof(sol)); sol.fix_type = d->have_lock?3:0; sol.fix_status = 221; - sol.satellites = d->have_lock ? _sitl->gps_numsats[instance] : 3; + sol.satellites = d->have_lock ? d->num_sats : 3; sol.time = gps_tow.ms; sol.week = gps_tow.week; @@ -248,46 +252,34 @@ void GPS_UBlox::publish(const GPS_Data *d) pvt.fix_type = d->have_lock? 0x3 : 0; pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok pvt.flags2 =0; - pvt.num_sv = d->have_lock ? _sitl->gps_numsats[instance] : 3; + pvt.num_sv = d->have_lock ? d->num_sats : 3; pvt.lon = d->longitude * 1.0e7; pvt.lat = d->latitude * 1.0e7; pvt.height = d->altitude * 1000.0f; pvt.h_msl = d->altitude * 1000.0f; - pvt.h_acc = _sitl->gps_accuracy[instance] * 1000; - pvt.v_acc = _sitl->gps_accuracy[instance] * 1000; + pvt.h_acc = d->horizontal_acc * 1000; + pvt.v_acc = d->vertical_acc * 1000; pvt.velN = 1000.0f * d->speedN; pvt.velE = 1000.0f * d->speedE; pvt.velD = 1000.0f * d->speedD; pvt.gspeed = norm(d->speedN, d->speedE) * 1000; pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; - pvt.s_acc = 40; + pvt.s_acc = velned.speed_accuracy; pvt.head_acc = 38 * 1.0e5; pvt.p_dop = 65535; memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1)); pvt.headVeh = 0; memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2)); - if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { - const Vector3f ant1_pos = _sitl->gps_pos_offset[instance^1].get(); - const Vector3f ant2_pos = _sitl->gps_pos_offset[instance].get(); - Vector3f rel_antenna_pos = ant2_pos - ant1_pos; - Matrix3f rot; - // project attitude back using gyros to get antenna orientation at time of GPS sample - Vector3f gyro(radians(_sitl->state.rollRate), - radians(_sitl->state.pitchRate), - radians(_sitl->state.yawRate)); - rot.from_euler(radians(_sitl->state.rollDeg), radians(_sitl->state.pitchDeg), radians(d->yaw_deg)); - const float lag = _sitl->gps_delay_ms[instance] * 0.001; - rot.rotate(gyro * (-lag)); - rel_antenna_pos = rot * rel_antenna_pos; - relposned.version = 1; - relposned.iTOW = gps_tow.ms; - relposned.relPosN = rel_antenna_pos.x * 100; - relposned.relPosE = rel_antenna_pos.y * 100; - relposned.relPosD = rel_antenna_pos.z * 100; - relposned.relPosLength = rel_antenna_pos.length() * 100; - relposned.relPosHeading = degrees(Vector2f(rel_antenna_pos.x, rel_antenna_pos.y).angle()) * 1.0e5; - relposned.flags = gnssFixOK | diffSoln | carrSolnFixed | isMoving | relPosValid | relPosHeadingValid; + switch (_sitl->gps[instance].hdg_enabled) { + case SITL::SIM::GPS_HEADING_NONE: + case SITL::SIM::GPS_HEADING_BASE: + break; + case SITL::SIM::GPS_HEADING_THS: + case SITL::SIM::GPS_HEADING_KSXT: + case SITL::SIM::GPS_HEADING_HDT: + update_relposned(relposned, gps_tow.ms, d->yaw_deg); + break; } send_ubx(MSG_POSLLH, (uint8_t*)&pos, sizeof(pos)); @@ -296,7 +288,7 @@ void GPS_UBlox::publish(const GPS_Data *d) send_ubx(MSG_SOL, (uint8_t*)&sol, sizeof(sol)); send_ubx(MSG_DOP, (uint8_t*)&dop, sizeof(dop)); send_ubx(MSG_PVT, (uint8_t*)&pvt, sizeof(pvt)); - if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { + if (_sitl->gps[instance].hdg_enabled > SITL::SIM::GPS_HEADING_NONE) { send_ubx(MSG_RELPOSNED, (uint8_t*)&relposned, sizeof(relposned)); } @@ -309,7 +301,7 @@ void GPS_UBlox::publish(const GPS_Data *d) for (uint8_t i = 0; i < SV_COUNT; i++) { svinfo.sv[i].chn = i; svinfo.sv[i].svid = i; - svinfo.sv[i].flags = (i < _sitl->gps_numsats[instance]) ? 0x7 : 0x6; // sv used, diff correction data, orbit information + svinfo.sv[i].flags = (i < d->num_sats) ? 0x7 : 0x6; // sv used, diff correction data, orbit information svinfo.sv[i].quality = 7; // code and carrier lock and time synchronized svinfo.sv[i].cno = MAX(20, 30 - i); svinfo.sv[i].elev = MAX(30, 90 - i); diff --git a/libraries/SITL/SIM_GPS_UBLOX.h b/libraries/SITL/SIM_GPS_UBLOX.h index 6ab5d01eea76fc..06f03cf5d8e60b 100644 --- a/libraries/SITL/SIM_GPS_UBLOX.h +++ b/libraries/SITL/SIM_GPS_UBLOX.h @@ -15,6 +15,45 @@ class GPS_UBlox : public GPS_Backend { void publish(const GPS_Data *d) override; private: + enum RELPOSNED { + gnssFixOK = 1U << 0, + diffSoln = 1U << 1, + relPosValid = 1U << 2, + carrSolnFloat = 1U << 3, + + carrSolnFixed = 1U << 4, + isMoving = 1U << 5, + refPosMiss = 1U << 6, + refObsMiss = 1U << 7, + + relPosHeadingValid = 1U << 8, + relPosNormalized = 1U << 9 + }; + struct PACKED ubx_nav_relposned { + uint8_t version; + uint8_t reserved1; + uint16_t refStationId; + uint32_t iTOW; + int32_t relPosN; + int32_t relPosE; + int32_t relPosD; + int32_t relPosLength; + int32_t relPosHeading; + uint8_t reserved2[4]; + int8_t relPosHPN; + int8_t relPosHPE; + int8_t relPosHPD; + int8_t relPosHPLength; + uint32_t accN; + uint32_t accE; + uint32_t accD; + uint32_t accLength; + uint32_t accHeading; + uint8_t reserved3[4]; + uint32_t flags; + }; + + void update_relposned(ubx_nav_relposned &relposned, uint32_t tow_ms, float yaw_deg); void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); }; diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 6a13d8b8e51441..9b76b3da23b6a4 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -43,7 +43,7 @@ class Gazebo : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Gazebo(frame_str); + return NEW_NOTHROW Gazebo(frame_str); } /* Create and set in/out socket for Gazebo simulator */ diff --git a/libraries/SITL/SIM_GeneratorEngine.cpp b/libraries/SITL/SIM_GeneratorEngine.cpp index 5e862cf1d78167..d0d5ba25cf70d5 100644 --- a/libraries/SITL/SIM_GeneratorEngine.cpp +++ b/libraries/SITL/SIM_GeneratorEngine.cpp @@ -42,7 +42,7 @@ void SIM_GeneratorEngine::update() temperature = MIN(temperature, 150); // now lose some heat to the environment const float heat_loss = ((temperature * heat_environment_loss_factor * (time_delta_ms * (1/1000.0f)))); // lose some % of heat per second - // gcs().send_text(MAV_SEVERITY_INFO, "heat=%f loss=%f", temperature, heat_loss); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "heat=%f loss=%f", temperature, heat_loss); temperature -= heat_loss; } diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index 5aede11b3b40a3..a905a38d731d09 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -13,19 +13,17 @@ along with this program. If not, see . */ /* - gimbal simulator class for MAVLink gimbal + gimbal simulator class for gimbal */ #include "SIM_Gimbal.h" -#if HAL_SIM_GIMBAL_ENABLED +#if AP_SIM_GIMBAL_ENABLED #include #include "SIM_Aircraft.h" -#include - extern const AP_HAL::HAL& hal; #define GIMBAL_DEBUG 0 @@ -38,27 +36,10 @@ extern const AP_HAL::HAL& hal; namespace SITL { -Gimbal::Gimbal(const struct sitl_fdm &_fdm) : - fdm(_fdm), - target_address("127.0.0.1"), - target_port(5762), - lower_joint_limits(radians(-40), radians(-135), radians(-7.5)), - upper_joint_limits(radians(40), radians(45), radians(7.5)), - travelLimitGain(20), - reporting_period_ms(10), - seen_heartbeat(false), - seen_gimbal_control(false), - mav_socket(false) -{ - memset(&mavlink, 0, sizeof(mavlink)); - fdm.quaternion.rotation_matrix(dcm); -} - - /* update the gimbal state */ -void Gimbal::update(void) +void Gimbal::update(const class Aircraft &aircraft) { // calculate delta time in seconds uint32_t now_us = AP_HAL::micros(); @@ -66,8 +47,10 @@ void Gimbal::update(void) float delta_t = (now_us - last_update_us) * 1.0e-6f; last_update_us = now_us; - Matrix3f vehicle_dcm; - fdm.quaternion.rotation_matrix(vehicle_dcm); + const Matrix3f &vehicle_dcm = aircraft.get_dcm(); + if (!init_done) { + dcm = vehicle_dcm; + } const Vector3f &vehicle_gyro = AP::ins().get_gyro(); const Vector3f &vehicle_accel_body = AP::ins().get_accel(); @@ -181,234 +164,21 @@ void Gimbal::update(void) // integrate velocity delta_velocity += accel * delta_t; - - // see if we should do a report - send_report(); } -static struct gimbal_param { - const char *name; - float value; -} gimbal_params[] = { - {"GMB_OFF_ACC_X", 0}, - {"GMB_OFF_ACC_Y", 0}, - {"GMB_OFF_ACC_Z", 0}, - {"GMB_GN_ACC_X", 0}, - {"GMB_GN_ACC_Y", 0}, - {"GMB_GN_ACC_Z", 0}, - {"GMB_OFF_GYRO_X", 0}, - {"GMB_OFF_GYRO_Y", 0}, - {"GMB_OFF_GYRO_Z", 0}, - {"GMB_OFF_JNT_X", 0}, - {"GMB_OFF_JNT_Y", 0}, - {"GMB_OFF_JNT_Z", 0}, - {"GMB_K_RATE", 0}, - {"GMB_POS_HOLD", 0}, - {"GMB_MAX_TORQUE", 0}, - {"GMB_SND_TORQUE", 0}, - {"GMB_SYSID", 0}, - {"GMB_FLASH", 0}, -}; - -/* - find a parameter structure - */ -struct gimbal_param *Gimbal::param_find(const char *name) -{ - for (uint8_t i=0; iname, sizeof(param_value.param_id)); - param_value.param_value = p->value; - param_value.param_count = 0; - param_value.param_index = 0; - param_value.param_type = MAV_PARAM_TYPE_REAL32; - - uint16_t len = mavlink_msg_param_value_encode_status(vehicle_system_id, - vehicle_component_id, - &mavlink.status, - &msg, ¶m_value); - - uint8_t msgbuf[len]; - len = mavlink_msg_to_send_buffer(msgbuf, &msg); - if (len > 0) { - mav_socket.send(msgbuf, len); - } -} + const uint32_t now_us = AP_HAL::micros(); - -/* - send a report to the vehicle control code over MAVLink -*/ -void Gimbal::send_report(void) -{ - uint32_t now = AP_HAL::millis(); - if (now < 10000) { - // don't send gimbal reports until 10s after startup. This - // avoids a windows threading issue with non-blocking sockets - // and the initial wait on SERIAL0 - return; - } - if (!mavlink.connected && mav_socket.connect(target_address, target_port)) { - ::printf("Gimbal connected to %s:%u\n", target_address, (unsigned)target_port); - mavlink.connected = true; - } - if (!mavlink.connected) { - return; - } - - if (param_send_last_ms && now - param_send_last_ms > 100) { - param_send(&gimbal_params[param_send_idx]); - if (++param_send_idx == ARRAY_SIZE(gimbal_params)) { - printf("Finished sending parameters\n"); - param_send_last_ms = 0; - } - } + _delta_angle = delta_angle; + _delta_velocity = delta_velocity; + _delta_time_us = now_us - delta_start_us; - // check for incoming MAVLink messages - uint8_t buf[100]; - ssize_t ret; - - while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) { - for (uint8_t i=0; ivalue = pkt.param_value; - param_send(p); - } - - break; - } - case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { - mavlink_param_request_list_t pkt; - mavlink_msg_param_request_list_decode(&msg, &pkt); - if (pkt.target_system == 0 && pkt.target_component == MAV_COMP_ID_GIMBAL) { - // start param send - param_send_idx = 0; - param_send_last_ms = AP_HAL::millis(); - } - printf("Gimbal sending %u parameters\n", (unsigned)ARRAY_SIZE(gimbal_params)); - break; - } - default: - debug("got unexpected msg %u\n", msg.msgid); - break; - } - } - } - } - - if (!seen_heartbeat) { - return; - } - mavlink_message_t msg; - uint16_t len; - - if (now - last_heartbeat_ms >= 1000) { - mavlink_heartbeat_t heartbeat; - heartbeat.type = MAV_TYPE_GIMBAL; - heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA; - heartbeat.base_mode = 0; - heartbeat.system_status = 0; - heartbeat.mavlink_version = 0; - heartbeat.custom_mode = 0; - - len = mavlink_msg_heartbeat_encode_status(vehicle_system_id, - vehicle_component_id, - &mavlink.status, - &msg, &heartbeat); - - mav_socket.send(&msg.magic, len); - last_heartbeat_ms = now; - } - - /* - send a GIMBAL_REPORT message - */ - uint32_t now_us = AP_HAL::micros(); - if (now_us - last_report_us > reporting_period_ms*1000UL) { - mavlink_gimbal_report_t gimbal_report; - float delta_time = (now_us - last_report_us) * 1.0e-6f; - last_report_us = now_us; - gimbal_report.target_system = vehicle_system_id; - gimbal_report.target_component = vehicle_component_id; - gimbal_report.delta_time = delta_time; - gimbal_report.delta_angle_x = delta_angle.x; - gimbal_report.delta_angle_y = delta_angle.y; - gimbal_report.delta_angle_z = delta_angle.z; - gimbal_report.delta_velocity_x = delta_velocity.x; - gimbal_report.delta_velocity_y = delta_velocity.y; - gimbal_report.delta_velocity_z = delta_velocity.z; - gimbal_report.joint_roll = joint_angles.x; - gimbal_report.joint_el = joint_angles.y; - gimbal_report.joint_az = joint_angles.z; - - len = mavlink_msg_gimbal_report_encode_status(vehicle_system_id, - vehicle_component_id, - &mavlink.status, - &msg, &gimbal_report); - - uint8_t msgbuf[len]; - len = mavlink_msg_to_send_buffer(msgbuf, &msg); - if (len > 0) { - mav_socket.send(msgbuf, len); - } - - delta_velocity.zero(); - delta_angle.zero(); - } + delta_angle.zero(); + delta_velocity.zero(); + delta_start_us = now_us; } } // namespace SITL -#endif // HAL_SIM_GIMBAL_ENABLED +#endif // AP_SIM_GIMBAL_ENABLED diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 2cedd3a1cf9c3f..d3814383b69ba1 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -18,32 +18,31 @@ #pragma once -#include +#include "SIM_config.h" -#ifndef HAL_SIM_GIMBAL_ENABLED -#define HAL_SIM_GIMBAL_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && !defined(HAL_BUILD_AP_PERIPH) -#endif +#if AP_SIM_GIMBAL_ENABLED -#if HAL_SIM_GIMBAL_ENABLED - -#include - -#include "SIM_Aircraft.h" +#include +#include namespace SITL { class Gimbal { public: - Gimbal(const struct sitl_fdm &_fdm); - void update(void); + + void update(const class Aircraft &aircraft); + void set_demanded_rates(const Vector3f &rates) { + demanded_angular_rate = rates; + } + + void get_deltas(Vector3f &_delta_angle, Vector3f &_delta_velocity, uint32_t &_delta_time_us); + void get_joint_angles(Vector3f &_angles) { _angles = joint_angles; } private: - const struct sitl_fdm &fdm; - const char *target_address; - const uint16_t target_port; // rotation matrix (gimbal body -> earth) Matrix3f dcm; + bool init_done; // time of last update uint32_t last_update_us; @@ -63,19 +62,16 @@ class Gimbal { Vector3f joint_angles; // physical constraints on joint angles in (roll, pitch, azimuth) order - Vector3f lower_joint_limits; - Vector3f upper_joint_limits; + Vector3f lower_joint_limits{radians(-40), radians(-135), radians(-7.5)}; + Vector3f upper_joint_limits{radians(40), radians(45), radians(7.5)}; - const float travelLimitGain; + const float travelLimitGain = 20; // true gyro bias Vector3f true_gyro_bias; - // reporting variables. gimbal pushes these to vehicle code over - // MAVLink at approx 100Hz - - // reporting period in ms - const float reporting_period_ms; + // time since delta angles/velocities returned + uint32_t delta_start_us; // integral of gyro vector over last time interval. In radians Vector3f delta_angle; @@ -92,32 +88,9 @@ class Gimbal { // gyro bias provided by EKF on vehicle. In rad/s. // Should be subtracted from the gyro readings to get true body // rotatation rates - Vector3f supplied_gyro_bias; - - uint32_t last_report_us; - uint32_t last_heartbeat_ms; - bool seen_heartbeat; - bool seen_gimbal_control; - uint8_t vehicle_system_id; - uint8_t vehicle_component_id; - - SocketAPM_native mav_socket; - struct { - // socket to telem2 on aircraft - bool connected; - mavlink_message_t rxmsg; - mavlink_status_t status; - uint8_t seq; - } mavlink; - - uint32_t param_send_last_ms; - uint8_t param_send_idx; - - void send_report(void); - void param_send(const struct gimbal_param *p); - struct gimbal_param *param_find(const char *name); + // Vector3f supplied_gyro_bias; }; } // namespace SITL -#endif // HAL_SIM_GIMBAL_ENABLED +#endif // AP_SIM_GIMBAL_ENABLED diff --git a/libraries/SITL/SIM_Glider.cpp b/libraries/SITL/SIM_Glider.cpp new file mode 100644 index 00000000000000..a1334aac6168c4 --- /dev/null +++ b/libraries/SITL/SIM_Glider.cpp @@ -0,0 +1,432 @@ +/* + 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 . + */ +/* + glider model for high altitude balloon drop + + controls: + - servo6: balloon lift, 1000 for no lift, 2000 for maximum lift + - servo10: balloon cut, this cuts away the balloon when high + + Note that the glider starts off in a lifted by tail pose, with pitch + -80 degrees. The balloon then lifts the glider above the ground. The + balloon automatically bursts at a height of SIM_GLD_BLN_BRST meters, + or can be cut away early with servo10. + + The maximum rate of the balloon lift is in SIM_GLD_BLN_RATE, in m/s + + To perform a takeoff first arm on the ground then use + servo set 6 2000 + to release the ground hold. Use this to cut away the balloon: + servo set 10 2000 + + For an automatic mission, NAV_ALTITUDE_WAIT should be used to wait + for a desired altitude under balloon lift. Then a DO_SET_SERVO with + servo 10 and a value of 2000 to cut away the balloon. + */ + +#include "SIM_Glider.h" + +#if AP_SIM_GLIDER_ENABLED + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +using namespace SITL; + +// SITL glider parameters +const AP_Param::GroupInfo Glider::var_info[] = { + // @Param: BLN_BRST + // @DisplayName: balloon burst height + // @Description: balloon burst height + // @Units: m + AP_GROUPINFO("BLN_BRST", 1, Glider, balloon_burst_amsl, 30000), + + // @Param: BLN_RATE + // @DisplayName: balloon climb rate + // @Description: balloon climb rate + // @Units: m/s + AP_GROUPINFO("BLN_RATE", 2, Glider, balloon_rate, 5.5), + + AP_GROUPEND +}; + +Glider::Glider(const char *frame_str) : + Aircraft(frame_str) +{ + ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; + carriage_state = carriageState::WAITING_FOR_PICKUP; + AP::sitl()->models.glider_ptr = this; + AP_Param::setup_object_defaults(this, var_info); +} + + +// Torque calculation function +Vector3f Glider::getTorque(float inputAileron, float inputElevator, float inputRudder, const Vector3f &force) const +{ + // Calculate dynamic pressure + const auto &m = model; + double qPa = 0.5*air_density*sq(velocity_air_bf.length()); + const float aileron_rad = inputAileron * radians(m.aileronDeflectionLimitDeg); + const float elevator_rad = inputElevator * radians(m.elevatorDeflectionLimitDeg); + const float rudder_rad = inputRudder * radians(m.rudderDeflectionLimitDeg); + const float tas = MAX(airspeed * AP::ahrs().get_EAS2TAS(), 1); + + float Cl = (m.Cl2 * sq(alpharad) + m.Cl1 * alpharad + m.Cl0) * betarad; + float Cm = m.Cm2 * sq(alpharad) + m.Cm1 * alpharad + m.Cm0; + float Cn = (m.Cn2 * sq(alpharad) + m.Cn1 * alpharad + m.Cn0) * betarad; + + Cl += m.deltaClperRadianElev * elevator_rad; + Cm += m.deltaCmperRadianElev * elevator_rad; + Cn += m.deltaCnperRadianElev * elevator_rad; + + Cl += m.deltaClperRadianRud * rudder_rad; + Cm += m.deltaCmperRadianRud * rudder_rad; + Cn += m.deltaCnperRadianRud * rudder_rad; + + Cl += (m.deltaClperRadianAil2 * sq(alpharad) + m.deltaClperRadianAil1 * alpharad + m.deltaClperRadianAil0) * aileron_rad; + Cm += m.deltaCmperRadianAil * aileron_rad; + Cn += (m.deltaCnperRadianAil2 * sq(alpharad) + m.deltaCnperRadianAil1 * alpharad + m.deltaCnperRadianAil0) * aileron_rad; + + // derivatives + float Clp = m.Clp2 * sq(alpharad) + m.Clp1 * alpharad + m.Clp0; + float Clr = m.Clr2 * sq(alpharad) + m.Clr1 * alpharad + m.Clr0; + float Cnp = m.Cnp2 * sq(alpharad) + m.Cnp1 * alpharad + m.Cnp0; + float Cnr = m.Cnr2 * sq(alpharad) + m.Cnr1 * alpharad + m.Cnr0; + + // normalise gyro rates + Vector3f pqr_norm = gyro; + pqr_norm.x *= 0.5 * m.refSpan / tas; + pqr_norm.y *= 0.5 * m.refChord / tas; + pqr_norm.z *= 0.5 * m.refSpan / tas; + + Cl += pqr_norm.x * Clp; + Cl += pqr_norm.z * Clr; + Cn += pqr_norm.x * Cnp; + Cn += pqr_norm.z * Cnr; + + Cm += pqr_norm.y * m.Cmq; + + float Mx = Cl * qPa * m.Sref * m.refSpan; + float My = Cm * qPa * m.Sref * m.refChord; + float Mz = Cn * qPa * m.Sref * m.refSpan; + + +#if 0 + AP::logger().Write("GLT", "TimeUS,Alpha,Beta,Cl,Cm,Cn", "Qfffff", + AP_HAL::micros64(), + degrees(alpharad), + degrees(betarad), + Cl, Cm, Cn); +#endif + + return Vector3f(Mx/m.IXX, My/m.IYY, Mz/m.IZZ); +} + +// Force calculation, return vector in Newtons +Vector3f Glider::getForce(float inputAileron, float inputElevator, float inputRudder) +{ + const auto &m = model; + const float aileron_rad = inputAileron * radians(m.aileronDeflectionLimitDeg); + const float elevator_rad = inputElevator * radians(m.elevatorDeflectionLimitDeg); + const float rudder_rad = inputRudder * radians(m.rudderDeflectionLimitDeg); + + // dynamic pressure + double qPa = 0.5*air_density*sq(velocity_air_bf.length()); + + float CA = m.CA2 * sq(alpharad) + m.CA1 * alpharad + m.CA0; + float CY = (m.CY2 * sq(alpharad) + m.CY1 * alpharad + m.CY0) * betarad; + float CN = m.CN2 * sq(alpharad) + m.CN1 * alpharad + m.CN0; + + CN += m.deltaCNperRadianElev * elevator_rad; + CA += m.deltaCAperRadianElev * elevator_rad; + CY += m.deltaCYperRadianElev * elevator_rad; + + CN += m.deltaCNperRadianRud * rudder_rad; + CA += m.deltaCAperRadianRud * rudder_rad; + CY += m.deltaCYperRadianRud * rudder_rad; + + CN += m.deltaCNperRadianAil * aileron_rad; + CA += m.deltaCAperRadianAil * aileron_rad; + CY += m.deltaCYperRadianAil * aileron_rad; + + float Fx = -CA * qPa * m.Sref; + float Fy = CY * qPa * m.Sref; + float Fz = -CN * qPa * m.Sref; + + Vector3f ret = Vector3f(Fx, Fy, Fz); + + float Flift = Fx * sin(alpharad) - Fz * cos(alpharad); + float Fdrag = -Fx * cos(alpharad) - Fz * sin(alpharad); + + if (carriage_state == carriageState::RELEASED) { + uint32_t now = AP_HAL::millis(); + sim_LD = 0.1 * constrain_float(Flift/MAX(1.0e-6,Fdrag),0,20) + 0.9 * sim_LD; + if (now - last_drag_ms > 10 && + airspeed > 1) { + last_drag_ms = now; +#if HAL_LOGGING_ENABLED + AP::logger().Write("SLD", "TimeUS,AltFt,AltM,EAS,TAS,AD,Fl,Fd,LD,Elev,AoA,Fx,Fy,Fz,q", "Qffffffffffffff", + AP_HAL::micros64(), + (location.alt*0.01)/FEET_TO_METERS, + location.alt*0.01, + velocity_air_bf.length()/eas2tas, + velocity_air_bf.length(), + air_density, + Flift, Fdrag, sim_LD, + degrees(elevator_rad), + degrees(alpharad), + Fx, Fy, Fz, + qPa); + AP::logger().Write("SL2", "TimeUS,AltFt,KEAS,KTAS,AD,Fl,Fd,LD,Elev,Ail,Rud,AoA,SSA,q,Az", "Qffffffffffffff", + AP_HAL::micros64(), + (location.alt*0.01)/FEET_TO_METERS, + M_PER_SEC_TO_KNOTS*velocity_air_bf.length()/eas2tas, + M_PER_SEC_TO_KNOTS*velocity_air_bf.length(), + air_density, + Flift, Fdrag, sim_LD, + degrees(elevator_rad), + degrees(aileron_rad), + degrees(rudder_rad), + degrees(alpharad), + degrees(betarad), + qPa, + accel_body.z); + + AP::logger().Write("SCTL", "TimeUS,Ail,Elev,Rudd", "Qfff", + AP_HAL::micros64(), + degrees(aileron_rad), + degrees(elevator_rad), + degrees(rudder_rad)); +#endif // HAL_LOGGING_ENABLED + } + } + + + return ret; +} + +void Glider::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel) +{ + filtered_servo_setup(1, 1100, 1900, model.aileronDeflectionLimitDeg); + filtered_servo_setup(4, 1100, 1900, model.aileronDeflectionLimitDeg); + filtered_servo_setup(2, 1100, 1900, model.elevatorDeflectionLimitDeg); + filtered_servo_setup(3, 1100, 1900, model.rudderDeflectionLimitDeg); + + float aileron = 0.5*(filtered_servo_angle(input, 1) + filtered_servo_angle(input, 4)); + float elevator = filtered_servo_angle(input, 2); + float rudder = filtered_servo_angle(input, 3); + float balloon = MAX(0.0f, filtered_servo_range(input, 5)); // Don't let the balloon receive downwards commands. + float balloon_cut = filtered_servo_range(input, 9); + + // Move balloon upwards using balloon velocity from channel 6 + // Aircraft is released from ground constraint when channel 6 PWM > 1010 + // Once released, plane will be dropped when balloon_burst_amsl is reached or channel 6 is set to PWM 1000 + if (carriage_state == carriageState::WAITING_FOR_RELEASE) { + balloon_velocity = Vector3f(-wind_ef.x, -wind_ef.y, -wind_ef.z -balloon_rate * balloon); + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + const float height_AMSL = 0.01f * (float)home.alt - position.z; + // release at burst height or when balloon cut output goes high + if (hal.scheduler->is_system_initialized() && + (height_AMSL > balloon_burst_amsl || balloon_cut > 0.8)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "pre-release at %i m AMSL\n", (int)height_AMSL); + carriage_state = carriageState::PRE_RELEASE; + } + } else if (carriage_state == carriageState::PRE_RELEASE) { + // slow down for release + balloon_velocity *= 0.999; + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + if (balloon_velocity.length() < 0.5) { + carriage_state = carriageState::RELEASED; + use_smoothing = false; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "released at %.0f m AMSL\n", (0.01f * home.alt) - position.z); + } + } else if (carriage_state == carriageState::WAITING_FOR_PICKUP) { + // Don't allow the balloon to drag sideways until the pickup + balloon_velocity = Vector3f(0.0f, 0.0f, -balloon_rate * balloon); + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + } + + // calculate angle of attack + alpharad = atan2f(velocity_air_bf.z, velocity_air_bf.x); + betarad = atan2f(velocity_air_bf.y,velocity_air_bf.x); + + alpharad = constrain_float(alpharad, -model.alphaRadMax, model.alphaRadMax); + betarad = constrain_float(betarad, -model.betaRadMax, model.betaRadMax); + + Vector3f force; + + if (!update_balloon(balloon, force, rot_accel)) { + force = getForce(aileron, elevator, rudder); + rot_accel = getTorque(aileron, elevator, rudder, force); + } + + accel_body = force / model.mass; + + if (on_ground()) { + // add some ground friction + Vector3f vel_body = dcm.transposed() * velocity_ef; + accel_body.x -= vel_body.x * 0.3f; + } + + // constrain accelerations + accel_body.x = constrain_float(accel_body.x, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + accel_body.y = constrain_float(accel_body.y, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + accel_body.z = constrain_float(accel_body.z, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + +} + +/* + update the plane simulation by one time step + */ +void Glider::update(const struct sitl_input &input) +{ + Vector3f rot_accel; + + update_wind(input); + + calculate_forces(input, rot_accel, accel_body); + + if (carriage_state == carriageState::WAITING_FOR_PICKUP) { + // Handle special case where plane is being held nose down waiting to be lifted + accel_body = dcm.transposed() * Vector3f(0.0f, 0.0f, -GRAVITY_MSS); + velocity_ef.zero(); + gyro.zero(); + dcm.from_euler(0.0f, radians(-80.0f), radians(home_yaw)); + use_smoothing = true; + adjust_frame_time(constrain_float(sitl->loop_rate_hz, rate_hz-1, rate_hz+1)); + } else { + update_dynamics(rot_accel); + } + update_external_payload(input); + + // update lat/lon/altitude + update_position(); + time_advance(); + + // update magnetic field + update_mag_field_bf(); +} + +/* + return true if we are on the ground +*/ +bool Glider::on_ground() const +{ + switch (carriage_state) { + case carriageState::NONE: + case carriageState::RELEASED: + return hagl() <= 0.001; + case carriageState::WAITING_FOR_PICKUP: + case carriageState::WAITING_FOR_RELEASE: + case carriageState::PRE_RELEASE: + // prevent bouncing around ground + // don't do ground interaction if being carried + break; + } + return false; +} + +/* + implement balloon lift + controlled by SIM_BLN_BRST and SIM_BLN_RATE + */ +bool Glider::update_balloon(float balloon, Vector3f &force, Vector3f &rot_accel) +{ + if (!hal.util->get_soft_armed()) { + return false; + } + + switch (carriage_state) { + case carriageState::NONE: + case carriageState::RELEASED: + // balloon not active + disable_origin_movement = false; + return false; + + case carriageState::WAITING_FOR_PICKUP: + case carriageState::WAITING_FOR_RELEASE: + case carriageState::PRE_RELEASE: + // while under balloon disable origin movement to allow for balloon position calculations + disable_origin_movement = true; + break; + } + + // assume a 50m tether with a 1Hz pogo frequency and damping ratio of 0.2 + Vector3f tether_pos_bf{-1.0f,0.0f,0.0f}; // tether attaches to vehicle tail approx 1m behind c.g. + const float omega = model.tetherPogoFreq * M_2PI; // rad/sec + const float zeta = 0.7f; + float tether_stiffness = model.mass * sq(omega); // N/m + float tether_damping = 2.0f * zeta * omega / model.mass; // N/(m/s) + // NED relative position vector from tether attachment on plane to balloon attachment + Vector3f relative_position = balloon_position - (position.tofloat() + (dcm * tether_pos_bf)); + const float separation_distance = relative_position.length(); + + // NED unit vector pointing from tether attachment on plane to attachment on balloon + Vector3f tether_unit_vec_ef = relative_position.normalized(); + + // NED velocity of attachment point on plane + Vector3f attachment_velocity_ef = velocity_ef + dcm * (gyro % tether_pos_bf); + + // NED velocity of attachment point on balloon as seen by observer on attachemnt point on plane + Vector3f relative_velocity = balloon_velocity - attachment_velocity_ef; + + float separation_speed = relative_velocity * tether_unit_vec_ef; + + // rate increase in separation between attachment point on plane and balloon + // tension force in tether due to stiffness and damping + float tension_force = MAX(0.0f, (separation_distance - model.tetherLength) * tether_stiffness); + if (tension_force > 0.0f) { + tension_force += constrain_float(separation_speed * tether_damping, 0.0f, 0.05f * tension_force); + } + + if (carriage_state == carriageState::WAITING_FOR_PICKUP && tension_force > 1.2f * model.mass * GRAVITY_MSS && balloon > 0.01f) { + carriage_state = carriageState::WAITING_FOR_RELEASE; + } + + if (carriage_state == carriageState::WAITING_FOR_RELEASE || + carriage_state == carriageState::PRE_RELEASE) { + Vector3f tension_force_vector_ef = tether_unit_vec_ef * tension_force; + Vector3f tension_force_vector_bf = dcm.transposed() * tension_force_vector_ef; + force = tension_force_vector_bf; + + // drag force due to lateral motion assuming projected area from Y is 20% of projected area seen from Z and + // assuming bluff body drag characteristic. In reality we would need an aero model that worked flying backwards, + // but this will have to do for now. + Vector3f aero_force_bf = Vector3f(0.0f, 0.2f * velocity_air_bf.y * fabsf(velocity_air_bf.y), velocity_air_bf.z * fabsf(velocity_air_bf.z)); + aero_force_bf *= air_density * model.Sref; + force -= aero_force_bf; + + Vector3f tension_moment_vector_bf = tether_pos_bf % tension_force_vector_bf; + Vector3f tension_rot_accel = Vector3f(tension_moment_vector_bf.x/model.IXX, tension_moment_vector_bf.y/model.IYY, tension_moment_vector_bf.z/model.IZZ); + rot_accel = tension_rot_accel; + + // add some rotation damping due to air resistance assuming a 2 sec damping time constant at SL density + // TODO model roll damping with more accuracy using Clp data for zero alpha as a first approximation + rot_accel -= gyro * 0.5 * air_density; + } else { + // tether is either slack awaiting pickup or released + rot_accel.zero(); + force = dcm.transposed() * Vector3f(0.0f, 0.0f, -GRAVITY_MSS * model.mass); + } + + // balloon is active + return true; +} + +#endif // AP_SIM_GLIDER_ENABLED diff --git a/libraries/SITL/SIM_Glider.h b/libraries/SITL/SIM_Glider.h new file mode 100644 index 00000000000000..8c373c2f9f3d50 --- /dev/null +++ b/libraries/SITL/SIM_Glider.h @@ -0,0 +1,203 @@ +/* + 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 . + */ +/* + Glider model for high altitude balloon drop +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GLIDER_ENABLED + +#include "SIM_Aircraft.h" +#include + +namespace SITL { + +/* + a very simple plane simulator + */ +class Glider : public Aircraft { +public: + Glider(const char *frame_str); + + /* update model by one time step */ + virtual void update(const struct sitl_input &input) override; + + /* static object creator */ + static Aircraft *create(const char *frame_str) { + return NEW_NOTHROW Glider(frame_str); + } + + bool on_ground() const override; + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + float alpharad; + float betarad; + + AP_Float balloon_burst_amsl; + AP_Float balloon_rate; + + /* + parameters that define the glider model + */ + const struct Model { + // total vehicle mass + float mass = 9.07441; // kg + + // reference area + float Sref = 0.92762; // m^2 + + float refSpan = 1.827411; // m + float refChord = 0.507614; // m + float IXX = 0.234; // kg-m^2 + float IYY = 1.85; // kg-m^2 + float IZZ = 2.04; // kg-m^2 + + // CN is coefficients for forces on +Z axis + // quadratic in alpharad + float CN2 = -0.5771; + float CN1 = 3.9496; + float CN0 = 0; + + // CA is the coefficients for forces on +X axis + // quadratic in alpharad + float CA2 = -1.6809; + float CA1 = -0.0057; + float CA0 = 0.0150; + + // CY is the coefficients for forces on the +Y axis + // quadratic in alpharad, with betarad factor + float CY2 = -3.342; + float CY1 = 0.0227; + float CY0 = -0.4608; + + // Cl is the coefficients for moments on X axis + // quadratic in alpharad, with betarad factor + float Cl2 = 0.2888; + float Cl1 = -0.8518; + float Cl0 = -0.0491; + + // Cm is the coefficients for moments on Y axis + // quadratic in alpharad + float Cm2 = 0.099; + float Cm1 = -0.6506; + float Cm0 = -0.0005; + + // Cn is the coefficients for moments on Z axis + // quadratic in alpharad, with betarad factor + float Cn2 = 0.0057; + float Cn1 = -0.0101; + float Cn0 = 0.1744; + + // controls neutral dynamic derivatives + // p, q, r are gyro rates + float Cmq = -6.1866; + + float Clp2 = 0.156; + float Clp1 = 0.0129; + float Clp0 = -0.315; + + float Clr2 = -0.0284; + float Clr1 = 0.2641; + float Clr0 = 0.0343; + + float Cnp2 = 0.0199; + float Cnp1 = -0.315; + float Cnp0 = -0.013; + + float Cnr2 = 0.1297; + float Cnr1 = 0.0343; + float Cnr0 = -0.264; + + // elevator + float elevatorDeflectionLimitDeg = -12.5; + float deltaCNperRadianElev = -0.7; + float deltaCAperRadianElev = 0.12; + float deltaCmperRadianElev = 1.39; + float deltaCYperRadianElev = 0; + float deltaClperRadianElev = 0; + float deltaCnperRadianElev = 0; + + // rudder + float rudderDeflectionLimitDeg = 18.0; + float deltaCNperRadianRud = 0; + float deltaCAperRadianRud = 0.058; + float deltaCmperRadianRud = 0; + float deltaCYperRadianRud = 0.31; + float deltaClperRadianRud = 0.038; + float deltaCnperRadianRud = -0.174; + + // aileron + float aileronDeflectionLimitDeg = 15.5; + float deltaCNperRadianAil = 0; + float deltaCAperRadianAil = 0.016; + float deltaCmperRadianAil = 0; + float deltaCYperRadianAil = -0.015; + + // quadratic in alpharad + float deltaClperRadianAil0 = 0.09191; + float deltaClperRadianAil1 = 0.0001; + float deltaClperRadianAil2 = -0.08645; + + // quadratic in alpharad + float deltaCnperRadianAil0 = 0.00789; + float deltaCnperRadianAil1 = 0.00773; + float deltaCnperRadianAil2 = -0.01162; + + // Forces in the +X direction are –CA * q * Sref + // Forces in the +Y direction are +CY * q * Sref + // Forces in the +Z direction are –CN * q *Sref + // Moments about the X axis are +Cl * q * Sref * RefSpan + // Moments about the Y axis are +Cm * q * Sref * RefChord + // Moments about the Z axis are +Cn * q * Sref * RefSpan + + // low altitude + float alphaRadMax = 0.209; + float betaRadMax = 0.209; + + // balloon launch parameters + float tetherLength = 50.0f; // length of tether from balloon to aircraft (m) + float tetherPogoFreq = 2.0f; // measured vertical frequency of on tether (Hz) + + } model; + + Vector3f getForce(float inputAileron, float inputElevator, float inputRudder); + Vector3f getTorque(float inputAileron, float inputElevator, float inputRudder, const Vector3f &force) const; + bool update_balloon(float balloon, Vector3f &force, Vector3f &rot_accel); + void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + + Vector3f balloon_velocity; // balloon velocity NED + Vector3f balloon_position{0.0f, 0.0f, -45.0f}; // balloon position NED from origin + + enum class carriageState { + NONE = 0, // no carriage option available + WAITING_FOR_PICKUP = 1, // in launch cradle waiting to be picked up by launch vehicle + WAITING_FOR_RELEASE = 2, // being carried by luanch vehicle waitng to be released + PRE_RELEASE = 3, // had been released by launch vehicle + RELEASED = 4 // had been released by launch vehicle + } carriage_state; + bool plane_air_release; // true when plane has separated from the airborne launching platform + + uint32_t last_drag_ms; + float sim_LD; +}; + +} // namespace SITL + +#endif // AP_SIM_GLIDER_ENABLED diff --git a/libraries/SITL/SIM_Gripper_EPM.cpp b/libraries/SITL/SIM_Gripper_EPM.cpp index 09f73102a421ca..c2b4e91b35183d 100644 --- a/libraries/SITL/SIM_Gripper_EPM.cpp +++ b/libraries/SITL/SIM_Gripper_EPM.cpp @@ -68,16 +68,16 @@ void Gripper_EPM::update_from_demand() const float dt = (now - last_update_us) * 1.0e-6f; // decay the field - field_strength = field_strength * (100.0f - field_decay_rate * dt) / 100.0f; + field_strength = field_strength * (100.0f - field_decay_rate * dt) * 0.01f; // note that "demand" here is just an on/off switch; we only care // about which range it falls into if (demand > 0.6f) { // we are instructed to grip harder - field_strength = field_strength + (100.0f - field_strength) * field_strength_slew_rate / 100.0f * dt; + field_strength = field_strength + (100.0f - field_strength) * field_strength_slew_rate * 0.01f * dt; } else if (demand < 0.4f) { // we are instructed to loosen grip - field_strength = field_strength * (100.0f - field_degauss_rate * dt) / 100.0f; + field_strength = field_strength * (100.0f - field_degauss_rate * dt) * 0.01f; } else { // neutral; no demanded change } @@ -121,5 +121,5 @@ float Gripper_EPM::tesla() const // https://en.wikipedia.org/wiki/Orders_of_magnitude_(magnetic_field) // 200N lifting capacity ~= 2.5T const float percentage_to_tesla = 0.25f; - return static_cast(percentage_to_tesla * field_strength / 100.0f); + return static_cast(percentage_to_tesla * field_strength * 0.01f); } diff --git a/libraries/SITL/SIM_Gripper_Servo.cpp b/libraries/SITL/SIM_Gripper_Servo.cpp index 2237e69a124f8c..d1b95c394dc21f 100644 --- a/libraries/SITL/SIM_Gripper_Servo.cpp +++ b/libraries/SITL/SIM_Gripper_Servo.cpp @@ -89,7 +89,7 @@ void Gripper_Servo::update(const struct sitl_input &input) position_demand = position; } - const float position_max_change = position_slew_rate / 100.0f * dt; + const float position_max_change = position_slew_rate * 0.01f * dt; position = constrain_float(position_demand, position - position_max_change, position + position_max_change); float jaw_gap; if ((release_pwm < grab_pwm && reverse) || (release_pwm > grab_pwm && !reverse)) { diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index 81143f3e3da9af..28727829e77904 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -33,7 +33,7 @@ Helicopter::Helicopter(const char *frame_str) : _time_delay = 30; nominal_rpm = 1300; mass = 9.08f; - iyy = 0.2f; + iyy = 5.0f; } else if (strstr(frame_str, "-compound")) { frame_type = HELI_FRAME_COMPOUND; _time_delay = 50; @@ -104,7 +104,7 @@ void Helicopter::update(const struct sitl_input &input) } } else if (servos_stored_buffer == nullptr) { uint16_t buffer_size = constrain_int16(_time_delay, 1, 100) * 0.001f / dt; - servos_stored_buffer = new ObjectBuffer(buffer_size); + servos_stored_buffer = NEW_NOTHROW ObjectBuffer(buffer_size); while (servos_stored_buffer->space() != 0) { push_to_buffer(input.servos); } @@ -218,7 +218,7 @@ void Helicopter::update(const struct sitl_input &input) case HELI_FRAME_DUAL: { - float Ma1s = 617.5f; + float Ma1s = 617.5f/5.0f; float Lb1s = 3588.6f; float Mu = 0.003f; float Lv = -0.006f; @@ -259,7 +259,7 @@ void Helicopter::update(const struct sitl_input &input) // rotational acceleration, in rad/s/s, in body frame rot_accel.x = (_tpp_angle_1.x + _tpp_angle_2.x) * Lb1s + Lv * velocity_air_bf.y; - rot_accel.y = (_tpp_angle_1.y + _tpp_angle_2.y) * Ma1s + (thrust_1 - thrust_2) * hub_dist / iyy + Mu * velocity_air_bf.x + hub_dist * gyro.y * Zw; + rot_accel.y = (_tpp_angle_1.y + _tpp_angle_2.y) * Ma1s + (thrust_1 - thrust_2) * hub_dist / iyy + Mu * velocity_air_bf.x; rot_accel.z = (_tpp_angle_1.x * thrust_1 - _tpp_angle_2.x * thrust_2) * hub_dist / (iyy * 2.0f) - 0.5f * gyro.z; lateral_y_thrust = GRAVITY_MSS * (_tpp_angle_1.x + _tpp_angle_2.x) + Yv * velocity_air_bf.y; diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index 4410b19dec903f..f1a445054310a2 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -34,7 +34,7 @@ class Helicopter : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Helicopter(frame_str); + return NEW_NOTHROW Helicopter(frame_str); } protected: diff --git a/libraries/SITL/SIM_I2CDevice.cpp b/libraries/SITL/SIM_I2CDevice.cpp index e8d8a20aaeaa06..53bbcf317fcbef 100644 --- a/libraries/SITL/SIM_I2CDevice.cpp +++ b/libraries/SITL/SIM_I2CDevice.cpp @@ -242,7 +242,7 @@ void SITL::I2CRegisters_ConfigurableLength::set_register(uint8_t reg, uint8_t va if (reg_data_len[reg] != 1) { AP_HAL::panic("Invalid set_register len"); } - reg_data[reg] = value; + reg_data[reg] = value << 24; } void SITL::I2CRegisters_ConfigurableLength::set_register(uint8_t reg, int8_t value) @@ -254,7 +254,7 @@ void SITL::I2CRegisters_ConfigurableLength::set_register(uint8_t reg, int8_t val if (reg_data_len[reg] != 1) { AP_HAL::panic("Invalid set_register len"); } - reg_data[reg] = value; + reg_data[reg] = value << 24; } int SITL::I2CRegisters_ConfigurableLength::rdwr(I2C::i2c_rdwr_ioctl_data *&data) diff --git a/libraries/SITL/SIM_InertialLabs.cpp b/libraries/SITL/SIM_InertialLabs.cpp index edaadf0b8756d1..632254fc392fee 100644 --- a/libraries/SITL/SIM_InertialLabs.cpp +++ b/libraries/SITL/SIM_InertialLabs.cpp @@ -31,71 +31,146 @@ void InertialLabs::send_packet(void) pkt.msg_len = sizeof(pkt)-2; - pkt.accel_data_hr.x = (fdm.yAccel * 1.0e6)/GRAVITY_MSS; - pkt.accel_data_hr.y = (fdm.xAccel * 1.0e6)/GRAVITY_MSS; - pkt.accel_data_hr.z = (-fdm.zAccel * 1.0e6)/GRAVITY_MSS; + const auto gps_tow = GPS_Backend::gps_time(); - pkt.gyro_data_hr.y = fdm.rollRate*1.0e5; - pkt.gyro_data_hr.x = fdm.pitchRate*1.0e5; - pkt.gyro_data_hr.z = -fdm.yawRate*1.0e5; + // 0x01 GPS INS Time (round) + pkt.gnss_ins_time_ms = gps_tow.ms; + + // 0x23 Accelerometer data HR + pkt.accel_data_hr.x = (fdm.yAccel / GRAVITY_MSS) * 1.0e6; // g*1.0e6 + pkt.accel_data_hr.y = (fdm.xAccel / GRAVITY_MSS) * 1.0e6; // g*1.0e6 + pkt.accel_data_hr.z = (-fdm.zAccel / GRAVITY_MSS) * 1.0e6; // g*1.0e6 + + // 0x21 Gyro data HR + pkt.gyro_data_hr.y = fdm.rollRate * 1.0e5; // deg/s*1.0e5 + pkt.gyro_data_hr.x = fdm.pitchRate * 1.0e5; // deg/s*1.0e5 + pkt.gyro_data_hr.z = -fdm.yawRate * 1.0e5; // deg/s*1.0e5 + + // 0x25 Barometer data + float p, t_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(fdm.altitude+rand_float()*0.25, p, t_K); + + pkt.baro_data.pressure_pa2 = p * 0.5; // Pa/2 + pkt.baro_data.baro_alt = fdm.altitude * 100; // m + + // 0x24 Magnetometer data + pkt.mag_data.x = (fdm.bodyMagField.y / NTESLA_TO_MGAUSS) * 0.1; // nT/10 + pkt.mag_data.y = (fdm.bodyMagField.x / NTESLA_TO_MGAUSS) * 0.1; // nT/10 + pkt.mag_data.z = (-fdm.bodyMagField.z / NTESLA_TO_MGAUSS) * 0.1; // nT/10 + + // 0x07 Orientation angles + float roll_rad, pitch_rad, yaw_rad, heading_deg; + fdm.quaternion.to_euler(roll_rad, pitch_rad, yaw_rad); + heading_deg = fmodf(degrees(yaw_rad), 360.0f); + if (heading_deg < 0.0f) { + heading_deg += 360.0f; + } + pkt.orientation_angles.roll = roll_rad * RAD_TO_DEG * 100; // deg*100 + pkt.orientation_angles.pitch = pitch_rad * RAD_TO_DEG * 100; // deg*100 + pkt.orientation_angles.yaw = heading_deg * 100; // deg*100 - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere((fdm.altitude+rand_float()*0.25) * 0.001, sigma, delta, theta); - pkt.baro_data.pressure_pa2 = SSL_AIR_PRESSURE * delta * 0.5; - pkt.baro_data.baro_alt = fdm.altitude; - pkt.temperature = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + // 0x12 Velocities + pkt.velocity.x = fdm.speedE * 100; // m/s*100 + pkt.velocity.y = fdm.speedN * 100; // m/s*100 + pkt.velocity.z = -fdm.speedD * 100; // m/s*100 - pkt.mag_data.x = (fdm.bodyMagField.y / NTESLA_TO_MGAUSS)*0.1; - pkt.mag_data.y = (fdm.bodyMagField.x / NTESLA_TO_MGAUSS)*0.1; - pkt.mag_data.z = (-fdm.bodyMagField.z / NTESLA_TO_MGAUSS)*0.1; + // 0x10 Position + pkt.position.lat = fdm.latitude * 1e7; // deg*1.0e7 + pkt.position.lon = fdm.longitude * 1e7; // deg*1.0e7 + pkt.position.alt = fdm.altitude * 1e2; // m*100 - pkt.orientation_angles.roll = fdm.rollDeg*100; - pkt.orientation_angles.pitch = fdm.pitchDeg*100; - pkt.orientation_angles.yaw = fdm.yawDeg*100; + // 0x58 KF velocity covariance + pkt.kf_vel_covariance.x = 10; // mm/s + pkt.kf_vel_covariance.y = 10; // mm/s + pkt.kf_vel_covariance.z = 10; // mm/s - pkt.velocity.x = fdm.speedE*100; - pkt.velocity.y = fdm.speedN*100; - pkt.velocity.z = -fdm.speedD*100; + // 0x57 KF position covariance HR + pkt.kf_pos_covariance.x = 20; // mm + pkt.kf_pos_covariance.y = 20; // mm + pkt.kf_pos_covariance.z = 20; // mm - pkt.position.lat = fdm.latitude*1e7; - pkt.position.lon = fdm.longitude*1e7; - pkt.position.alt = fdm.altitude*1e2; + // 0x53 Unit status word (USW) + pkt.unit_status = 0; // INS data is valid - pkt.kf_vel_covariance.x = 10; - pkt.kf_vel_covariance.z = 10; - pkt.kf_vel_covariance.z = 10; + // 0x28 Differential pressure + pkt.differential_pressure = fdm.airspeed_raw_pressure[0] * 0.01 * 1.0e4; // mbar*1.0e4 (0.01 - Pa to mbar) - pkt.kf_pos_covariance.x = 20; - pkt.kf_pos_covariance.z = 20; - pkt.kf_pos_covariance.z = 20; + // 0x86 True airspeed (TAS) + pkt.true_airspeed = fdm.airspeed * 100; // m/s*100 - const auto gps_tow = GPS_Backend::gps_time(); + // 0x8A Wind speed + pkt.wind_speed.x = fdm.wind_ef.y * 100; + pkt.wind_speed.y = fdm.wind_ef.x * 100; + pkt.wind_speed.z = 0; + + // 0x8D ADU status + pkt.air_data_status = 0; // ADU data is valid + + // 0x50 Supply voltage + pkt.supply_voltage = 12.3 * 100; // VDC*100 - pkt.gps_ins_time_ms = gps_tow.ms; + // 0x52 Temperature + pkt.temperature = KELVIN_TO_C(t_K)*10; // degC + + // 0x5A Unit status word (USW2) + pkt.unit_status2 = 0; // INS data is valid + + // 0x54 INS (Navigation) solution status + pkt.ins_sol_status = 0; // INS solution is good pkt.gnss_new_data = 0; + if (packets_sent % gnss_frequency == 0) { + // 0x3C GPS week + pkt.gnss_week = gps_tow.week; - if (packets_sent % gps_frequency == 0) { - // update GPS data at 5Hz - pkt.gps_week = gps_tow.week; - pkt.gnss_pos_timestamp = gps_tow.ms; - pkt.gnss_new_data = 3; - pkt.gps_position.lat = pkt.position.lat; - pkt.gps_position.lon = pkt.position.lon; - pkt.gps_position.alt = pkt.position.alt; + // 0x4A GNSS extended info + pkt.gnss_extended_info.fix_type = 2; // 3D fix + pkt.gnss_extended_info.spoofing_status = 1; // no spoofing indicated + // 0x3B Number of satellites used in solution pkt.num_sats = 32; - pkt.gnss_vel_track.hor_speed = norm(fdm.speedN,fdm.speedE)*100; + + // 0x30 GNSS Position + pkt.gnss_position.lat = fdm.latitude * 1e7; // deg*1.0e7 + pkt.gnss_position.lon = fdm.longitude * 1e7; // deg*1.0e7 + pkt.gnss_position.alt = fdm.altitude * 1e2; // m*100 + + // 0x32 GNSS Velocity, Track over ground Vector2d track{fdm.speedN,fdm.speedE}; - pkt.gnss_vel_track.track_over_ground = wrap_360(degrees(track.angle()))*100; - pkt.gnss_vel_track.ver_speed = -fdm.speedD*100; + pkt.gnss_vel_track.hor_speed = norm(fdm.speedN,fdm.speedE) * 100; // m/s*100 + pkt.gnss_vel_track.track_over_ground = wrap_360(degrees(track.angle())) * 100; // deg*100 + pkt.gnss_vel_track.ver_speed = -fdm.speedD * 100; // m/s*100 - pkt.gnss_extended_info.fix_type = 2; - } + // 0x3E GNSS Position timestamp + pkt.gnss_pos_timestamp = gps_tow.ms; + + // 0x36 GNSS info short + pkt.gnss_info_short.info1 = 0; // 0 – Single point position + pkt.gnss_info_short.info2 = 12; // bit 2 and 3 are set (Time is fine set and is being steered) + + // 0x41 New GPS + pkt.gnss_new_data = 3; // GNSS position and velocity data update + + // 0xС0 u-blox jamming status + pkt.gnss_jam_status = 1; // ok (no significant jamming) - pkt.differential_pressure = 0.5*sq(fdm.airspeed+fabsF(rand_float()*0.25))*1.0e4; - pkt.supply_voltage = 12.3*100; - pkt.temperature = 23.4*10; + // 0x33 GNSS Heading, GNSS Pitch + pkt.gnss_angles.heading = 0; // only for dual-antenna GNSS receiver + pkt.gnss_angles.pitch = 0; // only for dual-antenna GNSS receiver + + // 0x3A GNSS Angles position type + pkt.gnss_angle_pos_type = 0; // only for dual-antenna GNSS receiver + + // 0x40 GNSS Heading timestamp + pkt.gnss_heading_timestamp = 0; // only for dual-antenna GNSS receiver + + // 0x42 Dilution of precision + pkt.gnss_dop.gdop = 1000; // *1.0e3 + pkt.gnss_dop.pdop = 1000; // *1.0e3 + pkt.gnss_dop.hdop = 1000; // *1.0e3 + pkt.gnss_dop.vdop = 1000; // *1.0e3 + pkt.gnss_dop.tdop = 1000; // *1.0e3 + } const uint8_t *buffer = (const uint8_t *)&pkt; pkt.crc = crc_sum_of_bytes_16(&buffer[2], sizeof(pkt)-4); diff --git a/libraries/SITL/SIM_InertialLabs.h b/libraries/SITL/SIM_InertialLabs.h index 448d5bf48bd192..e30054270e1188 100644 --- a/libraries/SITL/SIM_InertialLabs.h +++ b/libraries/SITL/SIM_InertialLabs.h @@ -4,7 +4,7 @@ // param set EAHRS_TYPE 5 // param set SERIAL4_PROTOCOL 36 // param set SERIAL4_BAUD 460800 -// sim_vehicle.py -v ArduPlane -D --console --map -A --uartE=sim:ILabs +// sim_vehicle.py -v ArduPlane -D --console --map -A --serial4=sim:ILabs #pragma once #include "SIM_Aircraft.h" @@ -52,19 +52,19 @@ class InertialLabs : public SerialDevice struct PACKED ILabsPacket { uint16_t magic = 0x55AA; - uint8_t msg_type = 1; + uint8_t msg_type = 0x01; uint8_t msg_id = 0x95; uint16_t msg_len; // total packet length-2 - // send Table4, 27 messages - uint8_t num_messages = 27; - uint8_t messages[27] = { + // send Table4, 32 messages + uint8_t num_messages = 32; + uint8_t messages[32] = { 0x01, 0x3C, 0x23, 0x21, 0x25, 0x24, 0x07, 0x12, 0x10, 0x58, 0x57, 0x53, 0x4a, - 0x3b, 0x30, 0x32, 0x3e, 0x36, 0x41, 0xc0, 0x28, 0x86, 0x8a, 0x8d, 0x50, - 0x52, 0x5a + 0x3b, 0x30, 0x32, 0x3e, 0x36, 0x41, 0xc0, 0x28, 0x86, 0x8a, 0x8d, 0x50, 0x52, + 0x5a, 0x33, 0x3a, 0x40, 0x42, 0x54 }; - uint32_t gps_ins_time_ms; // ms since start of GPS week for IMU data - uint16_t gps_week; + uint32_t gnss_ins_time_ms; // ms since start of GPS week for IMU data + uint16_t gnss_week; vec3_32_t accel_data_hr; // g * 1e6 vec3_32_t gyro_data_hr; // deg/s * 1e5 struct PACKED { @@ -73,7 +73,7 @@ class InertialLabs : public SerialDevice } baro_data; vec3_16_t mag_data; // nT/10 struct PACKED { - int16_t yaw; // deg*100 + uint16_t yaw; // deg*100 int16_t pitch; // deg*100 int16_t roll; // deg*100 } orientation_angles; // 321 euler order @@ -84,7 +84,7 @@ class InertialLabs : public SerialDevice int32_t alt; // m*100, AMSL } position; vec3_u8_t kf_vel_covariance; // mm/s - vec3_u16_t kf_pos_covariance; + vec3_u16_t kf_pos_covariance; // mm uint16_t unit_status; gnss_extended_info_t gnss_extended_info; uint8_t num_sats; @@ -92,7 +92,7 @@ class InertialLabs : public SerialDevice int32_t lat; // deg*1e7 int32_t lon; // deg*1e7 int32_t alt; // m*100, AMSL - } gps_position; + } gnss_position; struct PACKED { int32_t hor_speed; // m/s*100 uint16_t track_over_ground; // deg*100 @@ -109,13 +109,27 @@ class InertialLabs : public SerialDevice uint16_t supply_voltage; // V*100 int16_t temperature; // degC*10 uint16_t unit_status2; + struct PACKED { + uint16_t heading; // deg*100 + int16_t pitch; // deg*100 + } gnss_angles; + uint8_t gnss_angle_pos_type; + uint32_t gnss_heading_timestamp; // ms + struct PACKED { + uint16_t gdop; + uint16_t pdop; + uint16_t hdop; + uint16_t vdop; + uint16_t tdop; + } gnss_dop; // 10e3 + uint8_t ins_sol_status; uint16_t crc; } pkt; uint32_t last_pkt_us; const uint16_t pkt_rate_hz = 200; - const uint16_t gps_rate_hz = 10; - const uint16_t gps_frequency = pkt_rate_hz / gps_rate_hz; + const uint16_t gnss_rate_hz = 10; + const uint16_t gnss_frequency = pkt_rate_hz / gnss_rate_hz; uint32_t packets_sent; }; diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index bbb2c1a46a0f4b..ca5fa9c099f293 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -44,7 +44,7 @@ class JSBSim : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new JSBSim(frame_str); + return NEW_NOTHROW JSBSim(frame_str); } private: diff --git a/libraries/SITL/SIM_JSON.cpp b/libraries/SITL/SIM_JSON.cpp index 5c32227d5d4592..701d07621abf7d 100644 --- a/libraries/SITL/SIM_JSON.cpp +++ b/libraries/SITL/SIM_JSON.cpp @@ -323,14 +323,18 @@ void JSON::recv_fdm(const struct sitl_input &input) airspeed_pitot = state.airspeed; } else { - // velocity relative to airmass in body frame - velocity_air_bf = dcm.transposed() * velocity_ef; + + // wind is not supported yet for JSON sim, assume zero for now + wind_ef.zero(); + + // velocity relative to airmass in Earth's frame + velocity_air_ef = velocity_ef - wind_ef; - // airspeed - airspeed = velocity_air_bf.length(); + // velocity relative to airmass in body frame + velocity_air_bf = dcm.transposed() * velocity_air_ef; - // airspeed as seen by a fwd pitot tube (limited to 120m/s) - airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f); + // airspeed fix for eas2tas + update_eas_airspeed(); } // Convert from a meters from origin physics to a lat long alt diff --git a/libraries/SITL/SIM_JSON.h b/libraries/SITL/SIM_JSON.h index b168219d9d351f..048378eae69fac 100644 --- a/libraries/SITL/SIM_JSON.h +++ b/libraries/SITL/SIM_JSON.h @@ -36,7 +36,7 @@ class JSON : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new JSON(frame_str); + return NEW_NOTHROW JSON(frame_str); } /* Create and set in/out socket for JSON generic simulator */ diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index 0130a7067dc068..9b8c3b59060364 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -49,7 +49,7 @@ void JSON_Master::init(const int32_t num_slaves) } printf("Slave %u: listening on %u\n", list->instance, port); - list->next = new socket_list; + list->next = NEW_NOTHROW socket_list; list = list->next; initialized = true; diff --git a/libraries/SITL/SIM_LED_n.cpp b/libraries/SITL/SIM_LED_n.cpp new file mode 100644 index 00000000000000..df721612f79275 --- /dev/null +++ b/libraries/SITL/SIM_LED_n.cpp @@ -0,0 +1,97 @@ +#include "SIM_config.h" + +#if AP_SIM_LED_N_ENABLED + +#include "SIM_LED_n.h" + +#include + +#ifdef HAVE_SFML_GRAPHICS_H +#include +#else +#include +#endif + +#include + +template +void SIM_LED_n::update_thread(void) +{ + sf::RenderWindow *w = nullptr; + { + WITH_SEMAPHORE(AP::notify().sf_window_mutex); + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(total_width, height), name); + w->clear(sf::Color(0, 0, 0, 255)); // blacken + } + + if (w == nullptr) { + AP_HAL::panic("Unable to create SIM_LED_n window"); + } + + while (true) { + { + WITH_SEMAPHORE(AP::notify().sf_window_mutex); + sf::Event event; + while (w->pollEvent(event)) { + if (event.type == sf::Event::Closed) { + w->close(); + break; + } + } + if (!w->isOpen()) { + break; + } + if (memcmp(new_state, last_state, sizeof(new_state)) != 0) { + memcpy(last_state, new_state, sizeof(last_state)); + w->clear(sf::Color(0, 0, 0, 255)); // blacken + sf::RectangleShape rectangle(sf::Vector2f(width, height)); + for (uint8_t i=0; idraw(rectangle); + } + w->display(); + } + } + usleep(10000); + } +} + +// trampoline for update thread +template +void *SIM_LED_n::update_thread_start(void *obj) +{ + ((SIM_LED_n *)obj)->update_thread(); + return nullptr; +} + +template +void SIM_LED_n::init() +{ + pthread_create(&thread, NULL, update_thread_start, this); +} + +template class SIM_LED_n<1>; +template class SIM_LED_n<2>; +template class SIM_LED_n<3>; + +#endif // AP_SIM_LED_N_ENABLED diff --git a/libraries/SITL/SIM_LED_n.h b/libraries/SITL/SIM_LED_n.h new file mode 100644 index 00000000000000..c6f5da09b36132 --- /dev/null +++ b/libraries/SITL/SIM_LED_n.h @@ -0,0 +1,62 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_LED_N_ENABLED + +#include +#include + +/* + A class to create output of some description or another for a group + of N LEDs. + + Hopefully something visual, but perhaps just text +*/ + +template +class SIM_LED_n +{ +public: + enum class LEDColour : uint8_t { + RED, + GREEN, + BLUE, + YELLOW, + }; + + SIM_LED_n(const char *_name, const LEDColour _led_colours[NUM_LEDS]) : + name{_name} + { + memcpy(led_colours, _led_colours, sizeof(led_colours)); + } + + void set_state(const bool state[NUM_LEDS]) { + memcpy(new_state, state, sizeof(new_state)); + } + + void init(); + +private: + + const char *name; + LEDColour led_colours[NUM_LEDS]; + + static constexpr uint8_t height = 50; + static constexpr uint8_t width = height; + static constexpr uint8_t total_width = width * NUM_LEDS; + + pthread_t thread; + static void *update_thread_start(void *obj); + void update_thread(void); + + // state to be written to LEDs; note lack of thread protection. + bool new_state[NUM_LEDS]; + + // avoid too-frequent display updates: + bool last_state[NUM_LEDS]; + + const bool ON_VALUE = 0; // so if the pin is low we are lit +}; + +#endif // AP_SIM_LED_N_ENABLED diff --git a/libraries/SITL/SIM_LM2755.cpp b/libraries/SITL/SIM_LM2755.cpp index 719e5bd3922c07..f34b60789b4147 100644 --- a/libraries/SITL/SIM_LM2755.cpp +++ b/libraries/SITL/SIM_LM2755.cpp @@ -70,7 +70,7 @@ void LM2755::init() // create objects for each of the channels to handle the dynamics // of updating each. The channel gets references to the relevant // configuration bytes. - d1 = new LEDChannel( + d1 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D1_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D1_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D1_DELAY], @@ -79,7 +79,7 @@ void LM2755::init() byte[(uint8_t)LM2755DevReg::D1_RAMP_DOWN_STEP_TIME], byte[(uint8_t)LM2755DevReg::D1_TIMING] ); - d2 = new LEDChannel( + d2 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D2_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D2_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D2_DELAY], @@ -88,7 +88,7 @@ void LM2755::init() byte[(uint8_t)LM2755DevReg::D2_RAMP_DOWN_STEP_TIME], byte[(uint8_t)LM2755DevReg::D2_TIMING] ); - d3 = new LEDChannel( + d3 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D3_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D3_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D3_DELAY], diff --git a/libraries/SITL/SIM_LP5562.cpp b/libraries/SITL/SIM_LP5562.cpp index 7d0e88087a5626..feb8e7eac43a63 100644 --- a/libraries/SITL/SIM_LP5562.cpp +++ b/libraries/SITL/SIM_LP5562.cpp @@ -34,13 +34,13 @@ void LP5562::init() // currently use this device but is a structure we use elsewhere. // Note that this assumed that the LED Map register is set to its // default value. - b = new LEDChannel( + b = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::B_PWM] ); - g = new LEDChannel( + g = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::G_PWM] ); - r = new LEDChannel( + r = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::R_PWM] ); diff --git a/libraries/SITL/SIM_Loweheiser.h b/libraries/SITL/SIM_Loweheiser.h index edad99a5569426..f8b9d5d412352d 100644 --- a/libraries/SITL/SIM_Loweheiser.h +++ b/libraries/SITL/SIM_Loweheiser.h @@ -15,7 +15,7 @@ /* Simulator for the Loweheiser EFI/generator -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:loweheiser --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:loweheiser --speedup=1 --console param set SIM_EFI_TYPE 2 param set SERIAL5_PROTOCOL 2 @@ -57,7 +57,7 @@ long SET_MESSAGE_INTERVAL 225 100000 # run SITL against real generator: DEV=/dev/serial/by-id/usb-Prolific_Technology_Inc._USB-Serial_Controller-if00-port0 -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=uart:$DEV:115200 --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=uart:$DEV:115200 --speedup=1 --console # run generator test script against simulator: python ./libraries/AP_Generator/scripts/test-loweheiser.py tcp:localhost:5762 diff --git a/libraries/SITL/SIM_MS5525.cpp b/libraries/SITL/SIM_MS5525.cpp index 24e2000d52c7c5..760c4202f92a90 100644 --- a/libraries/SITL/SIM_MS5525.cpp +++ b/libraries/SITL/SIM_MS5525.cpp @@ -68,11 +68,7 @@ void MS5525::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - - // To Do: Add a sensor board temperature offset parameter - Temp_C = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + Temp_C = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); 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 a1957df17da61e..d205665d5ef888 100644 --- a/libraries/SITL/SIM_MS5611.cpp +++ b/libraries/SITL/SIM_MS5611.cpp @@ -106,15 +106,14 @@ void MS5611::check_conversion_accuracy(float P_Pa, float Temp_C, uint32_t D1, ui void MS5611::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) { - float sigma, delta, theta; - float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - P_Pa = SSL_AIR_PRESSURE * delta; + float p, T_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K); - Temp_C = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta) + AP::sitl()->temp_board_offset; + P_Pa = p; + Temp_C = KELVIN_TO_C(T_K) + AP::sitl()->temp_board_offset; // TO DO add in temperature adjustment by inheritting from AP_Baro_SITL_Generic? // AP_Baro_SITL::temperature_adjustment(P_Pa, Temp_C); diff --git a/libraries/SITL/SIM_MS5XXX.cpp b/libraries/SITL/SIM_MS5XXX.cpp index 053a832048390a..faca67f0bd7af8 100644 --- a/libraries/SITL/SIM_MS5XXX.cpp +++ b/libraries/SITL/SIM_MS5XXX.cpp @@ -58,6 +58,8 @@ void MS5XXX::convert_D2() // bug in the conversion code. The simulation can pass in // very, very low numbers. Clamp it. P_Pa = 0.1; + + // This should be a simulation error??? Pressure at 86km is 0.374Pa } uint32_t D1; diff --git a/libraries/SITL/SIM_MicroStrain.cpp b/libraries/SITL/SIM_MicroStrain.cpp index af4b2c26d6cfe6..7cbff8263cb483 100644 --- a/libraries/SITL/SIM_MicroStrain.cpp +++ b/libraries/SITL/SIM_MicroStrain.cpp @@ -25,6 +25,7 @@ */ #include "SIM_MicroStrain.h" #include +#include #include #include #include @@ -101,9 +102,9 @@ void MicroStrain::send_imu_packet(void) // Add ambient pressure field packet.payload[packet.payload_size++] = 0x06; // Ambient Pressure Field Size packet.payload[packet.payload_size++] = 0x17; // Descriptor - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(fdm.altitude * 0.001f, sigma, delta, theta); - put_float(packet, SSL_AIR_PRESSURE * delta * 0.001 + rand_float() * 0.1); + + float pressure_Pa = AP_Baro::get_pressure_for_alt_amsl(fdm.altitude); + put_float(packet, pressure_Pa*0.001 + rand_float() * 0.1); // Add scaled magnetometer field packet.payload[packet.payload_size++] = 0x0E; // Scaled Magnetometer Field Size diff --git a/libraries/SITL/SIM_MicroStrain.h b/libraries/SITL/SIM_MicroStrain.h index 80684f1ef48920..84e3b261bc1bc4 100644 --- a/libraries/SITL/SIM_MicroStrain.h +++ b/libraries/SITL/SIM_MicroStrain.h @@ -6,6 +6,7 @@ #include #include "SIM_SerialDevice.h" +#include namespace SITL { diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index c680072ca3ef7d..5d530318c4102a 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -260,7 +260,7 @@ bool Morse::parse_sensors(const char *json) bool Morse::connect_sockets(void) { if (!sensors_sock) { - sensors_sock = new SocketAPM_native(false); + sensors_sock = NEW_NOTHROW SocketAPM_native(false); if (!sensors_sock) { AP_HAL::panic("Out of memory for sensors socket"); } @@ -279,7 +279,7 @@ bool Morse::connect_sockets(void) printf("Sensors connected\n"); } if (!control_sock) { - control_sock = new SocketAPM_native(false); + control_sock = NEW_NOTHROW SocketAPM_native(false); if (!control_sock) { AP_HAL::panic("Out of memory for control socket"); } diff --git a/libraries/SITL/SIM_Morse.h b/libraries/SITL/SIM_Morse.h index 9445c26d5817a3..10cff3eea2bceb 100644 --- a/libraries/SITL/SIM_Morse.h +++ b/libraries/SITL/SIM_Morse.h @@ -43,7 +43,7 @@ class Morse : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Morse(frame_str); + return NEW_NOTHROW Morse(frame_str); } private: diff --git a/libraries/SITL/SIM_Motor.h b/libraries/SITL/SIM_Motor.h index 39745b6843a912..720bbced871099 100644 --- a/libraries/SITL/SIM_Motor.h +++ b/libraries/SITL/SIM_Motor.h @@ -46,9 +46,9 @@ class Motor { float last_roll_value, last_pitch_value; Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order) : - servo(_servo), // what servo output drives this motor angle(_angle), // angle in degrees from front yaw_factor(_yaw_factor), // positive is clockwise + servo(_servo), // what servo output drives this motor display_order(_display_order) // order for clockwise display { position.x = cosf(radians(angle)); @@ -66,9 +66,9 @@ class Motor { Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order, int8_t _roll_servo, float _roll_min, float _roll_max, int8_t _pitch_servo, float _pitch_min, float _pitch_max) : - servo(_servo), // what servo output drives this motor angle(_angle), // angle in degrees from front yaw_factor(_yaw_factor), // positive is clockwise + servo(_servo), // what servo output drives this motor display_order(_display_order), // order for clockwise display roll_servo(_roll_servo), roll_min(_roll_min), diff --git a/libraries/SITL/SIM_MotorBoat.h b/libraries/SITL/SIM_MotorBoat.h index 66d979d3342a07..66c6367d11e022 100644 --- a/libraries/SITL/SIM_MotorBoat.h +++ b/libraries/SITL/SIM_MotorBoat.h @@ -34,7 +34,7 @@ class MotorBoat : public Sailboat { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new MotorBoat(frame_str); + return NEW_NOTHROW MotorBoat(frame_str); } }; diff --git a/libraries/SITL/SIM_Multicopter.cpp b/libraries/SITL/SIM_Multicopter.cpp index a834cc6f8567db..4e019dde9b4de4 100644 --- a/libraries/SITL/SIM_Multicopter.cpp +++ b/libraries/SITL/SIM_Multicopter.cpp @@ -48,6 +48,11 @@ void MultiCopter::calculate_forces(const struct sitl_input &input, Vector3f &rot add_shove_forces(rot_accel, body_accel); add_twist_forces(rot_accel); + +#if AP_SIM_SLUNGPAYLOAD_ENABLED + // add forces from slung payload + add_slungpayload_forces(body_accel); +#endif } /* @@ -61,6 +66,11 @@ void MultiCopter::update(const struct sitl_input &input) Vector3f rot_accel; calculate_forces(input, rot_accel, accel_body); + // simulated clamp holding vehicle down + if (clamp.clamped(*this, input)) { + rot_accel.zero(); + accel_body.zero(); + } // estimate voltage and current frame->current_and_voltage(battery_voltage, battery_current); diff --git a/libraries/SITL/SIM_Multicopter.h b/libraries/SITL/SIM_Multicopter.h index fa9a869358ac32..289aac318290f0 100644 --- a/libraries/SITL/SIM_Multicopter.h +++ b/libraries/SITL/SIM_Multicopter.h @@ -36,7 +36,7 @@ class MultiCopter : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new MultiCopter(frame_str); + return NEW_NOTHROW MultiCopter(frame_str); } protected: diff --git a/libraries/SITL/SIM_NoVehicle.h b/libraries/SITL/SIM_NoVehicle.h index 0d37392b0f9aed..3482a1ee9d0d85 100644 --- a/libraries/SITL/SIM_NoVehicle.h +++ b/libraries/SITL/SIM_NoVehicle.h @@ -33,7 +33,7 @@ class NoVehicle : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new NoVehicle(frame_str); + return NEW_NOTHROW NoVehicle(frame_str); } }; diff --git a/libraries/SITL/SIM_PS_LightWare_SF45B.h b/libraries/SITL/SIM_PS_LightWare_SF45B.h index 16fd9955734efd..2d0404b61e8b2c 100644 --- a/libraries/SITL/SIM_PS_LightWare_SF45B.h +++ b/libraries/SITL/SIM_PS_LightWare_SF45B.h @@ -71,8 +71,8 @@ class PS_LightWare_SF45B : public PS_LightWare { class PACKED PackedMessage { public: PackedMessage(T _msg, uint16_t _flags) : - msg(_msg), - flags(_flags) + flags(_flags), + msg(_msg) { flags |= (sizeof(T)) << 6; } diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index 8dbdfc6fc4a872..82aa8c659d9ee4 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -80,6 +80,9 @@ Plane::Plane(const char *frame_str) : ground_behavior = GROUND_BEHAVIOR_TAILSITTER; thrust_scale *= 1.5; } + if (strstr(frame_str, "-steering")) { + have_steering = true; + } #if AP_FILESYSTEM_FILE_READING_ENABLED if (strstr(frame_str, "-3d")) { @@ -395,6 +398,18 @@ void Plane::update(const struct sitl_input &input) calculate_forces(input, rot_accel); update_dynamics(rot_accel); + + /* + add in ground steering, this should be replaced with a proper + calculation of a nose wheel effect + */ + if (have_steering && on_ground()) { + const float steering = filtered_servo_angle(input, 4); + const Vector3f velocity_bf = dcm.transposed() * velocity_ef; + const float steer_scale = radians(5); + gyro.z += steering * velocity_bf.x * steer_scale; + } + update_external_payload(input); // update lat/lon/altitude diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index 53bb998e461cd6..2a49de12bea9fa 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -36,12 +36,11 @@ class Plane : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Plane(frame_str); + return NEW_NOTHROW Plane(frame_str); } protected: const float hover_throttle = 0.7f; - const float air_density = 1.225; // kg/m^3 at sea level, ISA conditions float angle_of_attack; float beta; @@ -102,6 +101,7 @@ class Plane : public Aircraft { bool aerobatic; bool copter_tailsitter; bool have_launcher; + bool have_steering; float launch_accel; float launch_time; uint64_t launch_start_ms; diff --git a/libraries/SITL/SIM_Precland.cpp b/libraries/SITL/SIM_Precland.cpp index 50af3960cdf5bb..a4d97022466d6c 100644 --- a/libraries/SITL/SIM_Precland.cpp +++ b/libraries/SITL/SIM_Precland.cpp @@ -85,7 +85,7 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = { // @User: Advanced AP_GROUPINFO("TYPE", 6, SIM_Precland, _type, SIM_Precland::PRECLAND_TYPE_CYLINDER), - // @Param: ALT_LIMIT + // @Param: ALT_LMT // @DisplayName: Precland device alt range // @Description: Precland device maximum range altitude // @Units: m @@ -93,7 +93,7 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = { // @User: Advanced AP_GROUPINFO("ALT_LMT", 7, SIM_Precland, _alt_limit, 15), - // @Param: DIST_LIMIT + // @Param: DIST_LMT // @DisplayName: Precland device lateral range // @Description: Precland device maximum lateral range // @Units: m @@ -150,7 +150,7 @@ void SIM_Precland::update(const Location &loc) */ auto *sitl = AP::sitl(); Location shiploc; - if (sitl != nullptr && sitl->shipsim.get_location(shiploc) && !shiploc.is_zero()) { + if (sitl != nullptr && sitl->models.shipsim.get_location(shiploc) && !shiploc.is_zero()) { shiploc.change_alt_frame(Location::AltFrame::ABOVE_ORIGIN); device_center = shiploc; } diff --git a/libraries/SITL/SIM_QuadPlane.h b/libraries/SITL/SIM_QuadPlane.h index f111b4040cefca..1915e5aa97c090 100644 --- a/libraries/SITL/SIM_QuadPlane.h +++ b/libraries/SITL/SIM_QuadPlane.h @@ -36,7 +36,7 @@ class QuadPlane : public Plane { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new QuadPlane(frame_str); + return NEW_NOTHROW QuadPlane(frame_str); } private: diff --git a/libraries/SITL/SIM_RF_LightWareSerial.cpp b/libraries/SITL/SIM_RF_LightWareSerial.cpp index bf44e4080663a9..fefa21c4ba54bf 100644 --- a/libraries/SITL/SIM_RF_LightWareSerial.cpp +++ b/libraries/SITL/SIM_RF_LightWareSerial.cpp @@ -55,5 +55,5 @@ uint32_t RF_LightWareSerial::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, ui alt_cm = 13000; // from datasheet } - return snprintf((char*)buffer, buflen, "%0.2f\r", alt_cm / 100.0f); // note tragic lack of snprintf return checking + return snprintf((char*)buffer, buflen, "%0.2f\r", alt_cm * 0.01f); // note tragic lack of snprintf return checking } diff --git a/libraries/SITL/SIM_RF_NMEA.cpp b/libraries/SITL/SIM_RF_NMEA.cpp index 6f5f1aceffb32e..4da7a2769d7e49 100644 --- a/libraries/SITL/SIM_RF_NMEA.cpp +++ b/libraries/SITL/SIM_RF_NMEA.cpp @@ -30,7 +30,7 @@ uint32_t RF_NMEA::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t bufle // Format 2 DBT NMEA mode (e.g. $SMDBT,5.94,f,1.81,M,67) // Format 3 DPT NMEA mode (e.g. $SMDPT,1.81,0.066) - ssize_t ret = snprintf((char*)buffer, buflen, "$SMDPT,%f,%f", alt_cm/100.0f, 0.01f); + ssize_t ret = snprintf((char*)buffer, buflen, "$SMDPT,%f,%f", alt_cm*0.01f, 0.01f); uint8_t checksum = 0; for (uint8_t i=1; i' offs += 1; // for space strncpy(string_configs[i].value, &_buffer[offs], MIN(ARRAY_SIZE(config.format), unsigned(cr - _buffer - offs - 1))); // -1 for the lf, -1 for the cr -// gcs().send_text(MAV_SEVERITY_INFO, "Wasp: config (%s) (%s)", string_configs[i].name, string_configs[i].value); +// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Wasp: config (%s) (%s)", string_configs[i].name, string_configs[i].value); char response[128]; const size_t x = snprintf(response, ARRAY_SIZE(response), @@ -80,7 +80,7 @@ void RF_Wasp::check_configuration() char tmp[32]{}; strncpy(tmp, &_buffer[offs], MIN(ARRAY_SIZE(config.format), unsigned(cr - _buffer - offs - 1))); // -1 for the lf, -1 for the cr *(integer_configs[i].value) = atoi(tmp); -// gcs().send_text(MAV_SEVERITY_INFO, "Wasp: config (%s) (%d)", integer_configs[i].name, *(integer_configs[i].value)); +// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Wasp: config (%s) (%d)", integer_configs[i].name, *(integer_configs[i].value)); char response[128]; const size_t x = snprintf(response, ARRAY_SIZE(response), @@ -113,5 +113,5 @@ void RF_Wasp::update(float range) uint32_t RF_Wasp::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) { - return snprintf((char*)buffer, buflen, "%f\n", alt_cm/100.0f); + return snprintf((char*)buffer, buflen, "%f\n", alt_cm*0.01f); } diff --git a/libraries/SITL/SIM_RGBLED.cpp b/libraries/SITL/SIM_RGBLED.cpp index 6e64c47c4b9281..a36ee06e064322 100644 --- a/libraries/SITL/SIM_RGBLED.cpp +++ b/libraries/SITL/SIM_RGBLED.cpp @@ -17,7 +17,7 @@ void SIM_RGBLED::update_thread(void) sf::RenderWindow *w = nullptr; { WITH_SEMAPHORE(AP::notify().sf_window_mutex); - w = new sf::RenderWindow(sf::VideoMode(width, height), name); + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(width, height), name); } if (w == nullptr) { diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index c1a7afb608f445..3182700dd9ad04 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -21,6 +21,8 @@ #include #include +#include + namespace SITL { SimRover::SimRover(const char *frame_str) : @@ -41,10 +43,14 @@ SimRover::SimRover(const char *frame_str) : if (vectored_thrust) { printf("Vectored Thrust Rover Simulation Started\n"); } - lock_step_scheduled = true; -} + omni3 = strstr(frame_str, "omni3mecanum") != nullptr; + if (omni3) { + printf("Omni3 Mecanum Rover Simulation Started\n"); + } + lock_step_scheduled = true; +} /* return turning circle (diameter) in meters for steering angle proportion in degrees @@ -92,6 +98,50 @@ float SimRover::calc_lat_accel(float steering_angle, float speed) update the rover simulation by one time step */ void SimRover::update(const struct sitl_input &input) +{ + // how much time has passed? + float delta_time = frame_time_us * 1.0e-6f; + + // update gyro and accel_body according to frame type + if (omni3) { + update_omni3(input, delta_time); + } else { + update_ackermann_or_skid(input, delta_time); + } + + // common to all rovers + + // now in earth frame + Vector3f accel_earth = dcm * accel_body; + accel_earth += Vector3f(0, 0, GRAVITY_MSS); + + // we are on the ground, so our vertical accel is zero + accel_earth.z = 0; + + // work out acceleration as seen by the accelerometers. It sees the kinematic + // acceleration (ie. real movement), plus gravity + accel_body = dcm.transposed() * (accel_earth + Vector3f(0, 0, -GRAVITY_MSS)); + + // new velocity vector + velocity_ef += accel_earth * delta_time; + + // new position vector + position += (velocity_ef * delta_time).todouble(); + + update_external_payload(input); + + // update lat/lon/altitude + update_position(); + time_advance(); + + // update magnetic field + update_mag_field_bf(); +} + +/* + update the ackermann or skid rover simulation by one time step + */ +void SimRover::update_ackermann_or_skid(const struct sitl_input &input, float delta_time) { float steering, throttle; @@ -113,9 +163,6 @@ void SimRover::update(const struct sitl_input &input) } } - // how much time has passed? - float delta_time = frame_time_us * 1.0e-6f; - // speed in m/s in body frame Vector3f velocity_body = dcm.transposed() * velocity_ef; @@ -137,37 +184,80 @@ void SimRover::update(const struct sitl_input &input) dcm.rotate(gyro * delta_time); dcm.normalize(); - // accel in body frame due to motor + // accel in body frame due to motor (excluding gravity) accel_body = Vector3f(accel, 0, 0); // add in accel due to direction change accel_body.y += radians(yaw_rate) * speed; +} - // now in earth frame - Vector3f accel_earth = dcm * accel_body; - accel_earth += Vector3f(0, 0, GRAVITY_MSS); - - // we are on the ground, so our vertical accel is zero - accel_earth.z = 0; - - // work out acceleration as seen by the accelerometers. It sees the kinematic - // acceleration (ie. real movement), plus gravity - accel_body = dcm.transposed() * (accel_earth + Vector3f(0, 0, -GRAVITY_MSS)); +/* + update the omni3 rover simulation by one time step + */ +void SimRover::update_omni3(const struct sitl_input &input, float delta_time) +{ + // in omni3 mode the first three servos are motor speeds + float motor1 = 2*((input.servos[0]-1000)/1000.0f - 0.5f); + float motor2 = 2*((input.servos[1]-1000)/1000.0f - 0.5f); + float motor3 = 2*((input.servos[2]-1000)/1000.0f - 0.5f); + + // use forward kinematics to calculate body frame velocity + Vector3f wheel_ang_vel( + motor1 * omni3_wheel_max_ang_vel, + motor2 * omni3_wheel_max_ang_vel, + motor3 * omni3_wheel_max_ang_vel + ); + + // derivation of forward kinematics for an Omni3Mecanum rover + // A. Gfrerrer. "Geometry and kinematics of the Mecanum wheel", + // Computer Aided Geometric Design 25 (2008) 784–791. + // Retrieved from https://www.geometrie.tugraz.at/gfrerrer/publications/MecanumWheel.pdf. + // + // the frame is equilateral triangle + // + // d[i] = 0.18 m is distance from frame centre to each wheel + // r_w = 0.04725 m is the wheel radius. + // delta = radians(-45) is angle of the roller to the direction of forward rotation + // alpha[i] is the angle the wheel axis is rotated about the body z-axis + // c[i] = cos(alpha[i] + delta) + // s[i] = sin(alpha[i] + delta) + // + // wheel d[i] alpha[i] a_x[i] a_y[i] c[i] s[i] + // 1 0.18 1.04719 0.09 0.15588 0.965925 0.258819 + // 2 0.18 3.14159 -0.18 0.0 -0.707106 0.707106 + // 3 0.18 5.23598 0.09 -0.15588 -0.258819 -0.965925 + // + // k = 1/(r_w * sin(delta)) = -29.930445 is a scale factor + // + // inverse kinematic matrix + // M[i, 0] = k * c[i] + // M[i, 1] = k * s[i] + // M[i, 2] = k * (a_x[i] s[i] - a_y[i] c[i]) + // + // forward kinematics matrix: Minv = M^-1 + constexpr Matrix3f Minv( + -0.0215149, 0.01575, 0.0057649, + -0.0057649, -0.01575, 0.0215149, + 0.0875, 0.0875, 0.0875); + + // twist - this is the target linear and angular velocity + Vector3f twist = Minv * wheel_ang_vel; - // new velocity vector - velocity_ef += accel_earth * delta_time; + // speed in m/s in body frame + Vector3f velocity_body = dcm.transposed() * velocity_ef; - // new position vector - position += (velocity_ef * delta_time).todouble(); + // linear acceleration in m/s/s - very crude model + float accel_x = omni3_max_accel * (twist.x - velocity_body.x) / omni3_max_speed; + float accel_y = omni3_max_accel * (twist.y - velocity_body.y) / omni3_max_speed; - update_external_payload(input); + gyro = Vector3f(0, 0, twist.z); - // update lat/lon/altitude - update_position(); - time_advance(); + // update attitude + dcm.rotate(gyro * delta_time); + dcm.normalize(); - // update magnetic field - update_mag_field_bf(); + // accel in body frame due to motors (excluding gravity) + accel_body = Vector3f(accel_x, accel_y, 0); } } // namespace SITL diff --git a/libraries/SITL/SIM_Rover.h b/libraries/SITL/SIM_Rover.h index ede3b3a732bd88..113bc55dfc1a82 100644 --- a/libraries/SITL/SIM_Rover.h +++ b/libraries/SITL/SIM_Rover.h @@ -34,7 +34,7 @@ class SimRover : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new SimRover(frame_str); + return NEW_NOTHROW SimRover(frame_str); } private: @@ -51,6 +51,15 @@ class SimRover : public Aircraft { float vectored_angle_max = 90.0f; // maximum angle (in degrees) to which thrust can be turned float vectored_turn_rate_max = 90.0f; // maximum turn rate (in deg/sec) with full throttle angled at 90deg + // omni3 Mecanum related members + bool omni3; // true if vehicle is omni-directional with 3 Mecanum wheels + float omni3_max_speed = 2.3625f; // omni vehicle's maximum forward speed in m/s + float omni3_max_accel = 1.0f; // omni vehicle's maximum forward acceleration in m/s/s + float omni3_wheel_max_ang_vel = 50.0f; // omni vehicle's wheel maximum angular velocity in rad/s + + void update_ackermann_or_skid(const struct sitl_input &input, float delta_time); + void update_omni3(const struct sitl_input &input, float delta_time); + float turn_circle(float steering) const; float calc_yaw_rate(float steering, float speed); float calc_lat_accel(float steering_angle, float speed); diff --git a/libraries/SITL/SIM_Sailboat.cpp b/libraries/SITL/SIM_Sailboat.cpp index 7d3dba67457ad1..a22d8c7df3fbf4 100644 --- a/libraries/SITL/SIM_Sailboat.cpp +++ b/libraries/SITL/SIM_Sailboat.cpp @@ -32,6 +32,8 @@ namespace SITL { #define STEERING_SERVO_CH 0 // steering controlled by servo output 1 #define MAINSAIL_SERVO_CH 3 // main sail controlled by servo output 4 #define THROTTLE_SERVO_CH 2 // throttle controlled by servo output 3 +#define MOTORLEFT_SERVO_CH 0 // skid-steering left motor controlled by servo output 1 +#define MOTORRIGHT_SERVO_CH 2 // skid-steering right motor controlled by servo output 3 #define DIRECT_WING_SERVO_CH 4 // very roughly sort of a stability factors for waves @@ -40,11 +42,12 @@ namespace SITL { Sailboat::Sailboat(const char *frame_str) : Aircraft(frame_str), + sail_area(1.0), steering_angle_max(35), - turning_circle(1.8), - sail_area(1.0) + turning_circle(1.8) { motor_connected = (strcmp(frame_str, "sailboat-motor") == 0); + skid_steering = strstr(frame_str, "skid") != nullptr; lock_step_scheduled = true; } @@ -97,13 +100,19 @@ float Sailboat::get_turn_circle(float steering) const // return yaw rate in deg/sec given a steering input (in the range -1 to +1) and speed in m/s float Sailboat::get_yaw_rate(float steering, float speed) const { - if (is_zero(steering) || is_zero(speed)) { - return 0; + float rate = 0.0f; + if (is_zero(steering) || (!skid_steering && is_zero(speed))) { + return rate; + } + + if (is_zero(speed) && skid_steering) { + rate = steering * M_PI * 5; + } else { + float d = get_turn_circle(steering); + float c = M_PI * d; + float t = c / speed; + rate = 360.0f / t; } - float d = get_turn_circle(steering); - float c = M_PI * d; - float t = c / speed; - float rate = 360.0f / t; return rate; } @@ -179,7 +188,14 @@ void Sailboat::update(const struct sitl_input &input) update_wind(input); // in sailboats the steering controls the rudder, the throttle controls the main sail position - float steering = 2*((input.servos[STEERING_SERVO_CH]-1000)/1000.0f - 0.5f); + float steering = 0.0f; + if (skid_steering) { + float steering_left = 2.0f*((input.servos[MOTORLEFT_SERVO_CH]-1000)/1000.0f - 0.5f); + float steering_right = 2.0f*((input.servos[MOTORRIGHT_SERVO_CH]-1000)/1000.0f - 0.5f); + steering = steering_left - steering_right; + } else { + steering = 2*((input.servos[STEERING_SERVO_CH]-1000)/1000.0f - 0.5f); + } // calculate apparent wind in earth-frame (this is the direction the wind is coming from) // Note than the SITL wind direction is defined as the direction the wind is travelling to @@ -257,8 +273,14 @@ void Sailboat::update(const struct sitl_input &input) // gives throttle force == hull drag at 10m/s float throttle_force = 0.0f; if (motor_connected) { - const uint16_t throttle_out = constrain_int16(input.servos[THROTTLE_SERVO_CH], 1000, 2000); - throttle_force = (throttle_out-1500) * 0.1f; + if (skid_steering) { + const uint16_t throttle_left = constrain_int16(input.servos[MOTORLEFT_SERVO_CH], 1000, 2000); + const uint16_t throttle_right = constrain_int16(input.servos[MOTORRIGHT_SERVO_CH], 1000, 2000); + throttle_force = (0.5f*(throttle_left + throttle_right)-1500) * 0.1f; + } else { + const uint16_t throttle_out = constrain_int16(input.servos[THROTTLE_SERVO_CH], 1000, 2000); + throttle_force = (throttle_out-1500) * 0.1f; + } } // accel in body frame due acceleration from sail and deceleration from hull friction diff --git a/libraries/SITL/SIM_Sailboat.h b/libraries/SITL/SIM_Sailboat.h index 62d0b3781d7cd6..e17d2c05dcd424 100644 --- a/libraries/SITL/SIM_Sailboat.h +++ b/libraries/SITL/SIM_Sailboat.h @@ -34,13 +34,14 @@ class Sailboat : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Sailboat(frame_str); + return NEW_NOTHROW Sailboat(frame_str); } bool on_ground() const override {return true;}; protected: bool motor_connected; // true if this frame has a motor + bool skid_steering; // true if this vehicle is a skid-steering vehicle float sail_area; // 1.0 for normal area private: diff --git a/libraries/SITL/SIM_Scrimmage.cpp b/libraries/SITL/SIM_Scrimmage.cpp index e4d91548ac34f3..9af2b7999194c5 100644 --- a/libraries/SITL/SIM_Scrimmage.cpp +++ b/libraries/SITL/SIM_Scrimmage.cpp @@ -106,7 +106,7 @@ void Scrimmage::recv_fdm(const struct sitl_input &input) // velocity relative to air mass, in earth frame TODO - velocity_air_ef = velocity_ef; + velocity_air_ef = velocity_ef - wind_ef; // velocity relative to airmass in body frame TODO velocity_air_bf = dcm.transposed() * velocity_air_ef; diff --git a/libraries/SITL/SIM_Scrimmage.h b/libraries/SITL/SIM_Scrimmage.h index 2fa8dfcbaf3ddd..c7bfbd972bd197 100644 --- a/libraries/SITL/SIM_Scrimmage.h +++ b/libraries/SITL/SIM_Scrimmage.h @@ -46,7 +46,7 @@ class Scrimmage : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Scrimmage(frame_str); + return NEW_NOTHROW Scrimmage(frame_str); } /* Create and set in/out socket for extenal simulator */ diff --git a/libraries/SITL/SIM_SerialDevice.cpp b/libraries/SITL/SIM_SerialDevice.cpp index 19065b7152de62..fe5943d5dee1d0 100644 --- a/libraries/SITL/SIM_SerialDevice.cpp +++ b/libraries/SITL/SIM_SerialDevice.cpp @@ -29,8 +29,8 @@ using namespace SITL; SerialDevice::SerialDevice(uint16_t tx_bufsize, uint16_t rx_bufsize) { - to_autopilot = new ByteBuffer{tx_bufsize}; - from_autopilot = new ByteBuffer{rx_bufsize}; + to_autopilot = NEW_NOTHROW ByteBuffer{tx_bufsize}; + from_autopilot = NEW_NOTHROW ByteBuffer{rx_bufsize}; } bool SerialDevice::init_sitl_pointer() diff --git a/libraries/SITL/SIM_SilentWings.cpp b/libraries/SITL/SIM_SilentWings.cpp index 424108e5ffa656..4ebba41e0c7f18 100644 --- a/libraries/SITL/SIM_SilentWings.cpp +++ b/libraries/SITL/SIM_SilentWings.cpp @@ -57,10 +57,10 @@ SilentWings::SilentWings(const char *frame_str) : Aircraft(frame_str), last_data_time_ms(0), first_pkt_timestamp_ms(0), + inited_first_pkt_timestamp(false), time_base_us(0), sock(true), - home_initialized(false), - inited_first_pkt_timestamp(false) + home_initialized(false) { // Force ArduPlane to use sensor data from SilentWings as the actual state, // without using EKF, i.e., using "fake EKF (type 10)". Disable gyro calibration. diff --git a/libraries/SITL/SIM_SilentWings.h b/libraries/SITL/SIM_SilentWings.h index 75fdd3984fff32..161597eb49aa36 100644 --- a/libraries/SITL/SIM_SilentWings.h +++ b/libraries/SITL/SIM_SilentWings.h @@ -41,7 +41,7 @@ class SilentWings : public Aircraft { /* Static object creator */ static Aircraft *create(const char *frame_str) { - return new SilentWings(frame_str); + return NEW_NOTHROW SilentWings(frame_str); } private: diff --git a/libraries/SITL/SIM_SingleCopter.cpp b/libraries/SITL/SIM_SingleCopter.cpp index d12699c4b8ffce..dc6bd719f4c291 100644 --- a/libraries/SITL/SIM_SingleCopter.cpp +++ b/libraries/SITL/SIM_SingleCopter.cpp @@ -90,7 +90,7 @@ void SingleCopter::update(const struct sitl_input &input) rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate; // air resistance - Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity); + Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity) / eas2tas; // scale thrust to newtons thrust *= thrust_scale; diff --git a/libraries/SITL/SIM_SingleCopter.h b/libraries/SITL/SIM_SingleCopter.h index 1ab8fb202711df..a7ace87fd5a638 100644 --- a/libraries/SITL/SIM_SingleCopter.h +++ b/libraries/SITL/SIM_SingleCopter.h @@ -35,7 +35,7 @@ class SingleCopter : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new SingleCopter(frame_str); + return NEW_NOTHROW SingleCopter(frame_str); } private: diff --git a/libraries/SITL/SIM_SlungPayload.cpp b/libraries/SITL/SIM_SlungPayload.cpp new file mode 100644 index 00000000000000..f761185853688d --- /dev/null +++ b/libraries/SITL/SIM_SlungPayload.cpp @@ -0,0 +1,463 @@ +/* + 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 . + */ +/* + simulate a slung payload +*/ + +#include "SIM_config.h" + +#if AP_SIM_SLUNGPAYLOAD_ENABLED + +#include "SIM_SlungPayload.h" +#include "SITL.h" +#include +#include "SIM_Aircraft.h" +#include +#include +#include + +using namespace SITL; + +// SlungPayloadSim parameters +const AP_Param::GroupInfo SlungPayloadSim::var_info[] = { + // @Param: ENABLE + // @DisplayName: Slung Payload Sim enable/disable + // @Description: Slung Payload Sim enable/disable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLE", 1, SlungPayloadSim, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: WEIGHT + // @DisplayName: Slung Payload weight + // @Description: Slung Payload weight in kg + // @Units: kg + // @Range: 0 15 + // @User: Advanced + AP_GROUPINFO("WEIGHT", 2, SlungPayloadSim, weight_kg, 1.0), + + // @Param: LINELEN + // @DisplayName: Slung Payload line length + // @Description: Slung Payload line length in meters + // @Units: m + // @Range: 0 100 + // @User: Advanced + AP_GROUPINFO("LINELEN", 3, SlungPayloadSim, line_length, 30.0), + + // @Param: DRAG + // @DisplayName: Slung Payload drag coefficient + // @Description: Slung Payload drag coefficient. Higher values increase drag and slow the payload more quickly + // @Units: m + // @Range: 0 10 + // @User: Advanced + AP_GROUPINFO("DRAG", 4, SlungPayloadSim, drag_coef, 1), + + // @Param: SYSID + // @DisplayName: Slung Payload MAVLink system ID + // @Description: Slung Payload MAVLink system id to distinguish it from others on the same network + // @Range: 0 255 + // @User: Advanced + AP_GROUPINFO("SYSID", 5, SlungPayloadSim, sys_id, 2), + + AP_GROUPEND +}; + +// SlungPayloadSim handles interaction with main vehicle +SlungPayloadSim::SlungPayloadSim() +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// update the SlungPayloadSim's state using the vehicle's earth-frame position, velocity, acceleration and wind +void SlungPayloadSim::update(const Vector3p& veh_pos, const Vector3f& veh_vel_ef, const Vector3f& veh_accel_ef, const Vector3f& wind_ef) +{ + if (!enable) { + return; + } + + // initialise slung payload location + const uint32_t now_us = AP_HAL::micros(); + if (!initialised) { + // capture EKF origin + auto *sitl = AP::sitl(); + const Location ekf_origin = sitl->state.home; + if (ekf_origin.lat == 0 && ekf_origin.lng == 0) { + return; + } + + // more initialisation + last_update_us = now_us; + initialised = true; + } + + // calculate dt and update slung payload + const float dt = (now_us - last_update_us)*1.0e-6; + last_update_us = now_us; + update_payload(veh_pos, veh_vel_ef, veh_accel_ef, wind_ef, dt); + + // send payload location to GCS at 5hz + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_report_ms >= reporting_period_ms) { + last_report_ms = now_ms; + send_report(); + write_log(); + } +} + +// get earth-frame forces on the vehicle from slung payload +// returns true on success and fills in forces_ef argument, false on failure +bool SlungPayloadSim::get_forces_on_vehicle(Vector3f& forces_ef) const +{ + if (!enable) { + return false; + } + + forces_ef = veh_forces_ef; + return true; +} + +// send a report to the vehicle control code over MAVLink +void SlungPayloadSim::send_report(void) +{ + if (!mavlink_connected && mav_socket.connect(target_address, target_port)) { + ::printf("SlungPayloadSim connected to %s:%u\n", target_address, (unsigned)target_port); + mavlink_connected = true; + } + if (!mavlink_connected) { + return; + } + + // get current time + uint32_t now_ms = AP_HAL::millis(); + + // send heartbeat at 1hz + const uint8_t component_id = MAV_COMP_ID_USER11; + if (now_ms - last_heartbeat_ms >= 1000) { + last_heartbeat_ms = now_ms; + + const mavlink_heartbeat_t heartbeat{ + custom_mode: 0, + type : MAV_TYPE_AIRSHIP, + autopilot : MAV_AUTOPILOT_INVALID, + base_mode: 0, + system_status: 0, + mavlink_version: 0, + }; + + mavlink_message_t msg; + mavlink_msg_heartbeat_encode_status( + sys_id.get(), + component_id, + &mav_status, + &msg, + &heartbeat); + uint8_t buf[300]; + const uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + mav_socket.send(buf, len); + } + + // send a GLOBAL_POSITION_INT messages + { + Location payload_loc; + int32_t alt_amsl_cm, alt_rel_cm; + if (!get_payload_location(payload_loc) || + !payload_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_amsl_cm) || + !payload_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_rel_cm)) { + return; + } + const mavlink_global_position_int_t global_position_int{ + time_boot_ms: now_ms, + lat: payload_loc.lat, + lon: payload_loc.lng, + alt: alt_amsl_cm * 10, // amsl alt in mm + relative_alt: alt_rel_cm * 10, // relative alt in mm + vx: int16_t(velocity_NED.x * 100), // velocity in cm/s + vy: int16_t(velocity_NED.y * 100), // velocity in cm/s + vz: int16_t(velocity_NED.z * 100), // velocity in cm/s + hdg: 0 // heading in centi-degrees + }; + mavlink_message_t msg; + mavlink_msg_global_position_int_encode_status(sys_id, component_id, &mav_status, &msg, &global_position_int); + uint8_t buf[300]; + const uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + if (len > 0) { + mav_socket.send(buf, len); + } + } + + // send ATTITUDE so MissionPlanner can display orientation + { + const mavlink_attitude_t attitude{ + time_boot_ms: now_ms, + roll: 0, + pitch: 0, + yaw: 0, // heading in radians + rollspeed: 0, + pitchspeed: 0, + yawspeed: 0 + }; + mavlink_message_t msg; + mavlink_msg_attitude_encode_status( + sys_id, + component_id, + &mav_status, + &msg, + &attitude); + uint8_t buf[300]; + const uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + if (len > 0) { + mav_socket.send(buf, len); + } + } +} + +// write onboard log +void SlungPayloadSim::write_log() +{ +#if HAL_LOGGING_ENABLED + // write log of slung payload state + // @LoggerMessage: SLUP + // @Description: Slung payload + // @Field: TimeUS: Time since system startup + // @Field: Land: 1 if payload is landed, 0 otherwise + // @Field: Tens: Tension ratio, 1 if line is taut, 0 if slack + // @Field: Len: Line length + // @Field: PN: Payload position as offset from vehicle in North direction + // @Field: PE: Payload position as offset from vehicle in East direction + // @Field: PD: Payload position as offset from vehicle in Down direction + // @Field: VN: Payload velocity in North direction + // @Field: VE: Payload velocity in East direction + // @Field: VD: Payload velocity in Down direction + // @Field: AN: Payload acceleration in North direction + // @Field: AE: Payload acceleration in East direction + // @Field: AD: Payload acceleration in Down direction + // @Field: VFN: Force on vehicle in North direction + // @Field: VFE: Force on vehicle in East direction + // @Field: VFD: Force on vehicle in Down direction + AP::logger().WriteStreaming("SLUP", + "TimeUS,Land,Tens,Len,PN,PE,PD,VN,VE,VD,AN,AE,AD,VFN,VFE,VFD", // labels + "s-%mmmmnnnooo---", // units + "F-20000000000000", // multipliers + "Qbffffffffffffff", // format + AP_HAL::micros64(), + (uint8_t)landed, + (float)tension_ratio, + (float)payload_to_veh.length(), + (double)-payload_to_veh.x, + (double)-payload_to_veh.y, + (double)-payload_to_veh.z, + (double)velocity_NED.x, + (double)velocity_NED.y, + (double)velocity_NED.z, + (double)accel_NED.x, + (double)accel_NED.y, + (double)accel_NED.z, + (double)veh_forces_ef.x, + (double)veh_forces_ef.y, + (double)veh_forces_ef.z); +#endif +} + +// returns true on success and fills in payload_loc argument, false on failure +bool SlungPayloadSim::get_payload_location(Location& payload_loc) const +{ + // get EKF origin + auto *sitl = AP::sitl(); + if (sitl == nullptr) { + return false; + } + const Location ekf_origin = sitl->state.home; + if (ekf_origin.lat == 0 && ekf_origin.lng == 0) { + return false; + } + + // calculate location + payload_loc = ekf_origin; + payload_loc.offset(position_NED); + return true; +} + +// update the slung payloads position, velocity, acceleration +// vehicle position, velocity, acceleration and wind should be in earth-frame NED frame +void SlungPayloadSim::update_payload(const Vector3p& veh_pos, const Vector3f& veh_vel_ef, const Vector3f& veh_accel_ef, + const Vector3f& wind_ef, float dt) +{ + // how we calculate the payload's position, velocity and acceleration + // 1. update the payload's position, velocity using the previous iterations acceleration + // 2. check that the payload does not fall below the terrain + // 3. check if the line is taught and that the payload does not move more than the line length from the vehicle + // 4. calculate gravity and drag forces on the payload + // 5. calculate the tension force between the payload and vehicle including force countering gravity, drag and centripetal force + // 6. update the payload's acceleration using the sum of the above forces + + // initialise position_NED from vehicle position + if (position_NED.is_zero()) { + if (!veh_pos.is_zero()) { + position_NED = veh_pos; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SlungPayload: initialised at %f %f %f", position_NED.x, position_NED.y, position_NED.z); + } + return; + } + + // integrate previous iterations acceleration into velocity and position + velocity_NED += accel_NED * dt; + position_NED += (velocity_NED * dt).todouble(); + + // calculate distance from payload to vehicle + payload_to_veh = veh_pos - position_NED; + float payload_to_veh_length = payload_to_veh.length(); + + // update landed state by checking if payload has dropped below terrain + Location payload_loc; + if (get_payload_location(payload_loc)) { + int32_t alt_terrain_cm; + bool landed_orig = landed; + if (payload_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_terrain_cm)) { + + // landed if below terrain + if (alt_terrain_cm <= 0) { + landed = true; + + // raise payload to match terrain + position_NED.z += (alt_terrain_cm * 0.01); + + // zero out velocity and acceleration in horizontal and downward direction + velocity_NED.xy().zero(); + velocity_NED.z = MIN(velocity_NED.z, 0); + accel_NED.xy().zero(); + accel_NED.z = MIN(accel_NED.z, 0); + + // zero out forces on vehicle + veh_forces_ef.zero(); + } + + // not landed if above terrain + if (landed && (alt_terrain_cm > 1)) { + landed = false; + } + } + + // inform user if landed state has changed + if (landed != landed_orig) { + if (landed) { + // get payload location again in case it has moved + get_payload_location(payload_loc); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SlungPayload: landed lat:%f lon:%f alt:%4.1f", + (double)payload_loc.lat * 1e-7, + (double)payload_loc.lng * 1e-7, + (double)payload_loc.alt * 1e-2); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SlungPayload: liftoff"); + } + } + } + + // calculate forces of gravity + Vector3f force_gravity_NED = Vector3f(0.0f, 0.0f, GRAVITY_MSS * weight_kg); + + // tension force on payload (resists gravity, drag, centripetal force) + Vector3f tension_force_NED; + + // tension ratio to smooth transition from line being taut to slack + tension_ratio = 0; + + // calculate drag force (0.5 * drag_coef * air_density * velocity^2 * surface area) + Vector3f force_drag_NED; + Vector3f velocity_air_NED = velocity_NED; + if (!landed) { + velocity_air_NED -= wind_ef; + } + if (drag_coef > 0 && !velocity_air_NED.is_zero()) { + const float air_density = 1.225; // 1.225 kg/m^3 (standard sea-level density) + const float surface_area_m2 = 0.07; // 30cm diameter sphere + const float drag_force = 0.5 * drag_coef * air_density * velocity_air_NED.length_squared() * surface_area_m2; + force_drag_NED = -velocity_air_NED.normalized() * drag_force; + } + + // sanity check payload distance from vehicle and calculate tension force + if (is_positive(payload_to_veh_length)) { + + // calculate unit vector from payload to vehicle + const Vector3f payload_to_veh_norm = payload_to_veh.normalized().tofloat(); + + // ensure payload is no more than line_length from vehicle + if (payload_to_veh_length > line_length) { + payload_to_veh *= (line_length / payload_to_veh_length); + position_NED = veh_pos - payload_to_veh; + } + + // calculate tension ratio as value between 0 and 1 + // tension ratio is 0 when payload-to-vehicle distance is 10cm less than line length + // tension ratio is 1 when payload-to-vehicle distance is equal to line length + tension_ratio = constrain_float(1.0 - (line_length - payload_to_veh_length) * 10, 0, 1); + + // calculate tension forces when line is taut + if (is_positive(tension_ratio)) { + + // tension resists gravity if vehicle is above payload + if (is_negative(payload_to_veh_norm.z)) { + tension_force_NED += -force_gravity_NED.projected(payload_to_veh_norm); + } + + // calculate tension force resulting from velocity difference between vehicle and payload + // use time constant to convert velocity to acceleration + const float velocity_to_accel_TC = 2.0; + Vector3f velocity_diff_NED = (veh_vel_ef - velocity_NED).projected(payload_to_veh_norm); + + // add to tension force if the vehicle is moving faster than the payload + if (vectors_same_direction(velocity_diff_NED, payload_to_veh_norm)) { + tension_force_NED += velocity_diff_NED / velocity_to_accel_TC * weight_kg; + } + + // tension force resisting payload drag + tension_force_NED += -force_drag_NED.projected(payload_to_veh_norm); + + // calculate centripetal force + const Vector3f velocity_parallel = velocity_NED.projected(payload_to_veh_norm); + const Vector3f velocity_perpendicular = velocity_NED - velocity_parallel; + const float tension_force_centripetal = velocity_perpendicular.length_squared() * weight_kg / line_length; + const Vector3f tension_force_centripetal_NED = payload_to_veh_norm * tension_force_centripetal; + + // add centripetal force to tension force + tension_force_NED += tension_force_centripetal_NED; + + // scale tension force by tension ratio + tension_force_NED *= tension_ratio; + } + } + + // force on vehicle is opposite to tension force on payload + veh_forces_ef = -tension_force_NED; + + // convert force to acceleration (f=m*a => a=f/m) + accel_NED = (force_gravity_NED + force_drag_NED + tension_force_NED) / weight_kg; + + // if slung payload is landed we zero out downward (e.g positive) acceleration + if (landed) { + accel_NED.z = MIN(accel_NED.z, 0); + // should probably zero out forces_ef vertical component as well? + } +} + +// returns true if the two vectors point in the same direction, false if perpendicular or opposite +bool SlungPayloadSim::vectors_same_direction(const Vector3f& v1, const Vector3f& v2) const +{ + // check both vectors are non-zero + if (v1.is_zero() || v2.is_zero()) { + return false; + } + return v1.dot(v2) > 0; +} + +#endif diff --git a/libraries/SITL/SIM_SlungPayload.h b/libraries/SITL/SIM_SlungPayload.h new file mode 100644 index 00000000000000..e9a60aaac7e50c --- /dev/null +++ b/libraries/SITL/SIM_SlungPayload.h @@ -0,0 +1,103 @@ +/* + 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 . + */ +/* + simulate a payload slung from a line under a vehicle +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_SLUNGPAYLOAD_ENABLED + +#include +#include +#include +#include + +namespace SITL { + +// SlungPayloadSim handles interaction with main vehicle +class SlungPayloadSim { +public: + friend class SlungPayload; + + // constructor + SlungPayloadSim(); + + // update the SlungPayloadSim's state using thevehicle's earth-frame position, velocity, acceleration and wind + void update(const Vector3p& veh_pos, const Vector3f& veh_vel_ef, const Vector3f& veh_accel_ef, const Vector3f& wind_ef); + + // get earth-frame forces on the vehicle from slung payload + // returns true on success and fills in forces_ef argument, false on failure + bool get_forces_on_vehicle(Vector3f& forces_ef) const; + + // parameter table + static const struct AP_Param::GroupInfo var_info[]; + +private: + + // parameters + AP_Int8 enable; // enable parameter + AP_Float weight_kg; // payload weight in kg + AP_Float line_length; // line length in meters + AP_Int8 sys_id; // mavlink system id for reporting to GCS + AP_Float drag_coef; // drag coefficient (spheres=0.5, cubes=1.05, barrels=0.8~1.2) + + // send MAVLink messages to GCS + void send_report(); + + // write onboard log + void write_log(); + + // get payload location + // returns true on success and fills in payload_loc argument, false on failure + bool get_payload_location(Location& payload_loc) const; + + // update the slung payload's position, velocity, acceleration + // vehicle position, velocity, acceleration and wind should be in earth-frame NED frame + void update_payload(const Vector3p& veh_pos, const Vector3f& veh_vel_ef, const Vector3f& veh_accel_ef, + const Vector3f& wind_ef, float dt); + + // returns true if the two vectors point in the same direction, false if perpendicular or opposite + bool vectors_same_direction(const Vector3f& v1, const Vector3f& v2) const; + + // socket connection variables + const char *target_address = "127.0.0.1"; + const uint16_t target_port = 5763; + SocketAPM_native mav_socket { false }; + bool initialised; // true if this class has been initialised + uint32_t last_update_us; // system time of last update + + // mavlink reporting variables + const float reporting_period_ms = 100; // reporting period in ms + uint32_t last_report_ms; // system time of last MAVLink report sent to GCS + uint32_t last_heartbeat_ms; // system time of last MAVLink heartbeat sent to GCS + bool mavlink_connected; // true if a mavlink connection has been established + mavlink_status_t mav_status; // reported mavlink status + + // payload variables + bool landed = true; // true if the payload is on the ground + float tension_ratio; // 0 if line is loose, 1 if completely taut + Vector3p payload_to_veh;// distance vector (in meters in NED frame) from payload to vehicle (used for reporting purposes) + Vector3p position_NED; // payload's position (as an offset from EKF origin? offset from vehicle?) in meters + Vector3f velocity_NED; // payload velocity + Vector3f accel_NED; // payload's acceleration + Vector3f veh_forces_ef; // earth-frame forces on the vehicle caused by the payload +}; + +} // namespace SITL + +#endif // AP_SIM_SLUNGPAYLOAD_ENABLED diff --git a/libraries/SITL/SIM_SoloGimbal.cpp b/libraries/SITL/SIM_SoloGimbal.cpp new file mode 100644 index 00000000000000..dccf15727249ea --- /dev/null +++ b/libraries/SITL/SIM_SoloGimbal.cpp @@ -0,0 +1,281 @@ +/* + 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 . + */ +/* + gimbal simulator class for MAVLink gimbal +*/ + +#include "SIM_SoloGimbal.h" + +#if AP_SIM_SOLOGIMBAL_ENABLED + +#include + +#include "SIM_Aircraft.h" + +extern const AP_HAL::HAL& hal; + +#define GIMBAL_DEBUG 0 + +#if GIMBAL_DEBUG +#define debug(fmt, args...) do { printf("GIMBAL: " fmt, ##args); } while(0) +#else +#define debug(fmt, args...) do { } while(0) +#endif + +namespace SITL { + +/* + update the gimbal state +*/ +void SoloGimbal::update(const Aircraft &aircraft) +{ + gimbal.update(aircraft); + + // see if we should do a report + send_report(); +} + +static struct gimbal_param { + const char *name; + float value; +} gimbal_params[] = { + {"GMB_OFF_ACC_X", 0}, + {"GMB_OFF_ACC_Y", 0}, + {"GMB_OFF_ACC_Z", 0}, + {"GMB_GN_ACC_X", 0}, + {"GMB_GN_ACC_Y", 0}, + {"GMB_GN_ACC_Z", 0}, + {"GMB_OFF_GYRO_X", 0}, + {"GMB_OFF_GYRO_Y", 0}, + {"GMB_OFF_GYRO_Z", 0}, + {"GMB_OFF_JNT_X", 0}, + {"GMB_OFF_JNT_Y", 0}, + {"GMB_OFF_JNT_Z", 0}, + {"GMB_K_RATE", 0}, + {"GMB_POS_HOLD", 0}, + {"GMB_MAX_TORQUE", 0}, + {"GMB_SND_TORQUE", 0}, + {"GMB_SYSID", 0}, + {"GMB_FLASH", 0}, +}; + +/* + find a parameter structure + */ +struct gimbal_param *SoloGimbal::param_find(const char *name) +{ + for (uint8_t i=0; iname, sizeof(param_value.param_id)); + param_value.param_value = p->value; + param_value.param_count = 0; + param_value.param_index = 0; + param_value.param_type = MAV_PARAM_TYPE_REAL32; + + uint16_t len = mavlink_msg_param_value_encode_status(vehicle_system_id, + gimbal_component_id, + &mavlink.status, + &msg, ¶m_value); + + uint8_t msgbuf[len]; + len = mavlink_msg_to_send_buffer(msgbuf, &msg); + if (len > 0) { + mav_socket.send(msgbuf, len); + } +} + + +/* + send a report to the vehicle control code over MAVLink +*/ +void SoloGimbal::send_report(void) +{ + uint32_t now = AP_HAL::millis(); + if (now < 10000) { + // don't send gimbal reports until 10s after startup. This + // avoids a windows threading issue with non-blocking sockets + // and the initial wait on SERIAL0 + return; + } + if (!mavlink.connected && mav_socket.connect(target_address, target_port)) { + ::printf("SoloGimbal connected to %s:%u\n", target_address, (unsigned)target_port); + mavlink.connected = true; + } + if (!mavlink.connected) { + return; + } + + if (param_send_last_ms && now - param_send_last_ms > 100) { + param_send(&gimbal_params[param_send_idx]); + if (++param_send_idx == ARRAY_SIZE(gimbal_params)) { + printf("Finished sending parameters\n"); + param_send_last_ms = 0; + } + } + + // check for incoming MAVLink messages + uint8_t buf[100]; + ssize_t ret; + + while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) { + for (uint8_t i=0; ivalue = pkt.param_value; + param_send(p); + } + + break; + } + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { + mavlink_param_request_list_t pkt; + mavlink_msg_param_request_list_decode(&msg, &pkt); + if (pkt.target_system == 0 && pkt.target_component == MAV_COMP_ID_GIMBAL) { + // start param send + param_send_idx = 0; + param_send_last_ms = AP_HAL::millis(); + } + printf("SoloGimbal sending %u parameters\n", (unsigned)ARRAY_SIZE(gimbal_params)); + break; + } + default: + debug("got unexpected msg %u\n", msg.msgid); + break; + } + } + } + } + + if (!seen_heartbeat) { + return; + } + mavlink_message_t msg; + uint16_t len; + + if (now - last_heartbeat_ms >= 1000) { + mavlink_heartbeat_t heartbeat; + heartbeat.type = MAV_TYPE_GIMBAL; + heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA; + heartbeat.base_mode = 0; + heartbeat.system_status = 0; + heartbeat.mavlink_version = 0; + heartbeat.custom_mode = 0; + + len = mavlink_msg_heartbeat_encode_status(vehicle_system_id, + gimbal_component_id, + &mavlink.status, + &msg, &heartbeat); + + mav_socket.send(&msg.magic, len); + last_heartbeat_ms = now; + } + + /* + send a GIMBAL_REPORT message + */ + uint32_t now_us = AP_HAL::micros(); + if (now_us - last_report_us > reporting_period_ms*1000UL) { + last_report_us = now_us; + + uint32_t delta_time_us; + Vector3f delta_angle; + Vector3f delta_velocity; + gimbal.get_deltas(delta_angle, delta_velocity, delta_time_us); + + Vector3f joint_angles; + gimbal.get_joint_angles(joint_angles); + + mavlink_gimbal_report_t gimbal_report; + gimbal_report.target_system = vehicle_system_id; + gimbal_report.target_component = vehicle_component_id; + gimbal_report.delta_time = delta_time_us * 1e-6; + gimbal_report.delta_angle_x = delta_angle.x; + gimbal_report.delta_angle_y = delta_angle.y; + gimbal_report.delta_angle_z = delta_angle.z; + gimbal_report.delta_velocity_x = delta_velocity.x; + gimbal_report.delta_velocity_y = delta_velocity.y; + gimbal_report.delta_velocity_z = delta_velocity.z; + gimbal_report.joint_roll = joint_angles.x; + gimbal_report.joint_el = joint_angles.y; + gimbal_report.joint_az = joint_angles.z; + + len = mavlink_msg_gimbal_report_encode_status(vehicle_system_id, + gimbal_component_id, + &mavlink.status, + &msg, &gimbal_report); + + uint8_t msgbuf[len]; + len = mavlink_msg_to_send_buffer(msgbuf, &msg); + if (len > 0) { + mav_socket.send(msgbuf, len); + } + + delta_velocity.zero(); + delta_angle.zero(); + } +} + +} // namespace SITL + +#endif // AP_SIM_SOLOGIMBAL_ENABLED diff --git a/libraries/SITL/SIM_SoloGimbal.h b/libraries/SITL/SIM_SoloGimbal.h new file mode 100644 index 00000000000000..d3fdb6d2d2188a --- /dev/null +++ b/libraries/SITL/SIM_SoloGimbal.h @@ -0,0 +1,88 @@ +/* + 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 . + */ +/* + gimbal simulator class + +./Tools/autotest/sim_vehicle.py -D -G -v ArduCopter --mavlink-gimbal +param set MNT1_TYPE 2 +param set RC6_OPTION 213 # MOUNT1_PITCH +rc 6 1818 # for neutral pitch input +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_SOLOGIMBAL_ENABLED + +#include "SIM_Gimbal.h" + +#include +#include +#include + +namespace SITL { + +class SoloGimbal { +public: + + SoloGimbal() {} + void update(const Aircraft &aicraft); + +private: + + const char *target_address = "127.0.0.1"; + const uint16_t target_port = 5762; + + // physic simulation of gimbal: + Gimbal gimbal; + + // reporting variables. gimbal pushes these to vehicle code over + // MAVLink at approx 100Hz + + // reporting period in ms + const float reporting_period_ms = 10; + + uint32_t last_report_us; + uint32_t last_heartbeat_ms; + bool seen_heartbeat; + bool seen_gimbal_control; + uint8_t vehicle_system_id; + uint8_t vehicle_component_id; + + SocketAPM_native mav_socket{false}; + struct { + // socket to telem2 on aircraft + bool connected; + mavlink_message_t rxmsg; + mavlink_status_t status; + uint8_t seq; + } mavlink; + + uint32_t param_send_last_ms; + uint8_t param_send_idx; + + // component ID we send from: + const uint8_t gimbal_component_id = 154; // MAV_COMP_ID_GIMBAL + + void send_report(void); + void param_send(const struct gimbal_param *p); + struct gimbal_param *param_find(const char *name); +}; + +} // namespace SITL + +#endif // AP_SIM_SOLOGIMBAL_ENABLED + diff --git a/libraries/SITL/SIM_Sprayer.cpp b/libraries/SITL/SIM_Sprayer.cpp index 1212fb8deea0ca..31736bc928402e 100644 --- a/libraries/SITL/SIM_Sprayer.cpp +++ b/libraries/SITL/SIM_Sprayer.cpp @@ -76,7 +76,7 @@ void Sprayer::update(const struct sitl_input &input) if (pump_demand < 0) { // never updated pump_demand = 0; } - const float pump_max_change = pump_slew_rate / 100.0f * dt; + const float pump_max_change = pump_slew_rate * 0.01f * dt; last_pump_output = constrain_float(pump_demand, last_pump_output - pump_max_change, last_pump_output + pump_max_change); last_pump_output = constrain_float(last_pump_output, 0, 1); diff --git a/libraries/SITL/SIM_StratoBlimp.cpp b/libraries/SITL/SIM_StratoBlimp.cpp new file mode 100644 index 00000000000000..915fceb7a1dced --- /dev/null +++ b/libraries/SITL/SIM_StratoBlimp.cpp @@ -0,0 +1,311 @@ +/* + 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 . + */ +/* + StratoBlimp simulator class +*/ + +#include "SIM_StratoBlimp.h" + +#if AP_SIM_STRATOBLIMP_ENABLED + +#include +#include + +#include + +using namespace SITL; + +extern const AP_HAL::HAL& hal; + +// SITL StratoBlimp parameters +const AP_Param::GroupInfo StratoBlimp::var_info[] = { + // @Param: MASS + // @DisplayName: mass + // @Description: mass of blimp not including lifting gas + // @Units: kg + AP_GROUPINFO("MASS", 1, StratoBlimp, mass, 80), + + // @Param: HMASS + // @DisplayName: helium mass + // @Description: mass of lifting gas + // @Units: kg + AP_GROUPINFO("HMASS", 2, StratoBlimp, helium_mass, 13.54), + + // @Param: ARM_LEN + // @DisplayName: arm length + // @Description: distance from center of mass to one motor + // @Units: m + AP_GROUPINFO("ARM_LEN", 3, StratoBlimp, arm_length, 3.6), + + // @Param: MOT_THST + // @DisplayName: motor thrust + // @Description: thrust at max throttle for one motor + // @Units: N + AP_GROUPINFO("MOT_THST", 4, StratoBlimp, motor_thrust, 145), + + // @Param: DRAG_FWD + // @DisplayName: drag in forward direction + // @Description: drag on X axis + AP_GROUPINFO("DRAG_FWD", 5, StratoBlimp, drag_fwd, 0.27), + + // @Param: DRAG_SIDE + // @DisplayName: drag in sidewards direction + // @Description: drag on Y axis + AP_GROUPINFO("DRAG_SIDE", 16, StratoBlimp, drag_side, 0.5), + + // @Param: DRAG_UP + // @DisplayName: drag in upward direction + // @Description: drag on Z axis + AP_GROUPINFO("DRAG_UP", 6, StratoBlimp, drag_up, 0.4), + + // @Param: MOI_YAW + // @DisplayName: moment of inertia in yaw + // @Description: moment of inertia in yaw + AP_GROUPINFO("MOI_YAW", 7, StratoBlimp, moi_yaw, 2800), + + // @Param: MOI_ROLL + // @DisplayName: moment of inertia in roll + // @Description: moment of inertia in roll + AP_GROUPINFO("MOI_ROLL", 8, StratoBlimp, moi_roll, 1400), + + // @Param: MOI_PITCH + // @DisplayName: moment of inertia in pitch + // @Description: moment of inertia in pitch + AP_GROUPINFO("MOI_PITCH", 9, StratoBlimp, moi_pitch, 3050), + + // @Param: ALT_TARG + // @DisplayName: altitude target + // @Description: altitude target + // @Units: m + AP_GROUPINFO("ALT_TARG", 10, StratoBlimp, altitude_target, 20000), + + // @Param: CLMB_RT + // @DisplayName: target climb rate + // @Description: target climb rate + // @Units: m/s + AP_GROUPINFO("CLMB_RT", 11, StratoBlimp, target_climb_rate, 5), + + // @Param: YAW_RT + // @DisplayName: yaw rate + // @Description: maximum yaw rate with full left throttle at target altitude + // @Units: deg/s + AP_GROUPINFO("YAW_RT", 12, StratoBlimp, yaw_rate_max, 60), + + // @Param: MOT_ANG + // @DisplayName: motor angle + // @Description: maximum motor tilt angle + // @Units: deg + AP_GROUPINFO("MOT_ANG", 13, StratoBlimp, motor_angle, 20), + + // @Param: COL + // @DisplayName: center of lift + // @Description: center of lift position above CoG + // @Units: m + AP_GROUPINFO("COL", 14, StratoBlimp, center_of_lift, 2.54), + + // @Param: WVANE + // @DisplayName: weathervaning offset + // @Description: center of drag for weathervaning + // @Units: m + AP_GROUPINFO("WVANE", 15, StratoBlimp, center_of_drag, 0.3), + + // @Param: FLR + // @DisplayName: free lift rate + // @Description: amount of additional lift generated by the helper balloon (for the purpose of ascent), as a proportion of the 'neutral buoyancy' lift + AP_GROUPINFO("FLR", 17, StratoBlimp, free_lift_rate, 0.12), + + AP_GROUPEND +}; + +StratoBlimp::StratoBlimp(const char *frame_str) : + Aircraft(frame_str) +{ + AP::sitl()->models.stratoblimp_ptr = this; + AP_Param::setup_object_defaults(this, var_info); +} + +/* + calculate coefficients to match parameters + */ +void StratoBlimp::calculate_coefficients(void) +{ + // calculate yaw drag based on turn rate at the given altitude + drag_yaw = 1.0; + + // get full throttle rotational accel for one motor + Vector3f body_acc, rot_accel; + handle_motor(1, 0, body_acc, rot_accel, -arm_length); + + // get rotational drag at target alt + Vector3f vel_bf, g, drag_linear, drag_rotaccel; + g.z = radians(yaw_rate_max); + + get_drag(vel_bf, g, + altitude_target, + drag_linear, drag_rotaccel); + + drag_yaw = rot_accel.z / -drag_rotaccel.z; +} + +void StratoBlimp::handle_motor(float throttle, float tilt, Vector3f &body_acc, Vector3f &rot_accel, float lateral_position) +{ + const float angle_rad = radians(motor_angle) * tilt; + const float thrust_x = motor_thrust * throttle; + const float total_mass = mass + helium_mass; + + const Vector3f thrust{cosf(angle_rad)*thrust_x, 0, -sinf(angle_rad)*thrust_x}; // assume constant with pressure alt and linear + Vector3f accel = thrust / total_mass; + Vector3f pos{0, lateral_position, 0}; + + Vector3f torque = (pos % thrust); + + rot_accel.z += torque.z / moi_yaw; + body_acc += accel; +} + + +/* + get body frame linear and rotational drag for a given velocity and altitude + */ +void StratoBlimp::get_drag(const Vector3f &velocity_linear, + const Vector3f &velocity_rot, + float altitude, + Vector3f &drag_linear, Vector3f &drag_rotaccel) +{ + Vector3f vel_air_bf = velocity_linear; + const float drag_x_sign = vel_air_bf.x>0? -1 : 1; + const float drag_y_sign = vel_air_bf.y>0? -1 : 1; + const float drag_z_sign = vel_air_bf.z>0? -1 : 1; + drag_linear.x = 0.5 * drag_x_sign * air_density * sq(vel_air_bf.x) * drag_fwd; + drag_linear.y = 0.5 * drag_y_sign * air_density * sq(vel_air_bf.y) * drag_fwd; + drag_linear.z = 0.5 * drag_z_sign * air_density * sq(vel_air_bf.z) * drag_up; + + drag_rotaccel = -velocity_rot * drag_yaw; + + /* + apply torque from drag + */ + Vector3f drag_force = drag_linear * mass; + Vector3f drag_pos{-center_of_drag, 0, -center_of_lift}; + Vector3f drag_torque = (drag_pos % drag_force); + drag_rotaccel += drag_torque / moi_pitch; +} + +/* + get vertical thrust from lift in Newtons + */ +float StratoBlimp::get_lift(float altitude) +{ + // start with neutral buoyancy + float lift_accel = GRAVITY_MSS; + + // add lift from helper balloon if still attached + if (helper_balloon_attached) { + // helper balloon additional lift amount based on Free Lift Ratio + lift_accel += GRAVITY_MSS*free_lift_rate; + // detach helper balloon if the target altitude has been reached + if (altitude >= altitude_target) { + helper_balloon_attached = false; + } + } + return mass * lift_accel; +} + +// calculate rotational and linear accelerations in body frame +void StratoBlimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc, Vector3f &rot_accel) +{ + //float delta_time = frame_time_us * 1.0e-6f; + + if (!hal.scheduler->is_system_initialized()) { + return; + } + + const float left_tilt = filtered_servo_angle(input, 0); + const float right_tilt = filtered_servo_angle(input, 1); + + const float left_throttle = filtered_servo_range(input, 2); + const float right_throttle = filtered_servo_range(input, 3); + const float ground_release = filtered_servo_range(input, 4); + + body_acc.zero(); + rot_accel.zero(); + + handle_motor(left_throttle, left_tilt, body_acc, rot_accel, -arm_length); + handle_motor(right_throttle, right_tilt, body_acc, rot_accel, arm_length); + + Vector3f drag_linear, drag_rotaccel; + get_drag(velocity_air_bf, gyro, + location.alt*0.01, + drag_linear, drag_rotaccel); + + body_acc += drag_linear; + rot_accel += drag_rotaccel; + + if (ground_release > 0.9) { + released = true; + } + if (released) { + Vector3f lift_thrust_ef{0, 0, -get_lift(location.alt*0.01)}; + Vector3f lift_thrust_bf = dcm.transposed() * lift_thrust_ef; + + body_acc += lift_thrust_bf / mass; + + /* + apply righting moment + */ + Vector3f lift_pos{0, 0, -center_of_lift}; + Vector3f lift_torque = (lift_pos % lift_thrust_bf); + rot_accel += lift_torque / moi_roll; + } +} + +/* + update the airship simulation by one time step + */ +void StratoBlimp::update(const struct sitl_input &input) +{ + air_density = get_air_density(location.alt*0.01); + EAS2TAS = sqrtf(SSL_AIR_DENSITY / air_density); + + calculate_coefficients(); + + float delta_time = frame_time_us * 1.0e-6f; + + Vector3f rot_accel = Vector3f(0,0,0); + calculate_forces(input, accel_body, rot_accel); + + // update rotational rates in body frame + gyro += rot_accel * delta_time; + + gyro.x = constrain_float(gyro.x, -radians(2000.0f), radians(2000.0f)); + gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f)); + gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f)); + + dcm.rotate(gyro * delta_time); + dcm.normalize(); + + update_dynamics(rot_accel); + update_external_payload(input); + + // update lat/lon/altitude + update_position(); + update_wind(input); + time_advance(); + + // update magnetic field + update_mag_field_bf(); +} + +#endif // AP_SIM_STRATOBLIMP_ENABLED diff --git a/libraries/SITL/SIM_StratoBlimp.h b/libraries/SITL/SIM_StratoBlimp.h new file mode 100644 index 00000000000000..683e5679707248 --- /dev/null +++ b/libraries/SITL/SIM_StratoBlimp.h @@ -0,0 +1,88 @@ +/* + 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 . + */ +/* + a stratospheric blimp simulator class +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_STRATOBLIMP_ENABLED + +#include "SIM_Aircraft.h" +#include + +namespace SITL { + +/* + a stratospheric blimp simulator + */ + +class StratoBlimp : public Aircraft { +public: + StratoBlimp(const char *frame_str); + + /* update model by one time step */ + void update(const struct sitl_input &input) override; + + /* static object creator */ + static Aircraft *create(const char *frame_str) { + return NEW_NOTHROW StratoBlimp(frame_str); + } + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + +private: + void calculate_coefficients(); + void handle_motor(float throttle, float tilt, Vector3f &body_acc, Vector3f &rot_accel, float lateral_position); + void get_drag(const Vector3f &velocity_linear, + const Vector3f &velocity_rot, + float altitude, + Vector3f &drag_linear, Vector3f &drag_rotaccel); + float get_lift(float altitude); + + float air_density; + float EAS2TAS; + float drag_yaw; + bool released; + bool helper_balloon_attached = true; + + AP_Float mass; + AP_Float helium_mass; + AP_Float arm_length; + AP_Float motor_thrust; + AP_Float drag_fwd; + AP_Float drag_side; + AP_Float drag_up; + AP_Float altitude_target; + AP_Float target_climb_rate; + AP_Float turn_rate; + AP_Float motor_angle; + AP_Float yaw_rate_max; + AP_Float moi_roll; + AP_Float moi_yaw; + AP_Float moi_pitch; + AP_Float center_of_lift; + AP_Float center_of_drag; + AP_Float free_lift_rate; +}; + +} + +#endif // AP_SIM_STRATOBLIMP_ENABLED diff --git a/libraries/SITL/SIM_Submarine.h b/libraries/SITL/SIM_Submarine.h index 6c562cd496ca1a..ea0e311760b216 100644 --- a/libraries/SITL/SIM_Submarine.h +++ b/libraries/SITL/SIM_Submarine.h @@ -51,7 +51,7 @@ class Submarine : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Submarine(frame_str); + return NEW_NOTHROW Submarine(frame_str); } diff --git a/libraries/SITL/SIM_Temperature_MCP9600.cpp b/libraries/SITL/SIM_Temperature_MCP9600.cpp index dd3b056a49b9e5..c05e7221504fa8 100644 --- a/libraries/SITL/SIM_Temperature_MCP9600.cpp +++ b/libraries/SITL/SIM_Temperature_MCP9600.cpp @@ -5,12 +5,19 @@ using namespace SITL; #include #include +enum class MCP9600StatusBits { + TH_UPDATE = (1 << 6) // data ready to read +}; + void MCP9600::init() { set_debug(true); - add_register("WHOAMI", MCP9600DevReg::WHOAMI, 2, I2CRegisters::RegMode::RDONLY); - set_register(MCP9600DevReg::WHOAMI, (uint16_t)0x40); + add_register("WHOAMI", MCP9600DevReg::WHOAMI, 1, I2CRegisters::RegMode::RDONLY); + set_register(MCP9600DevReg::WHOAMI, (uint8_t)0x40); + + add_register("SENSOR_STATUS", MCP9600DevReg::SENSOR_STATUS, 1, I2CRegisters::RegMode::RDWR); + set_register(MCP9600DevReg::SENSOR_STATUS, (uint8_t)0x00); add_register("SENSOR_CONFIG", MCP9600DevReg::SENSOR_CONFIG, 1, I2CRegisters::RegMode::RDWR); set_register(MCP9600DevReg::SENSOR_CONFIG, (uint8_t)0x00); @@ -32,14 +39,26 @@ void MCP9600::update(const class Aircraft &aircraft) // unconfigured; FIXME lack of fidelity return; } - if ((config & 0b111) != 1) { // FIXME: this is just the default config + if ((config & 0b111) != 0b10) { AP_HAL::panic("Unexpected filter configuration"); } if ((config >> 4) != 0) { // this is a K-type thermocouple, the default in the driver AP_HAL::panic("Unexpected thermocouple configuration"); } + + // dont update if we already have data ready to read (CHECKME: fidelity) + uint8_t status = 0; + get_reg_value(MCP9600DevReg::SENSOR_STATUS, config); + + if (status & (uint8_t)MCP9600StatusBits::TH_UPDATE) { + return; + } + static constexpr uint16_t factor = (1/0.0625); set_register(MCP9600DevReg::HOT_JUNC, uint16_t(htobe16(some_temperature + degrees(sinf(now_ms)) * factor))); + + // indicate we have data ready to read + set_register(MCP9600DevReg::SENSOR_STATUS, (uint8_t)MCP9600StatusBits::TH_UPDATE); } int MCP9600::rdwr(I2C::i2c_rdwr_ioctl_data *&data) diff --git a/libraries/SITL/SIM_Temperature_MCP9600.h b/libraries/SITL/SIM_Temperature_MCP9600.h index d8109cbaed558a..c0d2f3ae1ae21b 100644 --- a/libraries/SITL/SIM_Temperature_MCP9600.h +++ b/libraries/SITL/SIM_Temperature_MCP9600.h @@ -12,6 +12,7 @@ namespace SITL { class MCP9600DevReg : public I2CRegEnum { public: static constexpr uint8_t HOT_JUNC { 0x00 }; + static constexpr uint8_t SENSOR_STATUS { 0x04 }; static constexpr uint8_t SENSOR_CONFIG { 0x05 }; static constexpr uint8_t WHOAMI { 0x20 }; }; diff --git a/libraries/SITL/SIM_Temperature_TSYS01.cpp b/libraries/SITL/SIM_Temperature_TSYS01.cpp index 0c1ab789ab466a..5785a731527aeb 100644 --- a/libraries/SITL/SIM_Temperature_TSYS01.cpp +++ b/libraries/SITL/SIM_Temperature_TSYS01.cpp @@ -193,9 +193,6 @@ float SITL::TSYS01::get_sim_temperature() const float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - // To Do: Add a sensor board temperature offset parameter - return (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + return AP_Baro::get_temperatureC_for_alt_amsl(sim_alt) + 25; } diff --git a/libraries/SITL/SIM_ToshibaLED.cpp b/libraries/SITL/SIM_ToshibaLED.cpp index 7d54c7cc7fcb9d..82a55311a98da8 100644 --- a/libraries/SITL/SIM_ToshibaLED.cpp +++ b/libraries/SITL/SIM_ToshibaLED.cpp @@ -17,7 +17,7 @@ void SITL::ToshibaLED::update(const class Aircraft &aircraft) last_print_pwm1 = get_register(ToshibaLEDDevReg::PWM1); last_print_pwm2 = get_register(ToshibaLEDDevReg::PWM2); last_print_enable = get_register(ToshibaLEDDevReg::ENABLE); - // gcs().send_text(MAV_SEVERITY_INFO, "SIM_ToshibaLED: PWM0=%u PWM1=%u PWM2=%u ENABLE=%u", last_print_pwm0, last_print_pwm1, last_print_pwm2, last_print_enable); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ToshibaLED: PWM0=%u PWM1=%u PWM2=%u ENABLE=%u", last_print_pwm0, last_print_pwm1, last_print_pwm2, last_print_enable); if (get_register(ToshibaLEDDevReg::ENABLE)) { // here we convert from 0-15 BGR (the PWM values from the i2c bus) diff --git a/libraries/SITL/SIM_Tracker.h b/libraries/SITL/SIM_Tracker.h index 028fee42178ddf..2ff7ecaba4594f 100644 --- a/libraries/SITL/SIM_Tracker.h +++ b/libraries/SITL/SIM_Tracker.h @@ -33,7 +33,7 @@ class Tracker : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Tracker(frame_str); + return NEW_NOTHROW Tracker(frame_str); } private: diff --git a/libraries/SITL/SIM_VectorNav.cpp b/libraries/SITL/SIM_VectorNav.cpp index ee685ee88a1249..545445da46d40f 100644 --- a/libraries/SITL/SIM_VectorNav.cpp +++ b/libraries/SITL/SIM_VectorNav.cpp @@ -18,6 +18,7 @@ #include "SIM_VectorNav.h" #include +#include #include #include #include @@ -29,37 +30,49 @@ VectorNav::VectorNav() : { } -struct PACKED VN_packet1 { - float uncompMag[3]; + +struct PACKED VN_IMU_packet_sim { + static constexpr uint8_t header[]{0x01, 0x21, 0x07}; + uint64_t timeStartup; + float gyro[3]; + float accel[3]; float uncompAccel[3]; float uncompAngRate[3]; - float pressure; float mag[3]; - float accel[3]; - float gyro[3]; + float temp; + float pressure; +}; +constexpr uint8_t VN_IMU_packet_sim::header[]; + +struct PACKED VN_INS_ekf_packet_sim { + static constexpr uint8_t header[]{0x31, 0x01, 0x00, 0x06, 0x01, 0x13, 0x06}; + uint64_t timeStartup; float ypr[3]; float quaternion[4]; float yprU[3]; - double positionLLA[3]; - float velNED[3]; + uint16_t insStatus; + double posLla[3]; + float velNed[3]; float posU; float velU; }; - -struct PACKED VN_packet2 { - uint64_t timeGPS; - float temp; - uint8_t numGPS1Sats; - uint8_t GPS1Fix; - double GPS1posLLA[3]; - float GPS1velNED[3]; - float GPS1DOP[7]; - uint8_t numGPS2Sats; - uint8_t GPS2Fix; +constexpr uint8_t VN_INS_ekf_packet_sim::header[]; + +struct PACKED VN_INS_gnss_packet_sim { + static constexpr uint8_t header[]{0x49, 0x03, 0x00, 0xB8, 0x26, 0x18, 0x00}; + uint64_t timeStartup; + uint64_t timeGps; + uint8_t numSats1; + uint8_t fix1; + double posLla1[3]; + float velNed1[3]; + float posU1[3]; + float velU1; + float dop1[7]; + uint8_t numSats2; + uint8_t fix2; }; - -#define VN_PKT1_HEADER { 0xFA, 0x34, 0x2E, 0x07, 0x06, 0x01, 0x12, 0x06 } -#define VN_PKT2_HEADER { 0xFA, 0x4E, 0x02, 0x00, 0x10, 0x00, 0xB8, 0x20, 0x18, 0x00 } +constexpr uint8_t VN_INS_gnss_packet_sim::header[]; /* get timeval using simulation time @@ -80,37 +93,62 @@ static void simulation_timeval(struct timeval *tv) tv->tv_usec = new_usec % 1000000ULL; } -void VectorNav::send_packet1(void) +void VectorNav::send_imu_packet(void) { const auto &fdm = _sitl->state; - struct VN_packet1 pkt {}; + struct VN_IMU_packet_sim pkt {}; + + pkt.timeStartup = AP_HAL::micros() * 1e3; + + + const float gyro_noise = 0.05; + + pkt.gyro[0] = radians(fdm.rollRate + rand_float() * gyro_noise); + pkt.gyro[1] = radians(fdm.pitchRate + rand_float() * gyro_noise); + pkt.gyro[2] = radians(fdm.yawRate + rand_float() * gyro_noise); + + pkt.accel[0] = fdm.xAccel; + pkt.accel[1] = fdm.yAccel; + pkt.accel[2] = fdm.zAccel; pkt.uncompAccel[0] = fdm.xAccel; pkt.uncompAccel[1] = fdm.yAccel; pkt.uncompAccel[2] = fdm.zAccel; - const float gyro_noise = 0.05; + pkt.uncompAngRate[0] = radians(fdm.rollRate + gyro_noise * rand_float()); pkt.uncompAngRate[1] = radians(fdm.pitchRate + gyro_noise * rand_float()); pkt.uncompAngRate[2] = radians(fdm.yawRate + gyro_noise * rand_float()); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(fdm.altitude * 0.001f, sigma, delta, theta); - pkt.pressure = SSL_AIR_PRESSURE * delta * 0.001 + rand_float() * 0.01; - pkt.mag[0] = fdm.bodyMagField.x*0.001; pkt.mag[1] = fdm.bodyMagField.y*0.001; pkt.mag[2] = fdm.bodyMagField.z*0.001; - pkt.uncompMag[0] = pkt.mag[0]; - pkt.uncompMag[1] = pkt.mag[1]; - pkt.uncompMag[2] = pkt.mag[2]; - pkt.accel[0] = fdm.xAccel; - pkt.accel[1] = fdm.yAccel; - pkt.accel[2] = fdm.zAccel; - pkt.gyro[0] = radians(fdm.rollRate + rand_float() * gyro_noise); - pkt.gyro[1] = radians(fdm.pitchRate + rand_float() * gyro_noise); - pkt.gyro[2] = radians(fdm.yawRate + rand_float() * gyro_noise); + pkt.temp = AP_Baro::get_temperatureC_for_alt_amsl(fdm.altitude); + + const float pressure_Pa = AP_Baro::get_pressure_for_alt_amsl(fdm.altitude); + pkt.pressure = pressure_Pa*0.001 + rand_float() * 0.01; + + const uint8_t sync_byte = 0xFA; + write_to_autopilot((const char *)&sync_byte, 1); + write_to_autopilot((const char *)&VN_IMU_packet_sim::header, sizeof(VN_IMU_packet_sim::header)); + write_to_autopilot((const char *)&pkt, sizeof(pkt)); + + uint16_t crc = crc16_ccitt(&VN_IMU_packet_sim::header[0], sizeof(VN_IMU_packet_sim::header), 0); + crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc); + uint16_t crc2; + swab(&crc, &crc2, 2); + + write_to_autopilot((const char *)&crc2, sizeof(crc2)); +} + +void VectorNav::send_ins_ekf_packet(void) +{ + const auto &fdm = _sitl->state; + + struct VN_INS_ekf_packet_sim pkt {}; + + pkt.timeStartup = AP_HAL::micros() * 1e3; pkt.ypr[0] = fdm.yawDeg; pkt.ypr[1] = fdm.pitchDeg; @@ -121,63 +159,80 @@ void VectorNav::send_packet1(void) pkt.quaternion[2] = fdm.quaternion.q4; pkt.quaternion[3] = fdm.quaternion.q1; - pkt.positionLLA[0] = fdm.latitude; - pkt.positionLLA[1] = fdm.longitude; - pkt.positionLLA[2] = fdm.altitude; - pkt.velNED[0] = fdm.speedN; - pkt.velNED[1] = fdm.speedE; - pkt.velNED[2] = fdm.speedD; + pkt.yprU[0] = 0.03; + pkt.yprU[1] = 0.03; + pkt.yprU[2] = 0.15; + + pkt.insStatus = 0x0306; + + pkt.posLla[0] = fdm.latitude; + pkt.posLla[1] = fdm.longitude; + pkt.posLla[2] = fdm.altitude; + pkt.velNed[0] = fdm.speedN; + pkt.velNed[1] = fdm.speedE; + pkt.velNed[2] = fdm.speedD; pkt.posU = 0.5; pkt.velU = 0.25; - const uint8_t header[] VN_PKT1_HEADER; - - write_to_autopilot((char *)&header, sizeof(header)); - write_to_autopilot((char *)&pkt, sizeof(pkt)); + const uint8_t sync_byte = 0xFA; + write_to_autopilot((const char *)&sync_byte, 1); + write_to_autopilot((const char *)&VN_INS_ekf_packet_sim::header, sizeof(VN_INS_ekf_packet_sim::header)); + write_to_autopilot((const char *)&pkt, sizeof(pkt)); - uint16_t crc = crc16_ccitt(&header[1], sizeof(header)-1, 0); + uint16_t crc = crc16_ccitt(&VN_INS_ekf_packet_sim::header[0], sizeof(VN_INS_ekf_packet_sim::header), 0); crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc); + uint16_t crc2; swab(&crc, &crc2, 2); - write_to_autopilot((char *)&crc2, sizeof(crc2)); + write_to_autopilot((const char *)&crc2, sizeof(crc2)); } -void VectorNav::send_packet2(void) +void VectorNav::send_ins_gnss_packet(void) { const auto &fdm = _sitl->state; - struct VN_packet2 pkt {}; + struct VN_INS_gnss_packet_sim pkt {}; + + pkt.timeStartup = AP_HAL::micros() * 1e3; struct timeval tv; simulation_timeval(&tv); - pkt.timeGPS = tv.tv_usec * 1000ULL; - pkt.temp = 23.5; - pkt.numGPS1Sats = 19; - pkt.GPS1Fix = 3; - pkt.GPS1posLLA[0] = fdm.latitude; - pkt.GPS1posLLA[1] = fdm.longitude; - pkt.GPS1posLLA[2] = fdm.altitude; - pkt.GPS1velNED[0] = fdm.speedN; - pkt.GPS1velNED[1] = fdm.speedE; - pkt.GPS1velNED[2] = fdm.speedD; - // pkt.GPS1DOP = - pkt.numGPS2Sats = 18; - pkt.GPS2Fix = 3; - - const uint8_t header[] VN_PKT2_HEADER; - - write_to_autopilot((char *)&header, sizeof(header)); - write_to_autopilot((char *)&pkt, sizeof(pkt)); - - uint16_t crc = crc16_ccitt(&header[1], sizeof(header)-1, 0); + pkt.timeGps = tv.tv_usec * 1000ULL; + + pkt.numSats1 = 19; + pkt.fix1 = 3; + pkt.posLla1[0] = fdm.latitude; + pkt.posLla1[1] = fdm.longitude; + pkt.posLla1[2] = fdm.altitude; + pkt.velNed1[0] = fdm.speedN; + pkt.velNed1[1] = fdm.speedE; + pkt.velNed1[2] = fdm.speedD; + + pkt.posU1[0] = 1; + pkt.posU1[0] = 1; + pkt.posU1[0] = 1.5; + + pkt.velNed1[0] = 0.05; + pkt.velNed1[0] = 0.05; + pkt.velNed1[0] = 0.05; + // pkt.dop1 = + pkt.numSats2 = 18; + pkt.fix2 = 3; + + const uint8_t sync_byte = 0xFA; + write_to_autopilot((const char *)&sync_byte, 1); + write_to_autopilot((const char *)&VN_INS_gnss_packet_sim::header, sizeof(VN_INS_gnss_packet_sim::header)); + write_to_autopilot((const char *)&pkt, sizeof(pkt)); + + uint16_t crc = crc16_ccitt(&VN_INS_gnss_packet_sim::header[0], sizeof(VN_INS_gnss_packet_sim::header), 0); crc = crc16_ccitt((const uint8_t *)&pkt, sizeof(pkt), crc); uint16_t crc2; swab(&crc, &crc2, 2); - write_to_autopilot((char *)&crc2, sizeof(crc2)); + write_to_autopilot((const char *)&crc2, sizeof(crc2)); } void VectorNav::nmea_printf(const char *fmt, ...) @@ -203,22 +258,40 @@ void VectorNav::update(void) } uint32_t now = AP_HAL::micros(); - if (now - last_pkt1_us >= 20000) { - last_pkt1_us = now; - send_packet1(); + if (now - last_imu_pkt_us >= 20000) { + last_imu_pkt_us = now; + send_imu_packet(); } - - if (now - last_pkt2_us >= 200000) { - last_pkt2_us = now; - send_packet2(); + + if (now - last_ekf_pkt_us >= 20000) { + last_ekf_pkt_us = now; + send_ins_ekf_packet(); + } + + if (now - last_gnss_pkt_us >= 200000) { + last_gnss_pkt_us = now; + send_ins_gnss_packet(); } - // Strictly we should send this in responce to the request - // but sending it occasionally acheaves the same thing - if (now - last_type_us >= 1000000) { - last_type_us = now; - nmea_printf("$VNRRG,01,VN-300-SITL"); + char receive_buf[50]; + ssize_t n = read_from_autopilot(&receive_buf[0], ARRAY_SIZE(receive_buf)); + if (n <= 0) { + return; } + // avoid parsing the NMEA stream here by making assumptions about + // how we receive configuration strings. Generally we can just + // echo back the configuration string to make the driver happy. + if (n >= 9) { + // intercept device-version query, respond with simulated version: + const char *ver_query_string = "$VNRRG,01"; + if (strncmp(receive_buf, ver_query_string, strlen(ver_query_string)) == 0) { + nmea_printf("$VNRRG,01,VN-300-SITL"); + // consume the query so we don't "respond" twice: + memmove(&receive_buf[0], &receive_buf[strlen(ver_query_string)], n - strlen(ver_query_string)); + n -= strlen(ver_query_string); + } + } + write_to_autopilot(receive_buf, n); } diff --git a/libraries/SITL/SIM_VectorNav.h b/libraries/SITL/SIM_VectorNav.h index 589539e5d9a8f3..77fde25625733a 100644 --- a/libraries/SITL/SIM_VectorNav.h +++ b/libraries/SITL/SIM_VectorNav.h @@ -41,12 +41,13 @@ class VectorNav : public SerialDevice { void update(void); private: - uint32_t last_pkt1_us; - uint32_t last_pkt2_us; - uint32_t last_type_us; + uint32_t last_imu_pkt_us; + uint32_t last_ekf_pkt_us; + uint32_t last_gnss_pkt_us; - void send_packet1(); - void send_packet2(); + void send_imu_packet(); + void send_ins_ekf_packet(); + void send_ins_gnss_packet(); void nmea_printf(const char *fmt, ...); }; diff --git a/libraries/SITL/SIM_Webots.cpp b/libraries/SITL/SIM_Webots.cpp index 80a8583c410922..3e896d845a6835 100644 --- a/libraries/SITL/SIM_Webots.cpp +++ b/libraries/SITL/SIM_Webots.cpp @@ -290,7 +290,7 @@ bool Webots::parse_sensors(const char *json) bool Webots::connect_sockets(void) { if (!sim_sock) { - sim_sock = new SocketAPM_native(false); + sim_sock = NEW_NOTHROW SocketAPM_native(false); if (!sim_sock) { AP_HAL::panic("Out of memory for sensors socket"); } diff --git a/libraries/SITL/SIM_Webots.h b/libraries/SITL/SIM_Webots.h index 5457d6cd962a66..d82a9a36057e06 100644 --- a/libraries/SITL/SIM_Webots.h +++ b/libraries/SITL/SIM_Webots.h @@ -47,7 +47,7 @@ class Webots : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Webots(frame_str); + return NEW_NOTHROW Webots(frame_str); } diff --git a/libraries/SITL/SIM_Webots_Python.h b/libraries/SITL/SIM_Webots_Python.h index ec3e8ba4b56274..e1fde3b63c5bd5 100644 --- a/libraries/SITL/SIM_Webots_Python.h +++ b/libraries/SITL/SIM_Webots_Python.h @@ -43,7 +43,7 @@ class WebotsPython : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new WebotsPython(frame_str); + return NEW_NOTHROW WebotsPython(frame_str); } /* Create and set in/out socket for Webots simulator */ diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 24af0c6bab2fed..3633bb4b1a7394 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -125,7 +125,7 @@ XPlane::XPlane(const char *frame_str) : */ void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dref) { - struct DRef *d = new struct DRef; + struct DRef *d = NEW_NOTHROW struct DRef; if (d == nullptr) { AP_HAL::panic("out of memory for DRef %s", name); } @@ -151,7 +151,7 @@ void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dre void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value &d) { if (strncmp(label, "axis", 4) == 0) { - struct JoyInput *j = new struct JoyInput; + struct JoyInput *j = NEW_NOTHROW struct JoyInput; if (j == nullptr) { AP_HAL::panic("out of memory for JoyInput %s", label); } @@ -164,7 +164,7 @@ void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value joyinputs = j; } if (strncmp(label, "button", 6) == 0) { - struct JoyInput *j = new struct JoyInput; + struct JoyInput *j = NEW_NOTHROW struct JoyInput; if (j == nullptr) { AP_HAL::panic("out of memory for JoyInput %s", label); } diff --git a/libraries/SITL/SIM_XPlane.h b/libraries/SITL/SIM_XPlane.h index 2e711de5a1b5cf..4d4cd37724c72d 100644 --- a/libraries/SITL/SIM_XPlane.h +++ b/libraries/SITL/SIM_XPlane.h @@ -46,7 +46,7 @@ class XPlane : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new XPlane(frame_str); + return NEW_NOTHROW XPlane(frame_str); } private: diff --git a/libraries/SITL/SIM_config.h b/libraries/SITL/SIM_config.h index 419cac92262ba2..557c3077ed9dea 100644 --- a/libraries/SITL/SIM_config.h +++ b/libraries/SITL/SIM_config.h @@ -3,6 +3,8 @@ #include #include +#define AP_SIM_MAX_GPS_SENSORS 4 + #ifndef HAL_SIM_ADSB_ENABLED #define HAL_SIM_ADSB_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif @@ -23,6 +25,26 @@ #define AP_SIM_IS31FL3195_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif +#ifndef AP_SIM_LED_N_ENABLED +#define AP_SIM_LED_N_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && defined(WITH_SITL_RGBLED) +#endif + +#ifndef AP_SIM_GPIO_LED_1_ENABLED +#define AP_SIM_GPIO_LED_1_ENABLED AP_SIM_LED_N_ENABLED && 0 +#endif + +#ifndef AP_SIM_GPIO_LED_2_ENABLED +#define AP_SIM_GPIO_LED_2_ENABLED AP_SIM_LED_N_ENABLED && 0 +#endif + +#ifndef AP_SIM_GPIO_LED_3_ENABLED +#define AP_SIM_GPIO_LED_3_ENABLED AP_SIM_LED_N_ENABLED && 0 +#endif + +#ifndef AP_SIM_GPIO_LED_RGB_ENABLED +#define AP_SIM_GPIO_LED_RGB_ENABLED AP_SIM_LED_N_ENABLED && 0 +#endif + #ifndef AP_SIM_LOWEHEISER_ENABLED #define AP_SIM_LOWEHEISER_ENABLED AP_SIM_ENABLED && HAL_MAVLINK_BINDINGS_ENABLED #endif @@ -31,6 +53,14 @@ #define AP_SIM_SHIP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif +#ifndef AP_SIM_SLUNGPAYLOAD_ENABLED +#define AP_SIM_SLUNGPAYLOAD_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_SIM_FLIGHTAXIS_ENABLED +#define AP_SIM_FLIGHTAXIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + #ifndef AP_SIM_TSYS03_ENABLED #define AP_SIM_TSYS03_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif @@ -56,6 +86,10 @@ #define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) #endif +#ifndef AP_SIM_GPS_SBF_ENABLED +#define AP_SIM_GPS_SBF_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_SIM_GPS_TRIMBLE_ENABLED #define AP_SIM_GPS_TRIMBLE_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED #endif @@ -93,3 +127,20 @@ #ifndef AP_SIM_COMPASS_QMC5883L_ENABLED #define AP_SIM_COMPASS_QMC5883L_ENABLED AP_SIM_COMPASS_BACKEND_DEFAULT_ENABLED #endif + +#ifndef AP_SIM_STRATOBLIMP_ENABLED +#define AP_SIM_STRATOBLIMP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_SIM_GLIDER_ENABLED +#define AP_SIM_GLIDER_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_SIM_SOLOGIMBAL_ENABLED +#define AP_SIM_SOLOGIMBAL_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && HAL_MAVLINK_BINDINGS_ENABLED) +#endif + +#ifndef AP_SIM_GIMBAL_ENABLED +#define AP_SIM_GIMBAL_ENABLED (AP_SIM_SOLOGIMBAL_ENABLED) +#endif + diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index d8afa83ba0c694..a32fa79f727e87 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -44,7 +44,7 @@ class last_letter : public Aircraft { /* static object creator */ static Aircraft *create(const char *frame_str) { - return new last_letter(frame_str); + return NEW_NOTHROW last_letter(frame_str); } private: diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index abd099baf18099..e329ed232a9609 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -37,6 +37,10 @@ #endif #endif // SFML_JOYSTICK +#include "SIM_StratoBlimp.h" +#include "SIM_Glider.h" +#include "SIM_FlightAxis.h" + extern const AP_HAL::HAL& hal; #ifndef SIM_RATE_HZ_DEFAULT @@ -62,9 +66,19 @@ SIM *SIM::_singleton = nullptr; // table of user settable parameters const AP_Param::GroupInfo SIM::var_info[] = { - + + // @Param: DRIFT_SPEED + // @DisplayName: Gyro drift speed + // @Description: Gyro drift rate of change in degrees/second/minute AP_GROUPINFO("DRIFT_SPEED", 5, SIM, drift_speed, 0.05f), + // @Param: DRIFT_TIME + // @DisplayName: Gyro drift time + // @Description: Gyro drift duration of one full drift cycle (period in minutes) AP_GROUPINFO("DRIFT_TIME", 6, SIM, drift_time, 5), + // @Param: ENGINE_MUL + // @DisplayName: Engine failure thrust scaler + // @Description: Thrust from Motors in SIM_ENGINE_FAIL will be multiplied by this factor + // @Units: ms AP_GROUPINFO("ENGINE_MUL", 8, SIM, engine_mul, 1), // @Param: WIND_SPD // @DisplayName: Simulated Wind speed @@ -73,18 +87,33 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @User: Advanced AP_GROUPINFO("WIND_SPD", 9, SIM, wind_speed, 0), // @Param: WIND_DIR - // @DisplayName: Simulated Wind direction + // @DisplayName: Direction simulated wind is coming from // @Description: Allows you to set wind direction (true deg) in sim // @Units: deg // @User: Advanced AP_GROUPINFO("WIND_DIR", 10, SIM, wind_direction, 180), + // @Param: WIND_TURB // @DisplayName: Simulated Wind variation // @Description: Allows you to emulate random wind variations in sim // @Units: m/s // @User: Advanced AP_GROUPINFO("WIND_TURB", 11, SIM, wind_turbulance, 0), - AP_GROUPINFO("SERVO_SPEED", 16, SIM, servo_speed, 0.14), + + // @Param: WIND_TC + // @DisplayName: Wind variation time constant + // @Description: this controls the time over which wind changes take effect + // @Units: s + // @User: Advanced + AP_GROUPINFO("WIND_TC", 12, SIM, wind_change_tc, 5), + + // @Group: SERVO_ + // @Path: ./ServoModel.cpp + AP_SUBGROUPINFO(servo, "SERVO_", 16, SIM, ServoParams), + + // @Param: SONAR_ROT + // @DisplayName: Sonar rotation + // @Description: Sonar rotation from rotations enumeration AP_GROUPINFO("SONAR_ROT", 17, SIM, sonar_rot, Rotation::ROTATION_PITCH_270), // @Param: BATT_VOLTAGE // @DisplayName: Simulated battery voltage @@ -92,8 +121,22 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Units: V // @User: Advanced AP_GROUPINFO("BATT_VOLTAGE", 19, SIM, batt_voltage, 12.6f), + // @Param: BATT_CAP_AH + // @DisplayName: Simulated battery capacity + // @Description: Simulated battery capacity + // @Units: Ah + // @User: Advanced AP_GROUPINFO("BATT_CAP_AH", 20, SIM, batt_capacity_ah, 0), + // @Param: SONAR_GLITCH + // @DisplayName: Sonar glitch probablility + // @Description: Probablility a sonar glitch would happen + // @Range: 0 1 + // @User: Advanced AP_GROUPINFO("SONAR_GLITCH", 23, SIM, sonar_glitch, 0), + // @Param: SONAR_RND + // @DisplayName: Sonar noise factor + // @Description: Scaling factor for simulated sonar noise + // @User: Advanced AP_GROUPINFO("SONAR_RND", 24, SIM, sonar_noise, 0), // @Param: RC_FAIL // @DisplayName: Simulated RC signal failure @@ -118,7 +161,7 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Param: CAN_TYPE1 // @DisplayName: transport type for first CAN interface // @Description: transport type for first CAN interface - // @Values: 0:MulticastUDP,1:SocketCAN + // @Values: 0:None,1:MulticastUDP,2:SocketCAN // @User: Advanced AP_GROUPINFO("CAN_TYPE1", 30, SIM, can_transport[0], uint8_t(CANTransport::MulticastUDP)), #endif @@ -127,17 +170,25 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Param: CAN_TYPE2 // @DisplayName: transport type for second CAN interface // @Description: transport type for second CAN interface - // @Values: 0:MulticastUDP,1:SocketCAN + // @Values: 0:None,1:MulticastUDP,2:SocketCAN // @User: Advanced AP_GROUPINFO("CAN_TYPE2", 31, SIM, can_transport[1], uint8_t(CANTransport::MulticastUDP)), #endif + // @Param: SONAR_SCALE + // @DisplayName: Sonar conversion scale + // @Description: Sonar conversion scale from distance to voltage + // @Units: m/V AP_GROUPINFO("SONAR_SCALE", 32, SIM, sonar_scale, 12.1212f), // @Param: FLOW_ENABLE // @DisplayName: Opflow Enable // @Description: Enable simulated Optical Flow sensor // @Values: 0:Disable,1:Enabled AP_GROUPINFO("FLOW_ENABLE", 33, SIM, flow_enable, 0), + // @Param: TERRAIN + // @DisplayName: Terrain Enable + // @Description: Enable using terrain for height + // @Values: 0:Disable,1:Enabled AP_GROUPINFO("TERRAIN", 34, SIM, terrain_enable, 1), // @Param: FLOW_RATE // @DisplayName: Opflow Rate @@ -149,10 +200,28 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Description: Opflow data delay // @Units: ms AP_GROUPINFO("FLOW_DELAY", 36, SIM, flow_delay, 0), + // @Param: ADSB_COUNT + // @DisplayName: Number of ADSB aircrafts + // @Description: Total number of ADSB simulated aircraft AP_GROUPINFO("ADSB_COUNT", 45, SIM, adsb_plane_count, -1), + // @Param: ADSB_RADIUS + // @DisplayName: ADSB radius stddev of another aircraft + // @Description: Simulated standard deviation of radius in ADSB of another aircraft + // @Units: m AP_GROUPINFO("ADSB_RADIUS", 46, SIM, adsb_radius_m, 10000), + // @Param: ADSB_ALT + // @DisplayName: ADSB altitude of another aircraft + // @Description: Simulated ADSB altitude of another aircraft + // @Units: m AP_GROUPINFO("ADSB_ALT", 47, SIM, adsb_altitude_m, 1000), + // @Param: PIN_MASK + // @DisplayName: GPIO emulation + // @Description: SITL GPIO emulation AP_GROUPINFO("PIN_MASK", 50, SIM, pin_mask, 0), + // @Param: ADSB_TX + // @DisplayName: ADSB transmit enable + // @Description: ADSB transceiever enable and disable + // @Values: 0:Transceiever disable, 1:Transceiever enable AP_GROUPINFO("ADSB_TX", 51, SIM, adsb_tx, 0), // @Param: SPEEDUP // @DisplayName: Sim Speedup @@ -174,10 +243,12 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Units: m // @Vector3Parameter: 1 AP_GROUPINFO("FLOW_POS", 56, SIM, optflow_pos_offset, 0), + // @Param: ENGINE_FAIL + // @DisplayName: Engine Fail Mask + // @Description: mask of motors which SIM_ENGINE_MUL will be applied to + // @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 AP_GROUPINFO("ENGINE_FAIL", 58, SIM, engine_fail, 0), -#if AP_SIM_SHIP_ENABLED - AP_SUBGROUPINFO(shipsim, "SHIP_", 59, SIM, ShipSim), -#endif + AP_SUBGROUPINFO(models, "", 59, SIM, SIM::ModelParm), AP_SUBGROUPEXTENSION("", 60, SIM, var_mag), #if HAL_SIM_GPS_ENABLED AP_SUBGROUPEXTENSION("", 61, SIM, var_gps), @@ -189,13 +260,37 @@ const AP_Param::GroupInfo SIM::var_info[] = { // second table of user settable parameters for SITL. const AP_Param::GroupInfo SIM::var_info2[] = { + // @Param: TEMP_START + // @DisplayName: Start temperature + // @Description: Baro start temperature + // @Units: degC + // @User: Advanced AP_GROUPINFO("TEMP_START", 1, SIM, temp_start, 25), + // @Param: TEMP_BRD_OFF + // @DisplayName: Baro temperature offset + // @Description: Barometer board temperature offset from atmospheric temperature + // @Units: degC + // @User: Advanced AP_GROUPINFO("TEMP_BRD_OFF", 2, SIM, temp_board_offset, 20), + // @Param: TEMP_TCONST + // @DisplayName: Warmup time constant + // @Description: Barometer warmup temperature time constant + // @Units: degC + // @User: Advanced AP_GROUPINFO("TEMP_TCONST", 3, SIM, temp_tconst, 30), - AP_GROUPINFO("TEMP_BFACTOR", 4, SIM, temp_baro_factor, 0), + // @Param: TEMP_BFACTOR + // @DisplayName: Baro temperature factor + // @Description: A pressure change with temperature that closely matches what has been observed with a ICM-20789 + // @User: Advanced + AP_GROUPINFO("TEMP_BFACTOR", 4, SIM, temp_baro_factor, 0), + // @Param: WIND_DIR_Z + // @DisplayName: Simulated wind vertical direction + // @Description: Allows you to set vertical wind direction (true deg) in sim. 0 means pure horizontal wind. 90 means pure updraft. + // @Units: deg + // @User: Advanced AP_GROUPINFO("WIND_DIR_Z", 10, SIM, wind_dir_z, 0), - // @Param: WIND_T_ + // @Param: WIND_T // @DisplayName: Wind Profile Type // @Description: Selects how wind varies from surface to WIND_T_ALT // @Values: 0:square law,1: none, 2:linear-see WIND_T_COEF @@ -212,6 +307,9 @@ const AP_Param::GroupInfo SIM::var_info2[] = { // @Description: For linear wind profile,wind is reduced by (Altitude-WIND_T_ALT) x this value // @User: Advanced AP_GROUPINFO("WIND_T_COEF", 17, SIM, wind_type_coef, 0.01f), + // @Param: RC_CHANCOUNT + // @DisplayName: RC channel count + // @Description: SITL RC channel count AP_GROUPINFO("RC_CHANCOUNT",21, SIM, rc_chancount, 16), // @Group: SPR_ // @Path: ./SIM_Sprayer.cpp @@ -235,39 +333,104 @@ const AP_Param::GroupInfo SIM::var_info2[] = { // @Path: ./SIM_Parachute.cpp AP_SUBGROUPINFO(parachute_sim, "PARA_", 27, SIM, Parachute), - // enable bandwidth limitting on telemetry ports: + // @Param: BAUDLIMIT_EN + // @DisplayName: Telemetry bandwidth limitting + // @Description: SITL enable bandwidth limitting on telemetry ports with non-zero values AP_GROUPINFO("BAUDLIMIT_EN", 28, SIM, telem_baudlimit_enable, 0), // @Group: PLD_ // @Path: ./SIM_Precland.cpp AP_SUBGROUPINFO(precland_sim, "PLD_", 29, SIM, SIM_Precland), - // apply a force to the vehicle over a period of time: + // @Param: SHOVE_X + // @DisplayName: Acceleration of shove x + // @Description: Acceleration of shove to vehicle in x axis + // @Units: m/s/s AP_GROUPINFO("SHOVE_X", 30, SIM, shove.x, 0), + // @Param: SHOVE_Y + // @DisplayName: Acceleration of shove y + // @Description: Acceleration of shove to vehicle in y axis + // @Units: m/s/s AP_GROUPINFO("SHOVE_Y", 31, SIM, shove.y, 0), + // @Param: SHOVE_Z + // @DisplayName: Acceleration of shove z + // @Description: Acceleration of shove to vehicle in z axis + // @Units: m/s/s AP_GROUPINFO("SHOVE_Z", 32, SIM, shove.z, 0), + // @Param: SHOVE_TIME + // @DisplayName: Time length for shove + // @Description: Force to the vehicle over a period of time + // @Units: ms AP_GROUPINFO("SHOVE_TIME", 33, SIM, shove.t, 0), - // optical flow sensor measurement noise in rad/sec // @Param: FLOW_RND // @DisplayName: Opflow noise - // @Description: Optical Flow sensor measurement noise in rad/sec + // @Description: Optical Flow sensor measurement noise + // @Units: rad/s AP_GROUPINFO("FLOW_RND", 34, SIM, flow_noise, 0.05f), + // @Param: TWIST_X + // @DisplayName: Twist x + // @Description: Rotational acceleration of twist x axis + // @Units: rad/s/s AP_GROUPINFO("TWIST_X", 37, SIM, twist.x, 0), + // @Param: TWIST_Y + // @DisplayName: Twist y + // @Description: Rotational acceleration of twist y axis + // @Units: rad/s/s AP_GROUPINFO("TWIST_Y", 38, SIM, twist.y, 0), + // @Param: TWIST_Z + // @DisplayName: Twist z + // @Description: Rotational acceleration of twist z axis + // @Units: rad/s/s AP_GROUPINFO("TWIST_Z", 39, SIM, twist.z, 0), + // @Param: TWIST_TIME + // @DisplayName: Twist time + // @Description: Time that twist is applied on the vehicle + // @Units: ms AP_GROUPINFO("TWIST_TIME", 40, SIM, twist.t, 0), + // @Param: GND_BEHAV + // @DisplayName: Ground behavior + // @Description: Ground behavior of aircraft (tailsitter, no movement, forward only) AP_GROUPINFO("GND_BEHAV", 41, SIM, gnd_behav, -1), // sailboat wave and tide simulation parameters + + // @Param: WAVE_ENABLE + // @DisplayName: Wave enable + // @Description: Wave enable and modes + // @Values: 0:disabled, 1: roll and pitch, 2: roll and pitch and heave AP_GROUPINFO("WAVE_ENABLE", 44, SIM, wave.enable, 0.0f), + // @Param: WAVE_LENGTH + // @DisplayName: Wave length + // @Description: Wave length in SITL + // @Units: m AP_GROUPINFO("WAVE_LENGTH", 45, SIM, wave.length, 10.0f), + // @Param: WAVE_AMP + // @DisplayName: Wave amplitude + // @Description: Wave amplitude in SITL + // @Units: m AP_GROUPINFO("WAVE_AMP", 46, SIM, wave.amp, 0.5f), + // @Param: WAVE_DIR + // @DisplayName: Wave direction + // @Description: Direction wave is coming from + // @Units: deg AP_GROUPINFO("WAVE_DIR", 47, SIM, wave.direction, 0.0f), + // @Param: WAVE_SPEED + // @DisplayName: Wave speed + // @Description: Wave speed in SITL + // @Units: m/s AP_GROUPINFO("WAVE_SPEED", 48, SIM, wave.speed, 0.5f), + // @Param: TIDE_DIR + // @DisplayName: Tide direction + // @Description: Tide direction wave is coming from + // @Units: deg AP_GROUPINFO("TIDE_DIR", 49, SIM, tide.direction, 0.0f), + // @Param: TIDE_SPEED + // @DisplayName: Tide speed + // @Description: Tide speed in simulation + // @Units: m/s AP_GROUPINFO("TIDE_SPEED", 50, SIM, tide.speed, 0.0f), // the following coordinates are for CMAC, in Canberra @@ -291,8 +454,10 @@ const AP_Param::GroupInfo SIM::var_info2[] = { // @Description: Specifies vehicle's startup heading (0-360) // @User: Advanced AP_GROUPINFO("OPOS_HDG", 54, SIM, opos.hdg, 353.0f), - - // extra delay per main loop + // @Param: LOOP_DELAY + // @DisplayName: Extra delay per main loop + // @Description: Extra time delay per main loop + // @Units: us AP_GROUPINFO("LOOP_DELAY", 55, SIM, loop_delay, 0), // @Path: ./SIM_Buzzer.cpp @@ -301,21 +466,34 @@ const AP_Param::GroupInfo SIM::var_info2[] = { // @Path: ./SIM_ToneAlarm.cpp AP_SUBGROUPINFO(tonealarm_sim, "TA_", 57, SIM, ToneAlarm), + // @Param: EFI_TYPE + // @DisplayName: Type of Electronic Fuel Injection + // @Description: Different types of Electronic Fuel Injection (EFI) systems + // @Values: 0:None,1:MegaSquirt EFI system, 2:Löweheiser EFI system, 8:Hirth engines AP_GROUPINFO("EFI_TYPE", 58, SIM, efi_type, SIM::EFI_TYPE_NONE), // 59 was SAFETY_STATE - // motor harmonics + // @Param: VIB_MOT_HMNC + // @DisplayName: Motor harmonics + // @Description: Motor harmonics generated in SITL AP_GROUPINFO("VIB_MOT_HMNC", 60, SIM, vibe_motor_harmonics, 1), - - // motor mask, allowing external simulators to mark motors + // @Param: VIB_MOT_MASK + // @DisplayName: Motor mask + // @Description: Motor mask, allowing external simulators to mark motors AP_GROUPINFO("VIB_MOT_MASK", 5, SIM, vibe_motor_mask, 0), - - // max motor vibration frequency + // @Param: VIB_MOT_MAX + // @DisplayName: Max motor vibration frequency + // @Description: Max frequency to use as baseline for adding motor noise for the gyros and accels + // @Units: Hz AP_GROUPINFO("VIB_MOT_MAX", 61, SIM, vibe_motor, 0.0f), - // minimum throttle for simulated ins noise + // @Param: INS_THR_MIN + // @DisplayName: Minimum throttle INS noise + // @Description: Minimum throttle for simulated ins noise AP_GROUPINFO("INS_THR_MIN", 62, SIM, ins_noise_throttle_min, 0.1f), - // amplitude scaling of motor noise relative to gyro/accel noise + // @Param: VIB_MOT_MULT + // @DisplayName: Vibration motor scale + // @Description: Amplitude scaling of motor noise relative to gyro/accel noise AP_GROUPINFO("VIB_MOT_MULT", 63, SIM, vibe_motor_scale, 1.0f), @@ -325,11 +503,20 @@ const AP_Param::GroupInfo SIM::var_info2[] = { // third table of user settable parameters for SITL. const AP_Param::GroupInfo SIM::var_info3[] = { + // @Param: ODOM_ENABLE + // @DisplayName: Odometry enable + // @Description: SITL odometry enabl + // @Values: 0:Disable, 1:Enable AP_GROUPINFO("ODOM_ENABLE", 1, SIM, odom_enable, 0), + // @Param: LED_LAYOUT + // @DisplayName: LED layout + // @Description: LED layout config value AP_GROUPINFO("LED_LAYOUT", 11, SIM, led_layout, 0), - // Scenario for thermalling simulation, for soaring + // @Param: THML_SCENARI + // @DisplayName: Thermal scenarios + // @Description: Scenario for thermalling simulation, for soaring AP_GROUPINFO("THML_SCENARI", 12, SIM, thermal_scenario, 0), // @Param: VICON_POS_X @@ -425,6 +612,10 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @User: Advanced AP_GROUPINFO("VICON_VGLI", 21, SIM, vicon_vel_glitch, 0), + // @Param: RATE_HZ + // @DisplayName: Loop rate + // @Description: SITL Loop rate + // @Units: Hz AP_GROUPINFO("RATE_HZ", 22, SIM, loop_rate_hz, SIM_RATE_HZ_DEFAULT), // @Param: IMU_COUNT @@ -442,56 +633,33 @@ const AP_Param::GroupInfo SIM::var_info3[] = { AP_SUBGROUPINFO(ie24_sim, "IE24_", 32, SIM, IntelligentEnergy24), // user settable barometer parameters + + // @Param: BARO_COUNT + // @DisplayName: Baro count + // @Description: Number of simulated baros to create in SITL + // @Range: 0 3 AP_GROUPINFO("BARO_COUNT", 33, SIM, baro_count, 2), - AP_SUBGROUPINFO(baro[0], "BARO_", 34, SIM, SIM::BaroParm), + // @Group: BARO_ + // @Path: ./SITL_Baro.cpp + AP_SUBGROUPINFO(baro[0], "BARO_", 34, SIM, BaroParm), #if BARO_MAX_INSTANCES > 1 - AP_SUBGROUPINFO(baro[1], "BAR2_", 35, SIM, SIM::BaroParm), + // @Group: BAR2_ + // @Path: ./SITL_Baro.cpp + AP_SUBGROUPINFO(baro[1], "BAR2_", 35, SIM, BaroParm), #endif #if BARO_MAX_INSTANCES > 2 - AP_SUBGROUPINFO(baro[2], "BAR3_", 36, SIM, SIM::BaroParm), + // @Group: BAR3_ + // @Path: ./SITL_Baro.cpp + AP_SUBGROUPINFO(baro[2], "BAR3_", 36, SIM, BaroParm), #endif - AP_GROUPINFO("TIME_JITTER", 37, SIM, loop_time_jitter_us, 0), - - // user settable parameters for the 1st barometer - // @Param: BARO_RND - // @DisplayName: Baro Noise - // @Description: Amount of (evenly-distributed) noise injected into the 1st baro - // @Units: m - // @User: Advanced - - // @Param: BARO_GLITCH - // @DisplayName: Baro Glitch - // @Description: Glitch for 1st baro - // @Units: m - // @User: Advanced - - // user settable parameters for the 2nd barometer - // @Param: BAR2_RND - // @DisplayName: Baro2 Noise - // @Description: Amount of (evenly-distributed) noise injected into the 2nd baro - // @Units: m - // @User: Advanced - - // @Param: BAR2_GLITCH - // @DisplayName: Baro2 Glitch - // @Description: Glitch for 2nd baro - // @Units: m - // @User: Advanced - - // user settable parameters for the 3rd barometer - // @Param: BAR3_RND - // @DisplayName: Baro3 Noise - // @Description: Amount of (evenly-distributed) noise injected into the 3rd baro - // @Units: m - // @User: Advanced - - // @Param: BAR3_GLITCH - // @DisplayName: Baro3 Glitch - // @Description: Glitch for 2nd baro - // @Units: m + // @Param: TIME_JITTER + // @DisplayName: Loop time jitter + // @Description: Upper limit of random jitter in loop time + // @Units: us // @User: Advanced + AP_GROUPINFO("TIME_JITTER", 37, SIM, loop_time_jitter_us, 0), // @Param: ESC_TELEM // @DisplayName: Simulated ESC Telemetry @@ -499,6 +667,10 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @User: Advanced AP_GROUPINFO("ESC_TELEM", 40, SIM, esc_telem, 1), + // @Param: ESC_ARM_RPM + // @DisplayName: ESC RPM when armed + // @Description: Simulated RPM when motors are armed + // @User: Advanced AP_GROUPINFO("ESC_ARM_RPM", 41, SIM, esc_rpm_armed, 0.0f), // @Param: UART_LOSS @@ -537,7 +709,7 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @Range: 10 100 AP_GROUPINFO("OSD_ROWS", 54, SIM, osd_rows, 16), #endif - + #ifdef SFML_JOYSTICK AP_SUBGROUPEXTENSION("", 63, SIM, var_sfml_joystick), #endif // SFML_JOYSTICK @@ -545,203 +717,42 @@ const AP_Param::GroupInfo SIM::var_info3[] = { AP_GROUPEND }; -// user settable parameters for the barometers -const AP_Param::GroupInfo SIM::BaroParm::var_info[] = { - AP_GROUPINFO("RND", 1, SIM::BaroParm, noise, 0.2f), - AP_GROUPINFO("DRIFT", 2, SIM::BaroParm, drift, 0), - AP_GROUPINFO("DISABLE", 3, SIM::BaroParm, disable, 0), - AP_GROUPINFO("GLITCH", 4, SIM::BaroParm, glitch, 0), - AP_GROUPINFO("FREEZE", 5, SIM::BaroParm, freeze, 0), - AP_GROUPINFO("DELAY", 6, SIM::BaroParm, delay, 0), - - // wind coeffients - AP_GROUPINFO("WCF_FWD", 7, SIM::BaroParm, wcof_xp, 0.0), - AP_GROUPINFO("WCF_BAK", 8, SIM::BaroParm, wcof_xn, 0.0), - AP_GROUPINFO("WCF_RGT", 9, SIM::BaroParm, wcof_yp, 0.0), - AP_GROUPINFO("WCF_LFT", 10, SIM::BaroParm, wcof_yn, 0.0), - AP_GROUPINFO("WCF_UP", 11, SIM::BaroParm, wcof_zp, 0.0), - AP_GROUPINFO("WCF_DN", 12, SIM::BaroParm, wcof_zn, 0.0), - AP_GROUPEND -}; #if HAL_SIM_GPS_ENABLED // GPS SITL parameters const AP_Param::GroupInfo SIM::var_gps[] = { - // @Param: GPS_DISABLE - // @DisplayName: GPS 1 disable - // @Description: Disables GPS 1 - // @Values: 0:Enable, 1:GPS Disabled - // @User: Advanced - AP_GROUPINFO("GPS_DISABLE", 1, SIM, gps_disable[0], 0), - // @Param: GPS_LAG_MS - // @DisplayName: GPS 1 Lag - // @Description: GPS 1 lag - // @Units: ms - // @User: Advanced - AP_GROUPINFO("GPS_LAG_MS", 2, SIM, gps_delay_ms[0], 100), - // @Param: GPS_TYPE - // @DisplayName: GPS 1 type - // @Description: Sets the type of simulation used for GPS 1 - // @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP2, 11:Trimble, 19:MSP - // @User: Advanced - AP_GROUPINFO("GPS_TYPE", 3, SIM, gps_type[0], GPS::Type::UBLOX), - // @Param: GPS_BYTELOSS - // @DisplayName: GPS Byteloss - // @Description: Percent of bytes lost from GPS 1 - // @Units: % - // @User: Advanced - AP_GROUPINFO("GPS_BYTELOSS", 4, SIM, gps_byteloss[0], 0), - // @Param: GPS_NUMSATS - // @DisplayName: GPS 1 Num Satellites - // @Description: Number of satellites GPS 1 has in view - AP_GROUPINFO("GPS_NUMSATS", 5, SIM, gps_numsats[0], 10), - // @Param: GPS_GLITCH - // @DisplayName: GPS 1 Glitch - // @Description: Glitch offsets of simulated GPS 1 sensor - // @Vector3Parameter: 1 - // @User: Advanced - AP_GROUPINFO("GPS_GLITCH", 6, SIM, gps_glitch[0], 0), - // @Param: GPS_HZ - // @DisplayName: GPS 1 Hz - // @Description: GPS 1 Update rate - // @Units: Hz - AP_GROUPINFO("GPS_HZ", 7, SIM, gps_hertz[0], 5), - // @Param: GPS_DRIFTALT - // @DisplayName: GPS 1 Altitude Drift - // @Description: GPS 1 altitude drift error - // @Units: m - // @User: Advanced - AP_GROUPINFO("GPS_DRIFTALT", 8, SIM, gps_drift_alt[0], 0), - // @Param: GPS_POS - // @DisplayName: GPS 1 Position - // @Description: GPS 1 antenna phase center position relative to the body frame origin - // @Units: m - // @Vector3Parameter: 1 - AP_GROUPINFO("GPS_POS", 9, SIM, gps_pos_offset[0], 0), - // @Param: GPS_NOISE - // @DisplayName: GPS 1 Noise - // @Description: Amplitude of the GPS1 altitude error - // @Units: m - // @User: Advanced - AP_GROUPINFO("GPS_NOISE", 10, SIM, gps_noise[0], 0), - // @Param: GPS_LOCKTIME - // @DisplayName: GPS 1 Lock Time - // @Description: Delay in seconds before GPS1 acquires lock - // @Units: s - // @User: Advanced - AP_GROUPINFO("GPS_LOCKTIME", 11, SIM, gps_lock_time[0], 0), - // @Param: GPS_ALT_OFS - // @DisplayName: GPS 1 Altitude Offset - // @Description: GPS 1 Altitude Error - // @Units: m - AP_GROUPINFO("GPS_ALT_OFS", 12, SIM, gps_alt_offset[0], 0), - // @Param: GPS_HDG - // @DisplayName: GPS 1 Heading - // @Description: Enable GPS1 output of NMEA heading HDT sentence or UBLOX_RELPOSNED - // @Values: 0:Disabled, 1:Enabled - // @User: Advanced - AP_GROUPINFO("GPS_HDG", 13, SIM, gps_hdg_enabled[0], SIM::GPS_HEADING_NONE), - // @Param: GPS_ACC - // @DisplayName: GPS 1 Accuracy - // @Description: GPS 1 Accuracy - // @User: Advanced - AP_GROUPINFO("GPS_ACC", 14, SIM, gps_accuracy[0], 0.3), - // @Param: GPS_VERR - // @DisplayName: GPS 1 Velocity Error - // @Description: GPS 1 Velocity Error Offsets in NED - // @Vector3Parameter: 1 - // @User: Advanced - AP_GROUPINFO("GPS_VERR", 15, SIM, gps_vel_err[0], 0), - // @Param: GPS_JAM - // @DisplayName: GPS jamming enable - // @Description: Enable simulated GPS jamming - // @User: Advanced - // @Values: 0:Disabled, 1:Enabled - AP_GROUPINFO("GPS_JAM", 16, SIM, gps_jam[0], 0), - // @Param: GPS2_DISABLE - // @DisplayName: GPS 2 disable - // @Description: Disables GPS 2 - // @Values: 0:Enable, 1:GPS Disabled - // @User: Advanced - AP_GROUPINFO("GPS2_DISABLE", 30, SIM, gps_disable[1], 1), - // @Param: GPS2_LAG_MS - // @DisplayName: GPS 2 Lag - // @Description: GPS 2 lag in ms - // @Units: ms - // @User: Advanced - AP_GROUPINFO("GPS2_LAG_MS", 31, SIM, gps_delay_ms[1], 100), - // @Param: GPS2_TYPE - // @CopyFieldsFrom: SIM_GPS_TYPE - // @DisplayName: GPS 2 type - // @Description: Sets the type of simulation used for GPS 2 - AP_GROUPINFO("GPS2_TYPE", 32, SIM, gps_type[1], GPS::Type::UBLOX), - // @Param: GPS2_BYTELOS - // @DisplayName: GPS 2 Byteloss - // @Description: Percent of bytes lost from GPS 2 - // @Units: % - // @User: Advanced - AP_GROUPINFO("GPS2_BYTELOS", 33, SIM, gps_byteloss[1], 0), - // @Param: GPS2_NUMSATS - // @DisplayName: GPS 2 Num Satellites - // @Description: Number of satellites GPS 2 has in view - AP_GROUPINFO("GPS2_NUMSATS", 34, SIM, gps_numsats[1], 10), - // @Param: GPS2_GLTCH - // @DisplayName: GPS 2 Glitch - // @Description: Glitch offsets of simulated GPS 2 sensor - // @Vector3Parameter: 1 - // @User: Advanced - AP_GROUPINFO("GPS2_GLTCH", 35, SIM, gps_glitch[1], 0), - // @Param: GPS2_HZ - // @DisplayName: GPS 2 Hz - // @Description: GPS 2 Update rate - // @Units: Hz - AP_GROUPINFO("GPS2_HZ", 36, SIM, gps_hertz[1], 5), - // @Param: GPS2_DRFTALT - // @DisplayName: GPS 2 Altitude Drift - // @Description: GPS 2 altitude drift error - // @Units: m - // @User: Advanced - AP_GROUPINFO("GPS2_DRFTALT", 37, SIM, gps_drift_alt[1], 0), - // @Param: GPS2_POS - // @DisplayName: GPS 2 Position - // @Description: GPS 2 antenna phase center position relative to the body frame origin - // @Units: m - // @Vector3Parameter: 1 - AP_GROUPINFO("GPS2_POS", 38, SIM, gps_pos_offset[1], 0), - // @Param: GPS2_NOISE - // @DisplayName: GPS 2 Noise - // @Description: Amplitude of the GPS2 altitude error - // @Units: m - // @User: Advanced - AP_GROUPINFO("GPS2_NOISE", 39, SIM, gps_noise[1], 0), - // @Param: GPS2_LCKTIME - // @DisplayName: GPS 2 Lock Time - // @Description: Delay in seconds before GPS2 acquires lock - // @Units: s - // @User: Advanced - AP_GROUPINFO("GPS2_LCKTIME", 40, SIM, gps_lock_time[1], 0), - // @Param: GPS2_ALT_OFS - // @DisplayName: GPS 2 Altitude Offset - // @Description: GPS 2 Altitude Error - // @Units: m - AP_GROUPINFO("GPS2_ALT_OFS", 41, SIM, gps_alt_offset[1], 0), - // @Param: GPS2_HDG - // @DisplayName: GPS 2 Heading - // @Description: Enable GPS2 output of NMEA heading HDT sentence or UBLOX_RELPOSNED - // @Values: 0:Disabled, 1:Enabled - // @User: Advanced - AP_GROUPINFO("GPS2_HDG", 42, SIM, gps_hdg_enabled[1], SIM::GPS_HEADING_NONE), - // @Param: GPS2_ACC - // @DisplayName: GPS 2 Accuracy - // @Description: GPS 2 Accuracy - // @User: Advanced - AP_GROUPINFO("GPS2_ACC", 43, SIM, gps_accuracy[1], 0.3), - // @Param: GPS2_VERR - // @DisplayName: GPS 2 Velocity Error - // @Description: GPS 2 Velocity Error Offsets in NED - // @Vector3Parameter: 1 - // @User: Advanced - AP_GROUPINFO("GPS2_VERR", 44, SIM, gps_vel_err[1], 0), + // 1 was GPS_DISABLE + // 2 was GPS_LAG_MS + // 3 was GPS_TYPE + // 4 was GPS_BYTELOSS + // 5 was GPS_NUMSATS + // 6 was GPS_GLITCH + // 7 was GPS_HZ + // 8 was GPS_DRIFTALT + // 9 was GPS_POS + // 10 was GPS_NOISE + // 11 was GPS_LOCKTIME + // 12 was GPS_ALT_OFS + // 13 was GPS_HDG + // 14 was GPS_ACC + // 15 was GPS_VERR + // 16 was GPS_JAM + + // 30 was GPS2_DISABLE + // 31 was GPS2_LAG_MS + // 32 was GPS2_TYPE + // 33 was GPS2_BYTELOSS + // 34 was GPS2_NUMSATS + // 35 was GPS2_GLITCH + // 36 was GPS2_HZ + // 37 was GPS2_DRIFTALT + // 38 was GPS2_POS + // 39 was GPS2_NOISE + // 40 was GPS2_LOCKTIME + // 41 was GPS2_ALT_OFS + // 42 was GPS2_HDG + // 43 was GPS2_ACC + // 44 was GPS2_VERR // @Param: INIT_LAT_OFS // @DisplayName: Initial Latitude Offset @@ -761,51 +772,117 @@ const AP_Param::GroupInfo SIM::var_gps[] = { // @Description: Log number for GPS:update_file() AP_GROUPINFO("GPS_LOG_NUM", 48, SIM, gps_log_num, 0), - // @Param: GPS2_JAM - // @DisplayName: GPS jamming enable - // @Description: Enable simulated GPS jamming - // @User: Advanced - // @Values: 0:Disabled, 1:Enabled - AP_GROUPINFO("GPS2_JAM", 49, SIM, gps_jam[1], 0), + // 49 was GPS2_JAM - AP_GROUPEND +#if AP_SIM_MAX_GPS_SENSORS > 0 + // @Group: GPS1_ + // @Path: ./SIM_GPS.cpp + AP_SUBGROUPINFO(gps[0], "GPS1_", 50, SIM, GPSParms), +#endif +#if AP_SIM_MAX_GPS_SENSORS > 1 + // @Group: GPS2_ + // @Path: ./SIM_GPS.cpp + AP_SUBGROUPINFO(gps[1], "GPS2_", 51, SIM, GPSParms), +#endif +#if AP_SIM_MAX_GPS_SENSORS > 2 + // @Group: GPS3_ + // @Path: ./SIM_GPS.cpp + AP_SUBGROUPINFO(gps[2], "GPS3_", 52, SIM, GPSParms), +#endif +#if AP_SIM_MAX_GPS_SENSORS > 3 + // @Group: GPS4_ + // @Path: ./SIM_GPS.cpp + AP_SUBGROUPINFO(gps[3], "GPS4_", 53, SIM, GPSParms), +#endif + + AP_GROUPEND }; #endif // HAL_SIM_GPS_ENABLED // Mag SITL parameters const AP_Param::GroupInfo SIM::var_mag[] = { + // @Param: MAG_RND + // @DisplayName: Mag motor noise factor + // @Description: Scaling factor for simulated vibration from motors + // @User: Advanced AP_GROUPINFO("MAG_RND", 1, SIM, mag_noise, 0), AP_GROUPINFO("MAG_MOT", 2, SIM, mag_mot, 0), + // @Param: MAG_DELAY + // @DisplayName: Mag measurement delay + // @Description: Magnetometer measurement delay + // @Units: ms + // @User: Advanced AP_GROUPINFO("MAG_DELAY", 3, SIM, mag_delay, 0), AP_GROUPINFO("MAG1_OFS", 4, SIM, mag_ofs[0], 0), AP_GROUPINFO("MAG_ALY", 5, SIM, mag_anomaly_ned, 0), + // @Param: MAG_ALY_HGT + // @DisplayName: Magnetic anomaly height + // @Description: Height above ground where anomally strength has decayed to 1/8 of the ground level value + // @Units: m + // @User: Advanced AP_GROUPINFO("MAG_ALY_HGT", 6, SIM, mag_anomaly_hgt, 1.0f), AP_GROUPINFO("MAG1_DIA", 7, SIM, mag_diag[0], 0), AP_GROUPINFO("MAG1_ODI", 8, SIM, mag_offdiag[0], 0), + // @Param: MAG1_ORIENT + // @DisplayName: MAG1 Orientation + // @Description: MAG1 external compass orientation + // @User: Advanced AP_GROUPINFO("MAG1_ORIENT", 9, SIM, mag_orient[0], 0), + // @Param: MAG1_SCALING + // @DisplayName: MAG1 Scaling factor + // @Description: Scale the compass 1 to simulate sensor scale factor errors + // @User: Advanced AP_GROUPINFO("MAG1_SCALING", 10, SIM, mag_scaling[0], 1), // @Param: MAG1_DEVID // @DisplayName: MAG1 Device ID // @Description: Device ID of simulated compass 1 // @User: Advanced AP_GROUPINFO("MAG1_DEVID", 11, SIM, mag_devid[0], 97539), + // @Param: MAG2_DEVID + // @DisplayName: MAG2 Device ID + // @Description: Device ID of simulated compass 2 + // @User: Advanced AP_GROUPINFO("MAG2_DEVID", 12, SIM, mag_devid[1], 131874), #if MAX_CONNECTED_MAGS > 2 + // @Param: MAG3_DEVID + // @DisplayName: MAG3 Device ID + // @Description: Device ID of simulated compass 3 + // @User: Advanced AP_GROUPINFO("MAG3_DEVID", 13, SIM, mag_devid[2], 263178), #endif #if MAX_CONNECTED_MAGS > 3 + // @Param: MAG4_DEVID + // @DisplayName: MAG2 Device ID + // @Description: Device ID of simulated compass 4 + // @User: Advanced AP_GROUPINFO("MAG4_DEVID", 14, SIM, mag_devid[3], 97283), #endif #if MAX_CONNECTED_MAGS > 4 + // @Param: MAG5_DEVID + // @DisplayName: MAG5 Device ID + // @Description: Device ID of simulated compass 5 + // @User: Advanced AP_GROUPINFO("MAG5_DEVID", 15, SIM, mag_devid[4], 97795), #endif #if MAX_CONNECTED_MAGS > 5 + // @Param: MAG6_DEVID + // @DisplayName: MAG6 Device ID + // @Description: Device ID of simulated compass 6 + // @User: Advanced AP_GROUPINFO("MAG6_DEVID", 16, SIM, mag_devid[5], 98051), #endif #if MAX_CONNECTED_MAGS > 6 + // @Param: MAG7_DEVID + // @DisplayName: MAG7 Device ID + // @Description: Device ID of simulated compass 7 + // @User: Advanced AP_GROUPINFO("MAG7_DEVID", 17, SIM, mag_devid[6], 0), #endif #if MAX_CONNECTED_MAGS > 7 + // @Param: MAG8_DEVID + // @DisplayName: MAG8 Device ID + // @Description: Device ID of simulated compass 8 + // @User: Advanced AP_GROUPINFO("MAG8_DEVID", 18, SIM, mag_devid[7], 0), #endif // @Param: MAG1_FAIL @@ -818,6 +895,10 @@ const AP_Param::GroupInfo SIM::var_mag[] = { AP_GROUPINFO("MAG2_OFS", 19, SIM, mag_ofs[1], 0), AP_GROUPINFO("MAG2_DIA", 20, SIM, mag_diag[1], 0), AP_GROUPINFO("MAG2_ODI", 21, SIM, mag_offdiag[1], 0), + // @Param: MAG2_ORIENT + // @DisplayName: MAG2 Orientation + // @Description: MAG2 external compass orientation + // @User: Advanced AP_GROUPINFO("MAG2_ORIENT", 22, SIM, mag_orient[1], 0), // @Param: MAG2_FAIL // @DisplayName: MAG2 Failure @@ -825,6 +906,10 @@ const AP_Param::GroupInfo SIM::var_mag[] = { // @Values: 0:Disabled, 1:MAG2 Failure // @User: Advanced AP_GROUPINFO("MAG2_FAIL", 27, SIM, mag_fail[1], 0), + // @Param: MAG2_SCALING + // @DisplayName: MAG2 Scaling factor + // @Description: Scale the compass 2 to simulate sensor scale factor errors + // @User: Advanced AP_GROUPINFO("MAG2_SCALING", 28, SIM, mag_scaling[1], 1), #endif #if HAL_COMPASS_MAX_SENSORS > 2 @@ -837,7 +922,15 @@ const AP_Param::GroupInfo SIM::var_mag[] = { // @Values: 0:Disabled, 1:MAG3 Failure // @User: Advanced AP_GROUPINFO("MAG3_FAIL", 29, SIM, mag_fail[2], 0), + // @Param: MAG3_SCALING + // @DisplayName: MAG3 Scaling factor + // @Description: Scale the compass 3 to simulate sensor scale factor errors + // @User: Advanced AP_GROUPINFO("MAG3_SCALING", 30, SIM, mag_scaling[2], 1), + // @Param: MAG3_ORIENT + // @DisplayName: MAG3 Orientation + // @Description: MAG3 external compass orientation + // @User: Advanced AP_GROUPINFO("MAG3_ORIENT", 36, SIM, mag_orient[2], 0), #endif @@ -869,9 +962,21 @@ const AP_Param::GroupInfo SIM::var_sfml_joystick[] = { // INS SITL parameters const AP_Param::GroupInfo SIM::var_ins[] = { #if HAL_INS_TEMPERATURE_CAL_ENABLE + // @Param: IMUT_START + // @DisplayName: IMU temperature start + // @Description: Starting IMU temperature of a curve AP_GROUPINFO("IMUT_START", 1, SIM, imu_temp_start, 25), + // @Param: IMUT_END + // @DisplayName: IMU temperature end + // @Description: Ending IMU temperature of a curve AP_GROUPINFO("IMUT_END", 2, SIM, imu_temp_end, 45), + // @Param: IMUT_TCONST + // @DisplayName: IMU temperature time constant + // @Description: IMU temperature time constant of the curve AP_GROUPINFO("IMUT_TCONST", 3, SIM, imu_temp_tconst, 300), + // @Param: IMUT_FIXED + // @DisplayName: IMU fixed temperature + // @Description: IMU fixed temperature by user AP_GROUPINFO("IMUT_FIXED", 4, SIM, imu_temp_fixed, 0), #endif // @Param: ACC1_BIAS @@ -894,18 +999,38 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Vector3Parameter: 1 AP_GROUPINFO("ACC3_BIAS", 7, SIM, accel_bias[2], 0), #endif + // @Param: GYR1_RND + // @DisplayName: Gyro 1 motor noise factor + // @Description: scaling factor for simulated vibration from motors + // @User: Advanced AP_GROUPINFO("GYR1_RND", 8, SIM, gyro_noise[0], 0), #if INS_MAX_INSTANCES > 1 + // @Param: GYR2_RND + // @DisplayName: Gyro 2 motor noise factor + // @CopyFieldsFrom: SIM_GYR1_RND AP_GROUPINFO("GYR2_RND", 9, SIM, gyro_noise[1], 0), #endif #if INS_MAX_INSTANCES > 2 + // @Param: GYR3_RND + // @DisplayName: Gyro 3 motor noise factor + // @CopyFieldsFrom: SIM_GYR1_RND AP_GROUPINFO("GYR3_RND", 10, SIM, gyro_noise[2], 0), #endif + // @Param: ACC1_RND + // @DisplayName: Accel 1 motor noise factor + // @Description: scaling factor for simulated vibration from motors + // @User: Advanced AP_GROUPINFO("ACC1_RND", 11, SIM, accel_noise[0], 0), #if INS_MAX_INSTANCES > 1 + // @Param: ACC2_RND + // @DisplayName: Accel 2 motor noise factor + // @CopyFieldsFrom: SIM_ACC1_RND AP_GROUPINFO("ACC2_RND", 12, SIM, accel_noise[1], 0), #endif #if INS_MAX_INSTANCES > 2 + // @Param: ACC3_RND + // @DisplayName: Accel 3 motor noise factor + // @CopyFieldsFrom: SIM_ACC1_RND AP_GROUPINFO("ACC3_RND", 13, SIM, accel_noise[2], 0), #endif // @Param: GYR1_SCALE @@ -950,7 +1075,7 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @User: Advanced AP_GROUPINFO("ACCEL3_FAIL", 19, SIM, accel_fail[2], 0), #endif - // @Param: GYRO_FAIL_MSK + // @Param: GYR_FAIL_MSK // @DisplayName: Gyro Failure Mask // @Description: Determines if the gyro reading updates are stopped when for an IMU simulated failure by ACCELx_FAIL params // @Values: 0:Disabled, 1:Readings stopped @@ -1002,8 +1127,16 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Description: channels which are passed through to actual hardware when running sim on actual hardware AP_GROUPINFO("OH_MASK", 28, SIM, on_hardware_output_enable_mask, 0), #if AP_SIM_INS_FILE_ENABLED - // read and write IMU data to/from files + + // @Param: GYR_FILE_RW + // @DisplayName: Gyro data to/from files + // @Description: Read and write gyro data to/from files + // @Values: 0:Stop writing data, 1:Read data from file, 2:Write data to a file, 3: Read data from file and stop on EOF AP_GROUPINFO("GYR_FILE_RW", 29, SIM, gyro_file_rw, INSFileMode::INS_FILE_NONE), + // @Param: ACC_FILE_RW + // @DisplayName: Accelerometer data to/from files + // @Description: Read and write accelerometer data to/from files + // @Values: 0:Stop writing data, 1:Read data from file, 2:Write data to a file, 3: Read data from file and stop on EOF AP_GROUPINFO("ACC_FILE_RW", 30, SIM, accel_file_rw, INSFileMode::INS_FILE_NONE), #endif @@ -1083,8 +1216,14 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Vector3Parameter: 1 AP_GROUPINFO("GYR4_SCALE", 36, SIM, gyro_scale[3], 0), + // @Param: ACC4_RND + // @DisplayName: Accel 4 motor noise factor + // @CopyFieldsFrom: SIM_ACC1_RND AP_GROUPINFO("ACC4_RND", 37, SIM, accel_noise[3], 0), + // @Param: GYR4_RND + // @DisplayName: Gyro 4 motor noise factor + // @CopyFieldsFrom: SIM_GYR1_RND AP_GROUPINFO("GYR4_RND", 38, SIM, gyro_noise[3], 0), // @Param: ACC4_BIAS @@ -1133,8 +1272,14 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Vector3Parameter: 1 AP_GROUPINFO("GYR5_SCALE", 43, SIM, gyro_scale[4], 0), + // @Param: ACC5_RND + // @DisplayName: Accel 5 motor noise factor + // @CopyFieldsFrom: SIM_ACC1_RND AP_GROUPINFO("ACC5_RND", 44, SIM, accel_noise[4], 0), + // @Param: GYR5_RND + // @DisplayName: Gyro 5 motor noise factor + // @CopyFieldsFrom: SIM_GYR1_RND AP_GROUPINFO("GYR5_RND", 45, SIM, gyro_noise[4], 0), // @Param: ACC5_BIAS @@ -1166,6 +1311,11 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Description: Allow relay output operation when running SIM-on-hardware AP_GROUPINFO("OH_RELAY_MSK", 48, SIM, on_hardware_relay_enable_mask, SIM_DEFAULT_ENABLED_RELAY_CHANNELS), + // @Param: CLAMP_CH + // @DisplayName: Simulated Clamp Channel + // @Description: If non-zero the vehicle will be clamped in position until the value on this servo channel passes 1800PWM + AP_GROUPINFO("CLAMP_CH", 49, SIM, clamp_ch, 0), + // the IMUT parameters must be last due to the enable parameters #if HAL_INS_TEMPERATURE_CAL_ENABLE AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 61, SIM, AP_InertialSensor_TCal), @@ -1185,6 +1335,41 @@ const AP_Param::GroupInfo SIM::var_ins[] = { AP_GROUPEND }; +// user settable parameters for the physics models +const AP_Param::GroupInfo SIM::ModelParm::var_info[] = { + +#if AP_SIM_SHIP_ENABLED + // @Group: SHIP_ + // @Path: ./SIM_Ship.cpp + AP_SUBGROUPINFO(shipsim, "SHIP_", 1, SIM::ModelParm, ShipSim), +#endif +#if AP_SIM_STRATOBLIMP_ENABLED + // @Group: SB_ + // @Path: ./SIM_StratoBlimp.cpp + AP_SUBGROUPPTR(stratoblimp_ptr, "SB_", 2, SIM::ModelParm, StratoBlimp), +#endif + +#if AP_SIM_GLIDER_ENABLED + // @Group: GLD_ + // @Path: ./SIM_Glider.cpp + AP_SUBGROUPPTR(glider_ptr, "GLD_", 3, SIM::ModelParm, Glider), +#endif + +#if AP_SIM_SLUNGPAYLOAD_ENABLED + // @Group: SLUP_ + // @Path: ./SIM_SlungPayload.cpp + AP_SUBGROUPINFO(slung_payload_sim, "SLUP_", 4, SIM::ModelParm, SlungPayloadSim), +#endif + +#if AP_SIM_FLIGHTAXIS_ENABLED + // @Group: RFL_ + // @Path: ./SIM_FlightAxis.cpp + AP_SUBGROUPPTR(flightaxis_ptr, "RFL_", 5, SIM::ModelParm, FlightAxis), +#endif + + AP_GROUPEND +}; + const Location post_origin { 518752066, 146487830, @@ -1195,6 +1380,11 @@ const Location post_origin { /* report SITL state via MAVLink SIMSTATE*/ void SIM::simstate_send(mavlink_channel_t chan) const { + if (stop_MAVLink_sim_state) { + // Sim only MAVLink messages disabled to give more relaistic data rates + return; + } + float yaw; // convert to same conventions as DCM @@ -1220,6 +1410,11 @@ void SIM::simstate_send(mavlink_channel_t chan) const /* report SITL state via MAVLink SIM_STATE */ void SIM::sim_state_send(mavlink_channel_t chan) const { + if (stop_MAVLink_sim_state) { + // Sim only MAVLink messages disabled to give more relaistic data rates + return; + } + // convert to same conventions as DCM float yaw = state.yawDeg; if (yaw > 180) { @@ -1401,7 +1596,7 @@ float SIM::measure_distance_at_angle_bf(const Location &location, float angle) c post_location.offset(x*10+3, y*10+2); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (postfile != nullptr) { - ::fprintf(postfile, "map circle %f %f %f blue\n", post_location.lat*1e-7, post_location.lng*1e-7, radius_cm/100.0); + ::fprintf(postfile, "map circle %f %f %f blue\n", post_location.lat*1e-7, post_location.lng*1e-7, radius_cm*0.01); } #endif Vector2f post_position_cm; @@ -1415,8 +1610,8 @@ float SIM::measure_distance_at_angle_bf(const Location &location, float angle) c #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (intersectionsfile != nullptr) { Location intersection_point = location; - intersection_point.offset(intersection_point_cm.x/100.0, - intersection_point_cm.y/100.0); + intersection_point.offset(intersection_point_cm.x*0.01, + intersection_point_cm.y*0.01); ::fprintf(intersectionsfile, "map icon %f %f barrell\n", intersection_point.lat*1e-7, @@ -1438,8 +1633,8 @@ float SIM::measure_distance_at_angle_bf(const Location &location, float angle) c } #endif - // ::fprintf(stderr, "Distance @%f = %fm\n", angle, min_dist_cm/100.0f); - return min_dist_cm / 100.0f; + // ::fprintf(stderr, "Distance @%f = %fm\n", angle, min_dist_cm*0.01f); + return min_dist_cm * 0.01f; } } // namespace SITL diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 5198ba1f32b323..4edda5efd21e48 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -11,6 +11,7 @@ #include #include #include + #include "SIM_Buzzer.h" #include "SIM_Gripper_EPM.h" #include "SIM_Gripper_Servo.h" @@ -26,6 +27,7 @@ #include "SIM_FETtecOneWireESC.h" #include "SIM_IntelligentEnergy24.h" #include "SIM_Ship.h" +#include "SIM_SlungPayload.h" #include "SIM_GPS.h" #include "SIM_DroneCANDevice.h" #include "SIM_ADSB_Sagetech_MXS.h" @@ -46,7 +48,10 @@ struct float_array { uint16_t length; float *data; }; - + +class StratoBlimp; +class Glider; +class FlightAxis; struct sitl_fdm { // this is the structure passed between FDM models and the main SITL code @@ -60,8 +65,8 @@ struct sitl_fdm { double rollRate, pitchRate, yawRate; // degrees/s in body frame double rollDeg, pitchDeg, yawDeg; // euler angles, degrees Quaternion quaternion; - double airspeed; // m/s - Vector3f velocity_air_bf; // velocity relative to airmass, body frame + double airspeed; // m/s, EAS + Vector3f velocity_air_bf; // velocity relative to airmass, body frame, TAS double battery_voltage; // Volts double battery_current; // Amps double battery_remaining; // Ah, if non-zero capacity @@ -150,6 +155,7 @@ class SIM { GPS_HEADING_HDT = 1, GPS_HEADING_THS = 2, GPS_HEADING_KSXT = 3, + GPS_HEADING_BASE = 4, // act as an RTK base }; struct sitl_fdm state; @@ -181,7 +187,6 @@ class SIM { AP_Int8 mag_orient[HAL_COMPASS_MAX_SENSORS]; // external compass orientation AP_Int8 mag_fail[HAL_COMPASS_MAX_SENSORS]; // fail magnetometer, 1 for no data, 2 for freeze AP_Int8 mag_save_ids; - AP_Float servo_speed; // servo speed in seconds AP_Float sonar_glitch;// probability between 0-1 that any given sonar sample will read as max distance AP_Float sonar_noise; // in metres @@ -193,23 +198,6 @@ class SIM { AP_Float engine_mul; // engine multiplier AP_Int8 engine_fail; // engine servo to fail (0-7) - AP_Float gps_noise[2]; // amplitude of the gps altitude error - AP_Int16 gps_lock_time[2]; // delay in seconds before GPS gets lock - AP_Int16 gps_alt_offset[2]; // gps alt error - AP_Int8 gps_disable[2]; // disable simulated GPS - AP_Int16 gps_delay_ms[2]; // delay in milliseconds - AP_Int8 gps_type[2]; // see enum SITL::GPS::Type - AP_Float gps_byteloss[2];// byte loss as a percent - AP_Int8 gps_numsats[2]; // number of visible satellites - AP_Vector3f gps_glitch[2]; // glitch offsets in lat, lon and altitude - AP_Int8 gps_hertz[2]; // GPS update rate in Hz - AP_Int8 gps_hdg_enabled[2]; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED - AP_Float gps_drift_alt[2]; // altitude drift error - AP_Vector3f gps_pos_offset[2]; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m) - AP_Float gps_accuracy[2]; - AP_Vector3f gps_vel_err[2]; // Velocity error offsets in NED (x = N, y = E, z = D) - AP_Int8 gps_jam[2]; // jamming simulation enable - // initial offset on GPS lat/lon, used to shift origin AP_Float gps_init_lat_ofs; AP_Float gps_init_lon_ofs; @@ -227,8 +215,9 @@ class SIM { #if HAL_NUM_CAN_IFACES enum class CANTransport : uint8_t { - MulticastUDP = 0, - SocketCAN = 1 + None = 0, + MulticastUDP = 1, + SocketCAN = 2, }; AP_Enum can_transport[HAL_NUM_CAN_IFACES]; #endif @@ -294,6 +283,66 @@ class SIM { AP_Int8 signflip; }; AirspeedParm airspeed[AIRSPEED_MAX_SENSORS]; + + class ServoParams { + public: + ServoParams(void) { + AP_Param::setup_object_defaults(this, var_info); + } + static const struct AP_Param::GroupInfo var_info[]; + AP_Float servo_speed; // servo speed in seconds per 60 degrees + AP_Float servo_delay; // servo delay in seconds + AP_Float servo_filter; // servo 2p filter in Hz + }; + ServoParams servo; + + class GPSParms { + public: + GPSParms(void) { + AP_Param::setup_object_defaults(this, var_info); + } + static const struct AP_Param::GroupInfo var_info[]; + + AP_Float noise; // amplitude of the gps altitude error + AP_Int16 lock_time; // delay in seconds before GPS gets lock + AP_Int16 alt_offset; // gps alt error + AP_Int8 enabled; // enable simulated GPS + AP_Int16 delay_ms; // delay in milliseconds + AP_Int8 type; // see enum SITL::GPS::Type + AP_Float byteloss;// byte loss as a percent + AP_Int8 numsats; // number of visible satellites + AP_Vector3f glitch; // glitch offsets in lat, lon and altitude + AP_Int8 hertz; // GPS update rate in Hz + AP_Int8 hdg_enabled; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED + AP_Float drift_alt; // altitude drift error + AP_Vector3f pos_offset; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m) + AP_Float accuracy; + AP_Vector3f vel_err; // Velocity error offsets in NED (x = N, y = E, z = D) + AP_Int8 jam; // jamming simulation enable + }; + GPSParms gps[AP_SIM_MAX_GPS_SENSORS]; + + // physics model parameters + class ModelParm { + public: + static const struct AP_Param::GroupInfo var_info[]; +#if AP_SIM_STRATOBLIMP_ENABLED + StratoBlimp *stratoblimp_ptr; +#endif +#if AP_SIM_SHIP_ENABLED + ShipSim shipsim; +#endif +#if AP_SIM_GLIDER_ENABLED + Glider *glider_ptr; +#endif +#if AP_SIM_SLUNGPAYLOAD_ENABLED + SlungPayloadSim slung_payload_sim; +#endif +#if AP_SIM_FLIGHTAXIS_ENABLED + FlightAxis *flightaxis_ptr; +#endif + }; + ModelParm models; // EFI type enum EFIType { @@ -319,6 +368,7 @@ class SIM { AP_Float wind_direction; AP_Float wind_turbulance; AP_Float wind_dir_z; + AP_Float wind_change_tc; AP_Int8 wind_type; // enum WindLimitType AP_Float wind_type_alt; AP_Float wind_type_coef; @@ -443,11 +493,6 @@ class SIM { Sprayer sprayer_sim; - // simulated ship takeoffs -#if AP_SIM_SHIP_ENABLED - ShipSim shipsim; -#endif - Gripper_Servo gripper_sim; Gripper_EPM gripper_epm_sim; @@ -528,6 +573,9 @@ class SIM { // Master instance to use servos from with slave instances AP_Int8 ride_along_master; + // clamp simulation - servo channel starting at offset 1 (usually ailerons) + AP_Int8 clamp_ch; + #if AP_SIM_INS_FILE_ENABLED enum INSFileMode { INS_FILE_NONE = 0, @@ -543,6 +591,11 @@ class SIM { AP_Int16 osd_rows; AP_Int16 osd_columns; #endif + + // Allow inhibiting of SITL only sim state messages over MAVLink + // This gives more realistic data rates for testing links + void set_stop_MAVLink_sim_state() { stop_MAVLink_sim_state = true; } + bool stop_MAVLink_sim_state; }; } // namespace SITL diff --git a/libraries/SITL/SITL_Baro.cpp b/libraries/SITL/SITL_Baro.cpp new file mode 100644 index 00000000000000..e724d3898b27b4 --- /dev/null +++ b/libraries/SITL/SITL_Baro.cpp @@ -0,0 +1,78 @@ +#include "SITL.h" + +#if AP_SIM_ENABLED + +namespace SITL { +// user settable parameters for barometers +const AP_Param::GroupInfo SIM::BaroParm::var_info[] = { + // @Param: RND + // @DisplayName: Barometer noise + // @Description: Barometer noise in height + // @Units: m + // @User: Advanced + AP_GROUPINFO("RND", 1, SIM::BaroParm, noise, 0.2f), + // @Param: DRIFT + // @DisplayName: Barometer altitude drift + // @Description: Barometer altitude drifts at this rate + // @Units: m/s + // @User: Advanced + AP_GROUPINFO("DRIFT", 2, SIM::BaroParm, drift, 0), + // @Param: DISABLE + // @DisplayName: Barometer disable + // @Description: Disable barometer in SITL + // @Values: 0:Disable, 1:Enable + // @User: Advanced + AP_GROUPINFO("DISABLE", 3, SIM::BaroParm, disable, 0), + // @Param: GLITCH + // @DisplayName: Barometer glitch + // @Description: Barometer glitch height in SITL + // @Units: m + // @User: Advanced + AP_GROUPINFO("GLITCH", 4, SIM::BaroParm, glitch, 0), + // @Param: FREEZE + // @DisplayName: Barometer freeze + // @Description: Freeze barometer to last recorded altitude + // @User: Advanced + AP_GROUPINFO("FREEZE", 5, SIM::BaroParm, freeze, 0), + // @Param: DELAY + // @DisplayName: Barometer delay + // @Description: Barometer data time delay + // @Units: ms + // @User: Advanced + AP_GROUPINFO("DELAY", 6, SIM::BaroParm, delay, 0), + + // @Param: WCF_FWD + // @DisplayName: Wind coefficient forward + // @Description: Barometer wind coefficient direction forward in SITL + // @User: Advanced + AP_GROUPINFO("WCF_FWD", 7, SIM::BaroParm, wcof_xp, 0.0), + // @Param: WCF_BAK + // @DisplayName: Wind coefficient backward + // @Description: Barometer wind coefficient direction backward in SITL + // @User: Advanced + AP_GROUPINFO("WCF_BAK", 8, SIM::BaroParm, wcof_xn, 0.0), + // @Param: WCF_RGT + // @DisplayName: Wind coefficient right + // @Description: Barometer wind coefficient direction right in SITL + // @User: Advanced + AP_GROUPINFO("WCF_RGT", 9, SIM::BaroParm, wcof_yp, 0.0), + // @Param: WCF_LFT + // @DisplayName: Wind coefficient left + // @Description: Barometer wind coefficient direction left in SITL + // @User: Advanced + AP_GROUPINFO("WCF_LFT", 10, SIM::BaroParm, wcof_yn, 0.0), + // @Param: WCF_UP + // @DisplayName: Wind coefficient up + // @Description: Barometer wind coefficient direction up in SITL + // @User: Advanced + AP_GROUPINFO("WCF_UP", 11, SIM::BaroParm, wcof_zp, 0.0), + // @Param: WCF_DN + // @DisplayName: Wind coefficient down + // @Description: Barometer wind coefficient direction down in SITL + // @User: Advanced + AP_GROUPINFO("WCF_DN", 12, SIM::BaroParm, wcof_zn, 0.0), + AP_GROUPEND +}; +} + +#endif // AP_SIM_ENABLED diff --git a/libraries/SITL/ServoModel.cpp b/libraries/SITL/ServoModel.cpp new file mode 100644 index 00000000000000..03d6bd0a22f718 --- /dev/null +++ b/libraries/SITL/ServoModel.cpp @@ -0,0 +1,136 @@ +/* + 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 . + */ +/* + simple model of a servo. Model is: + + - time delay for transport protocol delay + - slew limit + - 2-pole butterworth +*/ + +#include "ServoModel.h" +#include "SITL.h" + +// SITL servo model parameters +const AP_Param::GroupInfo SITL::SIM::ServoParams::var_info[] = { + // @Param: SPEED + // @DisplayName: servo speed + // @Description: servo speed (time for 60 degree deflection). If DELAY and FILTER are not set then this is converted to a 1p lowpass filter. If DELAY or FILTER are set then this is treated as a rate of change limit + // @Units: s + AP_GROUPINFO("SPEED", 1, ServoParams, servo_speed, 0.14), + + // @Param: DELAY + // @DisplayName: servo delay + // @Description: servo delay + // @Units: s + AP_GROUPINFO("DELAY", 2, ServoParams, servo_delay, 0.0), + + // @Param: FILTER + // @DisplayName: servo filter + // @Description: servo filter + // @Units: Hz + AP_GROUPINFO("FILTER", 3, ServoParams, servo_filter, 0), + + AP_GROUPEND +}; + +/* + simpler filter used when SIM_SERVO_FILTER and SIM_SERVO_DELAY are not set + this filter is a 1p low pass based on SIM_SERVO_SPEED + */ +float ServoModel::apply_simple_filter(float v, float dt) +{ + const auto *sitl = AP::sitl(); + if (!is_positive(sitl->servo.servo_speed)) { + return v; + } + const float cutoff = 1.0f / (2 * M_PI * sitl->servo.servo_speed); + filter1p.set_cutoff_frequency(cutoff); + return filter1p.apply(v, dt); +} + +/* + apply a filter for a servo model consistting of a delay, speed and 2p filter + */ +float ServoModel::apply_filter(float v, float dt) +{ + const auto *sitl = AP::sitl(); + if (!sitl) { + return v; + } + + if (!is_positive(sitl->servo.servo_delay) && + !is_positive(sitl->servo.servo_filter)) { + // fallback to a simpler 1p filter model + return apply_simple_filter(v, dt); + } + + // apply delay + if (sitl->servo.servo_delay > 0) { + uint32_t delay_len = MAX(1,sitl->servo.servo_delay * sitl->loop_rate_hz); + if (!delay) { + delay = NEW_NOTHROW ObjectBuffer(); + } + if (delay->get_size() != delay_len) { + delay->set_size(delay_len); + } + while (delay->space() > 0) { + delay->push(v); + } + IGNORE_RETURN(delay->pop(v)); + } + + // apply slew limit + if (sitl->servo.servo_speed > 0) { + // assume SIM_SERVO_SPEED is time for 60 degrees + float time_per_degree = sitl->servo.servo_speed / 60.0; + float proportion_per_second = 1.0 / (angle_deg * time_per_degree); + delta_max = proportion_per_second * dt; + v = constrain_float(v, last_v-delta_max, last_v+delta_max); + v = constrain_float(v, -1, 1); + last_v = v; + } + + // apply filter + if (sitl->servo.servo_filter > 0) { + filter.set_cutoff_frequency(sitl->loop_rate_hz, sitl->servo.servo_filter); + v = filter.apply(v); + } + + return v; +} + +float ServoModel::filter_range(uint16_t pwm, float dt) +{ + const float v = (pwm - pwm_min)/float(pwm_max - pwm_min); + return apply_filter(v, dt); +} + +float ServoModel::filter_angle(uint16_t pwm, float dt) +{ + const float v = (pwm - 0.5*(pwm_max+pwm_min))/(0.5*float(pwm_max - pwm_min)); + return apply_filter(v, dt); +} + +void ServoModel::set_pwm_range(uint16_t _pwm_min, uint16_t _pwm_max) +{ + pwm_min = _pwm_min; + pwm_max = _pwm_max; +} + +void ServoModel::set_deflection(float _angle_deg) +{ + angle_deg = fabsf(_angle_deg); +} diff --git a/libraries/SITL/ServoModel.h b/libraries/SITL/ServoModel.h new file mode 100644 index 00000000000000..941f8a0312dc49 --- /dev/null +++ b/libraries/SITL/ServoModel.h @@ -0,0 +1,51 @@ +/* + 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 . + */ +/* + simple model of a servo. Model is: + + - time delay for transport protocol delay + - slew limit + - 2-pole butterworth +*/ + +#include +#include +#include +#include + + +class ServoModel { +public: + float filter_angle(uint16_t pwm, float dt); + float filter_range(uint16_t pwm, float dt); + void set_pwm_range(uint16_t _pwm_min, uint16_t _pwm_max); + void set_deflection(float _angle_deg); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + float apply_filter(float v, float dt); + float apply_simple_filter(float v, float dt); + + LowPassFilter2pFloat filter; + LowPassFilterFloat filter1p; + ObjectBuffer *delay; + float last_v; + float delta_max; + uint16_t pwm_min = 1000; + uint16_t pwm_max = 2000; + float angle_deg = 45.0; +}; + diff --git a/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param b/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param index 4a349fd3e72c42..98d5e0b7a06e42 100644 --- a/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param +++ b/libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param @@ -620,16 +620,9 @@ SIM_FLOW_POS_X,0 SIM_FLOW_POS_Y,0 SIM_FLOW_POS_Z,0 SIM_FLOW_RATE,10 -SIM_GP2_GLITCH_X,0 -SIM_GP2_GLITCH_Y,0 -SIM_GP2_GLITCH_Z,0 SIM_GPS_ALT_OFS,0 SIM_GPS_BYTELOSS,0 -SIM_GPS_DISABLE,0 SIM_GPS_DRIFTALT,0 -SIM_GPS_GLITCH_X,0 -SIM_GPS_GLITCH_Y,0 -SIM_GPS_GLITCH_Z,0 SIM_GPS_HZ,20 SIM_GPS_LOCKTIME,0 SIM_GPS_NOISE,0 diff --git a/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param b/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param index bfaf562bcfabe3..960c2c713c2c90 100644 --- a/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param +++ b/libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param @@ -640,21 +640,14 @@ SIM_FLOW_POS_X,0 SIM_FLOW_POS_Y,0 SIM_FLOW_POS_Z,0 SIM_FLOW_RATE,10 -SIM_GP2_GLITCH_X,0 -SIM_GP2_GLITCH_Y,0 -SIM_GP2_GLITCH_Z,0 -SIM_GPS_ALT_OFS,0 -SIM_GPS_BYTELOSS,0 -SIM_GPS_DISABLE,0 -SIM_GPS_DRIFTALT,0 -SIM_GPS_GLITCH_X,0 -SIM_GPS_GLITCH_Y,0 -SIM_GPS_GLITCH_Z,0 -SIM_GPS_HZ,20 -SIM_GPS_LOCKTIME,0 -SIM_GPS_NOISE,0 -SIM_GPS_NUMSATS,10 -SIM_GPS_TYPE,1 +SIM_GPS1_ALT_OFS,0 +SIM_GPS1_BYTELOSS,0 +SIM_GPS1_DRIFTALT,0 +SIM_GPS1_HZ,20 +SIM_GPS1_LOCKTIME,0 +SIM_GPS1_NOISE,0 +SIM_GPS1_NUMSATS,10 +SIM_GPS1_TYPE,1 SIM_GPS2_ENABLE,0 SIM_GPS2_TYPE,1 SIM_GRPE_ENABLE,0 diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 22bcc5f7791d4e..e4778b27738bf2 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -188,6 +188,7 @@ class SRV_Channel { k_rcin14_mapped = 153, k_rcin15_mapped = 154, k_rcin16_mapped = 155, + k_lift_release = 156, k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one) } Aux_servo_function_t; @@ -415,7 +416,13 @@ class SRV_Channels { // set MIN/MAX parameters for a function static void set_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm); - + + // set MIN/MAX parameter defaults for a function + static void set_output_min_max_defaults(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm); + + // Save MIN/MAX/REVERSED parameters for a function + static void save_output_min_max(SRV_Channel::Aux_servo_function_t function, uint16_t min_pwm, uint16_t max_pwm); + // save trims void save_trim(void); @@ -466,7 +473,7 @@ class SRV_Channels { int16_t value, int16_t angle_min, int16_t angle_max); // assign and enable auxiliary channels - static void enable_aux_servos(void); + void enable_aux_servos(void); // enable channels by mask static void enable_by_mask(uint32_t mask); @@ -531,10 +538,9 @@ class SRV_Channels { } return SRV_Channel::Aux_servo_function_t((SRV_Channel::k_motor9+(channel-8))); } - - static void cork(); - static void push(); + void cork(); + void push(); // disable PWM output to a set of channels given by a mask. This is used by the AP_BLHeli code static void set_disabled_channel_mask(uint32_t mask) { disabled_mask = mask; } @@ -563,7 +569,7 @@ class SRV_Channels { static void zero_rc_outputs(); // initialize before any call to push - static void init(uint32_t motor_mask = 0, AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE); + void init(uint32_t motor_mask = 0, AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE); // return true if a channel is set to type GPIO static bool is_GPIO(uint8_t channel); @@ -603,30 +609,25 @@ class SRV_Channels { #if AP_VOLZ_ENABLED // support for Volz protocol AP_Volz_Protocol volz; - static AP_Volz_Protocol *volz_ptr; #endif #if AP_SBUSOUTPUT_ENABLED // support for SBUS protocol AP_SBusOut sbus; - static AP_SBusOut *sbus_ptr; #endif #if AP_ROBOTISSERVO_ENABLED // support for Robotis servo protocol AP_RobotisServo robotis; - static AP_RobotisServo *robotis_ptr; #endif #if HAL_SUPPORT_RCOUT_SERIAL // support for BLHeli protocol AP_BLHeli blheli; - static AP_BLHeli *blheli_ptr; #endif #if AP_FETTEC_ONEWIRE_ENABLED AP_FETtecOneWire fetteconwire; - static AP_FETtecOneWire *fetteconwire_ptr; #endif // AP_FETTEC_ONEWIRE_ENABLED // mask of disabled channels @@ -685,3 +686,7 @@ class SRV_Channels { // semaphore for multi-thread use of override_counter array HAL_Semaphore override_counter_sem; }; + +namespace AP { + SRV_Channels &srv(); +}; diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index e6be2e6ef66ab1..3fb4e922744d70 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -140,6 +140,7 @@ void SRV_Channel::aux_servo_function_setup(void) case k_flap: case k_flap_auto: case k_egg_drop: + case k_lift_release: set_range(100); break; case k_heli_rsc: @@ -269,7 +270,7 @@ void SRV_Channels::enable_aux_servos() hal.rcout->update_channel_masks(); #if HAL_SUPPORT_RCOUT_SERIAL - blheli_ptr->update(); + blheli.update(); #endif } @@ -565,16 +566,25 @@ bool SRV_Channels::set_aux_channel_default(SRV_Channel::Aux_servo_function_t fun // find first channel that a function is assigned to bool SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan) { - if (!function_assigned(function)) { + // Must have populated channel masks + if (!initialised) { + update_aux_servo_function(); + } + + // Make sure function is valid + if (!SRV_Channel::valid_function(function)) { return false; } - for (uint8_t i=0; i max_pwm; + channels[i].servo_min.set_and_save(reversed ? max_pwm : min_pwm); + channels[i].servo_max.set_and_save(reversed ? min_pwm : max_pwm); + channels[i].reversed.set_and_save(reversed ? 1 : 0); + } + } +} + // constrain to output min/max for function void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function) { diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index 7f01f8b14cfd9a..c1fda6226c37cb 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -41,28 +41,8 @@ extern const AP_HAL::HAL& hal; SRV_Channel *SRV_Channels::channels; SRV_Channels *SRV_Channels::_singleton; -#if AP_VOLZ_ENABLED -AP_Volz_Protocol *SRV_Channels::volz_ptr; -#endif - -#if AP_SBUSOUTPUT_ENABLED -AP_SBusOut *SRV_Channels::sbus_ptr; -#endif - -#if AP_ROBOTISSERVO_ENABLED -AP_RobotisServo *SRV_Channels::robotis_ptr; -#endif - -#if AP_FETTEC_ONEWIRE_ENABLED -AP_FETtecOneWire *SRV_Channels::fetteconwire_ptr; -#endif - uint16_t SRV_Channels::override_counter[NUM_SERVO_CHANNELS]; -#if HAL_SUPPORT_RCOUT_SERIAL -AP_BLHeli *SRV_Channels::blheli_ptr; -#endif - uint32_t SRV_Channels::disabled_mask; uint32_t SRV_Channels::digital_mask; uint32_t SRV_Channels::reversible_mask; @@ -229,7 +209,7 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = { // @Param: _DSHOT_ESC // @DisplayName: Servo DShot ESC type // @Description: DShot ESC type for all outputs. The ESC type affects the range of DShot commands available and the bit widths used. None means that no dshot commands will be executed. Some ESC types support Extended DShot Telemetry (EDT) which allows telemetry other than RPM data to be returned when using bi-directional dshot. If you enable EDT you must install EDT capable firmware for correct operation. - // @Values: 0:None,1:BLHeli32/Kiss,2:BLHeli_S,3:BLHeli32/Kiss+EDT,4:BLHeli_S+EDT + // @Values: 0:None,1:BLHeli32/Kiss/AM32,2:BLHeli_S/BlueJay,3:BLHeli32/AM32/Kiss+EDT,4:BLHeli_S/BlueJay+EDT // @User: Advanced AP_GROUPINFO("_DSHOT_ESC", 24, SRV_Channels, dshot_esc_type, 0), @@ -379,26 +359,6 @@ SRV_Channels::SRV_Channels(void) } #endif } - -#if AP_FETTEC_ONEWIRE_ENABLED - fetteconwire_ptr = &fetteconwire; -#endif - -#if AP_VOLZ_ENABLED - volz_ptr = &volz; -#endif - -#if AP_SBUSOUTPUT_ENABLED - sbus_ptr = &sbus; -#endif - -#if AP_ROBOTISSERVO_ENABLED - robotis_ptr = &robotis; -#endif // AP_ROBOTISSERVO_ENABLED - -#if HAL_SUPPORT_RCOUT_SERIAL - blheli_ptr = &blheli; -#endif } // SRV_Channels initialization @@ -406,7 +366,7 @@ void SRV_Channels::init(uint32_t motor_mask, AP_HAL::RCOutput::output_mode mode) { // initialize BLHeli late so that all of the masks it might setup don't get trodden on by motor initialization #if HAL_SUPPORT_RCOUT_SERIAL - blheli_ptr->init(motor_mask, mode); + blheli.init(motor_mask, mode); #endif #ifndef HAL_BUILD_AP_PERIPH hal.rcout->set_dshot_rate(_singleton->dshot_rate, AP::scheduler().get_loop_rate_hz()); @@ -474,6 +434,7 @@ void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value) } } +#if AP_SCRIPTING_ENABLED && AP_SCHEDULER_ENABLED // set output value for a specific function channel as a pwm value with loop based timeout // timeout_ms of zero will clear override of the channel // minimum override is 1 MAIN_LOOP @@ -499,6 +460,7 @@ void SRV_Channels::set_output_pwm_chan_timeout(uint8_t chan, uint16_t value, uin } } } +#endif // AP_SCRIPTING_ENABLED /* wrapper around hal.rcout->cork() @@ -517,26 +479,26 @@ void SRV_Channels::push() #if AP_VOLZ_ENABLED // give volz library a chance to update - volz_ptr->update(); + volz.update(); #endif #if AP_SBUSOUTPUT_ENABLED // give sbus library a chance to update - sbus_ptr->update(); + sbus.update(); #endif #if AP_ROBOTISSERVO_ENABLED // give robotis library a chance to update - robotis_ptr->update(); + robotis.update(); #endif #if HAL_SUPPORT_RCOUT_SERIAL // give blheli telemetry a chance to update - blheli_ptr->update_telemetry(); + blheli.update_telemetry(); #endif #if AP_FETTEC_ONEWIRE_ENABLED - fetteconwire_ptr->update(); + fetteconwire.update(); #endif #if AP_KDECAN_ENABLED @@ -583,11 +545,12 @@ void SRV_Channels::zero_rc_outputs() * send an invalid signal to all channels to prevent * undesired/unexpected behavior */ - cork(); + auto &srv = AP::srv(); + srv.cork(); for (uint8_t i=0; iwrite(i, 0); } - push(); + srv.push(); } /* @@ -617,3 +580,12 @@ void SRV_Channels::set_emergency_stop(bool state) { #endif emergency_stop = state; } + +namespace AP { + +SRV_Channels &srv() +{ + return *SRV_Channels::get_singleton(); +} + +}; diff --git a/libraries/StorageManager/StorageManager.cpp b/libraries/StorageManager/StorageManager.cpp index c3bb826975a5ac..c9bb13e3e834ab 100644 --- a/libraries/StorageManager/StorageManager.cpp +++ b/libraries/StorageManager/StorageManager.cpp @@ -348,7 +348,7 @@ bool StorageAccess::attach_file(const char *filename, uint16_t size_kbyte) return false; } const uint32_t size = MIN(0xFFFFU, size_kbyte * 1024U); - auto *newfile = new FileStorage; + auto *newfile = NEW_NOTHROW FileStorage; if (newfile == nullptr) { AP_BoardConfig::allocation_error("StorageFile"); } @@ -358,7 +358,7 @@ bool StorageAccess::attach_file(const char *filename, uint16_t size_kbyte) if (newfile->fd == -1) { goto fail; } - newfile->buffer = new uint8_t[size]; + newfile->buffer = NEW_NOTHROW uint8_t[size]; if (newfile->buffer == nullptr) { AP_BoardConfig::allocation_error("StorageFile"); } diff --git a/modules/ChibiOS b/modules/ChibiOS index 8fc176ac1d68cd..88b84600b59d2f 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 8fc176ac1d68cde532a25c9b802372063a2246cb +Subproject commit 88b84600b59d2f39c9d9137aacdc9f098b374b4a diff --git a/modules/mavlink b/modules/mavlink index 1e04d8b8634daf..4c64b9522f9bb9 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 1e04d8b8634dafc8c9a2496c6922e0749e00c009 +Subproject commit 4c64b9522f9bb9815b089ab98cf2f33f11bded52 diff --git a/modules/waf b/modules/waf index 1b1625b8e7da6e..35eadbb64e2052 160000 --- a/modules/waf +++ b/modules/waf @@ -1 +1 @@ -Subproject commit 1b1625b8e7da6e1307d73335cb995fa8813d5950 +Subproject commit 35eadbb64e2052099a853b571e507c33032b392c diff --git a/wscript b/wscript index 5127c1b2df6e08..fff0a563f21111 100644 --- a/wscript +++ b/wscript @@ -10,10 +10,12 @@ import subprocess import json import fnmatch sys.path.insert(0, 'Tools/ardupilotwaf/') +sys.path.insert(0, 'Tools/scripts/') import ardupilotwaf import boards import shutil +import build_options from waflib import Build, ConfigSet, Configure, Context, Utils from waflib.Configure import conf @@ -204,11 +206,6 @@ def options(opt): default=False, help='enable OS level thread statistics.') - g.add_option('--enable-ppp', - action='store_true', - default=False, - help='enable PPP networking.') - g.add_option('--bootloader', action='store_true', default=False, @@ -388,16 +385,6 @@ configuration in order to save typing. default=False, help='Use flash storage emulation.') - g.add_option('--enable-ekf2', - action='store_true', - default=False, - help='Configure with EKF2.') - - g.add_option('--disable-ekf3', - action='store_true', - default=False, - help='Configure without EKF3.') - g.add_option('--ekf-double', action='store_true', default=False, @@ -441,6 +428,34 @@ configuration in order to save typing. type='int', default=0, help='zero time on boot in microseconds') + + g.add_option('--enable-iomcu-profiled-support', + action='store_true', + default=False, + help='enable iomcu profiled support') + + g.add_option('--enable-new-checking', + action='store_true', + default=False, + help='enables checking of new to ensure NEW_NOTHROW is used') + + # support enabling any option in build_options.py + for opt in build_options.BUILD_OPTIONS: + enable_option = "--" + opt.config_option() + disable_option = enable_option.replace("--enable", "--disable") + enable_description = opt.description + if not enable_description.lower().startswith("enable"): + enable_description = "Enable " + enable_description + disable_description = "Disable " + enable_description[len("Enable "):] + g.add_option(enable_option, + action='store_true', + default=False, + help=enable_description) + g.add_option(disable_option, + action='store_true', + default=False, + help=disable_description) + def _collect_autoconfig_files(cfg): for m in sys.modules.values(): @@ -496,6 +511,9 @@ def configure(cfg): cfg.env.ENABLE_STATS = cfg.options.enable_stats cfg.env.SAVE_TEMPS = cfg.options.save_temps + extra_hwdef = cfg.options.extra_hwdef + if extra_hwdef is not None and not os.path.exists(extra_hwdef): + raise FileNotFoundError(f"extra-hwdef file NOT found: '{cfg.options.extra_hwdef}'") cfg.env.HWDEF_EXTRA = cfg.options.extra_hwdef if cfg.env.HWDEF_EXTRA: cfg.env.HWDEF_EXTRA = os.path.abspath(cfg.env.HWDEF_EXTRA) @@ -528,7 +546,6 @@ def configure(cfg): cfg.msg('Setting board to', cfg.options.board) cfg.get_board().configure(cfg) - cfg.load('clang_compilation_database') cfg.load('waf_unit_test') cfg.load('mavgen') cfg.load('dronecangen') @@ -632,6 +649,7 @@ def configure(cfg): # add in generated flags cfg.env.CXXFLAGS += ['-include', 'ap_config.h'] + cfg.remove_target_list() _collect_autoconfig_files(cfg) def collect_dirs_to_recurse(bld, globs, **kw): @@ -657,6 +675,8 @@ def list_ap_periph_boards(ctx): def ap_periph_boards(ctx): return boards.get_ap_periph_boards() +vehicles = ['antennatracker', 'blimp', 'copter', 'heli', 'plane', 'rover', 'sub'] + def generate_tasklist(ctx, do_print=True): boardlist = boards.get_boards_names() ap_periph_targets = boards.get_ap_periph_boards() @@ -675,11 +695,11 @@ def generate_tasklist(ctx, do_print=True): task['targets'] = ['iofirmware', 'bootloader'] else: if boards.is_board_based(board, boards.sitl): - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'replay'] + task['targets'] = vehicles + ['replay'] elif boards.is_board_based(board, boards.linux): - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub'] + task['targets'] = vehicles else: - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'bootloader'] + task['targets'] = vehicles + ['bootloader'] task['buildOptions'] = '--upload' tasks.append(task) tlist.write(json.dumps(tasks)) @@ -901,7 +921,7 @@ ardupilotwaf.build_command('check-all', doc='shortcut for `waf check --alltests`', ) -for name in ('antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'blimp', 'bootloader','iofirmware','AP_Periph','replay'): +for name in (vehicles + ['bootloader','iofirmware','AP_Periph','replay']): ardupilotwaf.build_command(name, program_group_list=name, doc='builds %s programs' % name,